From eaf0f4ddb6dd283366e2b1e884d3730889e95b08 Mon Sep 17 00:00:00 2001 From: Michael Jeronimo Date: Fri, 25 Jun 2021 07:27:38 -0700 Subject: [PATCH 01/23] Feature/ros noetic port (#151) * Port to ROS Noetic/Ubuntu 20.04/Python 3 * Include a header to fix a lint issue * Include a header to fix a lint issue * noetic testing * autoware_msgs discrepancy fix with noetic * dependency fixes * dns error fix in vm * cleaned up comments * test with development tags * develop tags * develop changes * unit test changes * roslint fixes * more roslint changes * roslint changes * update to noetic/develop * relase tags * Update CMakeLists.txt files to use C++14 * Address code review feedback * Make explicit selection of OpenGL library; put back C++ selection in cmake Co-authored-by: Patrick Musau --- Dockerfile | 1 + autoware/ros/carma_autoware_build | 5 +- autoware/ros/src/.config/rviz/subnet_chk.py | 8 +- car_demo/car_demo/nodes/joystick_translator | 2 +- .../cmake/autoware_build_flags-extras.cmake | 8 +- common/autoware_health_checker/CMakeLists.txt | 2 +- .../system_status_subscriber.h | 1 + .../src/health_checker/health_checker.cpp | 5 +- .../src/health_checker/rate_checker.cpp | 1 + .../src/health_checker/value_manager.cpp | 1 + .../system_status_subscriber.cpp | 1 + .../test/src/test_autoware_health_checker.cpp | 1 + common/emergency_handler/CMakeLists.txt | 4 +- .../libsystem_status_filter.h | 1 + .../emergency_handler/libvital_monitor.h | 1 + .../emergency_handler/system_status_filter.h | 1 + .../lib/libsystem_status_filter.cpp | 1 + .../lib/libvital_monitor.cpp | 1 + .../src/emergency_handler.cpp | 1 + .../src/system_status_filter.cpp | 1 + .../test/src/test_emergency_handler.cpp | 1 + common/lanelet2_extension/CMakeLists.txt | 2 + .../nodes/grid_map_filter/grid_map_filter.h | 1 + .../wayarea2grid_lanelet2.cpp | 1 + common/op_planner/CMakeLists.txt | 1 - common/op_planner/Makefile | 4 +- common/op_simu/CMakeLists.txt | 3 + .../op_simu/include/op_simu/SimpleTracker.h | 6 +- common/ros_observer/CMakeLists.txt | 6 +- .../test/src/test_ros_observer.cpp | 1 + core_perception/deadreckoner/CMakeLists.txt | 2 +- .../include/gencolors.cpp | 4 +- .../lidar_euclidean_cluster_detect.cpp | 8 +- .../imm_ukf_pda_lanelet2.cpp | 1 + .../include/SimpleTracker.h | 2 +- .../lidar_localizer/CMakeLists.txt | 2 + .../approximate_ndt_mapping.cpp | 2 +- .../nodes/icp_matching/icp_matching.cpp | 2 +- .../nodes/ndt_mapping/ndt_mapping.cpp | 2 +- .../nodes/ndt_mapping_tku/mapping.cpp | 3 +- .../nodes/ndt_mapping_tku/ndt_mapping_tku.cpp | 4 +- .../nodes/ndt_matching/ndt_matching.cpp | 2 +- .../ndt_matching_tku/ndt_matching_tku.cpp | 2 +- core_perception/lidar_localizer/package.xml | 1 + .../lidar_point_pillars/CMakeLists.txt | 6 +- core_perception/ndt_gpu/CMakeLists.txt | 4 +- .../pcl_omp_registration/registration.h | 7 + .../points_downsampler/CMakeLists.txt | 4 +- .../nodes/ring_filter/ring_filter.cpp | 6 +- .../points_downsampler/package.xml | 2 +- .../points_preprocessor/CMakeLists.txt | 2 + .../points_preprocessor/include/gencolors.cpp | 1 + .../ray_ground_filter/ray_ground_filter.h | 4 +- .../cloud_transformer_node.cpp | 12 +- .../points_concat_filter.cpp | 2 +- .../ray_ground_filter/ray_ground_filter.cpp | 7 +- .../ring_ground_filter/ring_ground_filter.cpp | 26 +- .../points_preprocessor/package.xml | 1 + .../range_vision_fusion/CMakeLists.txt | 2 + .../road_occupancy_processor.h | 2 +- .../roi_object_filter/roi_object_filter.h | 4 +- .../trafficlight_recognizer/CMakeLists.txt | 5 +- .../include/trafficlight_recognizer/rate.h | 2 +- .../tlr_tuner/tuner_body.h | 1 + .../nodes/region_tlr/region_tlr.cpp | 8 +- .../region_tlr/traffic_light_detector.cpp | 2 + .../nodes/tlr_tuner/tuner_body.cpp | 32 +- .../twist_generator/CMakeLists.txt | 6 +- .../vel_pose_diff_checker/CMakeLists.txt | 2 +- .../vision_beyond_track/include/detection.h | 3 +- .../vision_darknet_detect/CMakeLists.txt | 2 +- .../darknet/src/darknet.h | 2 +- .../src/vision_darknet_detect.cpp | 2 +- .../vision_lane_detect/CMakeLists.txt | 2 + .../nodes/vision_lane_detect/utils.h | 2 + .../vision_lane_detect/vision_lane_detect.cpp | 10 +- .../test/src/test_node_lanelet2_functions.cpp | 1 + .../dp_planner/include/dp_planner_core.h | 4 +- core_planning/op_utilities/CMakeLists.txt | 3 + core_planning/pure_pursuit/CMakeLists.txt | 2 +- core_planning/twist_filter/CMakeLists.txt | 2 +- core_planning/twist_gate/CMakeLists.txt | 2 +- core_planning/twist_gate/src/twist_gate.cpp | 1 + .../velocity_set_lanelet2.cpp | 1 + docker/build-image.sh | 2 +- docker/checkout.bash | 4 +- docker/install.sh | 4 +- drivers/analog_devices/doc/conf.py | 2 +- .../include/adi_driver/adis16470.h | 2 +- drivers/analog_devices/src/adis16470.cpp | 2 +- drivers/analog_devices/src/adxl345_node.cpp | 7 +- drivers/analog_devices/test/test_adis16470.py | 2 +- drivers/analog_devices/test/test_adxl345.py | 2 +- drivers/hokuyo/nodes/hokuyo_3d/vssp.hpp | 4 +- .../nodes/javad_serial_driver | 2 +- .../nodes/javad_topic_driver | 2 +- .../nodes/javad_topic_serial_reader | 2 +- drivers/memsic/nodes/vg440/vg440_node.cpp | 2 +- .../microstrain/MIPSDK/C/Library/Source/mip.c | 1 + .../launch/show_urdf.launch | 2 +- .../sick_ldmrs_driver/cfg/SickLDMRSDriver.cfg | 2 +- .../launch/sick_ldmrs.launch | 2 +- .../sick_ldmrs_driver/src/sick_ldmrs_node.cpp | 6 +- .../launch/sick_ldmrs_demo.launch | 2 +- drivers/xsens_driver/src/mtdevice.py | 135 +- drivers/xsens_driver/src/mtnode.py | 2 +- ds4/ds4_driver/node/ds4_driver | 2 +- ds4/ds4_msgs/CMakeLists.txt | 2 +- lanelet2/lanelet2_core/CMakeLists.txt | 4 + .../lanelet2_examples/scripts/tutorial.py | 4 +- .../main.cpp | 3 + .../scripts/create_debug_routing_graph.py | 2 +- .../scripts/make_ids_positive.py | 2 +- lanelet2/lanelet2_python/scripts/print_ids.py | 2 +- messages/autoware_system_msgs/CMakeLists.txt | 4 +- .../cmake/Modules/GatherDeps.cmake | 4 +- .../cmake/Templates/python_api_install.py.in | 2 +- mrt_cmake_modules/doc/generate_doc/conf.py | 6 +- .../doc/generate_doc/generate_cmake_rst.py | 2 +- .../scripts/generate_cmake_dependency_file.py | 6 +- mrt_cmake_modules/setup.py | 2 +- mrt_cmake_modules/yaml/base-vanilla.yaml | 2 +- mrt_cmake_modules/yaml/base.yaml | 2 +- .../plugins/TrafficLightsGUIPlugin.cc | 10 +- .../lgsvl_simulator_bridge/CMakeLists.txt | 5 +- .../scripts/rqt_lgsvl_simulator_configurator | 4 +- .../lgsvl_simulator_bridge/configurator.py | 6 +- .../CMakeLists.txt | 2 +- .../scripts/fitParamDelayInputModel.py | 2 +- .../scripts/change_frame_id.py | 4 +- .../scripts/replace_msg_time_with_hdr.py | 4 +- .../nodes/cameracalibrator.py | 2 +- .../nodes/cameracheck.py | 2 +- .../scripts/tarfile_calibration.py | 2 +- .../autoware_camera_lidar_calibrator/setup.py | 2 +- .../autoware_camera_calibration/calibrator.py | 2 +- .../camera_calibrator.py | 2 +- .../camera_checker.py | 2 +- .../camera_lidar_calibration_node.cpp | 3 +- .../test/directed.py | 2 +- .../test/multiple_boards.py | 2 +- utilities/autoware_launcher/scripts/main | 2 +- utilities/autoware_launcher/scripts/tool | 4 +- .../data_preprocessor/scripts/baseframe.py | 24 +- .../scripts/create_h5file.py | 3 +- .../scripts/data_preprocessor.py | 4302 ++++++------ .../data_preprocessor/scripts/get_Depth.py | 18 +- .../scripts/get_ImageTopic.py | 4 +- .../data_preprocessor/scripts/get_PCD.py | 4 +- .../scripts/get_rosbaginfo.py | 2 +- .../data_preprocessor/scripts/insidedesign.py | 34 +- .../scripts/rosbag_data_extract_sample.py | 4 +- utilities/data_preprocessor/scripts/rtmgr.py | 68 +- utilities/graph_tools/scripts/yaml2dot.py | 12 +- .../scripts/kitti_box_publisher.py | 6 +- utilities/kitti_player/cfg/kitti_player.cfg | 2 +- utilities/kitti_player/src/kitti_player.cpp | 2 + .../lanelet2aisan_converter.cpp | 2 +- utilities/log_tools/CMakeLists.txt | 4 +- .../log_tools/scripts/autologger/client.py | 2 +- .../log_tools/scripts/autologger/common.py | 2 +- .../log_tools/scripts/autologger/recorder.py | 2 +- .../log_tools/scripts/autologger/server.py | 2 +- utilities/map_tf_generator/CMakeLists.txt | 6 +- utilities/marker_downsampler/scripts/app.py | 2 +- .../nodes/mqtt_receiver/mqtt_pose_receiver.py | 2 +- utilities/pc2_downsampler/scripts/app.py | 2 +- utilities/runtime_manager/scripts/ftrace.py | 8 +- .../runtime_manager/scripts/proc_manager.py | 16 +- utilities/runtime_manager/scripts/rtmgr.py | 70 +- .../scripts/runtime_manager_dialog.py | 6242 +++++++++-------- .../runtime_manager/scripts/subnet_chk.py | 6 +- utilities/runtime_manager/scripts/test_pub.py | 4 +- utilities/runtime_manager/scripts/test_srv.py | 2 +- .../sound_player/scripts/sound_player.py | 2 +- utilities/sync/sync_generator.py | 14 +- utilities/sync/sync_generator2.py | 14 +- utilities/sync/time_visualizer.py | 2 +- utilities/twist2odom/test/twist2odom_test.cpp | 1 + .../src/visualize_rects.cpp | 4 +- .../gazebo_world_description/CMakeLists.txt | 2 +- .../models/construction_cone | 2 +- .../gazebo_world_description/models/dumpster | 2 +- .../models/gas_station | 2 +- .../gazebo_world_description/models/grey_wall | 2 +- .../gazebo_world_description/models/house_1 | 2 +- .../gazebo_world_description/models/house_2 | 2 +- .../gazebo_world_description/models/house_3 | 2 +- .../models/jersey_barrier | 2 +- .../gazebo_world_description/models/mcity | 2 +- .../gazebo_world_description/models/ocean | 2 +- .../models/powerplant | 2 +- .../models/speed_limit_sign | 2 +- .../worlds/citysim_gazebo7.world | 2 +- .../worlds/citysim_gazebo9.world | 2 +- .../worlds/mcity.world | 2 +- .../worlds/mcity_r1.world | 2 +- visualization/glviewer/CMakeLists.txt | 3 + .../integrated_viewer/include/gencolors.cpp | 1 + .../integrated_viewer/lib/convert_image.h | 4 +- .../data_rate_checker_plugin.h | 5 +- .../node/image_viewer_plugin/draw_lane.cpp | 5 +- .../node/image_viewer_plugin/draw_lane.h | 2 +- .../node/image_viewer_plugin/draw_points.cpp | 1 + .../node/image_viewer_plugin/draw_points.h | 2 +- .../node/image_viewer_plugin/draw_rects.cpp | 5 +- .../node/image_viewer_plugin/draw_rects.h | 2 +- .../image_viewer_plugin.cpp | 6 +- .../image_viewer_plugin/image_viewer_plugin.h | 4 +- .../traffic_light_plugin.cpp | 1 + .../traffic_light_plugin.h | 4 +- visualization/points2image/CMakeLists.txt | 3 + visualization/vehicle_model/CMakeLists.txt | 2 +- 213 files changed, 5838 insertions(+), 5747 deletions(-) diff --git a/Dockerfile b/Dockerfile index 798a4aef859..1067e737363 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,5 +1,6 @@ FROM usdotfhwastoldev/carma-base:develop as build +RUN sudo apt-get install -y ros-noetic-velodyne-pcl COPY --chown=carma . /home/carma/autoware.ai RUN /home/carma/autoware.ai/docker/checkout.bash RUN ./home/carma/autoware.ai/docker/install.sh diff --git a/autoware/ros/carma_autoware_build b/autoware/ros/carma_autoware_build index 4451b45e297..d945c2db5d6 100755 --- a/autoware/ros/carma_autoware_build +++ b/autoware/ros/carma_autoware_build @@ -33,7 +33,7 @@ autoware_src="$(realpath .)" autoware_build_args="" use_catkin=false # The list of packages which are required by carma from autoware -AUTOWARE_PACKAGE_SELECTION="map_tools lidar_localizer map_file deadreckoner points_downsampler points_preprocessor lane_planner waypoint_maker autoware_msgs autoware_config_msgs as waypoint_planner pure_pursuit twist_filter twist_gate lanelet2_extension vision_darknet_detect vision_beyond_track lidar_euclidean_cluster_detect range_vision_fusion imm_ukf_pda_track naive_motion_predict ekf_localizer detected_objects_visualizer calibration_publisher mpc_follower autoware_camera_lidar_calibrator multi_lidar_calibrator runtime_manager" +AUTOWARE_PACKAGE_SELECTION="autoware_msgs map_tools lidar_localizer map_file deadreckoner points_downsampler points_preprocessor lane_planner waypoint_maker autoware_config_msgs as waypoint_planner pure_pursuit twist_filter twist_gate lanelet2_extension vision_darknet_detect vision_beyond_track lidar_euclidean_cluster_detect range_vision_fusion imm_ukf_pda_track naive_motion_predict ekf_localizer detected_objects_visualizer calibration_publisher mpc_follower autoware_camera_lidar_calibrator multi_lidar_calibrator runtime_manager" # Read Options while getopts a:kthb: option @@ -76,11 +76,10 @@ else else echo "Building with CMake args: ${autoware_build_args}" echo "Build with CUDA" - AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --cmake-args "${autoware_build_args}" --executor sequential --install-base ./ros/install --packages-up-to ${AUTOWARE_PACKAGE_SELECTION} + AUTOWARE_COMPILE_WITH_CUDA=0 colcon build --cmake-args "${autoware_build_args}" --executor sequential --install-base ./ros/install --packages-up-to ${AUTOWARE_PACKAGE_SELECTION} fi fi - source ./ros/install/setup.bash echo "Autoware built successfuly. Binaries sourced from $(realpath ./ros/install/setup.bash)" diff --git a/autoware/ros/src/.config/rviz/subnet_chk.py b/autoware/ros/src/.config/rviz/subnet_chk.py index 4e0f6cc5116..2995d3329fe 100755 --- a/autoware/ros/src/.config/rviz/subnet_chk.py +++ b/autoware/ros/src/.config/rviz/subnet_chk.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import os @@ -23,7 +23,7 @@ def addr_v(addr): return struct.unpack('!i', socket.inet_aton(addr))[0] if len(sys.argv) < 2: - print "Usage: {} ".format(sys.argv[0]) + print("Usage: {} ".format(sys.argv[0])) sys.exit(0) targ = sys.argv[1] @@ -37,7 +37,7 @@ def addr_v(addr): try: targ = socket.gethostbyname(targ) except socket.gaierror: - print >> sys.stderr, "%s: cannot convert to ip address" % (targ) + print("%s: cannot convert to ip address" % (targ), file=sys.stderr) sys.exit(2) targ_v = addr_v(targ) @@ -50,6 +50,6 @@ def addr_v(addr): v = addr_v(addr) mask = addr_v(mask_s) if (v & mask) == (targ_v & mask): - print addr + print(addr) sys.exit(0) sys.exit(1) diff --git a/car_demo/car_demo/nodes/joystick_translator b/car_demo/car_demo/nodes/joystick_translator index b3761702cd5..8fae3cbfa9f 100755 --- a/car_demo/car_demo/nodes/joystick_translator +++ b/car_demo/car_demo/nodes/joystick_translator @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Copyright 2017 Open Source Robotics Foundation # diff --git a/common/autoware_build_flags/cmake/autoware_build_flags-extras.cmake b/common/autoware_build_flags/cmake/autoware_build_flags-extras.cmake index de24b2e8f01..7f6c7531058 100644 --- a/common/autoware_build_flags/cmake/autoware_build_flags-extras.cmake +++ b/common/autoware_build_flags/cmake/autoware_build_flags-extras.cmake @@ -18,18 +18,14 @@ macro(AW_CHECK_CUDA) find_package(CUDA REQUIRED) find_package(Eigen3 REQUIRED) - if(NOT ${CUDA_VERSION} VERSION_LESS "10.0" - AND NOT ${CUDA_VERSION} VERSION_EQUAL "10.0" ) - message(FATAL_ERROR "GPU support on Melodic requires CUDA<=10.0") - endif() if(${CUDA_VERSION} VERSION_GREATER "9.1" AND ${CMAKE_VERSION} VERSION_LESS "3.12.3") unset(CUDA_cublas_device_LIBRARY CACHE) set(CUDA_cublas_device_LIBRARY ${CUDA_cublas_LIBRARY}) set(CUDA_CUBLAS_LIBRARIES ${CUDA_cublas_LIBRARY}) endif() - if ("$ENV{ROS_DISTRO}" STREQUAL "melodic" AND ${EIGEN3_VERSION_STRING} VERSION_LESS "3.3.7") - message(FATAL_ERROR "GPU support on Melodic requires Eigen version>= 3.3.7") + if ("$ENV{ROS_DISTRO}" STREQUAL "noetic" AND ${EIGEN3_VERSION_STRING} VERSION_LESS "3.3.7") + message(FATAL_ERROR "GPU support on Noetic requires Eigen version>= 3.3.7") endif() set(USE_CUDA ON) else() diff --git a/common/autoware_health_checker/CMakeLists.txt b/common/autoware_health_checker/CMakeLists.txt index bdcfe165830..538d8106bb7 100644 --- a/common/autoware_health_checker/CMakeLists.txt +++ b/common/autoware_health_checker/CMakeLists.txt @@ -20,7 +20,7 @@ catkin_package( CATKIN_DEPENDS autoware_system_msgs rosgraph_msgs ) -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() include_directories( diff --git a/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h b/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h index 3436ad6af69..d0a435f1046 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h +++ b/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h @@ -30,6 +30,7 @@ #include #include #include +#include namespace autoware_health_checker { diff --git a/common/autoware_health_checker/src/health_checker/health_checker.cpp b/common/autoware_health_checker/src/health_checker/health_checker.cpp index 0fb1e5e8e78..cc3b0f0eabf 100644 --- a/common/autoware_health_checker/src/health_checker/health_checker.cpp +++ b/common/autoware_health_checker/src/health_checker/health_checker.cpp @@ -19,6 +19,7 @@ #include #include +#include #include namespace autoware_health_checker @@ -167,7 +168,7 @@ ErrorLevel HealthChecker::CHECK_MIN_VALUE(const ErrorKey& key, static const ThreshType thresh_type = "min"; value_manager_.setDefaultValue( key, thresh_type, warn_value, error_value, fatal_value); - auto identify = [key, value, thresh_type, this](ErrorLevel level) + auto identify = [key, value, this](ErrorLevel level) { return (value < value_manager_.getValue(key, thresh_type, level).get()); }; @@ -192,7 +193,7 @@ ErrorLevel HealthChecker::CHECK_MAX_VALUE(const ErrorKey& key, static const ThreshType thresh_type = "max"; value_manager_.setDefaultValue( key, thresh_type, warn_value, error_value, fatal_value); - auto identify = [key, value, thresh_type, this](ErrorLevel level) + auto identify = [key, value, this](ErrorLevel level) { return (value > value_manager_.getValue(key, thresh_type, level).get()); }; diff --git a/common/autoware_health_checker/src/health_checker/rate_checker.cpp b/common/autoware_health_checker/src/health_checker/rate_checker.cpp index ffd3f68fcea..6583b4ebfb6 100644 --- a/common/autoware_health_checker/src/health_checker/rate_checker.cpp +++ b/common/autoware_health_checker/src/health_checker/rate_checker.cpp @@ -19,6 +19,7 @@ #include #include +#include #include namespace autoware_health_checker diff --git a/common/autoware_health_checker/src/health_checker/value_manager.cpp b/common/autoware_health_checker/src/health_checker/value_manager.cpp index 0afe32560ca..41cd131999e 100644 --- a/common/autoware_health_checker/src/health_checker/value_manager.cpp +++ b/common/autoware_health_checker/src/health_checker/value_manager.cpp @@ -18,6 +18,7 @@ */ #include +#include #include namespace autoware_health_checker { diff --git a/common/autoware_health_checker/src/system_status_subscriber/system_status_subscriber.cpp b/common/autoware_health_checker/src/system_status_subscriber/system_status_subscriber.cpp index b9472aac5af..174a84eb326 100644 --- a/common/autoware_health_checker/src/system_status_subscriber/system_status_subscriber.cpp +++ b/common/autoware_health_checker/src/system_status_subscriber/system_status_subscriber.cpp @@ -17,6 +17,7 @@ * v1.0 Masaya Kataoka */ +#include #include namespace autoware_health_checker diff --git a/common/autoware_health_checker/test/src/test_autoware_health_checker.cpp b/common/autoware_health_checker/test/src/test_autoware_health_checker.cpp index 4eb2d30c36c..056e09570cd 100644 --- a/common/autoware_health_checker/test/src/test_autoware_health_checker.cpp +++ b/common/autoware_health_checker/test/src/test_autoware_health_checker.cpp @@ -21,6 +21,7 @@ #include #include #include +#include using AwDiagStatus = autoware_system_msgs::DiagnosticStatus; using ErrorLevel = autoware_health_checker::ErrorLevel; diff --git a/common/emergency_handler/CMakeLists.txt b/common/emergency_handler/CMakeLists.txt index d2819772e83..0e2fecbca0c 100644 --- a/common/emergency_handler/CMakeLists.txt +++ b/common/emergency_handler/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(emergency_handler) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package( catkin REQUIRED COMPONENTS @@ -14,7 +14,7 @@ find_package( roslint ) -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() catkin_package( diff --git a/common/emergency_handler/include/emergency_handler/libsystem_status_filter.h b/common/emergency_handler/include/emergency_handler/libsystem_status_filter.h index 40990102b89..9d025776f6c 100644 --- a/common/emergency_handler/include/emergency_handler/libsystem_status_filter.h +++ b/common/emergency_handler/include/emergency_handler/libsystem_status_filter.h @@ -21,6 +21,7 @@ #include #include #include +#include #include #include diff --git a/common/emergency_handler/include/emergency_handler/libvital_monitor.h b/common/emergency_handler/include/emergency_handler/libvital_monitor.h index a248e42c553..df1a9dd1a1c 100644 --- a/common/emergency_handler/include/emergency_handler/libvital_monitor.h +++ b/common/emergency_handler/include/emergency_handler/libvital_monitor.h @@ -20,6 +20,7 @@ #include #include #include +#include #include #include diff --git a/common/emergency_handler/include/emergency_handler/system_status_filter.h b/common/emergency_handler/include/emergency_handler/system_status_filter.h index 97b79475717..5187dca1ba5 100644 --- a/common/emergency_handler/include/emergency_handler/system_status_filter.h +++ b/common/emergency_handler/include/emergency_handler/system_status_filter.h @@ -16,6 +16,7 @@ * limitations under the License. */ #include +#include class SimpleHardwareFilter : public SystemStatusFilter { diff --git a/common/emergency_handler/lib/libsystem_status_filter.cpp b/common/emergency_handler/lib/libsystem_status_filter.cpp index b0047ca51fe..ed57183e797 100644 --- a/common/emergency_handler/lib/libsystem_status_filter.cpp +++ b/common/emergency_handler/lib/libsystem_status_filter.cpp @@ -16,6 +16,7 @@ #include #include #include +#include #include void FactorStatusArray::add(const DiagnosticStatus& status) diff --git a/common/emergency_handler/lib/libvital_monitor.cpp b/common/emergency_handler/lib/libvital_monitor.cpp index e14fe67756d..3ae0766e8fb 100644 --- a/common/emergency_handler/lib/libvital_monitor.cpp +++ b/common/emergency_handler/lib/libvital_monitor.cpp @@ -16,6 +16,7 @@ #include #include #include +#include #include const std::map& VitalMonitor::getDeadNodes() diff --git a/common/emergency_handler/src/emergency_handler.cpp b/common/emergency_handler/src/emergency_handler.cpp index 69f471067f9..4cd9902996b 100644 --- a/common/emergency_handler/src/emergency_handler.cpp +++ b/common/emergency_handler/src/emergency_handler.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include diff --git a/common/emergency_handler/src/system_status_filter.cpp b/common/emergency_handler/src/system_status_filter.cpp index be5d5088276..ce79523479b 100644 --- a/common/emergency_handler/src/system_status_filter.cpp +++ b/common/emergency_handler/src/system_status_filter.cpp @@ -16,6 +16,7 @@ #include #include +#include static constexpr int DIAG_ERROR = autoware_system_msgs::DiagnosticStatus::ERROR; diff --git a/common/emergency_handler/test/src/test_emergency_handler.cpp b/common/emergency_handler/test/src/test_emergency_handler.cpp index 7f407dc581d..ad34fc4eb85 100644 --- a/common/emergency_handler/test/src/test_emergency_handler.cpp +++ b/common/emergency_handler/test/src/test_emergency_handler.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include diff --git a/common/lanelet2_extension/CMakeLists.txt b/common/lanelet2_extension/CMakeLists.txt index 9f014e3b12c..28cd2d1b8b8 100644 --- a/common/lanelet2_extension/CMakeLists.txt +++ b/common/lanelet2_extension/CMakeLists.txt @@ -7,6 +7,8 @@ project(lanelet2_extension) # - Michael McConnell # +set(CMAKE_CXX_FLAGS "-std=c++17") + find_package(PkgConfig) find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h PATH_SUFFIXES GeographicLib diff --git a/common/object_map/nodes/grid_map_filter/grid_map_filter.h b/common/object_map/nodes/grid_map_filter/grid_map_filter.h index 628a6679997..baeece7e302 100755 --- a/common/object_map/nodes/grid_map_filter/grid_map_filter.h +++ b/common/object_map/nodes/grid_map_filter/grid_map_filter.h @@ -33,6 +33,7 @@ #include #include +#include #include "object_map/object_map_utils.hpp" diff --git a/common/object_map/nodes/wayarea2grid_lanelet2/wayarea2grid_lanelet2.cpp b/common/object_map/nodes/wayarea2grid_lanelet2/wayarea2grid_lanelet2.cpp index 59fff9a528a..9539efe3f41 100755 --- a/common/object_map/nodes/wayarea2grid_lanelet2/wayarea2grid_lanelet2.cpp +++ b/common/object_map/nodes/wayarea2grid_lanelet2/wayarea2grid_lanelet2.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace object_map diff --git a/common/op_planner/CMakeLists.txt b/common/op_planner/CMakeLists.txt index 68ec24f68f3..e6538881aeb 100644 --- a/common/op_planner/CMakeLists.txt +++ b/common/op_planner/CMakeLists.txt @@ -3,7 +3,6 @@ cmake_minimum_required(VERSION 2.8.3) project(op_planner) find_package(autoware_build_flags REQUIRED) - find_package(catkin REQUIRED COMPONENTS cmake_modules op_utility diff --git a/common/op_planner/Makefile b/common/op_planner/Makefile index 7f437c4515a..07b7e930027 100755 --- a/common/op_planner/Makefile +++ b/common/op_planner/Makefile @@ -2,8 +2,8 @@ CC = g++ DEBUG = -g CFLAGS = -Iinclude -I../op_utility/include -Wall $(DEBUG) #For GPS enabled conversion ! -#LFLAGS = -Lbin -Llibs -lutilityh -lproj $(DEBUG) -std=c++11 -LFLAGS = -L../op_utility/libs -Llibs -lutility $(DEBUG) -std=c++11 +#LFLAGS = -Lbin -Llibs -lutilityh -lproj $(DEBUG) -std=c++14 +LFLAGS = -L../op_utility/libs -Llibs -lutility $(DEBUG) -std=c++14 SRC = $(wildcard src/*.cpp) BIN = $(wildcard bin/*.o) INCLUDES = $(wildcard include/*.h) diff --git a/common/op_simu/CMakeLists.txt b/common/op_simu/CMakeLists.txt index 55c5b5076ad..96804e35e26 100644 --- a/common/op_simu/CMakeLists.txt +++ b/common/op_simu/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(op_simu) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) + set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}/cmake") find_package(autoware_build_flags REQUIRED) diff --git a/common/op_simu/include/op_simu/SimpleTracker.h b/common/op_simu/include/op_simu/SimpleTracker.h index f39fc2baba4..8cfa4b3c592 100644 --- a/common/op_simu/include/op_simu/SimpleTracker.h +++ b/common/op_simu/include/op_simu/SimpleTracker.h @@ -114,7 +114,7 @@ class KFTrackV 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , 0 ,0 ,0 ,1 ); -#elif (CV_MAJOR_VERSION == 3) +#elif (CV_MAJOR_VERSION >= 3) m_filter.transitionMatrix = (cv::Mat_(nStates, nStates) << 1 ,0 ,_dt ,0 , 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , @@ -147,7 +147,7 @@ class KFTrackV 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , 0 ,0 ,0 ,1 ); -#elif (CV_MAJOR_VERSION == 3) +#elif (CV_MAJOR_VERSION >= 3) m_filter.transitionMatrix = (cv::Mat_(nStates, nStates) << 1 ,0 ,_dt ,0 , 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , @@ -257,7 +257,7 @@ class KFTrackV 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , 0 ,0 ,0 ,1 ); -#elif (CV_MAJOR_VERSION == 3) +#elif (CV_MAJOR_VERSION >= 3) m_filter.transitionMatrix = (cv::Mat_(nStates, nStates) << 1 ,0 ,_dt ,0 , 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , diff --git a/common/ros_observer/CMakeLists.txt b/common/ros_observer/CMakeLists.txt index 8965217ec03..03364f6de76 100644 --- a/common/ros_observer/CMakeLists.txt +++ b/common/ros_observer/CMakeLists.txt @@ -1,7 +1,7 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.1) project(ros_observer) -add_compile_options(-std=c++11) +set(CMAKE_CXX_STANDARD 14) find_package( catkin REQUIRED COMPONENTS @@ -13,7 +13,7 @@ find_package(Boost REQUIRED COMPONENTS thread ) -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() catkin_package( diff --git a/common/ros_observer/test/src/test_ros_observer.cpp b/common/ros_observer/test/src/test_ros_observer.cpp index 49346ae376d..88f00050a48 100644 --- a/common/ros_observer/test/src/test_ros_observer.cpp +++ b/common/ros_observer/test/src/test_ros_observer.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include using boost::interprocess::managed_shared_memory; diff --git a/core_perception/deadreckoner/CMakeLists.txt b/core_perception/deadreckoner/CMakeLists.txt index 8b58293313e..f89ddd5a422 100644 --- a/core_perception/deadreckoner/CMakeLists.txt +++ b/core_perception/deadreckoner/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 2.8.3) project(deadreckoner) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED COMPONENTS roscpp diff --git a/core_perception/lidar_euclidean_cluster_detect/include/gencolors.cpp b/core_perception/lidar_euclidean_cluster_detect/include/gencolors.cpp index 3f70c0200ea..3c177811979 100644 --- a/core_perception/lidar_euclidean_cluster_detect/include/gencolors.cpp +++ b/core_perception/lidar_euclidean_cluster_detect/include/gencolors.cpp @@ -42,8 +42,8 @@ // the use of this software, even if advised of the possibility of such damage. // //M*/ -#include "opencv2/core/core.hpp" -//#include "precomp.hpp" +#include +#include #include #include diff --git a/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp b/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp index 817680289f7..af26fc0784b 100644 --- a/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp +++ b/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp @@ -57,11 +57,11 @@ #include -#include -#include +#include +#include #include -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include "gencolors.cpp" @@ -944,7 +944,7 @@ int main(int argc, char **argv) _transform = &transform; _transform_listener = &listener; -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) generateColors(_colors, 255); #else cv::generateColors(_colors, 255); diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp b/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp index 077c5fc6055..217341abdec 100644 --- a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp +++ b/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp @@ -24,6 +24,7 @@ #include #include #include +#include namespace { diff --git a/core_perception/lidar_kf_contour_track/include/SimpleTracker.h b/core_perception/lidar_kf_contour_track/include/SimpleTracker.h index 7874fcef4dd..3e8c0241755 100644 --- a/core_perception/lidar_kf_contour_track/include/SimpleTracker.h +++ b/core_perception/lidar_kf_contour_track/include/SimpleTracker.h @@ -135,7 +135,7 @@ class KFTrackV 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , 0 ,0 ,0 ,1 ); -#elif (CV_MAJOR_VERSION == 3) +#elif (CV_MAJOR_VERSION >= 3) m_filter.transitionMatrix = (cv::Mat_(nStates, nStates) << 1 ,0 ,_dt ,0 , 0 ,1 ,0 ,_dt , 0 ,0 ,1 ,0 , diff --git a/core_perception/lidar_localizer/CMakeLists.txt b/core_perception/lidar_localizer/CMakeLists.txt index 6916f6519f2..35fd12abee9 100644 --- a/core_perception/lidar_localizer/CMakeLists.txt +++ b/core_perception/lidar_localizer/CMakeLists.txt @@ -46,6 +46,7 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs pcl_conversions velodyne_pointcloud + velodyne_pcl ndt_tku ndt_cpu autoware_health_checker @@ -62,6 +63,7 @@ catkin_package( CATKIN_DEPENDS std_msgs velodyne_pointcloud + velodyne_pcl autoware_msgs autoware_config_msgs autoware_health_checker diff --git a/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp b/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp index 08b2446da11..84de089cfcd 100644 --- a/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp +++ b/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include diff --git a/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp b/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp index ee338bb3536..9f597afe598 100644 --- a/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp +++ b/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp index 2e2ec667c68..8d94572fcd9 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp index cd0c8230562..95ca8a39740 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp @@ -14,13 +14,12 @@ #include "sensor_msgs/PointCloud2.h" #include "std_msgs/String.h" #include "tf/message_filter.h" -#include "velodyne_pointcloud/point_types.h" +#include "velodyne_pcl/point_types.h" #include "velodyne_pointcloud/rawdata.h" #include #include -pcl::PointCloud map; tf::TransformListener *tf_listener; ros::Publisher velodyne_pub; diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp index 67e6c74cad5..3f28f3c9ff8 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp @@ -35,7 +35,7 @@ #include "ros/ros.h" #include "sensor_msgs/PointCloud2.h" #include "std_msgs/String.h" -#include "velodyne_pointcloud/point_types.h" +#include "velodyne_pcl/point_types.h" #include "velodyne_pointcloud/rawdata.h" /*grobal variables*/ @@ -574,4 +574,4 @@ int main(int argc, char *argv[]) save_nd_map((char *)"/tmp/ndmap"); return 1; -} \ No newline at end of file +} diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 8c761f44e7c..5c055f9cc4d 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include diff --git a/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp b/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp index a17908c5024..240d9c44b35 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp @@ -36,7 +36,7 @@ #include "ros/ros.h" #include "sensor_msgs/PointCloud2.h" #include "std_msgs/String.h" -#include "velodyne_pointcloud/point_types.h" +#include "velodyne_pcl/point_types.h" #include "velodyne_pointcloud/rawdata.h" /*grobal variables*/ diff --git a/core_perception/lidar_localizer/package.xml b/core_perception/lidar_localizer/package.xml index fd55071f60e..c817153dac8 100644 --- a/core_perception/lidar_localizer/package.xml +++ b/core_perception/lidar_localizer/package.xml @@ -28,6 +28,7 @@ std_msgs tf velodyne_pointcloud + velodyne_pcl rostest diff --git a/core_perception/lidar_point_pillars/CMakeLists.txt b/core_perception/lidar_point_pillars/CMakeLists.txt index 595c73d9a86..b3158133286 100755 --- a/core_perception/lidar_point_pillars/CMakeLists.txt +++ b/core_perception/lidar_point_pillars/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.1) project(lidar_point_pillars) # set flags for CUDA availability @@ -60,8 +60,8 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) pcl_ros autoware_msgs ) - set(CMAKE_CXX_STANDARD 11) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") catkin_package( CATKIN_DEPENDS diff --git a/core_perception/ndt_gpu/CMakeLists.txt b/core_perception/ndt_gpu/CMakeLists.txt index d070f34edfa..088704d78af 100644 --- a/core_perception/ndt_gpu/CMakeLists.txt +++ b/core_perception/ndt_gpu/CMakeLists.txt @@ -45,7 +45,7 @@ if (USE_CUDA) endif () endif() - set(CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS};-arch=${CUDA_ARCH};-std=c++11;--ptxas-options=-v) + set(CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS};-arch=${CUDA_ARCH};-std=c++14;--ptxas-options=-v) set(SUBSYS_DESC "Point cloud ndt gpu library") @@ -107,4 +107,4 @@ if (USE_CUDA) else () message("ndt_gpu will not be built, CUDA was not found.") -endif () \ No newline at end of file +endif () diff --git a/core_perception/pcl_omp_registration/include/pcl_omp_registration/registration.h b/core_perception/pcl_omp_registration/include/pcl_omp_registration/registration.h index 82b416e26a8..ba038e4fe0c 100644 --- a/core_perception/pcl_omp_registration/include/pcl_omp_registration/registration.h +++ b/core_perception/pcl_omp_registration/include/pcl_omp_registration/registration.h @@ -52,6 +52,13 @@ #include #include +#include + +// gcc supports this starting from 4.5 : http://gcc.gnu.org/bugzilla/show_bug.cgi?id=43666 +#if (defined(__GNUC__) && PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) >= PCL_LINEAR_VERSION(4,5,0)) || (defined(__clang__) && __has_extension(attribute_deprecated_with_message)) +#define PCL_DEPRECATED(message) __attribute__ ((deprecated(message))) +#endif + namespace pcl_omp { /** \brief @b Registration represents the base registration class for general purpose, ICP-like methods. diff --git a/core_perception/points_downsampler/CMakeLists.txt b/core_perception/points_downsampler/CMakeLists.txt index 14fa44a72cb..159faddda97 100644 --- a/core_perception/points_downsampler/CMakeLists.txt +++ b/core_perception/points_downsampler/CMakeLists.txt @@ -10,7 +10,7 @@ find_package(catkin REQUIRED COMPONENTS pcl_ros sensor_msgs pcl_conversions - velodyne_pointcloud + velodyne_pcl message_generation autoware_config_msgs ) @@ -31,7 +31,7 @@ catkin_package( pcl_ros sensor_msgs pcl_conversions - velodyne_pointcloud + velodyne_pcl message_runtime autoware_config_msgs ) diff --git a/core_perception/points_downsampler/nodes/ring_filter/ring_filter.cpp b/core_perception/points_downsampler/nodes/ring_filter/ring_filter.cpp index 99572987f8f..03a6b520770 100644 --- a/core_perception/points_downsampler/nodes/ring_filter/ring_filter.cpp +++ b/core_perception/points_downsampler/nodes/ring_filter/ring_filter.cpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include "autoware_config_msgs/ConfigRingFilter.h" @@ -61,7 +61,7 @@ static void config_callback(const autoware_config_msgs::ConfigRingFilter::ConstP static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input) { pcl::PointCloud scan; - pcl::PointCloud tmp; + pcl::PointCloud tmp; sensor_msgs::PointCloud2 filtered_msg; pcl::fromROSMsg(*input, scan); @@ -73,7 +73,7 @@ static void scan_callback(const sensor_msgs::PointCloud2::ConstPtr& input) double square_measurement_range = measurement_range*measurement_range; - for (pcl::PointCloud::const_iterator item = tmp.begin(); item != tmp.end(); item++) + for (pcl::PointCloud::const_iterator item = tmp.begin(); item != tmp.end(); item++) { pcl::PointXYZI p; p.x = item->x; diff --git a/core_perception/points_downsampler/package.xml b/core_perception/points_downsampler/package.xml index 5ba8e9da4e4..8c47eacb38c 100644 --- a/core_perception/points_downsampler/package.xml +++ b/core_perception/points_downsampler/package.xml @@ -16,7 +16,7 @@ pcl_ros roscpp sensor_msgs - velodyne_pointcloud + velodyne_pcl message_runtime diff --git a/core_perception/points_preprocessor/CMakeLists.txt b/core_perception/points_preprocessor/CMakeLists.txt index 6d72f03a453..78242dec367 100644 --- a/core_perception/points_preprocessor/CMakeLists.txt +++ b/core_perception/points_preprocessor/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(catkin REQUIRED COMPONENTS pcl_conversions cv_bridge velodyne_pointcloud + velodyne_pcl autoware_config_msgs tf tf2 @@ -29,6 +30,7 @@ catkin_package(CATKIN_DEPENDS pcl_conversions cv_bridge velodyne_pointcloud + velodyne_pcl autoware_config_msgs tf tf2 diff --git a/core_perception/points_preprocessor/include/gencolors.cpp b/core_perception/points_preprocessor/include/gencolors.cpp index 60fb76ede5a..6fc0d3db634 100644 --- a/core_perception/points_preprocessor/include/gencolors.cpp +++ b/core_perception/points_preprocessor/include/gencolors.cpp @@ -45,6 +45,7 @@ #include "opencv2/core/core.hpp" //#include "precomp.hpp" #include +#include #include diff --git a/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h index f61877cec5d..c3595c660bf 100644 --- a/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h +++ b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include "autoware_config_msgs/ConfigRayGroundFilter.h" #include @@ -42,7 +42,7 @@ #include #include -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include "gencolors.cpp" #else #include diff --git a/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp b/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp index 565441f27a0..a12ccd47577 100644 --- a/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp +++ b/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include @@ -42,13 +42,13 @@ class CloudTransformerNode bool transform_ok_; void publish_cloud(const ros::Publisher& in_publisher, - const pcl::PointCloud::ConstPtr &in_cloud_msg) + const pcl::PointCloud::ConstPtr &in_cloud_msg) { in_publisher.publish(in_cloud_msg); } - void transformXYZIRCloud(const pcl::PointCloud& in_cloud, - pcl::PointCloud& out_cloud, + void transformXYZIRCloud(const pcl::PointCloud& in_cloud, + pcl::PointCloud& out_cloud, const tf::StampedTransform& in_tf_stamped_transform) { Eigen::Matrix4f transform; @@ -112,9 +112,9 @@ class CloudTransformerNode } } - void CloudCallback(const pcl::PointCloud::ConstPtr &in_sensor_cloud) + void CloudCallback(const pcl::PointCloud::ConstPtr &in_sensor_cloud) { - pcl::PointCloud::Ptr transformed_cloud_ptr (new pcl::PointCloud); + pcl::PointCloud::Ptr transformed_cloud_ptr (new pcl::PointCloud); bool do_transform = false; tf::StampedTransform transform; diff --git a/core_perception/points_preprocessor/nodes/points_concat_filter/points_concat_filter.cpp b/core_perception/points_preprocessor/nodes/points_concat_filter/points_concat_filter.cpp index 70af01f103e..38adc58b10d 100644 --- a/core_perception/points_preprocessor/nodes/points_concat_filter/points_concat_filter.cpp +++ b/core_perception/points_preprocessor/nodes/points_concat_filter/points_concat_filter.cpp @@ -25,7 +25,7 @@ #include #include #include -#include +#include #include class PointsConcatFilter diff --git a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp index 2836a72d813..d06faf6e99a 100644 --- a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp +++ b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp @@ -28,14 +28,13 @@ #include #include #include -#include +#include #include "autoware_config_msgs/ConfigRayGroundFilter.h" +#include #include #if (CV_MAJOR_VERSION == 3) #include "gencolors.cpp" -#else -#include #endif #include "points_preprocessor/ray_ground_filter/ray_ground_filter.h" @@ -417,7 +416,7 @@ void RayGroundFilter::Run() node_handle_.param("reclass_distance_threshold", reclass_distance_threshold_, 0.2); // 0.5 meters default ROS_INFO("reclass_distance_threshold[meters]: %f", reclass_distance_threshold_); -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) generateColors(colors_, color_num_); #else cv::generateColors(colors_, color_num_); diff --git a/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp b/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp index 359c3e58276..3ef120ff91f 100644 --- a/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp +++ b/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp @@ -10,8 +10,8 @@ #include #include #include -#include -#include +#include +#include enum Label { @@ -59,10 +59,10 @@ class GroundFilter void InitLabelArray(int in_model); void InitRadiusTable(int in_model); void InitDepthMap(int in_width); - void VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg); - void FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, - pcl::PointCloud &out_groundless_points, - pcl::PointCloud &out_ground_points); + void VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg); + void FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, + pcl::PointCloud &out_groundless_points, + pcl::PointCloud &out_ground_points); }; @@ -195,12 +195,12 @@ void GroundFilter::InitDepthMap(int in_width) index_map_ = cv::Mat_(vertical_res_, in_width, mOne); } -void GroundFilter::FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, - pcl::PointCloud &out_groundless_points, - pcl::PointCloud &out_ground_points) +void GroundFilter::FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, + pcl::PointCloud &out_groundless_points, + pcl::PointCloud &out_ground_points) { - velodyne_pointcloud::PointXYZIR point; + velodyne_pcl::PointXYZIRT point; InitDepthMap(horizontal_res_); for (size_t i = 0; i < in_cloud_msg->points.size(); i++) @@ -314,12 +314,12 @@ void GroundFilter::FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg) +void GroundFilter::VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg) { //t1_ = ros::Time().now(); - pcl::PointCloud vertical_points; - pcl::PointCloud ground_points; + pcl::PointCloud vertical_points; + pcl::PointCloud ground_points; vertical_points.header = in_cloud_msg->header; ground_points.header = in_cloud_msg->header; vertical_points.clear(); diff --git a/core_perception/points_preprocessor/package.xml b/core_perception/points_preprocessor/package.xml index c130c0c0da0..39b773ea88c 100644 --- a/core_perception/points_preprocessor/package.xml +++ b/core_perception/points_preprocessor/package.xml @@ -29,5 +29,6 @@ tf2_ros tf2_eigen velodyne_pointcloud + velodyne_pcl yaml-cpp diff --git a/core_perception/range_vision_fusion/CMakeLists.txt b/core_perception/range_vision_fusion/CMakeLists.txt index 63c170ad111..9e5c6148cc3 100644 --- a/core_perception/range_vision_fusion/CMakeLists.txt +++ b/core_perception/range_vision_fusion/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 2.8.12) project(range_vision_fusion) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) find_package(autoware_build_flags REQUIRED) diff --git a/core_perception/road_occupancy_processor/include/road_occupancy_processor/road_occupancy_processor.h b/core_perception/road_occupancy_processor/include/road_occupancy_processor/road_occupancy_processor.h index ae7dba9d4ef..5dd2482cef9 100644 --- a/core_perception/road_occupancy_processor/include/road_occupancy_processor/road_occupancy_processor.h +++ b/core_perception/road_occupancy_processor/include/road_occupancy_processor/road_occupancy_processor.h @@ -54,7 +54,7 @@ #include #include -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include #else #include diff --git a/core_perception/roi_object_filter/include/roi_object_filter/roi_object_filter.h b/core_perception/roi_object_filter/include/roi_object_filter/roi_object_filter.h index 1c60f9c29f8..2a2cfe5b4ef 100644 --- a/core_perception/roi_object_filter/include/roi_object_filter/roi_object_filter.h +++ b/core_perception/roi_object_filter/include/roi_object_filter/roi_object_filter.h @@ -42,8 +42,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/core_perception/trafficlight_recognizer/CMakeLists.txt b/core_perception/trafficlight_recognizer/CMakeLists.txt index b47066a7906..0aa84d34cf5 100644 --- a/core_perception/trafficlight_recognizer/CMakeLists.txt +++ b/core_perception/trafficlight_recognizer/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(trafficlight_recognizer) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) + find_package(autoware_build_flags REQUIRED) find_package(autoware_msgs REQUIRED) @@ -79,7 +82,7 @@ catkin_package( set(CMAKE_CXX_FLAGS "-O2 -Wall -Wunused-variable ${CMAKE_CXX_FLAGS}") -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() ########### diff --git a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/rate.h b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/rate.h index d6e9b745aa1..a37d8e52b1d 100644 --- a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/rate.h +++ b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/rate.h @@ -31,7 +31,7 @@ class Rate { assert(hz >= 1); float microsec = 1e6 / static_cast(hz); - sleeptime = pt::microseconds(microsec); + sleeptime = pt::microseconds(static_cast(microsec)); lastUpdate = pt::microsec_clock::local_time(); } diff --git a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/tlr_tuner/tuner_body.h b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/tlr_tuner/tuner_body.h index b74bd6d105a..baa83ad5559 100644 --- a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/tlr_tuner/tuner_body.h +++ b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/tlr_tuner/tuner_body.h @@ -24,6 +24,7 @@ #include #include +#include #include #include diff --git a/core_perception/trafficlight_recognizer/nodes/region_tlr/region_tlr.cpp b/core_perception/trafficlight_recognizer/nodes/region_tlr/region_tlr.cpp index b603112f549..bdf149a9015 100644 --- a/core_perception/trafficlight_recognizer/nodes/region_tlr/region_tlr.cpp +++ b/core_perception/trafficlight_recognizer/nodes/region_tlr/region_tlr.cpp @@ -30,6 +30,10 @@ #include #include #include +#include +#include +#include +#include #include #include #include @@ -114,8 +118,8 @@ static void putResult_inText(cv::Mat* image, const std::vector& context const float fontScale = 0.8f; const int fontThickness = 1; int baseline = 0; - CvPoint textOrg; - CvScalar textColor; + cv::Point textOrg; + cv::Scalar textColor; for (unsigned int i = 0; i < contexts.size(); i++) { diff --git a/core_perception/trafficlight_recognizer/nodes/region_tlr/traffic_light_detector.cpp b/core_perception/trafficlight_recognizer/nodes/region_tlr/traffic_light_detector.cpp index 91ed86f03fb..1c4a8ac6529 100644 --- a/core_perception/trafficlight_recognizer/nodes/region_tlr/traffic_light_detector.cpp +++ b/core_perception/trafficlight_recognizer/nodes/region_tlr/traffic_light_detector.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include #define BLACK CV_RGB(0, 0, 0) #define WHITE CV_RGB(255, 255, 255) diff --git a/core_perception/trafficlight_recognizer/nodes/tlr_tuner/tuner_body.cpp b/core_perception/trafficlight_recognizer/nodes/tlr_tuner/tuner_body.cpp index d4daa469a20..7b1fc0953e9 100644 --- a/core_perception/trafficlight_recognizer/nodes/tlr_tuner/tuner_body.cpp +++ b/core_perception/trafficlight_recognizer/nodes/tlr_tuner/tuner_body.cpp @@ -27,6 +27,8 @@ #else #define CV cv::internal #endif +#include +#include static constexpr int32_t ADVERTISE_QUEUE_SIZE = 10; static constexpr bool ADVERTISE_LATCH = true; @@ -387,51 +389,51 @@ void TunerBody::saveResult(std::string fileName) } /* open file strage */ - cv::FileStorage cvfs(fileName, CV_STORAGE_WRITE); + cv::FileStorage cvfs(fileName, cv::FileStorage::WRITE); /* write data to file */ { - CV::WriteStructContext st_red(cvfs, "RED", CV_NODE_MAP); + cv::internal::WriteStructContext st_red(cvfs, "RED", cv::FileNode::MAP); // cv::internal::WriteStructContext st_red(cvfs, "RED", CV_NODE_MAP); { - CV::WriteStructContext st_hue(cvfs, "Hue", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Hue", cv::FileNode::MAP); // cv::internal::WriteStructContext st_hue(cvfs, "Hue", CV_NODE_MAP); cv::write(cvfs, "center", Red_set.hue.center); cv::write(cvfs, "range", Red_set.hue.range); } { - CV::WriteStructContext st_hue(cvfs, "Saturation", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Saturation", cv::FileNode::MAP); cv::write(cvfs, "center", Red_set.sat.center); cv::write(cvfs, "range", Red_set.sat.range); } { - CV::WriteStructContext st_hue(cvfs, "Value", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Value", cv::FileNode::MAP); cv::write(cvfs, "center", Red_set.val.center); cv::write(cvfs, "range", Red_set.val.range); } } { - CV::WriteStructContext st_yellow(cvfs, "YELLOW", CV_NODE_MAP); + cv::internal::WriteStructContext st_yellow(cvfs, "YELLOW", cv::FileNode::MAP); // CV::WriteStructContext st_yellow(cvfs, "YELLOW", CV_NODE_MAP); { - CV::WriteStructContext st_hue(cvfs, "Hue", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Hue", cv::FileNode::MAP); // CV::WriteStructContext st_hue(cvfs, "Hue", CV_NODE_MAP); cv::write(cvfs, "center", Yellow_set.hue.center); cv::write(cvfs, "range", Yellow_set.hue.range); } { - CV::WriteStructContext st_hue(cvfs, "Saturation", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Saturation", cv::FileNode::MAP); // CV::WriteStructContext st_hue(cvfs, "Saturation", CV_NODE_MAP); cv::write(cvfs, "center", Yellow_set.sat.center); cv::write(cvfs, "range", Yellow_set.sat.range); } { - CV::WriteStructContext st_hue(cvfs, "Value", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Value", cv::FileNode::MAP); // CV::WriteStructContext st_hue(cvfs, "Value", CV_NODE_MAP); cv::write(cvfs, "center", Yellow_set.val.center); cv::write(cvfs, "range", Yellow_set.val.range); @@ -439,21 +441,21 @@ void TunerBody::saveResult(std::string fileName) } { - CV::WriteStructContext st_green(cvfs, "GREEN", CV_NODE_MAP); + cv::internal::WriteStructContext st_green(cvfs, "GREEN", cv::FileNode::MAP); { - CV::WriteStructContext st_hue(cvfs, "Hue", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Hue", cv::FileNode::MAP); cv::write(cvfs, "center", Green_set.hue.center); cv::write(cvfs, "range", Green_set.hue.range); } { - CV::WriteStructContext st_hue(cvfs, "Saturation", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Saturation", cv::FileNode::MAP); cv::write(cvfs, "center", Green_set.sat.center); cv::write(cvfs, "range", Green_set.sat.range); } { - CV::WriteStructContext st_hue(cvfs, "Value", CV_NODE_MAP); + cv::internal::WriteStructContext st_hue(cvfs, "Value", cv::FileNode::MAP); cv::write(cvfs, "center", Green_set.val.center); cv::write(cvfs, "range", Green_set.val.range); } @@ -463,10 +465,10 @@ void TunerBody::saveResult(std::string fileName) void TunerBody::openSetting(std::string fileName) { /* open file strage */ - cv::FileStorage cvfs(fileName, CV_STORAGE_READ); + cv::FileStorage cvfs(fileName, cv::FileStorage::READ); // CV_STORAGE_READ); /* read data from file */ - cv::FileNode topNode(cvfs.fs, NULL); + cv::FileNode topNode = cvfs.getFirstTopLevelNode(); { cv::FileNode nd_red = topNode[std::string("RED")]; { diff --git a/core_perception/twist_generator/CMakeLists.txt b/core_perception/twist_generator/CMakeLists.txt index 57103374a3e..92c71ffa0fb 100644 --- a/core_perception/twist_generator/CMakeLists.txt +++ b/core_perception/twist_generator/CMakeLists.txt @@ -1,8 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(twist_generator) -## Compile as C++11, supported in ROS Kinetic and newer -# add_compile_options(-std=c++11) +## Compile as C++14, supported in ROS Noetic and newer +# add_compile_options(-std=c++14) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) @@ -83,4 +83,4 @@ if(CATKIN_ENABLE_TESTING) test/src/test_vehicle_status_converter.cpp src/vehicle_status_converter.cpp) target_link_libraries(vehicle_status_converter-test ${catkin_LIBRARIES}) -endif() \ No newline at end of file +endif() diff --git a/core_perception/vel_pose_diff_checker/CMakeLists.txt b/core_perception/vel_pose_diff_checker/CMakeLists.txt index 3ceef171d1e..9f232bd8ed4 100755 --- a/core_perception/vel_pose_diff_checker/CMakeLists.txt +++ b/core_perception/vel_pose_diff_checker/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.1) project(vel_pose_diff_checker) if(NOT CMAKE_CXX_STANDARD) diff --git a/core_perception/vision_beyond_track/include/detection.h b/core_perception/vision_beyond_track/include/detection.h index d2e5546a0da..415b2d2d346 100644 --- a/core_perception/vision_beyond_track/include/detection.h +++ b/core_perception/vision_beyond_track/include/detection.h @@ -42,6 +42,7 @@ #include #include "opencv2/highgui/highgui.hpp" #include "opencv2/imgproc/imgproc.hpp" +#include "opencv2/core/types_c.h" #include "clipper.hpp" using namespace ClipperLib; @@ -231,7 +232,7 @@ namespace beyondtrack double min_val, max_val; CvPoint min_loc = cvPoint(0, 0); CvPoint max_loc = cvPoint(0, 0); - CvMat cvmat = sum_mat; + CvMat cvmat = cvMat(sum_mat); cvMinMaxLoc(&cvmat, &min_val, &max_val, &min_loc, &max_loc); offset = abs(car_bottom_plane_rot.at(max_loc.y, 1) - car_bottom_plane_rot.at(min_loc.y, 1)) / diff --git a/core_perception/vision_darknet_detect/CMakeLists.txt b/core_perception/vision_darknet_detect/CMakeLists.txt index de0f225d3a8..dbe9064236a 100644 --- a/core_perception/vision_darknet_detect/CMakeLists.txt +++ b/core_perception/vision_darknet_detect/CMakeLists.txt @@ -36,7 +36,7 @@ set(CMAKE_CXX_FLAGS "-O3 -g -Wall ${CMAKE_CXX_FLAGS}") AW_CHECK_CUDA() if (USE_CUDA) - list(APPEND CUDA_NVCC_FLAGS "--std=c++11 -I$${PROJECT_SOURCE_DIR}/darknet/src -I${PROJECT_SOURCE_DIR}/src -DGPU") + list(APPEND CUDA_NVCC_FLAGS "--std=c++14 -I$${PROJECT_SOURCE_DIR}/darknet/src -I${PROJECT_SOURCE_DIR}/src -DGPU") SET(CUDA_PROPAGATE_HOST_FLAGS OFF) #darknet diff --git a/core_perception/vision_darknet_detect/darknet/src/darknet.h b/core_perception/vision_darknet_detect/darknet/src/darknet.h index 9327ea8ca06..c5df7ca3258 100644 --- a/core_perception/vision_darknet_detect/darknet/src/darknet.h +++ b/core_perception/vision_darknet_detect/darknet/src/darknet.h @@ -25,7 +25,7 @@ extern int gpu_index; #include "opencv2/highgui/highgui_c.h" #include "opencv2/imgproc/imgproc_c.h" #include "opencv2/core/version.hpp" - #if CV_MAJOR_VERSION == 3 + #if CV_MAJOR_VERSION >= 3 #include "opencv2/videoio/videoio_c.h" #include "opencv2/imgcodecs/imgcodecs_c.h" #endif diff --git a/core_perception/vision_darknet_detect/src/vision_darknet_detect.cpp b/core_perception/vision_darknet_detect/src/vision_darknet_detect.cpp index f56e9e325b4..a15c58029c3 100644 --- a/core_perception/vision_darknet_detect/src/vision_darknet_detect.cpp +++ b/core_perception/vision_darknet_detect/src/vision_darknet_detect.cpp @@ -225,7 +225,7 @@ image Yolo3DetectorNode::convert_ipl_to_image(const sensor_msgs::ImageConstPtr& else final_mat = mat_image; - ipl_image = final_mat; + ipl_image = cvIplImage(final_mat); unsigned char *data = (unsigned char *)ipl_image.imageData; int h = ipl_image.height; diff --git a/core_perception/vision_lane_detect/CMakeLists.txt b/core_perception/vision_lane_detect/CMakeLists.txt index db06f30547e..d0ba489b692 100644 --- a/core_perception/vision_lane_detect/CMakeLists.txt +++ b/core_perception/vision_lane_detect/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(vision_lane_detect) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) find_package(autoware_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS diff --git a/core_perception/vision_lane_detect/nodes/vision_lane_detect/utils.h b/core_perception/vision_lane_detect/nodes/vision_lane_detect/utils.h index 1844ecfaf8c..e99eb8534d0 100644 --- a/core_perception/vision_lane_detect/nodes/vision_lane_detect/utils.h +++ b/core_perception/vision_lane_detect/nodes/vision_lane_detect/utils.h @@ -16,6 +16,8 @@ #pragma once +#include + class ExpMovingAverage { private: double alpha; // [0;1] less = more stable, more = less stable diff --git a/core_perception/vision_lane_detect/nodes/vision_lane_detect/vision_lane_detect.cpp b/core_perception/vision_lane_detect/nodes/vision_lane_detect/vision_lane_detect.cpp index 9bd763210ea..3ed93e3d69b 100644 --- a/core_perception/vision_lane_detect/nodes/vision_lane_detect/vision_lane_detect.cpp +++ b/core_perception/vision_lane_detect/nodes/vision_lane_detect/vision_lane_detect.cpp @@ -24,8 +24,10 @@ */ #include -#include -#include +#include +#include +#include +#include #include #include #include "utils.h" @@ -511,7 +513,7 @@ static void process_image_common(IplImage *frame) #ifdef SHOW_DETAIL /* show middle line */ cvLine(temp_frame, cvPoint(frame_size.width/2, 0), - cvPoint(frame_size.width/2, frame_size.height), CV_RGB(255, 255, 0), 1); + cvPoint(frame_size.width/2, frame_size.height), cvScalar(255, 255, 0), 1); // cvShowImage("Gray", gray); // cvShowImage("Edges", edges); @@ -541,7 +543,7 @@ static void process_image_common(IplImage *frame) static void lane_cannyhough_callback(const sensor_msgs::Image& image_source) { cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image_source, sensor_msgs::image_encodings::BGR8); - IplImage frame = cv_image->image; + IplImage frame = cvIplImage(cv_image->image); process_image_common(&frame); cvWaitKey(2); } diff --git a/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp b/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp index 66bf2a872ed..19ce3aaf7d7 100644 --- a/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp +++ b/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "decision_maker_node.hpp" #include "test_class.hpp" diff --git a/core_planning/dp_planner/include/dp_planner_core.h b/core_planning/dp_planner/include/dp_planner_core.h index 9ef436673ea..527d5bb9719 100644 --- a/core_planning/dp_planner/include/dp_planner_core.h +++ b/core_planning/dp_planner/include/dp_planner_core.h @@ -49,11 +49,11 @@ #include "ROSHelpers.h" #include "op_simu/SimpleTracker.h" -#include +#include #include #include #include -#include +#include #include #if (CV_MAJOR_VERSION < 3) diff --git a/core_planning/op_utilities/CMakeLists.txt b/core_planning/op_utilities/CMakeLists.txt index 18dbb3135c9..342b2fd4575 100644 --- a/core_planning/op_utilities/CMakeLists.txt +++ b/core_planning/op_utilities/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(op_utilities) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) + find_package(autoware_build_flags REQUIRED) find_package( diff --git a/core_planning/pure_pursuit/CMakeLists.txt b/core_planning/pure_pursuit/CMakeLists.txt index 3c2cc20db8d..9ca9ef931f0 100644 --- a/core_planning/pure_pursuit/CMakeLists.txt +++ b/core_planning/pure_pursuit/CMakeLists.txt @@ -36,7 +36,7 @@ catkin_package( SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() include_directories( diff --git a/core_planning/twist_filter/CMakeLists.txt b/core_planning/twist_filter/CMakeLists.txt index d6037ff4bf8..0715c676a08 100644 --- a/core_planning/twist_filter/CMakeLists.txt +++ b/core_planning/twist_filter/CMakeLists.txt @@ -33,7 +33,7 @@ catkin_package( std_msgs ) -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") diff --git a/core_planning/twist_gate/CMakeLists.txt b/core_planning/twist_gate/CMakeLists.txt index d04249a71b8..5d551c2740a 100644 --- a/core_planning/twist_gate/CMakeLists.txt +++ b/core_planning/twist_gate/CMakeLists.txt @@ -29,7 +29,7 @@ catkin_package( ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") -set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() diff --git a/core_planning/twist_gate/src/twist_gate.cpp b/core_planning/twist_gate/src/twist_gate.cpp index 3697734e19a..0a997190b2e 100644 --- a/core_planning/twist_gate/src/twist_gate.cpp +++ b/core_planning/twist_gate/src/twist_gate.cpp @@ -32,6 +32,7 @@ #include #include +#include #include #include diff --git a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp index d5939036972..b37d1addbe5 100644 --- a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp +++ b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp @@ -33,6 +33,7 @@ #include #include #include +#include #include #include diff --git a/docker/build-image.sh b/docker/build-image.sh index fe3205def6e..e916e8bd894 100755 --- a/docker/build-image.sh +++ b/docker/build-image.sh @@ -61,7 +61,7 @@ if [[ $COMPONENT_VERSION_STRING = "develop" ]]; then --build-arg VCS_REF=`git rev-parse --short HEAD` \ --build-arg BUILD_DATE=`date -u +”%Y-%m-%dT%H:%M:%SZ”` . else - docker build --no-cache -t $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING \ + docker build --network=host --no-cache -t $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING \ --build-arg VERSION="$COMPONENT_VERSION_STRING" \ --build-arg VCS_REF=`git rev-parse --short HEAD` \ --build-arg BUILD_DATE=`date -u +”%Y-%m-%dT%H:%M:%SZ”` . diff --git a/docker/checkout.bash b/docker/checkout.bash index 8567bd506d9..3e0e47f4524 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -35,7 +35,7 @@ done cd ${dir}/autoware.ai if [[ "$BRANCH" = "carma-develop" ]]; then - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch develop + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/develop else - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch develop + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/release fi diff --git a/docker/install.sh b/docker/install.sh index 372882a4d5e..ee21cc39f54 100755 --- a/docker/install.sh +++ b/docker/install.sh @@ -17,4 +17,6 @@ source /home/carma/.base-image/init-env.sh autoware_src="/home/carma/autoware.ai" cd ${autoware_src} -./autoware/ros/carma_autoware_build -a ${autoware_src} + +#build autoware +./autoware/ros/carma_autoware_build -a ${autoware_src} -b "-DCMAKE_BUILD_TYPE=Release" diff --git a/drivers/analog_devices/doc/conf.py b/drivers/analog_devices/doc/conf.py index 02586b3aadf..53d6eccf4d5 100644 --- a/drivers/analog_devices/doc/conf.py +++ b/drivers/analog_devices/doc/conf.py @@ -235,7 +235,7 @@ #'pointsize': '10pt', # Additional stuff for the LaTeX preamble. - 'preamble': '\usepackage{ascmac}\usepackage{fancybox}\setcounter{chapter}{0}\setcounter{tocdepth}{3}', + 'preamble': r'\usepackage{ascmac}\usepackage{fancybox}\setcounter{chapter}{0}\setcounter{tocdepth}{3}', # Latex figure (float) alignment #'figure_align': 'htbp', diff --git a/drivers/analog_devices/include/adi_driver/adis16470.h b/drivers/analog_devices/include/adi_driver/adis16470.h index 27f4174816e..31694e9c11e 100644 --- a/drivers/analog_devices/include/adi_driver/adis16470.h +++ b/drivers/analog_devices/include/adi_driver/adis16470.h @@ -55,7 +55,7 @@ class Adis16470 int get_product_id(int16_t& data); int update(void); int update_burst(void); - int read_register(char address, int16_t& data); + int read_register(unsigned char address, int16_t& data); }; #endif // ADI_DRIVER_ADIS16470_H diff --git a/drivers/analog_devices/src/adis16470.cpp b/drivers/analog_devices/src/adis16470.cpp index e0037cc327e..f1d6bfa0ad2 100644 --- a/drivers/analog_devices/src/adis16470.cpp +++ b/drivers/analog_devices/src/adis16470.cpp @@ -196,7 +196,7 @@ int Adis16470::get_product_id(int16_t& pid) * - Adress is the first byte of actual address * - Actual data at the adress will be returned by next call. */ -int Adis16470::read_register(char address, int16_t& data) +int Adis16470::read_register(unsigned char address, int16_t& data) { unsigned char buff[3] = {0x61, address, 0x00}; int size = write(fd_, buff, 3); diff --git a/drivers/analog_devices/src/adxl345_node.cpp b/drivers/analog_devices/src/adxl345_node.cpp index 28c03321a8a..9f645ceef44 100644 --- a/drivers/analog_devices/src/adxl345_node.cpp +++ b/drivers/analog_devices/src/adxl345_node.cpp @@ -68,7 +68,7 @@ class Adxl345Node /** * @brief Open IMU device file */ - bool open(void) + void open(void) { // Open device file if (imu_.open_device(device_) < 0) @@ -81,7 +81,7 @@ class Adxl345Node imu_.get_product_id(pid); ROS_INFO("Product ID: %0x\n", pid); } - int publish_imu_data() + void publish_imu_data() { sensor_msgs::Imu data; data.header.frame_id = frame_id_; @@ -100,7 +100,7 @@ class Adxl345Node imu_data_pub_.publish(data); } - bool spin() + void spin() { ros::Rate loop_rate(100); @@ -117,7 +117,6 @@ class Adxl345Node ros::spinOnce(); loop_rate.sleep(); } - return true; } }; diff --git a/drivers/analog_devices/test/test_adis16470.py b/drivers/analog_devices/test/test_adis16470.py index 90651f11603..41906f12801 100755 --- a/drivers/analog_devices/test/test_adis16470.py +++ b/drivers/analog_devices/test/test_adis16470.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Copyright (c) 2017, Analog Devices Inc. # All right reserved. diff --git a/drivers/analog_devices/test/test_adxl345.py b/drivers/analog_devices/test/test_adxl345.py index 3db78c37b99..37685a7aeaf 100755 --- a/drivers/analog_devices/test/test_adxl345.py +++ b/drivers/analog_devices/test/test_adxl345.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Copyright (c) 2017, Analog Devices Inc. # All right reserved. diff --git a/drivers/hokuyo/nodes/hokuyo_3d/vssp.hpp b/drivers/hokuyo/nodes/hokuyo_3d/vssp.hpp index a0ecef2a4c3..870aff83321 100644 --- a/drivers/hokuyo/nodes/hokuyo_3d/vssp.hpp +++ b/drivers/hokuyo/nodes/hokuyo_3d/vssp.hpp @@ -94,7 +94,7 @@ class vssp::vsspDriver cbConnect = cb; boost::asio::ip::tcp::endpoint endpoint( boost::asio::ip::address::from_string(ip), port); - timer.expires_from_now(boost::posix_time::seconds(timeout)); + timer.expires_from_now(boost::posix_time::seconds(static_cast(timeout))); timer.async_wait(boost::bind(&vsspDriver::on_timeout_connect, this, boost::asio::placeholders::error)); socket.async_connect(endpoint, @@ -149,7 +149,7 @@ class vssp::vsspDriver void receivePackets() { timer.cancel(); - timer.expires_from_now(boost::posix_time::seconds(timeout)); + timer.expires_from_now(boost::posix_time::seconds(static_cast(timeout))); timer.async_wait(boost::bind(&vsspDriver::on_timeout, this, boost::asio::placeholders::error)); boost::asio::async_read( diff --git a/drivers/javad_navsat_driver/nodes/javad_serial_driver b/drivers/javad_navsat_driver/nodes/javad_serial_driver index cf24effab65..3c2c523d7ae 100755 --- a/drivers/javad_navsat_driver/nodes/javad_serial_driver +++ b/drivers/javad_navsat_driver/nodes/javad_serial_driver @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 # Software License Agreement (BSD License) # diff --git a/drivers/javad_navsat_driver/nodes/javad_topic_driver b/drivers/javad_navsat_driver/nodes/javad_topic_driver index 8229519f3ac..fca23fd2147 100755 --- a/drivers/javad_navsat_driver/nodes/javad_topic_driver +++ b/drivers/javad_navsat_driver/nodes/javad_topic_driver @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 # Software License Agreement (BSD License) # diff --git a/drivers/javad_navsat_driver/nodes/javad_topic_serial_reader b/drivers/javad_navsat_driver/nodes/javad_topic_serial_reader index 59da3db3e35..4d562b6abc8 100755 --- a/drivers/javad_navsat_driver/nodes/javad_topic_serial_reader +++ b/drivers/javad_navsat_driver/nodes/javad_topic_serial_reader @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 # coding:utf-8 # Software License Agreement (BSD License) diff --git a/drivers/memsic/nodes/vg440/vg440_node.cpp b/drivers/memsic/nodes/vg440/vg440_node.cpp index 5177bbe46bc..f059b3c4567 100755 --- a/drivers/memsic/nodes/vg440/vg440_node.cpp +++ b/drivers/memsic/nodes/vg440/vg440_node.cpp @@ -327,7 +327,7 @@ struct SNAV1Msg{ unsigned short BITStatus; }; -bool MsgToNav1(const unsigned char* data, SNAV1Msg &sMsg) { +void MsgToNav1(const unsigned char* data, SNAV1Msg &sMsg) { sMsg.dRollAngle = MKShort(data+0)*2.0*M_PI/(256*256); sMsg.dPitchAngle = MKShort(data+2)*2.0*M_PI/(256*256); sMsg.dYawAngle = MKShort(data+4)*2.0*M_PI/(256*256); diff --git a/drivers/microstrain/MIPSDK/C/Library/Source/mip.c b/drivers/microstrain/MIPSDK/C/Library/Source/mip.c index 14690cefcd1..369b925691d 100644 --- a/drivers/microstrain/MIPSDK/C/Library/Source/mip.c +++ b/drivers/microstrain/MIPSDK/C/Library/Source/mip.c @@ -34,6 +34,7 @@ // //////////////////////////////////////////////////////////////////////////////// +#include #include "mip.h" diff --git a/drivers/sick_ldmrs_description/launch/show_urdf.launch b/drivers/sick_ldmrs_description/launch/show_urdf.launch index 28befa43215..57dac197275 100644 --- a/drivers/sick_ldmrs_description/launch/show_urdf.launch +++ b/drivers/sick_ldmrs_description/launch/show_urdf.launch @@ -4,6 +4,6 @@ - + diff --git a/drivers/sick_ldmrs_driver/cfg/SickLDMRSDriver.cfg b/drivers/sick_ldmrs_driver/cfg/SickLDMRSDriver.cfg index 1e020bcd74e..ac3d1357bb3 100755 --- a/drivers/sick_ldmrs_driver/cfg/SickLDMRSDriver.cfg +++ b/drivers/sick_ldmrs_driver/cfg/SickLDMRSDriver.cfg @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 # # Copyright (C) 2015, DFKI GmbH # All rights reserved. diff --git a/drivers/sick_ldmrs_driver/launch/sick_ldmrs.launch b/drivers/sick_ldmrs_driver/launch/sick_ldmrs.launch index c793a5bcf89..23f89c9e31f 100644 --- a/drivers/sick_ldmrs_driver/launch/sick_ldmrs.launch +++ b/drivers/sick_ldmrs_driver/launch/sick_ldmrs.launch @@ -45,7 +45,7 @@ - + diff --git a/drivers/sick_ldmrs_driver/src/sick_ldmrs_node.cpp b/drivers/sick_ldmrs_driver/src/sick_ldmrs_node.cpp index aa8542132a8..b96d5e696ed 100644 --- a/drivers/sick_ldmrs_driver/src/sick_ldmrs_node.cpp +++ b/drivers/sick_ldmrs_driver/src/sick_ldmrs_node.cpp @@ -368,13 +368,13 @@ void SickLDMRS::update_config(SickLDMRSDriverConfig &new_config, uint32_t level) switch (config_.scan_frequency) { case SickLDMRSDriver_ScanFreq1250: - expected_frequency_ = 12.5d; + expected_frequency_ = 12.5; break; case SickLDMRSDriver_ScanFreq2500: - expected_frequency_ = 25.0d; + expected_frequency_ = 25.0; break; case SickLDMRSDriver_ScanFreq5000: - expected_frequency_ = 50.0d; + expected_frequency_ = 50.0; break; default: ROS_ERROR("Unknown scan frequency: %i", config_.scan_frequency); diff --git a/drivers/sick_ldmrs_tools/launch/sick_ldmrs_demo.launch b/drivers/sick_ldmrs_tools/launch/sick_ldmrs_demo.launch index 2f0ba47a426..513b7db0e74 100644 --- a/drivers/sick_ldmrs_tools/launch/sick_ldmrs_demo.launch +++ b/drivers/sick_ldmrs_tools/launch/sick_ldmrs_demo.launch @@ -38,6 +38,6 @@ - + diff --git a/drivers/xsens_driver/src/mtdevice.py b/drivers/xsens_driver/src/mtdevice.py index 85831f333ec..970fb2edb17 100755 --- a/drivers/xsens_driver/src/mtdevice.py +++ b/drivers/xsens_driver/src/mtdevice.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import serial import struct @@ -21,8 +21,7 @@ def __init__(self, port, baudrate=115200, timeout=0.1, autoconf=True, """Open device.""" # self.device = serial.Serial(port, baudrate, timeout=timeout, # writeTimeout=timeout) - self.device = serial.Serial(port, baudrate, timeout=timeout, - writeTimeout=timeout, rtscts=True, dsrdtr=True) + self.device = serial.Serial(port, baudrate, timeout=timeout, writeTimeout=timeout, rtscts=True, dsrdtr=True) self.device.flushInput() # flush to make sure the port is ready TODO self.device.flushOutput() # flush to make sure the port is ready TODO ## timeout for communication @@ -62,8 +61,8 @@ def write_msg(self, mid, data=[]): pass self.device.write(msg) if verbose: - print "MT: Write message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length, - ' '.join("%02X"% v for v in data)) + print("MT: Write message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length, + ' '.join("%02X"% v for v in data))) ## Low-level message sending function for MK4 def write_msg_mk4(self, mid, data=[]): """Low-level message sending function.""" @@ -74,16 +73,16 @@ def write_msg_mk4(self, mid, data=[]): lendat = [length] packet = [0xFA, 0xFF, mid] + lendat + list(data) packet.append(0xFF&(-(sum(packet[1:])))) - print packet + print(packet) msg = struct.pack('%dB'%len(packet), *packet) start = time.time() while (time.time()-start)0xFA: + if ord(c) != 0xFA: continue # second part of preamble waitfor(3) - if ord(self.device.read())<>0xFF: # we assume no timeout anymore + if ord(self.device.read()) != 0xFF: # we assume no timeout anymore continue # read message id and length of message #msg = self.device.read(2) @@ -166,8 +165,8 @@ def waitfor(size=1): sys.stderr.write("MT error 0x%02X: %s."%(data[0], MID.ErrorCodes[data[0]])) if verbose: - print "MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length, - ' '.join("%02X"% v for v in data)) + print("MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length, + ' '.join("%02X"% v for v in data))) if 0xFF&sum(data, 0xFF+mid+length+checksum): sys.stderr.write("invalid checksum; discarding data and "\ "waiting for next message.\n") @@ -373,7 +372,7 @@ def SetCurrentScenario(self, scenario_id): validateSc = availableSc == str(scenario_id) if validateSc.any(): self.write_ack(MID.SetCurrentScenario, (0x00, scenario_id&0xFF)) - print "Set to scenario:%2d"%scenario_id + print("Set to scenario:%2d"%scenario_id) else: raise MTException("not an available XKF scenario") @@ -387,7 +386,7 @@ def configureMti(self, mtiSampleRate, mtiMode): """Configure the mode and settings of the MTMk4 device.""" self.GoToConfig() self.timeout = math.pow(mtiSampleRate,-1)+MID.additionalTimeOutOffset # additional 5ms leeway - print "Timeout changed to %1.3fs based on current settings."%(self.timeout) + print("Timeout changed to %1.3fs based on current settings."%(self.timeout)) mid = MID.SetOutputConfiguration midReqDID = MID.ReqDID dataReqDID = (0x00, 0x00) @@ -449,67 +448,67 @@ def configureMti(self, mtiSampleRate, mtiMode): # Output configuration set based on the product ID and user specification if (deviceIDProductMask[2] == XDIProductMask.MTi100Series) & (deviceTypeMask[2] == XDIProductMask.MTi700Device): - print "MTi-G-700/710 (GNSS/INS) device detected." + print("MTi-G-700/710 (GNSS/INS) device detected.") if mtiMode == 1: - print "Enabled publishing all sensor data" + print("Enabled publishing all sensor data") data = mStf+mImuDq+mImuDv+mImuMag+mImuP+mGnssPvt+mGnssSat+mSw+mOrientationQuat elif mtiMode == 2: - print "Enabled publishing all sensor data (rate quantities)" + print("Enabled publishing all sensor data (rate quantities)") data = mStf+mImuGyr+mImuAcc+mImuMag+mImuP+mGnssPvt+mGnssSat+mSw+mOrientationQuat elif mtiMode == 3: - print "Enabled publishing all filter estimates" + print("Enabled publishing all filter estimates") data = mStf+mSw+mOrientation+mVelocity+mPosition+mHeight else: raise MTException("unknown mtiMode: (%d)."% (mtiMode)) elif deviceIDProductMask[2] == XDIProductMask.MTi100Series: - print "MTi-100/200/300 device detected." + print("MTi-100/200/300 device detected.") if mtiMode == 1: - print "Enabled publishing all sensor data" + print("Enabled publishing all sensor data") data = mStf+mImuDq+mImuDv+mImuMag+mImuP+mSw+mOrientationQuat elif mtiMode == 2: - print "Enabled publishing all sensor data (rate quantities)" + print("Enabled publishing all sensor data (rate quantities)") data = mStf+mImuGyr+mImuAcc+mImuMag+mImuP+mSw+mOrientationQuat elif mtiMode == 3: - print "Enabled publishing all filter estimates" + print("Enabled publishing all filter estimates") data = mStf+mSw+mOrientation else: raise MTException("unknown mtiMode: (%d)."% (mtiMode)) elif deviceIDProductMask[2] == XDIProductMask.MTi10Series: - print "MTi-10/20/30 device detected" + print("MTi-10/20/30 device detected") if mtiMode == 1: - print "Enabled publishing all sensor data" + print("Enabled publishing all sensor data") data = mStf+mImuDq+mImuDv+mImuMag+mSw+mOrientationQuat elif mtiMode == 2: - print "Enabled publishing all sensor data (rate quantities)" + print("Enabled publishing all sensor data (rate quantities)") data = mStf+mImuGyr+mImuAcc+mImuMag+mSw+mOrientationQuat elif mtiMode == 3: - print "Enabled publishing all filter estimates" + print("Enabled publishing all filter estimates") data = mStf+mSw+mOrientation else: raise MTException("unknown mtiMode: (%d)."% (mtiMode)) elif deviceIDProductMask[2] == XDIProductMask.MTi1Series: - print "MTi-1/2/3 device detected" + print("MTi-1/2/3 device detected") if mtiMode == 1: - print "Enabled publishing all sensor data" + print("Enabled publishing all sensor data") data = mStf+mImuDq+mImuDv+mImuMag+mSw+mOrientationQuat elif mtiMode == 2: - print "Enabled publishing all sensor data (rate quantities)" + print("Enabled publishing all sensor data (rate quantities)") data = mStf+mImuGyr+mImuAcc+mImuMag+mSw+mOrientationQuat elif mtiMode == 3: - print "Enabled publishing all filter estimates" + print("Enabled publishing all filter estimates") data = mStf+mSw+mOrientation else: raise MTException("unknown mtiMode: (%d)."% (mtiMode)) elif deviceIDProductMask[2] == XDIProductMask.FMT1000Series: - print "FMT-1010/1020/1030 device detected" + print("FMT-1010/1020/1030 device detected") if mtiMode == 1: - print "Enabled publishing all sensor data" + print("Enabled publishing all sensor data") data = mStf+mImuDq+mImuDv+mImuMag+mSw+mOrientationQuat elif mtiMode == 2: - print "Enabled publishing all sensor data (rate quantities)" + print("Enabled publishing all sensor data (rate quantities)") data = mStf+mImuGyr+mImuAcc+mImuMag+mSw+mOrientationQuat elif mtiMode == 3: - print "Enabled publishing all filter estimates" + print("Enabled publishing all filter estimates") data = mStf+mSw+mOrientation else: raise MTException("unknown mtiMode: (%d)."% (mtiMode)) @@ -521,7 +520,7 @@ def configureMti(self, mtiSampleRate, mtiMode): dataAck = self.write_ack(MID.SetBaudrate, ()) bridAck = struct.unpack('!B',dataAck) brSettings = Baudrates.get_BR(bridAck[0]) - print "Device configured at %1.0f bps"%(brSettings) + print("Device configured at %1.0f bps"%(brSettings)) self.GoToMeasurement() def getMtiConfigBytes(self, dataMessage, dataFs): @@ -540,10 +539,10 @@ def auto_config(self): if Config.any(): configuredMtiFs = numpy.max(Config[Config[:,1]!=65535,1]) self.timeout = math.pow(configuredMtiFs,-1)+MID.additionalTimeOutOffset # additional 5ms leeway - print "Timeout defaults to %1.3fs based on output settings."%(self.timeout) + print("Timeout defaults to %1.3fs based on output settings."%(self.timeout)) else: self.timeout = 1+MID.additionalTimeOutOffset - print "Timeout defaults to %1.3fs based on output settings."%(self.timeout) + print("Timeout defaults to %1.3fs based on output settings."%(self.timeout)) self.GoToMeasurement() return self.timeout @@ -775,7 +774,7 @@ def parse_status(data_id, content, ffmt): output['Status'] = parse_status(data_id, content, ffmt) else: raise MTException("unknown XDI group: 0x%04X."%group) - except struct.error, e: + except (struct.error, e): raise MTException("couldn't parse MTData2 message.") return output @@ -788,10 +787,10 @@ def ChangeBaudrate(self, baudrate): bridAck = self.SetBaudrate(brid) if bridAck: # Testing if the BR was set correctly self.device.baudrate=baudrate - print "Baudrate set to %d bps"%baudrate + print("Baudrate set to %d bps"%baudrate) time.sleep(0.01) else: - print "NOK:Baudrate not configured." + print("NOK:Baudrate not configured.") @@ -833,7 +832,7 @@ def find_baudrate(port): # Documentation for stand alone usage ################################################################ def usage(): - print """MT device driver. + print("""MT device driver. Usage: ./mtdevice.py [commands] [opts] @@ -873,7 +872,7 @@ def usage(): 115200/(PERIOD * (SKIPFACTOR + 1)) If the value is 0xffff, no data is send unless a ReqData request is made. -""" +""") ################################################################ # Main function ################################################################ @@ -886,8 +885,8 @@ def main(): try: opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts) #pdb.set_trace() - except getopt.GetoptError, e: - print e + except (getopt.GetoptError, e): + print(e) usage() return 1 # default values @@ -912,7 +911,7 @@ def main(): try: new_baudrate = int(a) except ValueError: - print "change-baudrate argument must be integer." + print("change-baudrate argument must be integer.") return 1 actions.append('change-baudrate') if o in ('-e', '--echo'): @@ -923,7 +922,7 @@ def main(): try: new_xkf = int(a) except ValueError: - print "xkf-scenario argument must be integer." + print("xkf-scenario argument must be integer.") return 1 actions.append('xkf-scenario') if o in ('-d', '--device'): @@ -932,27 +931,27 @@ def main(): try: baudrate = int(a) except ValueError: - print "Baudrate argument must be integer." + print("Baudrate argument must be integer.") return 1 if o in ('-s', '--skip-factor'): try: skipfactor = int(a) except ValueError: - print "skip-factor argument must be integer." + print("skip-factor argument must be integer.") return 1 if o in ('-f', '--mti-odr'): try: sampleRate = int(a) actions.append('setMtiOutputConfiguration') except ValueError: - print "MTi sample rate argument must be integer." + print("MTi sample rate argument must be integer.") return 1 if o in ('-m','--mti-mode'): try: mode = int(a) actions.append('setMtiOutputConfiguration') except ValueError: - print "MTi mode argument must be integer." + print("MTi mode argument must be integer.") return 1 @@ -963,18 +962,18 @@ def main(): if device=='auto': devs = find_devices() if devs: - print "Detected devices:","".join('\n\t%s @ %d'%(d,p) for d,p in - devs) - print "Using %s @ %d"%devs[0] + print("Detected devices:","".join('\n\t%s @ %d'%(d,p) for d,p in + devs)) + print("Using %s @ %d"%devs[0]) device, baudrate = devs[0] else: - print "No suitable device found." + print("No suitable device found.") return 1 # find baudrate if not baudrate: baudrate = find_baudrate(device) if not baudrate: - print "No suitable baudrate found." + print("No suitable baudrate found.") return 1 # open device try: @@ -984,41 +983,41 @@ def main(): # execute actions if 'inspect' in actions: mt.GoToConfig() - print "Device: %s at %d bps:"%(device, baudrate) - print "General configuration:", mt.ReqConfiguration() - print "Available scenarios:", mt.ReqAvailableScenarios() - print "Current scenario: %s (id: %d)"%mt.ReqCurrentScenario()[::-1] + print("Device: %s at %d bps:"%(device, baudrate)) + print("General configuration:", mt.ReqConfiguration()) + print("Available scenarios:", mt.ReqAvailableScenarios()) + print("Current scenario: %s (id: %d)"%mt.ReqCurrentScenario()[::-1]) mt.GoToMeasurement() if 'change-baudrate' in actions: - print "Changing baudrate from %d to %d bps\n"%(baudrate, new_baudrate), + print("Changing baudrate from %d to %d bps\n"%(baudrate, new_baudrate)) sys.stdout.flush() mt.ChangeBaudrate(new_baudrate) if 'reset' in actions: - print "Restoring factory defaults", + print("Restoring factory defaults") sys.stdout.flush() mt.RestoreFactoryDefaults() - print " Ok" # should we test it was actually ok? + print(" Ok") # should we test it was actually ok? if 'xkf-scenario' in actions: - print "Changing XKF scenario..." + print("Changing XKF scenario...") sys.stdout.flush() mt.GoToConfig() mt.SetCurrentScenario(new_xkf) mt.GoToMeasurement() - print "Ok" + print("Ok") if 'setMtiOutputConfiguration' in actions: sys.stdout.flush() mt.GoToConfig() - print "Device intiated at %d Hz"%(sampleRate) + print("Device intiated at %d Hz"%(sampleRate)) mt.configureMti(sampleRate,mode) if 'echo' in actions: try: while True: - print mt.read_measurement(mode, settings) + print(mt.read_measurement(mode, settings)) except KeyboardInterrupt: pass except MTException as e: #traceback.print_tb(sys.exc_info()[2]) - print e + print(e) diff --git a/drivers/xsens_driver/src/mtnode.py b/drivers/xsens_driver/src/mtnode.py index ffc174c83a3..dec44174df7 100755 --- a/drivers/xsens_driver/src/mtnode.py +++ b/drivers/xsens_driver/src/mtnode.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import roslib; roslib.load_manifest('xsens_driver') import rospy import select diff --git a/ds4/ds4_driver/node/ds4_driver b/ds4/ds4_driver/node/ds4_driver index d75f03cfaf6..68f834e71ba 100755 --- a/ds4/ds4_driver/node/ds4_driver +++ b/ds4/ds4_driver/node/ds4_driver @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- """ diff --git a/ds4/ds4_msgs/CMakeLists.txt b/ds4/ds4_msgs/CMakeLists.txt index d0a51379fc3..c415fcec52a 100644 --- a/ds4/ds4_msgs/CMakeLists.txt +++ b/ds4/ds4_msgs/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(ds4_msgs) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED COMPONENTS message_generation diff --git a/lanelet2/lanelet2_core/CMakeLists.txt b/lanelet2/lanelet2_core/CMakeLists.txt index 3a8030d4bde..1612ef118f7 100644 --- a/lanelet2/lanelet2_core/CMakeLists.txt +++ b/lanelet2/lanelet2_core/CMakeLists.txt @@ -86,6 +86,10 @@ mrt_add_library(${PROJECT_NAME} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) +set_target_properties(${PROJECT_NAME} PROPERTIES + CXX_STANDARD 14 + ) + ############# ## Install ## ############# diff --git a/lanelet2/lanelet2_examples/scripts/tutorial.py b/lanelet2/lanelet2_examples/scripts/tutorial.py index 5122a5efce0..2bdaa9593e6 100755 --- a/lanelet2/lanelet2_examples/scripts/tutorial.py +++ b/lanelet2/lanelet2_examples/scripts/tutorial.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import lanelet2 import tempfile import os @@ -131,7 +131,7 @@ def part6routing(): def hasPathFromTo(graph, start, target): - class TargetFound: + class TargetFound(Exception): pass def raiseIfDestination(visitInformation): diff --git a/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp b/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp index c52400fdf57..8f641dad609 100644 --- a/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp +++ b/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp @@ -379,5 +379,8 @@ void part6Geometry() { // if you want more than an estimation you can use the primitives directly. Overlaps only returns true if the shared // area of the two primitives is >0. In 3d, the distance in z must also be smaller than a margin. + +#if 0 assert(geometry::overlaps3d(area, lanelet, 3)); +#endif } diff --git a/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py b/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py index bda01db78a1..18d33d3c2ab 100755 --- a/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py +++ b/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import lanelet2 import sys diff --git a/lanelet2/lanelet2_python/scripts/make_ids_positive.py b/lanelet2/lanelet2_python/scripts/make_ids_positive.py index 538c191ec60..251290004c6 100755 --- a/lanelet2/lanelet2_python/scripts/make_ids_positive.py +++ b/lanelet2/lanelet2_python/scripts/make_ids_positive.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import lanelet2 import sys diff --git a/lanelet2/lanelet2_python/scripts/print_ids.py b/lanelet2/lanelet2_python/scripts/print_ids.py index d2435f9b522..15d95b55c8e 100755 --- a/lanelet2/lanelet2_python/scripts/print_ids.py +++ b/lanelet2/lanelet2_python/scripts/print_ids.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import lanelet2 import sys diff --git a/messages/autoware_system_msgs/CMakeLists.txt b/messages/autoware_system_msgs/CMakeLists.txt index f0b97cbc97b..f1948e8221d 100644 --- a/messages/autoware_system_msgs/CMakeLists.txt +++ b/messages/autoware_system_msgs/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(autoware_system_msgs) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED COMPONENTS message_generation @@ -33,4 +33,4 @@ catkin_package( foreach(dir msg) install(DIRECTORY ${dir}/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) -endforeach(dir) \ No newline at end of file +endforeach(dir) diff --git a/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake b/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake index f14445547c9..fefae9fecc7 100644 --- a/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake +++ b/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake @@ -11,11 +11,11 @@ configure_file("${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${CMAKE_CURRENT_BINARY #so that rospack can find the packages in this workspace find_package(catkin REQUIRED) -#gather dependencies from package.xml. The command runs in python with the ros environemnt +#gather dependencies from package.xml. The command runs in python3 with the ros environemnt #variable set. This is used, because the python script is calling some ros tools to distinguish #between catkin and non catkin packages. execute_process( - COMMAND sh ${CATKIN_ENV} python ${MCM_ROOT}/scripts/generate_cmake_dependency_file.py "${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${MCM_ROOT}/yaml/base.yaml" "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake" + COMMAND sh ${CATKIN_ENV} /usr/bin/python3 ${MCM_ROOT}/scripts/generate_cmake_dependency_file.py "${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${MCM_ROOT}/yaml/base.yaml" "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake" RESULT_VARIABLE _GEN_DEPS_RES_ ERROR_VARIABLE _GEN_DEPS_ERROR_) if (NOT _GEN_DEPS_RES_ EQUAL 0) diff --git a/mrt_cmake_modules/cmake/Templates/python_api_install.py.in b/mrt_cmake_modules/cmake/Templates/python_api_install.py.in index e4e5060ecec..2166758626a 100755 --- a/mrt_cmake_modules/cmake/Templates/python_api_install.py.in +++ b/mrt_cmake_modules/cmake/Templates/python_api_install.py.in @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # this file is taken and converted from a bash script from catkin to correctly install python modules import os import sys diff --git a/mrt_cmake_modules/doc/generate_doc/conf.py b/mrt_cmake_modules/doc/generate_doc/conf.py index 0fc25f07851..27081d5735d 100644 --- a/mrt_cmake_modules/doc/generate_doc/conf.py +++ b/mrt_cmake_modules/doc/generate_doc/conf.py @@ -53,7 +53,7 @@ dochash = subprocess.Popen('git log -n1 --pretty=format:%H'.split(), stdout=subprocess.PIPE).communicate()[0] -print "dochash=", dochash +print("dochash=", dochash) copyright = u'MRT -- ' + ' Version ' + dochash + ", " + ' '.join(lastmod.split(' ')[:4]) # The version info for the project you're documenting, acts as replacement for @@ -195,8 +195,8 @@ # Grouping the document tree into LaTeX files. List of tuples # (source start file, target name, title, author, documentclass [howto/manual]). latex_documents = [ - ('generated_cmake_api', 'api.tex', ur'CMAKE API', - ur'Fabian Poggenhans', 'manual'), + ('generated_cmake_api', 'api.tex', r'CMAKE API', + r'Fabian Poggenhans', 'manual'), ] # The name of an image file (relative to this directory) to place at the top of diff --git a/mrt_cmake_modules/doc/generate_doc/generate_cmake_rst.py b/mrt_cmake_modules/doc/generate_doc/generate_cmake_rst.py index 7f803aaffed..7caf7821c8d 100755 --- a/mrt_cmake_modules/doc/generate_doc/generate_cmake_rst.py +++ b/mrt_cmake_modules/doc/generate_doc/generate_cmake_rst.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Software License Agreement (BSD License) # diff --git a/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py b/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py index 926e0ee925a..a9be5b88fbb 100755 --- a/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py +++ b/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py @@ -18,7 +18,7 @@ import os import sys import subprocess -import platform +import distro as dist import xml.etree.ElementTree as ET import yaml from catkin_pkg.packages import find_packages @@ -119,7 +119,7 @@ def readPackageCMakeData(rosDebYamlFileName): """ # load ros dep yaml file f = open(rosDebYamlFileName, "r") - rosDebYamlData = yaml.load(f) + rosDebYamlData = yaml.safe_load(f) # dictionary for storing cmake dependencies # e.g. { "" -> PackageCMakeData, "" -> PackageCMakeData ... } @@ -129,7 +129,7 @@ def readPackageCMakeData(rosDebYamlFileName): # cmake part (only ubuntu, etc.) if "cmake" in packageCMakeData: # find out which distribution - distro = platform.dist()[2] + distro = dist.linux_distribution()[2] if 'ROS_OS_OVERRIDE' in os.environ: ros_os_override = os.environ['ROS_OS_OVERRIDE'].split(':') if len(ros_os_override) == 2: diff --git a/mrt_cmake_modules/setup.py b/mrt_cmake_modules/setup.py index 0d11c491ad6..17ff5017cf9 100644 --- a/mrt_cmake_modules/setup.py +++ b/mrt_cmake_modules/setup.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup diff --git a/mrt_cmake_modules/yaml/base-vanilla.yaml b/mrt_cmake_modules/yaml/base-vanilla.yaml index f5658d91616..588cf5b250c 100644 --- a/mrt_cmake_modules/yaml/base-vanilla.yaml +++ b/mrt_cmake_modules/yaml/base-vanilla.yaml @@ -10,7 +10,7 @@ boost: cmake: components: - math_c99l wserialization math_tr1l thread random serialization log_setup prg_exec_monitor - wave system signals chrono math_c99 filesystem context locale timer math_tr1 + wave system chrono math_c99 filesystem context locale timer math_tr1 date_time regex graph program_options unit_test_framework math_tr1f math_c99f log atomic include_dirs: diff --git a/mrt_cmake_modules/yaml/base.yaml b/mrt_cmake_modules/yaml/base.yaml index 1a27463638f..7eec4c69008 100644 --- a/mrt_cmake_modules/yaml/base.yaml +++ b/mrt_cmake_modules/yaml/base.yaml @@ -35,7 +35,7 @@ boost: cmake: components: - wserialization thread random serialization log_setup prg_exec_monitor - wave system signals chrono filesystem locale timer date_time regex graph + wave system chrono filesystem locale timer date_time regex graph program_options unit_test_framework log atomic include_dirs: - Boost_INCLUDE_DIRS diff --git a/osrf_citysim/plugins/TrafficLightsGUIPlugin.cc b/osrf_citysim/plugins/TrafficLightsGUIPlugin.cc index 8d518942641..c6a43c4f1dd 100644 --- a/osrf_citysim/plugins/TrafficLightsGUIPlugin.cc +++ b/osrf_citysim/plugins/TrafficLightsGUIPlugin.cc @@ -15,9 +15,11 @@ * */ #include +#include #include #include #include +#include #include "TrafficLightsGUIPlugin.hh" @@ -77,10 +79,10 @@ void TrafficLightsGUIPlugin::Load(sdf::ElementPtr _sdf) void TrafficLightsGUIPlugin::OnKeyPress(ConstAnyPtr &_msg) { // Colors - auto red = std::make_pair(gazebo::common::Color::Red, "red"); - auto yellow = std::make_pair(gazebo::common::Color::Yellow, "yellow"); - auto green = std::make_pair(gazebo::common::Color::Green, "green"); - auto black = gazebo::common::Color::Black; + auto red = std::make_pair(ignition::math::Color::Red, "red"); + auto yellow = std::make_pair(ignition::math::Color::Yellow, "yellow"); + auto green = std::make_pair(ignition::math::Color::Green, "green"); + auto black = ignition::math::Color::Black; for (auto key : this->keys) { diff --git a/simulation/lgsvl_simulator_bridge/CMakeLists.txt b/simulation/lgsvl_simulator_bridge/CMakeLists.txt index ffd4bad45d2..0618daeeaf4 100644 --- a/simulation/lgsvl_simulator_bridge/CMakeLists.txt +++ b/simulation/lgsvl_simulator_bridge/CMakeLists.txt @@ -1,7 +1,8 @@ +cmake_policy(SET CMP0048 OLD) cmake_minimum_required(VERSION 2.8.3) project(lgsvl_simulator_bridge) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED COMPONENTS autoware_msgs @@ -55,4 +56,4 @@ endforeach(scripts) install(FILES plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) \ No newline at end of file +) diff --git a/simulation/lgsvl_simulator_bridge/scripts/rqt_lgsvl_simulator_configurator b/simulation/lgsvl_simulator_bridge/scripts/rqt_lgsvl_simulator_configurator index 4b55a65774a..59b0db273b1 100755 --- a/simulation/lgsvl_simulator_bridge/scripts/rqt_lgsvl_simulator_configurator +++ b/simulation/lgsvl_simulator_bridge/scripts/rqt_lgsvl_simulator_configurator @@ -1,8 +1,8 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys from rqt_gui.main import Main main = Main() -sys.exit(main.main(sys.argv, standalone='lgsvl_simulator_bridge.configurator.RqtLgsvlSimulatorConfiguratorPlugin')) \ No newline at end of file +sys.exit(main.main(sys.argv, standalone='lgsvl_simulator_bridge.configurator.RqtLgsvlSimulatorConfiguratorPlugin')) diff --git a/simulation/lgsvl_simulator_bridge/src/lgsvl_simulator_bridge/configurator.py b/simulation/lgsvl_simulator_bridge/src/lgsvl_simulator_bridge/configurator.py index 45ba1827191..14ee65c7cd0 100755 --- a/simulation/lgsvl_simulator_bridge/src/lgsvl_simulator_bridge/configurator.py +++ b/simulation/lgsvl_simulator_bridge/src/lgsvl_simulator_bridge/configurator.py @@ -29,8 +29,8 @@ def __init__(self, context): help="Put plugin in silent mode") args, unknowns = parser.parse_known_args(context.argv()) if not args.quiet: - print 'arguments: ', args - print 'unknowns: ', unknowns + print('arguments: {args}') + print('unknowns: {unknowns}') # Create QWidget self._widget = QWidget() @@ -145,4 +145,4 @@ def _handle_terminate_button_clicked(self): self._widget.terminate_button.setStyleSheet("background-color: #F5A9A9") return self._widget.terminate_button.setStyleSheet("background-color: #8fb8e0") - self._widget.launch_button.setStyleSheet("background-color: #FFFFFF") \ No newline at end of file + self._widget.launch_button.setStyleSheet("background-color: #FFFFFF") diff --git a/simulation/vehicle_gazebo_simulation_interface/CMakeLists.txt b/simulation/vehicle_gazebo_simulation_interface/CMakeLists.txt index 1370e835a9e..2465d94f9b2 100644 --- a/simulation/vehicle_gazebo_simulation_interface/CMakeLists.txt +++ b/simulation/vehicle_gazebo_simulation_interface/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(vehicle_gazebo_simulation_interface) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED geometry_msgs diff --git a/simulation/wf_simulator/scripts/fitParamDelayInputModel.py b/simulation/wf_simulator/scripts/fitParamDelayInputModel.py index b40899e9292..e4e91243927 100644 --- a/simulation/wf_simulator/scripts/fitParamDelayInputModel.py +++ b/simulation/wf_simulator/scripts/fitParamDelayInputModel.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- import numpy as np diff --git a/utilities/autoware_bag_tools/scripts/change_frame_id.py b/utilities/autoware_bag_tools/scripts/change_frame_id.py index 92f04aa8c18..806be0dd08b 100755 --- a/utilities/autoware_bag_tools/scripts/change_frame_id.py +++ b/utilities/autoware_bag_tools/scripts/change_frame_id.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Copyright 2018-2019 Autoware Foundation # @@ -105,6 +105,6 @@ def progress_bar(iteration, total): try: change_frame_id(args.i,args.o,args.f,args.t) - except Exception, e: + except Exception as e: import traceback traceback.print_exc() diff --git a/utilities/autoware_bag_tools/scripts/replace_msg_time_with_hdr.py b/utilities/autoware_bag_tools/scripts/replace_msg_time_with_hdr.py index a156fe3d54b..5525556f5f8 100755 --- a/utilities/autoware_bag_tools/scripts/replace_msg_time_with_hdr.py +++ b/utilities/autoware_bag_tools/scripts/replace_msg_time_with_hdr.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Copyright 2018-2019 Autoware Foundation # @@ -77,6 +77,6 @@ def rpl_msg_time_with_hdr(inbag,outbag): args = parser.parse_args() try: rpl_msg_time_with_hdr(args.i, args.o) - except Exception, e: + except Exception as e: import traceback traceback.print_exc() diff --git a/utilities/autoware_camera_lidar_calibrator/nodes/cameracalibrator.py b/utilities/autoware_camera_lidar_calibrator/nodes/cameracalibrator.py index 2a74a617496..68ae3e772e6 100755 --- a/utilities/autoware_camera_lidar_calibrator/nodes/cameracalibrator.py +++ b/utilities/autoware_camera_lidar_calibrator/nodes/cameracalibrator.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Copyright 2015-2019 Autoware Foundation # diff --git a/utilities/autoware_camera_lidar_calibrator/nodes/cameracheck.py b/utilities/autoware_camera_lidar_calibrator/nodes/cameracheck.py index fd30b220f39..300dbd0daaa 100755 --- a/utilities/autoware_camera_lidar_calibrator/nodes/cameracheck.py +++ b/utilities/autoware_camera_lidar_calibrator/nodes/cameracheck.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Software License Agreement (BSD License) # diff --git a/utilities/autoware_camera_lidar_calibrator/scripts/tarfile_calibration.py b/utilities/autoware_camera_lidar_calibrator/scripts/tarfile_calibration.py index 29f73f6704f..fbc76533599 100755 --- a/utilities/autoware_camera_lidar_calibrator/scripts/tarfile_calibration.py +++ b/utilities/autoware_camera_lidar_calibrator/scripts/tarfile_calibration.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2018-2019 Autoware Foundation # diff --git a/utilities/autoware_camera_lidar_calibrator/setup.py b/utilities/autoware_camera_lidar_calibrator/setup.py index a86b94d4f66..c126cebb6db 100644 --- a/utilities/autoware_camera_lidar_calibrator/setup.py +++ b/utilities/autoware_camera_lidar_calibrator/setup.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup diff --git a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/calibrator.py b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/calibrator.py index 64ded2fb441..c8a77daa073 100644 --- a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/calibrator.py +++ b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/calibrator.py @@ -1,4 +1,4 @@ -# !/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2018-2019 Autoware Foundation # diff --git a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_calibrator.py b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_calibrator.py index c2bb51fd06e..7d9b8d60820 100644 --- a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_calibrator.py +++ b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_calibrator.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Copyright 2018-2019 Autoware Foundation # diff --git a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_checker.py b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_checker.py index 07e70c368d2..f88128c061b 100644 --- a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_checker.py +++ b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_calibration/camera_checker.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # # Copyright 2018-2019 Autoware Foundation # diff --git a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_lidar_calibration/camera_lidar_calibration_node.cpp b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_lidar_calibration/camera_lidar_calibration_node.cpp index 87658e5486a..953e137cc0e 100644 --- a/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_lidar_calibration/camera_lidar_calibration_node.cpp +++ b/utilities/autoware_camera_lidar_calibrator/src/autoware_camera_lidar_calibration/camera_lidar_calibration_node.cpp @@ -30,8 +30,9 @@ #include "opencv2/imgproc/imgproc.hpp" #include "opencv2/calib3d/calib3d.hpp" -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include + #include #else #include #endif diff --git a/utilities/autoware_camera_lidar_calibrator/test/directed.py b/utilities/autoware_camera_lidar_calibrator/test/directed.py index 604f42f328a..21bea9e997d 100644 --- a/utilities/autoware_camera_lidar_calibrator/test/directed.py +++ b/utilities/autoware_camera_lidar_calibrator/test/directed.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Software License Agreement (BSD License) # diff --git a/utilities/autoware_camera_lidar_calibrator/test/multiple_boards.py b/utilities/autoware_camera_lidar_calibrator/test/multiple_boards.py index 309aed77789..a5ee8574426 100644 --- a/utilities/autoware_camera_lidar_calibrator/test/multiple_boards.py +++ b/utilities/autoware_camera_lidar_calibrator/test/multiple_boards.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Software License Agreement (BSD License) # diff --git a/utilities/autoware_launcher/scripts/main b/utilities/autoware_launcher/scripts/main index 7efb1b5ed47..59c809a3ec4 100755 --- a/utilities/autoware_launcher/scripts/main +++ b/utilities/autoware_launcher/scripts/main @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 import logging import sys diff --git a/utilities/autoware_launcher/scripts/tool b/utilities/autoware_launcher/scripts/tool index c8ffd4810ca..da7a37600e1 100755 --- a/utilities/autoware_launcher/scripts/tool +++ b/utilities/autoware_launcher/scripts/tool @@ -1,4 +1,4 @@ -#! /usr/bin/env python +#! /usr/bin/env python3 import logging import sys @@ -7,4 +7,4 @@ from autoware_launcher.tool import editor logging.basicConfig(level=logging.DEBUG, format="%(levelname)-5s: %(name)s: %(message)s") -sys.exit(editor.main(sys.argv)) \ No newline at end of file +sys.exit(editor.main(sys.argv)) diff --git a/utilities/data_preprocessor/scripts/baseframe.py b/utilities/data_preprocessor/scripts/baseframe.py index c2f44a067a2..61d1dcbbc52 100644 --- a/utilities/data_preprocessor/scripts/baseframe.py +++ b/utilities/data_preprocessor/scripts/baseframe.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: UTF-8 -*- import wx @@ -20,47 +20,47 @@ def __do_layout(self): pass def OnLaunchKill(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLaunchKill' not implemented!" + print("Event handler 'OnLaunchKill' not implemented!") event.Skip() def OnSetupLocalizer(self, event): # wxGlade: MyFrame. - print "Event handler 'OnSetupLocalizer' not implemented!" + print("Event handler 'OnSetupLocalizer' not implemented!") event.Skip() def OnCalibrationPublisher(self, event): # wxGlade: MyFrame. - print "Event handler 'OnCalibrationPublisher' not implemented!" + print("Event handler 'OnCalibrationPublisher' not implemented!") event.Skip() def OnLamp(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLamp' not implemented!" + print("Event handler 'OnLamp' not implemented!") event.Skip() def OnIndi(self, event): # wxGlade: MyFrame. - print "Event handler 'OnIndi' not implemented!" + print("Event handler 'OnIndi' not implemented!") event.Skip() def OnGear(self, event): # wxGlade: MyFrame. - print "Event handler 'OnGear' not implemented!" + print("Event handler 'OnGear' not implemented!") event.Skip() def OnQuery(self, event): # wxGlade: MyFrame. - print "Event handler 'OnQuery' not implemented!" + print("Event handler 'OnQuery' not implemented!") event.Skip() def OnROSbagPlay(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagPlay' not implemented!" + print("Event handler 'OnROSbagPlay' not implemented!") event.Skip() def OnFtrace(self, event): # wxGlade: MyFrame. - print "Event handler 'OnFtrace' not implemented!" + print("Event handler 'OnFtrace' not implemented!") event.Skip() def OnEcho(self, event): # wxGlade: MyFrame. - print "Event handler 'OnEcho' not implemented!" + print("Event handler 'OnEcho' not implemented!") event.Skip() def OnRefreshTopics(self, event): # wxGlade: MyFrame. - print "Event handler 'OnRefreshTopics' not implemented!" + print("Event handler 'OnRefreshTopics' not implemented!") event.Skip() class MyApp(wx.App): diff --git a/utilities/data_preprocessor/scripts/create_h5file.py b/utilities/data_preprocessor/scripts/create_h5file.py index 956799299f6..840f29974b5 100644 --- a/utilities/data_preprocessor/scripts/create_h5file.py +++ b/utilities/data_preprocessor/scripts/create_h5file.py @@ -1,7 +1,8 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import h5py def create_h5file(filename, keys, data): + pass if __name__ == "__main__": diff --git a/utilities/data_preprocessor/scripts/data_preprocessor.py b/utilities/data_preprocessor/scripts/data_preprocessor.py index d327c13d269..97dd20e9a8a 100755 --- a/utilities/data_preprocessor/scripts/data_preprocessor.py +++ b/utilities/data_preprocessor/scripts/data_preprocessor.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import wx import wx.lib.buttons @@ -51,16 +51,16 @@ def __init__(self, *args, **kwds): self.log_que_stdout = Queue.Queue() self.log_que_stderr = Queue.Queue() self.log_que_show = Queue.Queue() - ##################################### - ## ros - ##################################### + ##################################### + ## ros + ##################################### rospy.init_node('runime_manager', anonymous=True) rospy.Subscriber('to_rtmgr', std_msgs.msg.String, self.ROSCb) self.pub = rospy.Publisher('from_rtmgr', std_msgs.msg.String, queue_size=10) - ####################################### - # for Select Topic & Excecution Tab - ####################################### + ####################################### + # for Select Topic & Excecution Tab + ####################################### self.label_rosbag_play_bar.Destroy() self.label_rosbag_play_bar = BarLabel(self.tab_select, ' Playing... ') self.label_rosbag_play_bar.Enable(False) @@ -124,7 +124,7 @@ def __init__(self, *args, **kwds): self.tab_names = [ self.name_get_cond(tab, cond=cond, def_ret='').replace('tab_', '', 1) for tab in self.all_tabs ] # new_btn_grps = ( lambda btn_names, tab_names=self.tab_names : - [ [ self.obj_get('button_{}_{}'.format(bn, tn)) for tn in tab_names ] for bn in btn_names ] ) + [ [ self.obj_get('button_{}_{}'.format(bn, tn)) for tn in tab_names ] for bn in btn_names ] ) self.alias_grps = new_btn_grps( ('rosbag', 'rviz', 'rqt') ) @@ -142,9 +142,9 @@ def __init__(self, *args, **kwds): # # self.lb_top5 = [] # for i in range(5): - # lb = wx.StaticText(self, wx.ID_ANY, '') - # change_font_point_by_rate(lb, 0.75) - # self.lb_top5.append(lb) + # lb = wx.StaticText(self, wx.ID_ANY, '') + # change_font_point_by_rate(lb, 0.75) + # self.lb_top5.append(lb) # line = wx.StaticLine(self, wx.ID_ANY) # ibl = InfoBarLabel(self, 'Memory', bar_orient=wx.HORIZONTAL) # szr = sizer_wrap(self.lb_top5 + [ line, ibl ], flag=wx.EXPAND | wx.FIXED_MINSIZE) @@ -153,8 +153,8 @@ def __init__(self, *args, **kwds): # self.status_dic = self.load_yaml('status.yaml') # # th_arg = { 'setting':self.status_dic.get('top_cmd_setting', {}), - # 'cpu_ibls':cpu_ibls, 'mem_ibl':ibl, - # 'toprc':toprc, 'backup':backup } + # 'cpu_ibls':cpu_ibls, 'mem_ibl':ibl, + # 'toprc':toprc, 'backup':backup } # # thinf = th_start(self.top_cmd_th, th_arg) # self.all_th_infs.append(thinf) @@ -231,58 +231,58 @@ def OnROSbagPlay2(self, event): self.button_confirm_depth.Enable() self.button_confirm_topics.Enable() dic = { (True,True):('#F9F9F8','#8B8BB9'), (True,False):('#F9F9F8','#E0E0F0') } - self.button_play_rosbag_play2.SetBackgroundColour(wx.NullColour) + self.button_play_rosbag_play2.SetBackgroundColour(wx.NullColour) self.button_stop_rosbag_play2.SetBackgroundColour("#E0E0F0") self.button_pause_rosbag_play2.SetBackgroundColour(wx.NullColour) self.button_play_rosbag_play2.SetForegroundColour(wx.NullColour) sigint = 'SIGTERM' if True: - terminate_children(self.proc, sigint) + terminate_children(self.proc, sigint) terminate(self.proc, sigint) self.proc.wait() # del self.cmd_dic[self.button_play_rosbag_play2] if self.proc in self.all_procs: - self.all_procs.remove(self.proc) + self.all_procs.remove(self.proc) else: wx.MessageBox("Please Set Bag File") def rosbag_play_progress_bar2(self, file, ev): - while not ev.wait(0): - s = self.stdout_file_search(file, 'Duration:') - if not s: - break - lst = s.split() - pos = str_to_float(lst[0]) - # lst[1] is '/' - total = str_to_float(lst[2]) - if total == 0: - continue - prg = int(100 * pos / total + 0.5) - pos = str(int(pos)) - total = str(int(total)) - - wx.CallAfter(self.label_rosbag_play_bar2.set, prg) - wx.CallAfter(self.label_rosbag_play_pos2.SetLabel, pos) - wx.CallAfter(self.label_rosbag_play_total2.SetLabel, total) - wx.CallAfter(self.label_rosbag_play_bar2.clear) - wx.CallAfter(self.label_rosbag_play_pos2.SetLabel, '') - wx.CallAfter(self.label_rosbag_play_total2.SetLabel, '') + while not ev.wait(0): + s = self.stdout_file_search(file, 'Duration:') + if not s: + break + lst = s.split() + pos = str_to_float(lst[0]) + # lst[1] is '/' + total = str_to_float(lst[2]) + if total == 0: + continue + prg = int(100 * pos / total + 0.5) + pos = str(int(pos)) + total = str(int(total)) + + wx.CallAfter(self.label_rosbag_play_bar2.set, prg) + wx.CallAfter(self.label_rosbag_play_pos2.SetLabel, pos) + wx.CallAfter(self.label_rosbag_play_total2.SetLabel, total) + wx.CallAfter(self.label_rosbag_play_bar2.clear) + wx.CallAfter(self.label_rosbag_play_pos2.SetLabel, '') + wx.CallAfter(self.label_rosbag_play_total2.SetLabel, '') def stdout_file_search(self, file, k): - s = '' - while True: - c = file.read(1) - if not c: - return None - if c != '\r' and c != '\n': - s += c - continue - s = s.strip() - if k in s: - break - s = '' - i = s.find(k) + len(k) - return s[i:] + s = '' + while True: + c = file.read(1) + if not c: + return None + if c != '\r' and c != '\n': + s += c + continue + s = s.strip() + if k in s: + break + s = '' + i = s.find(k) + len(k) + return s[i:] def OnConvertCheckedTopic(self, event): push = event.GetEventObject() @@ -959,2518 +959,2520 @@ def get_depth_topic(self): wx.MessageBox("Please Set Bag File") def OnClose(self, event): - # kill_all - for proc in self.all_procs[:]: # copy - (_, obj) = self.proc_to_cmd_dic_obj(proc) - self.launch_kill(False, 'dmy', proc, obj=obj) - - save_dic = {} - for (name, pdic) in self.load_dic.items(): - if pdic and pdic != {}: - prm = self.cfg_dic( {'name':name, 'pdic':pdic} ).get('param', {}) - no_saves = prm.get('no_save_vars', []) - pdic = pdic.copy() - for k in pdic.keys(): - if k in no_saves: - del pdic[k] - save_dic[name] = pdic - if save_dic != {}: - dir = rtmgr_src_dir() - print('saving param.yaml') - f = open(dir + 'param.yaml', 'w') - s = yaml.dump(save_dic, default_flow_style=False) - f.write(s) - f.close() - - shutdown_proc_manager() - - shutdown_sh = self.get_autoware_dir() + '/ros/shutdown' - if os.path.exists(shutdown_sh): - os.system(shutdown_sh) - - for thinf in self.all_th_infs: - th_end(thinf) - - self.Destroy() + # kill_all + for proc in self.all_procs[:]: # copy + (_, obj) = self.proc_to_cmd_dic_obj(proc) + self.launch_kill(False, 'dmy', proc, obj=obj) + + save_dic = {} + for (name, pdic) in self.load_dic.items(): + if pdic and pdic != {}: + prm = self.cfg_dic( {'name':name, 'pdic':pdic} ).get('param', {}) + no_saves = prm.get('no_save_vars', []) + pdic = pdic.copy() + for k in pdic.keys(): + if k in no_saves: + del pdic[k] + save_dic[name] = pdic + if save_dic != {}: + dir = rtmgr_src_dir() + print('saving param.yaml') + f = open(dir + 'param.yaml', 'w') + s = yaml.dump(save_dic, default_flow_style=False) + f.write(s) + f.close() + + shutdown_proc_manager() + + shutdown_sh = self.get_autoware_dir() + '/ros/shutdown' + if os.path.exists(shutdown_sh): + os.system(shutdown_sh) + + for thinf in self.all_th_infs: + th_end(thinf) + + self.Destroy() def ROSCb(self, data): - print('recv topic msg : ' + data.data) + print('recv topic msg : ' + data.data) - r = rospy.Rate(10) - rospy.is_shutdown() - r.sleep() - self.pub.publish(data.data) - r.sleep() + r = rospy.Rate(10) + rospy.is_shutdown() + r.sleep() + self.pub.publish(data.data) + r.sleep() def setup_buttons(self, d, run_dic): - for (k,d2) in d.items(): + for (k,d2) in d.items(): pfs = [ 'button_', 'checkbox_' ] obj = next( (self.obj_get(pf+k) for pf in pfs if self.obj_get(pf+k)), None) if not obj: - s = 'button_' + k - obj = StrValObj(s, False) - setattr(self, s, obj) + s = 'button_' + k + obj = StrValObj(s, False) + setattr(self, s, obj) if not d2 or type(d2) is not dict: - continue + continue if 'run' in d2: - run_dic[obj] = (d2['run'], None) + run_dic[obj] = (d2['run'], None) set_tooltip(obj, d2) gdic = self.gdic_get_1st(d2) if 'param' in d2: - pdic = self.load_dic_pdic_setup(k, d2) - prm = self.get_param(d2.get('param')) - for var in prm.get('vars'): - name = var.get('name') - if name not in pdic and 'v' in var: - pdic[name] = var.get('v') - - for (name, v) in pdic.items(): - restore = eval( gdic.get(name, {}).get('restore', 'lambda a : None') ) - restore(v) - - self.add_cfg_info(obj, obj, k, pdic, gdic, False, prm) - - pnls = [ gdic.get(var.get('name'), {}).get('panel') for var in prm.get('vars') ] - for pnl in [ gdic.get('panel') ] + pnls: - if pnl: + pdic = self.load_dic_pdic_setup(k, d2) + prm = self.get_param(d2.get('param')) + for var in prm.get('vars'): + name = var.get('name') + if name not in pdic and 'v' in var: + pdic[name] = var.get('v') + + for (name, v) in pdic.items(): + restore = eval( gdic.get(name, {}).get('restore', 'lambda a : None') ) + restore(v) + + self.add_cfg_info(obj, obj, k, pdic, gdic, False, prm) + + pnls = [ gdic.get(var.get('name'), {}).get('panel') for var in prm.get('vars') ] + for pnl in [ gdic.get('panel') ] + pnls: + if pnl: self.set_param_panel(obj, eval_if_str(self, pnl)) #self.set_param_panel(obj, pnl) else: - self.add_cfg_info(obj, obj, k, None, gdic, False, None) + self.add_cfg_info(obj, obj, k, None, gdic, False, None) def OnGear(self, event): - grp = { self.button_statchk_d : 1, - self.button_statchk_r : 2, - self.button_statchk_b : 3, - self.button_statchk_n : 4 } - self.radio_action(event, grp.keys()) - v = grp.get(event.GetEventObject()) - if v is not None: - pub = rospy.Publisher('gear_cmd', gear_cmd, queue_size=10) - pub.publish(gear_cmd(gear=v)) + grp = { self.button_statchk_d : 1, + self.button_statchk_r : 2, + self.button_statchk_b : 3, + self.button_statchk_n : 4 } + self.radio_action(event, grp.keys()) + v = grp.get(event.GetEventObject()) + if v is not None: + pub = rospy.Publisher('gear_cmd', gear_cmd, queue_size=10) + pub.publish(gear_cmd(gear=v)) def OnLamp(self, event): - pub = rospy.Publisher('lamp_cmd', LampCmd, queue_size=10) - msg = LampCmd() - msg.l = self.button_statchk_lamp_l.GetValue() - msg.r = self.button_statchk_lamp_r.GetValue() - pub.publish(msg) + pub = rospy.Publisher('lamp_cmd', LampCmd, queue_size=10) + msg = LampCmd() + msg.l = self.button_statchk_lamp_l.GetValue() + msg.r = self.button_statchk_lamp_r.GetValue() + pub.publish(msg) def OnIndi(self, event): - pub = rospy.Publisher('indicator_cmd', IndicatorCmd, queue_size=10) - msg = IndicatorCmd() - msg.l = self.button_statchk_indi_l.GetValue() - msg.r = self.button_statchk_indi_r.GetValue() - pub.publish(msg) + pub = rospy.Publisher('indicator_cmd', IndicatorCmd, queue_size=10) + msg = IndicatorCmd() + msg.l = self.button_statchk_indi_l.GetValue() + msg.r = self.button_statchk_indi_r.GetValue() + pub.publish(msg) def OnAutoPilot(self, event): - obj = event.GetEventObject() - self.alias_sync(obj) - v = obj.GetValue() - pub = rospy.Publisher('mode_cmd', mode_cmd, queue_size=10) - pub.publish(mode_cmd(mode=v)) + obj = event.GetEventObject() + self.alias_sync(obj) + v = obj.GetValue() + pub = rospy.Publisher('mode_cmd', mode_cmd, queue_size=10) + pub.publish(mode_cmd(mode=v)) def radio_action(self, event, grp): - push = event.GetEventObject() - for b in grp: - v = b.GetValue() - act = None - act = True if b is push and not v else act - act = False if b is not push and v else act - if act is not None: - set_val(b, act) + push = event.GetEventObject() + for b in grp: + v = b.GetValue() + act = None + act = True if b is push and not v else act + act = False if b is not push and v else act + if act is not None: + set_val(b, act) def stat_label_off(self, obj): - qs_nms = [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ] - exec_time = self.runtime_dic.get('exec_time', {}) - - gdic = self.obj_to_gdic(obj, {}) - msg = std_msgs.msg.Bool(False) - for k in gdic.get('stat_topic', []): - # exec_time off - if next( (dic for dic in exec_time.values() if k in dic), None): - self.exec_time_callback(std_msgs.msg.Float32(0), (k, 'data')) - else: - self.stat_callback(msg, k) - - # Quick Start tab, exec_time off - obj_nm = self.name_get(obj) - nm = next( (nm for nm in qs_nms if 'button_' + nm + '_qs' == obj_nm), None) - for key in exec_time.get(nm, {}): - self.exec_time_callback(std_msgs.msg.Float32(0), (key, 'data')) + qs_nms = [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ] + exec_time = self.runtime_dic.get('exec_time', {}) + + gdic = self.obj_to_gdic(obj, {}) + msg = std_msgs.msg.Bool(False) + for k in gdic.get('stat_topic', []): + # exec_time off + if next( (dic for dic in exec_time.values() if k in dic), None): + self.exec_time_callback(std_msgs.msg.Float32(0), (k, 'data')) + else: + self.stat_callback(msg, k) + + # Quick Start tab, exec_time off + obj_nm = self.name_get(obj) + nm = next( (nm for nm in qs_nms if 'button_' + nm + '_qs' == obj_nm), None) + for key in exec_time.get(nm, {}): + self.exec_time_callback(std_msgs.msg.Float32(0), (key, 'data')) def route_cmd_callback(self, data): - self.route_cmd_waypoint = data.point + self.route_cmd_waypoint = data.point def stat_callback(self, msg, k): - self.stat_dic[k] = msg.data - if k == 'pmap': - v = self.stat_dic.get(k) - wx.CallAfter(self.label_point_cloud.SetLabel, 'OK' if v else '') - if k in [ 'pmap', 'vmap' ]: - v = self.stat_dic.get('pmap') and self.stat_dic.get('vmap') - wx.CallAfter(self.label_map_qs.SetLabel, 'OK' if v else '') - - def exec_time_callback(self, msg, (key, attr)): - msec = int(getattr(msg, attr, 0)) - exec_time = self.runtime_dic.get('exec_time', {}) - (nm, dic) = next( ( (nm, dic) for (nm, dic) in exec_time.items() if key in dic), None) - dic[ key ] = msec - lb = self.obj_get('label_' + nm + '_qs') - if lb: - sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) - wx.CallAfter(lb.SetLabel, str(sum)+' ms' if sum > 0 else '') - - # update Status tab - lb = '' - for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: - dic = exec_time.get(nm, {}) - sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) - if sum > 0: - s = nm + ' : ' + str(sum) + ' ms' - lb += s + '\n' - wx.CallAfter(self.label_node_time.SetLabel, lb) - wx.CallAfter(self.label_node_time.GetParent().FitInside) + self.stat_dic[k] = msg.data + if k == 'pmap': + v = self.stat_dic.get(k) + wx.CallAfter(self.label_point_cloud.SetLabel, 'OK' if v else '') + if k in [ 'pmap', 'vmap' ]: + v = self.stat_dic.get('pmap') and self.stat_dic.get('vmap') + wx.CallAfter(self.label_map_qs.SetLabel, 'OK' if v else '') + + def exec_time_callback(self, msg, key_attr): + key, attr = key_attr + msec = int(getattr(msg, attr, 0)) + exec_time = self.runtime_dic.get('exec_time', {}) + (nm, dic) = next( ( (nm, dic) for (nm, dic) in exec_time.items() if key in dic), None) + dic[ key ] = msec + lb = self.obj_get('label_' + nm + '_qs') + if lb: + sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) + wx.CallAfter(lb.SetLabel, str(sum)+' ms' if sum > 0 else '') + + # update Status tab + lb = '' + for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: + dic = exec_time.get(nm, {}) + sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) + if sum > 0: + s = nm + ' : ' + str(sum) + ' ms' + lb += s + '\n' + wx.CallAfter(self.label_node_time.SetLabel, lb) + wx.CallAfter(self.label_node_time.GetParent().FitInside) # # Setup tab # def OnSetupLocalizer(self, event): - obj = self.button_setup_tf - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - self.update_func(pdic, gdic, prm) + obj = self.button_setup_tf + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + self.update_func(pdic, gdic, prm) # # Computing Tab # def OnTreeMotion(self, event): - tree = event.GetEventObject() - pt = event.GetPosition() - event.Skip() - (item, flags) = tree.HitTest(pt) - if flags & CT.TREE_HITTEST_ONITEMLABEL == 0: - return - text = item.GetData() - if not text: - return - x = item.GetX() - y = item.GetY() - w = item.GetWidth() - h = item.GetHeight() - (x, y) = tree.CalcScrolledPosition(x, y) - iw = tree.GetItemWindow(item) - w -= iw.GetSize()[0] if iw else 0 - if not wx.Rect(x, y, w, h).Contains(pt): - return - (x, y) = tree.ClientToScreen((x, y)) - self.tip_info = (tree, text, wx.Rect(x, y, w, h)) - if getattr(self, 'tip_timer', None) is None: - self.tip_timer = wx.Timer(self) - self.Bind(wx.EVT_TIMER, self.OnTipTimer, self.tip_timer) - self.tip_timer.Start(200, oneShot=True) + tree = event.GetEventObject() + pt = event.GetPosition() + event.Skip() + (item, flags) = tree.HitTest(pt) + if flags & CT.TREE_HITTEST_ONITEMLABEL == 0: + return + text = item.GetData() + if not text: + return + x = item.GetX() + y = item.GetY() + w = item.GetWidth() + h = item.GetHeight() + (x, y) = tree.CalcScrolledPosition(x, y) + iw = tree.GetItemWindow(item) + w -= iw.GetSize()[0] if iw else 0 + if not wx.Rect(x, y, w, h).Contains(pt): + return + (x, y) = tree.ClientToScreen((x, y)) + self.tip_info = (tree, text, wx.Rect(x, y, w, h)) + if getattr(self, 'tip_timer', None) is None: + self.tip_timer = wx.Timer(self) + self.Bind(wx.EVT_TIMER, self.OnTipTimer, self.tip_timer) + self.tip_timer.Start(200, oneShot=True) def OnTipTimer(self, event): - if getattr(self, 'tip_info', None): - (tree, text, rect) = self.tip_info - (w, h) = self.GetSize() - wx.TipWindow(tree, text, maxLength=w, rectBound=rect) + if getattr(self, 'tip_info', None): + (tree, text, rect) = self.tip_info + (w, h) = self.GetSize() + wx.TipWindow(tree, text, maxLength=w, rectBound=rect) def OnTreeChecked(self, event): - self.OnChecked_obj(event.GetItem()) + self.OnChecked_obj(event.GetItem()) def OnChecked_obj(self, obj): - self.OnLaunchKill_obj(obj) + self.OnLaunchKill_obj(obj) def OnHyperlinked(self, event): - self.OnHyperlinked_obj(event.GetEventObject()) + self.OnHyperlinked_obj(event.GetEventObject()) def OnHyperlinked_obj(self, obj): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - if pdic is None or prm is None: - return - dic_list_push(gdic, 'dialog_type', 'config') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + if pdic is None or prm is None: + return + dic_list_push(gdic, 'dialog_type', 'config') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') def obj_to_add_args(self, obj, msg_box=True): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - if pdic is None or prm is None: - return None - - if 'need_camera_info' in gdic.get('flags', []) and msg_box: - ids = self.camera_ids() - if ids: - var = self.get_var(prm, 'camera_id', {}) - var['choices'] = ids - - dic_list_push(gdic, 'dialog_type', 'sel_cam') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - dlg_ret = show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') - if dlg_ret != 0: - return False - else: - pdic['camera_id'] = '' - - if 'open_dialog' in gdic.get('flags', []) and msg_box: - dic_list_push(gdic, 'dialog_type', 'open') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - dlg_ret = show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') - if dlg_ret != 0: - return False - - self.update_func(pdic, gdic, prm) - s = '' - - vars = [] - for var in prm.get('vars'): - cmd_param = var.get('cmd_param') - if cmd_param: - vars.append(var) - - for var in vars[:]: # copy - cmd_param = var.get('cmd_param') - if cmd_param.get('tail'): - vars.remove(var) - vars.append(var) - - for var in vars[:]: # copy - name = var.get('name') - flags = gdic.get(name, {}).get('flags', []) - if 'hide' in flags or 'disable' in flags: - vars.remove(var) - - for var in vars: - cmd_param = var.get('cmd_param') - name = var.get('name') - v = pdic.get(name) - if (v is None or v == '') and 'default' in cmd_param: - v = cmd_param.get('default') - if dic_eval_if_str(self, cmd_param, 'must') and (v is None or v == ''): - print 'cmd_param', name, 'is required' - if msg_box: - wx.MessageBox('cmd_param ' + name + ' is required') - return False - if dic_eval_if_str(self, cmd_param, 'only_enable') and not v: - continue - if dic_eval_if_str(self, cmd_param, 'only_disable') and v: - continue - name = cmd_param.get('var_name', name) - unpack = cmd_param.get('unpack') - if unpack is not None: - v = ' '.join( v.split(unpack) ) - add = '' - dash = cmd_param.get('dash') - if dash is not None: - add += dash + name - delim = cmd_param.get('delim') - if delim is not None: - str_v = str(v) - if var.get('kind') is None: - str_v = adjust_num_str(str_v) - if var.get('kind') == 'path': - str_v = path_expand_cmd(str_v) - str_v = os.path.expandvars(os.path.expanduser(str_v)) - - relpath_from = var.get('relpath_from') - if relpath_from: - relpath_from = path_expand_cmd(relpath_from) - relpath_from = os.path.expandvars(os.path.expanduser(relpath_from)) - str_v = os.path.relpath(str_v, relpath_from) - add += delim + str_v - if add != '': - s += add + ' ' - return s.strip(' ').split(' ') if s != '' else None + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + if pdic is None or prm is None: + return None + + if 'need_camera_info' in gdic.get('flags', []) and msg_box: + ids = self.camera_ids() + if ids: + var = self.get_var(prm, 'camera_id', {}) + var['choices'] = ids + + dic_list_push(gdic, 'dialog_type', 'sel_cam') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + dlg_ret = show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') + if dlg_ret != 0: + return False + else: + pdic['camera_id'] = '' + + if 'open_dialog' in gdic.get('flags', []) and msg_box: + dic_list_push(gdic, 'dialog_type', 'open') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + dlg_ret = show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') + if dlg_ret != 0: + return False + + self.update_func(pdic, gdic, prm) + s = '' + + vars = [] + for var in prm.get('vars'): + cmd_param = var.get('cmd_param') + if cmd_param: + vars.append(var) + + for var in vars[:]: # copy + cmd_param = var.get('cmd_param') + if cmd_param.get('tail'): + vars.remove(var) + vars.append(var) + + for var in vars[:]: # copy + name = var.get('name') + flags = gdic.get(name, {}).get('flags', []) + if 'hide' in flags or 'disable' in flags: + vars.remove(var) + + for var in vars: + cmd_param = var.get('cmd_param') + name = var.get('name') + v = pdic.get(name) + if (v is None or v == '') and 'default' in cmd_param: + v = cmd_param.get('default') + if dic_eval_if_str(self, cmd_param, 'must') and (v is None or v == ''): + print('cmd_param', name, 'is required') + if msg_box: + wx.MessageBox('cmd_param ' + name + ' is required') + return False + if dic_eval_if_str(self, cmd_param, 'only_enable') and not v: + continue + if dic_eval_if_str(self, cmd_param, 'only_disable') and v: + continue + name = cmd_param.get('var_name', name) + unpack = cmd_param.get('unpack') + if unpack is not None: + v = ' '.join( v.split(unpack) ) + add = '' + dash = cmd_param.get('dash') + if dash is not None: + add += dash + name + delim = cmd_param.get('delim') + if delim is not None: + str_v = str(v) + if var.get('kind') is None: + str_v = adjust_num_str(str_v) + if var.get('kind') == 'path': + str_v = path_expand_cmd(str_v) + str_v = os.path.expandvars(os.path.expanduser(str_v)) + + relpath_from = var.get('relpath_from') + if relpath_from: + relpath_from = path_expand_cmd(relpath_from) + relpath_from = os.path.expandvars(os.path.expanduser(relpath_from)) + str_v = os.path.relpath(str_v, relpath_from) + add += delim + str_v + if add != '': + s += add + ' ' + return s.strip(' ').split(' ') if s != '' else None def obj_to_pdic_gdic_prm(self, obj, sys=False): - info = self.config_dic.get(obj) - if info is None: - sys_prm = self.get_param('sys') - prm_chk = lambda prm : prm is sys_prm if sys else prm is not sys_prm - info = next( ( v for v in self.config_dic.values() if v.get('obj') is obj and prm_chk(v.get('param')) ), None) - if info is None: - return (None, None, None) - pdic = info.get('pdic') - prm = info.get('param') - gdic = info.get('gdic') - return (pdic, gdic, prm) + info = self.config_dic.get(obj) + if info is None: + sys_prm = self.get_param('sys') + prm_chk = lambda prm : prm is sys_prm if sys else prm is not sys_prm + info = next( ( v for v in self.config_dic.values() if v.get('obj') is obj and prm_chk(v.get('param')) ), None) + if info is None: + return (None, None, None) + pdic = info.get('pdic') + prm = info.get('param') + gdic = info.get('gdic') + return (pdic, gdic, prm) def obj_to_gdic(self, obj, def_ret=None): - (_, gdic, _) = self.obj_to_pdic_gdic_prm(obj) if obj else (None, None, None) - return gdic if gdic else def_ret + (_, gdic, _) = self.obj_to_pdic_gdic_prm(obj) if obj else (None, None, None) + return gdic if gdic else def_ret def cfg_obj_dic(self, arg_dic, sys=False, def_ret=(None,{})): - sys_prm = self.get_param('sys') - prm_chk = { - True : (lambda prm : prm is sys_prm), - False : (lambda prm : prm is not sys_prm), - None : (lambda prm : True) }.get(sys) - arg_dic_chk = lambda dic: all( [ dic.get(k) == v for (k,v) in arg_dic.items() ] ) - return next( ( (cfg_obj, dic) for (cfg_obj, dic) in self.config_dic.items() \ - if arg_dic_chk(dic) and prm_chk(dic.get('param')) ), def_ret) + sys_prm = self.get_param('sys') + prm_chk = { + True : (lambda prm : prm is sys_prm), + False : (lambda prm : prm is not sys_prm), + None : (lambda prm : True) }.get(sys) + arg_dic_chk = lambda dic: all( [ dic.get(k) == v for (k,v) in arg_dic.items() ] ) + return next( ( (cfg_obj, dic) for (cfg_obj, dic) in self.config_dic.items() \ + if arg_dic_chk(dic) and prm_chk(dic.get('param')) ), def_ret) def cfg_dic(self, arg_dic, sys=False, def_ret={}): - (_, dic) = self.cfg_obj_dic(arg_dic, sys=sys, def_ret=(None, def_ret)) - return dic + (_, dic) = self.cfg_obj_dic(arg_dic, sys=sys, def_ret=(None, def_ret)) + return dic def cfg_prm_to_obj(self, arg_dic, sys=False): - return self.cfg_dic(arg_dic, sys=sys).get('obj') + return self.cfg_dic(arg_dic, sys=sys).get('obj') def name_to_pdic_gdic_prm(self, name, sys=False): - d = self.cfg_dic( {'name':name}, sys=sys ) - return ( d.get('pdic'), d.get('gdic'), d.get('param') ) + d = self.cfg_dic( {'name':name}, sys=sys ) + return ( d.get('pdic'), d.get('gdic'), d.get('param') ) def update_func(self, pdic, gdic, prm): - pdic_empty = (pdic == {}) - for var in prm.get('vars', []): - name = var.get('name') - gdic_v = gdic.get(name, {}) - func = gdic_v.get('func') - if func is None and not pdic_empty: - continue - v = var.get('v') - if func is not None: - v = eval(func) if type(func) is str else func() - pdic[ name ] = v - - hook = gdic_v.get('update_hook') - if hook: - hook(v) - hook_var = gdic_v.get('hook_var', {}) - every_time = 'every_time' in hook_var.get('flags', []) - if var == gdic.get('update_func_arg_var') or every_time: - hook = hook_var.get('hook') - if hook: - hook(hook_var.get('args', {})) - - if 'pub' in prm: - self.publish_param_topic(pdic, prm) - self.rosparam_set(pdic, prm) - self.update_depend_enable(pdic, gdic, prm) - - d = self.cfg_dic( {'pdic':pdic, 'gdic':gdic, 'param':prm}, sys=True ) - self.update_proc_cpu(d.get('obj'), d.get('pdic'), d.get('param')) + pdic_empty = (pdic == {}) + for var in prm.get('vars', []): + name = var.get('name') + gdic_v = gdic.get(name, {}) + func = gdic_v.get('func') + if func is None and not pdic_empty: + continue + v = var.get('v') + if func is not None: + v = eval(func) if type(func) is str else func() + pdic[ name ] = v + + hook = gdic_v.get('update_hook') + if hook: + hook(v) + hook_var = gdic_v.get('hook_var', {}) + every_time = 'every_time' in hook_var.get('flags', []) + if var == gdic.get('update_func_arg_var') or every_time: + hook = hook_var.get('hook') + if hook: + hook(hook_var.get('args', {})) + + if 'pub' in prm: + self.publish_param_topic(pdic, prm) + self.rosparam_set(pdic, prm) + self.update_depend_enable(pdic, gdic, prm) + + d = self.cfg_dic( {'pdic':pdic, 'gdic':gdic, 'param':prm}, sys=True ) + self.update_proc_cpu(d.get('obj'), d.get('pdic'), d.get('param')) def update_proc_cpu(self, obj, pdic=None, prm=None): - if obj is None or not obj.GetValue(): - return - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) - if proc is None: - return - if pdic is None or prm is None: - (pdic, _, prm) = self.obj_to_pdic_gdic_prm(obj, sys=True) - - cpu_chks = self.param_value_get(pdic, prm, 'cpu_chks') - cpu_chks = cpu_chks if cpu_chks else [ True for i in range(get_cpu_count()) ] - cpus = [ i for i in range(get_cpu_count()) if cpu_chks[i] ] - nice = self.param_value_get(pdic, prm, 'nice', 0) - - d = { 'OTHER':SCHED_OTHER, 'FIFO':SCHED_FIFO, 'RR':SCHED_RR } - policy = SCHED_OTHER - priority = 0 - if self.param_value_get(pdic, prm, 'real_time', False): - policy = d.get(self.param_value_get(pdic, prm, 'policy', 'FIFO'), SCHED_FIFO) - priority = self.param_value_get(pdic, prm, 'prio', 0) - - procs = [ proc ] + proc.get_children(recursive=True) - for proc in procs: - print 'pid={}'.format(proc.pid) - if proc.get_nice() != nice: - print 'nice {} -> {}'.format(proc.get_nice(), nice) - if set_process_nice(proc, nice) is False: - print 'Err set_process_nice()' - if proc.get_cpu_affinity() != cpus: - print 'cpus {} -> {}'.format(proc.get_cpu_affinity(), cpus) - if set_process_cpu_affinity(proc, cpus) is False: - print 'Err set_process_cpu_affinity()' - - policy_str = next( (k for (k,v) in d.items() if v == policy), '?') - print 'sched policy={} prio={}'.format(policy_str, priority) - if set_scheduling_policy(proc, policy, priority) is False: - print 'Err scheduling_policy()' + if obj is None or not obj.GetValue(): + return + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) + if proc is None: + return + if pdic is None or prm is None: + (pdic, _, prm) = self.obj_to_pdic_gdic_prm(obj, sys=True) + + cpu_chks = self.param_value_get(pdic, prm, 'cpu_chks') + cpu_chks = cpu_chks if cpu_chks else [ True for i in range(get_cpu_count()) ] + cpus = [ i for i in range(get_cpu_count()) if cpu_chks[i] ] + nice = self.param_value_get(pdic, prm, 'nice', 0) + + d = { 'OTHER':SCHED_OTHER, 'FIFO':SCHED_FIFO, 'RR':SCHED_RR } + policy = SCHED_OTHER + priority = 0 + if self.param_value_get(pdic, prm, 'real_time', False): + policy = d.get(self.param_value_get(pdic, prm, 'policy', 'FIFO'), SCHED_FIFO) + priority = self.param_value_get(pdic, prm, 'prio', 0) + + procs = [ proc ] + proc.get_children(recursive=True) + for proc in procs: + print('pid={}'.format(proc.pid)) + if proc.get_nice() != nice: + print('nice {} -> {}'.format(proc.get_nice(), nice)) + if set_process_nice(proc, nice) is False: + print('Err set_process_nice()') + if proc.get_cpu_affinity() != cpus: + print('cpus {} -> {}'.format(proc.get_cpu_affinity(), cpus)) + if set_process_cpu_affinity(proc, cpus) is False: + print('Err set_process_cpu_affinity()') + + policy_str = next( (k for (k,v) in d.items() if v == policy), '?') + print('sched policy={} prio={}'.format(policy_str, priority)) + if set_scheduling_policy(proc, policy, priority) is False: + print('Err scheduling_policy()') def param_value_get(self, pdic, prm, name, def_ret=None): - def_ret = self.param_default_value_get(prm, name, def_ret) - return pdic.get(name, def_ret) if pdic else def_ret + def_ret = self.param_default_value_get(prm, name, def_ret) + return pdic.get(name, def_ret) if pdic else def_ret def param_default_value_get(self, prm, name, def_ret=None): - return next( (var.get('v') for var in prm.get('vars') if var.get('name') == name ), def_ret) \ - if prm else def_ret + return next( (var.get('v') for var in prm.get('vars') if var.get('name') == name ), def_ret) \ + if prm else def_ret def update_depend_enable(self, pdic, gdic, prm): - for var in prm.get('vars', []): - name = var.get('name') - gdic_v = gdic.get(name, {}) - depend = gdic_v.get('depend') - if depend is None: - continue - vp = gdic_v.get('var') - if vp is None: - continue - v = pdic.get(depend) - if v is None: - continue - depend_bool = eval( gdic_v.get('depend_bool', 'lambda v : bool(v)') ) - v = depend_bool(v) - enables_set(vp, 'depend', v) + for var in prm.get('vars', []): + name = var.get('name') + gdic_v = gdic.get(name, {}) + depend = gdic_v.get('depend') + if depend is None: + continue + vp = gdic_v.get('var') + if vp is None: + continue + v = pdic.get(depend) + if v is None: + continue + depend_bool = eval( gdic_v.get('depend_bool', 'lambda v : bool(v)') ) + v = depend_bool(v) + enables_set(vp, 'depend', v) def publish_param_topic(self, pdic, prm): - pub = prm['pub'] - klass_msg = globals()[ prm['msg'] ] - msg = klass_msg() + pub = prm['pub'] + klass_msg = globals()[ prm['msg'] ] + msg = klass_msg() - for (name, v) in pdic.items(): - if prm.get('topic') == '/twist_cmd' and name == 'twist.angular.z': - v = -v - (obj, attr) = msg_path_to_obj_attr(msg, name) - if obj and attr in obj.__slots__: - type_str = obj._slot_types[ obj.__slots__.index(attr) ] - setattr(obj, attr, str_to_rosval(v, type_str, v)) + for (name, v) in pdic.items(): + if prm.get('topic') == '/twist_cmd' and name == 'twist.angular.z': + v = -v + (obj, attr) = msg_path_to_obj_attr(msg, name) + if obj and attr in obj.__slots__: + type_str = obj._slot_types[ obj.__slots__.index(attr) ] + setattr(obj, attr, str_to_rosval(v, type_str, v)) - if 'stamp' in prm.get('flags', []): - (obj, attr) = msg_path_to_obj_attr(msg, 'header.stamp') - setattr(obj, attr, rospy.get_rostime()) + if 'stamp' in prm.get('flags', []): + (obj, attr) = msg_path_to_obj_attr(msg, 'header.stamp') + setattr(obj, attr, rospy.get_rostime()) - pub.publish(msg) + pub.publish(msg) def rosparam_set(self, pdic, prm): - rosparams = None - for var in prm.get('vars', []): - name = var['name'] - if 'rosparam' not in var or name not in pdic: - continue - rosparam = var['rosparam'] - v = pdic.get(name) - v = str(v) - cvdic = { 'True':'true', 'False':'false' } - if v in cvdic: - v = cvdic.get(v) - if rosparams is None: - cmd = [ 'rosparam', 'list' ] - rosparams = subprocess.check_output(cmd).strip().split('\n') - nm = rosparam - nm = ('/' if len(nm) > 0 and nm[0] != '/' else '') + nm - exist = nm in rosparams - if exist: - cmd = [ 'rosparam', 'get', rosparam ] - ov = subprocess.check_output(cmd).strip() - if ov == v: - continue - elif v == '': - continue - cmd = [ 'rosparam', 'set', rosparam, v ] if v != '' else [ 'rosparam', 'delete', rosparam ] - print("ROSparam_set") - print(cmd) - subprocess.call(cmd) + rosparams = None + for var in prm.get('vars', []): + name = var['name'] + if 'rosparam' not in var or name not in pdic: + continue + rosparam = var['rosparam'] + v = pdic.get(name) + v = str(v) + cvdic = { 'True':'true', 'False':'false' } + if v in cvdic: + v = cvdic.get(v) + if rosparams is None: + cmd = [ 'rosparam', 'list' ] + rosparams = subprocess.check_output(cmd).strip().split('\n') + nm = rosparam + nm = ('/' if len(nm) > 0 and nm[0] != '/' else '') + nm + exist = nm in rosparams + if exist: + cmd = [ 'rosparam', 'get', rosparam ] + ov = subprocess.check_output(cmd).strip() + if ov == v: + continue + elif v == '': + continue + cmd = [ 'rosparam', 'set', rosparam, v ] if v != '' else [ 'rosparam', 'delete', rosparam ] + print("ROSparam_set") + print(cmd) + subprocess.call(cmd) # # Sensing Tab # def OnSensingDriver(self, event): - self.OnChecked_obj(event.GetEventObject()) + self.OnChecked_obj(event.GetEventObject()) def OnROSbagRecord(self, event): - self.dlg_rosbag_record.Show() - obj = event.GetEventObject() - set_val(obj, False) + self.dlg_rosbag_record.Show() + obj = event.GetEventObject() + set_val(obj, False) def create_checkboxes(self, dic, panel, sizer, probe_dic, run_dic, bind_handler): - if 'name' not in dic: - return - obj = None - bdr_flg = wx.ALL - if 'subs' in dic: - lst = [] - for d in dic['subs']: - self.create_checkboxes(d, panel, lst, probe_dic, run_dic, bind_handler) - if dic['name']: - obj = static_box_sizer(panel, dic.get('name')) - set_tooltip(obj.GetStaticBox(), dic) - else: - obj = wx.BoxSizer(wx.VERTICAL) - for (o, flg) in lst: - obj.Add(o, 0, wx.EXPAND | flg, 4) - else: - obj = wx.CheckBox(panel, wx.ID_ANY, dic['name']) - set_tooltip(obj, dic) - self.Bind(wx.EVT_CHECKBOX, bind_handler, obj) - bdr_flg = wx.LEFT | wx.RIGHT - if 'probe' in dic: - probe_dic[obj] = (dic['probe'], None) - if 'run' in dic: - run_dic[obj] = (dic['run'], None) - if 'param' in dic: - obj = self.add_config_link(dic, panel, obj) - else: - gdic = self.gdic_get_1st(dic) - self.add_cfg_info(obj, obj, dic.get('name'), None, gdic, False, None) - if sizer is not None: - sizer.append((obj, bdr_flg)) - else: - panel.SetSizer(obj) + if 'name' not in dic: + return + obj = None + bdr_flg = wx.ALL + if 'subs' in dic: + lst = [] + for d in dic['subs']: + self.create_checkboxes(d, panel, lst, probe_dic, run_dic, bind_handler) + if dic['name']: + obj = static_box_sizer(panel, dic.get('name')) + set_tooltip(obj.GetStaticBox(), dic) + else: + obj = wx.BoxSizer(wx.VERTICAL) + for (o, flg) in lst: + obj.Add(o, 0, wx.EXPAND | flg, 4) + else: + obj = wx.CheckBox(panel, wx.ID_ANY, dic['name']) + set_tooltip(obj, dic) + self.Bind(wx.EVT_CHECKBOX, bind_handler, obj) + bdr_flg = wx.LEFT | wx.RIGHT + if 'probe' in dic: + probe_dic[obj] = (dic['probe'], None) + if 'run' in dic: + run_dic[obj] = (dic['run'], None) + if 'param' in dic: + obj = self.add_config_link(dic, panel, obj) + else: + gdic = self.gdic_get_1st(dic) + self.add_cfg_info(obj, obj, dic.get('name'), None, gdic, False, None) + if sizer is not None: + sizer.append((obj, bdr_flg)) + else: + panel.SetSizer(obj) def add_config_link(self, dic, panel, obj): - cfg_obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, '[config]', '') - fix_link_color(cfg_obj) - self.Bind(wx.EVT_HYPERLINK, self.OnConfig, cfg_obj) - add_objs = (obj, wx.StaticText(panel, wx.ID_ANY, ' '), cfg_obj) - hszr = sizer_wrap(add_objs, wx.HORIZONTAL) - name = dic['name'] - pdic = self.load_dic_pdic_setup(name, dic) - gdic = self.gdic_get_1st(dic) - prm = self.get_param(dic.get('param')) - self.add_cfg_info(cfg_obj, obj, name, pdic, gdic, True, prm) - return hszr + cfg_obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, '[config]', '') + fix_link_color(cfg_obj) + self.Bind(wx.EVT_HYPERLINK, self.OnConfig, cfg_obj) + add_objs = (obj, wx.StaticText(panel, wx.ID_ANY, ' '), cfg_obj) + hszr = sizer_wrap(add_objs, wx.HORIZONTAL) + name = dic['name'] + pdic = self.load_dic_pdic_setup(name, dic) + gdic = self.gdic_get_1st(dic) + prm = self.get_param(dic.get('param')) + self.add_cfg_info(cfg_obj, obj, name, pdic, gdic, True, prm) + return hszr def camera_ids(self): - if self.button_synchronization.GetValue(): - return [] - cmd = "rostopic list | sed -n 's|/image_raw||p' | sed s/^$//" - return subprocess.check_output(cmd, shell=True).strip().split() + if self.button_synchronization.GetValue(): + return [] + cmd = "rostopic list | sed -n 's|/image_raw||p' | sed s/^$//" + return subprocess.check_output(cmd, shell=True).strip().split() def cam_id_to_obj(self, cam_id, v): - cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) - if cam_id_obj is None: - cam_id_obj = StrValObj(cam_id, v) - cam_id_obj.SetValue(v) - return cam_id_obj + cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) + if cam_id_obj is None: + cam_id_obj = StrValObj(cam_id, v) + cam_id_obj.SetValue(v) + return cam_id_obj def camera_id_hook(self, args): - new_id = args.get('pdic', {}).get('camera_id', '') - ids = args.get('ids', []) - if new_id not in ids: - return - idx = ids.index(new_id) - - pp = args.get('param_panel') - if pp: - pp.detach_func() - dlg = args.get('dlg') - if dlg: - dlg.EndModal(idx + 100) + new_id = args.get('pdic', {}).get('camera_id', '') + ids = args.get('ids', []) + if new_id not in ids: + return + idx = ids.index(new_id) + + pp = args.get('param_panel') + if pp: + pp.detach_func() + dlg = args.get('dlg') + if dlg: + dlg.EndModal(idx + 100) def OnCalibrationPublisher(self, event): - obj = event.GetEventObject() - (_, gdic_org, prm) = self.obj_to_pdic_gdic_prm(obj) - if obj.GetValue(): - gdic_org['ids'] = self.camera_ids() - ids = gdic_org.get('ids', []) - - if ids == []: - self.OnLaunchKill(event) - return - # - # setup - # - (cmd_dic, cmd, _) = self.obj_to_cmd_dic_cmd_proc(obj) - - flags = gdic_org.get('flags', [])[:] # copy - if 'open_dialog' in flags: - flags.remove('open_dialog') - - pdic_baks = {} - for cam_id in ids: - (pdic_a, gdic_a, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic = pdic_a if pdic_a else self.load_dic_pdic_setup(cam_id, {}) - pdic_baks[cam_id] = pdic.copy() - gdic = gdic_a if gdic_a else gdic_org.copy() - gdic['flags'] = flags - - cam_id_obj = self.cam_id_to_obj(cam_id, obj.GetValue()) - if not pdic_a or not gdic_a: - self.add_cfg_info(cam_id_obj, cam_id_obj, cam_id, pdic, gdic, False, prm) - if not cam_id_obj in cmd_dic: - cmd_dic[ cam_id_obj ] = (cmd, None) - - var = self.get_var(prm, 'camera_id', {}) - var['choices'] = ids - - # - # Dialog - # - cam_id = ids[0] - while obj.GetValue(): - (pdic, gdic, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic['camera_id'] = cam_id - dic_list_push(gdic, 'dialog_type', 'open2') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - - gdic_v = dic_getset(gdic, 'camera_id', {}) - args = { 'pdic':pdic, 'ids':ids, 'param_panel':gdic.get('param_panel'), 'dlg':dlg } - gdic_v['hook_var'] = { 'hook':self.camera_id_hook, 'args':args } - - dlg_ret = show_modal(dlg) - - dic_list_pop(gdic, 'dialog_type') - pdic['camera_id'] = cam_id # restore - - if dlg_ret == 0: # OK - break - - idx = dlg_ret - 100 - if idx < 0 or len(ids) <= idx: # Cancel - for cam_id in ids: - (pdic, _, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic.update(pdic_baks.get(cam_id)) - set_val(obj, False) - return - - # Menu changed - cam_id = ids[idx] - - # - # Launch / Kill - # - for cam_id in ids: - cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) - (pdic, _, _) = self.obj_to_pdic_gdic_prm(cam_id_obj) - pdic['solo_camera'] = False - #print '@', cam_id, cam_id_obj.GetValue() - self.OnLaunchKill_obj(cam_id_obj) + obj = event.GetEventObject() + (_, gdic_org, prm) = self.obj_to_pdic_gdic_prm(obj) + if obj.GetValue(): + gdic_org['ids'] = self.camera_ids() + ids = gdic_org.get('ids', []) + + if ids == []: + self.OnLaunchKill(event) + return + # + # setup + # + (cmd_dic, cmd, _) = self.obj_to_cmd_dic_cmd_proc(obj) + + flags = gdic_org.get('flags', [])[:] # copy + if 'open_dialog' in flags: + flags.remove('open_dialog') + + pdic_baks = {} + for cam_id in ids: + (pdic_a, gdic_a, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic = pdic_a if pdic_a else self.load_dic_pdic_setup(cam_id, {}) + pdic_baks[cam_id] = pdic.copy() + gdic = gdic_a if gdic_a else gdic_org.copy() + gdic['flags'] = flags + + cam_id_obj = self.cam_id_to_obj(cam_id, obj.GetValue()) + if not pdic_a or not gdic_a: + self.add_cfg_info(cam_id_obj, cam_id_obj, cam_id, pdic, gdic, False, prm) + if not cam_id_obj in cmd_dic: + cmd_dic[ cam_id_obj ] = (cmd, None) + + var = self.get_var(prm, 'camera_id', {}) + var['choices'] = ids + + # + # Dialog + # + cam_id = ids[0] + while obj.GetValue(): + (pdic, gdic, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic['camera_id'] = cam_id + dic_list_push(gdic, 'dialog_type', 'open2') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + + gdic_v = dic_getset(gdic, 'camera_id', {}) + args = { 'pdic':pdic, 'ids':ids, 'param_panel':gdic.get('param_panel'), 'dlg':dlg } + gdic_v['hook_var'] = { 'hook':self.camera_id_hook, 'args':args } + + dlg_ret = show_modal(dlg) + + dic_list_pop(gdic, 'dialog_type') + pdic['camera_id'] = cam_id # restore + + if dlg_ret == 0: # OK + break + + idx = dlg_ret - 100 + if idx < 0 or len(ids) <= idx: # Cancel + for cam_id in ids: + (pdic, _, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic.update(pdic_baks.get(cam_id)) + set_val(obj, False) + return + + # Menu changed + cam_id = ids[idx] + + # + # Launch / Kill + # + for cam_id in ids: + cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) + (pdic, _, _) = self.obj_to_pdic_gdic_prm(cam_id_obj) + pdic['solo_camera'] = False + #print('@', cam_id, cam_id_obj.GetValue()) + self.OnLaunchKill_obj(cam_id_obj) # # Input ROSbag File Tab # def rosbag_info_hook(self, v): - if not v: - return - th_start(self.rosbag_info_hook_th, {'v':v} ) + if not v: + return + th_start(self.rosbag_info_hook_th, {'v':v} ) def rosbag_info_hook_th(self, ev, v): # thread - err = subprocess.STDOUT - s = subprocess.check_output([ 'rosbag', 'info', v ], stderr=err).strip() - wx.CallAfter(self.label_rosbag_info.SetLabel, s) - wx.CallAfter(self.label_rosbag_info.GetParent().FitInside) + err = subprocess.STDOUT + s = subprocess.check_output([ 'rosbag', 'info', v ], stderr=err).strip() + wx.CallAfter(self.label_rosbag_info.SetLabel, s) + wx.CallAfter(self.label_rosbag_info.GetParent().FitInside) def info_col(self, v, v_yellow, v_red, col_normal, col_red): - if v < v_yellow: - return col_normal - if v < v_red: - (nr,ng,nb) = col_normal - (rr,rg,rb) = col_red - return ( (nr+rr)/2, (ng+rg)/2, (nb+rb)/2 ) - return col_red + if v < v_yellow: + return col_normal + if v < v_red: + (nr,ng,nb) = col_normal + (rr,rg,rb) = col_red + return ( (nr+rr)/2, (ng+rg)/2, (nb+rb)/2 ) + return col_red def mem_kb_info(self): - lst = subprocess.check_output(['free']).strip().split('\n')[2].split()[2:4] - used = int(lst[0]) - free = int(lst[1]) - return (used + free, used) + lst = subprocess.check_output(['free']).strip().split('\n')[2].split()[2:4] + used = int(lst[0]) + free = int(lst[1]) + return (used + free, used) def toprc_create(self): - (child_pid, fd) = pty.fork() - if child_pid == 0: # child - os.execvp('top', ['top']) - else: #parent - sec = 0.2 - for s in ['1', 'c', 'W', 'q']: - time.sleep(sec) - os.write(fd, s) + (child_pid, fd) = pty.fork() + if child_pid == 0: # child + os.execvp('top', ['top']) + else: #parent + sec = 0.2 + for s in ['1', 'c', 'W', 'q']: + time.sleep(sec) + os.write(fd, s) def toprc_setup(self, toprc, backup): - if os.path.exists(toprc): - os.rename(toprc, backup) - self.toprc_create() + if os.path.exists(toprc): + os.rename(toprc, backup) + self.toprc_create() def toprc_restore(self, toprc, backup): - os.remove(toprc) - if os.path.exists(backup): - os.rename(backup, toprc) + os.remove(toprc) + if os.path.exists(backup): + os.rename(backup, toprc) # top command thread def top_cmd_th(self, ev, setting, cpu_ibls, mem_ibl, toprc, backup): - interval = setting.get('interval', 3) - alert_level = setting.get('alert_level', {}) - rate_per_cpu = alert_level.get('rate_per_cpu', 80) - rate_per_cpu_yellow = alert_level.get('rate_per_cpu_yellow', 80) - rate_cpu = alert_level.get('rate_cpu', 80) - rate_mem = alert_level.get('rate_mem', 80) - rate_mem_yellow = alert_level.get('rate_mem_yellow', 80) - - for ibl in cpu_ibls: - ibl.lmt_bar_prg = rate_per_cpu - mem_ibl.lmt_bar_prg = rate_mem - - alerted = False - cpu_n = get_cpu_count() - - while not ev.wait(interval): - s = subprocess.check_output(['sh', '-c', 'env COLUMNS=512 top -b -n 2 -d 0.1']).strip() - i = s.rfind('\ntop -') + 1 - s = s[i:] - wx.CallAfter(self.label_top_cmd.SetLabel, s) - wx.CallAfter(self.label_top_cmd.GetParent().FitInside) - - k = '%Cpu' - fv_sum = 0 - i = 0 - for t in s.split('\n'): - if t[:len(k)] != k: - continue - lst = t[1:].split() - v = lst[1] if lst[1] != ':' else lst[2] - if v[0] == ':': - v = v[1:] - fv = str_to_float(v) - col = self.info_col(fv, rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) - - if i < cpu_n: - ibl = cpu_ibls[i] - wx.CallAfter(ibl.lb_set, v+'%', col) - wx.CallAfter(ibl.bar_set, int(fv)) - fv_sum += fv - i += 1 - - k = 'KiB Mem:' - (total, used) = self.mem_kb_info() - rate = 100 * used / total - - for u in [ 'KB', 'MB', 'GB', 'TB' ]: - if total <= 10 * 1024 or used <= 10: - break - total /= 1024 - used /= 1024 - - col = self.info_col(rate, rate_mem_yellow, rate_mem, (64,64,64), (200,0,0)) - tx = str(used) + u + '/' + str(total) + u + '(' + str(rate) + '%)' - - wx.CallAfter(mem_ibl.lb_set, tx, col) - wx.CallAfter(mem_ibl.bar_set, rate) - - is_alert = (fv_sum >= rate_cpu * cpu_n) or rate >= rate_mem - - # --> for test - if os.path.exists('/tmp/alert_test_on'): - is_alert = True - if os.path.exists('/tmp/alert_test_off'): - is_alert = False - # <-- for test - - if is_alert and not alerted: - thinf = th_start(self.alert_th, {'bgcol':(200,50,50)}) - alerted = True - if not is_alert and alerted: - th_end(thinf) - alerted = False - - # top5 - i = s.find('\n\n') + 2 - lst = s[i:].split('\n') - hd = lst[0] - top5 = lst[1:1+5] - - i = hd.rfind('COMMAND') - cmds = [ line[i:].split(' ')[0] for line in top5 ] - - i = hd.find('%CPU') - loads = [ line[i-1:].strip().split(' ')[0] for line in top5 ] - - for (lb, cmd, load) in zip(self.lb_top5, cmds, loads): - col = self.info_col(str_to_float(load), rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) - wx.CallAfter(lb.SetForegroundColour, col) - wx.CallAfter(lb.SetLabel, cmd + ' (' + load + ' %CPU)') - - self.toprc_restore(toprc, backup) + interval = setting.get('interval', 3) + alert_level = setting.get('alert_level', {}) + rate_per_cpu = alert_level.get('rate_per_cpu', 80) + rate_per_cpu_yellow = alert_level.get('rate_per_cpu_yellow', 80) + rate_cpu = alert_level.get('rate_cpu', 80) + rate_mem = alert_level.get('rate_mem', 80) + rate_mem_yellow = alert_level.get('rate_mem_yellow', 80) + + for ibl in cpu_ibls: + ibl.lmt_bar_prg = rate_per_cpu + mem_ibl.lmt_bar_prg = rate_mem + + alerted = False + cpu_n = get_cpu_count() + + while not ev.wait(interval): + s = subprocess.check_output(['sh', '-c', 'env COLUMNS=512 top -b -n 2 -d 0.1']).strip() + i = s.rfind('\ntop -') + 1 + s = s[i:] + wx.CallAfter(self.label_top_cmd.SetLabel, s) + wx.CallAfter(self.label_top_cmd.GetParent().FitInside) + + k = '%Cpu' + fv_sum = 0 + i = 0 + for t in s.split('\n'): + if t[:len(k)] != k: + continue + lst = t[1:].split() + v = lst[1] if lst[1] != ':' else lst[2] + if v[0] == ':': + v = v[1:] + fv = str_to_float(v) + col = self.info_col(fv, rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) + + if i < cpu_n: + ibl = cpu_ibls[i] + wx.CallAfter(ibl.lb_set, v+'%', col) + wx.CallAfter(ibl.bar_set, int(fv)) + fv_sum += fv + i += 1 + + k = 'KiB Mem:' + (total, used) = self.mem_kb_info() + rate = 100 * used / total + + for u in [ 'KB', 'MB', 'GB', 'TB' ]: + if total <= 10 * 1024 or used <= 10: + break + total /= 1024 + used /= 1024 + + col = self.info_col(rate, rate_mem_yellow, rate_mem, (64,64,64), (200,0,0)) + tx = str(used) + u + '/' + str(total) + u + '(' + str(rate) + '%)' + + wx.CallAfter(mem_ibl.lb_set, tx, col) + wx.CallAfter(mem_ibl.bar_set, rate) + + is_alert = (fv_sum >= rate_cpu * cpu_n) or rate >= rate_mem + + # --> for test + if os.path.exists('/tmp/alert_test_on'): + is_alert = True + if os.path.exists('/tmp/alert_test_off'): + is_alert = False + # <-- for test + + if is_alert and not alerted: + thinf = th_start(self.alert_th, {'bgcol':(200,50,50)}) + alerted = True + if not is_alert and alerted: + th_end(thinf) + alerted = False + + # top5 + i = s.find('\n\n') + 2 + lst = s[i:].split('\n') + hd = lst[0] + top5 = lst[1:1+5] + + i = hd.rfind('COMMAND') + cmds = [ line[i:].split(' ')[0] for line in top5 ] + + i = hd.find('%CPU') + loads = [ line[i-1:].strip().split(' ')[0] for line in top5 ] + + for (lb, cmd, load) in zip(self.lb_top5, cmds, loads): + col = self.info_col(str_to_float(load), rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) + wx.CallAfter(lb.SetForegroundColour, col) + wx.CallAfter(lb.SetLabel, cmd + ' (' + load + ' %CPU)') + + self.toprc_restore(toprc, backup) def alert_th(self, bgcol, ev): - wx.CallAfter(self.RequestUserAttention) - c = bgcol - o = wx.NullColour - while not ev.wait(0.5): - for col in [ c, o, c, o, c, o ]: - wx.CallAfter(self.set_bg_all_tabs, col) - time.sleep(0.05) + wx.CallAfter(self.RequestUserAttention) + c = bgcol + o = wx.NullColour + while not ev.wait(0.5): + for col in [ c, o, c, o, c, o ]: + wx.CallAfter(self.set_bg_all_tabs, col) + time.sleep(0.05) def log_th(self, file, que, ev): - while not ev.wait(0): - s = file.readline() - if not s: - break - que.put(s) + while not ev.wait(0): + s = file.readline() + if not s: + break + que.put(s) def logout_th(self, que, interval, tc, ev): - if que == self.log_que_stdout or que == self.log_que_stderr: - while not ev.wait(0): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - self.log_que.put(s) - - if interval <= 0: - continue - - ckbox = self.checkbox_stdout if que == self.log_que_stdout else self.checkbox_stderr - if ckbox.GetValue(): - self.log_que_show.put( cut_esc(s) ) - - else: # == self.log_que - f = None - path = self.status_dic.get('log_path') - is_syslog = (path == 'syslog') - - if is_syslog: - ident = sys.argv[0].split('/')[-1] - syslog.openlog(ident, syslog.LOG_PID | syslog.LOG_CONS) - elif path: - path = os.path.expandvars(os.path.expanduser(path)) - f = open(path, 'a') if path else None - - while not ev.wait(0): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - print s.strip() - sys.stdout.flush() - - s = cut_esc(s) - if is_syslog: - syslog.syslog(s) - elif f: - f.write(s) - f.flush() - if is_syslog: - syslog.closelog() - if f: - f.close() + if que == self.log_que_stdout or que == self.log_que_stderr: + while not ev.wait(0): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + self.log_que.put(s) + + if interval <= 0: + continue + + ckbox = self.checkbox_stdout if que == self.log_que_stdout else self.checkbox_stderr + if ckbox.GetValue(): + self.log_que_show.put( cut_esc(s) ) + + else: # == self.log_que + f = None + path = self.status_dic.get('log_path') + is_syslog = (path == 'syslog') + + if is_syslog: + ident = sys.argv[0].split('/')[-1] + syslog.openlog(ident, syslog.LOG_PID | syslog.LOG_CONS) + elif path: + path = os.path.expandvars(os.path.expanduser(path)) + f = open(path, 'a') if path else None + + while not ev.wait(0): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + print(s.strip()) + sys.stdout.flush() + + s = cut_esc(s) + if is_syslog: + syslog.syslog(s) + elif f: + f.write(s) + f.flush() + if is_syslog: + syslog.closelog() + if f: + f.close() def logshow_th(self, que, interval, tc, ev): - while not ev.wait(interval): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - wx.CallAfter(append_tc_limit, tc, s) - - # que clear - if self.checkbox_stdout.GetValue() is False and \ - self.checkbox_stderr.GetValue() is False and \ - que.qsize() > 0: - que_clear(que) - wx.CallAfter(tc.Clear) + while not ev.wait(interval): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + wx.CallAfter(append_tc_limit, tc, s) + + # que clear + if self.checkbox_stdout.GetValue() is False and \ + self.checkbox_stderr.GetValue() is False and \ + que.qsize() > 0: + que_clear(que) + wx.CallAfter(tc.Clear) # # for Topics tab # def OnRefreshTopics(self, event): - self.refresh_topics_list() + self.refresh_topics_list() def refresh_topics_list(self): - lst = subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') - panel = self.panel_topics_list - szr = self.sizer_topics_list - for obj in self.topics_list: - szr.Remove(obj) - obj.Destroy() - self.topics_list = [] - for topic in lst: - obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, topic, '') - self.Bind(wx.EVT_HYPERLINK, self.OnTopicLink, obj) - szr.Add(obj, 0, wx.LEFT, 4) - fix_link_color(obj) - self.topics_list.append(obj) - szr.Layout() - panel.SetVirtualSize(szr.GetMinSize()) - - # info clear - lb = self.label_topics_info - lb.SetLabel('') - - # echo clear - self.topics_proc_th_end() - - # wait que clear - while self.topics_echo_que.qsize() > 0: - time.sleep(0.1) - - tc = self.text_ctrl_topics_echo - tc.Enable(False) - wx.CallAfter(tc.Clear) - wx.CallAfter(tc.Enable, True) - self.topics_echo_sum = 0 - self.topic_echo_curr_topic = None + lst = subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') + panel = self.panel_topics_list + szr = self.sizer_topics_list + for obj in self.topics_list: + szr.Remove(obj) + obj.Destroy() + self.topics_list = [] + for topic in lst: + obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, topic, '') + self.Bind(wx.EVT_HYPERLINK, self.OnTopicLink, obj) + szr.Add(obj, 0, wx.LEFT, 4) + fix_link_color(obj) + self.topics_list.append(obj) + szr.Layout() + panel.SetVirtualSize(szr.GetMinSize()) + + # info clear + lb = self.label_topics_info + lb.SetLabel('') + + # echo clear + self.topics_proc_th_end() + + # wait que clear + while self.topics_echo_que.qsize() > 0: + time.sleep(0.1) + + tc = self.text_ctrl_topics_echo + tc.Enable(False) + wx.CallAfter(tc.Clear) + wx.CallAfter(tc.Enable, True) + self.topics_echo_sum = 0 + self.topic_echo_curr_topic = None def OnEcho(self, event): - if self.checkbox_topics_echo.GetValue() and self.topic_echo_curr_topic: - self.topics_proc_th_start(self.topic_echo_curr_topic) - else: - self.topics_proc_th_end() + if self.checkbox_topics_echo.GetValue() and self.topic_echo_curr_topic: + self.topics_proc_th_start(self.topic_echo_curr_topic) + else: + self.topics_proc_th_end() def OnTopicLink(self, event): - obj = event.GetEventObject() - topic = obj.GetLabel() - self.topic_echo_curr_topic = topic + obj = event.GetEventObject() + topic = obj.GetLabel() + self.topic_echo_curr_topic = topic - # info - info = subprocess.check_output([ 'rostopic', 'info', topic ]).strip() - lb = self.label_topics_info - lb.SetLabel(info) - lb.GetParent().FitInside() + # info + info = subprocess.check_output([ 'rostopic', 'info', topic ]).strip() + lb = self.label_topics_info + lb.SetLabel(info) + lb.GetParent().FitInside() - # echo - self.topics_proc_th_end() - if self.checkbox_topics_echo.GetValue(): - self.topics_proc_th_start(topic) + # echo + self.topics_proc_th_end() + if self.checkbox_topics_echo.GetValue(): + self.topics_proc_th_start(topic) def topics_proc_th_start(self, topic): - out = subprocess.PIPE - err = subprocess.STDOUT - self.topics_echo_proc = psutil.Popen([ 'rostopic', 'echo', topic ], stdout=out, stderr=err) + out = subprocess.PIPE + err = subprocess.STDOUT + self.topics_echo_proc = psutil.Popen([ 'rostopic', 'echo', topic ], stdout=out, stderr=err) - self.topics_echo_thinf = th_start(self.topics_echo_th) + self.topics_echo_thinf = th_start(self.topics_echo_th) def topics_proc_th_end(self): - thinf = self.topics_echo_thinf - if thinf: - th_end(thinf) - self.topics_echo_thinf = None - - proc = self.topics_echo_proc - if proc: - terminate_children(proc) - terminate(proc) - #proc.wait() - self.topics_echo_proc = None + thinf = self.topics_echo_thinf + if thinf: + th_end(thinf) + self.topics_echo_thinf = None + + proc = self.topics_echo_proc + if proc: + terminate_children(proc) + terminate(proc) + #proc.wait() + self.topics_echo_proc = None def topics_echo_th(self, ev): - if not self.topics_echo_proc: - return - file = self.topics_echo_proc.stdout - fl = fcntl.fcntl(file.fileno(), fcntl.F_GETFL) - fcntl.fcntl(file.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) - - while not ev.wait(0): - try: - s = file.read(1) - except: - continue - if not s: - break - if self.checkbox_topics_echo.GetValue(): - self.topics_echo_que.put(s) - - que_clear(self.topics_echo_que) + if not self.topics_echo_proc: + return + file = self.topics_echo_proc.stdout + fl = fcntl.fcntl(file.fileno(), fcntl.F_GETFL) + fcntl.fcntl(file.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) + + while not ev.wait(0): + try: + s = file.read(1) + except: + continue + if not s: + break + if self.checkbox_topics_echo.GetValue(): + self.topics_echo_que.put(s) + + que_clear(self.topics_echo_que) def topics_echo_show_th(self, ev): - que = self.topics_echo_que - interval = self.topics_dic.get('gui_update_interval_ms', 100) * 0.001 - chars_limit = self.topics_dic.get('gui_chars_limit', 10000) - tc = self.text_ctrl_topics_echo - while not ev.wait(interval): - qsz = que.qsize() - if qsz <= 0: - continue - if qsz > chars_limit: - over = qsz - chars_limit - for i in range(over): - try: - que.get(timeout=1) - except Queue.Empty: - break - qsz = chars_limit - arr = [] - for i in range(qsz): - try: - s = que.get(timeout=1) - except Queue.Empty: - s = '' - arr.append(s) - s = ''.join(arr) - - self.topics_echo_sum += len(s) - rm_chars = 0 - if self.topics_echo_sum > chars_limit: - rm_chars = self.topics_echo_sum - chars_limit - self.topics_echo_sum = chars_limit - - if self.checkbox_topics_echo.GetValue(): - wx.CallAfter(append_tc_limit, tc, s, rm_chars) + que = self.topics_echo_que + interval = self.topics_dic.get('gui_update_interval_ms', 100) * 0.001 + chars_limit = self.topics_dic.get('gui_chars_limit', 10000) + tc = self.text_ctrl_topics_echo + while not ev.wait(interval): + qsz = que.qsize() + if qsz <= 0: + continue + if qsz > chars_limit: + over = qsz - chars_limit + for i in range(over): + try: + que.get(timeout=1) + except Queue.Empty: + break + qsz = chars_limit + arr = [] + for i in range(qsz): + try: + s = que.get(timeout=1) + except Queue.Empty: + s = '' + arr.append(s) + s = ''.join(arr) + + self.topics_echo_sum += len(s) + rm_chars = 0 + if self.topics_echo_sum > chars_limit: + rm_chars = self.topics_echo_sum - chars_limit + self.topics_echo_sum = chars_limit + + if self.checkbox_topics_echo.GetValue(): + wx.CallAfter(append_tc_limit, tc, s, rm_chars) # # Common Utils # def set_param_panel(self, obj, parent): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - panel = ParamPanel(parent, frame=self, pdic=pdic, gdic=gdic, prm=prm) - sizer_wrap((panel,), wx.VERTICAL, 0, wx.EXPAND, 0, parent) - k = 'ext_toggle_enables' - gdic[ k ] = gdic.get(k, []) + [ panel ] + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + panel = ParamPanel(parent, frame=self, pdic=pdic, gdic=gdic, prm=prm) + sizer_wrap((panel,), wx.VERTICAL, 0, wx.EXPAND, 0, parent) + k = 'ext_toggle_enables' + gdic[ k ] = gdic.get(k, []) + [ panel ] def obj_to_varpanel(self, obj, var_name): - gdic = self.obj_to_gdic(obj, {}) - return gdic.get(var_name, {}).get('var') + gdic = self.obj_to_gdic(obj, {}) + return gdic.get(var_name, {}).get('var') def obj_to_varpanel_tc(self, obj, var_name): - vp = self.obj_to_varpanel(obj, var_name) - return vp.tc if vp and vp.tc else None + vp = self.obj_to_varpanel(obj, var_name) + return vp.tc if vp and vp.tc else None def OnConfig(self, event): - self.OnHyperlinked_obj(event.GetEventObject()) + self.OnHyperlinked_obj(event.GetEventObject()) def add_params(self, params): - for prm in params: - if 'topic' in prm and 'msg' in prm: - klass_msg = globals()[ prm['msg'] ] - prm['pub'] = rospy.Publisher(prm['topic'], klass_msg, latch=True, queue_size=10) - self.params += params + for prm in params: + if 'topic' in prm and 'msg' in prm: + klass_msg = globals()[ prm['msg'] ] + prm['pub'] = rospy.Publisher(prm['topic'], klass_msg, latch=True, queue_size=10) + self.params += params def gdic_get_1st(self, dic): - gdic = dic.get('gui', {}) - gdic['update_func'] = self.update_func - return gdic + gdic = dic.get('gui', {}) + gdic['update_func'] = self.update_func + return gdic def add_cfg_info(self, cfg_obj, obj, name, pdic, gdic, run_disable, prm): - self.config_dic[ cfg_obj ] = { 'obj':obj , 'name':name , 'pdic':pdic , 'gdic':gdic, - 'run_disable':run_disable , 'param':prm } + self.config_dic[ cfg_obj ] = { 'obj':obj , 'name':name , 'pdic':pdic , 'gdic':gdic, + 'run_disable':run_disable , 'param':prm } def get_param(self, prm_name): - return next( (prm for prm in self.params if prm['name'] == prm_name), None) + return next( (prm for prm in self.params if prm['name'] == prm_name), None) def get_var(self, prm, var_name, def_ret=None): - return next( (var for var in prm.get('vars') if var.get('name') == var_name), def_ret) + return next( (var for var in prm.get('vars') if var.get('name') == var_name), def_ret) def obj_to_cmd_dic(self, obj): - return next( (cmd_dic for cmd_dic in self.all_cmd_dics if obj in cmd_dic), None) + return next( (cmd_dic for cmd_dic in self.all_cmd_dics if obj in cmd_dic), None) def obj_to_cmd_dic_cmd_proc(self, obj): - cmd_dic = self.obj_to_cmd_dic(obj) - if cmd_dic is None: - return (None, None, None) - (cmd, proc) = cmd_dic.get(obj, (None, None)) - return (cmd_dic, cmd, proc) + cmd_dic = self.obj_to_cmd_dic(obj) + if cmd_dic is None: + return (None, None, None) + (cmd, proc) = cmd_dic.get(obj, (None, None)) + return (cmd_dic, cmd, proc) def OnLaunchKill(self, event): - self.OnLaunchKill_obj(event.GetEventObject()) + self.OnLaunchKill_obj(event.GetEventObject()) def OnLaunchKill_obj(self, obj): - self.alias_sync(obj) - obj = self.alias_grp_top_obj(obj) - v = obj.GetValue() - add_args = self.obj_to_add_args(obj, msg_box=v) # no open dialog at kill + self.alias_sync(obj) + obj = self.alias_grp_top_obj(obj) + v = obj.GetValue() + add_args = self.obj_to_add_args(obj, msg_box=v) # no open dialog at kill # print("add_args", add_args) if add_args is False: - set_val(obj, not v) - return - (cmd_dic, _, proc_bak) = self.obj_to_cmd_dic_cmd_proc(obj) - self.launch_kill_proc(obj, cmd_dic, add_args=add_args) - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) - if proc != proc_bak: - self.toggle_enable_obj(obj) - if proc: - self.update_proc_cpu(obj) + set_val(obj, not v) + return + (cmd_dic, _, proc_bak) = self.obj_to_cmd_dic_cmd_proc(obj) + self.launch_kill_proc(obj, cmd_dic, add_args=add_args) + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) + if proc != proc_bak: + self.toggle_enable_obj(obj) + if proc: + self.update_proc_cpu(obj) def OnROSbagPlay(self, event): - obj = event.GetEventObject() - - play = self.button_play_rosbag_play - stop = self.button_stop_rosbag_play - pause = self.button_pause_rosbag_play - - (_, _, prm) = self.obj_to_pdic_gdic_prm(play) - var = self.get_var(prm, 'sim_time', {}) - - if obj == play: - var['v'] = True - self.OnLaunchKill_obj(play) - button_color_change(play); self.button_confirm_depth.Disable() - set_val(stop, False);self.button_play_rosbag_play2.Disable() - set_val(pause, False);self.button_confirm_topics.Disable() - elif obj == stop: - set_val(stop, True); self.button_confirm_depth.Enable() - set_val(play, False); self.button_play_rosbag_play2.Enable() - set_val(pause, False);self.button_confirm_topics.Enable() - var['v'] = False - self.OnLaunchKill_obj(play) - button_color_change(stop) - elif obj == pause: - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(play) - if proc: - proc.stdin.write(' ') + obj = event.GetEventObject() + + play = self.button_play_rosbag_play + stop = self.button_stop_rosbag_play + pause = self.button_pause_rosbag_play + + (_, _, prm) = self.obj_to_pdic_gdic_prm(play) + var = self.get_var(prm, 'sim_time', {}) + + if obj == play: + var['v'] = True + self.OnLaunchKill_obj(play) + button_color_change(play); self.button_confirm_depth.Disable() + set_val(stop, False);self.button_play_rosbag_play2.Disable() + set_val(pause, False);self.button_confirm_topics.Disable() + elif obj == stop: + set_val(stop, True); self.button_confirm_depth.Enable() + set_val(play, False); self.button_play_rosbag_play2.Enable() + set_val(pause, False);self.button_confirm_topics.Enable() + var['v'] = False + self.OnLaunchKill_obj(play) + button_color_change(stop) + elif obj == pause: + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(play) + if proc: + proc.stdin.write(' ') def OnFtrace(self, event): - obj = event.GetEventObject() - cmd = 'rosrun runtime_manager ftrace.py' - v = obj.GetValue() - self.ftrace_proc_ = self.launch_kill(v, cmd, - None if v else self.ftrace_proc_, obj=obj) + obj = event.GetEventObject() + cmd = 'rosrun runtime_manager ftrace.py' + v = obj.GetValue() + self.ftrace_proc_ = self.launch_kill(v, cmd, + None if v else self.ftrace_proc_, obj=obj) def stdout_file_search(self, file, k): - s = '' - while True: - c = file.read(1) - if not c: - return None - if c != '\r' and c != '\n': - s += c - continue - s = s.strip() - if k in s: - break - s = '' - i = s.find(k) + len(k) - return s[i:] + s = '' + while True: + c = file.read(1) + if not c: + return None + if c != '\r' and c != '\n': + s += c + continue + s = s.strip() + if k in s: + break + s = '' + i = s.find(k) + len(k) + return s[i:] # thread def point_cloud_progress_bar(self, file, ev): - obj = self.button_point_cloud - (pdic, _, _) = self.obj_to_pdic_gdic_prm(obj) - n = len(pdic.get('path_pcd', '').split(',')) - if n == 0: - return - i = 0 - while not ev.wait(0): - s = self.stdout_file_search(file, 'load ') - if not s: - break - err_key = 'failed ' - if s[:len(err_key)] != err_key: - i += 1 - else: - i -= 1 - print s - wx.CallAfter(self.label_point_cloud_bar.set, 100 * i / n) - wx.CallAfter(self.label_point_cloud_bar.clear) + obj = self.button_point_cloud + (pdic, _, _) = self.obj_to_pdic_gdic_prm(obj) + n = len(pdic.get('path_pcd', '').split(',')) + if n == 0: + return + i = 0 + while not ev.wait(0): + s = self.stdout_file_search(file, 'load ') + if not s: + break + err_key = 'failed ' + if s[:len(err_key)] != err_key: + i += 1 + else: + i -= 1 + print(s) + wx.CallAfter(self.label_point_cloud_bar.set, 100 * i / n) + wx.CallAfter(self.label_point_cloud_bar.clear) # thread def rosbag_play_progress_bar(self, file, ev): - while not ev.wait(0): - s = self.stdout_file_search(file, 'Duration:') - if not s: - break - lst = s.split() - pos = str_to_float(lst[0]) - # lst[1] is '/' - total = str_to_float(lst[2]) - if total == 0: - continue - prg = int(100 * pos / total + 0.5) - pos = str(int(pos)) - total = str(int(total)) - - wx.CallAfter(self.label_rosbag_play_bar.set, prg) - wx.CallAfter(self.label_rosbag_play_pos.SetLabel, pos) - wx.CallAfter(self.label_rosbag_play_total.SetLabel, total) - wx.CallAfter(self.label_rosbag_play_bar.clear) - wx.CallAfter(self.label_rosbag_play_pos.SetLabel, '') - wx.CallAfter(self.label_rosbag_play_total.SetLabel, '') + while not ev.wait(0): + s = self.stdout_file_search(file, 'Duration:') + if not s: + break + lst = s.split() + pos = str_to_float(lst[0]) + # lst[1] is '/' + total = str_to_float(lst[2]) + if total == 0: + continue + prg = int(100 * pos / total + 0.5) + pos = str(int(pos)) + total = str(int(total)) + + wx.CallAfter(self.label_rosbag_play_bar.set, prg) + wx.CallAfter(self.label_rosbag_play_pos.SetLabel, pos) + wx.CallAfter(self.label_rosbag_play_total.SetLabel, total) + wx.CallAfter(self.label_rosbag_play_bar.clear) + wx.CallAfter(self.label_rosbag_play_pos.SetLabel, '') + wx.CallAfter(self.label_rosbag_play_total.SetLabel, '') def alias_sync(self, obj, v=None): - en = None - if getattr(obj, 'IsEnabled', None): - (key, en) = enables_get_last(obj) - if not key: - en = obj.IsEnabled() - grp = self.alias_grp_get(obj) - if getattr(obj, 'GetValue', None): - v = obj.GetValue() - for o in grp: - if o is obj: - continue - - if en is not None and o.IsEnabled() != en and not self.is_toggle_button(o): - if key: - enable_set(o, key, en) - else: - o.Enable(en) - if v is not None and getattr(o, 'SetValue', None): - set_val(o, v) - if getattr(o, 'SetInsertionPointEnd', None): - o.SetInsertionPointEnd() + en = None + if getattr(obj, 'IsEnabled', None): + (key, en) = enables_get_last(obj) + if not key: + en = obj.IsEnabled() + grp = self.alias_grp_get(obj) + if getattr(obj, 'GetValue', None): + v = obj.GetValue() + for o in grp: + if o is obj: + continue + + if en is not None and o.IsEnabled() != en and not self.is_toggle_button(o): + if key: + enable_set(o, key, en) + else: + o.Enable(en) + if v is not None and getattr(o, 'SetValue', None): + set_val(o, v) + if getattr(o, 'SetInsertionPointEnd', None): + o.SetInsertionPointEnd() def alias_grp_top_obj(self, obj): - return get_top(self.alias_grp_get(obj), obj) + return get_top(self.alias_grp_get(obj), obj) def alias_grp_get(self, obj): - return next( (grp for grp in self.alias_grps if obj in grp), []) + return next( (grp for grp in self.alias_grps if obj in grp), []) def create_tree(self, parent, items, tree, item, cmd_dic): - name = items.get('name', '') - if tree is None: - style = wx.TR_HAS_BUTTONS | wx.TR_NO_LINES | wx.TR_HIDE_ROOT | wx.TR_DEFAULT_STYLE | wx.SUNKEN_BORDER - tree = CT.CustomTreeCtrl(parent, wx.ID_ANY, agwStyle=style) - item = tree.AddRoot(name, data=tree) - tree.Bind(wx.EVT_MOTION, self.OnTreeMotion) - else: - ct_type = 1 if 'cmd' in items else 0 # 1:checkbox type - item = tree.AppendItem(item, name, ct_type=ct_type) - if 'desc' in items: - item.SetData(items.get('desc')) - if 'cmd' in items: - cmd_dic[item] = (items['cmd'], None) - - pdic = self.load_dic_pdic_setup(name, items) - pnl = wx.Panel(tree, wx.ID_ANY) - add_objs = [] - self.new_link(item, name, pdic, self.sys_gdic, pnl, 'sys', 'sys', add_objs) - gdic = self.gdic_get_1st(items) - if 'param' in items: - self.new_link(item, name, pdic, gdic, pnl, 'app', items.get('param'), add_objs) - else: - self.add_cfg_info(item, item, name, None, gdic, False, None) - szr = sizer_wrap(add_objs, wx.HORIZONTAL, parent=pnl) - szr.Fit(pnl) - tree.SetItemWindow(item, pnl) - - for sub in items.get('subs', []): - self.create_tree(parent, sub, tree, item, cmd_dic) - return tree + name = items.get('name', '') + if tree is None: + style = wx.TR_HAS_BUTTONS | wx.TR_NO_LINES | wx.TR_HIDE_ROOT | wx.TR_DEFAULT_STYLE | wx.SUNKEN_BORDER + tree = CT.CustomTreeCtrl(parent, wx.ID_ANY, agwStyle=style) + item = tree.AddRoot(name, data=tree) + tree.Bind(wx.EVT_MOTION, self.OnTreeMotion) + else: + ct_type = 1 if 'cmd' in items else 0 # 1:checkbox type + item = tree.AppendItem(item, name, ct_type=ct_type) + if 'desc' in items: + item.SetData(items.get('desc')) + if 'cmd' in items: + cmd_dic[item] = (items['cmd'], None) + + pdic = self.load_dic_pdic_setup(name, items) + pnl = wx.Panel(tree, wx.ID_ANY) + add_objs = [] + self.new_link(item, name, pdic, self.sys_gdic, pnl, 'sys', 'sys', add_objs) + gdic = self.gdic_get_1st(items) + if 'param' in items: + self.new_link(item, name, pdic, gdic, pnl, 'app', items.get('param'), add_objs) + else: + self.add_cfg_info(item, item, name, None, gdic, False, None) + szr = sizer_wrap(add_objs, wx.HORIZONTAL, parent=pnl) + szr.Fit(pnl) + tree.SetItemWindow(item, pnl) + + for sub in items.get('subs', []): + self.create_tree(parent, sub, tree, item, cmd_dic) + return tree def new_link(self, item, name, pdic, gdic, pnl, link_str, prm_name, add_objs): - lkc = None - if 'no_link' not in gdic.get('flags', []): - lkc = wx.HyperlinkCtrl(pnl, wx.ID_ANY, link_str, "") - fix_link_color(lkc) - self.Bind(wx.EVT_HYPERLINK, self.OnHyperlinked, lkc) - if len(add_objs) > 0: - add_objs += [ wx.StaticText(pnl, wx.ID_ANY, ' ') ] - add_objs += [ wx.StaticText(pnl, wx.ID_ANY, '['), lkc, wx.StaticText(pnl, wx.ID_ANY, ']') ] - prm = self.get_param(prm_name) - self.add_cfg_info(lkc if lkc else item, item, name, pdic, gdic, False, prm) + lkc = None + if 'no_link' not in gdic.get('flags', []): + lkc = wx.HyperlinkCtrl(pnl, wx.ID_ANY, link_str, "") + fix_link_color(lkc) + self.Bind(wx.EVT_HYPERLINK, self.OnHyperlinked, lkc) + if len(add_objs) > 0: + add_objs += [ wx.StaticText(pnl, wx.ID_ANY, ' ') ] + add_objs += [ wx.StaticText(pnl, wx.ID_ANY, '['), lkc, wx.StaticText(pnl, wx.ID_ANY, ']') ] + prm = self.get_param(prm_name) + self.add_cfg_info(lkc if lkc else item, item, name, pdic, gdic, False, prm) def load_dic_pdic_setup(self, name, dic): - name = dic.get('share_val', dic.get('name', name)) - pdic = self.load_dic.get(name, {}) - self.load_dic[ name ] = pdic - return pdic + name = dic.get('share_val', dic.get('name', name)) + pdic = self.load_dic.get(name, {}) + self.load_dic[ name ] = pdic + return pdic def launch_kill_proc(self, obj, cmd_dic, add_args=None): - if obj not in cmd_dic: - set_val(obj, False) - print('not implemented.') - return - v = obj.GetValue() + if obj not in cmd_dic: + set_val(obj, False) + print('not implemented.') + return + v = obj.GetValue() - (cmd, proc) = cmd_dic[obj] - if not cmd: - set_val(obj, False) + (cmd, proc) = cmd_dic[obj] + if not cmd: + set_val(obj, False) - proc = self.launch_kill(v, cmd, proc, add_args, obj=obj, kill_children=True) + proc = self.launch_kill(v, cmd, proc, add_args, obj=obj, kill_children=True) - (cfg_obj, dic) = self.cfg_obj_dic( {'obj':obj} ) - if cfg_obj and dic.get('run_disable'): - cfg_obj.Enable(not v) + (cfg_obj, dic) = self.cfg_obj_dic( {'obj':obj} ) + if cfg_obj and dic.get('run_disable'): + cfg_obj.Enable(not v) - cmd_dic[obj] = (cmd, proc) - if not v: - self.stat_label_off(obj) + cmd_dic[obj] = (cmd, proc) + if not v: + self.stat_label_off(obj) def launch_kill_proc2(self, obj, cmd_dic, add_args=None, is_rapid_delete=None): - v = obj.GetValue() + v = obj.GetValue() - (cmd, proc) = cmd_dic[obj] - if not cmd: - set_val(obj, False) + (cmd, proc) = cmd_dic[obj] + if not cmd: + set_val(obj, False) - proc = self.launch_kill(v, cmd, proc, add_args, obj=obj, is_rapid_delete=is_rapid_delete) + proc = self.launch_kill(v, cmd, proc, add_args, obj=obj, is_rapid_delete=is_rapid_delete) - self.cmd_dic[obj] = (cmd, proc); return proc + self.cmd_dic[obj] = (cmd, proc); return proc def proc_to_cmd_dic_obj(self, proc): - for cmd_dic in self.all_cmd_dics: - obj = next( (obj for (obj, v) in cmd_dic.items() if proc in v), None) - if obj: - return (cmd_dic, obj) - return (None, None) + for cmd_dic in self.all_cmd_dics: + obj = next( (obj for (obj, v) in cmd_dic.items() if proc in v), None) + if obj: + return (cmd_dic, obj) + return (None, None) def launch_kill(self, v, cmd, proc, add_args=None, sigint=None, obj=None, kill_children=None, is_rapid_delete=False): - msg = None - msg = 'already launched.' if v and proc else msg - msg = 'already terminated.' if not v and proc is None else msg - msg = 'cmd not implemented.' if not cmd else msg - if msg is not None: - print(msg) - return proc - - if v: - args = shlex.split(cmd) - if add_args: - args += add_args - - f = self.obj_to_gdic(obj, {}).get('stdout_func') - f = eval_if_str(self, f) - f = f if f else self.log_th - - out = subprocess.PIPE if f else None - err = subprocess.STDOUT if f else None - if f == self.log_th: - err = subprocess.PIPE - - proc = psutil.Popen(args, stdin=subprocess.PIPE, stdout=out, stderr=err) - self.all_procs.append(proc) - - if f == self.log_th: - thinf = th_start(f, {'file':proc.stdout, 'que':self.log_que_stdout}) - self.all_th_infs.append(thinf) - thinf = th_start(f, {'file':proc.stderr, 'que':self.log_que_stderr}) - self.all_th_infs.append(thinf) - elif f: - thinf = th_start(f, {'file':proc.stdout}) - self.all_th_infs.append(thinf) - else: - flags = self.obj_to_gdic(obj, {}).get('flags', []) - if sigint is None: - sigint = 'SIGTERM' not in flags + msg = None + msg = 'already launched.' if v and proc else msg + msg = 'already terminated.' if not v and proc is None else msg + msg = 'cmd not implemented.' if not cmd else msg + if msg is not None: + print(msg) + return proc + + if v: + args = shlex.split(cmd) + if add_args: + args += add_args + + f = self.obj_to_gdic(obj, {}).get('stdout_func') + f = eval_if_str(self, f) + f = f if f else self.log_th + + out = subprocess.PIPE if f else None + err = subprocess.STDOUT if f else None + if f == self.log_th: + err = subprocess.PIPE + + proc = psutil.Popen(args, stdin=subprocess.PIPE, stdout=out, stderr=err) + self.all_procs.append(proc) + + if f == self.log_th: + thinf = th_start(f, {'file':proc.stdout, 'que':self.log_que_stdout}) + self.all_th_infs.append(thinf) + thinf = th_start(f, {'file':proc.stderr, 'que':self.log_que_stderr}) + self.all_th_infs.append(thinf) + elif f: + thinf = th_start(f, {'file':proc.stdout}) + self.all_th_infs.append(thinf) + else: + flags = self.obj_to_gdic(obj, {}).get('flags', []) + if sigint is None: + sigint = 'SIGTERM' not in flags if is_rapid_delete: sigint = False flags = ["SIGTERM", "kill_children"] - if kill_children is None: - kill_children = 'kill_children' in flags - if kill_children: - terminate_children(proc, sigint) - terminate(proc, sigint) - proc.wait() - if proc in self.all_procs: - self.all_procs.remove(proc) - proc = None - - return proc + if kill_children is None: + kill_children = 'kill_children' in flags + if kill_children: + terminate_children(proc, sigint) + terminate(proc, sigint) + proc.wait() + if proc in self.all_procs: + self.all_procs.remove(proc) + proc = None + + return proc def roslaunch_to_nodes(self, cmd): - try: - s = subprocess.check_output(cmd).strip() - return s.split('\n') if s != '' else [] - except subprocess.CalledProcessError: - return [] + try: + s = subprocess.check_output(cmd).strip() + return s.split('\n') if s != '' else [] + except subprocess.CalledProcessError: + return [] def set_bg_all_tabs(self, col=wx.NullColour): - add_pnls = [ - self, - # self.tree_ctrl_0, - # self.tree_ctrl_1, - # self.tree_ctrl_data + add_pnls = [ + self, + # self.tree_ctrl_0, + # self.tree_ctrl_1, + # self.tree_ctrl_data ] - for tab in self.all_tabs + add_pnls: - tab.SetBackgroundColour(col) + for tab in self.all_tabs + add_pnls: + tab.SetBackgroundColour(col) def get_autoware_dir(self): - dir = rtmgr_src_dir() + '../../../../../../' - return os.path.abspath(dir) + dir = rtmgr_src_dir() + '../../../../../../' + return os.path.abspath(dir) def load_yaml(self, filename, def_ret=None): - return load_yaml(filename, def_ret) + return load_yaml(filename, def_ret) def toggle_enable_obj(self, obj): - objs = [] - pfs = [ 'button_play_', 'button_stop_', 'button_pause_', - 'button_ref_', 'text_ctrl_' ] - key = self.obj_key_get(obj, pfs) - if key: - objs += self.key_objs_get(pfs, key) + objs = [] + pfs = [ 'button_play_', 'button_stop_', 'button_pause_', + 'button_ref_', 'text_ctrl_' ] + key = self.obj_key_get(obj, pfs) + if key: + objs += self.key_objs_get(pfs, key) - gdic = self.obj_to_gdic(obj, {}) - objs += [ eval_if_str(self, e) for e in gdic.get('ext_toggle_enables', []) ] + gdic = self.obj_to_gdic(obj, {}) + objs += [ eval_if_str(self, e) for e in gdic.get('ext_toggle_enables', []) ] - self.toggle_enables(objs) + self.toggle_enables(objs) def toggle_enables(self, objs): - for obj in objs: - if getattr(obj, 'IsEnabled', None): - en = enables_get(obj, 'toggle', obj.IsEnabled()) - enables_set(obj, 'toggle', not en) - self.alias_sync(obj) + for obj in objs: + if getattr(obj, 'IsEnabled', None): + en = enables_get(obj, 'toggle', obj.IsEnabled()) + enables_set(obj, 'toggle', not en) + self.alias_sync(obj) def is_toggle_button(self, obj): - return self.name_get(obj).split('_')[0] == 'button' and getattr(obj, 'GetValue', None) + return self.name_get(obj).split('_')[0] == 'button' and getattr(obj, 'GetValue', None) def obj_name_split(self, obj, pfs): - name = self.name_get(obj) - if name is None: - return (None, None) - return next( ( ( name[:len(pf)], name[len(pf):] ) for pf in pfs if name[:len(pf)] == pf ), None) + name = self.name_get(obj) + if name is None: + return (None, None) + return next( ( ( name[:len(pf)], name[len(pf):] ) for pf in pfs if name[:len(pf)] == pf ), None) def obj_key_get(self, obj, pfs): - name = self.name_get(obj) - if name is None: - return None - return next( (name[len(pf):] for pf in pfs if name[:len(pf)] == pf), None) + name = self.name_get(obj) + if name is None: + return None + return next( (name[len(pf):] for pf in pfs if name[:len(pf)] == pf), None) def key_objs_get(self, pfs, key): - return [ self.obj_get(pf + key) for pf in pfs if self.obj_get(pf + key) ] + return [ self.obj_get(pf + key) for pf in pfs if self.obj_get(pf + key) ] def name_get(self, obj): - return next( (nm for nm in dir(self) if getattr(self, nm) is obj), None) + return next( (nm for nm in dir(self) if getattr(self, nm) is obj), None) def name_get_cond(self, obj, cond=(lambda s : True), def_ret=None): - return next( (nm for nm in dir(self) if cond(nm) and getattr(self, nm) is obj), def_ret) + return next( (nm for nm in dir(self) if cond(nm) and getattr(self, nm) is obj), def_ret) def val_get(self, name): - obj = self.obj_get(name) - if obj is None: - return None - return obj.GetValue() if getattr(obj, 'GetValue', None) else None + obj = self.obj_get(name) + if obj is None: + return None + return obj.GetValue() if getattr(obj, 'GetValue', None) else None def obj_get(self, name): - return getattr(self, name, None) + return getattr(self, name, None) def gdic_dialog_type_chk(gdic, name): - dlg_type = dic_list_get(gdic, 'dialog_type', 'config') + dlg_type = dic_list_get(gdic, 'dialog_type', 'config') - tail = '_dialog_only' - lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] - only_chk = next( (False for (k,type) in lst if type != dlg_type and name in gdic.get(k, [])), True) + tail = '_dialog_only' + lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] + only_chk = next( (False for (k,type) in lst if type != dlg_type and name in gdic.get(k, [])), True) - tail = '_dialog_allow' - lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] - allow_chk = next( (False for (k,type) in lst if type == dlg_type and name not in gdic.get(k, [])), True) + tail = '_dialog_allow' + lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] + allow_chk = next( (False for (k,type) in lst if type == dlg_type and name not in gdic.get(k, [])), True) - return only_chk and allow_chk + return only_chk and allow_chk def gdic_dialog_name_get(gdic): - dlg_type = dic_list_get(gdic, 'dialog_type', 'config') - return gdic.get(dlg_type + '_dialog', gdic.get('dialog', 'MyDialogParam') ) + dlg_type = dic_list_get(gdic, 'dialog_type', 'config') + return gdic.get(dlg_type + '_dialog', gdic.get('dialog', 'MyDialogParam') ) class ParamPanel(wx.Panel): - def __init__(self, *args, **kwds): - self.frame = kwds.pop('frame') - self.pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - self.prm = kwds.pop('prm') - wx.Panel.__init__(self, *args, **kwds) - - self.gdic['param_panel'] = self - - obj = self.frame.cfg_prm_to_obj( {'pdic':self.pdic, 'gdic':self.gdic, 'param':self.prm} ) - (_, _, proc) = self.frame.obj_to_cmd_dic_cmd_proc(obj) - - hszr = None - self.vps = [] - self.tmp_msg = None - szr = wx.BoxSizer(wx.VERTICAL) - - topic_szrs = (None, None) - - vars = self.prm.get('vars') - if self.gdic.get('show_order'): - var_lst = lambda name, vars : [ var for var in vars if var.get('name') == name ] - vars = reduce( lambda lst, name : lst + var_lst(name, vars), self.gdic.get('show_order'), [] ) - - for var in vars: - name = var.get('name') - - if not gdic_dialog_type_chk(self.gdic, name): - continue - - gdic_v = self.get_gdic_v_and_chk_enable(name) - if gdic_v is None: - continue - - bak_stk_push(gdic_v, 'func') - if gdic_v.get('func'): - continue - - v = self.pdic.get(name, var.get('v')) - - vp = VarPanel(self, var=var, v=v, update=self.update) - vp.setup_tooltip() - self.vps.append(vp) - - gdic_v['var'] = vp - gdic_v['func'] = vp.get_v - prop = gdic_v.get('prop', 0) - border = gdic_v.get('border', 0) - flag = wx_flag_get(gdic_v.get('flags', [])) - - do_category = 'no_category' not in gdic_v.get('flags', []) - if do_category and self.in_msg(var): - bak = (szr, hszr) - (szr, hszr) = topic_szrs - if szr is None: - szr = static_box_sizer(self, 'topic : ' + self.prm.get('topic')) - bak[0].Add(szr, 0, wx.EXPAND | wx.ALL, 4) - targ_szr = szr - if vp.is_nl(): - hszr = None if hszr else hszr - flag |= wx.EXPAND - else: - if hszr is None: - hszr = wx.BoxSizer(wx.HORIZONTAL) - szr.Add(hszr, 0, wx.EXPAND) - flag |= wx.ALIGN_CENTER_VERTICAL - targ_szr = hszr - - if do_category and 'rosparam' in var: - rp_szr = static_box_sizer(self, 'rosparam : ' + var.get('rosparam')) - targ_szr.Add(rp_szr, 0, wx.EXPAND | wx.ALL, 4) - targ_szr = rp_szr - - user_category = gdic_v.get('user_category') - if user_category is not None and hszr: - user_szr = static_box_sizer(self, user_category, orient=wx.HORIZONTAL) - (flgs, bdr) = gdic_v.get('user_category_add', [ [], 0 ]) - targ_szr.Add(user_szr, 0, wx_flag_get(flgs), bdr) - targ_szr = hszr = user_szr - - targ_szr.Add(vp, prop, flag, border) - - if 'nl' in gdic_v.get('flags', []): - hszr = None - - if do_category and self.in_msg(var): - topic_szrs = (szr, hszr) - (szr, hszr) = bak - - if 'hline' in gdic_v.get('flags', []) and hszr is None: - szr.Add(wx.StaticLine(self, wx.ID_ANY), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 4) - - if not self.in_msg(var) and var.get('rosparam'): - k = 'ext_toggle_enables' - self.gdic[ k ] = self.gdic.get(k, []) + [ vp ] - enables_set(vp, 'toggle', proc is None) - - if 'disable' in gdic_v.get('flags', []): - vp.Enable(False) - if 'hide' in gdic_v.get('flags', []): - vp.Hide() - - self.SetSizer(szr) - if 'no_init_update' not in self.prm.get('flags', []): - self.update() - - def get_gdic_v_and_chk_enable(self, var_name): - gdic_v = dic_getset(self.gdic, var_name, {}) - if 'panel' in gdic_v and dic_eval_if_str(self.frame, gdic_v, 'panel') != self.GetParent(): - return None - return gdic_v - - def update(self, var=None): - update_func = self.gdic.get('update_func') - if update_func: - self.gdic['update_func_arg_var'] = var - update_func(self.pdic, self.gdic, self.prm) - - def detach_func(self): - for var in self.prm.get('vars'): - name = var.get('name') - - if not gdic_dialog_type_chk(self.gdic, name): - continue - - gdic_v = self.get_gdic_v_and_chk_enable(name) - if gdic_v is None: - continue - - if 'func' in gdic_v: - bak_stk_pop(gdic_v, 'func') - - vp = gdic_v.get('var') - lst_remove_once(self.gdic.get('ext_toggle_enables', []), vp) - - def in_msg(self, var): - if 'topic' not in self.prm or 'msg' not in self.prm: - return False - if self.tmp_msg is None: - klass_msg = globals().get( self.prm.get('msg') ) - if klass_msg is None: - return False - self.tmp_msg = klass_msg() - (obj, attr) = msg_path_to_obj_attr(self.tmp_msg, var.get('name')) - return obj and attr in obj.__slots__ + def __init__(self, *args, **kwds): + self.frame = kwds.pop('frame') + self.pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + self.prm = kwds.pop('prm') + wx.Panel.__init__(self, *args, **kwds) + + self.gdic['param_panel'] = self + + obj = self.frame.cfg_prm_to_obj( {'pdic':self.pdic, 'gdic':self.gdic, 'param':self.prm} ) + (_, _, proc) = self.frame.obj_to_cmd_dic_cmd_proc(obj) + + hszr = None + self.vps = [] + self.tmp_msg = None + szr = wx.BoxSizer(wx.VERTICAL) + + topic_szrs = (None, None) + + vars = self.prm.get('vars') + if self.gdic.get('show_order'): + var_lst = lambda name, vars : [ var for var in vars if var.get('name') == name ] + vars = reduce( lambda lst, name : lst + var_lst(name, vars), self.gdic.get('show_order'), [] ) + + for var in vars: + name = var.get('name') + + if not gdic_dialog_type_chk(self.gdic, name): + continue + + gdic_v = self.get_gdic_v_and_chk_enable(name) + if gdic_v is None: + continue + + bak_stk_push(gdic_v, 'func') + if gdic_v.get('func'): + continue + + v = self.pdic.get(name, var.get('v')) + + vp = VarPanel(self, var=var, v=v, update=self.update) + vp.setup_tooltip() + self.vps.append(vp) + + gdic_v['var'] = vp + gdic_v['func'] = vp.get_v + prop = gdic_v.get('prop', 0) + border = gdic_v.get('border', 0) + flag = wx_flag_get(gdic_v.get('flags', [])) + + do_category = 'no_category' not in gdic_v.get('flags', []) + if do_category and self.in_msg(var): + bak = (szr, hszr) + (szr, hszr) = topic_szrs + if szr is None: + szr = static_box_sizer(self, 'topic : ' + self.prm.get('topic')) + bak[0].Add(szr, 0, wx.EXPAND | wx.ALL, 4) + targ_szr = szr + if vp.is_nl(): + hszr = None if hszr else hszr + flag |= wx.EXPAND + else: + if hszr is None: + hszr = wx.BoxSizer(wx.HORIZONTAL) + szr.Add(hszr, 0, wx.EXPAND) + flag |= wx.ALIGN_CENTER_VERTICAL + targ_szr = hszr + + if do_category and 'rosparam' in var: + rp_szr = static_box_sizer(self, 'rosparam : ' + var.get('rosparam')) + targ_szr.Add(rp_szr, 0, wx.EXPAND | wx.ALL, 4) + targ_szr = rp_szr + + user_category = gdic_v.get('user_category') + if user_category is not None and hszr: + user_szr = static_box_sizer(self, user_category, orient=wx.HORIZONTAL) + (flgs, bdr) = gdic_v.get('user_category_add', [ [], 0 ]) + targ_szr.Add(user_szr, 0, wx_flag_get(flgs), bdr) + targ_szr = hszr = user_szr + + targ_szr.Add(vp, prop, flag, border) + + if 'nl' in gdic_v.get('flags', []): + hszr = None + + if do_category and self.in_msg(var): + topic_szrs = (szr, hszr) + (szr, hszr) = bak + + if 'hline' in gdic_v.get('flags', []) and hszr is None: + szr.Add(wx.StaticLine(self, wx.ID_ANY), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 4) + + if not self.in_msg(var) and var.get('rosparam'): + k = 'ext_toggle_enables' + self.gdic[ k ] = self.gdic.get(k, []) + [ vp ] + enables_set(vp, 'toggle', proc is None) + + if 'disable' in gdic_v.get('flags', []): + vp.Enable(False) + if 'hide' in gdic_v.get('flags', []): + vp.Hide() + + self.SetSizer(szr) + if 'no_init_update' not in self.prm.get('flags', []): + self.update() + + def get_gdic_v_and_chk_enable(self, var_name): + gdic_v = dic_getset(self.gdic, var_name, {}) + if 'panel' in gdic_v and dic_eval_if_str(self.frame, gdic_v, 'panel') != self.GetParent(): + return None + return gdic_v + + def update(self, var=None): + update_func = self.gdic.get('update_func') + if update_func: + self.gdic['update_func_arg_var'] = var + update_func(self.pdic, self.gdic, self.prm) + + def detach_func(self): + for var in self.prm.get('vars'): + name = var.get('name') + + if not gdic_dialog_type_chk(self.gdic, name): + continue + + gdic_v = self.get_gdic_v_and_chk_enable(name) + if gdic_v is None: + continue + + if 'func' in gdic_v: + bak_stk_pop(gdic_v, 'func') + + vp = gdic_v.get('var') + lst_remove_once(self.gdic.get('ext_toggle_enables', []), vp) + + def in_msg(self, var): + if 'topic' not in self.prm or 'msg' not in self.prm: + return False + if self.tmp_msg is None: + klass_msg = globals().get( self.prm.get('msg') ) + if klass_msg is None: + return False + self.tmp_msg = klass_msg() + (obj, attr) = msg_path_to_obj_attr(self.tmp_msg, var.get('name')) + return obj and attr in obj.__slots__ class VarPanel(wx.Panel): - def __init__(self, *args, **kwds): - self.var = kwds.pop('var') - v = kwds.pop('v') - self.update = kwds.pop('update') - wx.Panel.__init__(self, *args, **kwds) - - self.min = self.var.get('min') - self.max = self.var.get('max') - self.has_slider = self.min is not None and self.max is not None - self.lb = None - - label = self.var.get('label', '') - self.kind = self.var.get('kind') - if self.kind == 'radio_box': - choices = self.var.get('choices', []) - style = wx.RA_SPECIFY_COLS if self.var.get('choices_style') == 'h' else wx.RA_SPECIFY_ROWS - self.obj = wx.RadioBox(self, wx.ID_ANY, label, choices=choices, majorDimension=0, style=style) - self.choices_sel_set(v) - self.Bind(wx.EVT_RADIOBOX, self.OnUpdate, self.obj) - return - if self.kind == 'menu': - choices = self.var.get('choices', []) - self.obj = wx.Choice(self, wx.ID_ANY, choices=choices) - self.choices_sel_set(v) - self.Bind(wx.EVT_CHOICE, self.OnUpdate, self.obj) - if label: - self.lb = wx.StaticText(self, wx.ID_ANY, label) - flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL - sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) - return - if self.kind == 'checkbox': - self.obj = wx.CheckBox(self, wx.ID_ANY, label) - self.obj.SetValue(v) - self.Bind(wx.EVT_CHECKBOX, self.OnUpdate, self.obj) - return - if self.kind == 'checkboxes': - item_n = dic_eval_if_str(self, self.var, 'item_n', 1) - self.obj = Checkboxes(self, item_n, label) - self.obj.set(v) - for box in self.obj.boxes: - self.obj.Bind(wx.EVT_CHECKBOX, self.OnUpdate, box) - return - if self.kind == 'toggle_button': - self.obj = wx.ToggleButton(self, wx.ID_ANY, label) - set_val(self.obj, v) - self.Bind(wx.EVT_TOGGLEBUTTON, self.OnUpdate, self.obj) - button_color_hdr_setup(self.obj) - return - if self.kind == 'hide': - self.Hide() - return - - szr = wx.BoxSizer(wx.HORIZONTAL) - - self.lb = wx.StaticText(self, wx.ID_ANY, label) - flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL - szr.Add(self.lb, 0, flag, 4) - - if self.kind == 'path': - v = str(v) - v = path_expand_cmd(v) - v = os.path.expandvars(os.path.expanduser(v)) - - style = wx.TE_PROCESS_ENTER + wx_flag_get( self.var.get('str_flags', []) ) - - self.tc = wx.TextCtrl(self, wx.ID_ANY, str(v), style=style) - self.Bind(wx.EVT_TEXT_ENTER, self.OnUpdate, self.tc) - - if self.kind in ('num', None): - if self.has_slider: - self.w = self.max - self.min - vlst = [ v, self.min, self.max, self.var['v'] ] - self.is_float = len( [ v_ for v_ in vlst if type(v_) is not int ] ) > 0 - self.int_max = 1000 if self.is_float else self.max - self.int_min = 0 if self.is_float else self.min - - self.slider = wx.Slider(self, wx.ID_ANY, self.get_int_v(), self.int_min, self.int_max) - self.Bind(wx.EVT_COMMAND_SCROLL, self.OnScroll, self.slider) - self.slider.SetMinSize((82, 27)) - szr.Add(self.slider, 1, wx.LEFT | wx.RIGHT | wx.ALIGN_CENTER_VERTICAL, 4) - else: - self.is_float = type(self.var['v']) is not int - self.tc.SetMinSize((40,27)) - - flag = wx.ALIGN_CENTER_VERTICAL - prop = 1 if self.kind == 'path' or self.kind == 'str' else 0 - szr.Add(self.tc, prop, flag, 4) - - if self.kind == 'path': - self.ref = wx.Button(self, wx.ID_ANY, 'Ref') - self.Bind(wx.EVT_BUTTON, self.OnRef, self.ref) - button_color_hdr_setup(self.ref) - self.ref.SetMinSize((40,29)) - szr.Add(self.ref, 0, flag, 4) - - if self.has_slider or self.kind == 'num': - vszr = wx.BoxSizer(wx.VERTICAL) - vszr.Add( self.create_bmbtn("inc.png", self.OnIncBtn) ) - vszr.Add( self.create_bmbtn("dec.png", self.OnDecBtn) ) - szr.Add(vszr, 0, wx.ALIGN_CENTER_VERTICAL) - - self.SetSizer(szr) - - def setup_tooltip(self): - if get_tooltips(self.var): - set_tooltips(self.obj, self.var) - if get_tooltip(self.var): - obj = self.lb if self.lb else (self if self.kind == 'radio_box' else self.obj) - set_tooltip(obj, self.var) - - def create_bmbtn(self, filename, hdr): - dir = rtmgr_src_dir() - bm = wx.Bitmap(dir + filename, wx.BITMAP_TYPE_ANY) - style = wx.BORDER_NONE | wx.BU_EXACTFIT - obj = wx.lib.buttons.GenBitmapButton(self, wx.ID_ANY, bm, style=style) - self.Bind(wx.EVT_BUTTON, hdr, obj) - return obj - - def get_v(self): - if self.kind in [ 'radio_box', 'menu' ]: - return self.choices_sel_get() - if self.kind in [ 'checkbox', 'toggle_button' ]: - return self.obj.GetValue() - if self.kind == 'checkboxes': - return self.obj.get() - if self.kind == 'hide': - return self.var.get('v') - if self.kind in [ 'path', 'str' ]: - return str(self.tc.GetValue()) - - if not self.has_slider and self.tc.GetValue() == '': - return '' - return self.get_tc_v() - - def get_tc_v(self): - s = self.tc.GetValue() - v = str_to_float(s) if self.is_float else int(s) - if self.has_slider: - v = self.min if v < self.min else v - v = self.max if v > self.max else v - self.tc.SetValue(adjust_num_str(str(v))) - return v - - def get_int_v(self): - v = self.get_tc_v() - if self.is_float: - v = int( self.int_max * (v - self.min) / self.w if self.w != 0 else 0 ) - return v - - def OnScroll(self, event): - iv = self.slider.GetValue() - s = str(iv) - if self.is_float: - v = self.min + float(self.w) * iv / self.int_max - s = str(Decimal(v).quantize(Decimal(str(self.get_step())))) - self.tc.SetValue(s) - self.update(self.var) - - def OnIncBtn(self, event): - step = self.get_step() - self.add_v(step) - - def OnDecBtn(self, event): - step = self.get_step() - self.add_v(-step) - - def get_step(self): - step = self.var.get('step') - return step if step else 0.01 if self.is_float else 1 - - def add_v(self, step): - ov = self.get_v() - self.tc.SetValue(str(ov + step)) - v = self.get_v() - if v != ov: - if self.has_slider: - self.slider.SetValue(self.get_int_v()) - self.update(self.var) - - def OnUpdate(self, event): - if self.has_slider: - self.slider.SetValue(self.get_int_v()) - self.update(self.var) - - def OnRef(self, event): - if file_dialog(self, self.tc, self.var) == wx.ID_OK: - self.update(self.var) - - def choices_sel_get(self): - return self.obj.GetStringSelection() if self.var.get('choices_type') == 'str' else self.obj.GetSelection() - - def choices_sel_set(self, v): - if self.var.get('choices_type') == 'str': - self.obj.SetStringSelection(v) - else: - self.obj.SetSelection(v) - - def is_nl(self): - return self.has_slider or self.kind in [ 'path' ] + def __init__(self, *args, **kwds): + self.var = kwds.pop('var') + v = kwds.pop('v') + self.update = kwds.pop('update') + wx.Panel.__init__(self, *args, **kwds) + + self.min = self.var.get('min') + self.max = self.var.get('max') + self.has_slider = self.min is not None and self.max is not None + self.lb = None + + label = self.var.get('label', '') + self.kind = self.var.get('kind') + if self.kind == 'radio_box': + choices = self.var.get('choices', []) + style = wx.RA_SPECIFY_COLS if self.var.get('choices_style') == 'h' else wx.RA_SPECIFY_ROWS + self.obj = wx.RadioBox(self, wx.ID_ANY, label, choices=choices, majorDimension=0, style=style) + self.choices_sel_set(v) + self.Bind(wx.EVT_RADIOBOX, self.OnUpdate, self.obj) + return + if self.kind == 'menu': + choices = self.var.get('choices', []) + self.obj = wx.Choice(self, wx.ID_ANY, choices=choices) + self.choices_sel_set(v) + self.Bind(wx.EVT_CHOICE, self.OnUpdate, self.obj) + if label: + self.lb = wx.StaticText(self, wx.ID_ANY, label) + flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL + sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) + return + if self.kind == 'checkbox': + self.obj = wx.CheckBox(self, wx.ID_ANY, label) + self.obj.SetValue(v) + self.Bind(wx.EVT_CHECKBOX, self.OnUpdate, self.obj) + return + if self.kind == 'checkboxes': + item_n = dic_eval_if_str(self, self.var, 'item_n', 1) + self.obj = Checkboxes(self, item_n, label) + self.obj.set(v) + for box in self.obj.boxes: + self.obj.Bind(wx.EVT_CHECKBOX, self.OnUpdate, box) + return + if self.kind == 'toggle_button': + self.obj = wx.ToggleButton(self, wx.ID_ANY, label) + set_val(self.obj, v) + self.Bind(wx.EVT_TOGGLEBUTTON, self.OnUpdate, self.obj) + button_color_hdr_setup(self.obj) + return + if self.kind == 'hide': + self.Hide() + return + + szr = wx.BoxSizer(wx.HORIZONTAL) + + self.lb = wx.StaticText(self, wx.ID_ANY, label) + flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL + szr.Add(self.lb, 0, flag, 4) + + if self.kind == 'path': + v = str(v) + v = path_expand_cmd(v) + v = os.path.expandvars(os.path.expanduser(v)) + + style = wx.TE_PROCESS_ENTER + wx_flag_get( self.var.get('str_flags', []) ) + + self.tc = wx.TextCtrl(self, wx.ID_ANY, str(v), style=style) + self.Bind(wx.EVT_TEXT_ENTER, self.OnUpdate, self.tc) + + if self.kind in ('num', None): + if self.has_slider: + self.w = self.max - self.min + vlst = [ v, self.min, self.max, self.var['v'] ] + self.is_float = len( [ v_ for v_ in vlst if type(v_) is not int ] ) > 0 + self.int_max = 1000 if self.is_float else self.max + self.int_min = 0 if self.is_float else self.min + + self.slider = wx.Slider(self, wx.ID_ANY, self.get_int_v(), self.int_min, self.int_max) + self.Bind(wx.EVT_COMMAND_SCROLL, self.OnScroll, self.slider) + self.slider.SetMinSize((82, 27)) + szr.Add(self.slider, 1, wx.LEFT | wx.RIGHT | wx.ALIGN_CENTER_VERTICAL, 4) + else: + self.is_float = type(self.var['v']) is not int + self.tc.SetMinSize((40,27)) + + flag = wx.ALIGN_CENTER_VERTICAL + prop = 1 if self.kind == 'path' or self.kind == 'str' else 0 + szr.Add(self.tc, prop, flag, 4) + + if self.kind == 'path': + self.ref = wx.Button(self, wx.ID_ANY, 'Ref') + self.Bind(wx.EVT_BUTTON, self.OnRef, self.ref) + button_color_hdr_setup(self.ref) + self.ref.SetMinSize((40,29)) + szr.Add(self.ref, 0, flag, 4) + + if self.has_slider or self.kind == 'num': + vszr = wx.BoxSizer(wx.VERTICAL) + vszr.Add( self.create_bmbtn("inc.png", self.OnIncBtn) ) + vszr.Add( self.create_bmbtn("dec.png", self.OnDecBtn) ) + szr.Add(vszr, 0, wx.ALIGN_CENTER_VERTICAL) + + self.SetSizer(szr) + + def setup_tooltip(self): + if get_tooltips(self.var): + set_tooltips(self.obj, self.var) + if get_tooltip(self.var): + obj = self.lb if self.lb else (self if self.kind == 'radio_box' else self.obj) + set_tooltip(obj, self.var) + + def create_bmbtn(self, filename, hdr): + dir = rtmgr_src_dir() + bm = wx.Bitmap(dir + filename, wx.BITMAP_TYPE_ANY) + style = wx.BORDER_NONE | wx.BU_EXACTFIT + obj = wx.lib.buttons.GenBitmapButton(self, wx.ID_ANY, bm, style=style) + self.Bind(wx.EVT_BUTTON, hdr, obj) + return obj + + def get_v(self): + if self.kind in [ 'radio_box', 'menu' ]: + return self.choices_sel_get() + if self.kind in [ 'checkbox', 'toggle_button' ]: + return self.obj.GetValue() + if self.kind == 'checkboxes': + return self.obj.get() + if self.kind == 'hide': + return self.var.get('v') + if self.kind in [ 'path', 'str' ]: + return str(self.tc.GetValue()) + + if not self.has_slider and self.tc.GetValue() == '': + return '' + return self.get_tc_v() + + def get_tc_v(self): + s = self.tc.GetValue() + v = str_to_float(s) if self.is_float else int(s) + if self.has_slider: + v = self.min if v < self.min else v + v = self.max if v > self.max else v + self.tc.SetValue(adjust_num_str(str(v))) + return v + + def get_int_v(self): + v = self.get_tc_v() + if self.is_float: + v = int( self.int_max * (v - self.min) / self.w if self.w != 0 else 0 ) + return v + + def OnScroll(self, event): + iv = self.slider.GetValue() + s = str(iv) + if self.is_float: + v = self.min + float(self.w) * iv / self.int_max + s = str(Decimal(v).quantize(Decimal(str(self.get_step())))) + self.tc.SetValue(s) + self.update(self.var) + + def OnIncBtn(self, event): + step = self.get_step() + self.add_v(step) + + def OnDecBtn(self, event): + step = self.get_step() + self.add_v(-step) + + def get_step(self): + step = self.var.get('step') + return step if step else 0.01 if self.is_float else 1 + + def add_v(self, step): + ov = self.get_v() + self.tc.SetValue(str(ov + step)) + v = self.get_v() + if v != ov: + if self.has_slider: + self.slider.SetValue(self.get_int_v()) + self.update(self.var) + + def OnUpdate(self, event): + if self.has_slider: + self.slider.SetValue(self.get_int_v()) + self.update(self.var) + + def OnRef(self, event): + if file_dialog(self, self.tc, self.var) == wx.ID_OK: + self.update(self.var) + + def choices_sel_get(self): + return self.obj.GetStringSelection() if self.var.get('choices_type') == 'str' else self.obj.GetSelection() + + def choices_sel_set(self, v): + if self.var.get('choices_type') == 'str': + self.obj.SetStringSelection(v) + else: + self.obj.SetSelection(v) + + def is_nl(self): + return self.has_slider or self.kind in [ 'path' ] class MyDialogParam(rtmgr.MyDialogParam): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.pdic_bak = pdic.copy() - gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogParam.__init__(self, *args, **kwds) - - self.Bind(wx.EVT_CLOSE, self.OnClose) - - ok_lb_key = 'open_dialog_ok_label' - if dic_list_get(gdic, 'dialog_type', 'config') == 'open' and ok_lb_key in gdic: - self.button_1.SetLabel( gdic.get(ok_lb_key) ) - - parent = self.panel_v - frame = self.GetParent() - self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) - szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) - - self.SetTitle(prm.get('name', '')) - (w,h) = self.GetSize() - (w2,_) = szr.GetMinSize() - w2 += 20 - if w2 > w: - self.SetSize((w2,h)) - - def OnOk(self, event): - self.panel.update() - self.panel.detach_func() - self.EndModal(0) - - def OnCancel(self, event): - self.panel.pdic.update(self.pdic_bak) # restore - self.panel.detach_func() - self.panel.update() - self.EndModal(-1) - - def OnClose(self, event): - self.OnCancel(event) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.pdic_bak = pdic.copy() + gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogParam.__init__(self, *args, **kwds) + + self.Bind(wx.EVT_CLOSE, self.OnClose) + + ok_lb_key = 'open_dialog_ok_label' + if dic_list_get(gdic, 'dialog_type', 'config') == 'open' and ok_lb_key in gdic: + self.button_1.SetLabel( gdic.get(ok_lb_key) ) + + parent = self.panel_v + frame = self.GetParent() + self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) + szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) + + self.SetTitle(prm.get('name', '')) + (w,h) = self.GetSize() + (w2,_) = szr.GetMinSize() + w2 += 20 + if w2 > w: + self.SetSize((w2,h)) + + def OnOk(self, event): + self.panel.update() + self.panel.detach_func() + self.EndModal(0) + + def OnCancel(self, event): + self.panel.pdic.update(self.pdic_bak) # restore + self.panel.detach_func() + self.panel.update() + self.EndModal(-1) + + def OnClose(self, event): + self.OnCancel(event) class MyDialogDPM(rtmgr.MyDialogDPM): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.pdic_bak = pdic.copy() - gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogDPM.__init__(self, *args, **kwds) - - self.Bind(wx.EVT_CLOSE, self.OnClose) - - parent = self.panel_v - frame = self.GetParent() - self.frame = frame - self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) - szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) - - self.SetTitle(prm.get('name', '')) - (w,h) = self.GetSize() - (w2,_) = szr.GetMinSize() - w2 += 20 - if w2 > w: - self.SetSize((w2,h)) - - fix_link_color(self.hyperlink_car) - fix_link_color(self.hyperlink_pedestrian) - - def OnOk(self, event): - self.panel.update() - self.panel.detach_func() - self.EndModal(0) - - def OnLink(self, event): - obj = event.GetEventObject() - dic = { self.hyperlink_car : self.frame.button_car_dpm, - self.hyperlink_pedestrian : self.frame.button_pedestrian_dpm } - obj = dic.get(obj) - if obj: - self.frame.OnHyperlinked_obj(obj) - - def OnCancel(self, event): - self.panel.pdic.update(self.pdic_bak) # restore - self.panel.detach_func() - self.panel.update() - self.EndModal(-1) - - def OnClose(self, event): - self.OnCancel(event) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.pdic_bak = pdic.copy() + gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogDPM.__init__(self, *args, **kwds) + + self.Bind(wx.EVT_CLOSE, self.OnClose) + + parent = self.panel_v + frame = self.GetParent() + self.frame = frame + self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) + szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) + + self.SetTitle(prm.get('name', '')) + (w,h) = self.GetSize() + (w2,_) = szr.GetMinSize() + w2 += 20 + if w2 > w: + self.SetSize((w2,h)) + + fix_link_color(self.hyperlink_car) + fix_link_color(self.hyperlink_pedestrian) + + def OnOk(self, event): + self.panel.update() + self.panel.detach_func() + self.EndModal(0) + + def OnLink(self, event): + obj = event.GetEventObject() + dic = { self.hyperlink_car : self.frame.button_car_dpm, + self.hyperlink_pedestrian : self.frame.button_pedestrian_dpm } + obj = dic.get(obj) + if obj: + self.frame.OnHyperlinked_obj(obj) + + def OnCancel(self, event): + self.panel.pdic.update(self.pdic_bak) # restore + self.panel.detach_func() + self.panel.update() + self.EndModal(-1) + + def OnClose(self, event): + self.OnCancel(event) class MyDialogCarPedestrian(rtmgr.MyDialogCarPedestrian): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogCarPedestrian.__init__(self, *args, **kwds) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogCarPedestrian.__init__(self, *args, **kwds) - self.Bind(wx.EVT_CLOSE, self.OnClose) + self.Bind(wx.EVT_CLOSE, self.OnClose) - frame = self.GetParent() - self.frame = frame + frame = self.GetParent() + self.frame = frame - self.SetTitle(prm.get('name', '')) + self.SetTitle(prm.get('name', '')) - fix_link_color(self.hyperlink_car) - fix_link_color(self.hyperlink_pedestrian) + fix_link_color(self.hyperlink_car) + fix_link_color(self.hyperlink_pedestrian) - def OnLink(self, event): - obj = event.GetEventObject() - car_ped = { self.hyperlink_car : 'car', self.hyperlink_pedestrian : 'pedestrian' }.get(obj, 'car') - obj_key = self.gdic.get('car_pedestrian_obj_key', {}).get(car_ped) - obj = getattr(self.frame, 'button_' + obj_key, None) if obj_key else None - if obj: - self.frame.OnHyperlinked_obj(obj) - self.EndModal(0) + def OnLink(self, event): + obj = event.GetEventObject() + car_ped = { self.hyperlink_car : 'car', self.hyperlink_pedestrian : 'pedestrian' }.get(obj, 'car') + obj_key = self.gdic.get('car_pedestrian_obj_key', {}).get(car_ped) + obj = getattr(self.frame, 'button_' + obj_key, None) if obj_key else None + if obj: + self.frame.OnHyperlinked_obj(obj) + self.EndModal(0) - def OnClose(self, event): - self.EndModal(-1) + def OnClose(self, event): + self.EndModal(-1) class MyDialogLaneStop(rtmgr.MyDialogLaneStop): - def __init__(self, *args, **kwds): - self.pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - self.prm = kwds.pop('prm') - rtmgr.MyDialogLaneStop.__init__(self, *args, **kwds) - self.frame = self.GetParent() - - name = 'lane_stop' - var = next( ( var for var in self.prm.get('vars', []) if var.get('name') == name ), {} ) - v = self.pdic.get( name, var.get('v', False) ) - set_val(self.checkbox_lane_stop, v) - - def update(self): - update_func = self.gdic.get('update_func') - if update_func: - update_func(self.pdic, self.gdic, self.prm) - - def OnTrafficRedLight(self, event): - self.pdic['traffic_light'] = 0 - self.update() - - def OnTrafficGreenLight(self, event): - self.pdic['traffic_light'] = 1 - self.update() - - def OnTrafficLightRecognition(self, event): - pub = rospy.Publisher('/config/lane_stop', ConfigLaneStop, latch=True, queue_size=10) - msg = ConfigLaneStop() - v = event.GetEventObject().GetValue() - self.pdic['lane_stop'] = v - msg.manual_detection = not v - pub.publish(msg) - - def OnOk(self, event): - self.EndModal(0) - - def OnCancel(self, event): - self.EndModal(-1) + def __init__(self, *args, **kwds): + self.pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + self.prm = kwds.pop('prm') + rtmgr.MyDialogLaneStop.__init__(self, *args, **kwds) + self.frame = self.GetParent() + + name = 'lane_stop' + var = next( ( var for var in self.prm.get('vars', []) if var.get('name') == name ), {} ) + v = self.pdic.get( name, var.get('v', False) ) + set_val(self.checkbox_lane_stop, v) + + def update(self): + update_func = self.gdic.get('update_func') + if update_func: + update_func(self.pdic, self.gdic, self.prm) + + def OnTrafficRedLight(self, event): + self.pdic['traffic_light'] = 0 + self.update() + + def OnTrafficGreenLight(self, event): + self.pdic['traffic_light'] = 1 + self.update() + + def OnTrafficLightRecognition(self, event): + pub = rospy.Publisher('/config/lane_stop', ConfigLaneStop, latch=True, queue_size=10) + msg = ConfigLaneStop() + v = event.GetEventObject().GetValue() + self.pdic['lane_stop'] = v + msg.manual_detection = not v + pub.publish(msg) + + def OnOk(self, event): + self.EndModal(0) + + def OnCancel(self, event): + self.EndModal(-1) class InfoBarLabel(wx.BoxSizer): - def __init__(self, parent, btm_txt=None, lmt_bar_prg=90, bar_orient=wx.VERTICAL): - wx.BoxSizer.__init__(self, orient=wx.VERTICAL) - self.lb = wx.StaticText(parent, wx.ID_ANY, '') - self.bar = BarLabel(parent, hv=bar_orient, show_lb=False) - bt = wx.StaticText(parent, wx.ID_ANY, btm_txt) if btm_txt else None - - self.Add(self.lb, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) - if bar_orient == wx.VERTICAL: - sz = self.bar.GetSize() - sz.SetWidth(20) - self.bar.SetMinSize(sz) - self.Add(self.bar, 1, wx.ALIGN_CENTER_HORIZONTAL, 0) - if bt: - self.Add(bt, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) - else: - szr = wx.BoxSizer(wx.HORIZONTAL) - if bt: - szr.Add(bt, 0, 0, 0) - szr.Add(self.bar, 1, 0, 0) - self.Add(szr, 1, wx.EXPAND, 0) - - self.lmt_bar_prg = lmt_bar_prg - - def lb_set(self, txt, col): - self.lb.SetForegroundColour(col) - self.lb.SetLabel(txt); - self.Layout() - - def bar_set(self, prg): - (col1, col2) = (wx.Colour(0,0,250), wx.Colour(0,0,128)) - if prg >= self.lmt_bar_prg: - (col1, col2) = (wx.Colour(250,0,0), wx.Colour(128,0,0)) - self.bar.set_col(col1, col2) - self.bar.set(prg) + def __init__(self, parent, btm_txt=None, lmt_bar_prg=90, bar_orient=wx.VERTICAL): + wx.BoxSizer.__init__(self, orient=wx.VERTICAL) + self.lb = wx.StaticText(parent, wx.ID_ANY, '') + self.bar = BarLabel(parent, hv=bar_orient, show_lb=False) + bt = wx.StaticText(parent, wx.ID_ANY, btm_txt) if btm_txt else None + + self.Add(self.lb, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) + if bar_orient == wx.VERTICAL: + sz = self.bar.GetSize() + sz.SetWidth(20) + self.bar.SetMinSize(sz) + self.Add(self.bar, 1, wx.ALIGN_CENTER_HORIZONTAL, 0) + if bt: + self.Add(bt, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) + else: + szr = wx.BoxSizer(wx.HORIZONTAL) + if bt: + szr.Add(bt, 0, 0, 0) + szr.Add(self.bar, 1, 0, 0) + self.Add(szr, 1, wx.EXPAND, 0) + + self.lmt_bar_prg = lmt_bar_prg + + def lb_set(self, txt, col): + self.lb.SetForegroundColour(col) + self.lb.SetLabel(txt); + self.Layout() + + def bar_set(self, prg): + (col1, col2) = (wx.Colour(0,0,250), wx.Colour(0,0,128)) + if prg >= self.lmt_bar_prg: + (col1, col2) = (wx.Colour(250,0,0), wx.Colour(128,0,0)) + self.bar.set_col(col1, col2) + self.bar.set(prg) class Checkboxes(wx.Panel): - def __init__(self, parent, item_n, lb): - wx.Panel.__init__(self, parent, wx.ID_ANY, wx.DefaultPosition, wx.DefaultSize) - self.boxes = [ wx.CheckBox(self, wx.ID_ANY, lb + str(i)) for i in range(item_n) ] - vsz = wx.BoxSizer(wx.VERTICAL) - for j in range((item_n + 7) / 8): - hsz = wx.BoxSizer(wx.HORIZONTAL) - for i in range(8): - idx = j * 8 + i - if idx < len(self.boxes): - hsz.Add(self.boxes[idx], 0, wx.LEFT, 8) - vsz.Add(hsz) - self.SetSizer(vsz) - vsz.Fit(self) - - def set(self, vs): - vs = vs if vs else [ True for box in self.boxes ] - for (box, v) in zip(self.boxes, vs): - box.SetValue(v) - - def get(self): - return [ box.GetValue() for box in self.boxes ] + def __init__(self, parent, item_n, lb): + wx.Panel.__init__(self, parent, wx.ID_ANY, wx.DefaultPosition, wx.DefaultSize) + self.boxes = [ wx.CheckBox(self, wx.ID_ANY, lb + str(i)) for i in range(item_n) ] + vsz = wx.BoxSizer(wx.VERTICAL) + for j in range((item_n + 7) / 8): + hsz = wx.BoxSizer(wx.HORIZONTAL) + for i in range(8): + idx = j * 8 + i + if idx < len(self.boxes): + hsz.Add(self.boxes[idx], 0, wx.LEFT, 8) + vsz.Add(hsz) + self.SetSizer(vsz) + vsz.Fit(self) + + def set(self, vs): + vs = vs if vs else [ True for box in self.boxes ] + for (box, v) in zip(self.boxes, vs): + box.SetValue(v) + + def get(self): + return [ box.GetValue() for box in self.boxes ] class BarLabel(wx.Panel): - def __init__(self, parent, txt='', pos=wx.DefaultPosition, size=wx.DefaultSize, style=0, hv=wx.HORIZONTAL, show_lb=True): - wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) - self.lb = wx.StaticText(self, wx.ID_ANY, '', style=style) - self.txt = txt - self.hv = hv - self.dir = wx.SOUTH if hv == wx.HORIZONTAL else wx.EAST - self.show_lb = show_lb - self.prg = -1 - - self.dflt_col1 = wx.Colour(250,250,250) - self.dflt_col2 = wx.Colour(128,128,128) - self.col1 = self.dflt_col1 - self.col2 = self.dflt_col2 - - self.Bind(wx.EVT_PAINT, self.OnPaint) - - def set(self, prg): - self.prg = prg - if self.show_lb: - self.lb.SetLabel(self.txt + str(prg) + '%' if prg >= 0 else '') - self.Refresh() - - def set_col(self, col1, col2): - self.col1 = col1 if col1 != wx.NullColour else self.dflt_col1 - self.col2 = col2 if col2 != wx.NullColour else self.dflt_col2 - - def clear(self): - self.set(-1) - - def OnPaint(self, event): - dc = wx.PaintDC(self) - (w,h) = self.GetSize() - if self.IsEnabled(): - p = (w if self.hv == wx.HORIZONTAL else h) * self.prg / 100 - rect = wx.Rect(0, 0, p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, h-p, w, p) - dc.GradientFillLinear(rect, self.col1, self.col2, self.dir) - rect = wx.Rect(p, 0, w-p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, 0, w, h-p) - dc.GradientFillLinear(rect, wx.Colour(200,200,200), wx.Colour(220,220,220), self.dir) - else: - rect = wx.Rect(0, 0, w, h) - dc.GradientFillLinear(rect, wx.Colour(250,250,250), wx.Colour(250,250,250), self.dir) + def __init__(self, parent, txt='', pos=wx.DefaultPosition, size=wx.DefaultSize, style=0, hv=wx.HORIZONTAL, show_lb=True): + wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) + self.lb = wx.StaticText(self, wx.ID_ANY, '', style=style) + self.txt = txt + self.hv = hv + self.dir = wx.SOUTH if hv == wx.HORIZONTAL else wx.EAST + self.show_lb = show_lb + self.prg = -1 + + self.dflt_col1 = wx.Colour(250,250,250) + self.dflt_col2 = wx.Colour(128,128,128) + self.col1 = self.dflt_col1 + self.col2 = self.dflt_col2 + + self.Bind(wx.EVT_PAINT, self.OnPaint) + + def set(self, prg): + self.prg = prg + if self.show_lb: + self.lb.SetLabel(self.txt + str(prg) + '%' if prg >= 0 else '') + self.Refresh() + + def set_col(self, col1, col2): + self.col1 = col1 if col1 != wx.NullColour else self.dflt_col1 + self.col2 = col2 if col2 != wx.NullColour else self.dflt_col2 + + def clear(self): + self.set(-1) + + def OnPaint(self, event): + dc = wx.PaintDC(self) + (w,h) = self.GetSize() + if self.IsEnabled(): + p = (w if self.hv == wx.HORIZONTAL else h) * self.prg / 100 + rect = wx.Rect(0, 0, p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, h-p, w, p) + dc.GradientFillLinear(rect, self.col1, self.col2, self.dir) + rect = wx.Rect(p, 0, w-p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, 0, w, h-p) + dc.GradientFillLinear(rect, wx.Colour(200,200,200), wx.Colour(220,220,220), self.dir) + else: + rect = wx.Rect(0, 0, w, h) + dc.GradientFillLinear(rect, wx.Colour(250,250,250), wx.Colour(250,250,250), self.dir) class ColorLabel(wx.Panel): - def __init__(self, parent, lst=[], pos=wx.DefaultPosition, size=wx.DefaultSize, style=0): - wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) - self.lst = lst - self.Bind(wx.EVT_PAINT, self.OnPaint) - - def set(self, lst): - self.lst = lst - self.Refresh() - - def OnPaint(self, event): - dc = wx.PaintDC(self) - dc.Clear() - - #change_font_point_by_rate(dc, 0.75) - - (x,y) = (0,0) - (_, h, _, _) = dc.GetFullTextExtent(' ') - for v in self.lst: - if type(v) is tuple and len(v) == 2: - (x,y) = v - elif type(v) is tuple and len(v) == 3: - dc.SetTextForeground(v) - elif v == '\n': - (x,y) = (0,y+h) - elif type(v) is str: - dc.DrawText(v, x, y) - (w, _, _, _) = dc.GetFullTextExtent(v) - x += w + def __init__(self, parent, lst=[], pos=wx.DefaultPosition, size=wx.DefaultSize, style=0): + wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) + self.lst = lst + self.Bind(wx.EVT_PAINT, self.OnPaint) + + def set(self, lst): + self.lst = lst + self.Refresh() + + def OnPaint(self, event): + dc = wx.PaintDC(self) + dc.Clear() + + #change_font_point_by_rate(dc, 0.75) + + (x,y) = (0,0) + (_, h, _, _) = dc.GetFullTextExtent(' ') + for v in self.lst: + if type(v) is tuple and len(v) == 2: + (x,y) = v + elif type(v) is tuple and len(v) == 3: + dc.SetTextForeground(v) + elif v == '\n': + (x,y) = (0,y+h) + elif type(v) is str: + dc.DrawText(v, x, y) + (w, _, _, _) = dc.GetFullTextExtent(v) + x += w class StrValObj: - def __init__(self, s, v): - self.s = s - self.v = v - def GetValue(self): - return self.v - def SetValue(self, v): - self.v = v + def __init__(self, s, v): + self.s = s + self.v = v + def GetValue(self): + return self.v + def SetValue(self, v): + self.v = v class MyApp(wx.App): - def OnInit(self): - wx.InitAllImageHandlers() - frame_1 = Final(None, wx.ID_ANY, "") - self.SetTopWindow(frame_1) - buttons_color_hdr_setup(frame_1) - frame_1.Show() - return 1 + def OnInit(self): + wx.InitAllImageHandlers() + frame_1 = Final(None, wx.ID_ANY, "") + self.SetTopWindow(frame_1) + buttons_color_hdr_setup(frame_1) + frame_1.Show() + return 1 def file_dialog(parent, tc, path_inf_dic={}): - path = tc.GetValue() - path = get_top(path.split(','), path) - (dn, fn) = os.path.split(path) - path_type = path_inf_dic.get('path_type') - if path_type == 'dir': - fns = path_inf_dic.get('filenames') - if type(fns) is str and fns[-5:] == '.yaml': - fns = load_yaml(fns) - if type(fns) is not list: - fns = None - path_inf_dic['filenames'] = fns - dlg = wx.DirDialog(parent, defaultPath=path) - else: - st_dic = { 'save' : wx.FD_SAVE, 'multi' : wx.FD_MULTIPLE } - dlg = wx.FileDialog(parent, defaultDir=dn, defaultFile=fn, - style=st_dic.get(path_type, wx.FD_DEFAULT_STYLE)) - ret = show_modal(dlg) - if ret == wx.ID_OK: - path = ','.join(dlg.GetPaths()) if path_type == 'multi' else dlg.GetPath() - if path_type == 'dir' and fns: - path = ','.join([ path + '/' + fn for fn in fns ]) - set_path(tc, path) - dlg.Destroy() - return ret + path = tc.GetValue() + path = get_top(path.split(','), path) + (dn, fn) = os.path.split(path) + path_type = path_inf_dic.get('path_type') + if path_type == 'dir': + fns = path_inf_dic.get('filenames') + if type(fns) is str and fns[-5:] == '.yaml': + fns = load_yaml(fns) + if type(fns) is not list: + fns = None + path_inf_dic['filenames'] = fns + dlg = wx.DirDialog(parent, defaultPath=path) + else: + st_dic = { 'save' : wx.FD_SAVE, 'multi' : wx.FD_MULTIPLE } + dlg = wx.FileDialog(parent, defaultDir=dn, defaultFile=fn, + style=st_dic.get(path_type, wx.FD_DEFAULT_STYLE)) + ret = show_modal(dlg) + if ret == wx.ID_OK: + path = ','.join(dlg.GetPaths()) if path_type == 'multi' else dlg.GetPath() + if path_type == 'dir' and fns: + path = ','.join([ path + '/' + fn for fn in fns ]) + set_path(tc, path) + dlg.Destroy() + return ret def button_color_change(btn, v=None): - if v is None and type(btn) is wx.ToggleButton: - v = btn.GetValue() - key = ( v , btn.IsEnabled() ) - dic = { (True,True):('#F9F9F8','#8B8BB9'), (True,False):('#F9F9F8','#E0E0F0') } - (fcol, bcol) = dic.get(key, (wx.NullColour, wx.NullColour)) - btn.SetForegroundColour(fcol) - btn.SetBackgroundColour(bcol) + if v is None and type(btn) is wx.ToggleButton: + v = btn.GetValue() + key = ( v , btn.IsEnabled() ) + dic = { (True,True):('#F9F9F8','#8B8BB9'), (True,False):('#F9F9F8','#E0E0F0') } + (fcol, bcol) = dic.get(key, (wx.NullColour, wx.NullColour)) + btn.SetForegroundColour(fcol) + btn.SetBackgroundColour(bcol) def OnButtonColorHdr(event): - btn = event.GetEventObject() - dic = { wx.EVT_TOGGLEBUTTON.typeId : None, - wx.EVT_LEFT_DOWN.typeId : True, - wx.EVT_LEFT_UP.typeId : False } - v = dic.get(event.GetEventType(), '?') - if v != '?': - button_color_change(btn, v) - event.Skip() + btn = event.GetEventObject() + dic = { wx.EVT_TOGGLEBUTTON.typeId : None, + wx.EVT_LEFT_DOWN.typeId : True, + wx.EVT_LEFT_UP.typeId : False } + v = dic.get(event.GetEventType(), '?') + if v != '?': + button_color_change(btn, v) + event.Skip() btn_null_bgcol = None def is_btn_null_bgcol(btn): - global btn_null_bgcol - bak = btn.GetBackgroundColour() - if btn_null_bgcol is None: - btn.SetBackgroundColour(wx.NullColour) - btn_null_bgcol = btn.GetBackgroundColour() - if bak != btn_null_bgcol: - btn.SetBackgroundColour(bak) - return bak == btn_null_bgcol + global btn_null_bgcol + bak = btn.GetBackgroundColour() + if btn_null_bgcol is None: + btn.SetBackgroundColour(wx.NullColour) + btn_null_bgcol = btn.GetBackgroundColour() + if bak != btn_null_bgcol: + btn.SetBackgroundColour(bak) + return bak == btn_null_bgcol def button_color_hdr_setup(btn): - hdr = OnButtonColorHdr - if type(btn) is wx.ToggleButton: - btn.Bind(wx.EVT_TOGGLEBUTTON, hdr) - elif type(btn) is wx.Button and is_btn_null_bgcol(btn): - btn.Bind(wx.EVT_LEFT_DOWN, hdr) - btn.Bind(wx.EVT_LEFT_UP, hdr) + hdr = OnButtonColorHdr + if type(btn) is wx.ToggleButton: + btn.Bind(wx.EVT_TOGGLEBUTTON, hdr) + elif type(btn) is wx.Button and is_btn_null_bgcol(btn): + btn.Bind(wx.EVT_LEFT_DOWN, hdr) + btn.Bind(wx.EVT_LEFT_UP, hdr) def buttons_color_hdr_setup(frm_obj): - key = 'button_' - btns = [ getattr(frm_obj, nm) for nm in dir(frm_obj) if nm[:len(key)] == key ] - for btn in btns: - button_color_hdr_setup(btn) + key = 'button_' + btns = [ getattr(frm_obj, nm) for nm in dir(frm_obj) if nm[:len(key)] == key ] + for btn in btns: + button_color_hdr_setup(btn) def show_modal(dlg): - buttons_color_hdr_setup(dlg) - return dlg.ShowModal() + buttons_color_hdr_setup(dlg) + return dlg.ShowModal() def load_yaml(filename, def_ret=None): - dir = rtmgr_src_dir() - path = dir + filename - if not os.path.isfile(path): - return def_ret - print('loading ' + filename) - f = open(dir + filename, 'r') - d = yaml.load(f) - f.close() - return d + dir = rtmgr_src_dir() + path = dir + filename + if not os.path.isfile(path): + return def_ret + print('loading ' + filename) + f = open(dir + filename, 'r') + d = yaml.load(f) + f.close() + return d def terminate_children(proc, sigint=False): - for child in psutil.Process(proc.pid).get_children(): - terminate_children(child, sigint) - terminate(child, sigint) + for child in psutil.Process(proc.pid).get_children(): + terminate_children(child, sigint) + terminate(child, sigint) def terminate(proc, sigint=False): - if sigint: - proc.send_signal(signal.SIGINT) - else: - proc.terminate() + if sigint: + proc.send_signal(signal.SIGINT) + else: + proc.terminate() def th_start(target, kwargs={}): - ev = threading.Event() - kwargs['ev'] = ev - th = threading.Thread(target=target, kwargs=kwargs) - th.daemon = True - th.start() - return (th, ev) - -def th_end((th, ev)): - ev.set() - th.join() + ev = threading.Event() + kwargs['ev'] = ev + th = threading.Thread(target=target, kwargs=kwargs) + th.daemon = True + th.start() + return (th, ev) + +def th_end(th_ev): + th, ev = th_ev + ev.set() + th.join() def que_clear(que): - with que.mutex: - que.queue.clear() + with que.mutex: + que.queue.clear() def append_tc_limit(tc, s, rm_chars=0): - if rm_chars > 0: - tc.Remove(0, rm_chars) - tc.AppendText(s) + if rm_chars > 0: + tc.Remove(0, rm_chars) + tc.AppendText(s) def cut_esc(s): - while True: - i = s.find(chr(27)) - if i < 0: - break - j = s.find('m', i) - if j < 0: - break - s = s[:i] + s[j+1:] - return s + while True: + i = s.find(chr(27)) + if i < 0: + break + j = s.find('m', i) + if j < 0: + break + s = s[:i] + s[j+1:] + return s def change_font_point_by_rate(obj, rate=1.0): - font = obj.GetFont() - pt = font.GetPointSize() - pt = int(pt * rate) - font.SetPointSize(pt) - obj.SetFont(font) + font = obj.GetFont() + pt = font.GetPointSize() + pt = int(pt * rate) + font.SetPointSize(pt) + obj.SetFont(font) def fix_link_color(obj): - t = type(obj) - if t is CT.GenericTreeItem or t is CT.CustomTreeCtrl: - obj.SetHyperTextVisitedColour(obj.GetHyperTextNewColour()) - elif t is wx.HyperlinkCtrl: - obj.SetVisitedColour(obj.GetNormalColour()) + t = type(obj) + if t is CT.GenericTreeItem or t is CT.CustomTreeCtrl: + obj.SetHyperTextVisitedColour(obj.GetHyperTextNewColour()) + elif t is wx.HyperlinkCtrl: + obj.SetVisitedColour(obj.GetNormalColour()) def get_tooltip(dic): - return dic.get('desc') + return dic.get('desc') def get_tooltips(dic): - return dic.get('descs', []) + return dic.get('descs', []) def set_tooltip(obj, dic): - set_tooltip_str(obj, get_tooltip(dic)) + set_tooltip_str(obj, get_tooltip(dic)) def set_tooltip_str(obj, s): - if s and getattr(obj, 'SetToolTipString', None): - obj.SetToolTipString(s) + if s and getattr(obj, 'SetToolTipString', None): + obj.SetToolTipString(s) def set_tooltips(obj, dic): - lst = get_tooltips(dic) - if lst and getattr(obj, 'SetItemToolTip', None): - for (ix, s) in enumerate(lst): - obj.SetItemToolTip(ix, s) + lst = get_tooltips(dic) + if lst and getattr(obj, 'SetItemToolTip', None): + for (ix, s) in enumerate(lst): + obj.SetItemToolTip(ix, s) def get_tooltip_obj(obj): - if getattr(obj, 'GetToolTip', None): - t = obj.GetToolTip() - return t.GetTip() if t else None - return None + if getattr(obj, 'GetToolTip', None): + t = obj.GetToolTip() + return t.GetTip() if t else None + return None def scaled_bitmap(bm, scale): - (w, h) = bm.GetSize() - img = wx.ImageFromBitmap(bm) - img = img.Scale(w * scale, h * scale, wx.IMAGE_QUALITY_HIGH) - return wx.BitmapFromImage(img) + (w, h) = bm.GetSize() + img = wx.ImageFromBitmap(bm) + img = img.Scale(w * scale, h * scale, wx.IMAGE_QUALITY_HIGH) + return wx.BitmapFromImage(img) def sizer_wrap(add_objs, orient=wx.VERTICAL, prop=0, flag=0, border=0, parent=None): - szr = wx.BoxSizer(orient) - for obj in add_objs: - szr.Add(obj, prop, flag, border) - if parent: - parent.SetSizer(szr) - return szr + szr = wx.BoxSizer(orient) + for obj in add_objs: + szr.Add(obj, prop, flag, border) + if parent: + parent.SetSizer(szr) + return szr def static_box_sizer(parent, s, orient=wx.VERTICAL): - sb = wx.StaticBox(parent, wx.ID_ANY, s) - sb.Lower() - return wx.StaticBoxSizer(sb, orient) + sb = wx.StaticBox(parent, wx.ID_ANY, s) + sb.Lower() + return wx.StaticBoxSizer(sb, orient) def wx_flag_get(flags): - dic = { 'top' : wx.TOP, 'bottom' : wx.BOTTOM, 'left' : wx.LEFT, 'right' : wx.RIGHT, - 'all' : wx.ALL, 'expand' : wx.EXPAND, 'fixed_minsize' : wx.FIXED_MINSIZE, - 'center_v' : wx.ALIGN_CENTER_VERTICAL, 'center_h' : wx.ALIGN_CENTER_HORIZONTAL, - 'passwd' : wx.TE_PASSWORD } - lst = [ dic.get(f) for f in flags if f in dic ] - return reduce(lambda a,b : a+b, [0] + lst) + dic = { 'top' : wx.TOP, 'bottom' : wx.BOTTOM, 'left' : wx.LEFT, 'right' : wx.RIGHT, + 'all' : wx.ALL, 'expand' : wx.EXPAND, 'fixed_minsize' : wx.FIXED_MINSIZE, + 'center_v' : wx.ALIGN_CENTER_VERTICAL, 'center_h' : wx.ALIGN_CENTER_HORIZONTAL, + 'passwd' : wx.TE_PASSWORD } + lst = [ dic.get(f) for f in flags if f in dic ] + return reduce(lambda a,b : a+b, [0] + lst) def msg_path_to_obj_attr(msg, path): - lst = path.split('.') - obj = msg - for attr in lst[:-1]: - obj = getattr(obj, attr, None) - return (obj, lst[-1]) + lst = path.split('.') + obj = msg + for attr in lst[:-1]: + obj = getattr(obj, attr, None) + return (obj, lst[-1]) def str_to_rosval(s, type_str, def_ret=None): - cvt_dic = { - 'int8':int , 'int16':int , 'int32':int , - 'uint8':int , 'uint16':int , 'uint32':int , - 'int64':long , 'uint64':long, - 'float32':float, 'float64':float, - } - t = cvt_dic.get(type_str) - s = s.replace(',','.') if t is float and type(s) is str else s - return t(s) if t else def_ret + cvt_dic = { + 'int8':int , 'int16':int , 'int32':int , + 'uint8':int , 'uint16':int , 'uint32':int , + 'int64':long , 'uint64':long, + 'float32':float, 'float64':float, + } + t = cvt_dic.get(type_str) + s = s.replace(',','.') if t is float and type(s) is str else s + return t(s) if t else def_ret def str_to_float(s): - return float( s.replace(',','.') ) + return float( s.replace(',','.') ) def set_path(tc, v): - tc.SetValue(v) - tc.SetInsertionPointEnd() + tc.SetValue(v) + tc.SetInsertionPointEnd() def set_val(obj, v): - func = getattr(obj, 'SetValue', getattr(obj, 'Check', None)) - if func: - func(v) - obj_refresh(obj) - if type(obj) is wx.ToggleButton: - button_color_change(obj) + func = getattr(obj, 'SetValue', getattr(obj, 'Check', None)) + if func: + func(v) + obj_refresh(obj) + if type(obj) is wx.ToggleButton: + button_color_change(obj) def enables_set(obj, k, en): - d = attr_getset(obj, 'enabLes', {}) - d[k] = en - d['last_key'] = k - obj.Enable( all( d.values() ) ) - if isinstance(obj, wx.HyperlinkCtrl): - if not hasattr(obj, 'coLor'): - obj.coLor = { True:obj.GetNormalColour(), False:'#808080' } - c = obj.coLor.get(obj.IsEnabled()) - obj.SetNormalColour(c) - obj.SetVisitedColour(c) + d = attr_getset(obj, 'enabLes', {}) + d[k] = en + d['last_key'] = k + obj.Enable( all( d.values() ) ) + if isinstance(obj, wx.HyperlinkCtrl): + if not hasattr(obj, 'coLor'): + obj.coLor = { True:obj.GetNormalColour(), False:'#808080' } + c = obj.coLor.get(obj.IsEnabled()) + obj.SetNormalColour(c) + obj.SetVisitedColour(c) def enables_get(obj, k, def_ret=None): - return attr_getset(obj, 'enabLes', {}).get(k, def_ret) + return attr_getset(obj, 'enabLes', {}).get(k, def_ret) def enables_get_last(obj): - k = enables_get(obj, 'last_key') - return (k, enables_get(obj, k)) + k = enables_get(obj, 'last_key') + return (k, enables_get(obj, k)) def obj_refresh(obj): - if type(obj) is CT.GenericTreeItem: - while obj.GetParent(): - obj = obj.GetParent() - tree = obj.GetData() - tree.Refresh() + if type(obj) is CT.GenericTreeItem: + while obj.GetParent(): + obj = obj.GetParent() + tree = obj.GetData() + tree.Refresh() # dic_list util (push, pop, get) def dic_list_push(dic, key, v): - dic_getset(dic, key, []).append(v) + dic_getset(dic, key, []).append(v) def dic_list_pop(dic, key): - dic.get(key, [None]).pop() + dic.get(key, [None]).pop() def dic_list_get(dic, key, def_ret=None): - return dic.get(key, [def_ret])[-1] + return dic.get(key, [def_ret])[-1] def bak_stk_push(dic, key): - if key in dic: - k = key + '_bak_str' - dic_getset(dic, k, []).append( dic.get(key) ) + if key in dic: + k = key + '_bak_str' + dic_getset(dic, k, []).append( dic.get(key) ) def bak_stk_pop(dic, key): - k = key + '_bak_str' - stk = dic.get(k, []) - if len(stk) > 0: - dic[key] = stk.pop() - else: - del dic[key] + k = key + '_bak_str' + stk = dic.get(k, []) + if len(stk) > 0: + dic[key] = stk.pop() + else: + del dic[key] def bak_stk_set(dic, key, v): - bak_str_push(dic, key) - dic[key] = v + bak_str_push(dic, key) + dic[key] = v def attr_getset(obj, name, def_ret): - if not hasattr(obj, name): - setattr(obj, name, def_ret) - return getattr(obj, name) + if not hasattr(obj, name): + setattr(obj, name, def_ret) + return getattr(obj, name) def dic_getset(dic, key, def_ret): - if key not in dic: - dic[key] = def_ret - return dic.get(key) + if key not in dic: + dic[key] = def_ret + return dic.get(key) def lst_append_once(lst, v): - exist = v in lst - if not exist: - lst.append(v) - return exist + exist = v in lst + if not exist: + lst.append(v) + return exist def lst_remove_once(lst, v): - exist = v in lst - if exist: - lst.remove(v) - return exist + exist = v in lst + if exist: + lst.remove(v) + return exist def get_top(lst, def_ret=None): - return lst[0] if len(lst) > 0 else def_ret + return lst[0] if len(lst) > 0 else def_ret def adjust_num_str(s): - if '.' in s: - while s[-1] == '0': - s = s[:-1] - if s[-1] == '.': - s = s[:-1] - return s + if '.' in s: + while s[-1] == '0': + s = s[:-1] + if s[-1] == '.': + s = s[:-1] + return s def rtmgr_src_dir(): - return os.path.abspath(os.path.dirname(__file__)) + "/" + return os.path.abspath(os.path.dirname(__file__)) + "/" def path_expand_cmd(path): - lst = path.split('/') - s = lst[0] - if s[:2] == '$(' and s[-1] == ')': - cmd = s[2:-1].split(' ') - lst[0] = subprocess.check_output(cmd).strip() - path = '/'.join(lst) - return path + lst = path.split('/') + s = lst[0] + if s[:2] == '$(' and s[-1] == ')': + cmd = s[2:-1].split(' ') + lst[0] = subprocess.check_output(cmd).strip() + path = '/'.join(lst) + return path def eval_if_str(self, v): - return eval(v) if type(v) is str else v + return eval(v) if type(v) is str else v def dic_eval_if_str(self, dic, key, def_ret=None): - return eval_if_str( self, dic.get(key, def_ret) ) + return eval_if_str( self, dic.get(key, def_ret) ) def prn_dict(dic): - for (k,v) in dic.items(): - print (k, ':', v) + for (k,v) in dic.items(): + print(k, ':', v) def send_to_proc_manager(order): - sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM) + sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM) - try: - sock.connect(PROC_MANAGER_SOCK) - except socket.error: - print('Failed connect to {}'.format(PROC_MANAGER_SOCK)) - return -1 + try: + sock.connect(PROC_MANAGER_SOCK) + except socket.error: + print('Failed connect to {}'.format(PROC_MANAGER_SOCK)) + return -1 - sock.send(yaml.dump(order)) - ret = sock.recv(1024) - sock.close() - return int(ret) == 0 + sock.send(yaml.dump(order)) + ret = sock.recv(1024) + sock.close() + return int(ret) == 0 def set_process_nice(proc, value): - order = { - "name": "nice", - "pid": proc.pid, - "nice": value - } - return send_to_proc_manager(order) + order = { + "name": "nice", + "pid": proc.pid, + "nice": value + } + return send_to_proc_manager(order) def set_process_cpu_affinity(proc, cpus): - order = { - "name": "cpu_affinity", - "pid": proc.pid, - "cpus": cpus, - } - return send_to_proc_manager(order) + order = { + "name": "cpu_affinity", + "pid": proc.pid, + "cpus": cpus, + } + return send_to_proc_manager(order) def shutdown_proc_manager(): - order = { - "name": "shutdown", - } - return send_to_proc_manager(order) + order = { + "name": "shutdown", + } + return send_to_proc_manager(order) def set_scheduling_policy(proc, policy, priority): - order = { - "name": "scheduling_policy", - "pid": proc.pid, - "policy": policy, - "priority": priority, - } - return send_to_proc_manager(order) + order = { + "name": "scheduling_policy", + "pid": proc.pid, + "policy": policy, + "priority": priority, + } + return send_to_proc_manager(order) def get_cpu_count(): - try: - return psutil.NUM_CPUS - except AttributeError: - return psutil.cpu_count() + try: + return psutil.NUM_CPUS + except AttributeError: + return psutil.cpu_count() class DetailDialog(wx.Dialog): @@ -3486,15 +3488,15 @@ def __init__(self, parent): self.Bind(wx.EVT_TEXT_ENTER, self.update_path, self.tc2) ref = wx.Button(panel, wx.ID_ANY, 'Ref') - self.Bind(wx.EVT_BUTTON, self.open_dialog, ref) - ref.SetMinSize((40,29)) + self.Bind(wx.EVT_BUTTON, self.open_dialog, ref) + ref.SetMinSize((40,29)) self.dir = "" sb = wx.StaticBox(panel, wx.ID_ANY, "Spam, spam, spam") sb.SetLabel("Lidar's Calibration File") layout1 = wx.StaticBoxSizer(sb, wx.HORIZONTAL) layout1.Add(self.tc2, 0, wx.ALL, 4) - layout1.Add(ref, 0, wx.ALL, 4) + layout1.Add(ref, 0, wx.ALL, 4) layout.Add(layout1) button = wx.Button(panel, wx.ID_ANY, "OK") @@ -3580,7 +3582,7 @@ def button_close_Cancel(self, event): if __name__ == "__main__": - gettext.install("app") + gettext.install("app") - app = MyApp(0) - app.MainLoop() + app = MyApp(0) + app.MainLoop() diff --git a/utilities/data_preprocessor/scripts/get_Depth.py b/utilities/data_preprocessor/scripts/get_Depth.py index 3c1d598115f..88b04743569 100755 --- a/utilities/data_preprocessor/scripts/get_Depth.py +++ b/utilities/data_preprocessor/scripts/get_Depth.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import rospy import numpy as np @@ -28,7 +28,7 @@ def __init__(self, calibration_path, save_path): if 'ImageSize' in line: width=int(line[line.index('[')+1:line.index(',')]) height=int(line[line.index(',')+1:line.index(']')]) - print "Image Size: [",width,",",height,"]" + print("Image Size: [",width,",",height,"]") self.width = width self.height = height self.index = 0 @@ -98,7 +98,7 @@ def callback(self): d_mat[i_y,i_x]=i_z t1 = time.time() - print "Projection Time: ", t1-t0 + print("Projection Time: ", t1-t0) self.to_distance_image(d_mat,curr_image) self.in_callback = False @@ -108,7 +108,7 @@ def to_distance_image(self, img_mat,curr_image): self.index += 1 h = self.height w = self.width - print img_mat[np.isnan(img_mat)].shape, "nan" + print(img_mat[np.isnan(img_mat)].shape, "nan") # print(np.nanmax(img_mat)) # print(np.nanmin(img_mat)) @@ -135,18 +135,18 @@ def to_distance_image(self, img_mat,curr_image): # sub_mat.fill(avg) # new_mat[y:y+self.sub_mat_size*self.mat_ratio,x:x+self.sub_mat_size]=sub_mat # t1 = time.time() - # print "Interpolation time: ", t1-t0 + # print("Interpolation time: ", t1-t0) new_mat[np.isnan(new_mat)] = 0 - print new_mat.max() + print(new_mat.max()) d_img = PIL.Image.fromarray(plt.cm.jet_r(new_mat, bytes=True)) # rgba_img=PIL.Image.fromarray(curr_image).convert("RGBA") # overlay_img = PIL.Image.blend(rgba_img,d_img, 0.5) - # print new_mat.max(), new_mat.min() - # print plt.cm.jet_r(new_mat, bytes=True).max(), plt.cm.jet_r(new_mat, bytes=True).min() + # print(new_mat.max(), new_mat.min()) + # print(plt.cm.jet_r(new_mat, bytes=True).max(), plt.cm.jet_r(new_mat, bytes=True).min()) timestamp = time.time() d_img.save(self.save_path + '/depth_img_%08d.jpg' % self.index) @@ -187,7 +187,7 @@ def pc2_to_depth_image(): calibration_path = sys.argv[2] image = sys.argv[3] pointcloud = sys.argv[4] - except Exception, e: + except Exception as e: sys.exit("Please specify the save path. Example: rosbag_data_extract_unsync.py /media/0/output/") dc = DepthConverter(calibration_path, save_path) diff --git a/utilities/data_preprocessor/scripts/get_ImageTopic.py b/utilities/data_preprocessor/scripts/get_ImageTopic.py index 0d78d145540..ef1805400ec 100755 --- a/utilities/data_preprocessor/scripts/get_ImageTopic.py +++ b/utilities/data_preprocessor/scripts/get_ImageTopic.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import os @@ -50,7 +50,7 @@ def rosbag_data_extract_sample(): topic = sys.argv[2] output_type = "image" bagfile = "/home/katou01/.autoware/autoware-201701171120.bag" - except Exception, e: + except Exception as e: sys.exit("Please specify the save path. Example: rosbag_data_extract_unsync.py /media/0/output/") image_saver = ImageSaver(save_path, output_type, bagfile, topic) diff --git a/utilities/data_preprocessor/scripts/get_PCD.py b/utilities/data_preprocessor/scripts/get_PCD.py index ace6d5c06a3..0a9630a3dc5 100755 --- a/utilities/data_preprocessor/scripts/get_PCD.py +++ b/utilities/data_preprocessor/scripts/get_PCD.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import os import rospy @@ -24,7 +24,7 @@ def rosbag_data_extract_sample(): try: save_path = sys.argv[1] topic = sys.argv[2] - except Exception, e: + except Exception as e: #sys.exit("Please specify the save path. Example: rosbag_data_extract_unsync.py /media/0/output/") save_path = './sample' diff --git a/utilities/data_preprocessor/scripts/get_rosbaginfo.py b/utilities/data_preprocessor/scripts/get_rosbaginfo.py index dc9ff9fe443..1feac770268 100644 --- a/utilities/data_preprocessor/scripts/get_rosbaginfo.py +++ b/utilities/data_preprocessor/scripts/get_rosbaginfo.py @@ -32,7 +32,7 @@ def get_baginfo(file_path): if __name__ == '__main__': try: file_path = sys.argv[1] - except Exception, e: + except Exception as e: sys.exit("Please specify bag file. Example: get_rosbaginfo ex.bag") else: rostopic_list = get_rosbagtopics(file_path) diff --git a/utilities/data_preprocessor/scripts/insidedesign.py b/utilities/data_preprocessor/scripts/insidedesign.py index d2dd6f4bd72..e4f2a78ce6e 100644 --- a/utilities/data_preprocessor/scripts/insidedesign.py +++ b/utilities/data_preprocessor/scripts/insidedesign.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: UTF-8 -*- import wx @@ -186,39 +186,39 @@ def _do_layout(self): self.Layout() def OnLaunchKill(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLaunchKill' not implemented!" + print("Event handler 'OnLaunchKill' not implemented!") event.Skip() def OnSetupLocalizer(self, event): # wxGlade: MyFrame. - print "Event handler 'OnSetupLocalizer' not implemented!" + print("Event handler 'OnSetupLocalizer' not implemented!") event.Skip() def OnCalibrationPublisher(self, event): # wxGlade: MyFrame. - print "Event handler 'OnCalibrationPublisher' not implemented!" + print("Event handler 'OnCalibrationPublisher' not implemented!") event.Skip() def OnLamp(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLamp' not implemented!" + print("Event handler 'OnLamp' not implemented!") event.Skip() def OnIndi(self, event): # wxGlade: MyFrame. - print "Event handler 'OnIndi' not implemented!" + print("Event handler 'OnIndi' not implemented!") event.Skip() def OnGear(self, event): # wxGlade: MyFrame. - print "Event handler 'OnGear' not implemented!" + print("Event handler 'OnGear' not implemented!") event.Skip() def OnQuery(self, event): # wxGlade: MyFrame. - print "Event handler 'OnQuery' not implemented!" + print("Event handler 'OnQuery' not implemented!") event.Skip() def OnROSbagPlay(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagPlay' not implemented!" + print("Event handler 'OnROSbagPlay' not implemented!") event.Skip() def OnROSbagPlay2(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagPlay2' not implemented!" + print("Event handler 'OnROSbagPlay2' not implemented!") event.Skip() def OnRviz(self, event): @@ -226,15 +226,15 @@ def OnRviz(self, event): event.Skip() def OnFtrace(self, event): # wxGlade: MyFrame. - print "Event handler 'OnFtrace' not implemented!" + print("Event handler 'OnFtrace' not implemented!") event.Skip() def OnEcho(self, event): # wxGlade: MyFrame. - print "Event handler 'OnEcho' not implemented!" + print("Event handler 'OnEcho' not implemented!") event.Skip() def OnRefreshTopics(self, event): # wxGlade: MyFrame. - print "Event handler 'OnRefreshTopics' not implemented!" + print("Event handler 'OnRefreshTopics' not implemented!") event.Skip() def OnGetConfirmTopics(self, event): @@ -308,19 +308,19 @@ def __do_layout(self): # end wxGlade def OnRef(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRef' not implemented!" + print("Event handler 'OnRef' not implemented!") event.Skip() def OnStart(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStart' not implemented!" + print("Event handler 'OnStart' not implemented!") event.Skip() def OnStop(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStop' not implemented!" + print("Event handler 'OnStop' not implemented!") event.Skip() def OnRefresh(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRefresh' not implemented!" + print("Event handler 'OnRefresh' not implemented!") event.Skip() # end of class MyDialogCarPedestrian diff --git a/utilities/data_preprocessor/scripts/rosbag_data_extract_sample.py b/utilities/data_preprocessor/scripts/rosbag_data_extract_sample.py index 4d538ccdd95..e27a27da9c2 100755 --- a/utilities/data_preprocessor/scripts/rosbag_data_extract_sample.py +++ b/utilities/data_preprocessor/scripts/rosbag_data_extract_sample.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import os import rospy @@ -32,7 +32,7 @@ def rosbag_data_extract_sample(): global save_path try: save_path = sys.argv[1] - except Exception, e: + except Exception as e: #sys.exit("Please specify the save path. Example: rosbag_data_extract_unsync.py /media/0/output/") save_path = './sample' diff --git a/utilities/data_preprocessor/scripts/rtmgr.py b/utilities/data_preprocessor/scripts/rtmgr.py index 0f9738f4cbe..343c0de3bf4 100755 --- a/utilities/data_preprocessor/scripts/rtmgr.py +++ b/utilities/data_preprocessor/scripts/rtmgr.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: UTF-8 -*- # # generated by wxGlade 0.6.8 on Fri Sep 2 19:08:14 2016 @@ -437,55 +437,55 @@ def __do_layout(self): # # end wxGlade def OnLaunchKill(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLaunchKill' not implemented!" + print("Event handler 'OnLaunchKill' not implemented!") event.Skip() def OnAutoPilot(self, event): # wxGlade: MyFrame. - print "Event handler 'OnAutoPilot' not implemented!" + print("Event handler 'OnAutoPilot' not implemented!") event.Skip() def OnROSbagRecord(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagRecord' not implemented!" + print("Event handler 'OnROSbagRecord' not implemented!") event.Skip() def OnSetupLocalizer(self, event): # wxGlade: MyFrame. - print "Event handler 'OnSetupLocalizer' not implemented!" + print("Event handler 'OnSetupLocalizer' not implemented!") event.Skip() def OnCalibrationPublisher(self, event): # wxGlade: MyFrame. - print "Event handler 'OnCalibrationPublisher' not implemented!" + print("Event handler 'OnCalibrationPublisher' not implemented!") event.Skip() def OnLamp(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLamp' not implemented!" + print("Event handler 'OnLamp' not implemented!") event.Skip() def OnIndi(self, event): # wxGlade: MyFrame. - print "Event handler 'OnIndi' not implemented!" + print("Event handler 'OnIndi' not implemented!") event.Skip() def OnGear(self, event): # wxGlade: MyFrame. - print "Event handler 'OnGear' not implemented!" + print("Event handler 'OnGear' not implemented!") event.Skip() def OnQuery(self, event): # wxGlade: MyFrame. - print "Event handler 'OnQuery' not implemented!" + print("Event handler 'OnQuery' not implemented!") event.Skip() def OnROSbagPlay(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagPlay' not implemented!" + print("Event handler 'OnROSbagPlay' not implemented!") event.Skip() def OnFtrace(self, event): # wxGlade: MyFrame. - print "Event handler 'OnFtrace' not implemented!" + print("Event handler 'OnFtrace' not implemented!") event.Skip() def OnEcho(self, event): # wxGlade: MyFrame. - print "Event handler 'OnEcho' not implemented!" + print("Event handler 'OnEcho' not implemented!") event.Skip() def OnRefreshTopics(self, event): # wxGlade: MyFrame. - print "Event handler 'OnRefreshTopics' not implemented!" + print("Event handler 'OnRefreshTopics' not implemented!") event.Skip() # end of class MyFrame @@ -530,11 +530,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialog. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialog. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialog @@ -577,11 +577,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialogParam. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialogParam. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialogParam @@ -649,19 +649,19 @@ def __do_layout(self): # end wxGlade def OnRef(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRef' not implemented!" + print("Event handler 'OnRef' not implemented!") event.Skip() def OnStart(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStart' not implemented!" + print("Event handler 'OnStart' not implemented!") event.Skip() def OnStop(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStop' not implemented!" + print("Event handler 'OnStop' not implemented!") event.Skip() def OnRefresh(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRefresh' not implemented!" + print("Event handler 'OnRefresh' not implemented!") event.Skip() # end of class MyDialogROSbagRecord @@ -752,23 +752,23 @@ def __do_layout(self): # end wxGlade def OnTrafficRedLight(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficRedLight' not implemented!" + print("Event handler 'OnTrafficRedLight' not implemented!") event.Skip() def OnTrafficGreenLight(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficGreenLight' not implemented!" + print("Event handler 'OnTrafficGreenLight' not implemented!") event.Skip() def OnTrafficLightRecognition(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficLightRecognition' not implemented!" + print("Event handler 'OnTrafficLightRecognition' not implemented!") event.Skip() def OnOk(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialogLaneStop @@ -831,19 +831,19 @@ def __do_layout(self): # end wxGlade def OnRef(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnRef' not implemented!" + print("Event handler 'OnRef' not implemented!") event.Skip() def OnRadio(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnRadio' not implemented!" + print("Event handler 'OnRadio' not implemented!") event.Skip() def OnPcdOutput(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnPcdOutput' not implemented!" + print("Event handler 'OnPcdOutput' not implemented!") event.Skip() def OnOk(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() # end of class MyDialogNDTMapping @@ -891,11 +891,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialogDPM. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnLink(self, event): # wxGlade: MyDialogDPM. - print "Event handler 'OnLink' not implemented!" + print("Event handler 'OnLink' not implemented!") event.Skip() # end of class MyDialogDPM @@ -931,7 +931,7 @@ def __do_layout(self): # end wxGlade def OnLink(self, event): # wxGlade: MyDialogCarPedestrian. - print "Event handler 'OnLink' not implemented!" + print("Event handler 'OnLink' not implemented!") event.Skip() # end of class MyDialogCarPedestrian diff --git a/utilities/graph_tools/scripts/yaml2dot.py b/utilities/graph_tools/scripts/yaml2dot.py index 8a4343cf681..8189a9c32f3 100755 --- a/utilities/graph_tools/scripts/yaml2dot.py +++ b/utilities/graph_tools/scripts/yaml2dot.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 #-*- coding: utf-8 -*- import sys @@ -144,9 +144,9 @@ def is_one_leaf(topic, topics): graph0.add_edge(sub, n0, lhead=cname) # output - print "# output", args.output - print "# format", args.format + print("# output", args.output) + print("# format", args.format) graph0.draw(path=args.output, format=args.format, prog='dot') - #print "## ", reduce(lambda a,b: a + "\n### " + b, sorted(graph.nodes())) - print "# total file#=%d node#=%d topic#=%d" % \ - (graph_nr, node_nr, len(set(reduce(lambda m,n:m.keys()+n.keys(), topics)))) + #print("## ", reduce(lambda a,b: a + "\n### " + b, sorted(graph.nodes()))) + print("# total file#=%d node#=%d topic#=%d" % \ + (graph_nr, node_nr, len(set(reduce(lambda m,n:m.keys()+n.keys(), topics))))) diff --git a/utilities/kitti_box_publisher/scripts/kitti_box_publisher.py b/utilities/kitti_box_publisher/scripts/kitti_box_publisher.py index ebdcf7d75a2..d023b900eb1 100755 --- a/utilities/kitti_box_publisher/scripts/kitti_box_publisher.py +++ b/utilities/kitti_box_publisher/scripts/kitti_box_publisher.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import glob @@ -236,7 +236,7 @@ def run(): pub_points_clusters = rospy.Publisher('points_cluster', PointCloud2, queue_size=1) #projection_publisher = rospy.Publisher('projection_matrix', projection_matrix, queue_size=1, latch=True) #rospy.Subscriber("/kitti_player/hdl64e", PointCloud2, callback) - rospy.Subscriber("/points_raw", PointCloud2, callback) + rospy.Subscriber("/points_raw", PointCloud2, callback) rospy.spin() @@ -250,6 +250,6 @@ def run(): run() else : - print "[Usage] image.py tracklet_labels.xml" + print("[Usage] image.py tracklet_labels.xml") diff --git a/utilities/kitti_player/cfg/kitti_player.cfg b/utilities/kitti_player/cfg/kitti_player.cfg index adfd8fd38c8..da1bcb29b25 100755 --- a/utilities/kitti_player/cfg/kitti_player.cfg +++ b/utilities/kitti_player/cfg/kitti_player.cfg @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 PACKAGE = "kitti_player" from dynamic_reconfigure.parameter_generator_catkin import * diff --git a/utilities/kitti_player/src/kitti_player.cpp b/utilities/kitti_player/src/kitti_player.cpp index f3941ed6817..c4a8a0fa2fc 100644 --- a/utilities/kitti_player/src/kitti_player.cpp +++ b/utilities/kitti_player/src/kitti_player.cpp @@ -37,6 +37,8 @@ #include #include #include +#include +#include #include #include #include diff --git a/utilities/lanelet_aisan_converter/lib/lanelet2aisan_converter/lanelet2aisan_converter.cpp b/utilities/lanelet_aisan_converter/lib/lanelet2aisan_converter/lanelet2aisan_converter.cpp index 3eb1d29edc8..03a0296dd8c 100644 --- a/utilities/lanelet_aisan_converter/lib/lanelet2aisan_converter/lanelet2aisan_converter.cpp +++ b/utilities/lanelet_aisan_converter/lib/lanelet2aisan_converter/lanelet2aisan_converter.cpp @@ -17,7 +17,7 @@ */ #include "lanelet_aisan_converter/lanelet2aisan_converter/lanelet2aisan_converter.h" - +#include #include "lanelet_aisan_converter/lanelet_helper/lanelet_helper.h" namespace lanelet2aisan_converter diff --git a/utilities/log_tools/CMakeLists.txt b/utilities/log_tools/CMakeLists.txt index 301e2f41a18..01c064469ce 100644 --- a/utilities/log_tools/CMakeLists.txt +++ b/utilities/log_tools/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(log_tools) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(autoware_build_flags REQUIRED) @@ -15,4 +15,4 @@ catkin_install_python(PROGRAMS scripts/autologger/common.py scripts/autologger/recorder.py scripts/autologger/server.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) \ No newline at end of file + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/utilities/log_tools/scripts/autologger/client.py b/utilities/log_tools/scripts/autologger/client.py index 023d6c553f4..d2a116fd4d4 100755 --- a/utilities/log_tools/scripts/autologger/client.py +++ b/utilities/log_tools/scripts/autologger/client.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- import os, shutil, time, glob diff --git a/utilities/log_tools/scripts/autologger/common.py b/utilities/log_tools/scripts/autologger/common.py index 41232643d49..4b2d7e1eddc 100644 --- a/utilities/log_tools/scripts/autologger/common.py +++ b/utilities/log_tools/scripts/autologger/common.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- import os, sys, datetime, hashlib diff --git a/utilities/log_tools/scripts/autologger/recorder.py b/utilities/log_tools/scripts/autologger/recorder.py index 25095ca99e4..999d7c61840 100755 --- a/utilities/log_tools/scripts/autologger/recorder.py +++ b/utilities/log_tools/scripts/autologger/recorder.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- import time, signal, argparse diff --git a/utilities/log_tools/scripts/autologger/server.py b/utilities/log_tools/scripts/autologger/server.py index dca6324ebbc..cba5465eb2e 100755 --- a/utilities/log_tools/scripts/autologger/server.py +++ b/utilities/log_tools/scripts/autologger/server.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- from flask import Flask, request, json diff --git a/utilities/map_tf_generator/CMakeLists.txt b/utilities/map_tf_generator/CMakeLists.txt index 6568433e1ae..d4584e5fbc6 100644 --- a/utilities/map_tf_generator/CMakeLists.txt +++ b/utilities/map_tf_generator/CMakeLists.txt @@ -1,8 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(map_tf_generator) -## Compile as C++11, supported in ROS Kinetic and newer -# add_compile_options(-std=c++11) +## Compile as C++14, supported in ROS Noetic and newer +# add_compile_options(-std=c++14) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) @@ -53,4 +53,4 @@ install(TARGETS map_tf_generator install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) \ No newline at end of file + PATTERN ".svn" EXCLUDE) diff --git a/utilities/marker_downsampler/scripts/app.py b/utilities/marker_downsampler/scripts/app.py index 5423a3232ed..c8ec163c188 100755 --- a/utilities/marker_downsampler/scripts/app.py +++ b/utilities/marker_downsampler/scripts/app.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # coding: utf-8 import rospy diff --git a/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_pose_receiver.py b/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_pose_receiver.py index a1e718be8b4..c87307933c2 100644 --- a/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_pose_receiver.py +++ b/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_pose_receiver.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: utf-8 -*- import os diff --git a/utilities/pc2_downsampler/scripts/app.py b/utilities/pc2_downsampler/scripts/app.py index a4da55fa145..2f5bfa1f6cd 100755 --- a/utilities/pc2_downsampler/scripts/app.py +++ b/utilities/pc2_downsampler/scripts/app.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # coding: utf-8 import rospy diff --git a/utilities/runtime_manager/scripts/ftrace.py b/utilities/runtime_manager/scripts/ftrace.py index 16aaa1679f8..14d89f15045 100755 --- a/utilities/runtime_manager/scripts/ftrace.py +++ b/utilities/runtime_manager/scripts/ftrace.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 #-*- coding: utf-8 -*- import wx @@ -157,7 +157,7 @@ def OnUpdateCont(self, event): try: self.sock.connect("/tmp/autoware_proc_manager") except socket.error: - print "ERROR:[OnUpdateCont-01] cannot connect to proc_manager" + print("ERROR:[OnUpdateCont-01] cannot connect to proc_manager") return try: @@ -166,7 +166,7 @@ def OnUpdateCont(self, event): except socket.error: self.sock.close() self.sock = None - print "ERROR:[OnUpdateCont-02] cannot send to proc_manager" + print("ERROR:[OnUpdateCont-02] cannot send to proc_manager") return # start ftrace self.sbtn.SetBackgroundColour("#CCFFCC") @@ -318,7 +318,7 @@ def getROSNodes(self): try: nodenames = rosnode.get_node_names(None) except Exception as inst: - print "ERROR:[getROSNodes-01] ", inst + print("ERROR:[getROSNodes-01] ", inst) return nodes for nodename in nodenames: diff --git a/utilities/runtime_manager/scripts/proc_manager.py b/utilities/runtime_manager/scripts/proc_manager.py index 0089b66cb20..a96aeee50cc 100644 --- a/utilities/runtime_manager/scripts/proc_manager.py +++ b/utilities/runtime_manager/scripts/proc_manager.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -#!/usr/bin/env python +#!/usr/bin/env python3 import os import sys @@ -44,7 +44,7 @@ def __init__(self): self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) self.sock.bind(SOCK_PATH) self.sock.listen(10) - os.chmod(SOCK_PATH, 0777) + os.chmod(SOCK_PATH, 0o777) def set_nice(self, pid, value): try: @@ -161,7 +161,7 @@ def get_ftrace(self, sec, pids): self._set_sched_switch(False) self._ftrace(0) et = time.time() - st # for *debug* - print "* ftrace", et, "sec" # for *debug* + print("* ftrace", et, "sec") # for *debug* return ret def get_ftrace_cont(self, conn, interval, pids): @@ -199,7 +199,7 @@ def get_ftrace_cont(self, conn, interval, pids): while slen < len(dat): slen += conn.send(dat[slen:]) except socket.error: - print "ftrace disconnected" + print("ftrace disconnected") break f.close() self._set_ftrace(False) @@ -245,16 +245,16 @@ def run(self): #dat = yaml.dump(ret) ## too slow! dat = pickle.dumps(ret) tt = time.time() - st # for *debug* - print "** dump", tt, "sec" + print("** dump", tt, "sec") slen = 0 try: while slen < len(dat): slen += conn.send(dat[slen:]) except socket.error: - print 'socket failed' + print('socket failed') tt = time.time() - st # for *debug* - print "** sent", tt, "sec, size", len(dat) - #print "** md5", hashlib.md5(dat).hexdigest() + print("** sent", tt, "sec, size", len(dat)) + #print("** md5", hashlib.md5(dat).hexdigest()) conn.close() def cap_last_cap(): diff --git a/utilities/runtime_manager/scripts/rtmgr.py b/utilities/runtime_manager/scripts/rtmgr.py index 64354971a60..829a3e2cb37 100755 --- a/utilities/runtime_manager/scripts/rtmgr.py +++ b/utilities/runtime_manager/scripts/rtmgr.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # -*- coding: UTF-8 -*- # # generated by wxGlade 0.7.1 on Thu Dec 20 11:31:50 2018 @@ -858,59 +858,59 @@ def __do_layout(self): # end wxGlade def OnLaunchKill(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLaunchKill' not implemented!" + print("Event handler 'OnLaunchKill' not implemented!") event.Skip() def OnAutoPilot(self, event): # wxGlade: MyFrame. - print "Event handler 'OnAutoPilot' not implemented!" + print("Event handler 'OnAutoPilot' not implemented!") event.Skip() def OnROSbagRecord(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagRecord' not implemented!" + print("Event handler 'OnROSbagRecord' not implemented!") event.Skip() def OnSetupLocalizer(self, event): # wxGlade: MyFrame. - print "Event handler 'OnSetupLocalizer' not implemented!" + print("Event handler 'OnSetupLocalizer' not implemented!") event.Skip() def OnCalibrationPublisher(self, event): # wxGlade: MyFrame. - print "Event handler 'OnCalibrationPublisher' not implemented!" + print("Event handler 'OnCalibrationPublisher' not implemented!") event.Skip() def OnLamp(self, event): # wxGlade: MyFrame. - print "Event handler 'OnLamp' not implemented!" + print("Event handler 'OnLamp' not implemented!") event.Skip() def OnIndi(self, event): # wxGlade: MyFrame. - print "Event handler 'OnIndi' not implemented!" + print("Event handler 'OnIndi' not implemented!") event.Skip() def OnGear(self, event): # wxGlade: MyFrame. - print "Event handler 'OnGear' not implemented!" + print("Event handler 'OnGear' not implemented!") event.Skip() def OnQuery(self, event): # wxGlade: MyFrame. - print "Event handler 'OnQuery' not implemented!" + print("Event handler 'OnQuery' not implemented!") event.Skip() def OnROSbagPlay(self, event): # wxGlade: MyFrame. - print "Event handler 'OnROSbagPlay' not implemented!" + print("Event handler 'OnROSbagPlay' not implemented!") event.Skip() def OnFtrace(self, event): # wxGlade: MyFrame. - print "Event handler 'OnFtrace' not implemented!" + print("Event handler 'OnFtrace' not implemented!") event.Skip() def OnEcho(self, event): # wxGlade: MyFrame. - print "Event handler 'OnEcho' not implemented!" + print("Event handler 'OnEcho' not implemented!") event.Skip() def OnRefreshTopics(self, event): # wxGlade: MyFrame. - print "Event handler 'OnRefreshTopics' not implemented!" + print("Event handler 'OnRefreshTopics' not implemented!") event.Skip() def OnState(self, event): # wxGlade: MyFrame. - print "Event handler 'OnState' not implemented!" + print("Event handler 'OnState' not implemented!") event.Skip() # end of class MyFrame @@ -956,11 +956,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialog. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialog. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialog @@ -1003,11 +1003,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialogParam. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialogParam. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialogParam @@ -1075,19 +1075,19 @@ def __do_layout(self): # end wxGlade def OnRef(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRef' not implemented!" + print("Event handler 'OnRef' not implemented!") event.Skip() def OnStart(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStart' not implemented!" + print("Event handler 'OnStart' not implemented!") event.Skip() def OnStop(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnStop' not implemented!" + print("Event handler 'OnStop' not implemented!") event.Skip() def OnRefresh(self, event): # wxGlade: MyDialogROSbagRecord. - print "Event handler 'OnRefresh' not implemented!" + print("Event handler 'OnRefresh' not implemented!") event.Skip() # end of class MyDialogROSbagRecord @@ -1178,23 +1178,23 @@ def __do_layout(self): # end wxGlade def OnTrafficRedLight(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficRedLight' not implemented!" + print("Event handler 'OnTrafficRedLight' not implemented!") event.Skip() def OnTrafficGreenLight(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficGreenLight' not implemented!" + print("Event handler 'OnTrafficGreenLight' not implemented!") event.Skip() def OnTrafficLightRecognition(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnTrafficLightRecognition' not implemented!" + print("Event handler 'OnTrafficLightRecognition' not implemented!") event.Skip() def OnOk(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnCancel(self, event): # wxGlade: MyDialogLaneStop. - print "Event handler 'OnCancel' not implemented!" + print("Event handler 'OnCancel' not implemented!") event.Skip() # end of class MyDialogLaneStop @@ -1257,19 +1257,19 @@ def __do_layout(self): # end wxGlade def OnRef(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnRef' not implemented!" + print("Event handler 'OnRef' not implemented!") event.Skip() def OnRadio(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnRadio' not implemented!" + print("Event handler 'OnRadio' not implemented!") event.Skip() def OnPcdOutput(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnPcdOutput' not implemented!" + print("Event handler 'OnPcdOutput' not implemented!") event.Skip() def OnOk(self, event): # wxGlade: MyDialogNDTMapping. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() # end of class MyDialogNDTMapping @@ -1317,11 +1317,11 @@ def __do_layout(self): # end wxGlade def OnOk(self, event): # wxGlade: MyDialogDPM. - print "Event handler 'OnOk' not implemented!" + print("Event handler 'OnOk' not implemented!") event.Skip() def OnLink(self, event): # wxGlade: MyDialogDPM. - print "Event handler 'OnLink' not implemented!" + print("Event handler 'OnLink' not implemented!") event.Skip() # end of class MyDialogDPM @@ -1357,7 +1357,7 @@ def __do_layout(self): # end wxGlade def OnLink(self, event): # wxGlade: MyDialogCarPedestrian. - print "Event handler 'OnLink' not implemented!" + print("Event handler 'OnLink' not implemented!") event.Skip() # end of class MyDialogCarPedestrian diff --git a/utilities/runtime_manager/scripts/runtime_manager_dialog.py b/utilities/runtime_manager/scripts/runtime_manager_dialog.py index 0602fb21729..9eebab9d680 100755 --- a/utilities/runtime_manager/scripts/runtime_manager_dialog.py +++ b/utilities/runtime_manager/scripts/runtime_manager_dialog.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2015-2019 Autoware Foundation # @@ -95,1608 +95,1609 @@ class MyFrame(rtmgr.MyFrame): - def __init__(self, *args, **kwds): - rtmgr.MyFrame.__init__(self, *args, **kwds) - self.all_procs = [] - self.all_cmd_dics = [] - self.load_dic = self.load_yaml('param.yaml', def_ret={}) - self.config_dic = {} - self.Bind(wx.EVT_CLOSE, self.OnClose) - self.params = [] - self.all_tabs = [] - self.all_th_infs = [] - self.log_que = Queue.Queue() - self.log_que_stdout = Queue.Queue() - self.log_que_stderr = Queue.Queue() - self.log_que_show = Queue.Queue() - - # - # ros - # - rospy.init_node('runime_manager', anonymous=True) - rospy.Subscriber('to_rtmgr', std_msgs.msg.String, self.ROSCb) - self.pub = rospy.Publisher('from_rtmgr', std_msgs.msg.String, queue_size=10) - - # - # for Quick Start tab - # - tab = self.tab_qs - self.all_tabs.append(tab) - - self.qs_cmd = {} - self.all_cmd_dics.append(self.qs_cmd) - self.qs_dic = self.load_yaml('qs.yaml') - - self.add_params(self.qs_dic.get('params', [])) - - self.setup_buttons(self.qs_dic.get('buttons', {}), self.qs_cmd) - - for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: - for key in self.qs_dic.get('exec_time', {}).get(nm, {}).keys(): - (topic, msg, attr) = ( key.split('.') + [ None, None, None ] )[:3] - msg = globals().get(msg) - msg = msg if msg else std_msgs.msg.Float32 - attr = attr if attr else 'data' - rospy.Subscriber(topic, msg, self.exec_time_callback, callback_args=(key, attr)) - print 'Subscribe[{}] topic={}, key={}'.format(nm, topic, key) - - # - # for Setup tab - # - tab = self.tab_setup - self.all_tabs.append(tab) - - setup_cmd = {} - self.all_cmd_dics.append(setup_cmd) - dic = self.load_yaml('setup.yaml') - - self.add_params(dic.get('params', [])) - self.setup_buttons(dic.get('buttons', {}), setup_cmd) - - # - # for Map tab - # - tab = self.tab_map - self.all_tabs.append(tab) - - self.map_cmd = {} - self.all_cmd_dics.append(self.map_cmd) - self.map_dic = self.load_yaml('map.yaml') - - self.add_params(self.map_dic.get('params', [])) - - self.setup_buttons(self.map_dic.get('buttons', {}), self.map_cmd) - - self.tc_point_cloud = self.obj_to_varpanel_tc(self.button_point_cloud, 'path_pcd') - self.tc_area_list = self.obj_to_varpanel_tc(self.button_area_lists, 'path_area_list') - - self.label_point_cloud_bar.Destroy() - self.label_point_cloud_bar = BarLabel(tab, ' Loading... ') - self.label_point_cloud_bar.Enable(False) - - def hook1G(args): - for f in args.get('func')().split(','): - sz = os.path.getsize(f) - if sz > 1024*1024*1024: - wx.MessageBox("Over 1GB\n\n{}\n({:,})".format(f, sz), caption='Warning') - - args = { 'func':self.tc_point_cloud.GetValue } - hook_var = { 'hook':hook1G, 'args':args, 'flags':['every_time'] } - obj = self.button_point_cloud - gdic_v = self.obj_to_gdic(obj, {}).get('path_pcd', {}) - gdic_v['hook_var'] = hook_var - - # - # for Sensing tab - # - tab = self.tab_sensing - self.all_tabs.append(tab) - - self.drv_probe_cmd = {} - self.sensing_cmd = {} - self.all_cmd_dics.append(self.sensing_cmd) - dic = self.load_yaml('sensing.yaml') - - self.add_params(dic.get('params', [])) - - self.create_checkboxes(dic, self.panel_sensing, None, self.drv_probe_cmd, self.sensing_cmd, self.OnSensingDriver) - - self.setup_buttons(dic.get('buttons', {}), self.sensing_cmd) - - #self.timer = wx.Timer(self) - #self.Bind(wx.EVT_TIMER, self.OnProbe, self.timer) - #self.probe_interval = 10*1000 - #if self.checkbox_auto_probe.GetValue(): - # self.OnProbe(None) - # self.timer.Start(self.probe_interval) - - self.dlg_rosbag_record = MyDialogROSbagRecord(self, cmd_dic=self.sensing_cmd) - buttons_color_hdr_setup(self.dlg_rosbag_record) - - sense_cmds_dic = dic.get('cmds', {}) - - # - # for Computing tab - # - tab = self.tab_computing - self.all_tabs.append(tab) - - parent = self.tree_ctrl_0.GetParent() - for i in range(2): - self.obj_get('tree_ctrl_' + str(i)).Destroy() - items = self.load_yaml('computing.yaml') - - self.add_params(items.get('params', [])) - - self.sys_gdic = items.get('sys_gui') - self.sys_gdic['update_func'] = self.update_func - - self.computing_cmd = {} - self.all_cmd_dics.append(self.computing_cmd) - for i in range(2): - tree_ctrl = self.create_tree(parent, items['subs'][i], None, None, self.computing_cmd) - tree_ctrl.ExpandAll() - tree_ctrl.SetBackgroundColour(wx.NullColour) - setattr(self, 'tree_ctrl_' + str(i), tree_ctrl) - - self.Bind(CT.EVT_TREE_ITEM_CHECKED, self.OnTreeChecked) - - self.setup_buttons(items.get('buttons', {}), self.computing_cmd) - - # - # for Sensing tab (cmds) - # - parent = self.tree_ctrl_sense.GetParent() - self.tree_ctrl_sense.Destroy() - tree_ctrl = self.create_tree(parent, sense_cmds_dic, None, None, self.sensing_cmd) - tree_ctrl.ExpandAll() - tree_ctrl.SetBackgroundColour(wx.NullColour) - self.tree_ctrl_sense = tree_ctrl - - # - # for Interface tab - # - tab = self.tab_interface - self.all_tabs.append(tab) + def __init__(self, *args, **kwds): + rtmgr.MyFrame.__init__(self, *args, **kwds) + self.all_procs = [] + self.all_cmd_dics = [] + self.load_dic = self.load_yaml('param.yaml', def_ret={}) + self.config_dic = {} + self.Bind(wx.EVT_CLOSE, self.OnClose) + self.params = [] + self.all_tabs = [] + self.all_th_infs = [] + self.log_que = Queue.Queue() + self.log_que_stdout = Queue.Queue() + self.log_que_stderr = Queue.Queue() + self.log_que_show = Queue.Queue() - self.interface_cmd = {} - self.all_cmd_dics.append(self.interface_cmd) - self.interface_dic = self.load_yaml('interface.yaml') + # + # ros + # + rospy.init_node('runime_manager', anonymous=True) + rospy.Subscriber('to_rtmgr', std_msgs.msg.String, self.ROSCb) + self.pub = rospy.Publisher('from_rtmgr', std_msgs.msg.String, queue_size=10) + + # + # for Quick Start tab + # + tab = self.tab_qs + self.all_tabs.append(tab) + + self.qs_cmd = {} + self.all_cmd_dics.append(self.qs_cmd) + self.qs_dic = self.load_yaml('qs.yaml') + + self.add_params(self.qs_dic.get('params', [])) + + self.setup_buttons(self.qs_dic.get('buttons', {}), self.qs_cmd) + + for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: + for key in self.qs_dic.get('exec_time', {}).get(nm, {}).keys(): + (topic, msg, attr) = ( key.split('.') + [ None, None, None ] )[:3] + msg = globals().get(msg) + msg = msg if msg else std_msgs.msg.Float32 + attr = attr if attr else 'data' + rospy.Subscriber(topic, msg, self.exec_time_callback, callback_args=(key, attr)) + print('Subscribe[{}] topic={}, key={}'.format(nm, topic, key)) + + # + # for Setup tab + # + tab = self.tab_setup + self.all_tabs.append(tab) + + setup_cmd = {} + self.all_cmd_dics.append(setup_cmd) + dic = self.load_yaml('setup.yaml') + + self.add_params(dic.get('params', [])) + self.setup_buttons(dic.get('buttons', {}), setup_cmd) + + # + # for Map tab + # + tab = self.tab_map + self.all_tabs.append(tab) + + self.map_cmd = {} + self.all_cmd_dics.append(self.map_cmd) + self.map_dic = self.load_yaml('map.yaml') + + self.add_params(self.map_dic.get('params', [])) + + self.setup_buttons(self.map_dic.get('buttons', {}), self.map_cmd) + + self.tc_point_cloud = self.obj_to_varpanel_tc(self.button_point_cloud, 'path_pcd') + self.tc_area_list = self.obj_to_varpanel_tc(self.button_area_lists, 'path_area_list') + + self.label_point_cloud_bar.Destroy() + self.label_point_cloud_bar = BarLabel(tab, ' Loading... ') + self.label_point_cloud_bar.Enable(False) + + def hook1G(args): + for f in args.get('func')().split(','): + sz = os.path.getsize(f) + if sz > 1024*1024*1024: + wx.MessageBox("Over 1GB\n\n{}\n({:,})".format(f, sz), caption='Warning') + + args = { 'func':self.tc_point_cloud.GetValue } + hook_var = { 'hook':hook1G, 'args':args, 'flags':['every_time'] } + obj = self.button_point_cloud + gdic_v = self.obj_to_gdic(obj, {}).get('path_pcd', {}) + gdic_v['hook_var'] = hook_var + + # + # for Sensing tab + # + tab = self.tab_sensing + self.all_tabs.append(tab) + + self.drv_probe_cmd = {} + self.sensing_cmd = {} + self.all_cmd_dics.append(self.sensing_cmd) + dic = self.load_yaml('sensing.yaml') + + self.add_params(dic.get('params', [])) + + self.create_checkboxes(dic, self.panel_sensing, None, self.drv_probe_cmd, self.sensing_cmd, self.OnSensingDriver) + + self.setup_buttons(dic.get('buttons', {}), self.sensing_cmd) + + #self.timer = wx.Timer(self) + #self.Bind(wx.EVT_TIMER, self.OnProbe, self.timer) + #self.probe_interval = 10*1000 + #if self.checkbox_auto_probe.GetValue(): + # self.OnProbe(None) + # self.timer.Start(self.probe_interval) + + self.dlg_rosbag_record = MyDialogROSbagRecord(self, cmd_dic=self.sensing_cmd) + buttons_color_hdr_setup(self.dlg_rosbag_record) + + sense_cmds_dic = dic.get('cmds', {}) + + # + # for Computing tab + # + tab = self.tab_computing + self.all_tabs.append(tab) + + parent = self.tree_ctrl_0.GetParent() + for i in range(2): + self.obj_get('tree_ctrl_' + str(i)).Destroy() + items = self.load_yaml('computing.yaml') + + self.add_params(items.get('params', [])) + + self.sys_gdic = items.get('sys_gui') + self.sys_gdic['update_func'] = self.update_func + + self.computing_cmd = {} + self.all_cmd_dics.append(self.computing_cmd) + for i in range(2): + tree_ctrl = self.create_tree(parent, items['subs'][i], None, None, self.computing_cmd) + tree_ctrl.ExpandAll() + tree_ctrl.SetBackgroundColour(wx.NullColour) + setattr(self, 'tree_ctrl_' + str(i), tree_ctrl) + + self.Bind(CT.EVT_TREE_ITEM_CHECKED, self.OnTreeChecked) + + self.setup_buttons(items.get('buttons', {}), self.computing_cmd) + + # + # for Sensing tab (cmds) + # + parent = self.tree_ctrl_sense.GetParent() + self.tree_ctrl_sense.Destroy() + tree_ctrl = self.create_tree(parent, sense_cmds_dic, None, None, self.sensing_cmd) + tree_ctrl.ExpandAll() + tree_ctrl.SetBackgroundColour(wx.NullColour) + self.tree_ctrl_sense = tree_ctrl + + # + # for Interface tab + # + tab = self.tab_interface + self.all_tabs.append(tab) + + self.interface_cmd = {} + self.all_cmd_dics.append(self.interface_cmd) + self.interface_dic = self.load_yaml('interface.yaml') + + self.add_params(self.interface_dic.get('params', [])) + + self.setup_buttons(self.interface_dic.get('buttons', {}), self.interface_cmd) + self.setup_buttons(self.interface_dic.get('checkboxs', {}), self.interface_cmd) + + szr = wx.BoxSizer(wx.VERTICAL) + for cc in self.interface_dic.get('control_check', []): + pdic = {} + prm = self.get_param(cc.get('param')) + for var in prm['vars']: + pdic[ var['name'] ] = var['v'] + gdic = self.gdic_get_1st(cc) + panel = ParamPanel(self.panel_interface_cc, frame=self, pdic=pdic, gdic=gdic, prm=prm) + szr.Add(panel, 0, wx.EXPAND) + self.panel_interface_cc.SetSizer(szr) + + # + # for Database tab + # + tab = self.tab_database + self.all_tabs.append(tab) + + self.data_cmd = {} + self.all_cmd_dics.append(self.data_cmd) + dic = self.load_yaml('data.yaml') + + self.add_params(dic.get('params', [])) + + parent = self.tree_ctrl_data.GetParent() + self.tree_ctrl_data.Destroy() + tree_ctrl = self.create_tree(parent, dic, None, None, self.data_cmd) + tree_ctrl.ExpandAll() + tree_ctrl.SetBackgroundColour(wx.NullColour) + self.tree_ctrl_data = tree_ctrl + + #self.setup_config_param_pdic() + + if 'buttons' in dic: + self.setup_buttons(dic['buttons'], self.data_cmd) + + # + # for Simulation Tab + # + tab = self.tab_simulation + self.all_tabs.append(tab) + + self.simulation_cmd = {} + self.all_cmd_dics.append(self.simulation_cmd) + dic = self.load_yaml('simulation.yaml') + + self.add_params(dic.get('params', [])) + + self.setup_buttons(dic.get('buttons'), self.simulation_cmd) + + btn = self.button_play_rosbag_play + + # setup for rosbag info + gdic = self.obj_to_gdic(btn, {}) + gdic_v = dic_getset(gdic, 'file', {}) + gdic_v['update_hook'] = self.rosbag_info_hook + + tc = self.obj_to_varpanel_tc(btn, 'file') + if tc: + self.rosbag_info_hook( tc.GetValue() ) + + + #vp = self.obj_to_varpanel(btn, 'sim_time') + #self.checkbox_sim_time = vp.obj + + #try: + # cmd = ['rosparam', 'get', '/use_sim_time'] + # if subprocess.check_output(cmd, stderr=open(os.devnull, 'wb')).strip() == 'true': + # self.checkbox_sim_time.SetValue(True) + #except subprocess.CalledProcessError: + # pass + + self.label_rosbag_play_bar.Destroy() + self.label_rosbag_play_bar = BarLabel(tab, ' Playing... ') + self.label_rosbag_play_bar.Enable(False) + + # + # for Status tab + # + tab = self.tab_status + self.all_tabs.append(tab) + + self.status_cmd = {} + self.all_cmd_dics.append(self.status_cmd) + self.status_dic = self.load_yaml('status.yaml') + + self.add_params(self.status_dic.get('params', [])) + + self.setup_buttons(self.status_dic.get('buttons', {}), self.status_cmd) + + font = wx.Font(10, wx.FONTFAMILY_MODERN, wx.FONTSTYLE_NORMAL, wx.FONTWEIGHT_NORMAL) + self.label_top_cmd.SetFont(font) - self.add_params(self.interface_dic.get('params', [])) - - self.setup_buttons(self.interface_dic.get('buttons', {}), self.interface_cmd) - self.setup_buttons(self.interface_dic.get('checkboxs', {}), self.interface_cmd) - - szr = wx.BoxSizer(wx.VERTICAL) - for cc in self.interface_dic.get('control_check', []): - pdic = {} - prm = self.get_param(cc.get('param')) - for var in prm['vars']: - pdic[ var['name'] ] = var['v'] - gdic = self.gdic_get_1st(cc) - panel = ParamPanel(self.panel_interface_cc, frame=self, pdic=pdic, gdic=gdic, prm=prm) - szr.Add(panel, 0, wx.EXPAND) - self.panel_interface_cc.SetSizer(szr) - - # - # for Database tab - # - tab = self.tab_database - self.all_tabs.append(tab) - - self.data_cmd = {} - self.all_cmd_dics.append(self.data_cmd) - dic = self.load_yaml('data.yaml') - - self.add_params(dic.get('params', [])) + # + # for Topics tab + # + tab = self.tab_topics + self.all_tabs.append(tab) - parent = self.tree_ctrl_data.GetParent() - self.tree_ctrl_data.Destroy() - tree_ctrl = self.create_tree(parent, dic, None, None, self.data_cmd) - tree_ctrl.ExpandAll() - tree_ctrl.SetBackgroundColour(wx.NullColour) - self.tree_ctrl_data = tree_ctrl - - #self.setup_config_param_pdic() - - if 'buttons' in dic: - self.setup_buttons(dic['buttons'], self.data_cmd) - - # - # for Simulation Tab - # - tab = self.tab_simulation - self.all_tabs.append(tab) - - self.simulation_cmd = {} - self.all_cmd_dics.append(self.simulation_cmd) - dic = self.load_yaml('simulation.yaml') - - self.add_params(dic.get('params', [])) - - self.setup_buttons(dic.get('buttons'), self.simulation_cmd) - - btn = self.button_play_rosbag_play - - # setup for rosbag info - gdic = self.obj_to_gdic(btn, {}) - gdic_v = dic_getset(gdic, 'file', {}) - gdic_v['update_hook'] = self.rosbag_info_hook - - tc = self.obj_to_varpanel_tc(btn, 'file') - if tc: - self.rosbag_info_hook( tc.GetValue() ) - - - #vp = self.obj_to_varpanel(btn, 'sim_time') - #self.checkbox_sim_time = vp.obj - - #try: - # cmd = ['rosparam', 'get', '/use_sim_time'] - # if subprocess.check_output(cmd, stderr=open(os.devnull, 'wb')).strip() == 'true': - # self.checkbox_sim_time.SetValue(True) - #except subprocess.CalledProcessError: - # pass - - self.label_rosbag_play_bar.Destroy() - self.label_rosbag_play_bar = BarLabel(tab, ' Playing... ') - self.label_rosbag_play_bar.Enable(False) - - # - # for Status tab - # - tab = self.tab_status - self.all_tabs.append(tab) - - self.status_cmd = {} - self.all_cmd_dics.append(self.status_cmd) - self.status_dic = self.load_yaml('status.yaml') - - self.add_params(self.status_dic.get('params', [])) - - self.setup_buttons(self.status_dic.get('buttons', {}), self.status_cmd) - - font = wx.Font(10, wx.FONTFAMILY_MODERN, wx.FONTSTYLE_NORMAL, wx.FONTWEIGHT_NORMAL) - self.label_top_cmd.SetFont(font) - - # - # for Topics tab - # - tab = self.tab_topics - self.all_tabs.append(tab) - - # - # for State tab - # - tab = self.tab_states - self.all_tabs.append(tab) - - self.state_dic = self.load_yaml('state.yaml') - self.mainstate_dic = self.state_dic["mainstate"] - self.substate_dic = self.state_dic["substate"] - - # - # for All - # - self.bitmap_logo.Destroy() - bm = scaled_bitmap(wx.Bitmap(rtmgr_src_dir() + 'images/autoware_logo_1.png'), 0.2) - self.bitmap_logo = wx.StaticBitmap(self, wx.ID_ANY, bm) - - rtmgr.MyFrame.__do_layout(self) - - cond = lambda s : s.startswith('tab_') - self.tab_names = [ self.name_get_cond(tab, cond=cond, def_ret='').replace('tab_', '', 1) for tab in self.all_tabs ] - - new_btn_grps = ( lambda btn_names, tab_names=self.tab_names : - [ [ self.obj_get('button_{}_{}'.format(bn, tn)) for tn in tab_names ] for bn in btn_names ] ) - - self.alias_grps = new_btn_grps( ('rosbag', 'rviz', 'rqt') ) - self.alias_grps += new_btn_grps( ('android_tablet', 'oculus_rift', 'vehicle_gateway', 'remote_control', 'auto_pilot'), - ('qs', 'interface') ) - for grp in self.alias_grps: - wx.CallAfter(self.alias_sync, get_top(grp)) - s = get_tooltip_obj(grp[0]) - if s: - for obj in grp[1:]: - set_tooltip_str(obj, s) - - # Topics tab (need, after layout for sizer) - self.topics_dic = self.load_yaml('topics.yaml') - self.topics_list = [] - self.topics_echo_curr_topic = None - self.topics_echo_proc = None - self.topics_echo_thinf = None - - self.topics_echo_que = Queue.Queue() - self.topics_echo_sum = 0 - thinf = th_start(self.topics_echo_show_th) - self.all_th_infs.append(thinf) - - self.refresh_topics_list() - - # waypoint - self.route_cmd_waypoint = [ Waypoint(0,0), Waypoint(0,0) ] - rospy.Subscriber('route_cmd', route_cmd, self.route_cmd_callback) - - # topic /xxx_stat - self.stat_dic = {} - for k in [ 'gnss', 'pmap', 'vmap', 'lf' ]: - self.stat_dic[k] = False - name = k + '_stat' - rospy.Subscriber(name, std_msgs.msg.Bool, self.stat_callback, callback_args=k) - - # top command thread setup - toprc = os.path.expanduser('~/.toprc') - backup = os.path.expanduser('~/.toprc-autoware-backup') - self.toprc_setup(toprc, backup) - - cpu_ibls = [ InfoBarLabel(self, 'CPU'+str(i)) for i in range(get_cpu_count())] - sz = sizer_wrap(cpu_ibls, wx.HORIZONTAL, 1, wx.EXPAND, 0) - self.sizer_cpuinfo.Add(sz, 8, wx.ALL | wx.EXPAND, 4) - - self.lb_top5 = [] - for i in range(5): - lb = wx.StaticText(self, wx.ID_ANY, '') - change_font_point_by_rate(lb, 0.75) - self.lb_top5.append(lb) - line = wx.StaticLine(self, wx.ID_ANY) - ibl = InfoBarLabel(self, 'Memory', bar_orient=wx.HORIZONTAL) - szr = sizer_wrap(self.lb_top5 + [ line, ibl ], flag=wx.EXPAND | wx.FIXED_MINSIZE) - self.sizer_cpuinfo.Add(szr, 2, wx.ALL | wx.EXPAND, 4) - - th_arg = { 'setting':self.status_dic.get('top_cmd_setting', {}), - 'cpu_ibls':cpu_ibls, 'mem_ibl':ibl, - 'toprc':toprc, 'backup':backup } - thinf = th_start(self.top_cmd_th, th_arg) - self.all_th_infs.append(thinf) - - # ps command thread - #thinf = th_start(self.ps_cmd_th, { 'interval':5 }) - #self.all_th_infs.append(thinf) - - # logout thread - interval = self.status_dic.get('gui_update_interval_ms', 100) * 0.001 - tc = self.text_ctrl_stdout - - thinf = th_start(self.logout_th, { 'que':self.log_que_stdout, 'interval':interval, 'tc':tc } ) - self.all_th_infs.append(thinf) - thinf = th_start(self.logout_th, { 'que':self.log_que_stderr, 'interval':interval, 'tc':tc } ) - self.all_th_infs.append(thinf) - thinf = th_start(self.logout_th, { 'que':self.log_que, 'interval':interval, 'tc':tc } ) - self.all_th_infs.append(thinf) - - if interval > 0: - thinf = th_start(self.logshow_th, { 'que':self.log_que_show , 'interval':interval , 'tc':tc }) - self.all_th_infs.append(thinf) - else: - self.checkbox_stdout.Enable(False) - tc.Enable(False) - - # mkdir - paths = [ os.environ['HOME'] + '/.autoware/data/tf', - os.environ['HOME'] + '/.autoware/data/map/pointcloud_map', - os.environ['HOME'] + '/.autoware/data/map/vector_map' ] - for path in paths: - if not os.path.exists(path): - subprocess.call([ 'mkdir', '-p', path ]) - - # icon - bm = scaled_bitmap(wx.Bitmap(rtmgr_src_dir() + 'images/autoware_logo_2_white.png'), 0.5) - icon = wx.EmptyIcon() - icon.CopyFromBitmap(bm) - self.SetIcon(icon) - - - wx.CallAfter( self.boot_booted_cmds ) - - def __do_layout(self): - pass - - def boot_booted_cmds(self): - if not self.load_dic.get('booted_cmds', {}).get('enable', False): - return - names = self.load_dic.get('booted_cmds', {}).get('names', []) - lst = [ ( name, self.cfg_dic( { 'name': name } ).get('obj') ) for name in names ] - lst = [ (name, obj) for (name, obj) in lst if obj ] - if not lst: - return - - choices = [ obj.GetLabel() if hasattr(obj, 'GetLabel') else name for (name, obj) in lst ] - dlg = wx.MultiChoiceDialog(self, 'boot command ?', '', choices) - dlg.SetSelections( range( len(names) ) ) - if dlg.ShowModal() != wx.ID_OK: - return - - for i in dlg.GetSelections(): - (_, obj) = lst[i] - post_evt_toggle_obj(self, obj, True) - - def OnClose(self, event): - if self.quit_select() != 'quit': - return - - # kill_all - for proc in self.all_procs[:]: # copy - (_, obj) = self.proc_to_cmd_dic_obj(proc) - self.launch_kill(False, 'dmy', proc, obj=obj) - - shutdown_proc_manager() - - shutdown_sh = self.get_autoware_dir() + '/ros/shutdown' - if os.path.exists(shutdown_sh): - os.system(shutdown_sh) - - for thinf in self.all_th_infs: - th_end(thinf) - - self.Destroy() - - def quit_select(self): - def timer_func(): - if self.quit_timer: - self.quit_timer = 'timeout' - evt = wx.PyCommandEvent( wx.EVT_CLOSE.typeId, self.GetId() ) - wx.PostEvent(self, evt) - - if not hasattr(self, 'quit_timer') or not self.quit_timer: - self.quit_timer = threading.Timer(2.0, timer_func) - self.quit_timer.start() - return 'not quit' - - if self.quit_timer == 'timeout': - self.save_param_yaml() - return 'quit' - - self.quit_timer.cancel() - self.quit_timer = None - lst = [ - ( 'Save and Quit', [ 'save', 'quit' ] ), - ( 'Save to param.yaml', [ 'save' ] ), - ( 'Quit without saving', [ 'quit' ] ), - ( 'Reload computing.yaml', [ 'reload' ] ), - ( self.get_booted_cmds_enable_msg()[1], [ 'toggle_booted_cmds' ] ), - ] - choices = [ s for (s, _) in lst ] - dlg = wx.SingleChoiceDialog(self, 'select command', '', choices) - if dlg.ShowModal() != wx.ID_OK: - return 'not quit' - - i = dlg.GetSelection() # index of choices - (_, f) = lst[i] - if 'save' in f: - self.save_param_yaml() - if 'reload' in f: - self.reload_computing_yaml() - if 'toggle_booted_cmds' in f: - self.toggle_booted_cmds() - return 'quit' if 'quit' in f else 'not quit' - - def save_param_yaml(self): - save_dic = {} - for (name, pdic) in self.load_dic.items(): - if pdic and pdic != {}: - prm = self.cfg_dic( {'name':name, 'pdic':pdic} ).get('param', {}) - no_saves = prm.get('no_save_vars', []) - pdic = pdic.copy() - for k in pdic.keys(): - if k in no_saves: - del pdic[k] - save_dic[name] = pdic - - names = [] - for proc in self.all_procs: - (_, obj) = self.proc_to_cmd_dic_obj(proc) - name = self.cfg_dic( { 'obj': obj } ).get('name') - names.append(name) - if 'booted_cmds' not in save_dic: - save_dic['booted_cmds'] = {} - save_dic.get('booted_cmds')['names'] = names - - if save_dic != {}: - dir = rtmgr_src_dir() - print('saving param.yaml') - f = open(dir + 'param.yaml', 'w') - s = yaml.dump(save_dic, default_flow_style=False) - #print 'save\n', s # for debug - f.write(s) - f.close() - - def reload_computing_yaml(self): - parent = self.tree_ctrl_0.GetParent() - sizer = self.tree_ctrl_0.GetContainingSizer() - - items = self.load_yaml('computing.yaml') - - # backup cmd_dic proc - cmd_dic = self.computing_cmd - to_name = lambda obj: next( ( d.get('name') for d in self.config_dic.values() if d.get('obj') == obj ), None ) - procs = [ ( to_name(obj), proc ) for (obj, (cmd, proc)) in cmd_dic.items() if proc ] - - # remove old tree ctrl - for i in range(2): - self.obj_get('tree_ctrl_' + str(i)).Destroy() - - # remove old params - names = [ prm.get('name') for prm in items.get('params', []) ] - for prm in self.params[:]: # copy - if prm.get('name') in names: - self.params.remove(prm) - - self.add_params(items.get('params', [])) - - # overwrite sys_gdic - old = self.sys_gdic - self.sys_gdic = items.get('sys_gui') - self.sys_gdic['update_func'] = self.update_func - for d in self.config_dic.values(): - if d.get('gdic') == old: - d['gdic'] = self.sys_gdic - - # listing update names - def subs_names(subs): - f2 = lambda s: subs_names( s.get('subs') ) if 'subs' in s else [ s.get('name') ] - f = lambda lst, s: lst + f2(s) - return reduce(f, subs, []) - - names = subs_names( items.get('subs') ) - names += items.get('buttons', {}).keys() - - # remove old data of name in config_dic - for (k, v) in self.config_dic.items(): - if v.get('name') in names: - self.config_dic.pop(k, None) - - # rebuild tree ctrl - cmd_dic.clear() - for i in range(2): - tree_ctrl = self.create_tree(parent, items['subs'][i], None, None, self.computing_cmd) - tree_ctrl.ExpandAll() - tree_ctrl.SetBackgroundColour(wx.NullColour) - setattr(self, 'tree_ctrl_' + str(i), tree_ctrl) - sizer.Add(tree_ctrl, 1, wx.EXPAND, 0) - - self.setup_buttons(items.get('buttons', {}), self.computing_cmd) - - # restore cmd_dic proc - to_obj = lambda name: next( ( d.get('obj') for d in self.config_dic.values() if d.get('name') == name ), None ) - for (name, proc) in procs: - obj = to_obj(name) - if obj and obj in cmd_dic: - cmd_dic[ obj ] = ( cmd_dic.get(obj)[0], proc ) - set_val(obj, True) - - parent.Layout() - - def toggle_booted_cmds(self): - (enable, msg) = self.get_booted_cmds_enable_msg() - style = wx.OK | wx.CANCEL | wx.ICON_QUESTION - dlg = wx.MessageDialog(self, msg, '', style) - if dlg.ShowModal() != wx.ID_OK: - return - if 'booted_cmds' not in self.load_dic: - self.load_dic['booted_cmds'] = {} - self.load_dic.get('booted_cmds')['enable'] = not enable - - def get_booted_cmds_enable_msg(self): - enable = self.load_dic.get('booted_cmds', {}).get('enable', False) - s = 'Enable' if not enable else 'Disable' - msg = '{} booted commands menu ?'.format(s) - return (enable, msg) - - def ROSCb(self, data): - print('recv topic msg : ' + data.data) - - r = rospy.Rate(10) - rospy.is_shutdown() - r.sleep() - self.pub.publish(data.data) - r.sleep() - - def setup_buttons(self, d, run_dic): - for (k,d2) in d.items(): - pfs = [ 'button_', 'checkbox_' ] - obj = next( (self.obj_get(pf+k) for pf in pfs if self.obj_get(pf+k)), None) - if not obj: - s = 'button_' + k - obj = StrValObj(s, False) - setattr(self, s, obj) - if not d2 or type(d2) is not dict: - continue - if 'run' in d2: - run_dic[obj] = (d2['run'], None) - set_tooltip(obj, d2) - gdic = self.gdic_get_1st(d2) - if 'param' in d2: - pdic = self.load_dic_pdic_setup(k, d2) - prm = self.get_param(d2.get('param')) - for var in prm.get('vars'): - name = var.get('name') - if name not in pdic and 'v' in var: - pdic[name] = var.get('v') - - for (name, v) in pdic.items(): - restore = eval( gdic.get(name, {}).get('restore', 'lambda a : None') ) - restore(v) - - self.add_cfg_info(obj, obj, k, pdic, gdic, False, prm) - - pnls = [ gdic.get(var.get('name'), {}).get('panel') for var in prm.get('vars') ] - for pnl in [ gdic.get('panel') ] + pnls: - if pnl: - self.set_param_panel(obj, eval_if_str(self, pnl)) - else: - self.add_cfg_info(obj, obj, k, None, gdic, False, None) - - def OnGear(self, event): - grp = { self.button_statchk_d : 1, - self.button_statchk_r : 2, - self.button_statchk_b : 3, - self.button_statchk_n : 4, + # + # for State tab + # + tab = self.tab_states + self.all_tabs.append(tab) + + self.state_dic = self.load_yaml('state.yaml') + self.mainstate_dic = self.state_dic["mainstate"] + self.substate_dic = self.state_dic["substate"] + + # + # for All + # + self.bitmap_logo.Destroy() + bm = scaled_bitmap(wx.Bitmap(rtmgr_src_dir() + 'images/autoware_logo_1.png'), 0.2) + self.bitmap_logo = wx.StaticBitmap(self, wx.ID_ANY, bm) + + rtmgr.MyFrame.__do_layout(self) + + cond = lambda s : s.startswith('tab_') + self.tab_names = [ self.name_get_cond(tab, cond=cond, def_ret='').replace('tab_', '', 1) for tab in self.all_tabs ] + + new_btn_grps = ( lambda btn_names, tab_names=self.tab_names : + [ [ self.obj_get('button_{}_{}'.format(bn, tn)) for tn in tab_names ] for bn in btn_names ] ) + + self.alias_grps = new_btn_grps( ('rosbag', 'rviz', 'rqt') ) + self.alias_grps += new_btn_grps( ('android_tablet', 'oculus_rift', 'vehicle_gateway', 'remote_control', 'auto_pilot'), + ('qs', 'interface') ) + for grp in self.alias_grps: + wx.CallAfter(self.alias_sync, get_top(grp)) + s = get_tooltip_obj(grp[0]) + if s: + for obj in grp[1:]: + set_tooltip_str(obj, s) + + # Topics tab (need, after layout for sizer) + self.topics_dic = self.load_yaml('topics.yaml') + self.topics_list = [] + self.topics_echo_curr_topic = None + self.topics_echo_proc = None + self.topics_echo_thinf = None + + self.topics_echo_que = Queue.Queue() + self.topics_echo_sum = 0 + thinf = th_start(self.topics_echo_show_th) + self.all_th_infs.append(thinf) + + self.refresh_topics_list() + + # waypoint + self.route_cmd_waypoint = [ Waypoint(0,0), Waypoint(0,0) ] + rospy.Subscriber('route_cmd', route_cmd, self.route_cmd_callback) + + # topic /xxx_stat + self.stat_dic = {} + for k in [ 'gnss', 'pmap', 'vmap', 'lf' ]: + self.stat_dic[k] = False + name = k + '_stat' + rospy.Subscriber(name, std_msgs.msg.Bool, self.stat_callback, callback_args=k) + + # top command thread setup + toprc = os.path.expanduser('~/.toprc') + backup = os.path.expanduser('~/.toprc-autoware-backup') + self.toprc_setup(toprc, backup) + + cpu_ibls = [ InfoBarLabel(self, 'CPU'+str(i)) for i in range(get_cpu_count())] + sz = sizer_wrap(cpu_ibls, wx.HORIZONTAL, 1, wx.EXPAND, 0) + self.sizer_cpuinfo.Add(sz, 8, wx.ALL | wx.EXPAND, 4) + + self.lb_top5 = [] + for i in range(5): + lb = wx.StaticText(self, wx.ID_ANY, '') + change_font_point_by_rate(lb, 0.75) + self.lb_top5.append(lb) + line = wx.StaticLine(self, wx.ID_ANY) + ibl = InfoBarLabel(self, 'Memory', bar_orient=wx.HORIZONTAL) + szr = sizer_wrap(self.lb_top5 + [ line, ibl ], flag=wx.EXPAND | wx.FIXED_MINSIZE) + self.sizer_cpuinfo.Add(szr, 2, wx.ALL | wx.EXPAND, 4) + + th_arg = { 'setting':self.status_dic.get('top_cmd_setting', {}), + 'cpu_ibls':cpu_ibls, 'mem_ibl':ibl, + 'toprc':toprc, 'backup':backup } + thinf = th_start(self.top_cmd_th, th_arg) + self.all_th_infs.append(thinf) + + # ps command thread + #thinf = th_start(self.ps_cmd_th, { 'interval':5 }) + #self.all_th_infs.append(thinf) + + # logout thread + interval = self.status_dic.get('gui_update_interval_ms', 100) * 0.001 + tc = self.text_ctrl_stdout + + thinf = th_start(self.logout_th, { 'que':self.log_que_stdout, 'interval':interval, 'tc':tc } ) + self.all_th_infs.append(thinf) + thinf = th_start(self.logout_th, { 'que':self.log_que_stderr, 'interval':interval, 'tc':tc } ) + self.all_th_infs.append(thinf) + thinf = th_start(self.logout_th, { 'que':self.log_que, 'interval':interval, 'tc':tc } ) + self.all_th_infs.append(thinf) + + if interval > 0: + thinf = th_start(self.logshow_th, { 'que':self.log_que_show , 'interval':interval , 'tc':tc }) + self.all_th_infs.append(thinf) + else: + self.checkbox_stdout.Enable(False) + tc.Enable(False) + + # mkdir + paths = [ os.environ['HOME'] + '/.autoware/data/tf', + os.environ['HOME'] + '/.autoware/data/map/pointcloud_map', + os.environ['HOME'] + '/.autoware/data/map/vector_map' ] + for path in paths: + if not os.path.exists(path): + subprocess.call([ 'mkdir', '-p', path ]) + + # icon + bm = scaled_bitmap(wx.Bitmap(rtmgr_src_dir() + 'images/autoware_logo_2_white.png'), 0.5) + icon = wx.EmptyIcon() + icon.CopyFromBitmap(bm) + self.SetIcon(icon) + + + wx.CallAfter( self.boot_booted_cmds ) + + def __do_layout(self): + pass + + def boot_booted_cmds(self): + if not self.load_dic.get('booted_cmds', {}).get('enable', False): + return + names = self.load_dic.get('booted_cmds', {}).get('names', []) + lst = [ ( name, self.cfg_dic( { 'name': name } ).get('obj') ) for name in names ] + lst = [ (name, obj) for (name, obj) in lst if obj ] + if not lst: + return + + choices = [ obj.GetLabel() if hasattr(obj, 'GetLabel') else name for (name, obj) in lst ] + dlg = wx.MultiChoiceDialog(self, 'boot command ?', '', choices) + dlg.SetSelections( range( len(names) ) ) + if dlg.ShowModal() != wx.ID_OK: + return + + for i in dlg.GetSelections(): + (_, obj) = lst[i] + post_evt_toggle_obj(self, obj, True) + + def OnClose(self, event): + if self.quit_select() != 'quit': + return + + # kill_all + for proc in self.all_procs[:]: # copy + (_, obj) = self.proc_to_cmd_dic_obj(proc) + self.launch_kill(False, 'dmy', proc, obj=obj) + + shutdown_proc_manager() + + shutdown_sh = self.get_autoware_dir() + '/ros/shutdown' + if os.path.exists(shutdown_sh): + os.system(shutdown_sh) + + for thinf in self.all_th_infs: + th_end(thinf) + + self.Destroy() + + def quit_select(self): + def timer_func(): + if self.quit_timer: + self.quit_timer = 'timeout' + evt = wx.PyCommandEvent( wx.EVT_CLOSE.typeId, self.GetId() ) + wx.PostEvent(self, evt) + + if not hasattr(self, 'quit_timer') or not self.quit_timer: + self.quit_timer = threading.Timer(2.0, timer_func) + self.quit_timer.start() + return 'not quit' + + if self.quit_timer == 'timeout': + self.save_param_yaml() + return 'quit' + + self.quit_timer.cancel() + self.quit_timer = None + lst = [ + ( 'Save and Quit', [ 'save', 'quit' ] ), + ( 'Save to param.yaml', [ 'save' ] ), + ( 'Quit without saving', [ 'quit' ] ), + ( 'Reload computing.yaml', [ 'reload' ] ), + ( self.get_booted_cmds_enable_msg()[1], [ 'toggle_booted_cmds' ] ), + ] + choices = [ s for (s, _) in lst ] + dlg = wx.SingleChoiceDialog(self, 'select command', '', choices) + if dlg.ShowModal() != wx.ID_OK: + return 'not quit' + + i = dlg.GetSelection() # index of choices + (_, f) = lst[i] + if 'save' in f: + self.save_param_yaml() + if 'reload' in f: + self.reload_computing_yaml() + if 'toggle_booted_cmds' in f: + self.toggle_booted_cmds() + return 'quit' if 'quit' in f else 'not quit' + + def save_param_yaml(self): + save_dic = {} + for (name, pdic) in self.load_dic.items(): + if pdic and pdic != {}: + prm = self.cfg_dic( {'name':name, 'pdic':pdic} ).get('param', {}) + no_saves = prm.get('no_save_vars', []) + pdic = pdic.copy() + for k in pdic.keys(): + if k in no_saves: + del pdic[k] + save_dic[name] = pdic + + names = [] + for proc in self.all_procs: + (_, obj) = self.proc_to_cmd_dic_obj(proc) + name = self.cfg_dic( { 'obj': obj } ).get('name') + names.append(name) + if 'booted_cmds' not in save_dic: + save_dic['booted_cmds'] = {} + save_dic.get('booted_cmds')['names'] = names + + if save_dic != {}: + dir = rtmgr_src_dir() + print('saving param.yaml') + f = open(dir + 'param.yaml', 'w') + s = yaml.dump(save_dic, default_flow_style=False) + #print('save\n', s) # for debug + f.write(s) + f.close() + + def reload_computing_yaml(self): + parent = self.tree_ctrl_0.GetParent() + sizer = self.tree_ctrl_0.GetContainingSizer() + + items = self.load_yaml('computing.yaml') + + # backup cmd_dic proc + cmd_dic = self.computing_cmd + to_name = lambda obj: next( ( d.get('name') for d in self.config_dic.values() if d.get('obj') == obj ), None ) + procs = [ ( to_name(obj), proc ) for (obj, (cmd, proc)) in cmd_dic.items() if proc ] + + # remove old tree ctrl + for i in range(2): + self.obj_get('tree_ctrl_' + str(i)).Destroy() + + # remove old params + names = [ prm.get('name') for prm in items.get('params', []) ] + for prm in self.params[:]: # copy + if prm.get('name') in names: + self.params.remove(prm) + + self.add_params(items.get('params', [])) + + # overwrite sys_gdic + old = self.sys_gdic + self.sys_gdic = items.get('sys_gui') + self.sys_gdic['update_func'] = self.update_func + for d in self.config_dic.values(): + if d.get('gdic') == old: + d['gdic'] = self.sys_gdic + + # listing update names + def subs_names(subs): + f2 = lambda s: subs_names( s.get('subs') ) if 'subs' in s else [ s.get('name') ] + f = lambda lst, s: lst + f2(s) + return reduce(f, subs, []) + + names = subs_names( items.get('subs') ) + names += items.get('buttons', {}).keys() + + # remove old data of name in config_dic + for (k, v) in self.config_dic.items(): + if v.get('name') in names: + self.config_dic.pop(k, None) + + # rebuild tree ctrl + cmd_dic.clear() + for i in range(2): + tree_ctrl = self.create_tree(parent, items['subs'][i], None, None, self.computing_cmd) + tree_ctrl.ExpandAll() + tree_ctrl.SetBackgroundColour(wx.NullColour) + setattr(self, 'tree_ctrl_' + str(i), tree_ctrl) + sizer.Add(tree_ctrl, 1, wx.EXPAND, 0) + + self.setup_buttons(items.get('buttons', {}), self.computing_cmd) + + # restore cmd_dic proc + to_obj = lambda name: next( ( d.get('obj') for d in self.config_dic.values() if d.get('name') == name ), None ) + for (name, proc) in procs: + obj = to_obj(name) + if obj and obj in cmd_dic: + cmd_dic[ obj ] = ( cmd_dic.get(obj)[0], proc ) + set_val(obj, True) + + parent.Layout() + + def toggle_booted_cmds(self): + (enable, msg) = self.get_booted_cmds_enable_msg() + style = wx.OK | wx.CANCEL | wx.ICON_QUESTION + dlg = wx.MessageDialog(self, msg, '', style) + if dlg.ShowModal() != wx.ID_OK: + return + if 'booted_cmds' not in self.load_dic: + self.load_dic['booted_cmds'] = {} + self.load_dic.get('booted_cmds')['enable'] = not enable + + def get_booted_cmds_enable_msg(self): + enable = self.load_dic.get('booted_cmds', {}).get('enable', False) + s = 'Enable' if not enable else 'Disable' + msg = '{} booted commands menu ?'.format(s) + return (enable, msg) + + def ROSCb(self, data): + print('recv topic msg : ' + data.data) + + r = rospy.Rate(10) + rospy.is_shutdown() + r.sleep() + self.pub.publish(data.data) + r.sleep() + + def setup_buttons(self, d, run_dic): + for (k,d2) in d.items(): + pfs = [ 'button_', 'checkbox_' ] + obj = next( (self.obj_get(pf+k) for pf in pfs if self.obj_get(pf+k)), None) + if not obj: + s = 'button_' + k + obj = StrValObj(s, False) + setattr(self, s, obj) + if not d2 or type(d2) is not dict: + continue + if 'run' in d2: + run_dic[obj] = (d2['run'], None) + set_tooltip(obj, d2) + gdic = self.gdic_get_1st(d2) + if 'param' in d2: + pdic = self.load_dic_pdic_setup(k, d2) + prm = self.get_param(d2.get('param')) + for var in prm.get('vars'): + name = var.get('name') + if name not in pdic and 'v' in var: + pdic[name] = var.get('v') + + for (name, v) in pdic.items(): + restore = eval( gdic.get(name, {}).get('restore', 'lambda a : None') ) + restore(v) + + self.add_cfg_info(obj, obj, k, pdic, gdic, False, prm) + + pnls = [ gdic.get(var.get('name'), {}).get('panel') for var in prm.get('vars') ] + for pnl in [ gdic.get('panel') ] + pnls: + if pnl: + self.set_param_panel(obj, eval_if_str(self, pnl)) + else: + self.add_cfg_info(obj, obj, k, None, gdic, False, None) + + def OnGear(self, event): + grp = { self.button_statchk_d : 1, + self.button_statchk_r : 2, + self.button_statchk_b : 3, + self.button_statchk_n : 4, self.button_statchk_p : 5 } - self.radio_action(event, grp.keys()) - v = grp.get(event.GetEventObject()) - if v is not None: - pub = rospy.Publisher('gear_cmd', gear_cmd, queue_size=10) - pub.publish(gear_cmd(gear=v)) - - def OnLamp(self, event): - pub = rospy.Publisher('lamp_cmd', LampCmd, queue_size=10) - msg = LampCmd() - msg.l = self.button_statchk_lamp_l.GetValue() - msg.r = self.button_statchk_lamp_r.GetValue() - pub.publish(msg) - - def OnIndi(self, event): - pub = rospy.Publisher('indicator_cmd', IndicatorCmd, queue_size=10) - msg = IndicatorCmd() - msg.l = self.button_statchk_indi_l.GetValue() - msg.r = self.button_statchk_indi_r.GetValue() - pub.publish(msg) - - def OnAutoPilot(self, event): - obj = event.GetEventObject() - self.alias_sync(obj) - v = obj.GetValue() - pub = rospy.Publisher('mode_cmd', mode_cmd, queue_size=10) - pub.publish(mode_cmd(mode=v)) - - - - def radio_action(self, event, grp): - push = event.GetEventObject() - for b in grp: - v = b.GetValue() - act = None - act = True if b is push and not v else act - act = False if b is not push and v else act - if act is not None: - set_val(b, act) - - def stat_label_off(self, obj): - qs_nms = [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ] - exec_time = self.qs_dic.get('exec_time', {}) - - gdic = self.obj_to_gdic(obj, {}) - msg = std_msgs.msg.Bool(False) - for k in gdic.get('stat_topic', []): - # exec_time off - if next( (dic for dic in exec_time.values() if k in dic), None): - self.exec_time_callback(std_msgs.msg.Float32(0), (k, 'data')) - else: - self.stat_callback(msg, k) - - # Quick Start tab, exec_time off - obj_nm = self.name_get(obj) - nm = next( (nm for nm in qs_nms if 'button_' + nm + '_qs' == obj_nm), None) - for key in exec_time.get(nm, {}): - self.exec_time_callback(std_msgs.msg.Float32(0), (key, 'data')) - - def route_cmd_callback(self, data): - self.route_cmd_waypoint = data.point - - def stat_callback(self, msg, k): - self.stat_dic[k] = msg.data - if k == 'pmap': - v = self.stat_dic.get(k) - wx.CallAfter(self.label_point_cloud.SetLabel, 'OK' if v else '') - if k in [ 'pmap', 'vmap' ]: - v = self.stat_dic.get('pmap') and self.stat_dic.get('vmap') - wx.CallAfter(self.label_map_qs.SetLabel, 'OK' if v else '') - - def exec_time_callback(self, msg, (key, attr)): - msec = int(getattr(msg, attr, 0)) - exec_time = self.qs_dic.get('exec_time', {}) - (nm, dic) = next( ( (nm, dic) for (nm, dic) in exec_time.items() if key in dic), None) - dic[ key ] = msec - lb = self.obj_get('label_' + nm + '_qs') - if lb: - sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) - wx.CallAfter(lb.SetLabel, str(sum)+' ms' if sum > 0 else '') - - # update Status tab - lb = '' - for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: - dic = exec_time.get(nm, {}) - sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) - if sum > 0: - s = nm + ' : ' + str(sum) + ' ms' - lb += s + '\n' - wx.CallAfter(self.label_node_time.SetLabel, lb) - wx.CallAfter(self.label_node_time.GetParent().FitInside) - - # - # Setup tab - # - def OnSetupLocalizer(self, event): - obj = self.button_setup_tf - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - self.update_func(pdic, gdic, prm) - - # - # Computing Tab - # - def OnTreeMotion(self, event): - tree = event.GetEventObject() - pt = event.GetPosition() - event.Skip() - (item, flags) = tree.HitTest(pt) - if flags & CT.TREE_HITTEST_ONITEMLABEL == 0: - return - text = item.GetData() - if not text: - return - x = item.GetX() - y = item.GetY() - w = item.GetWidth() - h = item.GetHeight() - (x, y) = tree.CalcScrolledPosition(x, y) - iw = tree.GetItemWindow(item) - w -= iw.GetSize()[0] if iw else 0 - if not wx.Rect(x, y, w, h).Contains(pt): - return - (x, y) = tree.ClientToScreen((x, y)) - self.tip_info = (tree, text, wx.Rect(x, y, w, h)) - if getattr(self, 'tip_timer', None) is None: - self.tip_timer = wx.Timer(self) - self.Bind(wx.EVT_TIMER, self.OnTipTimer, self.tip_timer) - self.tip_timer.Start(200, oneShot=True) - - def OnTipTimer(self, event): - if getattr(self, 'tip_info', None): - (tree, text, rect) = self.tip_info - (w, h) = self.GetSize() - wx.TipWindow(tree, text, maxLength=w, rectBound=rect) - - def OnTreeChecked(self, event): - self.OnChecked_obj(event.GetItem()) - - def OnChecked_obj(self, obj): - self.OnLaunchKill_obj(obj) - - def OnHyperlinked(self, event): - self.OnHyperlinked_obj(event.GetEventObject()) - - def OnHyperlinked_obj(self, obj): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - if pdic is None or prm is None: - return - dic_list_push(gdic, 'dialog_type', 'config') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') - - def obj_to_add_args(self, obj, msg_box=True): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - if pdic is None or prm is None: - return None - - if 'need_camera_info' in gdic.get('flags', []) and msg_box: - ids = self.camera_ids() - if ids: - var = self.get_var(prm, 'camera_id', {}) - var['choices'] = ids - - dic_list_push(gdic, 'dialog_type', 'sel_cam') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - dlg_ret = show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') - if dlg_ret != 0: - return False - else: - pdic['camera_id'] = '' - - if 'open_dialog' in gdic.get('flags', []) and msg_box: - dic_list_push(gdic, 'dialog_type', 'open') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - dlg_ret = show_modal(dlg) - dic_list_pop(gdic, 'dialog_type') - if dlg_ret != 0: - return False - - self.update_func(pdic, gdic, prm) - s = '' - - vars = [] - for var in prm.get('vars'): - cmd_param = var.get('cmd_param') - if cmd_param: - vars.append(var) - - for var in vars[:]: # copy - cmd_param = var.get('cmd_param') - if cmd_param.get('tail'): - vars.remove(var) - vars.append(var) - - for var in vars[:]: # copy - name = var.get('name') - flags = gdic.get(name, {}).get('flags', []) - if 'hide' in flags or 'disable' in flags: - vars.remove(var) - - for var in vars: - cmd_param = var.get('cmd_param') - name = var.get('name') - v = pdic.get(name) - if (v is None or v == '') and 'default' in cmd_param: - v = cmd_param.get('default') - if dic_eval_if_str(self, cmd_param, 'must') and (v is None or v == ''): - print 'cmd_param', name, 'is required' - if msg_box: - wx.MessageBox('cmd_param ' + name + ' is required') - return False - if dic_eval_if_str(self, cmd_param, 'only_enable') and not v: - continue - if dic_eval_if_str(self, cmd_param, 'only_disable') and v: - continue - name = cmd_param.get('var_name', name) - unpack = cmd_param.get('unpack') - if unpack is not None: - v = ' '.join( v.split(unpack) ) - add = '' - dash = cmd_param.get('dash') - if dash is not None: - add += dash + name - delim = cmd_param.get('delim') - if delim is not None: - str_v = str(v) - if var.get('kind') is None: - str_v = adjust_num_str(str_v) - if var.get('kind') == 'path': - str_v = path_expand_cmd(str_v) - str_v = os.path.expandvars(os.path.expanduser(str_v)) - - relpath_from = var.get('relpath_from') - if relpath_from: - relpath_from = path_expand_cmd(relpath_from) - relpath_from = os.path.expandvars(os.path.expanduser(relpath_from)) - str_v = os.path.relpath(str_v, relpath_from) - add += delim + str_v - if add != '': - s += add + ' ' - return s.strip(' ').split(' ') if s != '' else None - - def obj_to_pdic_gdic_prm(self, obj, sys=False): - info = self.config_dic.get(obj) - if info is None: - sys_prm = self.get_param('sys') - prm_chk = lambda prm : prm is sys_prm if sys else prm is not sys_prm - info = next( ( v for v in self.config_dic.values() if v.get('obj') is obj and prm_chk(v.get('param')) ), None) - if info is None: - return (None, None, None) - pdic = info.get('pdic') - prm = info.get('param') - gdic = info.get('gdic') - return (pdic, gdic, prm) - - def obj_to_gdic(self, obj, def_ret=None): - (_, gdic, _) = self.obj_to_pdic_gdic_prm(obj) if obj else (None, None, None) - return gdic if gdic else def_ret - - def cfg_obj_dic(self, arg_dic, sys=False, def_ret=(None,{})): - sys_prm = self.get_param('sys') - prm_chk = { - True : (lambda prm : prm is sys_prm), - False : (lambda prm : prm is not sys_prm), - None : (lambda prm : True) }.get(sys) - arg_dic_chk = lambda dic: all( [ dic.get(k) == v for (k,v) in arg_dic.items() ] ) - return next( ( (cfg_obj, dic) for (cfg_obj, dic) in self.config_dic.items() \ - if arg_dic_chk(dic) and prm_chk(dic.get('param')) ), def_ret) - - def cfg_dic(self, arg_dic, sys=False, def_ret={}): - (_, dic) = self.cfg_obj_dic(arg_dic, sys=sys, def_ret=(None, def_ret)) - return dic - - def cfg_prm_to_obj(self, arg_dic, sys=False): - return self.cfg_dic(arg_dic, sys=sys).get('obj') - - def name_to_pdic_gdic_prm(self, name, sys=False): - d = self.cfg_dic( {'name':name}, sys=sys ) - return ( d.get('pdic'), d.get('gdic'), d.get('param') ) - - def update_func(self, pdic, gdic, prm): - for var in prm.get('vars', []): - name = var.get('name') - gdic_v = gdic.get(name, {}) - func = gdic_v.get('func') - if func is None and name in pdic: - continue - v = var.get('v') - if func is not None: - v = eval(func) if type(func) is str else func() - pdic[ name ] = v - - hook = gdic_v.get('update_hook') - if hook: - hook(v) - hook_var = gdic_v.get('hook_var', {}) - every_time = 'every_time' in hook_var.get('flags', []) - if var == gdic.get('update_func_arg_var') or every_time: - hook = hook_var.get('hook') - if hook: - hook(hook_var.get('args', {})) - - if 'pub' in prm: - self.publish_param_topic(pdic, prm) - self.rosparam_set(pdic, prm) - self.update_depend_enable(pdic, gdic, prm) - - d = self.cfg_dic( {'pdic':pdic, 'gdic':gdic, 'param':prm}, sys=True ) - self.update_proc_cpu(d.get('obj'), d.get('pdic'), d.get('param')) - - def update_proc_cpu(self, obj, pdic=None, prm=None): - if obj is None or not obj.GetValue(): - return - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) - if proc is None: - return - if pdic is None or prm is None: - (pdic, _, prm) = self.obj_to_pdic_gdic_prm(obj, sys=True) - - cpu_chks = self.param_value_get(pdic, prm, 'cpu_chks') - cpu_chks = cpu_chks if cpu_chks else [ True for i in range(get_cpu_count()) ] - cpus = [ i for i in range(get_cpu_count()) if cpu_chks[i] ] - nice = self.param_value_get(pdic, prm, 'nice', 0) - - d = { 'OTHER':SCHED_OTHER, 'FIFO':SCHED_FIFO, 'RR':SCHED_RR } - policy = SCHED_OTHER - priority = 0 - if self.param_value_get(pdic, prm, 'real_time', False): - policy = d.get(self.param_value_get(pdic, prm, 'policy', 'FIFO'), SCHED_FIFO) - priority = self.param_value_get(pdic, prm, 'prio', 0) - - procs = [ proc ] + get_proc_children(proc, r=True) - for proc in procs: - print 'pid={}'.format(proc.pid) - if get_proc_nice(proc) != nice: - print 'nice {} -> {}'.format(get_proc_nice(proc), nice) - if set_process_nice(proc, nice) is False: - print 'Err set_process_nice()' - if get_proc_cpu_affinity(proc) != cpus: - print 'cpus {} -> {}'.format(get_proc_cpu_affinity(proc), cpus) - if set_process_cpu_affinity(proc, cpus) is False: - print 'Err set_process_cpu_affinity()' - - policy_str = next( (k for (k,v) in d.items() if v == policy), '?') - print 'sched policy={} prio={}'.format(policy_str, priority) - if set_scheduling_policy(proc, policy, priority) is False: - print 'Err scheduling_policy()' - - def param_value_get(self, pdic, prm, name, def_ret=None): - def_ret = self.param_default_value_get(prm, name, def_ret) - return pdic.get(name, def_ret) if pdic else def_ret - - def param_default_value_get(self, prm, name, def_ret=None): - return next( (var.get('v') for var in prm.get('vars') if var.get('name') == name ), def_ret) \ - if prm else def_ret - - def update_depend_enable(self, pdic, gdic, prm): - for var in prm.get('vars', []): - name = var.get('name') - gdic_v = gdic.get(name, {}) - depend = gdic_v.get('depend') - if depend is None: - continue - vp = gdic_v.get('var') - if vp is None: - continue - v = pdic.get(depend) - if v is None: - continue - depend_bool = eval( gdic_v.get('depend_bool', 'lambda v : bool(v)') ) - v = depend_bool(v) - enables_set(vp, 'depend', v) - - def publish_param_topic(self, pdic, prm): - pub = prm['pub'] - klass_msg = globals()[ prm['msg'] ] - msg = klass_msg() - - for (name, v) in pdic.items(): - if prm.get('topic') == '/twist_cmd' and name == 'twist.angular.z': - v = -v - (obj, attr) = msg_path_to_obj_attr(msg, name) - if obj and attr in obj.__slots__: - type_str = obj._slot_types[ obj.__slots__.index(attr) ] - setattr(obj, attr, str_to_rosval(v, type_str, v)) - - if 'stamp' in prm.get('flags', []): - (obj, attr) = msg_path_to_obj_attr(msg, 'header.stamp') - setattr(obj, attr, rospy.get_rostime()) - - pub.publish(msg) - - def rosparam_set(self, pdic, prm): - rosparams = None - for var in prm.get('vars', []): - name = var['name'] - if 'rosparam' not in var or name not in pdic: - continue - rosparam = var['rosparam'] - v = pdic.get(name) - v = str(v) - cvdic = { 'True':'true', 'False':'false' } - if v in cvdic: - v = cvdic.get(v) - if rosparams is None: - cmd = [ 'rosparam', 'list' ] - rosparams = subprocess.check_output(cmd).strip().split('\n') - nm = rosparam - nm = ('/' if len(nm) > 0 and nm[0] != '/' else '') + nm - exist = nm in rosparams - if exist: - cmd = [ 'rosparam', 'get', rosparam ] - ov = subprocess.check_output(cmd).strip() - if ov == v: - continue - elif v == '': - continue - cmd = [ 'rosparam', 'set', rosparam, v ] if v != '' else [ 'rosparam', 'delete', rosparam ] - print(cmd) - subprocess.call(cmd) - - # - # Sensing Tab - # - def OnSensingDriver(self, event): - self.OnChecked_obj(event.GetEventObject()) - - def OnROSbagRecord(self, event): - self.dlg_rosbag_record.show() - obj = event.GetEventObject() - set_val(obj, False) - - def create_checkboxes(self, dic, panel, sizer, probe_dic, run_dic, bind_handler): - if 'name' not in dic: - return - obj = None - bdr_flg = wx.ALL - if 'subs' in dic: - lst = [] - for d in dic['subs']: - self.create_checkboxes(d, panel, lst, probe_dic, run_dic, bind_handler) - if dic['name']: - obj = static_box_sizer(panel, dic.get('name')) - set_tooltip(obj.GetStaticBox(), dic) - else: - obj = wx.BoxSizer(wx.VERTICAL) - for (o, flg) in lst: - obj.Add(o, 0, wx.EXPAND | flg, 4) - else: - obj = wx.CheckBox(panel, wx.ID_ANY, dic['name']) - set_tooltip(obj, dic) - self.Bind(wx.EVT_CHECKBOX, bind_handler, obj) - bdr_flg = wx.LEFT | wx.RIGHT - if 'probe' in dic: - probe_dic[obj] = (dic['probe'], None) - if 'run' in dic: - run_dic[obj] = (dic['run'], None) - if 'param' in dic: - obj = self.add_config_link(dic, panel, obj) - else: - gdic = self.gdic_get_1st(dic) - self.add_cfg_info(obj, obj, dic.get('name'), None, gdic, False, None) - if sizer is not None: - sizer.append((obj, bdr_flg)) - else: - panel.SetSizer(obj) - - def add_config_link(self, dic, panel, obj): - cfg_obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, '[config]', '') - fix_link_color(cfg_obj) - self.Bind(wx.EVT_HYPERLINK, self.OnConfig, cfg_obj) - add_objs = (obj, wx.StaticText(panel, wx.ID_ANY, ' '), cfg_obj) - hszr = sizer_wrap(add_objs, wx.HORIZONTAL) - name = dic['name'] - pdic = self.load_dic_pdic_setup(name, dic) - gdic = self.gdic_get_1st(dic) - prm = self.get_param(dic.get('param')) - self.add_cfg_info(cfg_obj, obj, name, pdic, gdic, True, prm) - return hszr - - def camera_ids(self): - if self.button_synchronization.GetValue(): - return [] - cmd = "rostopic list | sed -n 's|/image_raw||p' | sed 's/^$/\//'" - return subprocess.check_output(cmd, shell=True).strip().split() - - def cam_id_to_obj(self, cam_id, v): - cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) - if cam_id_obj is None: - cam_id_obj = StrValObj(cam_id, v) - cam_id_obj.SetValue(v) - return cam_id_obj - - def camera_id_hook(self, args): - new_id = args.get('pdic', {}).get('camera_id', '') - ids = args.get('ids', []) - if new_id not in ids: - return - idx = ids.index(new_id) - - pp = args.get('param_panel') - if pp: - pp.detach_func() - dlg = args.get('dlg') - if dlg: - dlg.EndModal(idx + 100) - - def OnCalibrationPublisher(self, event): - obj = event.GetEventObject() - (_, gdic_org, prm) = self.obj_to_pdic_gdic_prm(obj) - if obj.GetValue(): - gdic_org['ids'] = self.camera_ids() - ids = gdic_org.get('ids', []) - - if ids == []: - self.OnLaunchKill(event) - return - # - # setup - # - (cmd_dic, cmd, _) = self.obj_to_cmd_dic_cmd_proc(obj) - - flags = gdic_org.get('flags', [])[:] # copy - if 'open_dialog' in flags: - flags.remove('open_dialog') - - pdic_baks = {} - for cam_id in ids: - (pdic_a, gdic_a, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic = pdic_a if pdic_a else self.load_dic_pdic_setup(cam_id, {}) - pdic['camera_id'] = cam_id - pdic_baks[cam_id] = pdic.copy() - gdic = gdic_a if gdic_a else gdic_org.copy() - gdic['flags'] = flags - - cam_id_obj = self.cam_id_to_obj(cam_id, obj.GetValue()) - if not hasattr(cam_id_obj, 'enables_proxy'): - cam_id_obj.enables_proxy = (obj, cam_id_obj.s) - - if not pdic_a or not gdic_a: - self.add_cfg_info(cam_id_obj, cam_id_obj, cam_id, pdic, gdic, False, prm) - if not cam_id_obj in cmd_dic: - cmd_dic[ cam_id_obj ] = (cmd, None) - - var = self.get_var(prm, 'camera_id', {}) - var['choices'] = ids - - # - # Dialog - # - cam_id = ids[0] - while obj.GetValue(): - (pdic, gdic, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic['camera_id'] = cam_id - dic_list_push(gdic, 'dialog_type', 'open2') - klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) - dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) - - gdic_v = dic_getset(gdic, 'camera_id', {}) - args = { 'pdic':pdic, 'ids':ids, 'param_panel':gdic.get('param_panel'), 'dlg':dlg } - gdic_v['hook_var'] = { 'hook':self.camera_id_hook, 'args':args } - - dlg_ret = show_modal(dlg) - - dic_list_pop(gdic, 'dialog_type') - pdic['camera_id'] = cam_id # restore - - if dlg_ret == 0: # OK - break - - idx = dlg_ret - 100 - if idx < 0 or len(ids) <= idx: # Cancel - for cam_id in ids: - (pdic, _, _) = self.name_to_pdic_gdic_prm(cam_id) - pdic.update(pdic_baks.get(cam_id)) - set_val(obj, False) - return - - # Menu changed - cam_id = ids[idx] - - # - # Launch / Kill - # - for cam_id in ids: - cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) - (pdic, _, _) = self.obj_to_pdic_gdic_prm(cam_id_obj) - pdic['solo_camera'] = False - #print '@', cam_id, cam_id_obj.GetValue() - self.OnLaunchKill_obj(cam_id_obj) - - # - # Simulation Tab - # - def rosbag_info_hook(self, v): - if not v: - return - th_start(self.rosbag_info_hook_th, {'v':v} ) - - def rosbag_info_hook_th(self, ev, v): # thread - err = subprocess.STDOUT - s = subprocess.check_output([ 'rosbag', 'info', v ], stderr=err).strip() - wx.CallAfter(self.label_rosbag_info.SetLabel, s) - wx.CallAfter(self.label_rosbag_info.GetParent().FitInside) - - # - # Data Tab - # - - # - # Stauts tab - # - - def info_col(self, v, v_yellow, v_red, col_normal, col_red): - if v < v_yellow: - return col_normal - if v < v_red: - (nr,ng,nb) = col_normal - (rr,rg,rb) = col_red - return ( (nr+rr)/2, (ng+rg)/2, (nb+rb)/2 ) - return col_red - - def mem_kb_info(self): - lines = subprocess.check_output('cat /proc/meminfo', shell=True).strip().split(os.linesep) - cvt = lambda (k, v): ( k.replace(':', ''), int(v) ) - d = dict( map( lambda s: cvt( filter( lambda s: s!='kB', s.split() ) ), lines ) ) - total = d.get('MemTotal') - free = d.get('MemFree') + d.get('Buffers') + d.get('Cached') - return (total, total - free) - - def toprc_create(self): - (child_pid, fd) = pty.fork() - if child_pid == 0: # child - os.execvp('top', ['top']) - else: #parent - sec = 0.2 - for s in ['1', 'c', 'W', 'q']: - time.sleep(sec) - os.write(fd, s) - - def toprc_setup(self, toprc, backup): - if os.path.exists(toprc): - os.rename(toprc, backup) - self.toprc_create() - - def toprc_restore(self, toprc, backup): - os.remove(toprc) - if os.path.exists(backup): - os.rename(backup, toprc) - - # top command thread - def top_cmd_th(self, ev, setting, cpu_ibls, mem_ibl, toprc, backup): - interval = setting.get('interval', 3) - alert_level = setting.get('alert_level', {}) - rate_per_cpu = alert_level.get('rate_per_cpu', 80) - rate_per_cpu_yellow = alert_level.get('rate_per_cpu_yellow', 80) - rate_cpu = alert_level.get('rate_cpu', 80) - rate_mem = alert_level.get('rate_mem', 80) - rate_mem_yellow = alert_level.get('rate_mem_yellow', 80) - - for ibl in cpu_ibls: - ibl.lmt_bar_prg = rate_per_cpu - mem_ibl.lmt_bar_prg = rate_mem - - alerted = False - cpu_n = get_cpu_count() - - while not ev.wait(interval): - s = subprocess.check_output(['sh', '-c', 'env COLUMNS=512 top -b -n 2 -d 0.1']).strip() - i = s.rfind('\ntop -') + 1 - s = s[i:] - wx.CallAfter(self.label_top_cmd.SetLabel, s) - wx.CallAfter(self.label_top_cmd.GetParent().FitInside) - - k = '%Cpu' - fv_sum = 0 - i = 0 - for t in s.split('\n'): - if t[:len(k)] != k: - continue - lst = t[1:].split() - v = lst[1] if lst[1] != ':' else lst[2] - if v[0] == ':': - v = v[1:] - fv = str_to_float(v) - col = self.info_col(fv, rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) - - if i < cpu_n: - ibl = cpu_ibls[i] - wx.CallAfter(ibl.lb_set, v+'%', col) - wx.CallAfter(ibl.bar_set, int(fv)) - fv_sum += fv - i += 1 - - k = 'KiB Mem:' - (total, used) = self.mem_kb_info() - rate = 100 * used / total - - for u in [ 'KB', 'MB', 'GB', 'TB' ]: - if total <= 10 * 1024 or used <= 10: - break - total /= 1024 - used /= 1024 - - col = self.info_col(rate, rate_mem_yellow, rate_mem, (64,64,64), (200,0,0)) - tx = str(used) + u + '/' + str(total) + u + '(' + str(rate) + '%)' - - wx.CallAfter(mem_ibl.lb_set, tx, col) - wx.CallAfter(mem_ibl.bar_set, rate) - - is_alert = (fv_sum >= rate_cpu * cpu_n) or rate >= rate_mem - - # --> for test - if os.path.exists('/tmp/alert_test_on'): - is_alert = True - if os.path.exists('/tmp/alert_test_off'): - is_alert = False - # <-- for test - - if is_alert and not alerted: - thinf = th_start(self.alert_th, {'bgcol':(200,50,50)}) - alerted = True - if not is_alert and alerted: - th_end(thinf) - alerted = False - - # top5 - i = s.find('\n\n') + 2 - lst = s[i:].split('\n') - hd = lst[0] - top5 = lst[1:1+5] - - i = hd.rfind('COMMAND') - cmds = [ line[i:].split(' ')[0] for line in top5 ] - - i = hd.find('%CPU') - loads = [ line[i-1:].strip().split(' ')[0] for line in top5 ] - - for (lb, cmd, load) in zip(self.lb_top5, cmds, loads): - col = self.info_col(str_to_float(load), rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) - wx.CallAfter(lb.SetForegroundColour, col) - wx.CallAfter(lb.SetLabel, cmd + ' (' + load + ' %CPU)') - - self.toprc_restore(toprc, backup) - - def alert_th(self, bgcol, ev): - wx.CallAfter(self.RequestUserAttention) - c = bgcol - o = wx.NullColour - while not ev.wait(0.5): - for col in [ c, o, c, o, c, o ]: - wx.CallAfter(self.set_bg_all_tabs, col) - time.sleep(0.05) - - def log_th(self, file, que, ev): - while not ev.wait(0): - s = file.readline() - if not s: - break - que.put(s) - - def logout_th(self, que, interval, tc, ev): - if que == self.log_que_stdout or que == self.log_que_stderr: - while not ev.wait(0): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - self.log_que.put(s) - - if interval <= 0: - continue - - ckbox = self.checkbox_stdout if que == self.log_que_stdout else self.checkbox_stderr - if ckbox.GetValue(): - self.log_que_show.put( cut_esc(s) ) - - else: # == self.log_que - f = None - path = self.status_dic.get('log_path') - is_syslog = (path == 'syslog') - - if is_syslog: - ident = sys.argv[0].split('/')[-1] - syslog.openlog(ident, syslog.LOG_PID | syslog.LOG_CONS) - elif path: - path = os.path.expandvars(os.path.expanduser(path)) - f = open(path, 'a') if path else None - - while not ev.wait(0): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - print s.strip() - sys.stdout.flush() - - s = cut_esc(s) - if is_syslog: - syslog.syslog(s) - elif f: - f.write(s) - f.flush() - if is_syslog: - syslog.closelog() - if f: - f.close() - - def logshow_th(self, que, interval, tc, ev): - while not ev.wait(interval): - try: - s = que.get(timeout=1) - except Queue.Empty: - continue - wx.CallAfter(append_tc_limit, tc, s) - - # que clear - if self.checkbox_stdout.GetValue() is False and \ - self.checkbox_stderr.GetValue() is False and \ - que.qsize() > 0: - que_clear(que) - wx.CallAfter(tc.Clear) - - # - # for Topics tab - # - def OnRefreshTopics(self, event): - self.refresh_topics_list() - - def refresh_topics_list(self): - lst = subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') - panel = self.panel_topics_list - szr = self.sizer_topics_list - for obj in self.topics_list: - szr.Remove(obj) - obj.Destroy() - self.topics_list = [] - for topic in lst: - obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, topic, '') - self.Bind(wx.EVT_HYPERLINK, self.OnTopicLink, obj) - szr.Add(obj, 0, wx.LEFT, 4) - fix_link_color(obj) - self.topics_list.append(obj) - szr.Layout() - panel.SetVirtualSize(szr.GetMinSize()) - - # info clear - lb = self.label_topics_info - lb.SetLabel('') - - # echo clear - self.topics_proc_th_end() - - # wait que clear - while self.topics_echo_que.qsize() > 0: - time.sleep(0.1) - - tc = self.text_ctrl_topics_echo - tc.Enable(False) - wx.CallAfter(tc.Clear) - wx.CallAfter(tc.Enable, True) - self.topics_echo_sum = 0 - self.topic_echo_curr_topic = None - - def OnEcho(self, event): - if self.checkbox_topics_echo.GetValue() and self.topic_echo_curr_topic: - self.topics_proc_th_start(self.topic_echo_curr_topic) - else: - self.topics_proc_th_end() - - def OnTopicLink(self, event): - obj = event.GetEventObject() - topic = obj.GetLabel() - self.topic_echo_curr_topic = topic - - # info - info = subprocess.check_output([ 'rostopic', 'info', topic ]).strip() - lb = self.label_topics_info - lb.SetLabel(info) - lb.GetParent().FitInside() - - # echo - self.topics_proc_th_end() - if self.checkbox_topics_echo.GetValue(): - self.topics_proc_th_start(topic) - - def topics_proc_th_start(self, topic): - out = subprocess.PIPE - err = subprocess.STDOUT - self.topics_echo_proc = psutil.Popen([ 'rostopic', 'echo', topic ], stdout=out, stderr=err) - - self.topics_echo_thinf = th_start(self.topics_echo_th) - - def topics_proc_th_end(self): - thinf = self.topics_echo_thinf - if thinf: - th_end(thinf) - self.topics_echo_thinf = None - - proc = self.topics_echo_proc - if proc: - terminate_children(proc) - terminate(proc) - #proc.wait() - self.topics_echo_proc = None - - def topics_echo_th(self, ev): - if not self.topics_echo_proc: - return - file = self.topics_echo_proc.stdout - fl = fcntl.fcntl(file.fileno(), fcntl.F_GETFL) - fcntl.fcntl(file.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) - - while not ev.wait(0): - try: - s = file.read(1) - except: - continue - if not s: - break - if self.checkbox_topics_echo.GetValue(): - self.topics_echo_que.put(s) - - que_clear(self.topics_echo_que) - - def topics_echo_show_th(self, ev): - que = self.topics_echo_que - interval = self.topics_dic.get('gui_update_interval_ms', 100) * 0.001 - chars_limit = self.topics_dic.get('gui_chars_limit', 10000) - tc = self.text_ctrl_topics_echo - while not ev.wait(interval): - qsz = que.qsize() - if qsz <= 0: - continue - if qsz > chars_limit: - over = qsz - chars_limit - for i in range(over): - try: - que.get(timeout=1) - except Queue.Empty: - break - qsz = chars_limit - arr = [] - for i in range(qsz): - try: - s = que.get(timeout=1) - except Queue.Empty: - s = '' - arr.append(s) - s = ''.join(arr) - - self.topics_echo_sum += len(s) - rm_chars = 0 - if self.topics_echo_sum > chars_limit: - rm_chars = self.topics_echo_sum - chars_limit - self.topics_echo_sum = chars_limit - - if self.checkbox_topics_echo.GetValue(): - wx.CallAfter(append_tc_limit, tc, s, rm_chars) + self.radio_action(event, grp.keys()) + v = grp.get(event.GetEventObject()) + if v is not None: + pub = rospy.Publisher('gear_cmd', gear_cmd, queue_size=10) + pub.publish(gear_cmd(gear=v)) + + def OnLamp(self, event): + pub = rospy.Publisher('lamp_cmd', LampCmd, queue_size=10) + msg = LampCmd() + msg.l = self.button_statchk_lamp_l.GetValue() + msg.r = self.button_statchk_lamp_r.GetValue() + pub.publish(msg) + + def OnIndi(self, event): + pub = rospy.Publisher('indicator_cmd', IndicatorCmd, queue_size=10) + msg = IndicatorCmd() + msg.l = self.button_statchk_indi_l.GetValue() + msg.r = self.button_statchk_indi_r.GetValue() + pub.publish(msg) + + def OnAutoPilot(self, event): + obj = event.GetEventObject() + self.alias_sync(obj) + v = obj.GetValue() + pub = rospy.Publisher('mode_cmd', mode_cmd, queue_size=10) + pub.publish(mode_cmd(mode=v)) + + + + def radio_action(self, event, grp): + push = event.GetEventObject() + for b in grp: + v = b.GetValue() + act = None + act = True if b is push and not v else act + act = False if b is not push and v else act + if act is not None: + set_val(b, act) + + def stat_label_off(self, obj): + qs_nms = [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ] + exec_time = self.qs_dic.get('exec_time', {}) + + gdic = self.obj_to_gdic(obj, {}) + msg = std_msgs.msg.Bool(False) + for k in gdic.get('stat_topic', []): + # exec_time off + if next( (dic for dic in exec_time.values() if k in dic), None): + self.exec_time_callback(std_msgs.msg.Float32(0), (k, 'data')) + else: + self.stat_callback(msg, k) + + # Quick Start tab, exec_time off + obj_nm = self.name_get(obj) + nm = next( (nm for nm in qs_nms if 'button_' + nm + '_qs' == obj_nm), None) + for key in exec_time.get(nm, {}): + self.exec_time_callback(std_msgs.msg.Float32(0), (key, 'data')) + + def route_cmd_callback(self, data): + self.route_cmd_waypoint = data.point + + def stat_callback(self, msg, k): + self.stat_dic[k] = msg.data + if k == 'pmap': + v = self.stat_dic.get(k) + wx.CallAfter(self.label_point_cloud.SetLabel, 'OK' if v else '') + if k in [ 'pmap', 'vmap' ]: + v = self.stat_dic.get('pmap') and self.stat_dic.get('vmap') + wx.CallAfter(self.label_map_qs.SetLabel, 'OK' if v else '') + + def exec_time_callback(self, msg, key_attr): + key, attr = key_attr + msec = int(getattr(msg, attr, 0)) + exec_time = self.qs_dic.get('exec_time', {}) + (nm, dic) = next( ( (nm, dic) for (nm, dic) in exec_time.items() if key in dic), None) + dic[ key ] = msec + lb = self.obj_get('label_' + nm + '_qs') + if lb: + sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) + wx.CallAfter(lb.SetLabel, str(sum)+' ms' if sum > 0 else '') + + # update Status tab + lb = '' + for nm in [ 'map', 'sensing', 'localization', 'detection', 'mission_planning', 'motion_planning' ]: + dic = exec_time.get(nm, {}) + sum = reduce( lambda a,b:a+(b if b else 0), dic.values(), 0 ) + if sum > 0: + s = nm + ' : ' + str(sum) + ' ms' + lb += s + '\n' + wx.CallAfter(self.label_node_time.SetLabel, lb) + wx.CallAfter(self.label_node_time.GetParent().FitInside) + + # + # Setup tab + # + def OnSetupLocalizer(self, event): + obj = self.button_setup_tf + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + self.update_func(pdic, gdic, prm) + + # + # Computing Tab + # + def OnTreeMotion(self, event): + tree = event.GetEventObject() + pt = event.GetPosition() + event.Skip() + (item, flags) = tree.HitTest(pt) + if flags & CT.TREE_HITTEST_ONITEMLABEL == 0: + return + text = item.GetData() + if not text: + return + x = item.GetX() + y = item.GetY() + w = item.GetWidth() + h = item.GetHeight() + (x, y) = tree.CalcScrolledPosition(x, y) + iw = tree.GetItemWindow(item) + w -= iw.GetSize()[0] if iw else 0 + if not wx.Rect(x, y, w, h).Contains(pt): + return + (x, y) = tree.ClientToScreen((x, y)) + self.tip_info = (tree, text, wx.Rect(x, y, w, h)) + if getattr(self, 'tip_timer', None) is None: + self.tip_timer = wx.Timer(self) + self.Bind(wx.EVT_TIMER, self.OnTipTimer, self.tip_timer) + self.tip_timer.Start(200, oneShot=True) + + def OnTipTimer(self, event): + if getattr(self, 'tip_info', None): + (tree, text, rect) = self.tip_info + (w, h) = self.GetSize() + wx.TipWindow(tree, text, maxLength=w, rectBound=rect) + + def OnTreeChecked(self, event): + self.OnChecked_obj(event.GetItem()) + + def OnChecked_obj(self, obj): + self.OnLaunchKill_obj(obj) + + def OnHyperlinked(self, event): + self.OnHyperlinked_obj(event.GetEventObject()) + + def OnHyperlinked_obj(self, obj): + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + if pdic is None or prm is None: + return + dic_list_push(gdic, 'dialog_type', 'config') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') + + def obj_to_add_args(self, obj, msg_box=True): + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + if pdic is None or prm is None: + return None + + if 'need_camera_info' in gdic.get('flags', []) and msg_box: + ids = self.camera_ids() + if ids: + var = self.get_var(prm, 'camera_id', {}) + var['choices'] = ids + + dic_list_push(gdic, 'dialog_type', 'sel_cam') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + dlg_ret = show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') + if dlg_ret != 0: + return False + else: + pdic['camera_id'] = '' + + if 'open_dialog' in gdic.get('flags', []) and msg_box: + dic_list_push(gdic, 'dialog_type', 'open') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + dlg_ret = show_modal(dlg) + dic_list_pop(gdic, 'dialog_type') + if dlg_ret != 0: + return False + + self.update_func(pdic, gdic, prm) + s = '' + + vars = [] + for var in prm.get('vars'): + cmd_param = var.get('cmd_param') + if cmd_param: + vars.append(var) + + for var in vars[:]: # copy + cmd_param = var.get('cmd_param') + if cmd_param.get('tail'): + vars.remove(var) + vars.append(var) + + for var in vars[:]: # copy + name = var.get('name') + flags = gdic.get(name, {}).get('flags', []) + if 'hide' in flags or 'disable' in flags: + vars.remove(var) + + for var in vars: + cmd_param = var.get('cmd_param') + name = var.get('name') + v = pdic.get(name) + if (v is None or v == '') and 'default' in cmd_param: + v = cmd_param.get('default') + if dic_eval_if_str(self, cmd_param, 'must') and (v is None or v == ''): + print('cmd_param', name, 'is required') + if msg_box: + wx.MessageBox('cmd_param ' + name + ' is required') + return False + if dic_eval_if_str(self, cmd_param, 'only_enable') and not v: + continue + if dic_eval_if_str(self, cmd_param, 'only_disable') and v: + continue + name = cmd_param.get('var_name', name) + unpack = cmd_param.get('unpack') + if unpack is not None: + v = ' '.join( v.split(unpack) ) + add = '' + dash = cmd_param.get('dash') + if dash is not None: + add += dash + name + delim = cmd_param.get('delim') + if delim is not None: + str_v = str(v) + if var.get('kind') is None: + str_v = adjust_num_str(str_v) + if var.get('kind') == 'path': + str_v = path_expand_cmd(str_v) + str_v = os.path.expandvars(os.path.expanduser(str_v)) + + relpath_from = var.get('relpath_from') + if relpath_from: + relpath_from = path_expand_cmd(relpath_from) + relpath_from = os.path.expandvars(os.path.expanduser(relpath_from)) + str_v = os.path.relpath(str_v, relpath_from) + add += delim + str_v + if add != '': + s += add + ' ' + return s.strip(' ').split(' ') if s != '' else None + + def obj_to_pdic_gdic_prm(self, obj, sys=False): + info = self.config_dic.get(obj) + if info is None: + sys_prm = self.get_param('sys') + prm_chk = lambda prm : prm is sys_prm if sys else prm is not sys_prm + info = next( ( v for v in self.config_dic.values() if v.get('obj') is obj and prm_chk(v.get('param')) ), None) + if info is None: + return (None, None, None) + pdic = info.get('pdic') + prm = info.get('param') + gdic = info.get('gdic') + return (pdic, gdic, prm) + + def obj_to_gdic(self, obj, def_ret=None): + (_, gdic, _) = self.obj_to_pdic_gdic_prm(obj) if obj else (None, None, None) + return gdic if gdic else def_ret + + def cfg_obj_dic(self, arg_dic, sys=False, def_ret=(None,{})): + sys_prm = self.get_param('sys') + prm_chk = { + True : (lambda prm : prm is sys_prm), + False : (lambda prm : prm is not sys_prm), + None : (lambda prm : True) }.get(sys) + arg_dic_chk = lambda dic: all( [ dic.get(k) == v for (k,v) in arg_dic.items() ] ) + return next( ( (cfg_obj, dic) for (cfg_obj, dic) in self.config_dic.items() \ + if arg_dic_chk(dic) and prm_chk(dic.get('param')) ), def_ret) + + def cfg_dic(self, arg_dic, sys=False, def_ret={}): + (_, dic) = self.cfg_obj_dic(arg_dic, sys=sys, def_ret=(None, def_ret)) + return dic + + def cfg_prm_to_obj(self, arg_dic, sys=False): + return self.cfg_dic(arg_dic, sys=sys).get('obj') + + def name_to_pdic_gdic_prm(self, name, sys=False): + d = self.cfg_dic( {'name':name}, sys=sys ) + return ( d.get('pdic'), d.get('gdic'), d.get('param') ) + + def update_func(self, pdic, gdic, prm): + for var in prm.get('vars', []): + name = var.get('name') + gdic_v = gdic.get(name, {}) + func = gdic_v.get('func') + if func is None and name in pdic: + continue + v = var.get('v') + if func is not None: + v = eval(func) if type(func) is str else func() + pdic[ name ] = v + + hook = gdic_v.get('update_hook') + if hook: + hook(v) + hook_var = gdic_v.get('hook_var', {}) + every_time = 'every_time' in hook_var.get('flags', []) + if var == gdic.get('update_func_arg_var') or every_time: + hook = hook_var.get('hook') + if hook: + hook(hook_var.get('args', {})) + + if 'pub' in prm: + self.publish_param_topic(pdic, prm) + self.rosparam_set(pdic, prm) + self.update_depend_enable(pdic, gdic, prm) + + d = self.cfg_dic( {'pdic':pdic, 'gdic':gdic, 'param':prm}, sys=True ) + self.update_proc_cpu(d.get('obj'), d.get('pdic'), d.get('param')) + + def update_proc_cpu(self, obj, pdic=None, prm=None): + if obj is None or not obj.GetValue(): + return + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) + if proc is None: + return + if pdic is None or prm is None: + (pdic, _, prm) = self.obj_to_pdic_gdic_prm(obj, sys=True) + + cpu_chks = self.param_value_get(pdic, prm, 'cpu_chks') + cpu_chks = cpu_chks if cpu_chks else [ True for i in range(get_cpu_count()) ] + cpus = [ i for i in range(get_cpu_count()) if cpu_chks[i] ] + nice = self.param_value_get(pdic, prm, 'nice', 0) + + d = { 'OTHER':SCHED_OTHER, 'FIFO':SCHED_FIFO, 'RR':SCHED_RR } + policy = SCHED_OTHER + priority = 0 + if self.param_value_get(pdic, prm, 'real_time', False): + policy = d.get(self.param_value_get(pdic, prm, 'policy', 'FIFO'), SCHED_FIFO) + priority = self.param_value_get(pdic, prm, 'prio', 0) + + procs = [ proc ] + get_proc_children(proc, r=True) + for proc in procs: + print('pid={}'.format(proc.pid)) + if get_proc_nice(proc) != nice: + print('nice {} -> {}'.format(get_proc_nice(proc), nice)) + if set_process_nice(proc, nice) is False: + print('Err set_process_nice()') + if get_proc_cpu_affinity(proc) != cpus: + print('cpus {} -> {}'.format(get_proc_cpu_affinity(proc), cpus)) + if set_process_cpu_affinity(proc, cpus) is False: + print('Err set_process_cpu_affinity()') + + policy_str = next( (k for (k,v) in d.items() if v == policy), '?') + print('sched policy={} prio={}'.format(policy_str, priority)) + if set_scheduling_policy(proc, policy, priority) is False: + print('Err scheduling_policy()') + + def param_value_get(self, pdic, prm, name, def_ret=None): + def_ret = self.param_default_value_get(prm, name, def_ret) + return pdic.get(name, def_ret) if pdic else def_ret + + def param_default_value_get(self, prm, name, def_ret=None): + return next( (var.get('v') for var in prm.get('vars') if var.get('name') == name ), def_ret) \ + if prm else def_ret + + def update_depend_enable(self, pdic, gdic, prm): + for var in prm.get('vars', []): + name = var.get('name') + gdic_v = gdic.get(name, {}) + depend = gdic_v.get('depend') + if depend is None: + continue + vp = gdic_v.get('var') + if vp is None: + continue + v = pdic.get(depend) + if v is None: + continue + depend_bool = eval( gdic_v.get('depend_bool', 'lambda v : bool(v)') ) + v = depend_bool(v) + enables_set(vp, 'depend', v) + + def publish_param_topic(self, pdic, prm): + pub = prm['pub'] + klass_msg = globals()[ prm['msg'] ] + msg = klass_msg() + + for (name, v) in pdic.items(): + if prm.get('topic') == '/twist_cmd' and name == 'twist.angular.z': + v = -v + (obj, attr) = msg_path_to_obj_attr(msg, name) + if obj and attr in obj.__slots__: + type_str = obj._slot_types[ obj.__slots__.index(attr) ] + setattr(obj, attr, str_to_rosval(v, type_str, v)) + + if 'stamp' in prm.get('flags', []): + (obj, attr) = msg_path_to_obj_attr(msg, 'header.stamp') + setattr(obj, attr, rospy.get_rostime()) + + pub.publish(msg) + + def rosparam_set(self, pdic, prm): + rosparams = None + for var in prm.get('vars', []): + name = var['name'] + if 'rosparam' not in var or name not in pdic: + continue + rosparam = var['rosparam'] + v = pdic.get(name) + v = str(v) + cvdic = { 'True':'true', 'False':'false' } + if v in cvdic: + v = cvdic.get(v) + if rosparams is None: + cmd = [ 'rosparam', 'list' ] + rosparams = subprocess.check_output(cmd).strip().split('\n') + nm = rosparam + nm = ('/' if len(nm) > 0 and nm[0] != '/' else '') + nm + exist = nm in rosparams + if exist: + cmd = [ 'rosparam', 'get', rosparam ] + ov = subprocess.check_output(cmd).strip() + if ov == v: + continue + elif v == '': + continue + cmd = [ 'rosparam', 'set', rosparam, v ] if v != '' else [ 'rosparam', 'delete', rosparam ] + print(cmd) + subprocess.call(cmd) + + # + # Sensing Tab + # + def OnSensingDriver(self, event): + self.OnChecked_obj(event.GetEventObject()) + + def OnROSbagRecord(self, event): + self.dlg_rosbag_record.show() + obj = event.GetEventObject() + set_val(obj, False) + + def create_checkboxes(self, dic, panel, sizer, probe_dic, run_dic, bind_handler): + if 'name' not in dic: + return + obj = None + bdr_flg = wx.ALL + if 'subs' in dic: + lst = [] + for d in dic['subs']: + self.create_checkboxes(d, panel, lst, probe_dic, run_dic, bind_handler) + if dic['name']: + obj = static_box_sizer(panel, dic.get('name')) + set_tooltip(obj.GetStaticBox(), dic) + else: + obj = wx.BoxSizer(wx.VERTICAL) + for (o, flg) in lst: + obj.Add(o, 0, wx.EXPAND | flg, 4) + else: + obj = wx.CheckBox(panel, wx.ID_ANY, dic['name']) + set_tooltip(obj, dic) + self.Bind(wx.EVT_CHECKBOX, bind_handler, obj) + bdr_flg = wx.LEFT | wx.RIGHT + if 'probe' in dic: + probe_dic[obj] = (dic['probe'], None) + if 'run' in dic: + run_dic[obj] = (dic['run'], None) + if 'param' in dic: + obj = self.add_config_link(dic, panel, obj) + else: + gdic = self.gdic_get_1st(dic) + self.add_cfg_info(obj, obj, dic.get('name'), None, gdic, False, None) + if sizer is not None: + sizer.append((obj, bdr_flg)) + else: + panel.SetSizer(obj) + + def add_config_link(self, dic, panel, obj): + cfg_obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, '[config]', '') + fix_link_color(cfg_obj) + self.Bind(wx.EVT_HYPERLINK, self.OnConfig, cfg_obj) + add_objs = (obj, wx.StaticText(panel, wx.ID_ANY, ' '), cfg_obj) + hszr = sizer_wrap(add_objs, wx.HORIZONTAL) + name = dic['name'] + pdic = self.load_dic_pdic_setup(name, dic) + gdic = self.gdic_get_1st(dic) + prm = self.get_param(dic.get('param')) + self.add_cfg_info(cfg_obj, obj, name, pdic, gdic, True, prm) + return hszr + + def camera_ids(self): + if self.button_synchronization.GetValue(): + return [] + cmd = "rostopic list | sed -n 's|/image_raw||p' | sed 's/^$/\//'" + return subprocess.check_output(cmd, shell=True).strip().split() + + def cam_id_to_obj(self, cam_id, v): + cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) + if cam_id_obj is None: + cam_id_obj = StrValObj(cam_id, v) + cam_id_obj.SetValue(v) + return cam_id_obj + + def camera_id_hook(self, args): + new_id = args.get('pdic', {}).get('camera_id', '') + ids = args.get('ids', []) + if new_id not in ids: + return + idx = ids.index(new_id) + + pp = args.get('param_panel') + if pp: + pp.detach_func() + dlg = args.get('dlg') + if dlg: + dlg.EndModal(idx + 100) + + def OnCalibrationPublisher(self, event): + obj = event.GetEventObject() + (_, gdic_org, prm) = self.obj_to_pdic_gdic_prm(obj) + if obj.GetValue(): + gdic_org['ids'] = self.camera_ids() + ids = gdic_org.get('ids', []) + + if ids == []: + self.OnLaunchKill(event) + return + # + # setup + # + (cmd_dic, cmd, _) = self.obj_to_cmd_dic_cmd_proc(obj) + + flags = gdic_org.get('flags', [])[:] # copy + if 'open_dialog' in flags: + flags.remove('open_dialog') + + pdic_baks = {} + for cam_id in ids: + (pdic_a, gdic_a, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic = pdic_a if pdic_a else self.load_dic_pdic_setup(cam_id, {}) + pdic['camera_id'] = cam_id + pdic_baks[cam_id] = pdic.copy() + gdic = gdic_a if gdic_a else gdic_org.copy() + gdic['flags'] = flags + + cam_id_obj = self.cam_id_to_obj(cam_id, obj.GetValue()) + if not hasattr(cam_id_obj, 'enables_proxy'): + cam_id_obj.enables_proxy = (obj, cam_id_obj.s) + + if not pdic_a or not gdic_a: + self.add_cfg_info(cam_id_obj, cam_id_obj, cam_id, pdic, gdic, False, prm) + if not cam_id_obj in cmd_dic: + cmd_dic[ cam_id_obj ] = (cmd, None) + + var = self.get_var(prm, 'camera_id', {}) + var['choices'] = ids + + # + # Dialog + # + cam_id = ids[0] + while obj.GetValue(): + (pdic, gdic, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic['camera_id'] = cam_id + dic_list_push(gdic, 'dialog_type', 'open2') + klass_dlg = globals().get(gdic_dialog_name_get(gdic), MyDialogParam) + dlg = klass_dlg(self, pdic=pdic, gdic=gdic, prm=prm) + + gdic_v = dic_getset(gdic, 'camera_id', {}) + args = { 'pdic':pdic, 'ids':ids, 'param_panel':gdic.get('param_panel'), 'dlg':dlg } + gdic_v['hook_var'] = { 'hook':self.camera_id_hook, 'args':args } + + dlg_ret = show_modal(dlg) + + dic_list_pop(gdic, 'dialog_type') + pdic['camera_id'] = cam_id # restore + + if dlg_ret == 0: # OK + break + + idx = dlg_ret - 100 + if idx < 0 or len(ids) <= idx: # Cancel + for cam_id in ids: + (pdic, _, _) = self.name_to_pdic_gdic_prm(cam_id) + pdic.update(pdic_baks.get(cam_id)) + set_val(obj, False) + return + + # Menu changed + cam_id = ids[idx] + + # + # Launch / Kill + # + for cam_id in ids: + cam_id_obj = self.cfg_prm_to_obj( {'name':cam_id} ) + (pdic, _, _) = self.obj_to_pdic_gdic_prm(cam_id_obj) + pdic['solo_camera'] = False + #print('@', cam_id, cam_id_obj.GetValue()) + self.OnLaunchKill_obj(cam_id_obj) + + # + # Simulation Tab + # + def rosbag_info_hook(self, v): + if not v: + return + th_start(self.rosbag_info_hook_th, {'v':v} ) + + def rosbag_info_hook_th(self, ev, v): # thread + err = subprocess.STDOUT + s = subprocess.check_output([ 'rosbag', 'info', v ], stderr=err).strip() + wx.CallAfter(self.label_rosbag_info.SetLabel, s) + wx.CallAfter(self.label_rosbag_info.GetParent().FitInside) + + # + # Data Tab + # + + # + # Stauts tab + # + + def info_col(self, v, v_yellow, v_red, col_normal, col_red): + if v < v_yellow: + return col_normal + if v < v_red: + (nr,ng,nb) = col_normal + (rr,rg,rb) = col_red + return ( (nr+rr)/2, (ng+rg)/2, (nb+rb)/2 ) + return col_red + + def mem_kb_info(self): + lines = subprocess.check_output('cat /proc/meminfo', shell=True).strip().split(os.linesep) + cvt = lambda k_v: ( k_v[0].replace(':', ''), int(k_v[1]) ) + d = dict( map( lambda s: cvt( filter( lambda s: s!='kB', s.split() ) ), lines ) ) + total = d.get('MemTotal') + free = d.get('MemFree') + d.get('Buffers') + d.get('Cached') + return (total, total - free) + + def toprc_create(self): + (child_pid, fd) = pty.fork() + if child_pid == 0: # child + os.execvp('top', ['top']) + else: #parent + sec = 0.2 + for s in ['1', 'c', 'W', 'q']: + time.sleep(sec) + os.write(fd, s) + + def toprc_setup(self, toprc, backup): + if os.path.exists(toprc): + os.rename(toprc, backup) + self.toprc_create() + + def toprc_restore(self, toprc, backup): + os.remove(toprc) + if os.path.exists(backup): + os.rename(backup, toprc) + + # top command thread + def top_cmd_th(self, ev, setting, cpu_ibls, mem_ibl, toprc, backup): + interval = setting.get('interval', 3) + alert_level = setting.get('alert_level', {}) + rate_per_cpu = alert_level.get('rate_per_cpu', 80) + rate_per_cpu_yellow = alert_level.get('rate_per_cpu_yellow', 80) + rate_cpu = alert_level.get('rate_cpu', 80) + rate_mem = alert_level.get('rate_mem', 80) + rate_mem_yellow = alert_level.get('rate_mem_yellow', 80) + + for ibl in cpu_ibls: + ibl.lmt_bar_prg = rate_per_cpu + mem_ibl.lmt_bar_prg = rate_mem + + alerted = False + cpu_n = get_cpu_count() + + while not ev.wait(interval): + s = subprocess.check_output(['sh', '-c', 'env COLUMNS=512 top -b -n 2 -d 0.1']).strip() + i = s.rfind('\ntop -') + 1 + s = s[i:] + wx.CallAfter(self.label_top_cmd.SetLabel, s) + wx.CallAfter(self.label_top_cmd.GetParent().FitInside) + + k = '%Cpu' + fv_sum = 0 + i = 0 + for t in s.split('\n'): + if t[:len(k)] != k: + continue + lst = t[1:].split() + v = lst[1] if lst[1] != ':' else lst[2] + if v[0] == ':': + v = v[1:] + fv = str_to_float(v) + col = self.info_col(fv, rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) + + if i < cpu_n: + ibl = cpu_ibls[i] + wx.CallAfter(ibl.lb_set, v+'%', col) + wx.CallAfter(ibl.bar_set, int(fv)) + fv_sum += fv + i += 1 + + k = 'KiB Mem:' + (total, used) = self.mem_kb_info() + rate = 100 * used / total + + for u in [ 'KB', 'MB', 'GB', 'TB' ]: + if total <= 10 * 1024 or used <= 10: + break + total /= 1024 + used /= 1024 + + col = self.info_col(rate, rate_mem_yellow, rate_mem, (64,64,64), (200,0,0)) + tx = str(used) + u + '/' + str(total) + u + '(' + str(rate) + '%)' + + wx.CallAfter(mem_ibl.lb_set, tx, col) + wx.CallAfter(mem_ibl.bar_set, rate) + + is_alert = (fv_sum >= rate_cpu * cpu_n) or rate >= rate_mem + + # --> for test + if os.path.exists('/tmp/alert_test_on'): + is_alert = True + if os.path.exists('/tmp/alert_test_off'): + is_alert = False + # <-- for test + + if is_alert and not alerted: + thinf = th_start(self.alert_th, {'bgcol':(200,50,50)}) + alerted = True + if not is_alert and alerted: + th_end(thinf) + alerted = False + + # top5 + i = s.find('\n\n') + 2 + lst = s[i:].split('\n') + hd = lst[0] + top5 = lst[1:1+5] + + i = hd.rfind('COMMAND') + cmds = [ line[i:].split(' ')[0] for line in top5 ] + + i = hd.find('%CPU') + loads = [ line[i-1:].strip().split(' ')[0] for line in top5 ] + + for (lb, cmd, load) in zip(self.lb_top5, cmds, loads): + col = self.info_col(str_to_float(load), rate_per_cpu_yellow, rate_per_cpu, (64,64,64), (200,0,0)) + wx.CallAfter(lb.SetForegroundColour, col) + wx.CallAfter(lb.SetLabel, cmd + ' (' + load + ' %CPU)') + + self.toprc_restore(toprc, backup) + + def alert_th(self, bgcol, ev): + wx.CallAfter(self.RequestUserAttention) + c = bgcol + o = wx.NullColour + while not ev.wait(0.5): + for col in [ c, o, c, o, c, o ]: + wx.CallAfter(self.set_bg_all_tabs, col) + time.sleep(0.05) + + def log_th(self, file, que, ev): + while not ev.wait(0): + s = file.readline() + if not s: + break + que.put(s) + + def logout_th(self, que, interval, tc, ev): + if que == self.log_que_stdout or que == self.log_que_stderr: + while not ev.wait(0): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + self.log_que.put(s) + + if interval <= 0: + continue + + ckbox = self.checkbox_stdout if que == self.log_que_stdout else self.checkbox_stderr + if ckbox.GetValue(): + self.log_que_show.put( cut_esc(s) ) + + else: # == self.log_que + f = None + path = self.status_dic.get('log_path') + is_syslog = (path == 'syslog') + + if is_syslog: + ident = sys.argv[0].split('/')[-1] + syslog.openlog(ident, syslog.LOG_PID | syslog.LOG_CONS) + elif path: + path = os.path.expandvars(os.path.expanduser(path)) + f = open(path, 'a') if path else None + + while not ev.wait(0): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + print(s.strip()) + sys.stdout.flush() + + s = cut_esc(s) + if is_syslog: + syslog.syslog(s) + elif f: + f.write(s) + f.flush() + if is_syslog: + syslog.closelog() + if f: + f.close() + + def logshow_th(self, que, interval, tc, ev): + while not ev.wait(interval): + try: + s = que.get(timeout=1) + except Queue.Empty: + continue + wx.CallAfter(append_tc_limit, tc, s) + + # que clear + if self.checkbox_stdout.GetValue() is False and \ + self.checkbox_stderr.GetValue() is False and \ + que.qsize() > 0: + que_clear(que) + wx.CallAfter(tc.Clear) + + # + # for Topics tab + # + def OnRefreshTopics(self, event): + self.refresh_topics_list() + + def refresh_topics_list(self): + lst = subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') + panel = self.panel_topics_list + szr = self.sizer_topics_list + for obj in self.topics_list: + szr.Remove(obj) + obj.Destroy() + self.topics_list = [] + for topic in lst: + obj = wx.HyperlinkCtrl(panel, wx.ID_ANY, topic, '') + self.Bind(wx.EVT_HYPERLINK, self.OnTopicLink, obj) + szr.Add(obj, 0, wx.LEFT, 4) + fix_link_color(obj) + self.topics_list.append(obj) + szr.Layout() + panel.SetVirtualSize(szr.GetMinSize()) + + # info clear + lb = self.label_topics_info + lb.SetLabel('') + + # echo clear + self.topics_proc_th_end() + + # wait que clear + while self.topics_echo_que.qsize() > 0: + time.sleep(0.1) + + tc = self.text_ctrl_topics_echo + tc.Enable(False) + wx.CallAfter(tc.Clear) + wx.CallAfter(tc.Enable, True) + self.topics_echo_sum = 0 + self.topic_echo_curr_topic = None + + def OnEcho(self, event): + if self.checkbox_topics_echo.GetValue() and self.topic_echo_curr_topic: + self.topics_proc_th_start(self.topic_echo_curr_topic) + else: + self.topics_proc_th_end() + + def OnTopicLink(self, event): + obj = event.GetEventObject() + topic = obj.GetLabel() + self.topic_echo_curr_topic = topic + + # info + info = subprocess.check_output([ 'rostopic', 'info', topic ]).strip() + lb = self.label_topics_info + lb.SetLabel(info) + lb.GetParent().FitInside() + + # echo + self.topics_proc_th_end() + if self.checkbox_topics_echo.GetValue(): + self.topics_proc_th_start(topic) + + def topics_proc_th_start(self, topic): + out = subprocess.PIPE + err = subprocess.STDOUT + self.topics_echo_proc = psutil.Popen([ 'rostopic', 'echo', topic ], stdout=out, stderr=err) + + self.topics_echo_thinf = th_start(self.topics_echo_th) + + def topics_proc_th_end(self): + thinf = self.topics_echo_thinf + if thinf: + th_end(thinf) + self.topics_echo_thinf = None + + proc = self.topics_echo_proc + if proc: + terminate_children(proc) + terminate(proc) + #proc.wait() + self.topics_echo_proc = None + + def topics_echo_th(self, ev): + if not self.topics_echo_proc: + return + file = self.topics_echo_proc.stdout + fl = fcntl.fcntl(file.fileno(), fcntl.F_GETFL) + fcntl.fcntl(file.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) + + while not ev.wait(0): + try: + s = file.read(1) + except: + continue + if not s: + break + if self.checkbox_topics_echo.GetValue(): + self.topics_echo_que.put(s) + + que_clear(self.topics_echo_que) + + def topics_echo_show_th(self, ev): + que = self.topics_echo_que + interval = self.topics_dic.get('gui_update_interval_ms', 100) * 0.001 + chars_limit = self.topics_dic.get('gui_chars_limit', 10000) + tc = self.text_ctrl_topics_echo + while not ev.wait(interval): + qsz = que.qsize() + if qsz <= 0: + continue + if qsz > chars_limit: + over = qsz - chars_limit + for i in range(over): + try: + que.get(timeout=1) + except Queue.Empty: + break + qsz = chars_limit + arr = [] + for i in range(qsz): + try: + s = que.get(timeout=1) + except Queue.Empty: + s = '' + arr.append(s) + s = ''.join(arr) + + self.topics_echo_sum += len(s) + rm_chars = 0 + if self.topics_echo_sum > chars_limit: + rm_chars = self.topics_echo_sum - chars_limit + self.topics_echo_sum = chars_limit + + if self.checkbox_topics_echo.GetValue(): + wx.CallAfter(append_tc_limit, tc, s, rm_chars) # # State Tabs # @@ -1715,1370 +1716,1370 @@ def OnState(self, event): msg.data = self.getStateId(clicked_event.GetLabel()) pub.publish(msg) - # - # Common Utils - # - def set_param_panel(self, obj, parent): - (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) - panel = ParamPanel(parent, frame=self, pdic=pdic, gdic=gdic, prm=prm) - sizer_wrap((panel,), wx.VERTICAL, 0, wx.EXPAND, 0, parent) - k = 'ext_toggle_enables' - gdic[ k ] = gdic.get(k, []) + [ panel ] - - def obj_to_varpanel(self, obj, var_name): - gdic = self.obj_to_gdic(obj, {}) - return gdic.get(var_name, {}).get('var') - - def obj_to_varpanel_tc(self, obj, var_name): - vp = self.obj_to_varpanel(obj, var_name) - return vp.tc if vp and vp.tc else None - - def OnConfig(self, event): - self.OnHyperlinked_obj(event.GetEventObject()) - - def add_params(self, params): - for prm in params: - if 'topic' in prm and 'msg' in prm: - klass_msg = globals()[ prm['msg'] ] - prm['pub'] = rospy.Publisher(prm['topic'], klass_msg, latch=True, queue_size=10) - self.params += params - - def gdic_get_1st(self, dic): - gdic = dic.get('gui', {}) - gdic['update_func'] = self.update_func - return gdic - - def add_cfg_info(self, cfg_obj, obj, name, pdic, gdic, run_disable, prm): - self.config_dic[ cfg_obj ] = { 'obj':obj , 'name':name , 'pdic':pdic , 'gdic':gdic, - 'run_disable':run_disable , 'param':prm } - - def get_param(self, prm_name): - return next( (prm for prm in self.params if prm['name'] == prm_name), None) - - def get_var(self, prm, var_name, def_ret=None): - return next( (var for var in prm.get('vars') if var.get('name') == var_name), def_ret) - - def obj_to_cmd_dic(self, obj): - return next( (cmd_dic for cmd_dic in self.all_cmd_dics if obj in cmd_dic), None) - - def obj_to_cmd_dic_cmd_proc(self, obj): - cmd_dic = self.obj_to_cmd_dic(obj) - if cmd_dic is None: - return (None, None, None) - (cmd, proc) = cmd_dic.get(obj, (None, None)) - return (cmd_dic, cmd, proc) - - def OnLaunchKill(self, event): - self.OnLaunchKill_obj(event.GetEventObject()) - - def OnLaunchKill_obj(self, obj): - self.alias_sync(obj) - obj = self.alias_grp_top_obj(obj) - v = obj.GetValue() - add_args = self.obj_to_add_args(obj, msg_box=v) # no open dialog at kill - if add_args is False: - set_val(obj, not v) - return - (cmd_dic, _, proc_bak) = self.obj_to_cmd_dic_cmd_proc(obj) - self.launch_kill_proc(obj, cmd_dic, add_args=add_args) - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) - if proc != proc_bak: - self.toggle_enable_obj(obj) - if proc: - self.update_proc_cpu(obj) - - def OnROSbagPlay(self, event): - obj = event.GetEventObject() - - play = self.button_play_rosbag_play - stop = self.button_stop_rosbag_play - pause = self.button_pause_rosbag_play - - (_, _, prm) = self.obj_to_pdic_gdic_prm(play) - var = self.get_var(prm, 'sim_time', {}) - - if obj == play: - var['v'] = True - self.OnLaunchKill_obj(play) - button_color_change(play) - set_val(stop, False) - set_val(pause, False) - elif obj == stop: - set_val(stop, True) - set_val(play, False) - set_val(pause, False) - var['v'] = False - self.OnLaunchKill_obj(play) - button_color_change(stop) - elif obj == pause: - (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(play) - if proc: - proc.stdin.write(' ') - - def OnFtrace(self, event): - obj = event.GetEventObject() - cmd = 'rosrun runtime_manager ftrace.py' - v = obj.GetValue() - self.ftrace_proc_ = self.launch_kill(v, cmd, - None if v else self.ftrace_proc_, obj=obj) - - def stdout_file_search(self, file, k): - s = '' - while True: - c = file.read(1) - if not c: - return None - if c != '\r' and c != '\n': - s += c - continue - s = s.strip() - if k in s: - break - s = '' - i = s.find(k) + len(k) - return s[i:] - - # thread - def point_cloud_progress_bar(self, file, ev): - obj = self.button_point_cloud - (pdic, _, _) = self.obj_to_pdic_gdic_prm(obj) - n = len(pdic.get('path_pcd', '').split(',')) - if n == 0: - return - i = 0 - while not ev.wait(0): - s = self.stdout_file_search(file, 'load ') - if not s: - break - err_key = 'failed ' - if s[:len(err_key)] != err_key: - i += 1 - else: - i -= 1 - print s - wx.CallAfter(self.label_point_cloud_bar.set, 100 * i / n) - wx.CallAfter(self.label_point_cloud_bar.clear) - - # thread - def rosbag_play_progress_bar(self, file, ev): - while not ev.wait(0): - s = self.stdout_file_search(file, 'Duration:') - if not s: - break - lst = s.split() - pos = str_to_float(lst[0]) - # lst[1] is '/' - total = str_to_float(lst[2]) - if total == 0: - continue - prg = int(100 * pos / total + 0.5) - pos = str(int(pos)) - total = str(int(total)) - - wx.CallAfter(self.label_rosbag_play_bar.set, prg) - wx.CallAfter(self.label_rosbag_play_pos.SetLabel, pos) - wx.CallAfter(self.label_rosbag_play_total.SetLabel, total) - wx.CallAfter(self.label_rosbag_play_bar.clear) - wx.CallAfter(self.label_rosbag_play_pos.SetLabel, '') - wx.CallAfter(self.label_rosbag_play_total.SetLabel, '') - - def alias_sync(self, obj, v=None): - en = None - if getattr(obj, 'IsEnabled', None): - (key, en) = enables_get_last(obj) - if not key: - en = obj.IsEnabled() - grp = self.alias_grp_get(obj) - if getattr(obj, 'GetValue', None): - v = obj.GetValue() - for o in grp: - if o is obj: - continue - - if en is not None and o.IsEnabled() != en and not self.is_toggle_button(o): - if key: - enable_set(o, key, en) - else: - o.Enable(en) - if v is not None and getattr(o, 'SetValue', None): - set_val(o, v) - if getattr(o, 'SetInsertionPointEnd', None): - o.SetInsertionPointEnd() - - def alias_grp_top_obj(self, obj): - return get_top(self.alias_grp_get(obj), obj) - - def alias_grp_get(self, obj): - return next( (grp for grp in self.alias_grps if obj in grp), []) - - def create_tree(self, parent, items, tree, item, cmd_dic): - name = items.get('name', '') - if tree is None: - style = wx.TR_HAS_BUTTONS | wx.TR_NO_LINES | wx.TR_HIDE_ROOT | wx.TR_DEFAULT_STYLE | wx.SUNKEN_BORDER - tree = CT.CustomTreeCtrl(parent, wx.ID_ANY, agwStyle=style) - - # for disable wrong scrolling at checked - tree.AcceptsFocus = MethodType(lambda self: False, tree, CT.CustomTreeCtrl) - - item = tree.AddRoot(name, data=tree) - tree.Bind(wx.EVT_MOTION, self.OnTreeMotion) - else: - ct_type = 1 if 'cmd' in items else 0 # 1:checkbox type - item = tree.AppendItem(item, name, ct_type=ct_type) - if 'desc' in items: - item.SetData(items.get('desc')) - if 'cmd' in items: - cmd_dic[item] = (items['cmd'], None) - - pdic = self.load_dic_pdic_setup(name, items) - pnl = wx.Panel(tree, wx.ID_ANY) - add_objs = [] - self.new_link(item, name, pdic, self.sys_gdic, pnl, 'sys', 'sys', add_objs) - gdic = self.gdic_get_1st(items) - if 'param' in items: - self.new_link(item, name, pdic, gdic, pnl, 'app', items.get('param'), add_objs) - else: - self.add_cfg_info(item, item, name, None, gdic, False, None) - szr = sizer_wrap(add_objs, wx.HORIZONTAL, flag=wx.ALIGN_CENTER_VERTICAL, parent=pnl) - szr.Fit(pnl) - tree.SetItemWindow(item, pnl) - - for sub in items.get('subs', []): - self.create_tree(parent, sub, tree, item, cmd_dic) - return tree - - def new_link(self, item, name, pdic, gdic, pnl, link_str, prm_name, add_objs): - lkc = None - if 'no_link' not in gdic.get('flags', []): - lkc = wx.HyperlinkCtrl(pnl, wx.ID_ANY, link_str, "") - if hasattr(lkc, 'SetCanFocus'): - lkc.SetCanFocus(False) - fix_link_color(lkc) - self.Bind(wx.EVT_HYPERLINK, self.OnHyperlinked, lkc) - if len(add_objs) > 0: - add_objs += [ wx.StaticText(pnl, wx.ID_ANY, ' ') ] - add_objs += [ wx.StaticText(pnl, wx.ID_ANY, '['), lkc, wx.StaticText(pnl, wx.ID_ANY, ']') ] - prm = self.get_param(prm_name) - self.add_cfg_info(lkc if lkc else item, item, name, pdic, gdic, False, prm) - - def load_dic_pdic_setup(self, name, dic): - name = dic.get('share_val', dic.get('name', name)) - pdic = self.load_dic.get(name, {}) - self.load_dic[ name ] = pdic - return pdic - - def launch_kill_proc(self, obj, cmd_dic, add_args=None): - if obj not in cmd_dic: - set_val(obj, False) - print('not implemented.') - return - v = obj.GetValue() - - (cmd, proc) = cmd_dic[obj] - if not cmd: - set_val(obj, False) - - proc = self.launch_kill(v, cmd, proc, add_args, obj=obj) - - (cfg_obj, dic) = self.cfg_obj_dic( {'obj':obj} ) - if cfg_obj and dic.get('run_disable'): - cfg_obj.Enable(not v) - - cmd_dic[obj] = (cmd, proc) - if not v: - self.stat_label_off(obj) - - def proc_to_cmd_dic_obj(self, proc): - for cmd_dic in self.all_cmd_dics: - obj = next( (obj for (obj, v) in cmd_dic.items() if proc in v), None) - if obj: - return (cmd_dic, obj) - return (None, None) - - def launch_kill(self, v, cmd, proc, add_args=None, sigint=None, obj=None, kill_children=None): - msg = None - msg = 'already launched.' if v and proc else msg - msg = 'already terminated.' if not v and proc is None else msg - msg = 'cmd not implemented.' if not cmd else msg - if msg is not None: - print(msg) - return proc - - if v: - args = shlex.split(cmd) - if add_args: - args += add_args - print(args) # for debug - - f = self.obj_to_gdic(obj, {}).get('stdout_func') - f = eval_if_str(self, f) - f = f if f else self.log_th - - out = subprocess.PIPE if f else None - err = subprocess.STDOUT if f else None - if f == self.log_th: - err = subprocess.PIPE - - shell = ( len(args) > 0 and args[0] == 'do_shell_exec' ) - if shell: - args = ' '.join( args[1:] ) - proc = psutil.Popen(args, stdin=subprocess.PIPE, stdout=out, stderr=err, shell=shell) - self.all_procs.append(proc) - - if f == self.log_th: - thinf = th_start(f, {'file':proc.stdout, 'que':self.log_que_stdout}) - self.all_th_infs.append(thinf) - thinf = th_start(f, {'file':proc.stderr, 'que':self.log_que_stderr}) - self.all_th_infs.append(thinf) - elif f: - thinf = th_start(f, {'file':proc.stdout}) - self.all_th_infs.append(thinf) - else: - flags = self.obj_to_gdic(obj, {}).get('flags', []) - if sigint is None: - sigint = 'SIGTERM' not in flags - if kill_children is None: - kill_children = 'kill_children' in flags - if kill_children: - terminate_children(proc, sigint) - terminate(proc, sigint) - enables_set(obj, 'proc_wait', False) - th_start( proc_wait_thread, {'proc': proc, 'obj': obj} ) - if proc in self.all_procs: - self.all_procs.remove(proc) - proc = None - - return proc - - def roslaunch_to_nodes(self, cmd): - try: - s = subprocess.check_output(cmd).strip() - return s.split('\n') if s != '' else [] - except subprocess.CalledProcessError: - return [] - - def set_bg_all_tabs(self, col=wx.NullColour): - - add_pnls = [ - self, - self.tree_ctrl_0, - self.tree_ctrl_1, - self.tree_ctrl_data ] - - for tab in self.all_tabs + add_pnls: - tab.SetBackgroundColour(col) - - def get_autoware_dir(self): - dir = rtmgr_src_dir() + '../../../../../../' - return os.path.abspath(dir) - - def load_yaml(self, filename, def_ret=None): - return load_yaml(filename, def_ret) - - def toggle_enable_obj(self, obj): - objs = [] - pfs = [ 'button_play_', 'button_stop_', 'button_pause_', - 'button_ref_', 'text_ctrl_' ] - key = self.obj_key_get(obj, pfs) - if key: - objs += self.key_objs_get(pfs, key) - - gdic = self.obj_to_gdic(obj, {}) - objs += [ eval_if_str(self, e) for e in gdic.get('ext_toggle_enables', []) ] - - self.toggle_enables(objs) - - def toggle_enables(self, objs): - for obj in objs: - if getattr(obj, 'IsEnabled', None): - en = enables_get(obj, 'toggle', obj.IsEnabled()) - enables_set(obj, 'toggle', not en) - self.alias_sync(obj) - - def is_toggle_button(self, obj): - return self.name_get(obj).split('_')[0] == 'button' and getattr(obj, 'GetValue', None) - - def obj_name_split(self, obj, pfs): - name = self.name_get(obj) - if name is None: - return (None, None) - return next( ( ( name[:len(pf)], name[len(pf):] ) for pf in pfs if name[:len(pf)] == pf ), None) - - def obj_key_get(self, obj, pfs): - name = self.name_get(obj) - if name is None: - return None - return next( (name[len(pf):] for pf in pfs if name[:len(pf)] == pf), None) - - def key_objs_get(self, pfs, key): - return [ self.obj_get(pf + key) for pf in pfs if self.obj_get(pf + key) ] - - def name_get(self, obj): - return next( (nm for nm in self.__dict__ if getattr(self, nm) is obj), None) - - def name_get_cond(self, obj, cond=(lambda s : True), def_ret=None): - return next( (nm for nm in self.__dict__ if cond(nm) and getattr(self, nm) is obj), None) - - def val_get(self, name): - obj = self.obj_get(name) - if obj is None: - return None - return obj.GetValue() if getattr(obj, 'GetValue', None) else None - - def obj_get(self, name): - return getattr(self, name, None) + # + # Common Utils + # + def set_param_panel(self, obj, parent): + (pdic, gdic, prm) = self.obj_to_pdic_gdic_prm(obj) + panel = ParamPanel(parent, frame=self, pdic=pdic, gdic=gdic, prm=prm) + sizer_wrap((panel,), wx.VERTICAL, 0, wx.EXPAND, 0, parent) + k = 'ext_toggle_enables' + gdic[ k ] = gdic.get(k, []) + [ panel ] + + def obj_to_varpanel(self, obj, var_name): + gdic = self.obj_to_gdic(obj, {}) + return gdic.get(var_name, {}).get('var') + + def obj_to_varpanel_tc(self, obj, var_name): + vp = self.obj_to_varpanel(obj, var_name) + return vp.tc if vp and vp.tc else None + + def OnConfig(self, event): + self.OnHyperlinked_obj(event.GetEventObject()) + + def add_params(self, params): + for prm in params: + if 'topic' in prm and 'msg' in prm: + klass_msg = globals()[ prm['msg'] ] + prm['pub'] = rospy.Publisher(prm['topic'], klass_msg, latch=True, queue_size=10) + self.params += params + + def gdic_get_1st(self, dic): + gdic = dic.get('gui', {}) + gdic['update_func'] = self.update_func + return gdic + + def add_cfg_info(self, cfg_obj, obj, name, pdic, gdic, run_disable, prm): + self.config_dic[ cfg_obj ] = { 'obj':obj , 'name':name , 'pdic':pdic , 'gdic':gdic, + 'run_disable':run_disable , 'param':prm } + + def get_param(self, prm_name): + return next( (prm for prm in self.params if prm['name'] == prm_name), None) + + def get_var(self, prm, var_name, def_ret=None): + return next( (var for var in prm.get('vars') if var.get('name') == var_name), def_ret) + + def obj_to_cmd_dic(self, obj): + return next( (cmd_dic for cmd_dic in self.all_cmd_dics if obj in cmd_dic), None) + + def obj_to_cmd_dic_cmd_proc(self, obj): + cmd_dic = self.obj_to_cmd_dic(obj) + if cmd_dic is None: + return (None, None, None) + (cmd, proc) = cmd_dic.get(obj, (None, None)) + return (cmd_dic, cmd, proc) + + def OnLaunchKill(self, event): + self.OnLaunchKill_obj(event.GetEventObject()) + + def OnLaunchKill_obj(self, obj): + self.alias_sync(obj) + obj = self.alias_grp_top_obj(obj) + v = obj.GetValue() + add_args = self.obj_to_add_args(obj, msg_box=v) # no open dialog at kill + if add_args is False: + set_val(obj, not v) + return + (cmd_dic, _, proc_bak) = self.obj_to_cmd_dic_cmd_proc(obj) + self.launch_kill_proc(obj, cmd_dic, add_args=add_args) + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(obj) + if proc != proc_bak: + self.toggle_enable_obj(obj) + if proc: + self.update_proc_cpu(obj) + + def OnROSbagPlay(self, event): + obj = event.GetEventObject() + + play = self.button_play_rosbag_play + stop = self.button_stop_rosbag_play + pause = self.button_pause_rosbag_play + + (_, _, prm) = self.obj_to_pdic_gdic_prm(play) + var = self.get_var(prm, 'sim_time', {}) + + if obj == play: + var['v'] = True + self.OnLaunchKill_obj(play) + button_color_change(play) + set_val(stop, False) + set_val(pause, False) + elif obj == stop: + set_val(stop, True) + set_val(play, False) + set_val(pause, False) + var['v'] = False + self.OnLaunchKill_obj(play) + button_color_change(stop) + elif obj == pause: + (_, _, proc) = self.obj_to_cmd_dic_cmd_proc(play) + if proc: + proc.stdin.write(' ') + + def OnFtrace(self, event): + obj = event.GetEventObject() + cmd = 'rosrun runtime_manager ftrace.py' + v = obj.GetValue() + self.ftrace_proc_ = self.launch_kill(v, cmd, + None if v else self.ftrace_proc_, obj=obj) + + def stdout_file_search(self, file, k): + s = '' + while True: + c = file.read(1) + if not c: + return None + if c != '\r' and c != '\n': + s += c + continue + s = s.strip() + if k in s: + break + s = '' + i = s.find(k) + len(k) + return s[i:] + + # thread + def point_cloud_progress_bar(self, file, ev): + obj = self.button_point_cloud + (pdic, _, _) = self.obj_to_pdic_gdic_prm(obj) + n = len(pdic.get('path_pcd', '').split(',')) + if n == 0: + return + i = 0 + while not ev.wait(0): + s = self.stdout_file_search(file, 'load ') + if not s: + break + err_key = 'failed ' + if s[:len(err_key)] != err_key: + i += 1 + else: + i -= 1 + print(s) + wx.CallAfter(self.label_point_cloud_bar.set, 100 * i / n) + wx.CallAfter(self.label_point_cloud_bar.clear) + + # thread + def rosbag_play_progress_bar(self, file, ev): + while not ev.wait(0): + s = self.stdout_file_search(file, 'Duration:') + if not s: + break + lst = s.split() + pos = str_to_float(lst[0]) + # lst[1] is '/' + total = str_to_float(lst[2]) + if total == 0: + continue + prg = int(100 * pos / total + 0.5) + pos = str(int(pos)) + total = str(int(total)) + + wx.CallAfter(self.label_rosbag_play_bar.set, prg) + wx.CallAfter(self.label_rosbag_play_pos.SetLabel, pos) + wx.CallAfter(self.label_rosbag_play_total.SetLabel, total) + wx.CallAfter(self.label_rosbag_play_bar.clear) + wx.CallAfter(self.label_rosbag_play_pos.SetLabel, '') + wx.CallAfter(self.label_rosbag_play_total.SetLabel, '') + + def alias_sync(self, obj, v=None): + en = None + if getattr(obj, 'IsEnabled', None): + (key, en) = enables_get_last(obj) + if not key: + en = obj.IsEnabled() + grp = self.alias_grp_get(obj) + if getattr(obj, 'GetValue', None): + v = obj.GetValue() + for o in grp: + if o is obj: + continue + + if en is not None and o.IsEnabled() != en and not self.is_toggle_button(o): + if key: + enable_set(o, key, en) + else: + o.Enable(en) + if v is not None and getattr(o, 'SetValue', None): + set_val(o, v) + if getattr(o, 'SetInsertionPointEnd', None): + o.SetInsertionPointEnd() + + def alias_grp_top_obj(self, obj): + return get_top(self.alias_grp_get(obj), obj) + + def alias_grp_get(self, obj): + return next( (grp for grp in self.alias_grps if obj in grp), []) + + def create_tree(self, parent, items, tree, item, cmd_dic): + name = items.get('name', '') + if tree is None: + style = wx.TR_HAS_BUTTONS | wx.TR_NO_LINES | wx.TR_HIDE_ROOT | wx.TR_DEFAULT_STYLE | wx.SUNKEN_BORDER + tree = CT.CustomTreeCtrl(parent, wx.ID_ANY, agwStyle=style) + + # for disable wrong scrolling at checked + tree.AcceptsFocus = MethodType(lambda self: False, tree, CT.CustomTreeCtrl) + + item = tree.AddRoot(name, data=tree) + tree.Bind(wx.EVT_MOTION, self.OnTreeMotion) + else: + ct_type = 1 if 'cmd' in items else 0 # 1:checkbox type + item = tree.AppendItem(item, name, ct_type=ct_type) + if 'desc' in items: + item.SetData(items.get('desc')) + if 'cmd' in items: + cmd_dic[item] = (items['cmd'], None) + + pdic = self.load_dic_pdic_setup(name, items) + pnl = wx.Panel(tree, wx.ID_ANY) + add_objs = [] + self.new_link(item, name, pdic, self.sys_gdic, pnl, 'sys', 'sys', add_objs) + gdic = self.gdic_get_1st(items) + if 'param' in items: + self.new_link(item, name, pdic, gdic, pnl, 'app', items.get('param'), add_objs) + else: + self.add_cfg_info(item, item, name, None, gdic, False, None) + szr = sizer_wrap(add_objs, wx.HORIZONTAL, flag=wx.ALIGN_CENTER_VERTICAL, parent=pnl) + szr.Fit(pnl) + tree.SetItemWindow(item, pnl) + + for sub in items.get('subs', []): + self.create_tree(parent, sub, tree, item, cmd_dic) + return tree + + def new_link(self, item, name, pdic, gdic, pnl, link_str, prm_name, add_objs): + lkc = None + if 'no_link' not in gdic.get('flags', []): + lkc = wx.HyperlinkCtrl(pnl, wx.ID_ANY, link_str, "") + if hasattr(lkc, 'SetCanFocus'): + lkc.SetCanFocus(False) + fix_link_color(lkc) + self.Bind(wx.EVT_HYPERLINK, self.OnHyperlinked, lkc) + if len(add_objs) > 0: + add_objs += [ wx.StaticText(pnl, wx.ID_ANY, ' ') ] + add_objs += [ wx.StaticText(pnl, wx.ID_ANY, '['), lkc, wx.StaticText(pnl, wx.ID_ANY, ']') ] + prm = self.get_param(prm_name) + self.add_cfg_info(lkc if lkc else item, item, name, pdic, gdic, False, prm) + + def load_dic_pdic_setup(self, name, dic): + name = dic.get('share_val', dic.get('name', name)) + pdic = self.load_dic.get(name, {}) + self.load_dic[ name ] = pdic + return pdic + + def launch_kill_proc(self, obj, cmd_dic, add_args=None): + if obj not in cmd_dic: + set_val(obj, False) + print('not implemented.') + return + v = obj.GetValue() + + (cmd, proc) = cmd_dic[obj] + if not cmd: + set_val(obj, False) + + proc = self.launch_kill(v, cmd, proc, add_args, obj=obj) + + (cfg_obj, dic) = self.cfg_obj_dic( {'obj':obj} ) + if cfg_obj and dic.get('run_disable'): + cfg_obj.Enable(not v) + + cmd_dic[obj] = (cmd, proc) + if not v: + self.stat_label_off(obj) + + def proc_to_cmd_dic_obj(self, proc): + for cmd_dic in self.all_cmd_dics: + obj = next( (obj for (obj, v) in cmd_dic.items() if proc in v), None) + if obj: + return (cmd_dic, obj) + return (None, None) + + def launch_kill(self, v, cmd, proc, add_args=None, sigint=None, obj=None, kill_children=None): + msg = None + msg = 'already launched.' if v and proc else msg + msg = 'already terminated.' if not v and proc is None else msg + msg = 'cmd not implemented.' if not cmd else msg + if msg is not None: + print(msg) + return proc + + if v: + args = shlex.split(cmd) + if add_args: + args += add_args + print(args) # for debug + + f = self.obj_to_gdic(obj, {}).get('stdout_func') + f = eval_if_str(self, f) + f = f if f else self.log_th + + out = subprocess.PIPE if f else None + err = subprocess.STDOUT if f else None + if f == self.log_th: + err = subprocess.PIPE + + shell = ( len(args) > 0 and args[0] == 'do_shell_exec' ) + if shell: + args = ' '.join( args[1:] ) + proc = psutil.Popen(args, stdin=subprocess.PIPE, stdout=out, stderr=err, shell=shell) + self.all_procs.append(proc) + + if f == self.log_th: + thinf = th_start(f, {'file':proc.stdout, 'que':self.log_que_stdout}) + self.all_th_infs.append(thinf) + thinf = th_start(f, {'file':proc.stderr, 'que':self.log_que_stderr}) + self.all_th_infs.append(thinf) + elif f: + thinf = th_start(f, {'file':proc.stdout}) + self.all_th_infs.append(thinf) + else: + flags = self.obj_to_gdic(obj, {}).get('flags', []) + if sigint is None: + sigint = 'SIGTERM' not in flags + if kill_children is None: + kill_children = 'kill_children' in flags + if kill_children: + terminate_children(proc, sigint) + terminate(proc, sigint) + enables_set(obj, 'proc_wait', False) + th_start( proc_wait_thread, {'proc': proc, 'obj': obj} ) + if proc in self.all_procs: + self.all_procs.remove(proc) + proc = None + + return proc + + def roslaunch_to_nodes(self, cmd): + try: + s = subprocess.check_output(cmd).strip() + return s.split('\n') if s != '' else [] + except subprocess.CalledProcessError: + return [] + + def set_bg_all_tabs(self, col=wx.NullColour): + + add_pnls = [ + self, + self.tree_ctrl_0, + self.tree_ctrl_1, + self.tree_ctrl_data ] + + for tab in self.all_tabs + add_pnls: + tab.SetBackgroundColour(col) + + def get_autoware_dir(self): + dir = rtmgr_src_dir() + '../../../../../../' + return os.path.abspath(dir) + + def load_yaml(self, filename, def_ret=None): + return load_yaml(filename, def_ret) + + def toggle_enable_obj(self, obj): + objs = [] + pfs = [ 'button_play_', 'button_stop_', 'button_pause_', + 'button_ref_', 'text_ctrl_' ] + key = self.obj_key_get(obj, pfs) + if key: + objs += self.key_objs_get(pfs, key) + + gdic = self.obj_to_gdic(obj, {}) + objs += [ eval_if_str(self, e) for e in gdic.get('ext_toggle_enables', []) ] + + self.toggle_enables(objs) + + def toggle_enables(self, objs): + for obj in objs: + if getattr(obj, 'IsEnabled', None): + en = enables_get(obj, 'toggle', obj.IsEnabled()) + enables_set(obj, 'toggle', not en) + self.alias_sync(obj) + + def is_toggle_button(self, obj): + return self.name_get(obj).split('_')[0] == 'button' and getattr(obj, 'GetValue', None) + + def obj_name_split(self, obj, pfs): + name = self.name_get(obj) + if name is None: + return (None, None) + return next( ( ( name[:len(pf)], name[len(pf):] ) for pf in pfs if name[:len(pf)] == pf ), None) + + def obj_key_get(self, obj, pfs): + name = self.name_get(obj) + if name is None: + return None + return next( (name[len(pf):] for pf in pfs if name[:len(pf)] == pf), None) + + def key_objs_get(self, pfs, key): + return [ self.obj_get(pf + key) for pf in pfs if self.obj_get(pf + key) ] + + def name_get(self, obj): + return next( (nm for nm in self.__dict__ if getattr(self, nm) is obj), None) + + def name_get_cond(self, obj, cond=(lambda s : True), def_ret=None): + return next( (nm for nm in self.__dict__ if cond(nm) and getattr(self, nm) is obj), None) + + def val_get(self, name): + obj = self.obj_get(name) + if obj is None: + return None + return obj.GetValue() if getattr(obj, 'GetValue', None) else None + + def obj_get(self, name): + return getattr(self, name, None) def gdic_dialog_type_chk(gdic, name): - dlg_type = dic_list_get(gdic, 'dialog_type', 'config') + dlg_type = dic_list_get(gdic, 'dialog_type', 'config') - tail = '_dialog_only' - lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] - only_chk = next( (False for (k,type) in lst if type != dlg_type and name in gdic.get(k, [])), True) + tail = '_dialog_only' + lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] + only_chk = next( (False for (k,type) in lst if type != dlg_type and name in gdic.get(k, [])), True) - tail = '_dialog_allow' - lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] - allow_chk = next( (False for (k,type) in lst if type == dlg_type and name not in gdic.get(k, [])), True) + tail = '_dialog_allow' + lst = [ (k, k[:-len(tail)]) for k in gdic.keys() if k[-len(tail):] == tail ] + allow_chk = next( (False for (k,type) in lst if type == dlg_type and name not in gdic.get(k, [])), True) - return only_chk and allow_chk + return only_chk and allow_chk def gdic_dialog_name_get(gdic): - dlg_type = dic_list_get(gdic, 'dialog_type', 'config') - return gdic.get(dlg_type + '_dialog', gdic.get('dialog', 'MyDialogParam') ) + dlg_type = dic_list_get(gdic, 'dialog_type', 'config') + return gdic.get(dlg_type + '_dialog', gdic.get('dialog', 'MyDialogParam') ) class ParamPanel(wx.Panel): - def __init__(self, *args, **kwds): - self.frame = kwds.pop('frame') - self.pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - self.prm = kwds.pop('prm') - wx.Panel.__init__(self, *args, **kwds) - - self.gdic['param_panel'] = self - - obj = self.frame.cfg_prm_to_obj( {'pdic':self.pdic, 'gdic':self.gdic, 'param':self.prm} ) - (_, _, proc) = self.frame.obj_to_cmd_dic_cmd_proc(obj) - - hszr = None - self.vps = [] - self.tmp_msg = None - szr = wx.BoxSizer(wx.VERTICAL) - - topic_szrs = (None, None) - - vars = self.prm.get('vars') - if self.gdic.get('show_order'): - var_lst = lambda name, vars : [ var for var in vars if var.get('name') == name ] - vars = reduce( lambda lst, name : lst + var_lst(name, vars), self.gdic.get('show_order'), [] ) - - for var in vars: - name = var.get('name') - - if not gdic_dialog_type_chk(self.gdic, name): - continue - - gdic_v = self.get_gdic_v_and_chk_enable(name) - if gdic_v is None: - continue - - bak_stk_push(gdic_v, 'func') - if gdic_v.get('func'): - continue - - v = self.pdic.get(name, var.get('v')) - - vp = VarPanel(self, var=var, v=v, update=self.update) - vp.setup_tooltip() - self.vps.append(vp) - - gdic_v['var'] = vp - gdic_v['func'] = vp.get_v - prop = gdic_v.get('prop', 0) - border = gdic_v.get('border', 0) - flag = wx_flag_get(gdic_v.get('flags', [])) - - do_category = 'no_category' not in gdic_v.get('flags', []) - if do_category and self.in_msg(var): - bak = (szr, hszr) - (szr, hszr) = topic_szrs - if szr is None: - szr = static_box_sizer(self, 'topic : ' + self.prm.get('topic')) - bak[0].Add(szr, 0, wx.EXPAND | wx.ALL, 4) - targ_szr = szr - if vp.is_nl(): - hszr = None if hszr else hszr - flag |= wx.EXPAND - else: - if hszr is None: - hszr = wx.BoxSizer(wx.HORIZONTAL) - szr.Add(hszr, 0, wx.EXPAND) - flag |= wx.ALIGN_CENTER_VERTICAL - targ_szr = hszr - - if do_category and 'rosparam' in var: - rp_szr = static_box_sizer(self, 'rosparam : ' + var.get('rosparam')) - targ_szr.Add(rp_szr, 0, wx.EXPAND | wx.ALL, 4) - targ_szr = rp_szr - - user_category = gdic_v.get('user_category') - if user_category is not None and hszr: - user_szr = static_box_sizer(self, user_category, orient=wx.HORIZONTAL) - (flgs, bdr) = gdic_v.get('user_category_add', [ [], 0 ]) - targ_szr.Add(user_szr, 0, wx_flag_get(flgs), bdr) - targ_szr = hszr = user_szr - - targ_szr.Add(vp, prop, flag, border) - - if 'nl' in gdic_v.get('flags', []): - hszr = None - - if do_category and self.in_msg(var): - topic_szrs = (szr, hszr) - (szr, hszr) = bak - - if 'hline' in gdic_v.get('flags', []) and hszr is None: - szr.Add(wx.StaticLine(self, wx.ID_ANY), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 4) - - if not self.in_msg(var) and var.get('rosparam'): - k = 'ext_toggle_enables' - self.gdic[ k ] = self.gdic.get(k, []) + [ vp ] - enables_set(vp, 'toggle', proc is None) - - if 'disable' in gdic_v.get('flags', []): - vp.Enable(False) - if 'hide' in gdic_v.get('flags', []): - vp.Hide() - - self.SetSizer(szr) - if 'no_init_update' not in self.prm.get('flags', []): - self.update() - - def get_gdic_v_and_chk_enable(self, var_name): - gdic_v = dic_getset(self.gdic, var_name, {}) - if 'panel' in gdic_v and dic_eval_if_str(self.frame, gdic_v, 'panel') != self.GetParent(): - return None - return gdic_v - - def update(self, var=None): - update_func = self.gdic.get('update_func') - if update_func: - self.gdic['update_func_arg_var'] = var - update_func(self.pdic, self.gdic, self.prm) - - def detach_func(self): - for var in self.prm.get('vars'): - name = var.get('name') - - if not gdic_dialog_type_chk(self.gdic, name): - continue - - gdic_v = self.get_gdic_v_and_chk_enable(name) - if gdic_v is None: - continue - - if 'func' in gdic_v: - bak_stk_pop(gdic_v, 'func') - - vp = gdic_v.get('var') - lst_remove_once(self.gdic.get('ext_toggle_enables', []), vp) - - def in_msg(self, var): - if 'topic' not in self.prm or 'msg' not in self.prm: - return False - if self.tmp_msg is None: - klass_msg = globals().get( self.prm.get('msg') ) - if klass_msg is None: - return False - self.tmp_msg = klass_msg() - (obj, attr) = msg_path_to_obj_attr(self.tmp_msg, var.get('name')) - return obj and attr in obj.__slots__ + def __init__(self, *args, **kwds): + self.frame = kwds.pop('frame') + self.pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + self.prm = kwds.pop('prm') + wx.Panel.__init__(self, *args, **kwds) + + self.gdic['param_panel'] = self + + obj = self.frame.cfg_prm_to_obj( {'pdic':self.pdic, 'gdic':self.gdic, 'param':self.prm} ) + (_, _, proc) = self.frame.obj_to_cmd_dic_cmd_proc(obj) + + hszr = None + self.vps = [] + self.tmp_msg = None + szr = wx.BoxSizer(wx.VERTICAL) + + topic_szrs = (None, None) + + vars = self.prm.get('vars') + if self.gdic.get('show_order'): + var_lst = lambda name, vars : [ var for var in vars if var.get('name') == name ] + vars = reduce( lambda lst, name : lst + var_lst(name, vars), self.gdic.get('show_order'), [] ) + + for var in vars: + name = var.get('name') + + if not gdic_dialog_type_chk(self.gdic, name): + continue + + gdic_v = self.get_gdic_v_and_chk_enable(name) + if gdic_v is None: + continue + + bak_stk_push(gdic_v, 'func') + if gdic_v.get('func'): + continue + + v = self.pdic.get(name, var.get('v')) + + vp = VarPanel(self, var=var, v=v, update=self.update) + vp.setup_tooltip() + self.vps.append(vp) + + gdic_v['var'] = vp + gdic_v['func'] = vp.get_v + prop = gdic_v.get('prop', 0) + border = gdic_v.get('border', 0) + flag = wx_flag_get(gdic_v.get('flags', [])) + + do_category = 'no_category' not in gdic_v.get('flags', []) + if do_category and self.in_msg(var): + bak = (szr, hszr) + (szr, hszr) = topic_szrs + if szr is None: + szr = static_box_sizer(self, 'topic : ' + self.prm.get('topic')) + bak[0].Add(szr, 0, wx.EXPAND | wx.ALL, 4) + targ_szr = szr + if vp.is_nl(): + hszr = None if hszr else hszr + flag |= wx.EXPAND + else: + if hszr is None: + hszr = wx.BoxSizer(wx.HORIZONTAL) + szr.Add(hszr, 0, wx.EXPAND) + flag |= wx.ALIGN_CENTER_VERTICAL + targ_szr = hszr + + if do_category and 'rosparam' in var: + rp_szr = static_box_sizer(self, 'rosparam : ' + var.get('rosparam')) + targ_szr.Add(rp_szr, 0, wx.EXPAND | wx.ALL, 4) + targ_szr = rp_szr + + user_category = gdic_v.get('user_category') + if user_category is not None and hszr: + user_szr = static_box_sizer(self, user_category, orient=wx.HORIZONTAL) + (flgs, bdr) = gdic_v.get('user_category_add', [ [], 0 ]) + targ_szr.Add(user_szr, 0, wx_flag_get(flgs), bdr) + targ_szr = hszr = user_szr + + targ_szr.Add(vp, prop, flag, border) + + if 'nl' in gdic_v.get('flags', []): + hszr = None + + if do_category and self.in_msg(var): + topic_szrs = (szr, hszr) + (szr, hszr) = bak + + if 'hline' in gdic_v.get('flags', []) and hszr is None: + szr.Add(wx.StaticLine(self, wx.ID_ANY), 0, wx.EXPAND | wx.TOP | wx.BOTTOM, 4) + + if not self.in_msg(var) and var.get('rosparam'): + k = 'ext_toggle_enables' + self.gdic[ k ] = self.gdic.get(k, []) + [ vp ] + enables_set(vp, 'toggle', proc is None) + + if 'disable' in gdic_v.get('flags', []): + vp.Enable(False) + if 'hide' in gdic_v.get('flags', []): + vp.Hide() + + self.SetSizer(szr) + if 'no_init_update' not in self.prm.get('flags', []): + self.update() + + def get_gdic_v_and_chk_enable(self, var_name): + gdic_v = dic_getset(self.gdic, var_name, {}) + if 'panel' in gdic_v and dic_eval_if_str(self.frame, gdic_v, 'panel') != self.GetParent(): + return None + return gdic_v + + def update(self, var=None): + update_func = self.gdic.get('update_func') + if update_func: + self.gdic['update_func_arg_var'] = var + update_func(self.pdic, self.gdic, self.prm) + + def detach_func(self): + for var in self.prm.get('vars'): + name = var.get('name') + + if not gdic_dialog_type_chk(self.gdic, name): + continue + + gdic_v = self.get_gdic_v_and_chk_enable(name) + if gdic_v is None: + continue + + if 'func' in gdic_v: + bak_stk_pop(gdic_v, 'func') + + vp = gdic_v.get('var') + lst_remove_once(self.gdic.get('ext_toggle_enables', []), vp) + + def in_msg(self, var): + if 'topic' not in self.prm or 'msg' not in self.prm: + return False + if self.tmp_msg is None: + klass_msg = globals().get( self.prm.get('msg') ) + if klass_msg is None: + return False + self.tmp_msg = klass_msg() + (obj, attr) = msg_path_to_obj_attr(self.tmp_msg, var.get('name')) + return obj and attr in obj.__slots__ class VarPanel(wx.Panel): - def __init__(self, *args, **kwds): - self.var = kwds.pop('var') - v = kwds.pop('v') - self.update = kwds.pop('update') - wx.Panel.__init__(self, *args, **kwds) - - self.min = self.var.get('min') - self.max = self.var.get('max') - self.has_slider = self.min is not None and self.max is not None - self.lb = None - - label = self.var.get('label', '') - self.kind = self.var.get('kind') - if self.kind == 'radio_box': - choices = self.var.get('choices', []) - style = wx.RA_SPECIFY_COLS if self.var.get('choices_style') == 'h' else wx.RA_SPECIFY_ROWS - self.obj = wx.RadioBox(self, wx.ID_ANY, label, choices=choices, majorDimension=0, style=style) - self.choices_sel_set(v) - self.Bind(wx.EVT_RADIOBOX, self.OnUpdate, self.obj) - return - if self.kind == 'menu': - choices = self.var.get('choices', []) - self.obj = wx.Choice(self, wx.ID_ANY, choices=choices) - self.choices_sel_set(v) - self.Bind(wx.EVT_CHOICE, self.OnUpdate, self.obj) - if label: - self.lb = wx.StaticText(self, wx.ID_ANY, label) - flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL - sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) - return - if self.kind == 'checkbox': - self.obj = wx.CheckBox(self, wx.ID_ANY, label) - self.obj.SetValue(v) - self.Bind(wx.EVT_CHECKBOX, self.OnUpdate, self.obj) - return - if self.kind == 'checkboxes': - item_n = dic_eval_if_str(self, self.var, 'item_n', 1) - self.obj = Checkboxes(self, item_n, label) - self.obj.set(v) - for box in self.obj.boxes: - self.obj.Bind(wx.EVT_CHECKBOX, self.OnUpdate, box) - return - if self.kind == 'toggle_button': - self.obj = wx.ToggleButton(self, wx.ID_ANY, label) - set_val(self.obj, v) - self.Bind(wx.EVT_TOGGLEBUTTON, self.OnUpdate, self.obj) - button_color_hdr_setup(self.obj) - return - if self.kind == 'hide': - self.Hide() - return - if self.kind == 'topic': - topic_type = self.var.get('topic_type') - topics = self._get_topics_by_type(topic_type) - self.obj = wx.ComboBox(self, id=wx.ID_ANY, value=v, choices=topics, style=wx.CB_DROPDOWN, size=(130,-1)) - self.lb = wx.StaticText(self, wx.ID_ANY, label) - flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL - sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) - return - - szr = wx.BoxSizer(wx.HORIZONTAL) - - self.lb = wx.StaticText(self, wx.ID_ANY, label) - flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL - szr.Add(self.lb, 0, flag, 4) - - if self.kind == 'path': - v = str(v) - v = path_expand_cmd(v) - v = os.path.expandvars(os.path.expanduser(v)) - - style = wx.TE_PROCESS_ENTER + wx_flag_get( self.var.get('str_flags', []) ) - - self.tc = wx.TextCtrl(self, wx.ID_ANY, str(v), style=style, size=(130,-1)) - self.Bind(wx.EVT_TEXT_ENTER, self.OnUpdate, self.tc) - - if self.kind in ('num', None): - if self.has_slider: - self.w = self.max - self.min - vlst = [ v, self.min, self.max, self.var['v'] ] - self.is_float = len( [ v_ for v_ in vlst if type(v_) is not int ] ) > 0 - self.int_max = 1000 if self.is_float else self.max - self.int_min = 0 if self.is_float else self.min - - self.slider = wx.Slider(self, wx.ID_ANY, self.get_int_v(), self.int_min, self.int_max) - self.Bind(wx.EVT_COMMAND_SCROLL, self.OnScroll, self.slider) - self.slider.SetMinSize((82, 27)) - szr.Add(self.slider, 1, wx.LEFT | wx.RIGHT | wx.ALIGN_CENTER_VERTICAL, 4) - else: - self.is_float = type(self.var['v']) is not int - self.tc.SetMinSize((40,27)) - - flag = wx.ALIGN_CENTER_VERTICAL - prop = 1 if self.kind == 'path' or self.kind == 'str' else 0 - szr.Add(self.tc, prop, flag, 4) - - if self.kind == 'path': - self.ref = wx.Button(self, wx.ID_ANY, 'Ref') - self.Bind(wx.EVT_BUTTON, self.OnRef, self.ref) - button_color_hdr_setup(self.ref) - self.ref.SetMinSize((40,29)) - szr.Add(self.ref, 0, flag, 4) - - if self.has_slider or self.kind == 'num': - vszr = wx.BoxSizer(wx.VERTICAL) - vszr.Add( self.create_bmbtn("images/inc.png", self.OnIncBtn) ) - vszr.Add( self.create_bmbtn("images/dec.png", self.OnDecBtn) ) - szr.Add(vszr, 0, wx.ALIGN_CENTER_VERTICAL) - - self.SetSizer(szr) - - def _get_topics_by_type(self, message_type): - #get list of current available topics: - ros_topics = rospy.get_published_topics() - matched_topics = list(filter(lambda x: x[1]==message_type,ros_topics)) - topic_names = [x[0] for x in matched_topics] - topic_names.sort() - return topic_names - - def setup_tooltip(self): - if get_tooltips(self.var): - set_tooltips(self.obj, self.var) - if get_tooltip(self.var): - obj = self.lb if self.lb else (self if self.kind == 'radio_box' else self.obj) - set_tooltip(obj, self.var) - - def create_bmbtn(self, filename, hdr): - dir = rtmgr_src_dir() - bm = wx.Bitmap(dir + filename, wx.BITMAP_TYPE_ANY) - style = wx.BORDER_NONE | wx.BU_EXACTFIT - obj = wx.lib.buttons.GenBitmapButton(self, wx.ID_ANY, bm, style=style) - self.Bind(wx.EVT_BUTTON, hdr, obj) - return obj - - def get_v(self): - if self.kind in [ 'radio_box', 'menu' ]: - return self.choices_sel_get() - if self.kind in [ 'checkbox', 'toggle_button', 'topic' ]: - return self.obj.GetValue() - if self.kind == 'checkboxes': - return self.obj.get() - if self.kind == 'hide': - return self.var.get('v') - if self.kind in [ 'path', 'str' ]: - return str(self.tc.GetValue()) - - if not self.has_slider and self.tc.GetValue() == '': - return '' - return self.get_tc_v() - - def get_tc_v(self): - s = self.tc.GetValue() - v = str_to_float(s) if self.is_float else int(s) - if self.has_slider: - v = self.min if v < self.min else v - v = self.max if v > self.max else v - self.tc.SetValue(adjust_num_str(str(v))) - return v - - def get_int_v(self): - v = self.get_tc_v() - if self.is_float: - v = int( self.int_max * (v - self.min) / self.w if self.w != 0 else 0 ) - return v - - def OnScroll(self, event): - iv = self.slider.GetValue() - s = str(iv) - if self.is_float: - v = self.min + float(self.w) * iv / self.int_max - s = str(Decimal(v).quantize(Decimal(str(self.get_step())))) - self.tc.SetValue(s) - self.update(self.var) - - def OnIncBtn(self, event): - step = self.get_step() - self.add_v(step) - - def OnDecBtn(self, event): - step = self.get_step() - self.add_v(-step) - - def get_step(self): - step = self.var.get('step') - return step if step else 0.01 if self.is_float else 1 - - def add_v(self, step): - ov = self.get_v() - self.tc.SetValue(str(ov + step)) - v = self.get_v() - if v != ov: - if self.has_slider: - self.slider.SetValue(self.get_int_v()) - self.update(self.var) - - def OnUpdate(self, event): - if self.has_slider: - self.slider.SetValue(self.get_int_v()) - self.update(self.var) - - def OnRef(self, event): - if file_dialog(self, self.tc, self.var) == wx.ID_OK: - self.update(self.var) - - def choices_sel_get(self): - return self.obj.GetStringSelection() if self.var.get('choices_type') == 'str' else self.obj.GetSelection() - - def choices_sel_set(self, v): - if self.var.get('choices_type') == 'str': - self.obj.SetStringSelection(v) - else: - self.obj.SetSelection(v) - - def is_nl(self): - return self.has_slider or self.kind in [ 'path' ] + def __init__(self, *args, **kwds): + self.var = kwds.pop('var') + v = kwds.pop('v') + self.update = kwds.pop('update') + wx.Panel.__init__(self, *args, **kwds) + + self.min = self.var.get('min') + self.max = self.var.get('max') + self.has_slider = self.min is not None and self.max is not None + self.lb = None + + label = self.var.get('label', '') + self.kind = self.var.get('kind') + if self.kind == 'radio_box': + choices = self.var.get('choices', []) + style = wx.RA_SPECIFY_COLS if self.var.get('choices_style') == 'h' else wx.RA_SPECIFY_ROWS + self.obj = wx.RadioBox(self, wx.ID_ANY, label, choices=choices, majorDimension=0, style=style) + self.choices_sel_set(v) + self.Bind(wx.EVT_RADIOBOX, self.OnUpdate, self.obj) + return + if self.kind == 'menu': + choices = self.var.get('choices', []) + self.obj = wx.Choice(self, wx.ID_ANY, choices=choices) + self.choices_sel_set(v) + self.Bind(wx.EVT_CHOICE, self.OnUpdate, self.obj) + if label: + self.lb = wx.StaticText(self, wx.ID_ANY, label) + flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL + sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) + return + if self.kind == 'checkbox': + self.obj = wx.CheckBox(self, wx.ID_ANY, label) + self.obj.SetValue(v) + self.Bind(wx.EVT_CHECKBOX, self.OnUpdate, self.obj) + return + if self.kind == 'checkboxes': + item_n = dic_eval_if_str(self, self.var, 'item_n', 1) + self.obj = Checkboxes(self, item_n, label) + self.obj.set(v) + for box in self.obj.boxes: + self.obj.Bind(wx.EVT_CHECKBOX, self.OnUpdate, box) + return + if self.kind == 'toggle_button': + self.obj = wx.ToggleButton(self, wx.ID_ANY, label) + set_val(self.obj, v) + self.Bind(wx.EVT_TOGGLEBUTTON, self.OnUpdate, self.obj) + button_color_hdr_setup(self.obj) + return + if self.kind == 'hide': + self.Hide() + return + if self.kind == 'topic': + topic_type = self.var.get('topic_type') + topics = self._get_topics_by_type(topic_type) + self.obj = wx.ComboBox(self, id=wx.ID_ANY, value=v, choices=topics, style=wx.CB_DROPDOWN, size=(130,-1)) + self.lb = wx.StaticText(self, wx.ID_ANY, label) + flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL + sizer_wrap((self.lb, self.obj), wx.HORIZONTAL, 0, flag, 4, self) + return + + szr = wx.BoxSizer(wx.HORIZONTAL) + + self.lb = wx.StaticText(self, wx.ID_ANY, label) + flag = wx.LEFT | wx.ALIGN_CENTER_VERTICAL + szr.Add(self.lb, 0, flag, 4) + + if self.kind == 'path': + v = str(v) + v = path_expand_cmd(v) + v = os.path.expandvars(os.path.expanduser(v)) + + style = wx.TE_PROCESS_ENTER + wx_flag_get( self.var.get('str_flags', []) ) + + self.tc = wx.TextCtrl(self, wx.ID_ANY, str(v), style=style, size=(130,-1)) + self.Bind(wx.EVT_TEXT_ENTER, self.OnUpdate, self.tc) + + if self.kind in ('num', None): + if self.has_slider: + self.w = self.max - self.min + vlst = [ v, self.min, self.max, self.var['v'] ] + self.is_float = len( [ v_ for v_ in vlst if type(v_) is not int ] ) > 0 + self.int_max = 1000 if self.is_float else self.max + self.int_min = 0 if self.is_float else self.min + + self.slider = wx.Slider(self, wx.ID_ANY, self.get_int_v(), self.int_min, self.int_max) + self.Bind(wx.EVT_COMMAND_SCROLL, self.OnScroll, self.slider) + self.slider.SetMinSize((82, 27)) + szr.Add(self.slider, 1, wx.LEFT | wx.RIGHT | wx.ALIGN_CENTER_VERTICAL, 4) + else: + self.is_float = type(self.var['v']) is not int + self.tc.SetMinSize((40,27)) + + flag = wx.ALIGN_CENTER_VERTICAL + prop = 1 if self.kind == 'path' or self.kind == 'str' else 0 + szr.Add(self.tc, prop, flag, 4) + + if self.kind == 'path': + self.ref = wx.Button(self, wx.ID_ANY, 'Ref') + self.Bind(wx.EVT_BUTTON, self.OnRef, self.ref) + button_color_hdr_setup(self.ref) + self.ref.SetMinSize((40,29)) + szr.Add(self.ref, 0, flag, 4) + + if self.has_slider or self.kind == 'num': + vszr = wx.BoxSizer(wx.VERTICAL) + vszr.Add( self.create_bmbtn("images/inc.png", self.OnIncBtn) ) + vszr.Add( self.create_bmbtn("images/dec.png", self.OnDecBtn) ) + szr.Add(vszr, 0, wx.ALIGN_CENTER_VERTICAL) + + self.SetSizer(szr) + + def _get_topics_by_type(self, message_type): + #get list of current available topics: + ros_topics = rospy.get_published_topics() + matched_topics = list(filter(lambda x: x[1]==message_type,ros_topics)) + topic_names = [x[0] for x in matched_topics] + topic_names.sort() + return topic_names + + def setup_tooltip(self): + if get_tooltips(self.var): + set_tooltips(self.obj, self.var) + if get_tooltip(self.var): + obj = self.lb if self.lb else (self if self.kind == 'radio_box' else self.obj) + set_tooltip(obj, self.var) + + def create_bmbtn(self, filename, hdr): + dir = rtmgr_src_dir() + bm = wx.Bitmap(dir + filename, wx.BITMAP_TYPE_ANY) + style = wx.BORDER_NONE | wx.BU_EXACTFIT + obj = wx.lib.buttons.GenBitmapButton(self, wx.ID_ANY, bm, style=style) + self.Bind(wx.EVT_BUTTON, hdr, obj) + return obj + + def get_v(self): + if self.kind in [ 'radio_box', 'menu' ]: + return self.choices_sel_get() + if self.kind in [ 'checkbox', 'toggle_button', 'topic' ]: + return self.obj.GetValue() + if self.kind == 'checkboxes': + return self.obj.get() + if self.kind == 'hide': + return self.var.get('v') + if self.kind in [ 'path', 'str' ]: + return str(self.tc.GetValue()) + + if not self.has_slider and self.tc.GetValue() == '': + return '' + return self.get_tc_v() + + def get_tc_v(self): + s = self.tc.GetValue() + v = str_to_float(s) if self.is_float else int(s) + if self.has_slider: + v = self.min if v < self.min else v + v = self.max if v > self.max else v + self.tc.SetValue(adjust_num_str(str(v))) + return v + + def get_int_v(self): + v = self.get_tc_v() + if self.is_float: + v = int( self.int_max * (v - self.min) / self.w if self.w != 0 else 0 ) + return v + + def OnScroll(self, event): + iv = self.slider.GetValue() + s = str(iv) + if self.is_float: + v = self.min + float(self.w) * iv / self.int_max + s = str(Decimal(v).quantize(Decimal(str(self.get_step())))) + self.tc.SetValue(s) + self.update(self.var) + + def OnIncBtn(self, event): + step = self.get_step() + self.add_v(step) + + def OnDecBtn(self, event): + step = self.get_step() + self.add_v(-step) + + def get_step(self): + step = self.var.get('step') + return step if step else 0.01 if self.is_float else 1 + + def add_v(self, step): + ov = self.get_v() + self.tc.SetValue(str(ov + step)) + v = self.get_v() + if v != ov: + if self.has_slider: + self.slider.SetValue(self.get_int_v()) + self.update(self.var) + + def OnUpdate(self, event): + if self.has_slider: + self.slider.SetValue(self.get_int_v()) + self.update(self.var) + + def OnRef(self, event): + if file_dialog(self, self.tc, self.var) == wx.ID_OK: + self.update(self.var) + + def choices_sel_get(self): + return self.obj.GetStringSelection() if self.var.get('choices_type') == 'str' else self.obj.GetSelection() + + def choices_sel_set(self, v): + if self.var.get('choices_type') == 'str': + self.obj.SetStringSelection(v) + else: + self.obj.SetSelection(v) + + def is_nl(self): + return self.has_slider or self.kind in [ 'path' ] class MyDialogParam(rtmgr.MyDialogParam): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.pdic_bak = pdic.copy() - gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogParam.__init__(self, *args, **kwds) - set_size_gdic(self, gdic) - - self.Bind(wx.EVT_CLOSE, self.OnClose) - - ok_lb_key = 'open_dialog_ok_label' - if dic_list_get(gdic, 'dialog_type', 'config') == 'open' and ok_lb_key in gdic: - self.button_1.SetLabel( gdic.get(ok_lb_key) ) - - parent = self.panel_v - frame = self.GetParent() - self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) - szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) - - self.SetTitle(prm.get('name', '')) - (w,h) = self.GetSize() - (w2,_) = szr.GetMinSize() - w2 += 20 - if w2 > w: - self.SetSize((w2,h)) - - def OnOk(self, event): - self.panel.update() - self.panel.detach_func() - self.EndModal(0) - - def OnCancel(self, event): - self.panel.pdic.update(self.pdic_bak) # restore - self.panel.detach_func() - self.panel.update() - self.EndModal(-1) - - def OnClose(self, event): - self.OnCancel(event) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.pdic_bak = pdic.copy() + gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogParam.__init__(self, *args, **kwds) + set_size_gdic(self, gdic) + + self.Bind(wx.EVT_CLOSE, self.OnClose) + + ok_lb_key = 'open_dialog_ok_label' + if dic_list_get(gdic, 'dialog_type', 'config') == 'open' and ok_lb_key in gdic: + self.button_1.SetLabel( gdic.get(ok_lb_key) ) + + parent = self.panel_v + frame = self.GetParent() + self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) + szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) + + self.SetTitle(prm.get('name', '')) + (w,h) = self.GetSize() + (w2,_) = szr.GetMinSize() + w2 += 20 + if w2 > w: + self.SetSize((w2,h)) + + def OnOk(self, event): + self.panel.update() + self.panel.detach_func() + self.EndModal(0) + + def OnCancel(self, event): + self.panel.pdic.update(self.pdic_bak) # restore + self.panel.detach_func() + self.panel.update() + self.EndModal(-1) + + def OnClose(self, event): + self.OnCancel(event) class MyDialogDPM(rtmgr.MyDialogDPM): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.pdic_bak = pdic.copy() - gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogDPM.__init__(self, *args, **kwds) - set_size_gdic(self, gdic) - - self.Bind(wx.EVT_CLOSE, self.OnClose) - - parent = self.panel_v - frame = self.GetParent() - self.frame = frame - self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) - szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) - - self.SetTitle(prm.get('name', '')) - (w,h) = self.GetSize() - (w2,_) = szr.GetMinSize() - w2 += 20 - if w2 > w: - self.SetSize((w2,h)) - - fix_link_color(self.hyperlink_car) - fix_link_color(self.hyperlink_pedestrian) - - def OnOk(self, event): - self.panel.update() - self.panel.detach_func() - self.EndModal(0) - - def OnLink(self, event): - obj = event.GetEventObject() - dic = { self.hyperlink_car : self.frame.button_car_dpm, - self.hyperlink_pedestrian : self.frame.button_pedestrian_dpm } - obj = dic.get(obj) - if obj: - self.frame.OnHyperlinked_obj(obj) - - def OnCancel(self, event): - self.panel.pdic.update(self.pdic_bak) # restore - self.panel.detach_func() - self.panel.update() - self.EndModal(-1) - - def OnClose(self, event): - self.OnCancel(event) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.pdic_bak = pdic.copy() + gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogDPM.__init__(self, *args, **kwds) + set_size_gdic(self, gdic) + + self.Bind(wx.EVT_CLOSE, self.OnClose) + + parent = self.panel_v + frame = self.GetParent() + self.frame = frame + self.panel = ParamPanel(parent, frame=frame, pdic=pdic, gdic=gdic, prm=prm) + szr = sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) + + self.SetTitle(prm.get('name', '')) + (w,h) = self.GetSize() + (w2,_) = szr.GetMinSize() + w2 += 20 + if w2 > w: + self.SetSize((w2,h)) + + fix_link_color(self.hyperlink_car) + fix_link_color(self.hyperlink_pedestrian) + + def OnOk(self, event): + self.panel.update() + self.panel.detach_func() + self.EndModal(0) + + def OnLink(self, event): + obj = event.GetEventObject() + dic = { self.hyperlink_car : self.frame.button_car_dpm, + self.hyperlink_pedestrian : self.frame.button_pedestrian_dpm } + obj = dic.get(obj) + if obj: + self.frame.OnHyperlinked_obj(obj) + + def OnCancel(self, event): + self.panel.pdic.update(self.pdic_bak) # restore + self.panel.detach_func() + self.panel.update() + self.EndModal(-1) + + def OnClose(self, event): + self.OnCancel(event) class MyDialogCarPedestrian(rtmgr.MyDialogCarPedestrian): - def __init__(self, *args, **kwds): - pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - prm = kwds.pop('prm') - rtmgr.MyDialogCarPedestrian.__init__(self, *args, **kwds) - set_size_gdic(self) + def __init__(self, *args, **kwds): + pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + prm = kwds.pop('prm') + rtmgr.MyDialogCarPedestrian.__init__(self, *args, **kwds) + set_size_gdic(self) - self.Bind(wx.EVT_CLOSE, self.OnClose) + self.Bind(wx.EVT_CLOSE, self.OnClose) - frame = self.GetParent() - self.frame = frame + frame = self.GetParent() + self.frame = frame - self.SetTitle(prm.get('name', '')) + self.SetTitle(prm.get('name', '')) - fix_link_color(self.hyperlink_car) - fix_link_color(self.hyperlink_pedestrian) + fix_link_color(self.hyperlink_car) + fix_link_color(self.hyperlink_pedestrian) - def OnLink(self, event): - obj = event.GetEventObject() - car_ped = { self.hyperlink_car : 'car', self.hyperlink_pedestrian : 'pedestrian' }.get(obj, 'car') - obj_key = self.gdic.get('car_pedestrian_obj_key', {}).get(car_ped) - obj = getattr(self.frame, 'button_' + obj_key, None) if obj_key else None - if obj: - self.frame.OnHyperlinked_obj(obj) - self.EndModal(0) + def OnLink(self, event): + obj = event.GetEventObject() + car_ped = { self.hyperlink_car : 'car', self.hyperlink_pedestrian : 'pedestrian' }.get(obj, 'car') + obj_key = self.gdic.get('car_pedestrian_obj_key', {}).get(car_ped) + obj = getattr(self.frame, 'button_' + obj_key, None) if obj_key else None + if obj: + self.frame.OnHyperlinked_obj(obj) + self.EndModal(0) - def OnClose(self, event): - self.EndModal(-1) + def OnClose(self, event): + self.EndModal(-1) class MyDialogLaneStop(rtmgr.MyDialogLaneStop): - def __init__(self, *args, **kwds): - self.pdic = kwds.pop('pdic') - self.gdic = kwds.pop('gdic') - self.prm = kwds.pop('prm') - rtmgr.MyDialogLaneStop.__init__(self, *args, **kwds) - set_size_gdic(self) - self.frame = self.GetParent() - - name = 'lane_stop' - var = next( ( var for var in self.prm.get('vars', []) if var.get('name') == name ), {} ) - v = self.pdic.get( name, var.get('v', False) ) - set_val(self.checkbox_lane_stop, v) - - def update(self): - update_func = self.gdic.get('update_func') - if update_func: - update_func(self.pdic, self.gdic, self.prm) - - def OnTrafficRedLight(self, event): - self.pdic['traffic_light'] = 0 - self.update() - - def OnTrafficGreenLight(self, event): - self.pdic['traffic_light'] = 1 - self.update() - - def OnTrafficLightRecognition(self, event): - pub = rospy.Publisher('/config/lane_stop', ConfigLaneStop, latch=True, queue_size=10) - msg = ConfigLaneStop() - v = event.GetEventObject().GetValue() - self.pdic['lane_stop'] = v - msg.manual_detection = not v - pub.publish(msg) - - def OnOk(self, event): - self.EndModal(0) - - def OnCancel(self, event): - self.EndModal(-1) + def __init__(self, *args, **kwds): + self.pdic = kwds.pop('pdic') + self.gdic = kwds.pop('gdic') + self.prm = kwds.pop('prm') + rtmgr.MyDialogLaneStop.__init__(self, *args, **kwds) + set_size_gdic(self) + self.frame = self.GetParent() + + name = 'lane_stop' + var = next( ( var for var in self.prm.get('vars', []) if var.get('name') == name ), {} ) + v = self.pdic.get( name, var.get('v', False) ) + set_val(self.checkbox_lane_stop, v) + + def update(self): + update_func = self.gdic.get('update_func') + if update_func: + update_func(self.pdic, self.gdic, self.prm) + + def OnTrafficRedLight(self, event): + self.pdic['traffic_light'] = 0 + self.update() + + def OnTrafficGreenLight(self, event): + self.pdic['traffic_light'] = 1 + self.update() + + def OnTrafficLightRecognition(self, event): + pub = rospy.Publisher('/config/lane_stop', ConfigLaneStop, latch=True, queue_size=10) + msg = ConfigLaneStop() + v = event.GetEventObject().GetValue() + self.pdic['lane_stop'] = v + msg.manual_detection = not v + pub.publish(msg) + + def OnOk(self, event): + self.EndModal(0) + + def OnCancel(self, event): + self.EndModal(-1) class MyDialogNDTMapping(rtmgr.MyDialogNDTMapping): - def __init__(self, *args, **kwds): - self.pdic = kwds.pop('pdic') - self.pdic_bak = self.pdic.copy() - self.gdic = kwds.pop('gdic') - self.prm = kwds.pop('prm') - rtmgr.MyDialogNDTMapping.__init__(self, *args, **kwds) - set_size_gdic(self) - - parent = self.panel_v - frame = self.GetParent() - self.panel = ParamPanel(parent, frame=frame, pdic=self.pdic, gdic=self.gdic, prm=self.prm) - sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) - - self.update_filename() - self.klass_msg = ConfigNDTMappingOutput - self.pub = rospy.Publisher('/config/ndt_mapping_output', self.klass_msg, queue_size=10) - - def update_filename(self): - tc = self.text_ctrl_path - path = tc.GetValue() - (dn, fn) = os.path.split(path) - now = datetime.datetime.now() - fn = 'autoware-%02d%02d%02d.pcd' % ( - now.year % 100, now.month, now.day) - path = os.path.join(dn, fn) - set_path(tc, path) - - def OnRef(self, event): - tc = self.text_ctrl_path - file_dialog(self, tc, { 'path_type' : 'save' } ) - - def OnRadio(self, event): - v = self.radio_btn_filter_resolution.GetValue() - tc = self.text_ctrl_filter_resolution - tc.Enable(v) - - def OnPcdOutput(self, event): - tc = self.text_ctrl_filter_resolution - v = tc.GetValue() if self.radio_btn_filter_resolution.GetValue() else '0.0' - msg = self.klass_msg() - msg.filename = self.text_ctrl_path.GetValue() - msg.filter_res = str_to_float(v) - self.pub.publish(msg) - - def OnOk(self, event): - self.panel.detach_func() - self.EndModal(0) + def __init__(self, *args, **kwds): + self.pdic = kwds.pop('pdic') + self.pdic_bak = self.pdic.copy() + self.gdic = kwds.pop('gdic') + self.prm = kwds.pop('prm') + rtmgr.MyDialogNDTMapping.__init__(self, *args, **kwds) + set_size_gdic(self) + + parent = self.panel_v + frame = self.GetParent() + self.panel = ParamPanel(parent, frame=frame, pdic=self.pdic, gdic=self.gdic, prm=self.prm) + sizer_wrap((self.panel,), wx.VERTICAL, 1, wx.EXPAND, 0, parent) + + self.update_filename() + self.klass_msg = ConfigNDTMappingOutput + self.pub = rospy.Publisher('/config/ndt_mapping_output', self.klass_msg, queue_size=10) + + def update_filename(self): + tc = self.text_ctrl_path + path = tc.GetValue() + (dn, fn) = os.path.split(path) + now = datetime.datetime.now() + fn = 'autoware-%02d%02d%02d.pcd' % ( + now.year % 100, now.month, now.day) + path = os.path.join(dn, fn) + set_path(tc, path) + + def OnRef(self, event): + tc = self.text_ctrl_path + file_dialog(self, tc, { 'path_type' : 'save' } ) + + def OnRadio(self, event): + v = self.radio_btn_filter_resolution.GetValue() + tc = self.text_ctrl_filter_resolution + tc.Enable(v) + + def OnPcdOutput(self, event): + tc = self.text_ctrl_filter_resolution + v = tc.GetValue() if self.radio_btn_filter_resolution.GetValue() else '0.0' + msg = self.klass_msg() + msg.filename = self.text_ctrl_path.GetValue() + msg.filter_res = str_to_float(v) + self.pub.publish(msg) + + def OnOk(self, event): + self.panel.detach_func() + self.EndModal(0) class InfoBarLabel(wx.BoxSizer): - def __init__(self, parent, btm_txt=None, lmt_bar_prg=90, bar_orient=wx.VERTICAL): - wx.BoxSizer.__init__(self, orient=wx.VERTICAL) - self.lb = wx.StaticText(parent, wx.ID_ANY, '') - self.bar = BarLabel(parent, hv=bar_orient, show_lb=False) - bt = wx.StaticText(parent, wx.ID_ANY, btm_txt) if btm_txt else None - - self.Add(self.lb, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) - if bar_orient == wx.VERTICAL: - sz = self.bar.GetSize() - sz.SetWidth(20) - self.bar.SetMinSize(sz) - self.Add(self.bar, 1, wx.ALIGN_CENTER_HORIZONTAL, 0) - if bt: - self.Add(bt, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) - else: - szr = wx.BoxSizer(wx.HORIZONTAL) - if bt: - szr.Add(bt, 0, 0, 0) - szr.Add(self.bar, 1, 0, 0) - self.Add(szr, 1, wx.EXPAND, 0) - - self.lmt_bar_prg = lmt_bar_prg - - def lb_set(self, txt, col): - self.lb.SetForegroundColour(col) - self.lb.SetLabel(txt); - self.Layout() - - def bar_set(self, prg): - (col1, col2) = (wx.Colour(0,0,250), wx.Colour(0,0,128)) - if prg >= self.lmt_bar_prg: - (col1, col2) = (wx.Colour(250,0,0), wx.Colour(128,0,0)) - self.bar.set_col(col1, col2) - self.bar.set(prg) + def __init__(self, parent, btm_txt=None, lmt_bar_prg=90, bar_orient=wx.VERTICAL): + wx.BoxSizer.__init__(self, orient=wx.VERTICAL) + self.lb = wx.StaticText(parent, wx.ID_ANY, '') + self.bar = BarLabel(parent, hv=bar_orient, show_lb=False) + bt = wx.StaticText(parent, wx.ID_ANY, btm_txt) if btm_txt else None + + self.Add(self.lb, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) + if bar_orient == wx.VERTICAL: + sz = self.bar.GetSize() + sz.SetWidth(20) + self.bar.SetMinSize(sz) + self.Add(self.bar, 1, wx.ALIGN_CENTER_HORIZONTAL, 0) + if bt: + self.Add(bt, 0, wx.ALIGN_CENTER_HORIZONTAL, 0) + else: + szr = wx.BoxSizer(wx.HORIZONTAL) + if bt: + szr.Add(bt, 0, 0, 0) + szr.Add(self.bar, 1, 0, 0) + self.Add(szr, 1, wx.EXPAND, 0) + + self.lmt_bar_prg = lmt_bar_prg + + def lb_set(self, txt, col): + self.lb.SetForegroundColour(col) + self.lb.SetLabel(txt); + self.Layout() + + def bar_set(self, prg): + (col1, col2) = (wx.Colour(0,0,250), wx.Colour(0,0,128)) + if prg >= self.lmt_bar_prg: + (col1, col2) = (wx.Colour(250,0,0), wx.Colour(128,0,0)) + self.bar.set_col(col1, col2) + self.bar.set(prg) class Checkboxes(wx.Panel): - def __init__(self, parent, item_n, lb): - wx.Panel.__init__(self, parent, wx.ID_ANY, wx.DefaultPosition, wx.DefaultSize) - self.boxes = [ wx.CheckBox(self, wx.ID_ANY, lb + str(i)) for i in range(item_n) ] - vsz = wx.BoxSizer(wx.VERTICAL) - for j in range((item_n + 7) / 8): - hsz = wx.BoxSizer(wx.HORIZONTAL) - for i in range(8): - idx = j * 8 + i - if idx < len(self.boxes): - hsz.Add(self.boxes[idx], 0, wx.LEFT, 8) - vsz.Add(hsz) - self.SetSizer(vsz) - vsz.Fit(self) - - def set(self, vs): - vs = vs if vs else [ True for box in self.boxes ] - for (box, v) in zip(self.boxes, vs): - box.SetValue(v) - - def get(self): - return [ box.GetValue() for box in self.boxes ] + def __init__(self, parent, item_n, lb): + wx.Panel.__init__(self, parent, wx.ID_ANY, wx.DefaultPosition, wx.DefaultSize) + self.boxes = [ wx.CheckBox(self, wx.ID_ANY, lb + str(i)) for i in range(item_n) ] + vsz = wx.BoxSizer(wx.VERTICAL) + for j in range((item_n + 7) / 8): + hsz = wx.BoxSizer(wx.HORIZONTAL) + for i in range(8): + idx = j * 8 + i + if idx < len(self.boxes): + hsz.Add(self.boxes[idx], 0, wx.LEFT, 8) + vsz.Add(hsz) + self.SetSizer(vsz) + vsz.Fit(self) + + def set(self, vs): + vs = vs if vs else [ True for box in self.boxes ] + for (box, v) in zip(self.boxes, vs): + box.SetValue(v) + + def get(self): + return [ box.GetValue() for box in self.boxes ] class BarLabel(wx.Panel): - def __init__(self, parent, txt='', pos=wx.DefaultPosition, size=wx.DefaultSize, style=0, hv=wx.HORIZONTAL, show_lb=True): - wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) - self.lb = wx.StaticText(self, wx.ID_ANY, '', style=style) - self.txt = txt - self.hv = hv - self.dir = wx.SOUTH if hv == wx.HORIZONTAL else wx.EAST - self.show_lb = show_lb - self.prg = -1 - - self.dflt_col1 = wx.Colour(250,250,250) - self.dflt_col2 = wx.Colour(128,128,128) - self.col1 = self.dflt_col1 - self.col2 = self.dflt_col2 - - self.Bind(wx.EVT_PAINT, self.OnPaint) - - def set(self, prg): - self.prg = prg - if self.show_lb: - self.lb.SetLabel(self.txt + str(prg) + '%' if prg >= 0 else '') - self.Refresh() - - def set_col(self, col1, col2): - self.col1 = col1 if col1 != wx.NullColour else self.dflt_col1 - self.col2 = col2 if col2 != wx.NullColour else self.dflt_col2 - - def clear(self): - self.set(-1) - - def OnPaint(self, event): - dc = wx.PaintDC(self) - (w,h) = self.GetSize() - if self.IsEnabled(): - p = (w if self.hv == wx.HORIZONTAL else h) * self.prg / 100 - rect = wx.Rect(0, 0, p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, h-p, w, p) - dc.GradientFillLinear(rect, self.col1, self.col2, self.dir) - rect = wx.Rect(p, 0, w-p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, 0, w, h-p) - dc.GradientFillLinear(rect, wx.Colour(200,200,200), wx.Colour(220,220,220), self.dir) - else: - rect = wx.Rect(0, 0, w, h) - dc.GradientFillLinear(rect, wx.Colour(250,250,250), wx.Colour(250,250,250), self.dir) + def __init__(self, parent, txt='', pos=wx.DefaultPosition, size=wx.DefaultSize, style=0, hv=wx.HORIZONTAL, show_lb=True): + wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) + self.lb = wx.StaticText(self, wx.ID_ANY, '', style=style) + self.txt = txt + self.hv = hv + self.dir = wx.SOUTH if hv == wx.HORIZONTAL else wx.EAST + self.show_lb = show_lb + self.prg = -1 + + self.dflt_col1 = wx.Colour(250,250,250) + self.dflt_col2 = wx.Colour(128,128,128) + self.col1 = self.dflt_col1 + self.col2 = self.dflt_col2 + + self.Bind(wx.EVT_PAINT, self.OnPaint) + + def set(self, prg): + self.prg = prg + if self.show_lb: + self.lb.SetLabel(self.txt + str(prg) + '%' if prg >= 0 else '') + self.Refresh() + + def set_col(self, col1, col2): + self.col1 = col1 if col1 != wx.NullColour else self.dflt_col1 + self.col2 = col2 if col2 != wx.NullColour else self.dflt_col2 + + def clear(self): + self.set(-1) + + def OnPaint(self, event): + dc = wx.PaintDC(self) + (w,h) = self.GetSize() + if self.IsEnabled(): + p = (w if self.hv == wx.HORIZONTAL else h) * self.prg / 100 + rect = wx.Rect(0, 0, p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, h-p, w, p) + dc.GradientFillLinear(rect, self.col1, self.col2, self.dir) + rect = wx.Rect(p, 0, w-p, h) if self.hv == wx.HORIZONTAL else wx.Rect(0, 0, w, h-p) + dc.GradientFillLinear(rect, wx.Colour(200,200,200), wx.Colour(220,220,220), self.dir) + else: + rect = wx.Rect(0, 0, w, h) + dc.GradientFillLinear(rect, wx.Colour(250,250,250), wx.Colour(250,250,250), self.dir) class ColorLabel(wx.Panel): - def __init__(self, parent, lst=[], pos=wx.DefaultPosition, size=wx.DefaultSize, style=0): - wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) - self.lst = lst - self.Bind(wx.EVT_PAINT, self.OnPaint) - - def set(self, lst): - self.lst = lst - self.Refresh() - - def OnPaint(self, event): - dc = wx.PaintDC(self) - dc.Clear() - - #change_font_point_by_rate(dc, 0.75) - - (x,y) = (0,0) - (_, h, _, _) = dc.GetFullTextExtent(' ') - for v in self.lst: - if type(v) is tuple and len(v) == 2: - (x,y) = v - elif type(v) is tuple and len(v) == 3: - dc.SetTextForeground(v) - elif v == '\n': - (x,y) = (0,y+h) - elif type(v) is str: - dc.DrawText(v, x, y) - (w, _, _, _) = dc.GetFullTextExtent(v) - x += w + def __init__(self, parent, lst=[], pos=wx.DefaultPosition, size=wx.DefaultSize, style=0): + wx.Panel.__init__(self, parent, wx.ID_ANY, pos, size) + self.lst = lst + self.Bind(wx.EVT_PAINT, self.OnPaint) + + def set(self, lst): + self.lst = lst + self.Refresh() + + def OnPaint(self, event): + dc = wx.PaintDC(self) + dc.Clear() + + #change_font_point_by_rate(dc, 0.75) + + (x,y) = (0,0) + (_, h, _, _) = dc.GetFullTextExtent(' ') + for v in self.lst: + if type(v) is tuple and len(v) == 2: + (x,y) = v + elif type(v) is tuple and len(v) == 3: + dc.SetTextForeground(v) + elif v == '\n': + (x,y) = (0,y+h) + elif type(v) is str: + dc.DrawText(v, x, y) + (w, _, _, _) = dc.GetFullTextExtent(v) + x += w class StrValObj: - def __init__(self, s, v): - self.s = s - self.v = v - def GetValue(self): - return self.v - def SetValue(self, v): - self.v = v + def __init__(self, s, v): + self.s = s + self.v = v + def GetValue(self): + return self.v + def SetValue(self, v): + self.v = v class MyApp(wx.App): - def OnInit(self): - wx.InitAllImageHandlers() - frame_1 = MyFrame(None, wx.ID_ANY, "") - self.SetTopWindow(frame_1) - buttons_color_hdr_setup(frame_1) - frame_1.Show() - return 1 + def OnInit(self): + wx.InitAllImageHandlers() + frame_1 = MyFrame(None, wx.ID_ANY, "") + self.SetTopWindow(frame_1) + buttons_color_hdr_setup(frame_1) + frame_1.Show() + return 1 class MyDialogROSbagRecord(rtmgr.MyDialogROSbagRecord): - def __init__(self, *args, **kwds): - self.cmd_dic = kwds.pop('cmd_dic') - rtmgr.MyDialogROSbagRecord.__init__(self, *args, **kwds) - self.cbs = [] - self.refresh() - self.parent = self.GetParent() - self.cmd_dic[ self.button_start ] = ('rosbag record', None) - self.toggles = [ self.button_start, self.button_stop ] - - def OnRef(self, event): - tc = self.text_ctrl - file_dialog(self, tc, { 'path_type' : 'save' } ) - - def OnStart(self, event): - key_obj = self.button_start - path = self.text_ctrl.GetValue() - if path == '': - print('path=""') - return - topic_opt = [] - if self.cbs[0].GetValue(): # 'All' - topic_opt = [ '-a' ] - else: - for obj in self.cbs: - if obj.GetValue(): - topic_opt += [ obj.GetLabel() ] - if topic_opt == []: - print('topic=[]') - return - args = topic_opt + [ '-O', path ] - - split_arg = [ '--split' ] if self.checkbox_split.GetValue() else [] - size_arg = self.size_arg_get() - if split_arg and not size_arg: - wx.MessageBox('size is required, with split') - return - args += split_arg + size_arg - - (cmd, proc) = self.cmd_dic[ key_obj ] - proc = self.parent.launch_kill(True, cmd, proc, add_args=args, obj=key_obj, kill_children=True) - self.cmd_dic[ key_obj ] = (cmd, proc) - self.parent.toggle_enables(self.toggles) - - def OnStop(self, event): - key_obj = self.button_start - (cmd, proc) = self.cmd_dic[ key_obj ] - proc = self.parent.launch_kill(False, cmd, proc, sigint=True, obj=key_obj, kill_children=True) - self.cmd_dic[ key_obj ] = (cmd, proc) - self.parent.toggle_enables(self.toggles) - self.Hide() - - def OnRefresh(self, event): - self.refresh() - - def refresh(self): - lst = [ 'all' ] + subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') - panel = self.panel_1 - szr = self.sizer_topic - for obj in self.cbs: - szr.Remove(obj) - obj.Destroy() - self.cbs = [] - for topic in lst: - obj = wx.CheckBox(panel, wx.ID_ANY, topic) - bdr = 4 if topic == 'All' else 4 * 4 - szr.Add(obj, 0, wx.LEFT, bdr) - self.cbs.append(obj) - szr.Layout() - panel.SetVirtualSize(szr.GetMinSize()) - - def show(self): - self.Show() - self.update_filename() - - def update_filename(self): - tc = self.text_ctrl - path = tc.GetValue() - (dn, fn) = os.path.split(path) - now = datetime.datetime.now() - fn = 'autoware-%04d%02d%02d%02d%02d%02d' % ( - now.year, now.month, now.day, now.hour, now.minute, now.second) - path = os.path.join(dn, fn) - set_path(tc, path) - - def size_arg_get(self): - tc = self.text_ctrl_size - s = tc.GetValue() - mb = 0 - try: - mb = str_to_float(s) - except ValueError: - mb = 0 - if mb <= 0: - tc.SetValue('') - return [ '--size=' + str(int(mb)) ] if mb > 0 else [] + def __init__(self, *args, **kwds): + self.cmd_dic = kwds.pop('cmd_dic') + rtmgr.MyDialogROSbagRecord.__init__(self, *args, **kwds) + self.cbs = [] + self.refresh() + self.parent = self.GetParent() + self.cmd_dic[ self.button_start ] = ('rosbag record', None) + self.toggles = [ self.button_start, self.button_stop ] + + def OnRef(self, event): + tc = self.text_ctrl + file_dialog(self, tc, { 'path_type' : 'save' } ) + + def OnStart(self, event): + key_obj = self.button_start + path = self.text_ctrl.GetValue() + if path == '': + print('path=""') + return + topic_opt = [] + if self.cbs[0].GetValue(): # 'All' + topic_opt = [ '-a' ] + else: + for obj in self.cbs: + if obj.GetValue(): + topic_opt += [ obj.GetLabel() ] + if topic_opt == []: + print('topic=[]') + return + args = topic_opt + [ '-O', path ] + + split_arg = [ '--split' ] if self.checkbox_split.GetValue() else [] + size_arg = self.size_arg_get() + if split_arg and not size_arg: + wx.MessageBox('size is required, with split') + return + args += split_arg + size_arg + + (cmd, proc) = self.cmd_dic[ key_obj ] + proc = self.parent.launch_kill(True, cmd, proc, add_args=args, obj=key_obj, kill_children=True) + self.cmd_dic[ key_obj ] = (cmd, proc) + self.parent.toggle_enables(self.toggles) + + def OnStop(self, event): + key_obj = self.button_start + (cmd, proc) = self.cmd_dic[ key_obj ] + proc = self.parent.launch_kill(False, cmd, proc, sigint=True, obj=key_obj, kill_children=True) + self.cmd_dic[ key_obj ] = (cmd, proc) + self.parent.toggle_enables(self.toggles) + self.Hide() + + def OnRefresh(self, event): + self.refresh() + + def refresh(self): + lst = [ 'all' ] + subprocess.check_output([ 'rostopic', 'list' ]).strip().split('\n') + panel = self.panel_1 + szr = self.sizer_topic + for obj in self.cbs: + szr.Remove(obj) + obj.Destroy() + self.cbs = [] + for topic in lst: + obj = wx.CheckBox(panel, wx.ID_ANY, topic) + bdr = 4 if topic == 'All' else 4 * 4 + szr.Add(obj, 0, wx.LEFT, bdr) + self.cbs.append(obj) + szr.Layout() + panel.SetVirtualSize(szr.GetMinSize()) + + def show(self): + self.Show() + self.update_filename() + + def update_filename(self): + tc = self.text_ctrl + path = tc.GetValue() + (dn, fn) = os.path.split(path) + now = datetime.datetime.now() + fn = 'autoware-%04d%02d%02d%02d%02d%02d' % ( + now.year, now.month, now.day, now.hour, now.minute, now.second) + path = os.path.join(dn, fn) + set_path(tc, path) + + def size_arg_get(self): + tc = self.text_ctrl_size + s = tc.GetValue() + mb = 0 + try: + mb = str_to_float(s) + except ValueError: + mb = 0 + if mb <= 0: + tc.SetValue('') + return [ '--size=' + str(int(mb)) ] if mb > 0 else [] def set_size_gdic(dlg, gdic={}): - (w, h) = dlg.GetSize() - if not gdic: - gdic = getattr(dlg, 'gdic', {}) - nw = gdic.get('dialog_width', w) - nh = gdic.get('dialog_height', h) - if (w, h) != (nw, nh): - dlg.SetSize((nw, nh)) + (w, h) = dlg.GetSize() + if not gdic: + gdic = getattr(dlg, 'gdic', {}) + nw = gdic.get('dialog_width', w) + nh = gdic.get('dialog_height', h) + if (w, h) != (nw, nh): + dlg.SetSize((nw, nh)) def file_dialog(parent, tc, path_inf_dic={}): - path = tc.GetValue() - path = get_top(path.split(','), path) - (dn, fn) = os.path.split(path) - path_type = path_inf_dic.get('path_type') - if path_type == 'dir': - fns = path_inf_dic.get('filenames') - if type(fns) is str and fns[-5:] == '.yaml': - fns = load_yaml(fns) - if type(fns) is not list: - fns = None - path_inf_dic['filenames'] = fns - dlg = wx.DirDialog(parent, defaultPath=path) - else: - st_dic = { 'save' : wx.FD_SAVE, 'multi' : wx.FD_MULTIPLE } - dlg = wx.FileDialog(parent, defaultDir=dn, defaultFile=fn, - style=st_dic.get(path_type, wx.FD_DEFAULT_STYLE)) - ret = show_modal(dlg) - if ret == wx.ID_OK: - path = ','.join(dlg.GetPaths()) if path_type == 'multi' else dlg.GetPath() - if path_type == 'dir' and fns: - path = ','.join([ path + '/' + fn for fn in fns ]) - set_path(tc, path) - dlg.Destroy() - return ret + path = tc.GetValue() + path = get_top(path.split(','), path) + (dn, fn) = os.path.split(path) + path_type = path_inf_dic.get('path_type') + if path_type == 'dir': + fns = path_inf_dic.get('filenames') + if type(fns) is str and fns[-5:] == '.yaml': + fns = load_yaml(fns) + if type(fns) is not list: + fns = None + path_inf_dic['filenames'] = fns + dlg = wx.DirDialog(parent, defaultPath=path) + else: + st_dic = { 'save' : wx.FD_SAVE, 'multi' : wx.FD_MULTIPLE } + dlg = wx.FileDialog(parent, defaultDir=dn, defaultFile=fn, + style=st_dic.get(path_type, wx.FD_DEFAULT_STYLE)) + ret = show_modal(dlg) + if ret == wx.ID_OK: + path = ','.join(dlg.GetPaths()) if path_type == 'multi' else dlg.GetPath() + if path_type == 'dir' and fns: + path = ','.join([ path + '/' + fn for fn in fns ]) + set_path(tc, path) + dlg.Destroy() + return ret def post_evt_toggle_obj(win, obj, v): - evt_id = { - CT.GenericTreeItem : CT.wxEVT_TREE_ITEM_CHECKED, - wx.CheckBox : wx.EVT_CHECKBOX.typeId, - wx.ToggleButton : wx.EVT_TOGGLEBUTTON.typeId, - wx.Button : wx.EVT_BUTTON.typeId, - }.get( type(obj) ) - - if evt_id == CT.wxEVT_TREE_ITEM_CHECKED: - evt = CT.TreeEvent( evt_id, win.GetId() ) - evt.SetItem(obj) - else: - evt = wx.PyCommandEvent( evt_id, obj.GetId() ) - evt.SetEventObject(obj) - - set_val(obj, v) - wx.PostEvent(win, evt) + evt_id = { + CT.GenericTreeItem : CT.wxEVT_TREE_ITEM_CHECKED, + wx.CheckBox : wx.EVT_CHECKBOX.typeId, + wx.ToggleButton : wx.EVT_TOGGLEBUTTON.typeId, + wx.Button : wx.EVT_BUTTON.typeId, + }.get( type(obj) ) + + if evt_id == CT.wxEVT_TREE_ITEM_CHECKED: + evt = CT.TreeEvent( evt_id, win.GetId() ) + evt.SetItem(obj) + else: + evt = wx.PyCommandEvent( evt_id, obj.GetId() ) + evt.SetEventObject(obj) + + set_val(obj, v) + wx.PostEvent(win, evt) def button_color_change(btn, v=None): - if v is None and type(btn) is wx.ToggleButton: - v = btn.GetValue() - key = ( v , btn.IsEnabled() ) - dic = { (True,True):('#F9F9F8','#8B8BB9'), (True,False):('#F9F9F8','#E0E0F0') } - (fcol, bcol) = dic.get(key, (wx.NullColour, wx.NullColour)) - btn.SetForegroundColour(fcol) - btn.SetBackgroundColour(bcol) + if v is None and type(btn) is wx.ToggleButton: + v = btn.GetValue() + key = ( v , btn.IsEnabled() ) + dic = { (True,True):('#F9F9F8','#8B8BB9'), (True,False):('#F9F9F8','#E0E0F0') } + (fcol, bcol) = dic.get(key, (wx.NullColour, wx.NullColour)) + btn.SetForegroundColour(fcol) + btn.SetBackgroundColour(bcol) def OnButtonColorHdr(event): - btn = event.GetEventObject() - dic = { wx.EVT_TOGGLEBUTTON.typeId : None, - wx.EVT_LEFT_DOWN.typeId : True, - wx.EVT_LEFT_UP.typeId : False } - v = dic.get(event.GetEventType(), '?') - if v != '?': - button_color_change(btn, v) - event.Skip() + btn = event.GetEventObject() + dic = { wx.EVT_TOGGLEBUTTON.typeId : None, + wx.EVT_LEFT_DOWN.typeId : True, + wx.EVT_LEFT_UP.typeId : False } + v = dic.get(event.GetEventType(), '?') + if v != '?': + button_color_change(btn, v) + event.Skip() btn_null_bgcol = None def is_btn_null_bgcol(btn): - global btn_null_bgcol - bak = btn.GetBackgroundColour() - if btn_null_bgcol is None: - btn.SetBackgroundColour(wx.NullColour) - btn_null_bgcol = btn.GetBackgroundColour() - if bak != btn_null_bgcol: - btn.SetBackgroundColour(bak) - return bak == btn_null_bgcol + global btn_null_bgcol + bak = btn.GetBackgroundColour() + if btn_null_bgcol is None: + btn.SetBackgroundColour(wx.NullColour) + btn_null_bgcol = btn.GetBackgroundColour() + if bak != btn_null_bgcol: + btn.SetBackgroundColour(bak) + return bak == btn_null_bgcol def button_color_hdr_setup(btn): - hdr = OnButtonColorHdr - if type(btn) is wx.ToggleButton: - btn.Bind(wx.EVT_TOGGLEBUTTON, hdr) - elif type(btn) is wx.Button and is_btn_null_bgcol(btn): - btn.Bind(wx.EVT_LEFT_DOWN, hdr) - btn.Bind(wx.EVT_LEFT_UP, hdr) + hdr = OnButtonColorHdr + if type(btn) is wx.ToggleButton: + btn.Bind(wx.EVT_TOGGLEBUTTON, hdr) + elif type(btn) is wx.Button and is_btn_null_bgcol(btn): + btn.Bind(wx.EVT_LEFT_DOWN, hdr) + btn.Bind(wx.EVT_LEFT_UP, hdr) def buttons_color_hdr_setup(frm_obj): - key = 'button_' - btns = [ getattr(frm_obj, nm) for nm in dir(frm_obj) if nm[:len(key)] == key ] - for btn in btns: - button_color_hdr_setup(btn) + key = 'button_' + btns = [ getattr(frm_obj, nm) for nm in dir(frm_obj) if nm[:len(key)] == key ] + for btn in btns: + button_color_hdr_setup(btn) def show_modal(dlg): - buttons_color_hdr_setup(dlg) - return dlg.ShowModal() + buttons_color_hdr_setup(dlg) + return dlg.ShowModal() def load_yaml(filename, def_ret=None): - dir = rtmgr_src_dir() - path = dir + filename - if not os.path.isfile(path): - return def_ret - print('loading ' + filename) - f = open(dir + filename, 'r') - d = yaml.load(f) - f.close() - return d + dir = rtmgr_src_dir() + path = dir + filename + if not os.path.isfile(path): + return def_ret + print('loading ' + filename) + f = open(dir + filename, 'r') + d = yaml.load(f) + f.close() + return d def terminate_children(proc, sigint=False): for child in get_proc_children(proc): @@ -3086,339 +3087,340 @@ def terminate_children(proc, sigint=False): terminate(child, sigint) def terminate(proc, sigint=False): - if sigint: - proc.send_signal(signal.SIGINT) - else: - proc.terminate() + if sigint: + proc.send_signal(signal.SIGINT) + else: + proc.terminate() def proc_wait_thread(ev, proc, obj): - proc.wait() - wx.CallAfter(enables_set, obj, 'proc_wait', True) - th_end((None, ev)) + proc.wait() + wx.CallAfter(enables_set, obj, 'proc_wait', True) + th_end((None, ev)) def th_start(target, kwargs={}): - ev = threading.Event() - kwargs['ev'] = ev - th = threading.Thread(target=target, kwargs=kwargs) - th.daemon = True - th.start() - return (th, ev) - -def th_end((th, ev)): - if not th: - th = threading.current_thread() - threading.Timer( 1.0, th_end, ((th, ev),) ).start() - return - ev.set() - th.join() + ev = threading.Event() + kwargs['ev'] = ev + th = threading.Thread(target=target, kwargs=kwargs) + th.daemon = True + th.start() + return (th, ev) + +def th_end(th_ev): + th, ev = th_ev + if not th: + th = threading.current_thread() + threading.Timer( 1.0, th_end, ((th, ev),) ).start() + return + ev.set() + th.join() def que_clear(que): - with que.mutex: - que.queue.clear() + with que.mutex: + que.queue.clear() def append_tc_limit(tc, s, rm_chars=0): - if rm_chars > 0: - tc.Remove(0, rm_chars) - tc.AppendText(s) + if rm_chars > 0: + tc.Remove(0, rm_chars) + tc.AppendText(s) def cut_esc(s): - while True: - i = s.find(chr(27)) - if i < 0: - break - j = s.find('m', i) - if j < 0: - break - s = s[:i] + s[j+1:] - return s + while True: + i = s.find(chr(27)) + if i < 0: + break + j = s.find('m', i) + if j < 0: + break + s = s[:i] + s[j+1:] + return s def change_font_point_by_rate(obj, rate=1.0): - font = obj.GetFont() - pt = font.GetPointSize() - pt = int(pt * rate) - font.SetPointSize(pt) - obj.SetFont(font) + font = obj.GetFont() + pt = font.GetPointSize() + pt = int(pt * rate) + font.SetPointSize(pt) + obj.SetFont(font) def fix_link_color(obj): - t = type(obj) - if t is CT.GenericTreeItem or t is CT.CustomTreeCtrl: - obj.SetHyperTextVisitedColour(obj.GetHyperTextNewColour()) - elif t is wx.HyperlinkCtrl: - obj.SetVisitedColour(obj.GetNormalColour()) + t = type(obj) + if t is CT.GenericTreeItem or t is CT.CustomTreeCtrl: + obj.SetHyperTextVisitedColour(obj.GetHyperTextNewColour()) + elif t is wx.HyperlinkCtrl: + obj.SetVisitedColour(obj.GetNormalColour()) def get_tooltip(dic): - return dic.get('desc') + return dic.get('desc') def get_tooltips(dic): - return dic.get('descs', []) + return dic.get('descs', []) def set_tooltip(obj, dic): - set_tooltip_str(obj, get_tooltip(dic)) + set_tooltip_str(obj, get_tooltip(dic)) def set_tooltip_str(obj, s): - if s and getattr(obj, 'SetToolTipString', None): - obj.SetToolTipString(s) + if s and getattr(obj, 'SetToolTipString', None): + obj.SetToolTipString(s) def set_tooltips(obj, dic): - lst = get_tooltips(dic) - if lst and getattr(obj, 'SetItemToolTip', None): - for (ix, s) in enumerate(lst): - obj.SetItemToolTip(ix, s) + lst = get_tooltips(dic) + if lst and getattr(obj, 'SetItemToolTip', None): + for (ix, s) in enumerate(lst): + obj.SetItemToolTip(ix, s) def get_tooltip_obj(obj): - if getattr(obj, 'GetToolTip', None): - t = obj.GetToolTip() - return t.GetTip() if t else None - return None + if getattr(obj, 'GetToolTip', None): + t = obj.GetToolTip() + return t.GetTip() if t else None + return None def scaled_bitmap(bm, scale): - (w, h) = bm.GetSize() - img = wx.ImageFromBitmap(bm) - img = img.Scale(w * scale, h * scale, wx.IMAGE_QUALITY_HIGH) - return wx.BitmapFromImage(img) + (w, h) = bm.GetSize() + img = wx.ImageFromBitmap(bm) + img = img.Scale(w * scale, h * scale, wx.IMAGE_QUALITY_HIGH) + return wx.BitmapFromImage(img) def sizer_wrap(add_objs, orient=wx.VERTICAL, prop=0, flag=0, border=0, parent=None): - szr = wx.BoxSizer(orient) - for obj in add_objs: - szr.Add(obj, prop, flag, border) - if parent: - parent.SetSizer(szr) - return szr + szr = wx.BoxSizer(orient) + for obj in add_objs: + szr.Add(obj, prop, flag, border) + if parent: + parent.SetSizer(szr) + return szr def static_box_sizer(parent, s, orient=wx.VERTICAL): - sb = wx.StaticBox(parent, wx.ID_ANY, s) - sb.Lower() - return wx.StaticBoxSizer(sb, orient) + sb = wx.StaticBox(parent, wx.ID_ANY, s) + sb.Lower() + return wx.StaticBoxSizer(sb, orient) def wx_flag_get(flags): - dic = { 'top' : wx.TOP, 'bottom' : wx.BOTTOM, 'left' : wx.LEFT, 'right' : wx.RIGHT, - 'all' : wx.ALL, 'expand' : wx.EXPAND, 'fixed_minsize' : wx.FIXED_MINSIZE, - 'center_v' : wx.ALIGN_CENTER_VERTICAL, 'center_h' : wx.ALIGN_CENTER_HORIZONTAL, - 'passwd' : wx.TE_PASSWORD } - lst = [ dic.get(f) for f in flags if f in dic ] - return reduce(lambda a,b : a+b, [0] + lst) + dic = { 'top' : wx.TOP, 'bottom' : wx.BOTTOM, 'left' : wx.LEFT, 'right' : wx.RIGHT, + 'all' : wx.ALL, 'expand' : wx.EXPAND, 'fixed_minsize' : wx.FIXED_MINSIZE, + 'center_v' : wx.ALIGN_CENTER_VERTICAL, 'center_h' : wx.ALIGN_CENTER_HORIZONTAL, + 'passwd' : wx.TE_PASSWORD } + lst = [ dic.get(f) for f in flags if f in dic ] + return reduce(lambda a,b : a+b, [0] + lst) def msg_path_to_obj_attr(msg, path): - lst = path.split('.') - obj = msg - for attr in lst[:-1]: - obj = getattr(obj, attr, None) - return (obj, lst[-1]) + lst = path.split('.') + obj = msg + for attr in lst[:-1]: + obj = getattr(obj, attr, None) + return (obj, lst[-1]) def str_to_rosval(s, type_str, def_ret=None): - cvt_dic = { - 'int8':int , 'int16':int , 'int32':int , - 'uint8':int , 'uint16':int , 'uint32':int , - 'int64':long , 'uint64':long, - 'float32':float, 'float64':float, - } - t = cvt_dic.get(type_str) - s = s.replace(',','.') if t is float and type(s) is str else s - return t(s) if t else def_ret + cvt_dic = { + 'int8':int , 'int16':int , 'int32':int , + 'uint8':int , 'uint16':int , 'uint32':int , + 'int64':long , 'uint64':long, + 'float32':float, 'float64':float, + } + t = cvt_dic.get(type_str) + s = s.replace(',','.') if t is float and type(s) is str else s + return t(s) if t else def_ret def str_to_float(s): - return float( s.replace(',','.') ) + return float( s.replace(',','.') ) def set_path(tc, v): - tc.SetValue(v) - tc.SetInsertionPointEnd() + tc.SetValue(v) + tc.SetInsertionPointEnd() def set_val(obj, v): - func = getattr(obj, 'SetValue', getattr(obj, 'Check', None)) - if func: - func(v) - obj_refresh(obj) - if type(obj) is wx.ToggleButton: - button_color_change(obj) + func = getattr(obj, 'SetValue', getattr(obj, 'Check', None)) + if func: + func(v) + obj_refresh(obj) + if type(obj) is wx.ToggleButton: + button_color_change(obj) def enables_set(obj, k, en): - if hasattr(obj, 'enables_proxy'): - (obj, k) = obj.enables_proxy - d = attr_getset(obj, 'enabLes', {}) - d[k] = en - d['last_key'] = k - if hasattr(obj, 'Enable'): - obj.Enable( all( d.values() ) ) - obj_refresh(obj) - if isinstance(obj, wx.HyperlinkCtrl): - if not hasattr(obj, 'coLor'): - obj.coLor = { True:obj.GetNormalColour(), False:'#808080' } - c = obj.coLor.get(obj.IsEnabled()) - obj.SetNormalColour(c) - obj.SetVisitedColour(c) + if hasattr(obj, 'enables_proxy'): + (obj, k) = obj.enables_proxy + d = attr_getset(obj, 'enabLes', {}) + d[k] = en + d['last_key'] = k + if hasattr(obj, 'Enable'): + obj.Enable( all( d.values() ) ) + obj_refresh(obj) + if isinstance(obj, wx.HyperlinkCtrl): + if not hasattr(obj, 'coLor'): + obj.coLor = { True:obj.GetNormalColour(), False:'#808080' } + c = obj.coLor.get(obj.IsEnabled()) + obj.SetNormalColour(c) + obj.SetVisitedColour(c) def enables_get(obj, k, def_ret=None): - return attr_getset(obj, 'enabLes', {}).get(k, def_ret) + return attr_getset(obj, 'enabLes', {}).get(k, def_ret) def enables_get_last(obj): - k = enables_get(obj, 'last_key') - return (k, enables_get(obj, k)) + k = enables_get(obj, 'last_key') + return (k, enables_get(obj, k)) def obj_refresh(obj): - if type(obj) is CT.GenericTreeItem: - while obj.GetParent(): - obj = obj.GetParent() - tree = obj.GetData() - tree.Refresh() + if type(obj) is CT.GenericTreeItem: + while obj.GetParent(): + obj = obj.GetParent() + tree = obj.GetData() + tree.Refresh() # dic_list util (push, pop, get) def dic_list_push(dic, key, v): - dic_getset(dic, key, []).append(v) + dic_getset(dic, key, []).append(v) def dic_list_pop(dic, key): - dic.get(key, [None]).pop() + dic.get(key, [None]).pop() def dic_list_get(dic, key, def_ret=None): - return dic.get(key, [def_ret])[-1] + return dic.get(key, [def_ret])[-1] def bak_stk_push(dic, key): - if key in dic: - k = key + '_bak_str' - dic_getset(dic, k, []).append( dic.get(key) ) + if key in dic: + k = key + '_bak_str' + dic_getset(dic, k, []).append( dic.get(key) ) def bak_stk_pop(dic, key): - k = key + '_bak_str' - stk = dic.get(k, []) - if len(stk) > 0: - dic[key] = stk.pop() - else: - del dic[key] + k = key + '_bak_str' + stk = dic.get(k, []) + if len(stk) > 0: + dic[key] = stk.pop() + else: + del dic[key] def bak_stk_set(dic, key, v): - bak_str_push(dic, key) - dic[key] = v + bak_str_push(dic, key) + dic[key] = v def attr_getset(obj, name, def_ret): - if not hasattr(obj, name): - setattr(obj, name, def_ret) - return getattr(obj, name) + if not hasattr(obj, name): + setattr(obj, name, def_ret) + return getattr(obj, name) def dic_getset(dic, key, def_ret): - if key not in dic: - dic[key] = def_ret - return dic.get(key) + if key not in dic: + dic[key] = def_ret + return dic.get(key) def lst_append_once(lst, v): - exist = v in lst - if not exist: - lst.append(v) - return exist + exist = v in lst + if not exist: + lst.append(v) + return exist def lst_remove_once(lst, v): - exist = v in lst - if exist: - lst.remove(v) - return exist + exist = v in lst + if exist: + lst.remove(v) + return exist def get_top(lst, def_ret=None): - return lst[0] if len(lst) > 0 else def_ret + return lst[0] if len(lst) > 0 else def_ret def adjust_num_str(s): - if '.' in s: - while s[-1] == '0': - s = s[:-1] - if s[-1] == '.': - s = s[:-1] - return s + if '.' in s: + while s[-1] == '0': + s = s[:-1] + if s[-1] == '.': + s = s[:-1] + return s def rtmgr_src_dir(): - return os.path.abspath(os.path.dirname(__file__)) + "/" + return os.path.abspath(os.path.dirname(__file__)) + "/" def path_expand_cmd(path): - lst = path.split('/') - s = lst[0] - if s[:2] == '$(' and s[-1] == ')': - cmd = s[2:-1].split(' ') - lst[0] = subprocess.check_output(cmd).strip() - path = '/'.join(lst) - return path + lst = path.split('/') + s = lst[0] + if s[:2] == '$(' and s[-1] == ')': + cmd = s[2:-1].split(' ') + lst[0] = subprocess.check_output(cmd).strip() + path = '/'.join(lst) + return path def eval_if_str(self, v): - return eval(v) if type(v) is str else v + return eval(v) if type(v) is str else v def dic_eval_if_str(self, dic, key, def_ret=None): - return eval_if_str( self, dic.get(key, def_ret) ) + return eval_if_str( self, dic.get(key, def_ret) ) def prn_dict(dic): - for (k,v) in dic.items(): - print (k, ':', v) + for (k,v) in dic.items(): + print(k, ':', v) def send_to_proc_manager(order): - sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM) + sock = socket.socket(socket.AF_UNIX, socket.SOCK_STREAM) - try: - sock.connect(PROC_MANAGER_SOCK) - except socket.error: - print('Failed connect to {}'.format(PROC_MANAGER_SOCK)) - return -1 + try: + sock.connect(PROC_MANAGER_SOCK) + except socket.error: + print('Failed connect to {}'.format(PROC_MANAGER_SOCK)) + return -1 - sock.send(yaml.dump(order)) - ret = sock.recv(1024) - sock.close() - return int(ret) == 0 + sock.send(yaml.dump(order)) + ret = sock.recv(1024) + sock.close() + return int(ret) == 0 def set_process_nice(proc, value): - order = { - "name": "nice", - "pid": proc.pid, - "nice": value - } - return send_to_proc_manager(order) + order = { + "name": "nice", + "pid": proc.pid, + "nice": value + } + return send_to_proc_manager(order) def set_process_cpu_affinity(proc, cpus): - order = { - "name": "cpu_affinity", - "pid": proc.pid, - "cpus": cpus, - } - return send_to_proc_manager(order) + order = { + "name": "cpu_affinity", + "pid": proc.pid, + "cpus": cpus, + } + return send_to_proc_manager(order) def shutdown_proc_manager(): - order = { - "name": "shutdown", - } - return send_to_proc_manager(order) + order = { + "name": "shutdown", + } + return send_to_proc_manager(order) def set_scheduling_policy(proc, policy, priority): - order = { - "name": "scheduling_policy", - "pid": proc.pid, - "policy": policy, - "priority": priority, - } - return send_to_proc_manager(order) + order = { + "name": "scheduling_policy", + "pid": proc.pid, + "policy": policy, + "priority": priority, + } + return send_to_proc_manager(order) # psutil 3.x to 1.x backward compatibility def get_cpu_count(): - try: - return psutil.NUM_CPUS - except AttributeError: - return psutil.cpu_count() + try: + return psutil.NUM_CPUS + except AttributeError: + return psutil.cpu_count() def get_proc_children(proc, r=False): - try: - return proc.get_children(recursive=r) - except AttributeError: - return proc.children(recursive=r) + try: + return proc.get_children(recursive=r) + except AttributeError: + return proc.children(recursive=r) def get_proc_nice(proc): - try: - return proc.get_nice() - except AttributeError: - return proc.nice() + try: + return proc.get_nice() + except AttributeError: + return proc.nice() def get_proc_cpu_affinity(proc): - try: - return proc.get_cpu_affinity() - except AttributeError: - return proc.cpu_affinity() + try: + return proc.get_cpu_affinity() + except AttributeError: + return proc.cpu_affinity() if __name__ == "__main__": - gettext.install("app") + gettext.install("app") - app = MyApp(0) - app.MainLoop() + app = MyApp(0) + app.MainLoop() # EOF diff --git a/utilities/runtime_manager/scripts/subnet_chk.py b/utilities/runtime_manager/scripts/subnet_chk.py index 4e0f6cc5116..6da3cd9eec3 100755 --- a/utilities/runtime_manager/scripts/subnet_chk.py +++ b/utilities/runtime_manager/scripts/subnet_chk.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import sys import os @@ -23,7 +23,7 @@ def addr_v(addr): return struct.unpack('!i', socket.inet_aton(addr))[0] if len(sys.argv) < 2: - print "Usage: {} ".format(sys.argv[0]) + print("Usage: {} ".format(sys.argv[0])) sys.exit(0) targ = sys.argv[1] @@ -50,6 +50,6 @@ def addr_v(addr): v = addr_v(addr) mask = addr_v(mask_s) if (v & mask) == (targ_v & mask): - print addr + print(addr) sys.exit(0) sys.exit(1) diff --git a/utilities/runtime_manager/scripts/test_pub.py b/utilities/runtime_manager/scripts/test_pub.py index 18f2cd43c44..3d135b193c4 100755 --- a/utilities/runtime_manager/scripts/test_pub.py +++ b/utilities/runtime_manager/scripts/test_pub.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2015-2019 Autoware Foundation # @@ -24,7 +24,7 @@ pub = rospy.Publisher('to_rtmgr', std_msgs.msg.String, queue_size=10) r = rospy.Rate(10) r.sleep() - pub.publish(s) + pub.publish(s) r.sleep() # EOF diff --git a/utilities/runtime_manager/scripts/test_srv.py b/utilities/runtime_manager/scripts/test_srv.py index b7929d34e32..c1c7234dc2a 100755 --- a/utilities/runtime_manager/scripts/test_srv.py +++ b/utilities/runtime_manager/scripts/test_srv.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2015-2019 Autoware Foundation # diff --git a/utilities/sound_player/scripts/sound_player.py b/utilities/sound_player/scripts/sound_player.py index 71ed71d1759..439b3fbcd78 100755 --- a/utilities/sound_player/scripts/sound_player.py +++ b/utilities/sound_player/scripts/sound_player.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # Copyright 2015-2019 Autoware Foundation # diff --git a/utilities/sync/sync_generator.py b/utilities/sync/sync_generator.py index 45cb121f590..6b025cc2a80 100644 --- a/utilities/sync/sync_generator.py +++ b/utilities/sync/sync_generator.py @@ -8,9 +8,9 @@ if __name__ == "__main__": if (argc != 3): - print '%python sync_generator.py argv[1] argv[2]' - print '\t' + 'argv[1]: input *.yaml file' - print '\t' + 'argv[2]: output *.cpp file' + print('%python sync_generator.py argv[1] argv[2]') + print('\t' + 'argv[1]: input *.yaml file') + print('\t' + 'argv[2]: output *.cpp file') quit() f_config = open(argvs[1], 'r') f_generate = open(argvs[2], 'w') @@ -213,7 +213,7 @@ text += ' p_%s_buf = &(%s_ringbuf.back());\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' publish_msg(p_%s_buf, p_%s_buf);\n' % (data['sub1'].split('/')[-1], data['sub2'].split('/')[-1]) text += ' pthread_mutex_unlock(&mutex);\n' @@ -322,7 +322,7 @@ text += ' %s_buf = %s_ringbuf.back();\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' pthread_mutex_unlock(&mutex);\n' text += '}\n\n' @@ -422,7 +422,7 @@ text += ' %s_buf = %s_ringbuf.back();\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' pthread_mutex_unlock(&mutex);\n' text += '}\n\n' @@ -543,4 +543,4 @@ f_config.close() f_generate.close() - print "generate " + print("generate ") diff --git a/utilities/sync/sync_generator2.py b/utilities/sync/sync_generator2.py index 9edbb7a3e52..c08720aeb6d 100644 --- a/utilities/sync/sync_generator2.py +++ b/utilities/sync/sync_generator2.py @@ -8,9 +8,9 @@ if __name__ == "__main__": if (argc != 3): - print '%python sync_generator.py argv[1] argv[2]' - print '\t' + 'argv[1]: input *.yaml file' - print '\t' + 'argv[2]: output *.cpp file' + print('%python sync_generator.py argv[1] argv[2]') + print('\t' + 'argv[1]: input *.yaml file') + print('\t' + 'argv[2]: output *.cpp file') quit() f_config = open(argvs[1], 'r') f_generate = open(argvs[2], 'w') @@ -200,7 +200,7 @@ text += ' p_%s_buf = &(%s_ringbuf.back());\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' publish_msg(p_%s_buf, p_%s_buf);\n' % (data['sub1'].split('/')[-1], data['sub2'].split('/')[-1]) text += ' if (%s_flag == true){\n' % data['sync_sub'].split('/')[-1] @@ -382,7 +382,7 @@ text += ' %s_buf = %s_ringbuf.back();\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' pthread_mutex_unlock(&mutex);\n' text += '}\n\n' @@ -493,7 +493,7 @@ text += ' %s_buf = %s_ringbuf.back();\n' % (data['sub1'].split('/')[-1], data['sub1'].split('/')[-1]) text += ' }\n' else : - print "failed: sched_policy 2, short_rate unmatched sub1 or sub2" + print("failed: sched_policy 2, short_rate unmatched sub1 or sub2") text += ' pthread_mutex_unlock(&mutex);\n' text += '}\n\n' @@ -580,4 +580,4 @@ f_config.close() f_generate.close() - print "generate " + print("generate ") diff --git a/utilities/sync/time_visualizer.py b/utilities/sync/time_visualizer.py index 9a56e1781f6..ade40c64331 100755 --- a/utilities/sync/time_visualizer.py +++ b/utilities/sync/time_visualizer.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import rospy import numpy as np import matplotlib.pyplot as plt diff --git a/utilities/twist2odom/test/twist2odom_test.cpp b/utilities/twist2odom/test/twist2odom_test.cpp index fff9283ef2f..f57af0074c8 100644 --- a/utilities/twist2odom/test/twist2odom_test.cpp +++ b/utilities/twist2odom/test/twist2odom_test.cpp @@ -8,6 +8,7 @@ * http://www.apache.org/licenses/LICENSE-2.0 */ +#include #include #include #include diff --git a/visualization/detected_objects_visualizer/src/visualize_rects.cpp b/visualization/detected_objects_visualizer/src/visualize_rects.cpp index 57941eea97b..ccaea867182 100644 --- a/visualization/detected_objects_visualizer/src/visualize_rects.cpp +++ b/visualization/detected_objects_visualizer/src/visualize_rects.cpp @@ -17,6 +17,8 @@ * v1.0: amc-nu (abrahammonrroy@yahoo.com) */ +#include + #include "visualize_rects.h" VisualizeRects::VisualizeRects() @@ -166,4 +168,4 @@ bool VisualizeRects::IsObjectValid(const autoware_msgs::DetectedObject &in_objec return false; } return true; -}//end IsObjectValid \ No newline at end of file +}//end IsObjectValid diff --git a/visualization/gazebo_world_description/CMakeLists.txt b/visualization/gazebo_world_description/CMakeLists.txt index 6c200d435bb..1b8f1282f66 100644 --- a/visualization/gazebo_world_description/CMakeLists.txt +++ b/visualization/gazebo_world_description/CMakeLists.txt @@ -15,4 +15,4 @@ install(CODE "execute_process( \ COMMAND cp -rL \ ${CMAKE_CURRENT_SOURCE_DIR}/models/ \ ${CMAKE_INSTALL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/)" -) \ No newline at end of file +) diff --git a/visualization/gazebo_world_description/models/construction_cone b/visualization/gazebo_world_description/models/construction_cone index f983f716951..0b5a8680481 120000 --- a/visualization/gazebo_world_description/models/construction_cone +++ b/visualization/gazebo_world_description/models/construction_cone @@ -1 +1 @@ -../../../../car_demo/car_demo/models/construction_cone \ No newline at end of file +../../../car_demo/car_demo/models/construction_cone \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/dumpster b/visualization/gazebo_world_description/models/dumpster index 2b4faec3271..b5b6d7f1bd3 120000 --- a/visualization/gazebo_world_description/models/dumpster +++ b/visualization/gazebo_world_description/models/dumpster @@ -1 +1 @@ -../../../../car_demo/car_demo/models/dumpster \ No newline at end of file +../../../car_demo/car_demo/models/dumpster \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/gas_station b/visualization/gazebo_world_description/models/gas_station index 1287cf366dc..432d92dfdab 120000 --- a/visualization/gazebo_world_description/models/gas_station +++ b/visualization/gazebo_world_description/models/gas_station @@ -1 +1 @@ -../../../../car_demo/car_demo/models/gas_station \ No newline at end of file +../../../car_demo/car_demo/models/gas_station \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/grey_wall b/visualization/gazebo_world_description/models/grey_wall index 3577e0bacd5..f06a4f7c729 120000 --- a/visualization/gazebo_world_description/models/grey_wall +++ b/visualization/gazebo_world_description/models/grey_wall @@ -1 +1 @@ -../../../../car_demo/car_demo/models/grey_wall \ No newline at end of file +../../../car_demo/car_demo/models/grey_wall \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/house_1 b/visualization/gazebo_world_description/models/house_1 index 68e273aa325..06f95acc368 120000 --- a/visualization/gazebo_world_description/models/house_1 +++ b/visualization/gazebo_world_description/models/house_1 @@ -1 +1 @@ -../../../../car_demo/car_demo/models/house_1 \ No newline at end of file +../../../car_demo/car_demo/models/house_1 \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/house_2 b/visualization/gazebo_world_description/models/house_2 index 2fbf5faf475..d0613ae1b6c 120000 --- a/visualization/gazebo_world_description/models/house_2 +++ b/visualization/gazebo_world_description/models/house_2 @@ -1 +1 @@ -../../../../car_demo/car_demo/models/house_2 \ No newline at end of file +../../../car_demo/car_demo/models/house_2 \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/house_3 b/visualization/gazebo_world_description/models/house_3 index 833d3499933..a278c444b43 120000 --- a/visualization/gazebo_world_description/models/house_3 +++ b/visualization/gazebo_world_description/models/house_3 @@ -1 +1 @@ -../../../../car_demo/car_demo/models/house_3 \ No newline at end of file +../../../car_demo/car_demo/models/house_3 \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/jersey_barrier b/visualization/gazebo_world_description/models/jersey_barrier index 2ad1913ff3b..4d40e61a940 120000 --- a/visualization/gazebo_world_description/models/jersey_barrier +++ b/visualization/gazebo_world_description/models/jersey_barrier @@ -1 +1 @@ -../../../../car_demo/car_demo/models/jersey_barrier \ No newline at end of file +../../../car_demo/car_demo/models/jersey_barrier \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/mcity b/visualization/gazebo_world_description/models/mcity index 54762bcd5aa..21cbba8e60a 120000 --- a/visualization/gazebo_world_description/models/mcity +++ b/visualization/gazebo_world_description/models/mcity @@ -1 +1 @@ -../../../../car_demo/car_demo/models/mcity \ No newline at end of file +../../../car_demo/car_demo/models/mcity \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/ocean b/visualization/gazebo_world_description/models/ocean index 8f680cec02b..35a1bbccf49 120000 --- a/visualization/gazebo_world_description/models/ocean +++ b/visualization/gazebo_world_description/models/ocean @@ -1 +1 @@ -../../../../citysim/models/ocean \ No newline at end of file +../../../osrf_citysim/models/ocean \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/powerplant b/visualization/gazebo_world_description/models/powerplant index ec68b17b138..c536f982986 120000 --- a/visualization/gazebo_world_description/models/powerplant +++ b/visualization/gazebo_world_description/models/powerplant @@ -1 +1 @@ -../../../../car_demo/car_demo/models/powerplant \ No newline at end of file +../../../car_demo/car_demo/models/powerplant \ No newline at end of file diff --git a/visualization/gazebo_world_description/models/speed_limit_sign b/visualization/gazebo_world_description/models/speed_limit_sign index 0714d0f49a5..bcd6ab3c0f8 120000 --- a/visualization/gazebo_world_description/models/speed_limit_sign +++ b/visualization/gazebo_world_description/models/speed_limit_sign @@ -1 +1 @@ -../../../../car_demo/car_demo/models/speed_limit_sign \ No newline at end of file +../../../car_demo/car_demo/models/speed_limit_sign \ No newline at end of file diff --git a/visualization/gazebo_world_description/worlds/citysim_gazebo7.world b/visualization/gazebo_world_description/worlds/citysim_gazebo7.world index 5768b66b8bc..0af6952867e 120000 --- a/visualization/gazebo_world_description/worlds/citysim_gazebo7.world +++ b/visualization/gazebo_world_description/worlds/citysim_gazebo7.world @@ -1 +1 @@ -../../../../citysim/worlds/citysim_gazebo7.world \ No newline at end of file +../../../osrf_citysim/worlds/citysim_gazebo7.world \ No newline at end of file diff --git a/visualization/gazebo_world_description/worlds/citysim_gazebo9.world b/visualization/gazebo_world_description/worlds/citysim_gazebo9.world index 7049dd4ae29..99796e4d927 120000 --- a/visualization/gazebo_world_description/worlds/citysim_gazebo9.world +++ b/visualization/gazebo_world_description/worlds/citysim_gazebo9.world @@ -1 +1 @@ -../../../../citysim/worlds/citysim_gazebo9.world \ No newline at end of file +../../../osrf_citysim/worlds/citysim_gazebo9.world \ No newline at end of file diff --git a/visualization/gazebo_world_description/worlds/mcity.world b/visualization/gazebo_world_description/worlds/mcity.world index a63392894a7..2366a57bd3c 120000 --- a/visualization/gazebo_world_description/worlds/mcity.world +++ b/visualization/gazebo_world_description/worlds/mcity.world @@ -1 +1 @@ -../../../../car_demo/car_demo/worlds/mcity.world \ No newline at end of file +../../../car_demo/car_demo/worlds/mcity.world \ No newline at end of file diff --git a/visualization/gazebo_world_description/worlds/mcity_r1.world b/visualization/gazebo_world_description/worlds/mcity_r1.world index 20e2a059d72..bae55ed4079 120000 --- a/visualization/gazebo_world_description/worlds/mcity_r1.world +++ b/visualization/gazebo_world_description/worlds/mcity_r1.world @@ -1 +1 @@ -../../../../car_demo/car_demo/worlds/mcity_r1.world \ No newline at end of file +../../../car_demo/car_demo/worlds/mcity_r1.world \ No newline at end of file diff --git a/visualization/glviewer/CMakeLists.txt b/visualization/glviewer/CMakeLists.txt index 1ad0f7b8241..fc133404613 100644 --- a/visualization/glviewer/CMakeLists.txt +++ b/visualization/glviewer/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(glviewer) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) + include(FindPkgConfig) find_package(autoware_build_flags REQUIRED) diff --git a/visualization/integrated_viewer/include/gencolors.cpp b/visualization/integrated_viewer/include/gencolors.cpp index 60fb76ede5a..f30c5205fc9 100644 --- a/visualization/integrated_viewer/include/gencolors.cpp +++ b/visualization/integrated_viewer/include/gencolors.cpp @@ -43,6 +43,7 @@ // //M*/ #include "opencv2/core/core.hpp" +#include "opencv2/core/core_c.h" //#include "precomp.hpp" #include diff --git a/visualization/integrated_viewer/lib/convert_image.h b/visualization/integrated_viewer/lib/convert_image.h index 74981e79f2d..5b5c0e65847 100644 --- a/visualization/integrated_viewer/lib/convert_image.h +++ b/visualization/integrated_viewer/lib/convert_image.h @@ -4,8 +4,8 @@ #include #include -#include -#include +#include +#include namespace convert_image { inline QImage CvMatToQImage(const cv::Mat &input) { diff --git a/visualization/integrated_viewer/node/data_rate_checker_plugin/data_rate_checker_plugin.h b/visualization/integrated_viewer/node/data_rate_checker_plugin/data_rate_checker_plugin.h index 7878b30ef39..719c05e7e47 100644 --- a/visualization/integrated_viewer/node/data_rate_checker_plugin/data_rate_checker_plugin.h +++ b/visualization/integrated_viewer/node/data_rate_checker_plugin/data_rate_checker_plugin.h @@ -3,11 +3,12 @@ #ifndef Q_MOC_RUN #include -#include -#include +#include +#include #include #include #include +#include #include #include diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.cpp b/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.cpp index 711c314ac29..0f8d9020787 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.cpp +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.cpp @@ -1,9 +1,10 @@ #include "draw_lane.h" -#include +#include #include +#include -#if (CV_MAJOR_VERSION != 3) +#if (CV_MAJOR_VERSION < 3) #include #endif diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.h b/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.h index 1d633c4f912..e03a7eae73a 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.h +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_lane.h @@ -1,6 +1,6 @@ #ifndef DRAW_LANE_H #define DRAW_LANE_H -#include +#include #include "autoware_msgs/ImageLaneObjects.h" namespace integrated_viewer { diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.cpp b/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.cpp index 622a8909ec7..f12af300253 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.cpp +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.cpp @@ -1,5 +1,6 @@ #include "draw_points.h" #include +#include namespace integrated_viewer { diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.h b/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.h index 5abfabad0b5..2a0df0e018e 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.h +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_points.h @@ -1,7 +1,7 @@ #ifndef DRAW_POINTS_H #define DRAW_POINTS_H -#include +#include #include "autoware_msgs/PointsImage.h" namespace integrated_viewer { diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.cpp b/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.cpp index 08623e56312..e02767c62d7 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.cpp +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.cpp @@ -5,9 +5,10 @@ #include #include +#include #include "draw_rects.h" -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include "gencolors.cpp" @@ -24,7 +25,7 @@ namespace integrated_viewer DrawRects::DrawRects(void) { // Generate color map to represent tracked object -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) generateColors(color_map_, 10); #else cv::generateColors(color_map_, 10); diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.h b/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.h index c38f8f1bb93..dbe050dd229 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.h +++ b/visualization/integrated_viewer/node/image_viewer_plugin/draw_rects.h @@ -1,7 +1,7 @@ #ifndef DRAW_RECTS_H #define DRAW_RECTS_H -#include +#include #include #define XSTR(x) #x diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.cpp b/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.cpp index 29db6b5d21c..3b08ef32cf8 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.cpp +++ b/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.cpp @@ -1,8 +1,8 @@ #include -#include -#include +#include +#include -#if (CV_MAJOR_VERSION == 3) +#if (CV_MAJOR_VERSION >= 3) #include #endif diff --git a/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.h b/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.h index 16c5a1fda3e..98cc69dab3d 100644 --- a/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.h +++ b/visualization/integrated_viewer/node/image_viewer_plugin/image_viewer_plugin.h @@ -14,8 +14,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.cpp b/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.cpp index 34e6e056c7d..ab9aeed0f6b 100644 --- a/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.cpp +++ b/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include #include diff --git a/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.h b/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.h index 1001d031c1f..63556fba83a 100644 --- a/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.h +++ b/visualization/integrated_viewer/node/traffic_light_plugin/traffic_light_plugin.h @@ -3,8 +3,8 @@ #ifndef Q_MOC_RUN #include -#include -#include +#include +#include #include #include "autoware_msgs/TrafficLight.h" diff --git a/visualization/points2image/CMakeLists.txt b/visualization/points2image/CMakeLists.txt index 2158bc995e8..81142a65ef2 100644 --- a/visualization/points2image/CMakeLists.txt +++ b/visualization/points2image/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 2.8.12) project(points2image) +# Set OpenGL_GL_PREFERENCE to GLVND +cmake_policy(SET CMP0072 NEW) + include(FindPkgConfig) find_package(autoware_build_flags REQUIRED) diff --git a/visualization/vehicle_model/CMakeLists.txt b/visualization/vehicle_model/CMakeLists.txt index 2d24e53f8f7..1108819a866 100644 --- a/visualization/vehicle_model/CMakeLists.txt +++ b/visualization/vehicle_model/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(vehicle_model) -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) find_package(catkin REQUIRED autoware_build_flags From df575e3f58757e8480c032d168ff35e3d55ebc08 Mon Sep 17 00:00:00 2001 From: Michael Jeronimo Date: Tue, 29 Jun 2021 09:11:55 -0700 Subject: [PATCH 02/23] Add COLCON_IGNORE to those packages that aren't needed (#156) * Add COLCON_IGNORE to those packages that aren't needed * Restore a few directories to the build --- car_demo/car_demo/COLCON_IGNORE | 0 car_demo/prius_description/COLCON_IGNORE | 0 car_demo/prius_msgs/COLCON_IGNORE | 0 common/emergency_handler/COLCON_IGNORE | 0 common/libvectormap/COLCON_IGNORE | 0 common/object_map/COLCON_IGNORE | 0 common/op_planner/COLCON_IGNORE | 0 common/op_ros_helpers/COLCON_IGNORE | 0 common/op_simu/COLCON_IGNORE | 0 common/op_utility/COLCON_IGNORE | 0 core_perception/autoware_connector/COLCON_IGNORE | 0 core_perception/gnss_localizer/COLCON_IGNORE | 0 core_perception/image_processor/COLCON_IGNORE | 0 core_perception/lidar_apollo_cnn_seg_detect/COLCON_IGNORE | 0 core_perception/lidar_fake_perception/COLCON_IGNORE | 0 core_perception/lidar_kf_contour_track/COLCON_IGNORE | 0 core_perception/lidar_naive_l_shape_detect/COLCON_IGNORE | 0 core_perception/lidar_point_pillars/COLCON_IGNORE | 0 core_perception/lidar_shape_estimation/COLCON_IGNORE | 0 core_perception/ndt_gpu/COLCON_IGNORE | 0 core_perception/obj_db/COLCON_IGNORE | 0 core_perception/pixel_cloud_fusion/COLCON_IGNORE | 0 core_perception/pos_db/COLCON_IGNORE | 0 core_perception/road_occupancy_processor/COLCON_IGNORE | 0 core_perception/roi_object_filter/COLCON_IGNORE | 0 core_perception/trafficlight_recognizer/COLCON_IGNORE | 0 core_perception/twist_generator/COLCON_IGNORE | 0 core_perception/vel_pose_diff_checker/COLCON_IGNORE | 0 core_perception/vision_lane_detect/COLCON_IGNORE | 0 core_perception/vision_segment_enet_detect/COLCON_IGNORE | 0 core_perception/vision_ssd_detect/COLCON_IGNORE | 0 core_planning/costmap_generator/COLCON_IGNORE | 0 core_planning/decision_maker/COLCON_IGNORE | 0 core_planning/dp_planner/COLCON_IGNORE | 0 core_planning/ff_waypoint_follower/COLCON_IGNORE | 0 core_planning/freespace_planner/COLCON_IGNORE | 0 core_planning/lattice_planner/COLCON_IGNORE | 0 core_planning/op_global_planner/COLCON_IGNORE | 0 core_planning/op_local_planner/COLCON_IGNORE | 0 core_planning/op_simulation_package/COLCON_IGNORE | 0 core_planning/op_utilities/COLCON_IGNORE | 0 core_planning/state_machine_lib/COLCON_IGNORE | 0 core_planning/way_planner/COLCON_IGNORE | 0 documentation/autoware_quickstart_examples/COLCON_IGNORE | 0 drivers/analog_devices/COLCON_IGNORE | 0 drivers/autoware_driveworks_gmsl_interface/COLCON_IGNORE | 0 drivers/autoware_driveworks_interface/COLCON_IGNORE | 0 drivers/baumer/COLCON_IGNORE | 0 drivers/custom_msgs/COLCON_IGNORE | 0 drivers/garmin/COLCON_IGNORE | 0 drivers/hokuyo/COLCON_IGNORE | 0 drivers/javad_navsat_driver/COLCON_IGNORE | 0 drivers/kvaser/COLCON_IGNORE | 0 drivers/lms5xx/COLCON_IGNORE | 0 drivers/memsic/COLCON_IGNORE | 0 drivers/microstrain/COLCON_IGNORE | 0 drivers/nmea_navsat/COLCON_IGNORE | 0 drivers/pointgrey/COLCON_IGNORE | 0 drivers/sick_ldmrs_description/COLCON_IGNORE | 0 drivers/sick_ldmrs_driver/COLCON_IGNORE | 0 drivers/sick_ldmrs_driver/src/driver/COLCON_IGNORE | 0 drivers/sick_ldmrs_laser/COLCON_IGNORE | 0 drivers/sick_ldmrs_msgs/COLCON_IGNORE | 0 drivers/sick_ldmrs_tools/COLCON_IGNORE | 0 drivers/vectacam/COLCON_IGNORE | 0 drivers/xsens_driver/COLCON_IGNORE | 0 drivers/ymc/COLCON_IGNORE | 0 ds4/ds4/COLCON_IGNORE | 0 ds4/ds4_driver/COLCON_IGNORE | 0 ds4/ds4_msgs/COLCON_IGNORE | 0 messages/autoware_can_msgs/COLCON_IGNORE | 0 messages/autoware_external_msgs/COLCON_IGNORE | 0 messages/autoware_map_msgs/COLCON_IGNORE | 0 messages/autoware_system_msgs/COLCON_IGNORE | 0 messages/tablet_socket_msgs/COLCON_IGNORE | 0 messages/vector_map_msgs/COLCON_IGNORE | 0 simulation/gazebo_camera_description/COLCON_IGNORE | 0 simulation/gazebo_imu_description/COLCON_IGNORE | 0 simulation/lgsvl_simulator_bridge/COLCON_IGNORE | 0 simulation/vehicle_gazebo_simulation_interface/COLCON_IGNORE | 0 simulation/vehicle_gazebo_simulation_launcher/COLCON_IGNORE | 0 simulation/wf_simulator/COLCON_IGNORE | 0 utilities/autoware_bag_tools/COLCON_IGNORE | 0 utilities/autoware_launcher/COLCON_IGNORE | 0 utilities/autoware_launcher_rviz/COLCON_IGNORE | 0 utilities/data_preprocessor/COLCON_IGNORE | 0 utilities/graph_tools/COLCON_IGNORE | 0 utilities/kitti_box_publisher/COLCON_IGNORE | 0 utilities/kitti_launch/COLCON_IGNORE | 0 utilities/kitti_player/COLCON_IGNORE | 0 utilities/lanelet_aisan_converter/COLCON_IGNORE | 0 utilities/log_tools/COLCON_IGNORE | 0 utilities/map_tf_generator/COLCON_IGNORE | 0 utilities/marker_downsampler/COLCON_IGNORE | 0 utilities/mqtt_socket/COLCON_IGNORE | 0 utilities/oculus_socket/COLCON_IGNORE | 0 utilities/pc2_downsampler/COLCON_IGNORE | 0 utilities/rosbag_controller/COLCON_IGNORE | 0 utilities/sound_player/COLCON_IGNORE | 0 utilities/sync/COLCON_IGNORE | 0 utilities/tablet_socket/COLCON_IGNORE | 0 utilities/twist2odom/COLCON_IGNORE | 0 utilities/udon_socket/COLCON_IGNORE | 0 utilities/vehicle_engage_panel/COLCON_IGNORE | 0 utilities/vehicle_socket/COLCON_IGNORE | 0 visualization/decision_maker_panel/COLCON_IGNORE | 0 visualization/fastvirtualscan/COLCON_IGNORE | 0 visualization/gazebo_world_description/COLCON_IGNORE | 0 visualization/glviewer/COLCON_IGNORE | 0 visualization/integrated_viewer/COLCON_IGNORE | 0 visualization/points2image/COLCON_IGNORE | 0 visualization/rosinterface/COLCON_IGNORE | 0 visualization/state_panel/COLCON_IGNORE | 0 visualization/vehicle_description/COLCON_IGNORE | 0 visualization/vehicle_model/COLCON_IGNORE | 0 115 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 car_demo/car_demo/COLCON_IGNORE create mode 100644 car_demo/prius_description/COLCON_IGNORE create mode 100644 car_demo/prius_msgs/COLCON_IGNORE create mode 100644 common/emergency_handler/COLCON_IGNORE create mode 100644 common/libvectormap/COLCON_IGNORE create mode 100644 common/object_map/COLCON_IGNORE create mode 100644 common/op_planner/COLCON_IGNORE create mode 100644 common/op_ros_helpers/COLCON_IGNORE create mode 100644 common/op_simu/COLCON_IGNORE create mode 100644 common/op_utility/COLCON_IGNORE create mode 100644 core_perception/autoware_connector/COLCON_IGNORE create mode 100644 core_perception/gnss_localizer/COLCON_IGNORE create mode 100644 core_perception/image_processor/COLCON_IGNORE create mode 100644 core_perception/lidar_apollo_cnn_seg_detect/COLCON_IGNORE create mode 100644 core_perception/lidar_fake_perception/COLCON_IGNORE create mode 100644 core_perception/lidar_kf_contour_track/COLCON_IGNORE create mode 100644 core_perception/lidar_naive_l_shape_detect/COLCON_IGNORE create mode 100644 core_perception/lidar_point_pillars/COLCON_IGNORE create mode 100644 core_perception/lidar_shape_estimation/COLCON_IGNORE create mode 100644 core_perception/ndt_gpu/COLCON_IGNORE create mode 100644 core_perception/obj_db/COLCON_IGNORE create mode 100644 core_perception/pixel_cloud_fusion/COLCON_IGNORE create mode 100644 core_perception/pos_db/COLCON_IGNORE create mode 100644 core_perception/road_occupancy_processor/COLCON_IGNORE create mode 100644 core_perception/roi_object_filter/COLCON_IGNORE create mode 100644 core_perception/trafficlight_recognizer/COLCON_IGNORE create mode 100644 core_perception/twist_generator/COLCON_IGNORE create mode 100644 core_perception/vel_pose_diff_checker/COLCON_IGNORE create mode 100644 core_perception/vision_lane_detect/COLCON_IGNORE create mode 100644 core_perception/vision_segment_enet_detect/COLCON_IGNORE create mode 100644 core_perception/vision_ssd_detect/COLCON_IGNORE create mode 100644 core_planning/costmap_generator/COLCON_IGNORE create mode 100644 core_planning/decision_maker/COLCON_IGNORE create mode 100644 core_planning/dp_planner/COLCON_IGNORE create mode 100644 core_planning/ff_waypoint_follower/COLCON_IGNORE create mode 100644 core_planning/freespace_planner/COLCON_IGNORE create mode 100644 core_planning/lattice_planner/COLCON_IGNORE create mode 100644 core_planning/op_global_planner/COLCON_IGNORE create mode 100644 core_planning/op_local_planner/COLCON_IGNORE create mode 100644 core_planning/op_simulation_package/COLCON_IGNORE create mode 100644 core_planning/op_utilities/COLCON_IGNORE create mode 100644 core_planning/state_machine_lib/COLCON_IGNORE create mode 100644 core_planning/way_planner/COLCON_IGNORE create mode 100644 documentation/autoware_quickstart_examples/COLCON_IGNORE create mode 100644 drivers/analog_devices/COLCON_IGNORE create mode 100644 drivers/autoware_driveworks_gmsl_interface/COLCON_IGNORE create mode 100644 drivers/autoware_driveworks_interface/COLCON_IGNORE create mode 100644 drivers/baumer/COLCON_IGNORE create mode 100644 drivers/custom_msgs/COLCON_IGNORE create mode 100644 drivers/garmin/COLCON_IGNORE create mode 100644 drivers/hokuyo/COLCON_IGNORE create mode 100644 drivers/javad_navsat_driver/COLCON_IGNORE create mode 100644 drivers/kvaser/COLCON_IGNORE create mode 100644 drivers/lms5xx/COLCON_IGNORE create mode 100644 drivers/memsic/COLCON_IGNORE create mode 100644 drivers/microstrain/COLCON_IGNORE create mode 100644 drivers/nmea_navsat/COLCON_IGNORE create mode 100644 drivers/pointgrey/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_description/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_driver/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_driver/src/driver/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_laser/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_msgs/COLCON_IGNORE create mode 100644 drivers/sick_ldmrs_tools/COLCON_IGNORE create mode 100644 drivers/vectacam/COLCON_IGNORE create mode 100644 drivers/xsens_driver/COLCON_IGNORE create mode 100644 drivers/ymc/COLCON_IGNORE create mode 100644 ds4/ds4/COLCON_IGNORE create mode 100644 ds4/ds4_driver/COLCON_IGNORE create mode 100644 ds4/ds4_msgs/COLCON_IGNORE create mode 100644 messages/autoware_can_msgs/COLCON_IGNORE create mode 100644 messages/autoware_external_msgs/COLCON_IGNORE create mode 100644 messages/autoware_map_msgs/COLCON_IGNORE create mode 100644 messages/autoware_system_msgs/COLCON_IGNORE create mode 100644 messages/tablet_socket_msgs/COLCON_IGNORE create mode 100644 messages/vector_map_msgs/COLCON_IGNORE create mode 100644 simulation/gazebo_camera_description/COLCON_IGNORE create mode 100644 simulation/gazebo_imu_description/COLCON_IGNORE create mode 100644 simulation/lgsvl_simulator_bridge/COLCON_IGNORE create mode 100644 simulation/vehicle_gazebo_simulation_interface/COLCON_IGNORE create mode 100644 simulation/vehicle_gazebo_simulation_launcher/COLCON_IGNORE create mode 100644 simulation/wf_simulator/COLCON_IGNORE create mode 100644 utilities/autoware_bag_tools/COLCON_IGNORE create mode 100644 utilities/autoware_launcher/COLCON_IGNORE create mode 100644 utilities/autoware_launcher_rviz/COLCON_IGNORE create mode 100644 utilities/data_preprocessor/COLCON_IGNORE create mode 100644 utilities/graph_tools/COLCON_IGNORE create mode 100644 utilities/kitti_box_publisher/COLCON_IGNORE create mode 100644 utilities/kitti_launch/COLCON_IGNORE create mode 100644 utilities/kitti_player/COLCON_IGNORE create mode 100644 utilities/lanelet_aisan_converter/COLCON_IGNORE create mode 100644 utilities/log_tools/COLCON_IGNORE create mode 100644 utilities/map_tf_generator/COLCON_IGNORE create mode 100644 utilities/marker_downsampler/COLCON_IGNORE create mode 100644 utilities/mqtt_socket/COLCON_IGNORE create mode 100644 utilities/oculus_socket/COLCON_IGNORE create mode 100644 utilities/pc2_downsampler/COLCON_IGNORE create mode 100644 utilities/rosbag_controller/COLCON_IGNORE create mode 100644 utilities/sound_player/COLCON_IGNORE create mode 100644 utilities/sync/COLCON_IGNORE create mode 100644 utilities/tablet_socket/COLCON_IGNORE create mode 100644 utilities/twist2odom/COLCON_IGNORE create mode 100644 utilities/udon_socket/COLCON_IGNORE create mode 100644 utilities/vehicle_engage_panel/COLCON_IGNORE create mode 100644 utilities/vehicle_socket/COLCON_IGNORE create mode 100644 visualization/decision_maker_panel/COLCON_IGNORE create mode 100644 visualization/fastvirtualscan/COLCON_IGNORE create mode 100644 visualization/gazebo_world_description/COLCON_IGNORE create mode 100644 visualization/glviewer/COLCON_IGNORE create mode 100644 visualization/integrated_viewer/COLCON_IGNORE create mode 100644 visualization/points2image/COLCON_IGNORE create mode 100644 visualization/rosinterface/COLCON_IGNORE create mode 100644 visualization/state_panel/COLCON_IGNORE create mode 100644 visualization/vehicle_description/COLCON_IGNORE create mode 100644 visualization/vehicle_model/COLCON_IGNORE diff --git a/car_demo/car_demo/COLCON_IGNORE b/car_demo/car_demo/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/car_demo/prius_description/COLCON_IGNORE b/car_demo/prius_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/car_demo/prius_msgs/COLCON_IGNORE b/car_demo/prius_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/emergency_handler/COLCON_IGNORE b/common/emergency_handler/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/libvectormap/COLCON_IGNORE b/common/libvectormap/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/object_map/COLCON_IGNORE b/common/object_map/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/op_planner/COLCON_IGNORE b/common/op_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/op_ros_helpers/COLCON_IGNORE b/common/op_ros_helpers/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/op_simu/COLCON_IGNORE b/common/op_simu/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/common/op_utility/COLCON_IGNORE b/common/op_utility/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/autoware_connector/COLCON_IGNORE b/core_perception/autoware_connector/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/gnss_localizer/COLCON_IGNORE b/core_perception/gnss_localizer/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/image_processor/COLCON_IGNORE b/core_perception/image_processor/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_apollo_cnn_seg_detect/COLCON_IGNORE b/core_perception/lidar_apollo_cnn_seg_detect/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_fake_perception/COLCON_IGNORE b/core_perception/lidar_fake_perception/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_kf_contour_track/COLCON_IGNORE b/core_perception/lidar_kf_contour_track/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_naive_l_shape_detect/COLCON_IGNORE b/core_perception/lidar_naive_l_shape_detect/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_point_pillars/COLCON_IGNORE b/core_perception/lidar_point_pillars/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/lidar_shape_estimation/COLCON_IGNORE b/core_perception/lidar_shape_estimation/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/ndt_gpu/COLCON_IGNORE b/core_perception/ndt_gpu/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/obj_db/COLCON_IGNORE b/core_perception/obj_db/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/pixel_cloud_fusion/COLCON_IGNORE b/core_perception/pixel_cloud_fusion/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/pos_db/COLCON_IGNORE b/core_perception/pos_db/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/road_occupancy_processor/COLCON_IGNORE b/core_perception/road_occupancy_processor/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/roi_object_filter/COLCON_IGNORE b/core_perception/roi_object_filter/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/trafficlight_recognizer/COLCON_IGNORE b/core_perception/trafficlight_recognizer/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/twist_generator/COLCON_IGNORE b/core_perception/twist_generator/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/vel_pose_diff_checker/COLCON_IGNORE b/core_perception/vel_pose_diff_checker/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/vision_lane_detect/COLCON_IGNORE b/core_perception/vision_lane_detect/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/vision_segment_enet_detect/COLCON_IGNORE b/core_perception/vision_segment_enet_detect/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_perception/vision_ssd_detect/COLCON_IGNORE b/core_perception/vision_ssd_detect/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/costmap_generator/COLCON_IGNORE b/core_planning/costmap_generator/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/decision_maker/COLCON_IGNORE b/core_planning/decision_maker/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/dp_planner/COLCON_IGNORE b/core_planning/dp_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/ff_waypoint_follower/COLCON_IGNORE b/core_planning/ff_waypoint_follower/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/freespace_planner/COLCON_IGNORE b/core_planning/freespace_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/lattice_planner/COLCON_IGNORE b/core_planning/lattice_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/op_global_planner/COLCON_IGNORE b/core_planning/op_global_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/op_local_planner/COLCON_IGNORE b/core_planning/op_local_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/op_simulation_package/COLCON_IGNORE b/core_planning/op_simulation_package/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/op_utilities/COLCON_IGNORE b/core_planning/op_utilities/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/state_machine_lib/COLCON_IGNORE b/core_planning/state_machine_lib/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/way_planner/COLCON_IGNORE b/core_planning/way_planner/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/documentation/autoware_quickstart_examples/COLCON_IGNORE b/documentation/autoware_quickstart_examples/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/analog_devices/COLCON_IGNORE b/drivers/analog_devices/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/autoware_driveworks_gmsl_interface/COLCON_IGNORE b/drivers/autoware_driveworks_gmsl_interface/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/autoware_driveworks_interface/COLCON_IGNORE b/drivers/autoware_driveworks_interface/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/baumer/COLCON_IGNORE b/drivers/baumer/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/custom_msgs/COLCON_IGNORE b/drivers/custom_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/garmin/COLCON_IGNORE b/drivers/garmin/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/hokuyo/COLCON_IGNORE b/drivers/hokuyo/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/javad_navsat_driver/COLCON_IGNORE b/drivers/javad_navsat_driver/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/kvaser/COLCON_IGNORE b/drivers/kvaser/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/lms5xx/COLCON_IGNORE b/drivers/lms5xx/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/memsic/COLCON_IGNORE b/drivers/memsic/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/microstrain/COLCON_IGNORE b/drivers/microstrain/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/nmea_navsat/COLCON_IGNORE b/drivers/nmea_navsat/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/pointgrey/COLCON_IGNORE b/drivers/pointgrey/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_description/COLCON_IGNORE b/drivers/sick_ldmrs_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_driver/COLCON_IGNORE b/drivers/sick_ldmrs_driver/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_driver/src/driver/COLCON_IGNORE b/drivers/sick_ldmrs_driver/src/driver/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_laser/COLCON_IGNORE b/drivers/sick_ldmrs_laser/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_msgs/COLCON_IGNORE b/drivers/sick_ldmrs_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/sick_ldmrs_tools/COLCON_IGNORE b/drivers/sick_ldmrs_tools/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/vectacam/COLCON_IGNORE b/drivers/vectacam/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/xsens_driver/COLCON_IGNORE b/drivers/xsens_driver/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/drivers/ymc/COLCON_IGNORE b/drivers/ymc/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/ds4/ds4/COLCON_IGNORE b/ds4/ds4/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/ds4/ds4_driver/COLCON_IGNORE b/ds4/ds4_driver/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/ds4/ds4_msgs/COLCON_IGNORE b/ds4/ds4_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/autoware_can_msgs/COLCON_IGNORE b/messages/autoware_can_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/autoware_external_msgs/COLCON_IGNORE b/messages/autoware_external_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/autoware_map_msgs/COLCON_IGNORE b/messages/autoware_map_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/autoware_system_msgs/COLCON_IGNORE b/messages/autoware_system_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/tablet_socket_msgs/COLCON_IGNORE b/messages/tablet_socket_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/messages/vector_map_msgs/COLCON_IGNORE b/messages/vector_map_msgs/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/gazebo_camera_description/COLCON_IGNORE b/simulation/gazebo_camera_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/gazebo_imu_description/COLCON_IGNORE b/simulation/gazebo_imu_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/lgsvl_simulator_bridge/COLCON_IGNORE b/simulation/lgsvl_simulator_bridge/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/vehicle_gazebo_simulation_interface/COLCON_IGNORE b/simulation/vehicle_gazebo_simulation_interface/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/vehicle_gazebo_simulation_launcher/COLCON_IGNORE b/simulation/vehicle_gazebo_simulation_launcher/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/simulation/wf_simulator/COLCON_IGNORE b/simulation/wf_simulator/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/autoware_bag_tools/COLCON_IGNORE b/utilities/autoware_bag_tools/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/autoware_launcher/COLCON_IGNORE b/utilities/autoware_launcher/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/autoware_launcher_rviz/COLCON_IGNORE b/utilities/autoware_launcher_rviz/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/data_preprocessor/COLCON_IGNORE b/utilities/data_preprocessor/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/graph_tools/COLCON_IGNORE b/utilities/graph_tools/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/kitti_box_publisher/COLCON_IGNORE b/utilities/kitti_box_publisher/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/kitti_launch/COLCON_IGNORE b/utilities/kitti_launch/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/kitti_player/COLCON_IGNORE b/utilities/kitti_player/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/lanelet_aisan_converter/COLCON_IGNORE b/utilities/lanelet_aisan_converter/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/log_tools/COLCON_IGNORE b/utilities/log_tools/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/map_tf_generator/COLCON_IGNORE b/utilities/map_tf_generator/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/marker_downsampler/COLCON_IGNORE b/utilities/marker_downsampler/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/mqtt_socket/COLCON_IGNORE b/utilities/mqtt_socket/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/oculus_socket/COLCON_IGNORE b/utilities/oculus_socket/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/pc2_downsampler/COLCON_IGNORE b/utilities/pc2_downsampler/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/rosbag_controller/COLCON_IGNORE b/utilities/rosbag_controller/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/sound_player/COLCON_IGNORE b/utilities/sound_player/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/sync/COLCON_IGNORE b/utilities/sync/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/tablet_socket/COLCON_IGNORE b/utilities/tablet_socket/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/twist2odom/COLCON_IGNORE b/utilities/twist2odom/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/udon_socket/COLCON_IGNORE b/utilities/udon_socket/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/vehicle_engage_panel/COLCON_IGNORE b/utilities/vehicle_engage_panel/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/utilities/vehicle_socket/COLCON_IGNORE b/utilities/vehicle_socket/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/decision_maker_panel/COLCON_IGNORE b/visualization/decision_maker_panel/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/fastvirtualscan/COLCON_IGNORE b/visualization/fastvirtualscan/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/gazebo_world_description/COLCON_IGNORE b/visualization/gazebo_world_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/glviewer/COLCON_IGNORE b/visualization/glviewer/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/integrated_viewer/COLCON_IGNORE b/visualization/integrated_viewer/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/points2image/COLCON_IGNORE b/visualization/points2image/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/rosinterface/COLCON_IGNORE b/visualization/rosinterface/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/state_panel/COLCON_IGNORE b/visualization/state_panel/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/vehicle_description/COLCON_IGNORE b/visualization/vehicle_description/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d diff --git a/visualization/vehicle_model/COLCON_IGNORE b/visualization/vehicle_model/COLCON_IGNORE new file mode 100644 index 00000000000..e69de29bb2d From 51d52f47de94a5884a10a1b9cdceec41b3d0dc4c Mon Sep 17 00:00:00 2001 From: Patrick Musau Date: Tue, 29 Jun 2021 13:39:45 -0500 Subject: [PATCH 03/23] Feature/lanelet2 autoware update (#155) * lanelet and minimal autoware update Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * revert lanelet CMakelists.txt to ensure correct catkin imports --- .../autoware_connector/CMakeLists.txt | 67 +- .../launch/can_status_translator.launch | 4 + .../launch/localization_connect.launch | 8 + .../can_status_translator_core.cpp | 18 +- .../can_status_translator_core.h | 1 + core_planning/twist_gate/CMakeLists.txt | 13 +- .../include/twist_gate/twist_gate.h | 40 +- core_planning/twist_gate/src/twist_gate.cpp | 81 +- .../twist_gate/test/src/test_twist_gate.cpp | 18 +- .../twist_gate/test/src/test_twist_gate.hpp | 4 +- core_planning/waypoint_maker/CMakeLists.txt | 16 +- .../launch/waypoint_creator.launch | 48 +- .../launch/waypoint_loader.launch | 12 +- .../launch/waypoint_saver.launch | 26 +- .../waypoint_velocity_visualizer.launch | 28 +- .../waypoint_clicker/waypoint_clicker.cpp | 298 +- .../waypoint_loader/waypoint_loader_core.cpp | 20 - .../waypoint_loader/waypoint_loader_core.h | 5 - .../waypoint_marker_publisher.cpp | 86 +- .../waypoint_replanner/waypoint_replanner.cpp | 124 +- .../waypoint_replanner/waypoint_replanner.h | 26 +- .../waypoint_replanner_node.cpp | 6 +- core_planning/waypoint_maker/package.xml | 6 +- core_planning/waypoint_planner/CMakeLists.txt | 15 +- .../astar_avoid/astar_avoid.h | 38 +- .../velocity_set/libvelocity_set.h | 5 +- .../velocity_set/velocity_set_info.h | 13 +- .../velocity_set/velocity_set_path.h | 22 +- .../launch/velocity_set.launch | 10 +- .../launch/velocity_set_lanelet2.launch | 2 +- .../launch/velocity_set_option.launch | 2 +- .../src/astar_avoid/astar_avoid.cpp | 231 +- .../src/velocity_set/libvelocity_set.cpp | 49 +- .../src/velocity_set/velocity_set.cpp | 306 +- .../src/velocity_set/velocity_set_info.cpp | 26 +- .../src/velocity_set/velocity_set_path.cpp | 96 +- .../velocity_set_lanelet2.cpp | 41 +- .../as/nodes/ssc_interface/ssc_interface.cpp | 12 +- drivers/ymc/CMakeLists.txt | 42 +- drivers/ymc/include/g30esli_interface.h | 1 + drivers/ymc/include/g30esli_ros.h | 1 + drivers/ymc/launch/g30esli_interface.launch | 2 + .../g30esli_interface/g30esli_interface.cpp | 6 + .../node/g30esli_interface/g30esli_ros.cpp | 40 +- drivers/ymc/package.xml | 2 +- lanelet2/.clang-tidy | 6 +- lanelet2/.gitlab-ci.yml | 198 +- lanelet2/.travis.yml | 53 +- lanelet2/CODEOWNERS | 4 +- lanelet2/Dockerfile | 79 +- lanelet2/README.md | 46 +- lanelet2/conanfile.py | 135 + lanelet2/lanelet2/CHANGELOG.rst | 27 + lanelet2/lanelet2/CMakeLists.txt | 12 +- lanelet2/lanelet2/package.xml | 15 +- lanelet2/lanelet2_core/CHANGELOG.rst | 60 + lanelet2/lanelet2_core/CMakeLists.txt | 11 +- .../doc/LaneletAndAreaTagging.md | 4 +- .../lanelet2_core/doc/LaneletPrimitives.md | 4 +- .../doc/RegulatoryElementTagging.md | 57 +- .../include/lanelet2_core/Attribute.h | 9 +- .../include/lanelet2_core/LaneletMap.h | 27 +- .../include/lanelet2_core/geometry/Area.h | 80 +- .../lanelet2_core/geometry/BoundingBox.h | 9 +- .../lanelet2_core/geometry/GeometryHelper.h | 21 +- .../include/lanelet2_core/geometry/Lanelet.h | 14 +- .../lanelet2_core/geometry/LaneletMap.h | 17 +- .../lanelet2_core/geometry/LineString.h | 27 +- .../include/lanelet2_core/geometry/Point.h | 8 +- .../include/lanelet2_core/geometry/Polygon.h | 62 +- .../geometry/RegulatoryElement.h | 4 +- .../lanelet2_core/geometry/impl/Area.h | 72 +- .../lanelet2_core/geometry/impl/Lanelet.h | 32 +- .../lanelet2_core/geometry/impl/LaneletMap.h | 11 +- .../lanelet2_core/geometry/impl/LineString.h | 49 +- .../lanelet2_core/geometry/impl/Polygon.h | 37 +- .../include/lanelet2_core/primitives/Area.h | 19 +- .../primitives/BasicRegulatoryElements.h | 11 +- .../lanelet2_core/primitives/BoundingBox.h | 9 +- .../primitives/CompoundLineString.h | 5 +- .../primitives/CompoundPolygon.h | 4 +- .../lanelet2_core/primitives/GPSPoint.h | 2 +- .../lanelet2_core/primitives/Lanelet.h | 14 +- .../lanelet2_core/primitives/LaneletOrArea.h | 21 +- .../primitives/LaneletSequence.h | 7 +- .../lanelet2_core/primitives/LineString.h | 29 +- .../primitives/LineStringOrPolygon.h | 16 +- .../include/lanelet2_core/primitives/Point.h | 19 +- .../lanelet2_core/primitives/Polygon.h | 10 +- .../lanelet2_core/primitives/Primitive.h | 13 +- .../primitives/RegulatoryElement.h | 32 +- .../include/lanelet2_core/primitives/Traits.h | 6 +- .../include/lanelet2_core/utility/HybridMap.h | 26 +- .../include/lanelet2_core/utility/Units.h | 3 +- .../include/lanelet2_core/utility/Utilities.h | 7 +- lanelet2/lanelet2_core/package.xml | 14 +- lanelet2/lanelet2_core/res/lanelet_gdb.py | 4 +- .../res/qtcreator_debugging_helpers.py | 99 +- lanelet2/lanelet2_core/src/Attribute.cpp | 18 +- .../src/BasicRegulatoryElements.cpp | 22 +- lanelet2/lanelet2_core/src/Lanelet.cpp | 22 +- lanelet2/lanelet2_core/src/LaneletMap.cpp | 36 +- .../lanelet2_core/src/LaneletSequence.cpp | 2 +- .../lanelet2_core/src/LineStringGeometry.cpp | 166 +- .../src/PolygonTriangulationGeometry.cpp | 457 + .../lanelet2_core/src/RegulatoryElement.cpp | 32 +- .../src/RegulatoryElementGeometry.cpp | 13 +- .../test/lanelet_map_test_case.h | 8 +- lanelet2/lanelet2_core/test/test_area.cpp | 203 +- .../lanelet2_core/test/test_attribute.cpp | 7 +- lanelet2/lanelet2_core/test/test_lanelet.cpp | 62 +- .../lanelet2_core/test/test_lanelet_map.cpp | 10 +- .../test/test_lanelet_map_geometry.cpp | 60 +- .../test/test_lanelet_or_area.cpp | 16 +- .../test/test_lanelet_sequence.cpp | 15 +- .../lanelet2_core/test/test_linestring.cpp | 84 +- lanelet2/lanelet2_core/test/test_point.cpp | 6 +- lanelet2/lanelet2_core/test/test_polygon.cpp | 124 +- .../test/test_regulatory_element.cpp | 9 +- lanelet2/lanelet2_examples/CHANGELOG.rst | 32 + lanelet2/lanelet2_examples/CMakeLists.txt | 49 +- lanelet2/lanelet2_examples/README.md | 2 +- lanelet2/lanelet2_examples/custom.cmake | 1 + .../internal}/ExampleHelpers.h | 4 +- lanelet2/lanelet2_examples/package.xml | 16 +- .../lanelet2_examples/scripts/tutorial.py | 8 +- .../main.cpp | 15 +- .../src/02_regulatory_elements/main.cpp | 3 +- .../src/03_lanelet_map/main.cpp | 3 +- .../src/04_reading_and_writing/main.cpp | 3 +- .../src/05_traffic_rules/main.cpp | 8 +- .../lanelet2_examples/test/test_examples.py | 9 +- lanelet2/lanelet2_io/CHANGELOG.rst | 38 + lanelet2/lanelet2_io/CMakeLists.txt | 4 +- .../include/lanelet2_io/Configuration.h | 1 + .../include/lanelet2_io/Exceptions.h | 1 + lanelet2/lanelet2_io/include/lanelet2_io/Io.h | 6 +- .../include/lanelet2_io/Projection.h | 1 + .../lanelet2_io/io_handlers/BinHandler.h | 4 +- .../include/lanelet2_io/io_handlers/Factory.h | 10 +- .../lanelet2_io/io_handlers/IoHandler.h | 7 +- .../include/lanelet2_io/io_handlers/OsmFile.h | 1 + .../lanelet2_io/io_handlers/OsmHandler.h | 6 +- .../include/lanelet2_io/io_handlers/Parser.h | 8 +- .../lanelet2_io/io_handlers/Serialize.h | 97 +- .../include/lanelet2_io/io_handlers/Writer.h | 6 +- lanelet2/lanelet2_io/package.xml | 13 +- lanelet2/lanelet2_io/src/BinHandler.cpp | 12 +- lanelet2/lanelet2_io/src/Factory.cpp | 5 +- lanelet2/lanelet2_io/src/Io.cpp | 8 +- lanelet2/lanelet2_io/src/OsmFile.cpp | 23 +- lanelet2/lanelet2_io/src/OsmHandlerLoad.cpp | 29 +- lanelet2/lanelet2_io/src/OsmHandlerWrite.cpp | 32 +- lanelet2/lanelet2_io/test/TestBinHandler.cpp | 17 +- lanelet2/lanelet2_io/test/TestLanelet2Io.cpp | 18 +- lanelet2/lanelet2_io/test/TestOsmFile.cpp | 3 +- lanelet2/lanelet2_io/test/TestOsmHandler.cpp | 20 +- lanelet2/lanelet2_io/test/TestSetup.h | 30 + lanelet2/lanelet2_io/test/TestSimpleUsage.cpp | 10 +- lanelet2/lanelet2_maps/CHANGELOG.rst | 31 + lanelet2/lanelet2_maps/CMakeLists.txt | 73 +- lanelet2/lanelet2_maps/README.md | 8 +- lanelet2/lanelet2_maps/package.xml | 15 +- lanelet2/lanelet2_matching/CMakeLists.txt | 69 + lanelet2/lanelet2_matching/README.md | 57 + lanelet2/lanelet2_matching/custom.cmake | 1 + .../include/lanelet2_matching/Exceptions.h | 47 + .../lanelet2_matching/LaneletMatching.h | 98 + .../include/lanelet2_matching/Types.h | 83 + .../include/lanelet2_matching/Utilities.h | 72 + .../lanelet2_matching/internal/.gitignore | 0 lanelet2/lanelet2_matching/package.xml | 31 + lanelet2/lanelet2_matching/src/.gitignore | 0 .../lanelet2_matching/src/LaneletMatching.cpp | 107 + lanelet2/lanelet2_matching/src/Utilities.cpp | 103 + .../test/lanelet2_matching.cpp | 260 + .../test/lanelet2_matching_integration.cpp | 169 + .../test/mapping_example.osm | 14535 ++++++++++++++++ lanelet2/lanelet2_projection/CHANGELOG.rst | 27 + lanelet2/lanelet2_projection/CMakeLists.txt | 73 +- lanelet2/lanelet2_projection/package.xml | 16 +- lanelet2/lanelet2_projection/src/UTM.cpp | 11 +- .../test/test_Mercator.cpp | 3 +- .../lanelet2_projection/test/test_UTM.cpp | 2 +- lanelet2/lanelet2_python/CHANGELOG.rst | 55 + lanelet2/lanelet2_python/CMakeLists.txt | 73 +- .../lanelet2_python/internal}/converter.h | 16 +- lanelet2/lanelet2_python/package.xml | 16 +- lanelet2/lanelet2_python/python_api/core.cpp | 143 +- .../lanelet2_python/python_api/geometry.cpp | 295 +- lanelet2/lanelet2_python/python_api/io.cpp | 3 +- .../lanelet2_python/python_api/matching.cpp | 187 + .../lanelet2_python/python_api/projection.cpp | 1 + .../lanelet2_python/python_api/routing.cpp | 232 +- .../python_api/std_map_indexing.h | 350 - .../python_api/traffic_rules.cpp | 13 +- .../scripts/create_debug_routing_graph.py | 2 +- .../scripts/make_ids_positive.py | 2 +- lanelet2/lanelet2_python/scripts/print_ids.py | 2 +- .../test/test_lanelet2_matching.py | 94 + lanelet2/lanelet2_routing/CHANGELOG.rst | 61 + lanelet2/lanelet2_routing/CMakeLists.txt | 7 +- lanelet2/lanelet2_routing/README.md | 16 +- .../include/lanelet2_routing/Forward.h | 2 +- .../include/lanelet2_routing/LaneletPath.h | 11 +- .../include/lanelet2_routing/Route.h | 12 +- .../include/lanelet2_routing/RoutingCost.h | 11 +- .../include/lanelet2_routing/RoutingGraph.h | 195 +- .../lanelet2_routing/RoutingGraphContainer.h | 6 +- .../include/lanelet2_routing/Types.h | 4 +- .../include/lanelet2_routing/internal/Graph.h | 16 +- .../lanelet2_routing/internal/GraphUtils.h | 56 +- .../lanelet2_routing/internal/RouteBuilder.h | 6 +- .../internal/RoutingGraphBuilder.h | 12 +- .../internal/RoutingGraphVisualization.h | 7 +- .../lanelet2_routing/internal/ShortestPath.h | 7 +- lanelet2/lanelet2_routing/package.xml | 13 +- lanelet2/lanelet2_routing/src/LaneletPath.cpp | 337 +- lanelet2/lanelet2_routing/src/Route.cpp | 16 +- .../lanelet2_routing/src/RouteBuilder.cpp | 108 +- lanelet2/lanelet2_routing/src/RoutingCost.cpp | 13 +- .../lanelet2_routing/src/RoutingGraph.cpp | 341 +- .../src/RoutingGraphBuilder.cpp | 51 +- .../test/test_lanelet_or_area_path.cpp | 211 + .../lanelet2_routing/test/test_relations.cpp | 16 +- lanelet2/lanelet2_routing/test/test_route.cpp | 12 +- .../lanelet2_routing/test/test_routing.cpp | 93 +- .../test/test_routing_graph_container.cpp | 9 +- .../lanelet2_routing/test/test_routing_map.h | 32 +- .../test/test_routing_visualization.cpp | 18 +- lanelet2/lanelet2_traffic_rules/CHANGELOG.rst | 28 + .../lanelet2_traffic_rules/CMakeLists.txt | 74 +- .../GenericTrafficRules.h | 3 +- .../GermanTrafficRules.h | 3 +- .../TrafficRulesFactory.h | 2 +- lanelet2/lanelet2_traffic_rules/package.xml | 13 +- .../src/GenericTrafficRules.cpp | 6 +- .../src/GermanTrafficRules.cpp | 10 +- .../src/TrafficRulesFactory.cpp | 2 +- .../test/lanelet2_traffic_rules.cpp | 11 +- lanelet2/lanelet2_validation/CHANGELOG.rst | 43 + lanelet2/lanelet2_validation/CMakeLists.txt | 74 +- .../lanelet2_validation/BasicValidator.h | 4 +- .../include/lanelet2_validation/Cli.h | 2 +- .../include/lanelet2_validation/Issue.h | 1 + .../include/lanelet2_validation/Validation.h | 3 +- .../lanelet2_validation/ValidatorFactory.h | 4 +- .../validators/mapping/BoolTags.h | 3 +- .../validators/mapping/CurvatureTooBig.h | 8 +- .../validators/mapping/DuplicatedPoints.h | 3 +- .../validators/mapping/MandatoryTags.h | 3 +- .../validators/mapping/PointsTooClose.h | 3 +- .../validators/mapping/UnknownTagValue.h | 3 +- .../validators/mapping/UnknownTags.h | 3 +- .../validators/routing/RoutingGraphIsValid.h | 2 +- lanelet2/lanelet2_validation/package.xml | 13 +- lanelet2/lanelet2_validation/src/Cli.cpp | 3 +- .../lanelet2_validation/src/Validation.cpp | 14 +- .../src/ValidatorFactory.cpp | 4 +- .../src/validators/CheckTags.cpp | 23 +- .../src/validators/CurvatureTooBig.cpp | 25 +- .../src/validators/DuplicatedPoints.cpp | 12 +- .../src/validators/PointsTooClose.cpp | 10 +- .../src/validators/RoutingGraphIsValid.cpp | 8 +- .../test/lanelet2_validation.cpp | 5 +- .../tools/lanelet2_validate/main.cpp | 2 +- messages/CONTRIBUTING.md | 10 +- messages/DISCLAIMER.md | 50 + messages/README.md | 2 + messages/SUPPORT.md | 4 +- messages/autoware_can_msgs/CHANGELOG.rst | 12 +- messages/autoware_can_msgs/CMakeLists.txt | 11 +- messages/autoware_can_msgs/package.xml | 4 +- messages/autoware_config_msgs/CHANGELOG.rst | 11 + messages/autoware_config_msgs/CMakeLists.txt | 68 +- .../msg/ConfigWaypointReplanner.msg | 6 +- messages/autoware_config_msgs/package.xml | 2 +- messages/autoware_external_msgs/CHANGELOG.rst | 8 + messages/autoware_external_msgs/package.xml | 2 +- messages/autoware_map_msgs/CHANGELOG.rst | 8 + messages/autoware_map_msgs/CMakeLists.txt | 67 +- messages/autoware_map_msgs/package.xml | 2 +- messages/autoware_msgs/CHANGELOG.rst | 9 + messages/autoware_msgs/CMakeLists.txt | 148 +- messages/autoware_msgs/msg/Gear.msg | 7 + messages/autoware_msgs/msg/VehicleCmd.msg | 2 +- messages/autoware_msgs/msg/VehicleStatus.msg | 2 +- messages/autoware_msgs/msg/Waypoint.msg | 14 +- messages/autoware_msgs/package.xml | 2 +- messages/autoware_system_msgs/CHANGELOG.rst | 9 + messages/autoware_system_msgs/CMakeLists.txt | 27 +- messages/autoware_system_msgs/package.xml | 2 +- messages/tablet_socket_msgs/CHANGELOG.rst | 8 + messages/tablet_socket_msgs/CMakeLists.txt | 179 +- messages/tablet_socket_msgs/package.xml | 2 +- messages/vector_map_msgs/CHANGELOG.rst | 8 + messages/vector_map_msgs/CMakeLists.txt | 137 +- messages/vector_map_msgs/package.xml | 2 +- mrt_cmake_modules/.cmake-format | 50 + mrt_cmake_modules/.gitlab-ci.yml | 14 + mrt_cmake_modules/CHANGELOG.rst | 86 + mrt_cmake_modules/CMakeLists.txt | 41 +- mrt_cmake_modules/CODEOWNERS | 6 +- mrt_cmake_modules/LICENSE | 675 +- mrt_cmake_modules/README.md | 206 +- mrt_cmake_modules/ci_templates/CMakeLists.txt | 71 +- .../ci_templates/catkin_project_template.yml | 4 +- .../ci_templates/default_catkin_project.yml | 174 +- .../ci_templates/gbp_project.yml | 86 +- .../cmake/Modules/CatkinMockForConan.cmake | 27 +- .../cmake/Modules/ExportPackage.cmake | 118 + mrt_cmake_modules/cmake/Modules/FindANN.cmake | 11 + .../cmake/Modules/FindAravis.cmake | 5 +- .../cmake/Modules/FindAutoDeps.cmake | 422 +- .../cmake/Modules/FindBoostPython.cmake | 56 +- .../cmake/Modules/FindCTensorflow.cmake | 21 + .../cmake/Modules/FindCairo.cmake | 62 +- .../cmake/Modules/FindCereal.cmake | 11 + .../cmake/Modules/FindClangTidy.cmake | 14 +- .../cmake/Modules/FindEigen2.cmake | 81 - .../cmake/Modules/FindFlann.cmake | 10 +- mrt_cmake_modules/cmake/Modules/FindG2O.cmake | 113 - .../cmake/Modules/FindGTKMM.cmake | 6 - .../cmake/Modules/FindGTest-headers.cmake | 5 - .../cmake/Modules/FindGeographicLib.cmake | 14 +- .../cmake/Modules/FindGlog.cmake | 400 +- mrt_cmake_modules/cmake/Modules/FindIGL.cmake | 38 +- .../cmake/Modules/FindIpopt.cmake | 12 +- .../cmake/Modules/FindJsonCpp.cmake | 443 + .../cmake/Modules/FindLeptonica.cmake | 11 + .../{FindMrtMetis.cmake => FindMetis.cmake} | 6 +- .../cmake/Modules/FindMinpack.cmake | 34 - .../cmake/Modules/FindMrtANN.cmake | 11 - .../cmake/Modules/FindMrtCTensorflow.cmake | 28 - .../cmake/Modules/FindMrtCUDA.cmake | 48 +- .../cmake/Modules/FindMrtCaffe.cmake | 21 - .../cmake/Modules/FindMrtCereal.cmake | 11 - .../cmake/Modules/FindMrtCeres.cmake | 25 - .../cmake/Modules/FindMrtLAPACK.cmake | 15 - .../cmake/Modules/FindMrtLeptonica.cmake | 11 - .../cmake/Modules/FindMrtOpenCV.cmake | 20 - .../cmake/Modules/FindMrtOpenGL.cmake | 10 + .../cmake/Modules/FindMrtPCL.cmake | 64 +- .../cmake/Modules/FindMrtQt4.cmake | 3 +- .../cmake/Modules/FindMrtQt5.cmake | 17 +- .../cmake/Modules/FindMrtSuiteSparse.cmake | 620 - .../cmake/Modules/FindMrtTensorflow.cmake | 30 - .../cmake/Modules/FindMrtTesseract.cmake | 11 - .../cmake/Modules/FindMrtVTK.cmake | 25 +- .../cmake/Modules/FindMrtbenchmark.cmake | 11 - .../cmake/Modules/FindMrtf2c.cmake | 15 - .../cmake/Modules/FindMrtnlopt.cmake | 33 - mrt_cmake_modules/cmake/Modules/FindOSG.cmake | 274 - .../cmake/Modules/FindPCAP.cmake | 74 - .../cmake/Modules/FindPNG++.cmake | 25 +- .../cmake/Modules/FindPoco.cmake | 63 - mrt_cmake_modules/cmake/Modules/FindQwt.cmake | 118 - .../cmake/Modules/FindRapidXML.cmake | 36 - .../{FindMrtSDL2.cmake => FindSDL2.cmake} | 178 +- .../cmake/Modules/FindSqlite3.cmake | 109 +- .../cmake/Modules/FindSuiteSparse.cmake | 521 + mrt_cmake_modules/cmake/Modules/FindTBB.cmake | 614 +- .../cmake/Modules/FindTensorflow.cmake | 20 + .../cmake/Modules/FindTesseract.cmake | 11 + .../cmake/Modules/FindTinyXML.cmake | 22 +- .../cmake/Modules/FindTinyXML2.cmake | 23 + ...ndMrtebus-sdk.cmake => Findebus-sdk.cmake} | 17 +- .../cmake/Modules/Findgtest.cmake | 12 +- .../cmake/Modules/Findlibgps.cmake | 57 - .../cmake/Modules/Findnlopt.cmake | 29 + .../cmake/Modules/Findpugixml.cmake | 15 +- .../cmake/Modules/Findrange-v3.cmake | 9 - .../cmake/Modules/Findyaml-cpp.cmake | 34 - .../cmake/Modules/GatherDeps.cmake | 25 +- .../cmake/Modules/MRTCoverage.cmake | 168 - .../cmake/Modules/MrtParamGenerator.cmake | 23 - .../cmake/Modules/MrtTesting.cmake | 304 + .../Modules/UseMrtStdCompilerFlags.cmake | 192 +- mrt_cmake_modules/cmake/README.md | 3 + .../cmake/Templates/CTestCustom.cmake.in | 6 + .../cmake/Templates/__init__.py.in | 9 +- .../Templates/mrt_cached_variables.cmake.in | 7 - .../cmake/Templates/packageConfig.cmake.in | 80 + .../cmake/Templates/python_api_install.py.in | 2 +- mrt_cmake_modules/cmake/Templates/setup.py.in | 2 +- .../cmake/Templates/test_utility.hpp.in | 2 +- .../cmake/mrt_cmake_modules-extras.cmake.em | 1120 -- .../cmake/mrt_cmake_modules-extras.cmake.in | 26 + .../cmake/mrt_cmake_modules-macros.cmake | 1524 ++ mrt_cmake_modules/doc/.buildinfo | 2 +- mrt_cmake_modules/doc/_static/basic.css | 97 +- .../doc/_static/comment-bright.png | Bin 3500 -> 756 bytes .../doc/_static/comment-close.png | Bin 3578 -> 829 bytes mrt_cmake_modules/doc/_static/comment.png | Bin 3445 -> 641 bytes mrt_cmake_modules/doc/_static/contents.png | Bin 202 -> 107 bytes mrt_cmake_modules/doc/_static/doctools.js | 82 +- .../doc/_static/documentation_options.js | 10 + .../doc/_static/down-pressed.png | Bin 347 -> 222 bytes mrt_cmake_modules/doc/_static/down.png | Bin 347 -> 202 bytes mrt_cmake_modules/doc/_static/file.png | Bin 358 -> 286 bytes mrt_cmake_modules/doc/_static/graphviz.css | 19 + mrt_cmake_modules/doc/_static/jquery-3.2.1.js | 10253 +++++++++++ mrt_cmake_modules/doc/_static/jquery.js | 9060 +++++----- .../doc/_static/language_data.js | 297 + mrt_cmake_modules/doc/_static/minus.png | Bin 173 -> 90 bytes mrt_cmake_modules/doc/_static/navigation.png | Bin 218 -> 120 bytes mrt_cmake_modules/doc/_static/plus.png | Bin 173 -> 90 bytes mrt_cmake_modules/doc/_static/searchtools.js | 124 +- .../doc/_static/underscore-1.3.1.js | 999 ++ mrt_cmake_modules/doc/_static/underscore.js | 745 +- mrt_cmake_modules/doc/_static/up-pressed.png | Bin 345 -> 214 bytes mrt_cmake_modules/doc/_static/up.png | Bin 345 -> 203 bytes mrt_cmake_modules/doc/_static/websupport.js | 4 +- mrt_cmake_modules/doc/generate_doc/Makefile | 2 +- mrt_cmake_modules/doc/generate_doc/conf.py | 15 +- .../doc/generate_doc/generate_cmake_rst.py | 14 +- .../doc/generated_cmake_api.html | 602 +- mrt_cmake_modules/doc/genindex.html | 207 +- mrt_cmake_modules/doc/objects.inv | Bin 652 -> 976 bytes mrt_cmake_modules/doc/search.html | 25 +- mrt_cmake_modules/doc/searchindex.js | 2 +- mrt_cmake_modules/package.xml | 45 +- mrt_cmake_modules/rosdoc.yaml | 2 + mrt_cmake_modules/scripts/eval_coverage.py | 153 + .../scripts/generate_cmake_dependency_file.py | 338 +- .../scripts/generate_cmakelists.py | 46 + mrt_cmake_modules/scripts/init_coverage.py | 62 + mrt_cmake_modules/scripts/run_test.py | 128 + mrt_cmake_modules/setup.py | 12 - .../parameter_generator_catkin.py | 3 - mrt_cmake_modules/yaml/base-vanilla.yaml | 453 - mrt_cmake_modules/yaml/base.yaml | 797 - mrt_cmake_modules/yaml/cmake.yaml | 440 + .../yaml/external-mrt-ros-bionic.yaml | 6044 ------- .../yaml/external-mrt-ros-xenial.yaml | 9284 ---------- mrt_cmake_modules/yaml/external.yaml | 51 - mrt_cmake_modules/yaml/metapackages.yaml | 51 - mrt_cmake_modules/yaml/mrt-ros.yaml | 546 - utilities/vehicle_socket/CMakeLists.txt | 32 +- .../nodes/vehicle_sender/vehicle_sender.cpp | 113 +- 440 files changed, 45435 insertions(+), 31581 deletions(-) create mode 100644 core_perception/autoware_connector/launch/can_status_translator.launch create mode 100644 core_perception/autoware_connector/launch/localization_connect.launch create mode 100644 lanelet2/conanfile.py create mode 100644 lanelet2/lanelet2/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_core/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_core/src/PolygonTriangulationGeometry.cpp create mode 100644 lanelet2/lanelet2_examples/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_examples/custom.cmake rename lanelet2/lanelet2_examples/{src => include/lanelet2_examples/internal}/ExampleHelpers.h (93%) create mode 100644 lanelet2/lanelet2_io/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_maps/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_matching/CMakeLists.txt create mode 100644 lanelet2/lanelet2_matching/README.md create mode 100644 lanelet2/lanelet2_matching/custom.cmake create mode 100644 lanelet2/lanelet2_matching/include/lanelet2_matching/Exceptions.h create mode 100644 lanelet2/lanelet2_matching/include/lanelet2_matching/LaneletMatching.h create mode 100644 lanelet2/lanelet2_matching/include/lanelet2_matching/Types.h create mode 100644 lanelet2/lanelet2_matching/include/lanelet2_matching/Utilities.h rename mrt_cmake_modules/src/mrt_cmake_modules/__init__.py => lanelet2/lanelet2_matching/include/lanelet2_matching/internal/.gitignore (100%) create mode 100644 lanelet2/lanelet2_matching/package.xml create mode 100644 lanelet2/lanelet2_matching/src/.gitignore create mode 100644 lanelet2/lanelet2_matching/src/LaneletMatching.cpp create mode 100644 lanelet2/lanelet2_matching/src/Utilities.cpp create mode 100644 lanelet2/lanelet2_matching/test/lanelet2_matching.cpp create mode 100644 lanelet2/lanelet2_matching/test/lanelet2_matching_integration.cpp create mode 100644 lanelet2/lanelet2_matching/test/mapping_example.osm create mode 100644 lanelet2/lanelet2_projection/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_python/CHANGELOG.rst rename lanelet2/lanelet2_python/{python_api => include/lanelet2_python/internal}/converter.h (96%) create mode 100644 lanelet2/lanelet2_python/python_api/matching.cpp delete mode 100644 lanelet2/lanelet2_python/python_api/std_map_indexing.h create mode 100644 lanelet2/lanelet2_python/test/test_lanelet2_matching.py create mode 100644 lanelet2/lanelet2_routing/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_routing/test/test_lanelet_or_area_path.cpp create mode 100644 lanelet2/lanelet2_traffic_rules/CHANGELOG.rst create mode 100644 lanelet2/lanelet2_validation/CHANGELOG.rst create mode 100644 messages/DISCLAIMER.md create mode 100644 messages/autoware_msgs/msg/Gear.msg create mode 100644 mrt_cmake_modules/.cmake-format create mode 100644 mrt_cmake_modules/CHANGELOG.rst create mode 100644 mrt_cmake_modules/cmake/Modules/ExportPackage.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindANN.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindCTensorflow.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindCereal.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindEigen2.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindG2O.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindGTKMM.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindGTest-headers.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindJsonCpp.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindLeptonica.cmake rename mrt_cmake_modules/cmake/Modules/{FindMrtMetis.cmake => FindMetis.cmake} (63%) delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMinpack.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtANN.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtCTensorflow.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtCaffe.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtCereal.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtCeres.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtLAPACK.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtLeptonica.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtOpenCV.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtOpenGL.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtSuiteSparse.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtTensorflow.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtTesseract.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtbenchmark.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtf2c.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindMrtnlopt.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindOSG.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindPCAP.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindPoco.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindQwt.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/FindRapidXML.cmake rename mrt_cmake_modules/cmake/Modules/{FindMrtSDL2.cmake => FindSDL2.cmake} (52%) create mode 100644 mrt_cmake_modules/cmake/Modules/FindSuiteSparse.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindTensorflow.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindTesseract.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/FindTinyXML2.cmake rename mrt_cmake_modules/cmake/Modules/{FindMrtebus-sdk.cmake => Findebus-sdk.cmake} (71%) delete mode 100644 mrt_cmake_modules/cmake/Modules/Findlibgps.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/Findnlopt.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/Findrange-v3.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/Findyaml-cpp.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/MRTCoverage.cmake delete mode 100644 mrt_cmake_modules/cmake/Modules/MrtParamGenerator.cmake create mode 100644 mrt_cmake_modules/cmake/Modules/MrtTesting.cmake create mode 100644 mrt_cmake_modules/cmake/README.md create mode 100644 mrt_cmake_modules/cmake/Templates/CTestCustom.cmake.in delete mode 100644 mrt_cmake_modules/cmake/Templates/mrt_cached_variables.cmake.in create mode 100644 mrt_cmake_modules/cmake/Templates/packageConfig.cmake.in delete mode 100644 mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.em create mode 100644 mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.in create mode 100644 mrt_cmake_modules/cmake/mrt_cmake_modules-macros.cmake create mode 100644 mrt_cmake_modules/doc/_static/documentation_options.js create mode 100644 mrt_cmake_modules/doc/_static/graphviz.css create mode 100644 mrt_cmake_modules/doc/_static/jquery-3.2.1.js create mode 100644 mrt_cmake_modules/doc/_static/language_data.js create mode 100644 mrt_cmake_modules/doc/_static/underscore-1.3.1.js create mode 100644 mrt_cmake_modules/rosdoc.yaml create mode 100755 mrt_cmake_modules/scripts/eval_coverage.py create mode 100755 mrt_cmake_modules/scripts/generate_cmakelists.py create mode 100755 mrt_cmake_modules/scripts/init_coverage.py create mode 100644 mrt_cmake_modules/scripts/run_test.py delete mode 100644 mrt_cmake_modules/setup.py delete mode 100644 mrt_cmake_modules/src/mrt_cmake_modules/parameter_generator_catkin.py delete mode 100644 mrt_cmake_modules/yaml/base-vanilla.yaml delete mode 100644 mrt_cmake_modules/yaml/base.yaml create mode 100644 mrt_cmake_modules/yaml/cmake.yaml delete mode 100644 mrt_cmake_modules/yaml/external-mrt-ros-bionic.yaml delete mode 100644 mrt_cmake_modules/yaml/external-mrt-ros-xenial.yaml delete mode 100644 mrt_cmake_modules/yaml/external.yaml delete mode 100644 mrt_cmake_modules/yaml/metapackages.yaml delete mode 100644 mrt_cmake_modules/yaml/mrt-ros.yaml diff --git a/core_perception/autoware_connector/CMakeLists.txt b/core_perception/autoware_connector/CMakeLists.txt index bface1fe43a..580b71cc198 100644 --- a/core_perception/autoware_connector/CMakeLists.txt +++ b/core_perception/autoware_connector/CMakeLists.txt @@ -1,64 +1,63 @@ cmake_minimum_required(VERSION 2.8.3) project(autoware_connector) - -find_package(autoware_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS - autoware_build_flags - roscpp - tf - geometry_msgs - autoware_msgs - autoware_can_msgs - nav_msgs - std_msgs - ) - - -catkin_package( + autoware_build_flags + autoware_can_msgs + autoware_msgs + geometry_msgs + nav_msgs + roscpp + std_msgs + tf ) +catkin_package() + include_directories( - ${catkin_INCLUDE_DIRS} - include + include + ${catkin_INCLUDE_DIRS} ) add_executable(can_status_translator - nodes/can_status_translator/can_status_translator_node.cpp - nodes/can_status_translator/can_status_translator_core.cpp - ) + nodes/can_status_translator/can_status_translator_node.cpp + nodes/can_status_translator/can_status_translator_core.cpp +) target_link_libraries(can_status_translator - ${catkin_LIBRARIES} - ) + ${catkin_LIBRARIES} +) add_dependencies(can_status_translator - ${catkin_EXPORTED_TARGETS} - ) + ${catkin_EXPORTED_TARGETS} +) add_executable(can_odometry - nodes/can_odometry/can_odometry_node.cpp - nodes/can_odometry/can_odometry_core.cpp - ) + nodes/can_odometry/can_odometry_node.cpp + nodes/can_odometry/can_odometry_core.cpp +) target_link_libraries(can_odometry - ${catkin_LIBRARIES} - ) + ${catkin_LIBRARIES} +) add_dependencies(can_odometry - ${catkin_EXPORTED_TARGETS} - ) + ${catkin_EXPORTED_TARGETS} +) install(TARGETS can_status_translator ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(TARGETS can_odometry ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) diff --git a/core_perception/autoware_connector/launch/can_status_translator.launch b/core_perception/autoware_connector/launch/can_status_translator.launch new file mode 100644 index 00000000000..000a06c2866 --- /dev/null +++ b/core_perception/autoware_connector/launch/can_status_translator.launch @@ -0,0 +1,4 @@ + + + + diff --git a/core_perception/autoware_connector/launch/localization_connect.launch b/core_perception/autoware_connector/launch/localization_connect.launch new file mode 100644 index 00000000000..e5f5ecbf365 --- /dev/null +++ b/core_perception/autoware_connector/launch/localization_connect.launch @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.cpp b/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.cpp index b0220fc542b..cddc759c0d0 100644 --- a/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.cpp +++ b/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.cpp @@ -97,10 +97,24 @@ void CanStatusTranslatorNode::publishVehicleStatus(const autoware_can_msgs::CANI vs.tm = msg->tm; vs.drivemode = msg->devmode; // I think devmode is typo in CANInfo... vs.steeringmode = msg->strmode; - vs.gearshift = msg->driveshift; + if (msg->driveshift == static_cast(GearShift::Drive)){ + vs.current_gear.gear = autoware_msgs::Gear::DRIVE; + } + else if (msg->driveshift == static_cast(GearShift::Reverse)){ + vs.current_gear.gear = autoware_msgs::Gear::REVERSE; + } + else if (msg->driveshift == static_cast(GearShift::Parking)){ + vs.current_gear.gear = autoware_msgs::Gear::PARK; + } + else if (msg->driveshift == static_cast(GearShift::Neutral)){ + vs.current_gear.gear = autoware_msgs::Gear::NEUTRAL; + } + else{ + vs.current_gear.gear = autoware_msgs::Gear::NEUTRAL; + } vs.speed = msg->speed; - if (vs.gearshift == static_cast(GearShift::Reverse)) + if (vs.current_gear.gear == autoware_msgs::Gear::REVERSE) { vs.speed *= -1.0; } diff --git a/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.h b/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.h index 6b9c1dd795d..05e5a51fca5 100644 --- a/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.h +++ b/core_perception/autoware_connector/nodes/can_status_translator/can_status_translator_core.h @@ -27,6 +27,7 @@ // User Defined Includes #include "autoware_can_msgs/CANInfo.h" #include "autoware_msgs/VehicleStatus.h" +#include "autoware_msgs/Gear.h" #include "can_vehicle_info.h" namespace autoware_connector diff --git a/core_planning/twist_gate/CMakeLists.txt b/core_planning/twist_gate/CMakeLists.txt index 5d551c2740a..6d629f4acda 100644 --- a/core_planning/twist_gate/CMakeLists.txt +++ b/core_planning/twist_gate/CMakeLists.txt @@ -1,31 +1,22 @@ cmake_minimum_required(VERSION 2.8.3) project(twist_gate) +find_package(autoware_build_flags REQUIRED) find_package( catkin REQUIRED COMPONENTS - autoware_build_flags autoware_config_msgs autoware_health_checker autoware_msgs geometry_msgs + ros_observer roscpp - rostest - rosunit roslint std_msgs tablet_socket_msgs - ros_observer ) catkin_package( INCLUDE_DIRS include - CATKIN_DEPENDS - autoware_config_msgs - autoware_health_checker - autoware_msgs - geometry_msgs - std_msgs - tablet_socket_msgs ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") diff --git a/core_planning/twist_gate/include/twist_gate/twist_gate.h b/core_planning/twist_gate/include/twist_gate/twist_gate.h index 094b890c39c..3220eb4b6ba 100644 --- a/core_planning/twist_gate/include/twist_gate/twist_gate.h +++ b/core_planning/twist_gate/include/twist_gate/twist_gate.h @@ -33,6 +33,7 @@ #include "autoware_msgs/ControlCommandStamped.h" #include "autoware_msgs/RemoteCmd.h" #include "autoware_msgs/VehicleCmd.h" +#include "autoware_msgs/Gear.h" #include "tablet_socket_msgs/gear_cmd.h" #include "tablet_socket_msgs/mode_cmd.h" @@ -40,11 +41,6 @@ // headers in Autowae Health Checker #include -#define CMD_GEAR_D 1 -#define CMD_GEAR_R 2 -#define CMD_GEAR_B 3 -#define CMD_GEAR_N 4 -#define CMD_GEAR_P 5 class TwistGate { @@ -58,23 +54,23 @@ class TwistGate ~TwistGate(); private: - void check_state(); - void watchdog_timer(); - void remote_cmd_callback(const remote_msgs_t::ConstPtr& input_msg); - void auto_cmd_twist_cmd_callback(const geometry_msgs::TwistStamped::ConstPtr& input_msg); - void mode_cmd_callback(const tablet_socket_msgs::mode_cmd::ConstPtr& input_msg); - void gear_cmd_callback(const tablet_socket_msgs::gear_cmd::ConstPtr& input_msg); - void accel_cmd_callback(const autoware_msgs::AccelCmd::ConstPtr& input_msg); - void steer_cmd_callback(const autoware_msgs::SteerCmd::ConstPtr& input_msg); - void brake_cmd_callback(const autoware_msgs::BrakeCmd::ConstPtr& input_msg); - void lamp_cmd_callback(const autoware_msgs::LampCmd::ConstPtr& input_msg); - void ctrl_cmd_callback(const autoware_msgs::ControlCommandStamped::ConstPtr& input_msg); - void state_callback(const std_msgs::StringConstPtr& input_msg); - void emergency_cmd_callback(const vehicle_cmd_msg_t::ConstPtr& input_msg); - void timer_callback(const ros::TimerEvent& e); - void config_callback(const autoware_config_msgs::ConfigTwistFilter& msg); - - void reset_vehicle_cmd_msg(); + void checkState(); + void watchdogTimer(); + void remoteCmdCallback(const remote_msgs_t::ConstPtr& input_msg); + void autoCmdTwistCmdCallback(const geometry_msgs::TwistStamped::ConstPtr& input_msg); + void modeCmdCallback(const tablet_socket_msgs::mode_cmd::ConstPtr& input_msg); + void gearCmdCallback(const tablet_socket_msgs::gear_cmd::ConstPtr& input_msg); + void accelCmdCallback(const autoware_msgs::AccelCmd::ConstPtr& input_msg); + void steerCmdCallback(const autoware_msgs::SteerCmd::ConstPtr& input_msg); + void brakeCmdCallback(const autoware_msgs::BrakeCmd::ConstPtr& input_msg); + void lampCmdCallback(const autoware_msgs::LampCmd::ConstPtr& input_msg); + void ctrlCmdCallback(const autoware_msgs::ControlCommandStamped::ConstPtr& input_msg); + void stateCallback(const std_msgs::StringConstPtr& input_msg); + void emergencyCmdCallback(const vehicle_cmd_msg_t::ConstPtr& input_msg); + void timerCallback(const ros::TimerEvent& e); + void configCallback(const autoware_config_msgs::ConfigTwistFilter& msg); + + void resetVehicleCmdMsg(); // spinOnce for test void spinOnce() { ros::spinOnce(); } diff --git a/core_planning/twist_gate/src/twist_gate.cpp b/core_planning/twist_gate/src/twist_gate.cpp index 0a997190b2e..3c785a70216 100644 --- a/core_planning/twist_gate/src/twist_gate.cpp +++ b/core_planning/twist_gate/src/twist_gate.cpp @@ -32,7 +32,6 @@ #include #include -#include #include #include @@ -51,22 +50,22 @@ TwistGate::TwistGate(const ros::NodeHandle& nh, const ros::NodeHandle& private_n health_checker_ptr_ = std::make_shared(nh_, private_nh_); control_command_pub_ = nh_.advertise("/ctrl_mode", 1); vehicle_cmd_pub_ = nh_.advertise("/vehicle_cmd", 1, true); - remote_cmd_sub_ = nh_.subscribe("/remote_cmd", 1, &TwistGate::remote_cmd_callback, this); - config_sub_ = nh_.subscribe("config/twist_filter", 1, &TwistGate::config_callback, this); - - timer_ = nh_.createTimer(ros::Duration(1.0 / loop_rate_), &TwistGate::timer_callback, this); - - auto_cmd_sub_stdmap_["twist_cmd"] = nh_.subscribe("/twist_cmd", 1, &TwistGate::auto_cmd_twist_cmd_callback, this); - auto_cmd_sub_stdmap_["mode_cmd"] = nh_.subscribe("/mode_cmd", 1, &TwistGate::mode_cmd_callback, this); - auto_cmd_sub_stdmap_["gear_cmd"] = nh_.subscribe("/gear_cmd", 1, &TwistGate::gear_cmd_callback, this); - auto_cmd_sub_stdmap_["accel_cmd"] = nh_.subscribe("/accel_cmd", 1, &TwistGate::accel_cmd_callback, this); - auto_cmd_sub_stdmap_["steer_cmd"] = nh_.subscribe("/steer_cmd", 1, &TwistGate::steer_cmd_callback, this); - auto_cmd_sub_stdmap_["brake_cmd"] = nh_.subscribe("/brake_cmd", 1, &TwistGate::brake_cmd_callback, this); - auto_cmd_sub_stdmap_["lamp_cmd"] = nh_.subscribe("/lamp_cmd", 1, &TwistGate::lamp_cmd_callback, this); - auto_cmd_sub_stdmap_["ctrl_cmd"] = nh_.subscribe("/ctrl_cmd", 1, &TwistGate::ctrl_cmd_callback, this); - auto_cmd_sub_stdmap_["state"] = nh_.subscribe("/decision_maker/state", 1, &TwistGate::state_callback, this); + remote_cmd_sub_ = nh_.subscribe("/remote_cmd", 1, &TwistGate::remoteCmdCallback, this); + config_sub_ = nh_.subscribe("config/twist_filter", 1, &TwistGate::configCallback, this); + + timer_ = nh_.createTimer(ros::Duration(1.0 / loop_rate_), &TwistGate::timerCallback, this); + + auto_cmd_sub_stdmap_["twist_cmd"] = nh_.subscribe("/twist_cmd", 1, &TwistGate::autoCmdTwistCmdCallback, this); + auto_cmd_sub_stdmap_["mode_cmd"] = nh_.subscribe("/mode_cmd", 1, &TwistGate::modeCmdCallback, this); + auto_cmd_sub_stdmap_["gear_cmd"] = nh_.subscribe("/gear_cmd", 1, &TwistGate::gearCmdCallback, this); + auto_cmd_sub_stdmap_["accel_cmd"] = nh_.subscribe("/accel_cmd", 1, &TwistGate::accelCmdCallback, this); + auto_cmd_sub_stdmap_["steer_cmd"] = nh_.subscribe("/steer_cmd", 1, &TwistGate::steerCmdCallback, this); + auto_cmd_sub_stdmap_["brake_cmd"] = nh_.subscribe("/brake_cmd", 1, &TwistGate::brakeCmdCallback, this); + auto_cmd_sub_stdmap_["lamp_cmd"] = nh_.subscribe("/lamp_cmd", 1, &TwistGate::lampCmdCallback, this); + auto_cmd_sub_stdmap_["ctrl_cmd"] = nh_.subscribe("/ctrl_cmd", 1, &TwistGate::ctrlCmdCallback, this); + auto_cmd_sub_stdmap_["state"] = nh_.subscribe("/decision_maker/state", 1, &TwistGate::stateCallback, this); auto_cmd_sub_stdmap_["emergency_velocity"] = - nh_.subscribe("emergency_velocity", 1, &TwistGate::emergency_cmd_callback, this); + nh_.subscribe("emergency_velocity", 1, &TwistGate::emergencyCmdCallback, this); twist_gate_msg_.header.seq = 0; emergency_stop_msg_.data = false; @@ -76,7 +75,7 @@ TwistGate::TwistGate(const ros::NodeHandle& nh, const ros::NodeHandle& private_n remote_cmd_time_ = ros::Time::now(); emergency_handling_time_ = ros::Time::now(); state_time_ = ros::Time::now(); - watchdog_timer_thread_ = std::thread(&TwistGate::watchdog_timer, this); + watchdog_timer_thread_ = std::thread(&TwistGate::watchdogTimer, this); is_alive = true; } @@ -86,12 +85,12 @@ TwistGate::~TwistGate() watchdog_timer_thread_.join(); } -void TwistGate::reset_vehicle_cmd_msg() +void TwistGate::resetVehicleCmdMsg() { twist_gate_msg_.twist_cmd.twist.linear.x = 0; twist_gate_msg_.twist_cmd.twist.angular.z = 0; twist_gate_msg_.mode = 0; - twist_gate_msg_.gear = 0; + twist_gate_msg_.gear_cmd.gear = autoware_msgs::Gear::NONE; twist_gate_msg_.lamp_cmd.l = 0; twist_gate_msg_.lamp_cmd.r = 0; twist_gate_msg_.accel_cmd.accel = 0; @@ -102,7 +101,7 @@ void TwistGate::reset_vehicle_cmd_msg() twist_gate_msg_.emergency = 0; } -void TwistGate::check_state() +void TwistGate::checkState() { const double state_msg_timeout = 0.5; double state_time_diff = ros::Time::now().toSec() - state_time_.toSec(); @@ -114,7 +113,7 @@ void TwistGate::check_state() } } -void TwistGate::watchdog_timer() +void TwistGate::watchdogTimer() { ShmVitalMonitor shm_vmon("TwistGate", 100); @@ -167,7 +166,7 @@ void TwistGate::watchdog_timer() } } -void TwistGate::remote_cmd_callback(const remote_msgs_t::ConstPtr& input_msg) +void TwistGate::remoteCmdCallback(const remote_msgs_t::ConstPtr& input_msg) { remote_cmd_time_ = ros::Time::now(); command_mode_ = static_cast(input_msg->control_mode); @@ -185,13 +184,13 @@ void TwistGate::remote_cmd_callback(const remote_msgs_t::ConstPtr& input_msg) twist_gate_msg_.accel_cmd = input_msg->vehicle_cmd.accel_cmd; twist_gate_msg_.brake_cmd = input_msg->vehicle_cmd.brake_cmd; twist_gate_msg_.steer_cmd = input_msg->vehicle_cmd.steer_cmd; - twist_gate_msg_.gear = input_msg->vehicle_cmd.gear; + twist_gate_msg_.gear_cmd.gear = input_msg->vehicle_cmd.gear_cmd.gear; twist_gate_msg_.lamp_cmd = input_msg->vehicle_cmd.lamp_cmd; twist_gate_msg_.mode = input_msg->vehicle_cmd.mode; } } -void TwistGate::auto_cmd_twist_cmd_callback(const geometry_msgs::TwistStamped::ConstPtr& input_msg) +void TwistGate::autoCmdTwistCmdCallback(const geometry_msgs::TwistStamped::ConstPtr& input_msg) { health_checker_ptr_->CHECK_RATE("topic_rate_twist_cmd_slow", 8, 5, 1, "topic twist_cmd subscribe rate slow."); health_checker_ptr_->CHECK_MAX_VALUE("twist_cmd_linear_high", input_msg->twist.linear.x, @@ -204,18 +203,18 @@ void TwistGate::auto_cmd_twist_cmd_callback(const geometry_msgs::TwistStamped::C twist_gate_msg_.header.seq++; twist_gate_msg_.twist_cmd.twist = input_msg->twist; - check_state(); + checkState(); } } -void TwistGate::mode_cmd_callback(const tablet_socket_msgs::mode_cmd::ConstPtr& input_msg) +void TwistGate::modeCmdCallback(const tablet_socket_msgs::mode_cmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { // TODO(unknown): check this if statement if (input_msg->mode == -1 || input_msg->mode == 0) { - reset_vehicle_cmd_msg(); + resetVehicleCmdMsg(); } twist_gate_msg_.header.frame_id = input_msg->header.frame_id; twist_gate_msg_.header.stamp = input_msg->header.stamp; @@ -224,15 +223,15 @@ void TwistGate::mode_cmd_callback(const tablet_socket_msgs::mode_cmd::ConstPtr& } } -void TwistGate::gear_cmd_callback(const tablet_socket_msgs::gear_cmd::ConstPtr& input_msg) +void TwistGate::gearCmdCallback(const tablet_socket_msgs::gear_cmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { - twist_gate_msg_.gear = input_msg->gear; + twist_gate_msg_.gear_cmd.gear = input_msg->gear; } } -void TwistGate::accel_cmd_callback(const autoware_msgs::AccelCmd::ConstPtr& input_msg) +void TwistGate::accelCmdCallback(const autoware_msgs::AccelCmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { @@ -243,7 +242,7 @@ void TwistGate::accel_cmd_callback(const autoware_msgs::AccelCmd::ConstPtr& inpu } } -void TwistGate::steer_cmd_callback(const autoware_msgs::SteerCmd::ConstPtr& input_msg) +void TwistGate::steerCmdCallback(const autoware_msgs::SteerCmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { @@ -254,7 +253,7 @@ void TwistGate::steer_cmd_callback(const autoware_msgs::SteerCmd::ConstPtr& inpu } } -void TwistGate::brake_cmd_callback(const autoware_msgs::BrakeCmd::ConstPtr& input_msg) +void TwistGate::brakeCmdCallback(const autoware_msgs::BrakeCmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { @@ -265,7 +264,7 @@ void TwistGate::brake_cmd_callback(const autoware_msgs::BrakeCmd::ConstPtr& inpu } } -void TwistGate::lamp_cmd_callback(const autoware_msgs::LampCmd::ConstPtr& input_msg) +void TwistGate::lampCmdCallback(const autoware_msgs::LampCmd::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { @@ -277,7 +276,7 @@ void TwistGate::lamp_cmd_callback(const autoware_msgs::LampCmd::ConstPtr& input_ } } -void TwistGate::ctrl_cmd_callback(const autoware_msgs::ControlCommandStamped::ConstPtr& input_msg) +void TwistGate::ctrlCmdCallback(const autoware_msgs::ControlCommandStamped::ConstPtr& input_msg) { if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) { @@ -286,11 +285,11 @@ void TwistGate::ctrl_cmd_callback(const autoware_msgs::ControlCommandStamped::Co twist_gate_msg_.header.seq++; twist_gate_msg_.ctrl_cmd = input_msg->cmd; - check_state(); + checkState(); } } -void TwistGate::state_callback(const std_msgs::StringConstPtr& input_msg) +void TwistGate::stateCallback(const std_msgs::StringConstPtr& input_msg) { state_time_ = ros::Time::now(); if (command_mode_ == CommandMode::AUTO && !emergency_handling_active_) @@ -298,12 +297,12 @@ void TwistGate::state_callback(const std_msgs::StringConstPtr& input_msg) // Set Parking Gear if (input_msg->data.find("WaitOrder") != std::string::npos) { - twist_gate_msg_.gear = CMD_GEAR_P; + twist_gate_msg_.gear_cmd.gear = autoware_msgs::Gear::PARK; } // Set Drive Gear else { - twist_gate_msg_.gear = CMD_GEAR_D; + twist_gate_msg_.gear_cmd.gear = autoware_msgs::Gear::DRIVE; } // get drive state @@ -325,19 +324,19 @@ void TwistGate::state_callback(const std_msgs::StringConstPtr& input_msg) } } -void TwistGate::emergency_cmd_callback(const vehicle_cmd_msg_t::ConstPtr& input_msg) +void TwistGate::emergencyCmdCallback(const vehicle_cmd_msg_t::ConstPtr& input_msg) { emergency_handling_time_ = ros::Time::now(); emergency_handling_active_ = true; twist_gate_msg_ = *input_msg; } -void TwistGate::timer_callback(const ros::TimerEvent& e) +void TwistGate::timerCallback(const ros::TimerEvent& e) { vehicle_cmd_pub_.publish(twist_gate_msg_); } -void TwistGate::config_callback(const autoware_config_msgs::ConfigTwistFilter& msg) +void TwistGate::configCallback(const autoware_config_msgs::ConfigTwistFilter& msg) { use_decision_maker_ = msg.use_decision_maker; } diff --git a/core_planning/twist_gate/test/src/test_twist_gate.cpp b/core_planning/twist_gate/test/src/test_twist_gate.cpp index 2e2307b44b5..cf8882a2376 100644 --- a/core_planning/twist_gate/test/src/test_twist_gate.cpp +++ b/core_planning/twist_gate/test/src/test_twist_gate.cpp @@ -47,7 +47,7 @@ TEST_F(TwistGateTestSuite, resetVehicelCmd) ASSERT_EQ(d_value, msg.twist_cmd.twist.linear.x); ASSERT_EQ(d_value, msg.twist_cmd.twist.angular.z); ASSERT_EQ(i_value, msg.mode); - ASSERT_EQ(i_value, msg.gear); + ASSERT_EQ(i_value, msg.gear_cmd.gear); ASSERT_EQ(i_value, msg.lamp_cmd.l); ASSERT_EQ(i_value, msg.lamp_cmd.r); ASSERT_EQ(i_value, msg.accel_cmd.accel); @@ -63,7 +63,7 @@ TEST_F(TwistGateTestSuite, resetVehicelCmd) ASSERT_EQ(0, msg.twist_cmd.twist.linear.x); ASSERT_EQ(0, msg.twist_cmd.twist.angular.z); ASSERT_EQ(0, msg.mode); - ASSERT_EQ(0, msg.gear); + ASSERT_EQ(0, msg.gear_cmd.gear); ASSERT_EQ(0, msg.lamp_cmd.l); ASSERT_EQ(0, msg.lamp_cmd.r); ASSERT_EQ(0, msg.accel_cmd.accel); @@ -124,7 +124,7 @@ TEST_F(TwistGateTestSuite, remoteCmdCallback) remote_cmd.vehicle_cmd.accel_cmd.accel = 10; remote_cmd.vehicle_cmd.brake_cmd.brake = 20; remote_cmd.vehicle_cmd.steer_cmd.steer = 30; - remote_cmd.vehicle_cmd.gear = CMD_GEAR_P; + remote_cmd.vehicle_cmd.gear_cmd.gear = autoware_msgs::Gear::PARK; remote_cmd.vehicle_cmd.lamp_cmd.l = 1; remote_cmd.vehicle_cmd.lamp_cmd.r = 1; remote_cmd.vehicle_cmd.mode = 6; @@ -160,8 +160,8 @@ TEST_F(TwistGateTestSuite, remoteCmdCallback) , test_obj_.cb_vehicle_cmd.brake_cmd.brake); ASSERT_EQ(remote_cmd.vehicle_cmd.steer_cmd.steer , test_obj_.cb_vehicle_cmd.steer_cmd.steer); - ASSERT_EQ(remote_cmd.vehicle_cmd.gear - , test_obj_.cb_vehicle_cmd.gear); + ASSERT_EQ(remote_cmd.vehicle_cmd.gear_cmd.gear + , test_obj_.cb_vehicle_cmd.gear_cmd.gear); ASSERT_EQ(remote_cmd.vehicle_cmd.lamp_cmd.l , test_obj_.cb_vehicle_cmd.lamp_cmd.l); ASSERT_EQ(remote_cmd.vehicle_cmd.lamp_cmd.r @@ -189,7 +189,7 @@ TEST_F(TwistGateTestSuite, modeCmdCallback) TEST_F(TwistGateTestSuite, gearCmdCallback) { - int gear = CMD_GEAR_D; + int gear = autoware_msgs::Gear::DRIVE; test_obj_.publishGearCmd(gear); ros::WallDuration(0.1).sleep(); @@ -201,7 +201,7 @@ TEST_F(TwistGateTestSuite, gearCmdCallback) } - ASSERT_EQ(gear, test_obj_.cb_vehicle_cmd.gear); + ASSERT_EQ(gear, test_obj_.cb_vehicle_cmd.gear_cmd.gear); } TEST_F(TwistGateTestSuite, accelCmdCallback) @@ -330,7 +330,7 @@ TEST_F(TwistGateTestSuite, stateCallback) ros::spinOnce(); autoware_msgs::VehicleCmd tg_msg = test_obj_.getTwistGateMsg(); - ASSERT_EQ(CMD_GEAR_P, tg_msg.gear); + ASSERT_EQ(autoware_msgs::Gear::PARK, tg_msg.gear_cmd.gear); ASSERT_EQ(false, test_obj_.getIsStateDriveFlag()); test_obj_.publishDecisionMakerState("VehicleReady\nDriving\nDrive\n"); @@ -339,7 +339,7 @@ TEST_F(TwistGateTestSuite, stateCallback) ros::spinOnce(); tg_msg = test_obj_.getTwistGateMsg(); - ASSERT_EQ(CMD_GEAR_D, tg_msg.gear); + ASSERT_EQ(autoware_msgs::Gear::DRIVE, tg_msg.gear_cmd.gear); ASSERT_EQ(true, test_obj_.getIsStateDriveFlag()); } diff --git a/core_planning/twist_gate/test/src/test_twist_gate.hpp b/core_planning/twist_gate/test/src/test_twist_gate.hpp index 00f171eede8..bd4acca197b 100644 --- a/core_planning/twist_gate/test/src/test_twist_gate.hpp +++ b/core_planning/twist_gate/test/src/test_twist_gate.hpp @@ -49,13 +49,13 @@ class TwistGateTestClass { void tgSpinOnce() { tg->spinOnce(); } - void tgResetVehicleCmdMsg() { tg->reset_vehicle_cmd_msg(); } + void tgResetVehicleCmdMsg() { tg->resetVehicleCmdMsg(); } autoware_msgs::VehicleCmd setTgTwistGateMsg(double d_value, int i_value) { tg->twist_gate_msg_.twist_cmd.twist.linear.x = d_value; tg->twist_gate_msg_.twist_cmd.twist.angular.z = d_value; tg->twist_gate_msg_.mode = i_value; - tg->twist_gate_msg_.gear = i_value; + tg->twist_gate_msg_.gear_cmd.gear = i_value; tg->twist_gate_msg_.lamp_cmd.l = i_value; tg->twist_gate_msg_.lamp_cmd.r = i_value; tg->twist_gate_msg_.accel_cmd.accel = i_value; diff --git a/core_planning/waypoint_maker/CMakeLists.txt b/core_planning/waypoint_maker/CMakeLists.txt index 604181cca1f..088cd9b67a4 100644 --- a/core_planning/waypoint_maker/CMakeLists.txt +++ b/core_planning/waypoint_maker/CMakeLists.txt @@ -7,6 +7,7 @@ find_package( catkin REQUIRED COMPONENTS amathutils_lib autoware_msgs + autoware_config_msgs geometry_msgs gnss lane_planner @@ -14,25 +15,14 @@ find_package( nav_msgs roscpp std_msgs + tablet_socket_msgs tf vector_map ) find_package(Boost REQUIRED) -catkin_package( - CATKIN_DEPENDS - amathutils_lib - autoware_msgs - geometry_msgs - gnss - lane_planner - libwaypoint_follower - nav_msgs - std_msgs - tf - vector_map -) +catkin_package() SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") diff --git a/core_planning/waypoint_maker/launch/waypoint_creator.launch b/core_planning/waypoint_maker/launch/waypoint_creator.launch index 1bb2115066a..cd19a6ad405 100644 --- a/core_planning/waypoint_maker/launch/waypoint_creator.launch +++ b/core_planning/waypoint_maker/launch/waypoint_creator.launch @@ -1,29 +1,29 @@ - - - - - - - - + + + + + + + + - - - - - - - - - - - + + + + + + + + + + + - - - - - + + + + + diff --git a/core_planning/waypoint_maker/launch/waypoint_loader.launch b/core_planning/waypoint_maker/launch/waypoint_loader.launch index 9a6622fa637..de56936fcb1 100644 --- a/core_planning/waypoint_maker/launch/waypoint_loader.launch +++ b/core_planning/waypoint_maker/launch/waypoint_loader.launch @@ -7,17 +7,13 @@ - - - - - + @@ -30,17 +26,13 @@ - - - - - + diff --git a/core_planning/waypoint_maker/launch/waypoint_saver.launch b/core_planning/waypoint_maker/launch/waypoint_saver.launch index 67519fce7f2..4f282c46643 100644 --- a/core_planning/waypoint_maker/launch/waypoint_saver.launch +++ b/core_planning/waypoint_maker/launch/waypoint_saver.launch @@ -1,24 +1,24 @@ - - + + - + - - - - - + + + + + - - - - - + + + + + diff --git a/core_planning/waypoint_maker/launch/waypoint_velocity_visualizer.launch b/core_planning/waypoint_maker/launch/waypoint_velocity_visualizer.launch index b0dcf38aae0..24e84b51bd1 100644 --- a/core_planning/waypoint_maker/launch/waypoint_velocity_visualizer.launch +++ b/core_planning/waypoint_maker/launch/waypoint_velocity_visualizer.launch @@ -1,12 +1,12 @@ - + - + - + @@ -20,12 +20,12 @@ - - - - - - + + + + + + @@ -33,9 +33,9 @@ - $(arg base_waypoints_rgba) - $(arg final_waypoints_rgba) - $(arg current_twist_rgba) - $(arg command_twist_rgba) - + $(arg base_waypoints_rgba) + $(arg final_waypoints_rgba) + $(arg current_twist_rgba) + $(arg command_twist_rgba) + diff --git a/core_planning/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp b/core_planning/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp index 386ef11e99a..0c35c1e3000 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp +++ b/core_planning/waypoint_maker/nodes/waypoint_clicker/waypoint_clicker.cpp @@ -44,180 +44,180 @@ lane_planner::vmap::VectorMap coarse_vmap; void create_route(const geometry_msgs::PointStamped& msg) { - if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) - return; + if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) + return; - geometry_msgs::Point point; - point.x = msg.point.x + transform.getOrigin().x(); - point.y = msg.point.y + transform.getOrigin().y(); - point.z = msg.point.z + transform.getOrigin().z(); - coarse_vmap.points.push_back(lane_planner::vmap::create_vector_map_point(point)); - lane_planner::vmap::publish_add_marker(marker_pub, selection_marker, coarse_vmap.points); + geometry_msgs::Point point; + point.x = msg.point.x + transform.getOrigin().x(); + point.y = msg.point.y + transform.getOrigin().y(); + point.z = msg.point.z + transform.getOrigin().z(); + coarse_vmap.points.push_back(lane_planner::vmap::create_vector_map_point(point)); + lane_planner::vmap::publish_add_marker(marker_pub, selection_marker, coarse_vmap.points); - if (coarse_vmap.points.size() < 2) - return; + if (coarse_vmap.points.size() < 2) + return; - lane_planner::vmap::VectorMap fine_vmap = - lane_planner::vmap::create_fine_vmap(lane_vmap, lane_planner::vmap::LNO_ALL, coarse_vmap, - search_radius, waypoint_max); - if (fine_vmap.points.size() < 2) - return; + lane_planner::vmap::VectorMap fine_vmap = + lane_planner::vmap::create_fine_vmap(lane_vmap, lane_planner::vmap::LNO_ALL, coarse_vmap, + search_radius, waypoint_max); + if (fine_vmap.points.size() < 2) + return; - lane_planner::vmap::publish_add_marker(marker_pub, route_marker, fine_vmap.points); + lane_planner::vmap::publish_add_marker(marker_pub, route_marker, fine_vmap.points); - lane_planner::vmap::write_waypoints(fine_vmap.points, velocity, output_file); + lane_planner::vmap::write_waypoints(fine_vmap.points, velocity, output_file); } void update_values() { - if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) - return; - - lane_vmap = lane_planner::vmap::create_lane_vmap(all_vmap, lane_planner::vmap::LNO_ALL); - coarse_vmap.points.clear(); - coarse_vmap.points.shrink_to_fit(); - - lane_planner::vmap::publish_delete_marker(marker_pub, waypoint_marker); - lane_planner::vmap::publish_delete_marker(marker_pub, branching_marker); - lane_planner::vmap::publish_delete_marker(marker_pub, merging_marker); - lane_planner::vmap::publish_delete_marker(marker_pub, selection_marker); - lane_planner::vmap::publish_delete_marker(marker_pub, route_marker); - - lane_planner::vmap::publish_add_marker(marker_pub, waypoint_marker, lane_vmap.points); - lane_planner::vmap::publish_add_marker(marker_pub, branching_marker, - lane_planner::vmap::create_branching_points(lane_vmap)); - lane_planner::vmap::publish_add_marker(marker_pub, merging_marker, - lane_planner::vmap::create_merging_points(lane_vmap)); + if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) + return; + + lane_vmap = lane_planner::vmap::create_lane_vmap(all_vmap, lane_planner::vmap::LNO_ALL); + coarse_vmap.points.clear(); + coarse_vmap.points.shrink_to_fit(); + + lane_planner::vmap::publish_delete_marker(marker_pub, waypoint_marker); + lane_planner::vmap::publish_delete_marker(marker_pub, branching_marker); + lane_planner::vmap::publish_delete_marker(marker_pub, merging_marker); + lane_planner::vmap::publish_delete_marker(marker_pub, selection_marker); + lane_planner::vmap::publish_delete_marker(marker_pub, route_marker); + + lane_planner::vmap::publish_add_marker(marker_pub, waypoint_marker, lane_vmap.points); + lane_planner::vmap::publish_add_marker(marker_pub, branching_marker, + lane_planner::vmap::create_branching_points(lane_vmap)); + lane_planner::vmap::publish_add_marker(marker_pub, merging_marker, + lane_planner::vmap::create_merging_points(lane_vmap)); } void cache_point(const vector_map::PointArray& msg) { - all_vmap.points = msg.data; - update_values(); + all_vmap.points = msg.data; + update_values(); } void cache_lane(const vector_map::LaneArray& msg) { - all_vmap.lanes = msg.data; - update_values(); + all_vmap.lanes = msg.data; + update_values(); } void cache_node(const vector_map::NodeArray& msg) { - all_vmap.nodes = msg.data; - update_values(); + all_vmap.nodes = msg.data; + update_values(); } } // namespace int main(int argc, char **argv) { - ros::init(argc, argv, "waypoint_clicker"); - - ros::NodeHandle n; - - int sub_vmap_queue_size; - n.param("/waypoint_clicker/sub_vmap_queue_size", sub_vmap_queue_size, 1); - int sub_pose_queue_size; - n.param("/waypoint_clicker/sub_pose_queue_size", sub_pose_queue_size, 1); - int pub_marker_queue_size; - n.param("/waypoint_clicker/pub_marker_queue_size", pub_marker_queue_size, 10); - bool pub_marker_latch; - n.param("/waypoint_clicker/pub_marker_latch", pub_marker_latch, true); - - n.param("/waypoint_clicker/waypoint_max", waypoint_max, 10000); - n.param("/waypoint_clicker/search_radius", search_radius, 10); - n.param("/waypoint_clicker/velocity", velocity, 40); - n.param("/waypoint_clicker/frame_id", frame_id, "map"); - n.param("/waypoint_clicker/output_file", output_file, "/tmp/lane_waypoint.csv"); - - if (output_file.empty()) { - ROS_ERROR_STREAM("output filename is empty"); - return EXIT_FAILURE; - } - if (output_file.back() == '/') { - ROS_ERROR_STREAM(output_file << " is directory"); - return EXIT_FAILURE; - } - - waypoint_marker.header.frame_id = frame_id; - waypoint_marker.ns = "waypoint"; - waypoint_marker.id = 0; - waypoint_marker.type = visualization_msgs::Marker::SPHERE_LIST; - waypoint_marker.scale.x = 0.2; - waypoint_marker.scale.y = 0.2; - waypoint_marker.color.r = 1; - waypoint_marker.color.g = 1; - waypoint_marker.color.b = 0; - waypoint_marker.color.a = 1; - waypoint_marker.frame_locked = true; - - branching_marker.header.frame_id = frame_id; - branching_marker.ns = "branching"; - branching_marker.id = 0; - branching_marker.type = visualization_msgs::Marker::SPHERE_LIST; - branching_marker.scale.x = 0.3; - branching_marker.scale.y = 0.3; - branching_marker.color.r = 0; - branching_marker.color.g = 1; - branching_marker.color.b = 0; - branching_marker.color.a = 1; - branching_marker.frame_locked = true; - - merging_marker.header.frame_id = frame_id; - merging_marker.ns = "merging"; - merging_marker.id = 0; - merging_marker.type = visualization_msgs::Marker::SPHERE_LIST; - merging_marker.scale.x = 0.3; - merging_marker.scale.y = 0.3; - merging_marker.color.r = 1; - merging_marker.color.g = 0; - merging_marker.color.b = 0; - merging_marker.color.a = 1; - merging_marker.frame_locked = true; - - selection_marker.header.frame_id = frame_id; - selection_marker.ns = "selection"; - selection_marker.id = 0; - selection_marker.type = visualization_msgs::Marker::SPHERE_LIST; - selection_marker.scale.x = 0.4; - selection_marker.scale.y = 0.4; - selection_marker.color.r = 1; - selection_marker.color.g = 1; - selection_marker.color.b = 0; - selection_marker.color.a = 1; - selection_marker.frame_locked = true; - - route_marker.header.frame_id = frame_id; - route_marker.ns = "route"; - route_marker.id = 0; - route_marker.type = visualization_msgs::Marker::LINE_STRIP; - route_marker.scale.x = 0.2; - route_marker.scale.y = 0.2; - route_marker.color.r = 1; - route_marker.color.g = 1; - route_marker.color.b = 0; - route_marker.color.a = 1; - route_marker.frame_locked = true; - - marker_pub = n.advertise("/waypoint_guide", pub_marker_queue_size, - pub_marker_latch); - - tf::TransformListener listener; - try { - ros::Time zero = ros::Time(0); - listener.waitForTransform("map", "world", zero, ros::Duration(10)); - listener.lookupTransform("map", "world", zero, transform); - } catch (tf::TransformException &ex) { - ROS_ERROR_STREAM(ex.what()); - } - - ros::Subscriber pose_sub = n.subscribe("/clicked_point", sub_pose_queue_size, create_route); - ros::Subscriber point_sub = n.subscribe("/vector_map_info/point", sub_vmap_queue_size, cache_point); - ros::Subscriber lane_sub = n.subscribe("/vector_map_info/lane", sub_vmap_queue_size, cache_lane); - ros::Subscriber node_sub = n.subscribe("/vector_map_info/node", sub_vmap_queue_size, cache_node); - - ros::spin(); - - return EXIT_SUCCESS; + ros::init(argc, argv, "waypoint_clicker"); + + ros::NodeHandle n; + + int sub_vmap_queue_size; + n.param("/waypoint_clicker/sub_vmap_queue_size", sub_vmap_queue_size, 1); + int sub_pose_queue_size; + n.param("/waypoint_clicker/sub_pose_queue_size", sub_pose_queue_size, 1); + int pub_marker_queue_size; + n.param("/waypoint_clicker/pub_marker_queue_size", pub_marker_queue_size, 10); + bool pub_marker_latch; + n.param("/waypoint_clicker/pub_marker_latch", pub_marker_latch, true); + + n.param("/waypoint_clicker/waypoint_max", waypoint_max, 10000); + n.param("/waypoint_clicker/search_radius", search_radius, 10); + n.param("/waypoint_clicker/velocity", velocity, 40); + n.param("/waypoint_clicker/frame_id", frame_id, "map"); + n.param("/waypoint_clicker/output_file", output_file, "/tmp/lane_waypoint.csv"); + + if (output_file.empty()) { + ROS_ERROR_STREAM("output filename is empty"); + return EXIT_FAILURE; + } + if (output_file.back() == '/') { + ROS_ERROR_STREAM(output_file << " is directory"); + return EXIT_FAILURE; + } + + waypoint_marker.header.frame_id = frame_id; + waypoint_marker.ns = "waypoint"; + waypoint_marker.id = 0; + waypoint_marker.type = visualization_msgs::Marker::SPHERE_LIST; + waypoint_marker.scale.x = 0.2; + waypoint_marker.scale.y = 0.2; + waypoint_marker.color.r = 1; + waypoint_marker.color.g = 1; + waypoint_marker.color.b = 0; + waypoint_marker.color.a = 1; + waypoint_marker.frame_locked = true; + + branching_marker.header.frame_id = frame_id; + branching_marker.ns = "branching"; + branching_marker.id = 0; + branching_marker.type = visualization_msgs::Marker::SPHERE_LIST; + branching_marker.scale.x = 0.3; + branching_marker.scale.y = 0.3; + branching_marker.color.r = 0; + branching_marker.color.g = 1; + branching_marker.color.b = 0; + branching_marker.color.a = 1; + branching_marker.frame_locked = true; + + merging_marker.header.frame_id = frame_id; + merging_marker.ns = "merging"; + merging_marker.id = 0; + merging_marker.type = visualization_msgs::Marker::SPHERE_LIST; + merging_marker.scale.x = 0.3; + merging_marker.scale.y = 0.3; + merging_marker.color.r = 1; + merging_marker.color.g = 0; + merging_marker.color.b = 0; + merging_marker.color.a = 1; + merging_marker.frame_locked = true; + + selection_marker.header.frame_id = frame_id; + selection_marker.ns = "selection"; + selection_marker.id = 0; + selection_marker.type = visualization_msgs::Marker::SPHERE_LIST; + selection_marker.scale.x = 0.4; + selection_marker.scale.y = 0.4; + selection_marker.color.r = 1; + selection_marker.color.g = 1; + selection_marker.color.b = 0; + selection_marker.color.a = 1; + selection_marker.frame_locked = true; + + route_marker.header.frame_id = frame_id; + route_marker.ns = "route"; + route_marker.id = 0; + route_marker.type = visualization_msgs::Marker::LINE_STRIP; + route_marker.scale.x = 0.2; + route_marker.scale.y = 0.2; + route_marker.color.r = 1; + route_marker.color.g = 1; + route_marker.color.b = 0; + route_marker.color.a = 1; + route_marker.frame_locked = true; + + marker_pub = n.advertise("/waypoint_guide", pub_marker_queue_size, + pub_marker_latch); + + tf::TransformListener listener; + try { + ros::Time zero = ros::Time(0); + listener.waitForTransform("map", "world", zero, ros::Duration(10)); + listener.lookupTransform("map", "world", zero, transform); + } catch (tf::TransformException &ex) { + ROS_ERROR_STREAM(ex.what()); + } + + ros::Subscriber pose_sub = n.subscribe("/clicked_point", sub_pose_queue_size, create_route); + ros::Subscriber point_sub = n.subscribe("/vector_map_info/point", sub_vmap_queue_size, cache_point); + ros::Subscriber lane_sub = n.subscribe("/vector_map_info/lane", sub_vmap_queue_size, cache_lane); + ros::Subscriber node_sub = n.subscribe("/vector_map_info/node", sub_vmap_queue_size, cache_node); + + ros::spin(); + + return EXIT_SUCCESS; } diff --git a/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.cpp b/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.cpp index d52739ef6fe..1358c8c0e71 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.cpp +++ b/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.cpp @@ -14,13 +14,6 @@ * limitations under the License. */ -/* - * Modifications: - * - Modified waypoint_loader node to allow reloading a new route csv file using the file path provided by the rostopic - * - 6/24/2019 - * - Shuwei Qiang - */ - #include "waypoint_loader_core.h" namespace waypoint_maker @@ -41,8 +34,6 @@ void WaypointLoaderNode::initPubSub() private_nh_.param("multi_lane_csv", multi_lane_csv_, "/tmp/driving_lane.csv"); // setup publisher lane_pub_ = nh_.advertise("/based/lane_waypoints_raw", 10, true); - // setup subscriber - route_selection_sub_ = nh_.subscribe("selected_route_path", 1, &WaypointLoaderNode::routeSelectionCb, this); } void WaypointLoaderNode::run() @@ -289,17 +280,6 @@ bool WaypointLoaderNode::verifyFileConsistency(const char* filename) return true; } -void WaypointLoaderNode::routeSelectionCb(const std_msgs::String::ConstPtr& msg) -{ - multi_lane_csv_ = msg->data.c_str(); - multi_file_path_.clear(); - parseColumns(multi_lane_csv_, &multi_file_path_); - autoware_msgs::LaneArray lane_array; - createLaneArray(multi_file_path_, &lane_array); - lane_pub_.publish(lane_array); - output_lane_array_ = lane_array; -} - void parseColumns(const std::string& line, std::vector* columns) { std::istringstream ss(line); diff --git a/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.h b/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.h index 07e67a65be8..ebf945367e4 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.h +++ b/core_planning/waypoint_maker/nodes/waypoint_loader/waypoint_loader_core.h @@ -25,7 +25,6 @@ #include #include #include -#include #include #include @@ -70,7 +69,6 @@ class WaypointLoaderNode // publisher & subscriber ros::Publisher lane_pub_; ros::Subscriber config_sub_; - ros::Subscriber route_selection_sub_; // variables std::string multi_lane_csv_; @@ -93,9 +91,6 @@ class WaypointLoaderNode void loadWaypointsForVer3(const char* filename, std::vector* wps); void parseWaypointForVer3(const std::string& line, const std::vector& contents, autoware_msgs::Waypoint* wp); - - // callback for setting waypoint file path - void routeSelectionCb(const std_msgs::String::ConstPtr& msg); }; const std::string addFileSuffix(std::string file_path, std::string suffix); diff --git a/core_planning/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp b/core_planning/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp index fbabd6e0e9e..3d2c94a015d 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp +++ b/core_planning/waypoint_maker/nodes/waypoint_marker_publisher/waypoint_marker_publisher.cpp @@ -14,20 +14,21 @@ * limitations under the License. */ -#include #include -#include +#include #include #include +#include +#include #include -#include #include +#include -#include "libwaypoint_follower/libwaypoint_follower.h" -#include "autoware_msgs/LaneArray.h" #include "autoware_config_msgs/ConfigLaneStop.h" +#include "autoware_msgs/LaneArray.h" #include "autoware_msgs/TrafficLight.h" +#include "libwaypoint_follower/libwaypoint_follower.h" namespace { @@ -70,7 +71,8 @@ void setLifetime(double sec, visualization_msgs::MarkerArray* marker_array) } } -void publishMarkerArray(const visualization_msgs::MarkerArray& marker_array, const ros::Publisher& publisher, bool delete_markers=false) +void publishMarkerArray(const visualization_msgs::MarkerArray& marker_array, const ros::Publisher& publisher, + bool delete_markers = false) { visualization_msgs::MarkerArray msg; @@ -88,8 +90,6 @@ void publishMarkerArray(const visualization_msgs::MarkerArray& marker_array, con publisher.publish(msg); } - - void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray& lane_waypoints_array) { visualization_msgs::MarkerArray tmp_marker_array; @@ -107,7 +107,7 @@ void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray& lane_wa velocity_marker.frame_locked = true; int count = 1; - for (auto lane : lane_waypoints_array.lanes) + for (const auto& lane : lane_waypoints_array.lanes) { velocity_marker.ns = "global_velocity_lane_" + std::to_string(count); for (int i = 0; i < static_cast(lane.waypoints.size()); i++) @@ -148,7 +148,7 @@ void createGlobalLaneArrayChangeFlagMarker(const autoware_msgs::LaneArray& lane_ marker.frame_locked = true; int count = 1; - for (auto lane : lane_waypoints_array.lanes) + for (const auto& lane : lane_waypoints_array.lanes) { marker.ns = "global_change_flag_lane_" + std::to_string(count); for (int i = 0; i < static_cast(lane.waypoints.size()); i++) @@ -233,12 +233,12 @@ void createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, const autoware_msgs: lane_waypoint_marker.frame_locked = true; int count = 0; - for (auto lane : lane_waypoints_array.lanes) + for (const auto& lane : lane_waypoints_array.lanes) { lane_waypoint_marker.points.clear(); lane_waypoint_marker.id = count; - for (auto el : lane.waypoints) + for (const auto& el : lane.waypoints) { geometry_msgs::Point point; point = el.pose.pose.position; @@ -265,7 +265,7 @@ void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray& lane lane_waypoint_marker.frame_locked = true; int count = 1; - for (auto lane : lane_waypoints_array.lanes) + for (const auto& lane : lane_waypoints_array.lanes) { lane_waypoint_marker.ns = "global_lane_waypoint_orientation_marker_" + std::to_string(count); @@ -282,6 +282,63 @@ void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray& lane tmp_marker_array.markers.end()); } +void createGlobalLaneArrayTurnMarker(const autoware_msgs::LaneArray& lane_waypoints_array) +{ + visualization_msgs::MarkerArray tmp_marker_array; + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time::now(); + lane_waypoint_marker.type = visualization_msgs::Marker::ARROW; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.25; + lane_waypoint_marker.scale.y = 0.05; + lane_waypoint_marker.scale.z = 0.05; + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.a = 1.0; + lane_waypoint_marker.frame_locked = true; + + int count = 1; + for (const auto& lane : lane_waypoints_array.lanes) + { + lane_waypoint_marker.ns = "global_lane_waypoint_turn_marker_" + std::to_string(count); + + for (int i = 0; i < static_cast(lane.waypoints.size()); i++) + { + uint8_t steering_state = lane.waypoints[i].wpstate.steering_state; + + if (steering_state == autoware_msgs::WaypointState::STR_LEFT || + steering_state == autoware_msgs::WaypointState::STR_RIGHT) + { + lane_waypoint_marker.id = i; + lane_waypoint_marker.pose = lane.waypoints[i].pose.pose; + + tf2::Quaternion directional_offset(0, 0, 0); + tf2::Quaternion wp_orientation; + tf2::convert(lane_waypoint_marker.pose.orientation, wp_orientation); + + if (steering_state == autoware_msgs::WaypointState::STR_LEFT) + { + directional_offset.setRPY(0, 0, M_PI / 2); + } + else if (steering_state == autoware_msgs::WaypointState::STR_RIGHT) + { + directional_offset.setRPY(0, 0, -M_PI / 2); + } + wp_orientation *= directional_offset; + wp_orientation.normalize(); + + tf2::convert(wp_orientation, lane_waypoint_marker.pose.orientation); + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + } + count++; + } + + g_global_marker_array.markers.insert(g_global_marker_array.markers.end(), tmp_marker_array.markers.begin(), + tmp_marker_array.markers.end()); +} + void createLocalPathMarker(std_msgs::ColorRGBA color, const autoware_msgs::Lane& lane_waypoint) { visualization_msgs::Marker lane_waypoint_marker; @@ -389,6 +446,7 @@ void laneArrayCallback(const autoware_msgs::LaneArrayConstPtr& msg) createGlobalLaneArrayVelocityMarker(*msg); createGlobalLaneArrayOrientationMarker(*msg); createGlobalLaneArrayChangeFlagMarker(*msg); + createGlobalLaneArrayTurnMarker(*msg); publishMarkerArray(g_global_marker_array, g_global_mark_pub); } @@ -407,7 +465,7 @@ void closestCallback(const std_msgs::Int32ConstPtr& msg) { _closest_waypoint = msg->data; } -} +} // namespace int main(int argc, char** argv) { diff --git a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.cpp b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.cpp index 9f3a674d14d..6bd877dffc9 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.cpp +++ b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.cpp @@ -29,8 +29,6 @@ WaypointReplanner::~WaypointReplanner() void WaypointReplanner::updateConfig(const WaypointReplannerConfig& config) { config_ = config; - config_.radius_inf = 10 * config_.radius_thresh; - config_.velocity_param = calcVelParam(config_.velocity_max); } void WaypointReplanner::initParameter(const autoware_config_msgs::ConfigWaypointReplanner::ConstPtr& conf) @@ -41,17 +39,13 @@ void WaypointReplanner::initParameter(const autoware_config_msgs::ConfigWaypoint temp_config.velocity_min = kmph2mps(conf->velocity_min); temp_config.accel_limit = conf->accel_limit; temp_config.decel_limit = conf->decel_limit; - temp_config.radius_thresh = conf->radius_thresh; + temp_config.lateral_accel_limit = conf->lateral_accel_limit; temp_config.radius_min = conf->radius_min; temp_config.lookup_crv_width = 5; temp_config.resample_mode = conf->resample_mode; temp_config.resample_interval = conf->resample_interval; temp_config.replan_curve_mode = conf->replan_curve_mode; temp_config.replan_endpoint_mode = conf->replan_endpoint_mode; - temp_config.overwrite_vmax_mode = conf->overwrite_vmax_mode; - temp_config.velocity_offset = conf->velocity_offset; - temp_config.end_point_offset = conf->end_point_offset; - temp_config.braking_distance = conf->braking_distance; updateConfig(temp_config); } @@ -74,41 +68,38 @@ void WaypointReplanner::replanLaneWaypointVel(autoware_msgs::Lane& lane) const LaneDirection dir = getLaneDirection(lane); unsigned long last = lane.waypoints.size() - 1; changeVelSign(lane, true); - limitVelocityByRange(0, last, 0, config_.velocity_max, lane); + limitVelocityByRange(0, last, config_.velocity_max, lane); if (config_.resample_mode) { resampleLaneWaypoint(config_.resample_interval, lane, dir); last = lane.waypoints.size() - 1; } + + // set velocity based on curvature at each waypoint if (config_.replan_curve_mode) { std::vector curve_radius; - KeyVal curve_list; createRadiusList(lane, curve_radius); - createCurveList(curve_radius, curve_list); - if (config_.overwrite_vmax_mode) - {// set velocity_max for all_point - setVelocityByRange(0, last, 0, config_.velocity_max, lane); - } - // set velocity by curve - for (const auto& el : curve_list) + setVelocityByRange(0, last, config_.velocity_max, lane); + for (unsigned long i = 0; i < curve_radius.size(); i++) { - const double& radius = el.second.second; - double vmin = config_.velocity_max - config_.velocity_param * (config_.radius_thresh - radius); - vmin = (vmin < config_.velocity_min) ? config_.velocity_min : vmin; - limitVelocityByRange(el.first, el.second.first, config_.velocity_offset, vmin, lane); + lane.waypoints[i].twist.twist.linear.x = std::fmin(lane.waypoints[i].twist.twist.linear.x, + std::sqrt(config_.lateral_accel_limit * std::fmax(curve_radius[i], config_.radius_min))); } + limitVelocityByRange(0, last, config_.velocity_max, lane); } - // set velocity on start & end of lane + + // set velocity at end of the lane if (config_.replan_endpoint_mode) { - const unsigned long zerospeed_start = last - config_.end_point_offset; - const unsigned long lowspeed_start = zerospeed_start - config_.braking_distance; - raiseVelocityByRange(0, last, 0, config_.velocity_min, lane); - limitVelocityByRange(0, 0, 0, config_.velocity_min, lane); - limitVelocityByRange(lowspeed_start, last, 0, config_.velocity_min, lane); - setVelocityByRange(zerospeed_start, last, 0, 0.0, lane); + // set last waypoint speed to zero + setVelocityByRange(last - 1, last, 0.0, lane); + // set minimum speed for each waypoint except for the last waypoint. + raiseVelocityByRange(0, last - 1, config_.velocity_min, lane); + // smooth it out again + limitVelocityByRange(0, last, config_.velocity_max, lane); } + if (dir == LaneDirection::Backward) { changeVelSign(lane, false); @@ -257,12 +248,14 @@ const CbufGPoint WaypointReplanner::getCrvPoints(const autoware_msgs::Lane& lane void WaypointReplanner::createRadiusList(const autoware_msgs::Lane& lane, std::vector& curve_radius) { + static constexpr double radius_inf = 5.0e2; + if (lane.waypoints.empty()) { return; } curve_radius.resize(lane.waypoints.size()); - curve_radius.at(0) = curve_radius.back() = config_.radius_inf; + curve_radius.at(0) = curve_radius.back() = radius_inf; for (unsigned long i = 1; i < lane.waypoints.size() - 1; i++) { @@ -272,71 +265,23 @@ void WaypointReplanner::createRadiusList(const autoware_msgs::Lane& lane, std::v // if going straight if (curve_param.empty()) { - curve_radius.at(i) = config_.radius_inf; + curve_radius.at(i) = radius_inf; } // else if turnning curve else { - curve_radius.at(i) = (curve_param[2] > config_.radius_inf) ? config_.radius_inf : curve_param[2]; + curve_radius.at(i) = (curve_param[2] > radius_inf) ? radius_inf : curve_param[2]; } } } -const double WaypointReplanner::calcVelParam(double vmax) const -{ - if (fabs(config_.radius_thresh - config_.radius_min) < 1e-8) - { - return DBL_MAX; // error - } - return (vmax - config_.velocity_min) / (config_.radius_thresh - config_.radius_min); -} - -void WaypointReplanner::createCurveList(const std::vector& curve_radius, KeyVal& curve_list) -{ - unsigned long index = 0; - bool on_curve = false; - double radius_localmin = DBL_MAX; - for (unsigned long i = 1; i < curve_radius.size(); i++) - { - if (!on_curve && curve_radius[i] <= config_.radius_thresh && curve_radius[i - 1] > config_.radius_thresh) - { - index = i; - on_curve = true; - } - else if (on_curve && curve_radius[i - 1] <= config_.radius_thresh && curve_radius[i] > config_.radius_thresh) - { - on_curve = false; - if (radius_localmin < config_.radius_min) - { - radius_localmin = config_.radius_min; - } - curve_list[index] = std::make_pair(i, radius_localmin); - radius_localmin = DBL_MAX; - } - if (!on_curve) - { - continue; - } - if (radius_localmin > curve_radius[i]) - { - radius_localmin = curve_radius[i]; - } - } -} - - -void WaypointReplanner::setVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, +void WaypointReplanner::setVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vel, autoware_msgs::Lane& lane) { if (lane.waypoints.empty()) { return; } - if (offset > 0) - { - start_idx = (start_idx > offset) ? (start_idx - offset) : 0; - end_idx = (end_idx > offset) ? (end_idx - offset) : 0; - } end_idx = (end_idx >= lane.waypoints.size()) ? lane.waypoints.size() - 1 : end_idx; for (unsigned long idx = start_idx; idx <= end_idx; idx++) { @@ -344,18 +289,13 @@ void WaypointReplanner::setVelocityByRange(unsigned long start_idx, unsigned lon } } -void WaypointReplanner::raiseVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, +void WaypointReplanner::raiseVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vmin, autoware_msgs::Lane& lane) { if (lane.waypoints.empty()) { return; } - if (offset > 0) - { - start_idx = (start_idx > offset) ? (start_idx - offset) : 0; - end_idx = (end_idx > offset) ? (end_idx - offset) : 0; - } end_idx = (end_idx >= lane.waypoints.size()) ? lane.waypoints.size() - 1 : end_idx; for (unsigned long idx = start_idx; idx <= end_idx; idx++) { @@ -367,18 +307,13 @@ void WaypointReplanner::raiseVelocityByRange(unsigned long start_idx, unsigned l } } -void WaypointReplanner::limitVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, +void WaypointReplanner::limitVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vmin, autoware_msgs::Lane& lane) { if (lane.waypoints.empty()) { return; } - if (offset > 0) - { - start_idx = (start_idx > offset) ? (start_idx - offset) : 0; - end_idx = (end_idx > offset) ? (end_idx - offset) : 0; - } end_idx = (end_idx >= lane.waypoints.size()) ? lane.waypoints.size() - 1 : end_idx; for (unsigned long idx = start_idx; idx <= end_idx; idx++) { @@ -406,11 +341,10 @@ void WaypointReplanner::limitAccelDecel(const unsigned long idx, autoware_msgs:: const geometry_msgs::Point& p0 = lane.waypoints[next - sgn[j]].pose.pose.position; const geometry_msgs::Point& p1 = lane.waypoints[next].pose.pose.position; const double dist = std::hypot(p0.x - p1.x, p0.y - p1.y); + // maximum speed based on max_accel_limit or max_decel_limit v = sqrt(2 * acc[j] * dist + v * v); - if (v > config_.velocity_max || v > lane.waypoints[next].twist.twist.linear.x) - { - break; - } + // cap it in case it is larger than the current velocity or velocity_max. + v = std::min({v, lane.waypoints[next].twist.twist.linear.x, config_.velocity_max}); lane.waypoints[next].twist.twist.linear.x = v; } } diff --git a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.h b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.h index 39102c9438f..9792d40cb44 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.h +++ b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner.h @@ -35,20 +35,15 @@ struct WaypointReplannerConfig { double velocity_max = 0.0; double velocity_min = 0.0; - double velocity_param = 0.0; double accel_limit = 0.0; double decel_limit = 0.0; - double radius_thresh = 0.0; + double lateral_accel_limit = 0.0; double radius_min = 0.0; - double radius_inf = 0.0; bool resample_mode = false; double resample_interval = 0.0; bool replan_curve_mode = false; bool replan_endpoint_mode = false; - bool overwrite_vmax_mode = false; - double velocity_offset = 0.0; - double end_point_offset = 0.0; - double braking_distance = 0.0; + // The number of consective waypoints used to compute the local radius. int lookup_crv_width = 5; }; @@ -64,7 +59,7 @@ class WaypointReplanner void initParameter(const autoware_config_msgs::ConfigWaypointReplanner::ConstPtr& conf); void replanLaneWaypointVel(autoware_msgs::Lane& lane); -protected: +private: void changeVelSign(autoware_msgs::Lane& lane, bool positive) const; void resampleLaneWaypoint(const double resample_interval, autoware_msgs::Lane& lane, LaneDirection dir); void resampleOnStraight(const CbufGPoint& curve_point, autoware_msgs::Lane& lane, LaneDirection dir); @@ -76,19 +71,10 @@ class WaypointReplanner const CbufGPoint getCrvPoints(const autoware_msgs::Lane& lane, unsigned long index) const; void createRadiusList(const autoware_msgs::Lane& lane, std::vector& curve_radius); - const double calcVelParam(double vmax) const; - void createCurveList(const std::vector& curve_radius, KeyVal& curve_list); - void createVmaxList(const autoware_msgs::Lane& lane, const KeyVal &curve_list, - unsigned long offset, KeyVal &vmax_list); - double searchVmaxByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, - const autoware_msgs::Lane &lane) const; - void setVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, double vel, - autoware_msgs::Lane& lane); - void raiseVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, - double vmin, autoware_msgs::Lane& lane); + void setVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vel, autoware_msgs::Lane& lane); + void raiseVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vmin, autoware_msgs::Lane& lane); - void limitVelocityByRange(unsigned long start_idx, unsigned long end_idx, unsigned int offset, double vmin, - autoware_msgs::Lane& lane); + void limitVelocityByRange(unsigned long start_idx, unsigned long end_idx, double vmin, autoware_msgs::Lane& lane); void limitAccelDecel(const unsigned long idx, autoware_msgs::Lane& lane); const std::vector calcCurveParam(CbufGPoint point) const; diff --git a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner_node.cpp b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner_node.cpp index 8b5821223fb..f601a0f9e59 100644 --- a/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner_node.cpp +++ b/core_planning/waypoint_maker/nodes/waypoint_replanner/waypoint_replanner_node.cpp @@ -52,16 +52,12 @@ WaypointReplannerNode::WaypointReplannerNode() : pnh_("~"), is_first_publish_(tr pnh_.param("velocity_min", velocity_min_kph, 0.0); pnh_.param("accel_limit", temp_config.accel_limit, 0.0); pnh_.param("decel_limit", temp_config.decel_limit, 0.0); - pnh_.param("radius_thresh", temp_config.radius_thresh, 0.0); + pnh_.param("lateral_accel_limit", temp_config.lateral_accel_limit, 0.0); pnh_.param("radius_min", temp_config.radius_min, 0.0); pnh_.param("resample_mode", temp_config.resample_mode, false); pnh_.param("resample_interval", temp_config.resample_interval, 0.0); pnh_.param("replan_curve_mode", temp_config.replan_curve_mode, false); pnh_.param("replan_endpoint_mode", temp_config.replan_endpoint_mode, false); - pnh_.param("overwrite_vmax_mode", temp_config.overwrite_vmax_mode, false); - pnh_.param("velocity_offset", temp_config.velocity_offset, 0.0); - pnh_.param("end_point_offset", temp_config.end_point_offset, 0.0); - pnh_.param("braking_distance", temp_config.braking_distance, 0.0); pnh_.param("use_decision_maker", use_decision_maker_, false); temp_config.velocity_max = kmph2mps(velocity_max_kph); diff --git a/core_planning/waypoint_maker/package.xml b/core_planning/waypoint_maker/package.xml index db7dc1d24b6..359c0333a7d 100644 --- a/core_planning/waypoint_maker/package.xml +++ b/core_planning/waypoint_maker/package.xml @@ -9,15 +9,17 @@ autoware_build_flags catkin + amathutils_lib + autoware_config_msgs autoware_msgs geometry_msgs gnss lane_planner + libwaypoint_follower nav_msgs roscpp std_msgs + tablet_socket_msgs tf vector_map - libwaypoint_follower - amathutils_lib diff --git a/core_planning/waypoint_planner/CMakeLists.txt b/core_planning/waypoint_planner/CMakeLists.txt index 07e79be3182..7e5790b600a 100644 --- a/core_planning/waypoint_planner/CMakeLists.txt +++ b/core_planning/waypoint_planner/CMakeLists.txt @@ -16,25 +16,14 @@ find_package( pcl_conversions pcl_ros roscpp - std_msgs - tf - vector_map roslint -) - -catkin_package( - CATKIN_DEPENDS - astar_search - autoware_config_msgs - autoware_health_checker - autoware_msgs - lanelet2_extension - libwaypoint_follower std_msgs tf vector_map ) +catkin_package() + # TODO add all codes to roslint roslint_cpp(src/velocity_set_lanelet2/velocity_set_lanelet2.cpp) diff --git a/core_planning/waypoint_planner/include/waypoint_planner/astar_avoid/astar_avoid.h b/core_planning/waypoint_planner/include/waypoint_planner/astar_avoid/astar_avoid.h index e6d8fbba2af..cef20b730af 100644 --- a/core_planning/waypoint_planner/include/waypoint_planner/astar_avoid/astar_avoid.h +++ b/core_planning/waypoint_planner/include/waypoint_planner/astar_avoid/astar_avoid.h @@ -46,7 +46,7 @@ class AstarAvoid } State; AstarAvoid(); - ~AstarAvoid(); + ~AstarAvoid() = default; void run(); private: @@ -61,6 +61,7 @@ class AstarAvoid ros::Subscriber obstacle_waypoint_sub_; ros::Subscriber state_sub_; ros::Rate *rate_; + ros::Timer timer_; tf::TransformListener tf_listener_; // params @@ -79,30 +80,30 @@ class AstarAvoid AstarSearch astar_; State state_; - // threads - std::thread publish_thread_; - std::mutex mutex_; - // variables - bool terminate_thread_; bool found_avoid_path_; - int closest_waypoint_index_; - int obstacle_waypoint_index_; - int closest_local_index_; + + // Index of the closest waypoint in the current_waypoints_ Lane. + // Not the same as the waypoint gid. This value can change suddenly if the + // current_waypoints_ switches between base_waypoints_ and avoid_waypoints_. + int closest_waypoint_index_ = -1; + + // Index of the obstacle relative to closest_waypoint_index_. + int obstacle_waypoint_index_ = -1; nav_msgs::OccupancyGrid costmap_; autoware_msgs::Lane base_waypoints_; autoware_msgs::Lane avoid_waypoints_; - autoware_msgs::Lane safety_waypoints_; + autoware_msgs::Lane current_waypoints_; geometry_msgs::PoseStamped current_pose_local_, current_pose_global_; geometry_msgs::PoseStamped goal_pose_local_, goal_pose_global_; geometry_msgs::TwistStamped current_velocity_; tf::Transform local2costmap_; // local frame (e.g. velodyne) -> costmap origin - bool costmap_initialized_; - bool current_pose_initialized_; - bool current_velocity_initialized_; - bool base_waypoints_initialized_; - bool closest_waypoint_initialized_; + bool costmap_initialized_ = false; + bool current_pose_initialized_ = false; + bool current_velocity_initialized_ = false; + bool base_waypoints_initialized_ = false; + bool closest_waypoint_initialized_ = false; // functions, callback void costmapCallback(const nav_msgs::OccupancyGrid& msg); @@ -116,9 +117,12 @@ class AstarAvoid bool checkInitialized(); bool planAvoidWaypoints(int& end_of_avoid_index); void mergeAvoidWaypoints(const nav_msgs::Path& path, int& end_of_avoid_index); - void publishWaypoints(); tf::Transform getTransform(const std::string& from, const std::string& to); - int getLocalClosestWaypoint(const autoware_msgs::Lane& waypoints, const geometry_msgs::Pose& pose, const int& search_size); + + // Find closest waypoint index within a search_size around the previous closest waypoint + void updateClosestWaypoint(const autoware_msgs::Lane& waypoints, const geometry_msgs::Pose& pose, const int& search_size); + // publish safety waypoints using a timer + void publishWaypoints(const ros::TimerEvent& e); }; #endif diff --git a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/libvelocity_set.h b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/libvelocity_set.h index be7689e1d31..dab866e81b9 100644 --- a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/libvelocity_set.h +++ b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/libvelocity_set.h @@ -85,7 +85,7 @@ class CrossWalk { return bdID_; } - CrossWalkPoints getDetectionPoints(const int &id) const + const CrossWalkPoints& getDetectionPoints(const int &id) const { return detection_points_.at(id); } @@ -113,7 +113,7 @@ class CrossWalk void addDetectionCrossWalkIDs(const int &id) { auto itr = std::find(detection_crosswalk_array_.begin(), detection_crosswalk_array_.end(), id); - if (detection_crosswalk_array_.empty() || itr == detection_crosswalk_array_.end()) + if (itr == detection_crosswalk_array_.end()) { detection_crosswalk_array_.push_back(id); } @@ -134,6 +134,7 @@ class CrossWalk CrossWalk() : detection_waypoint_(-1) , detection_crosswalk_id_(-1) + , enable_multiple_crosswalk_detection_(false) , loaded_crosswalk(false) , loaded_area(false) , loaded_line(false) diff --git a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_info.h b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_info.h index b2966494aa2..60842294118 100644 --- a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_info.h +++ b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_info.h @@ -21,6 +21,7 @@ #include #include #include +#include #include @@ -42,13 +43,13 @@ class VelocitySetInfo double deceleration_stopline_; // (m/s^2) deceleration for stopline double velocity_change_limit_; // (m/s) double temporal_waypoints_size_; // (meter) - int wpidx_detectionResultByOtherNodes_; // waypoints index@finalwaypoints + int wpidx_detectionResultByOtherNodes_; // waypoints index@finalwaypoints // ROS param double remove_points_upto_; pcl::PointCloud points_; - geometry_msgs::PoseStamped localizer_pose_; // pose of sensor + geometry_msgs::Pose localizer_pose_; // pose of sensor geometry_msgs::PoseStamped control_pose_; // pose of base_link bool set_pose_; @@ -56,21 +57,21 @@ class VelocitySetInfo public: VelocitySetInfo(); - ~VelocitySetInfo(); + ~VelocitySetInfo() = default; // ROS Callback void configCallback(const autoware_config_msgs::ConfigVelocitySetConstPtr &msg); void pointsCallback(const sensor_msgs::PointCloud2ConstPtr &msg); void controlPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg); - void localizerPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg); void detectionCallback(const std_msgs::Int32 &msg); + void setLocalizerPose(const geometry_msgs::TransformStamped &map_to_lidar_tf); void clearPoints(); int getDetectionResultByOtherNodes() const { - return wpidx_detectionResultByOtherNodes_; + return wpidx_detectionResultByOtherNodes_; } double getStopRange() const @@ -138,7 +139,7 @@ class VelocitySetInfo return control_pose_; } - geometry_msgs::PoseStamped getLocalizerPose() const + const geometry_msgs::Pose& getLocalizerPose() const { return localizer_pose_; } diff --git a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_path.h b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_path.h index 0566553fd9c..a5b14ba68ed 100644 --- a/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_path.h +++ b/core_planning/waypoint_planner/include/waypoint_planner/velocity_set/velocity_set_path.h @@ -23,21 +23,21 @@ class VelocitySetPath { private: - autoware_msgs::Lane prev_waypoints_; - autoware_msgs::Lane new_waypoints_; + autoware_msgs::Lane original_waypoints_; + autoware_msgs::Lane updated_waypoints_; autoware_msgs::Lane temporal_waypoints_; - bool set_path_; - double current_vel_; + bool set_path_{false}; + double current_vel_{0.0}; // ROS param double velocity_offset_; // m/s double decelerate_vel_min_; // m/s - bool checkWaypoint(int num, const char *name) const; + bool checkWaypoint(int num) const; public: VelocitySetPath(); - ~VelocitySetPath(); + ~VelocitySetPath() = default; double calcChangedVelocity(const double& current_vel, const double& accel, const std::array& range) const; void changeWaypointsForStopping(int stop_waypoint, int obstacle_waypoint, int closest_waypoint, double deceleration); @@ -56,12 +56,12 @@ class VelocitySetPath autoware_msgs::Lane getPrevWaypoints() const { - return prev_waypoints_; + return original_waypoints_; } autoware_msgs::Lane getNewWaypoints() const { - return new_waypoints_; + return updated_waypoints_; } autoware_msgs::Lane getTemporalWaypoints() const @@ -81,12 +81,12 @@ class VelocitySetPath int getPrevWaypointsSize() const { - return prev_waypoints_.waypoints.size(); - } + return original_waypoints_.waypoints.size(); + } int getNewWaypointsSize() const { - return new_waypoints_.waypoints.size(); + return updated_waypoints_.waypoints.size(); } }; diff --git a/core_planning/waypoint_planner/launch/velocity_set.launch b/core_planning/waypoint_planner/launch/velocity_set.launch index b1b1a5c013b..3accd61550b 100644 --- a/core_planning/waypoint_planner/launch/velocity_set.launch +++ b/core_planning/waypoint_planner/launch/velocity_set.launch @@ -1,24 +1,32 @@ + + + + - + + + + + diff --git a/core_planning/waypoint_planner/launch/velocity_set_lanelet2.launch b/core_planning/waypoint_planner/launch/velocity_set_lanelet2.launch index 0633c2a7383..84968476f14 100644 --- a/core_planning/waypoint_planner/launch/velocity_set_lanelet2.launch +++ b/core_planning/waypoint_planner/launch/velocity_set_lanelet2.launch @@ -18,7 +18,7 @@ - + diff --git a/core_planning/waypoint_planner/launch/velocity_set_option.launch b/core_planning/waypoint_planner/launch/velocity_set_option.launch index 4b879d39c02..de35225413d 100644 --- a/core_planning/waypoint_planner/launch/velocity_set_option.launch +++ b/core_planning/waypoint_planner/launch/velocity_set_option.launch @@ -21,7 +21,7 @@ - + diff --git a/core_planning/waypoint_planner/src/astar_avoid/astar_avoid.cpp b/core_planning/waypoint_planner/src/astar_avoid/astar_avoid.cpp index b13651c2caa..0d005986cf6 100644 --- a/core_planning/waypoint_planner/src/astar_avoid/astar_avoid.cpp +++ b/core_planning/waypoint_planner/src/astar_avoid/astar_avoid.cpp @@ -19,15 +19,6 @@ AstarAvoid::AstarAvoid() : nh_() , private_nh_("~") - , closest_waypoint_index_(-1) - , obstacle_waypoint_index_(-1) - , closest_local_index_(-1) - , costmap_initialized_(false) - , current_pose_initialized_(false) - , current_velocity_initialized_(false) - , base_waypoints_initialized_(false) - , closest_waypoint_initialized_(false) - , terminate_thread_(false) { private_nh_.param("safety_waypoints_size", safety_waypoints_size_, 100); private_nh_.param("update_rate", update_rate_, 10.0); @@ -51,11 +42,6 @@ AstarAvoid::AstarAvoid() rate_ = new ros::Rate(update_rate_); } -AstarAvoid::~AstarAvoid() -{ - publish_thread_.join(); -} - void AstarAvoid::costmapCallback(const nav_msgs::OccupancyGrid& msg) { costmap_ = msg; @@ -89,38 +75,13 @@ void AstarAvoid::currentVelocityCallback(const geometry_msgs::TwistStamped& msg) void AstarAvoid::baseWaypointsCallback(const autoware_msgs::Lane& msg) { - static autoware_msgs::Lane prev_base_waypoints; base_waypoints_ = msg; - - if (base_waypoints_initialized_) - { - // detect waypoint change by timestamp update - ros::Time t1 = prev_base_waypoints.header.stamp; - ros::Time t2 = base_waypoints_.header.stamp; - if ((t2 - t1).toSec() > 1e-3) - { - ROS_INFO("Receive new /base_waypoints, reset waypoint index."); - closest_local_index_ = -1; // reset local closest waypoint - prev_base_waypoints = base_waypoints_; - } - } - else - { - prev_base_waypoints = base_waypoints_; - } - base_waypoints_initialized_ = true; } void AstarAvoid::closestWaypointCallback(const std_msgs::Int32& msg) { closest_waypoint_index_ = msg.data; - - if (closest_waypoint_index_ == -1) - { - closest_local_index_ = -1; // reset local closest waypoint - } - closest_waypoint_initialized_ = true; } @@ -141,7 +102,6 @@ void AstarAvoid::run() { break; } - ROS_WARN("Waiting for subscribing topics..."); ros::Duration(1.0).sleep(); } @@ -156,8 +116,8 @@ void AstarAvoid::run() // relaying mode at startup state_ = AstarAvoid::STATE::RELAYING; - // start publish thread - publish_thread_ = std::thread(&AstarAvoid::publishWaypoints, this); + // Kick off a timer to publish final waypoints + timer_ = nh_.createTimer(ros::Duration(1.0/update_rate_), &AstarAvoid::publishWaypoints, this); while (ros::ok()) { @@ -209,6 +169,7 @@ void AstarAvoid::run() ROS_INFO("PLANNING -> AVOIDING, Found path"); state_ = AstarAvoid::STATE::AVOIDING; start_avoid_time = ros::WallTime::now(); + closest_waypoint_index_ = -1; } else { @@ -218,11 +179,12 @@ void AstarAvoid::run() } else if (state_ == AstarAvoid::STATE::AVOIDING) { - bool reached = (getLocalClosestWaypoint(avoid_waypoints_, current_pose_global_.pose, closest_search_size_) > end_of_avoid_index); - if (reached) + updateClosestWaypoint(avoid_waypoints_, current_pose_global_.pose, closest_search_size_); + if (closest_waypoint_index_ > end_of_avoid_index) { ROS_INFO("AVOIDING -> RELAYING, Reached goal"); state_ = AstarAvoid::STATE::RELAYING; + closest_waypoint_index_ = -1; } else if (found_obstacle && avoid_velocity) { @@ -237,22 +199,45 @@ void AstarAvoid::run() rate_->sleep(); } - - terminate_thread_ = true; } bool AstarAvoid::checkInitialized() { - bool initialized = false; - // check for relay mode - initialized = (current_pose_initialized_ && closest_waypoint_initialized_ && base_waypoints_initialized_ && - (closest_waypoint_index_ >= 0)); + bool initialized = current_pose_initialized_ && closest_waypoint_initialized_ && base_waypoints_initialized_; + + if (!initialized) + { + if (!current_pose_initialized_) + { + ROS_WARN_THROTTLE(5, "Waiting for current_pose topic ..."); + } + if (!closest_waypoint_initialized_) + { + ROS_WARN_THROTTLE(5, "Waiting for closest_waypoint topic ..."); + } + if (!base_waypoints_initialized_) + { + ROS_WARN_THROTTLE(5, "Waiting for base_waypoints topic ..."); + } + } // check for avoidance mode, additionally if (enable_avoidance_) { - initialized = (initialized && (current_velocity_initialized_ && costmap_initialized_)); + initialized = initialized && current_velocity_initialized_ && costmap_initialized_; + + if (!initialized) + { + if (!current_velocity_initialized_) + { + ROS_WARN_THROTTLE(5, "Waiting for current_velocity topic ..."); + } + if (!costmap_initialized_) + { + ROS_WARN_THROTTLE(5, "Waiting for costmap topic ..."); + } + } } return initialized; @@ -261,13 +246,21 @@ bool AstarAvoid::checkInitialized() bool AstarAvoid::planAvoidWaypoints(int& end_of_avoid_index) { bool found_path = false; - int closest_waypoint_index = getLocalClosestWaypoint(avoid_waypoints_, current_pose_global_.pose, closest_search_size_); + updateClosestWaypoint(avoid_waypoints_, current_pose_global_.pose, closest_search_size_); + + if (closest_waypoint_index_ == -1) + { + return false; + } // update goal pose incrementally and execute A* search for (int i = search_waypoints_delta_; i < static_cast(search_waypoints_size_); i += search_waypoints_delta_) { // update goal index - int goal_waypoint_index = closest_waypoint_index + obstacle_waypoint_index_ + i; + // Note: obstacle_waypoint_index_ is supposed to be relative to closest_waypoint_index_. + // However, obstacle_waypoint_index_ is published by velocity_set node. The astar_avoid and velocity_set + // should be combined together to prevent this kind of inconsistency. + int goal_waypoint_index = closest_waypoint_index_ + obstacle_waypoint_index_ + i; if (goal_waypoint_index >= static_cast(avoid_waypoints_.waypoints.size())) { break; @@ -283,14 +276,10 @@ bool AstarAvoid::planAvoidWaypoints(int& end_of_avoid_index) astar_.initialize(costmap_); // execute astar search - // ros::WallTime start = ros::WallTime::now(); found_path = astar_.makePlan(current_pose_local_.pose, goal_pose_local_.pose); - // ros::WallTime end = ros::WallTime::now(); static ros::Publisher pub = nh_.advertise("debug", 1, true); - // ROS_INFO("Astar planning: %f [s], at index = %d", (end - start).toSec(), goal_waypoint_index); - if (found_path) { pub.publish(astar_.getPath()); @@ -319,12 +308,15 @@ void AstarAvoid::mergeAvoidWaypoints(const nav_msgs::Path& path, int& end_of_avo autoware_msgs::Lane current_waypoints = avoid_waypoints_; // reset - std::lock_guard lock(mutex_); avoid_waypoints_.waypoints.clear(); // add waypoints before start index - int closest_waypoint_index = getLocalClosestWaypoint(current_waypoints, current_pose_global_.pose, closest_search_size_); - for (int i = 0; i < closest_waypoint_index; ++i) + updateClosestWaypoint(current_waypoints, current_pose_global_.pose, closest_search_size_); + if (closest_waypoint_index_ == -1) { + return; + } + + for (int i = 0; i < closest_waypoint_index_; ++i) { avoid_waypoints_.waypoints.push_back(current_waypoints.waypoints.at(i)); } @@ -347,57 +339,51 @@ void AstarAvoid::mergeAvoidWaypoints(const nav_msgs::Path& path, int& end_of_avo } // update index for merged waypoints - end_of_avoid_index = closest_waypoint_index + path.poses.size(); + end_of_avoid_index = closest_waypoint_index_ + path.poses.size(); } -void AstarAvoid::publishWaypoints() +void AstarAvoid::publishWaypoints(const ros::TimerEvent& e) { - autoware_msgs::Lane current_waypoints; - - while (!terminate_thread_) + // select waypoints + switch (state_) { - // select waypoints - switch (state_) - { - case AstarAvoid::STATE::RELAYING: - current_waypoints = base_waypoints_; - break; - case AstarAvoid::STATE::STOPPING: - // do nothing, keep current waypoints - break; - case AstarAvoid::STATE::PLANNING: - // do nothing, keep current waypoints - break; - case AstarAvoid::STATE::AVOIDING: - current_waypoints = avoid_waypoints_; - break; - default: - current_waypoints = base_waypoints_; - break; - } + case AstarAvoid::STATE::RELAYING: + current_waypoints_ = base_waypoints_; + break; + case AstarAvoid::STATE::STOPPING: + // do nothing, keep current waypoints + break; + case AstarAvoid::STATE::PLANNING: + // do nothing, keep current waypoints + break; + case AstarAvoid::STATE::AVOIDING: + current_waypoints_ = avoid_waypoints_; + break; + default: + current_waypoints_ = base_waypoints_; + break; + } - autoware_msgs::Lane safety_waypoints; - safety_waypoints.header = current_waypoints.header; - safety_waypoints.increment = current_waypoints.increment; + // Create local path starting at closest global waypoint + autoware_msgs::Lane safety_waypoints; + safety_waypoints.header = current_waypoints_.header; + safety_waypoints.increment = current_waypoints_.increment; - // push waypoints from closest index - for (int i = 0; i < safety_waypoints_size_; ++i) - { - int index = getLocalClosestWaypoint(current_waypoints, current_pose_global_.pose, closest_search_size_) + i; - if (index < 0 || static_cast(current_waypoints.waypoints.size()) <= index) - { - break; - } - const autoware_msgs::Waypoint& wp = current_waypoints.waypoints[index]; - safety_waypoints.waypoints.push_back(wp); - } + updateClosestWaypoint(current_waypoints_, current_pose_global_.pose, closest_search_size_); + if (closest_waypoint_index_ == -1) + { + return; + } - if (safety_waypoints.waypoints.size() > 0) - { - safety_waypoints_pub_.publish(safety_waypoints); - } + for (int i = closest_waypoint_index_; + i < closest_waypoint_index_ + safety_waypoints_size_ && i < static_cast(current_waypoints_.waypoints.size()); ++i) + { + safety_waypoints.waypoints.push_back(current_waypoints_.waypoints[i]); + } - rate_->sleep(); + if (!safety_waypoints.waypoints.empty()) + { + safety_waypoints_pub_.publish(safety_waypoints); } } @@ -415,29 +401,32 @@ tf::Transform AstarAvoid::getTransform(const std::string& from, const std::strin return stf; } -int AstarAvoid::getLocalClosestWaypoint(const autoware_msgs::Lane& waypoints, const geometry_msgs::Pose& pose, const int& search_size) +void AstarAvoid::updateClosestWaypoint(const autoware_msgs::Lane& waypoints, const geometry_msgs::Pose& pose, + const int& search_size) { - static autoware_msgs::Lane local_waypoints; // around self-vehicle - const int prev_index = closest_local_index_; - // search in all waypoints if lane_select judges you're not on waypoints - if (closest_local_index_ == -1) + if (closest_waypoint_index_ == -1) { - closest_local_index_ = getClosestWaypoint(waypoints, pose); + closest_waypoint_index_ = getClosestWaypoint(waypoints, pose); } - // search in limited area based on prev_index else { - // get neighborhood waypoints around prev_index - int start_index = std::max(0, prev_index - search_size / 2); - int end_index = std::min(prev_index + search_size / 2, (int)waypoints.waypoints.size()); - auto start_itr = waypoints.waypoints.begin() + start_index; - auto end_itr = waypoints.waypoints.begin() + end_index; - local_waypoints.waypoints = std::vector(start_itr, end_itr); - - // get closest waypoint in neighborhood waypoints - closest_local_index_ = start_index + getClosestWaypoint(local_waypoints, pose); + // search within a limited area around closest_waypoint_index_ found in the previous loop. + const int start_index = std::max(0, closest_waypoint_index_ - search_size / 2); + const int end_index = std::min(closest_waypoint_index_ + search_size / 2, static_cast(waypoints.waypoints.size())); + + // consists of search_size/2 waypoints before and after ego-vehicle. + autoware_msgs::Lane local_waypoints; + local_waypoints.waypoints = std::vector(waypoints.waypoints.begin() + start_index, + waypoints.waypoints.begin() + end_index); + const int closest_local_index = getClosestWaypoint(local_waypoints, pose); + if (closest_local_index != -1) + { + closest_waypoint_index_ = start_index + closest_local_index; + } + else + { + closest_waypoint_index_ = -1; + } } - - return closest_local_index_; } diff --git a/core_planning/waypoint_planner/src/velocity_set/libvelocity_set.cpp b/core_planning/waypoint_planner/src/velocity_set/libvelocity_set.cpp index 0d5c39cd00f..10fbebb7a45 100644 --- a/core_planning/waypoint_planner/src/velocity_set/libvelocity_set.cpp +++ b/core_planning/waypoint_planner/src/velocity_set/libvelocity_set.cpp @@ -254,53 +254,50 @@ int CrossWalk::findClosestCrosswalk(const int closest_waypoint, const autoware_m if (!set_points || closest_waypoint < 0) return -1; - double find_distance = 2.0 * 2.0; // meter - double ignore_distance = 20.0 * 20.0; // meter - static std::vector bdid = getBDID(); + static constexpr double find_distance = 2.0 * 2.0; // meter + static constexpr double ignore_distance = 20.0 * 20.0; // meter - int _return_val = 0; + bool is_found = false; + // keep the first crosswalks waypoint index if found + int closest_crosswalk_waypoint_idx = -1; + detection_crosswalk_id_ = -1; + detection_crosswalk_array_.clear(); // for multiple - initDetectionCrossWalkIDs(); // for multiple - - // Find near cross walk - for (int num = closest_waypoint; num < closest_waypoint + search_distance && num < (int)lane.waypoints.size(); num++) + // Find crosswalks within search distance + for (int wp_idx = closest_waypoint; wp_idx < closest_waypoint + search_distance && wp_idx < (int)lane.waypoints.size(); wp_idx++) { - geometry_msgs::Point waypoint = lane.waypoints[num].pose.pose.position; + geometry_msgs::Point waypoint = lane.waypoints[wp_idx].pose.pose.position; waypoint.z = 0.0; // ignore Z axis - for (const auto &i : bdid) + for (const int &id : bdID_) { // ignore far crosswalk - geometry_msgs::Point crosswalk_center = getDetectionPoints(i).center; + const auto& crosswalk = detection_points_.at(id); + geometry_msgs::Point crosswalk_center = crosswalk.center; crosswalk_center.z = 0.0; if (calcSquareOfLength(crosswalk_center, waypoint) > ignore_distance) continue; - for (auto p : getDetectionPoints(i).points) + for (auto p : crosswalk.points) { p.z = waypoint.z; if (calcSquareOfLength(p, waypoint) < find_distance) { - addDetectionCrossWalkIDs(i); - if (!this->isMultipleDetection()) - { - setDetectionCrossWalkID(i); - return num; + if (!is_found) { + closest_crosswalk_waypoint_idx = wp_idx; + detection_crosswalk_id_ = id; + is_found = true; } - else if (!_return_val) - { - setDetectionCrossWalkID(i); - _return_val = num; + addDetectionCrossWalkIDs(id); + if (!enable_multiple_crosswalk_detection_) + { + return closest_crosswalk_waypoint_idx; } } } } } - if (_return_val) - return _return_val; - - setDetectionCrossWalkID(-1); - return -1; // no near crosswalk + return closest_crosswalk_waypoint_idx; } geometry_msgs::Point ObstaclePoints::getObstaclePoint(const EControl &kind) const diff --git a/core_planning/waypoint_planner/src/velocity_set/velocity_set.cpp b/core_planning/waypoint_planner/src/velocity_set/velocity_set.cpp index cf5b823e033..3bf5e95b094 100644 --- a/core_planning/waypoint_planner/src/velocity_set/velocity_set.cpp +++ b/core_planning/waypoint_planner/src/velocity_set/velocity_set.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -25,9 +26,9 @@ namespace { -constexpr int LOOP_RATE = 10; -constexpr double DECELERATION_SEARCH_DISTANCE = 30; -constexpr double STOP_SEARCH_DISTANCE = 60; +constexpr int32_t DECELERATION_SEARCH_DISTANCE = 30; +// The number of waypoints ahead of the current closest waypoint to search. +constexpr int32_t STOP_SEARCH_DISTANCE = 60; void obstacleColorByKind(const EControl kind, std_msgs::ColorRGBA &color, const double alpha=0.5) { @@ -92,7 +93,7 @@ void displayDetectionRange(const autoware_msgs::Lane& lane, const CrossWalk& cro visualization_msgs::Marker crosswalk_marker; visualization_msgs::Marker waypoint_marker_stop; visualization_msgs::Marker waypoint_marker_decelerate; - visualization_msgs::Marker stop_line; + visualization_msgs::Marker stop_line_marker; crosswalk_marker.header.frame_id = "/map"; crosswalk_marker.header.stamp = ros::Time(); crosswalk_marker.id = 0; @@ -100,14 +101,14 @@ void displayDetectionRange(const autoware_msgs::Lane& lane, const CrossWalk& cro crosswalk_marker.action = visualization_msgs::Marker::ADD; waypoint_marker_stop = crosswalk_marker; waypoint_marker_decelerate = crosswalk_marker; - stop_line = crosswalk_marker; - stop_line.type = visualization_msgs::Marker::CUBE; + stop_line_marker = crosswalk_marker; + stop_line_marker.type = visualization_msgs::Marker::CUBE; // set each namespace crosswalk_marker.ns = "Crosswalk Detection"; waypoint_marker_stop.ns = "Stop Detection"; waypoint_marker_decelerate.ns = "Decelerate Detection"; - stop_line.ns = "Stop Line"; + stop_line_marker.ns = "Stop Line"; // set scale and color double scale = 2 * stop_range; @@ -130,49 +131,38 @@ void displayDetectionRange(const autoware_msgs::Lane& lane, const CrossWalk& cro waypoint_marker_decelerate.color.b = 0.0; waypoint_marker_decelerate.frame_locked = true; - if (obstacle_waypoint > -1) + // stop_line marker + if (kind != EControl::KEEP) { - stop_line.pose.position = lane.waypoints[obstacle_waypoint].pose.pose.position; - stop_line.pose.orientation = lane.waypoints[obstacle_waypoint].pose.pose.orientation; + if (obstacle_waypoint > -1) + { + stop_line_marker.pose.position = lane.waypoints[obstacle_waypoint].pose.pose.position; + stop_line_marker.pose.orientation = lane.waypoints[obstacle_waypoint].pose.pose.orientation; + } + stop_line_marker.pose.position.z += 1.0; + stop_line_marker.scale.x = 0.1; + stop_line_marker.scale.y = 15.0; + stop_line_marker.scale.z = 2.0; + stop_line_marker.lifetime = ros::Duration(0.1); + stop_line_marker.frame_locked = true; + obstacleColorByKind(kind, stop_line_marker.color, 0.3); + marker_array.markers.push_back(stop_line_marker); } - stop_line.pose.position.z += 1.0; - stop_line.scale.x = 0.1; - stop_line.scale.y = 15.0; - stop_line.scale.z = 2.0; - stop_line.lifetime = ros::Duration(0.1); - stop_line.frame_locked = true; - obstacleColorByKind(kind, stop_line.color, 0.3); + // crosswalk marker int crosswalk_id = crosswalk.getDetectionCrossWalkID(); if (crosswalk_id > 0) - scale = crosswalk.getDetectionPoints(crosswalk_id).width; - crosswalk_marker.scale.x = scale; - crosswalk_marker.scale.y = scale; - crosswalk_marker.scale.z = scale; - crosswalk_marker.color.a = 0.5; - crosswalk_marker.color.r = 0.0; - crosswalk_marker.color.g = 1.0; - crosswalk_marker.color.b = 0.0; - crosswalk_marker.frame_locked = true; - - // set marker points coordinate - for (int i = 0; i < STOP_SEARCH_DISTANCE; i++) { - if (closest_waypoint < 0 || i + closest_waypoint > static_cast(lane.waypoints.size()) - 1) - break; - - geometry_msgs::Point point; - point = lane.waypoints[closest_waypoint + i].pose.pose.position; - - waypoint_marker_stop.points.push_back(point); - - if (i > DECELERATION_SEARCH_DISTANCE) - continue; - waypoint_marker_decelerate.points.push_back(point); - } + scale = crosswalk.getDetectionPoints(crosswalk_id).width; + crosswalk_marker.scale.x = scale; + crosswalk_marker.scale.y = scale; + crosswalk_marker.scale.z = scale; + crosswalk_marker.color.a = 0.5; + crosswalk_marker.color.r = 0.0; + crosswalk_marker.color.g = 1.0; + crosswalk_marker.color.b = 0.0; + crosswalk_marker.frame_locked = true; - if (crosswalk_id > 0) - { if (!crosswalk.isMultipleDetection()) { for (const auto& p : crosswalk.getDetectionPoints(crosswalk_id).points) @@ -189,37 +179,56 @@ void displayDetectionRange(const autoware_msgs::Lane& lane, const CrossWalk& cro } } } + marker_array.markers.push_back(crosswalk_marker); } - // publish marker - marker_array.markers.push_back(crosswalk_marker); - marker_array.markers.push_back(waypoint_marker_stop); - marker_array.markers.push_back(waypoint_marker_decelerate); - if (kind != EControl::KEEP) - marker_array.markers.push_back(stop_line); + + // stop and deceleration markers + for (int i = 0; i < STOP_SEARCH_DISTANCE; i++) + { + if (closest_waypoint < 0 || i + closest_waypoint > static_cast(lane.waypoints.size()) - 1) + break; + + geometry_msgs::Point point; + point = lane.waypoints[closest_waypoint + i].pose.pose.position; + + waypoint_marker_stop.points.push_back(point); + + if (i > DECELERATION_SEARCH_DISTANCE) + continue; + waypoint_marker_decelerate.points.push_back(point); + } + if (!waypoint_marker_stop.points.empty()) + { + marker_array.markers.push_back(waypoint_marker_stop); + } + if (!waypoint_marker_decelerate.points.empty()) + { + marker_array.markers.push_back(waypoint_marker_decelerate); + } + detection_range_pub.publish(marker_array); marker_array.markers.clear(); } // obstacle detection for crosswalk -EControl crossWalkDetection(const pcl::PointCloud& points, const CrossWalk& crosswalk, - const geometry_msgs::PoseStamped& localizer_pose, const int points_threshold, +EControl crossWalkDetection(const pcl::PointCloud& pcl_points, const CrossWalk& crosswalk, + const geometry_msgs::Pose localizer_pose, const int points_threshold, ObstaclePoints* obstacle_points) { int crosswalk_id = crosswalk.getDetectionCrossWalkID(); double search_radius = crosswalk.getDetectionPoints(crosswalk_id).width / 2; - // std::vector crosswalk_ids crosswalk.getDetectionCrossWalkIDs(); // Search each calculated points in the crosswalk for (const auto& c_id : crosswalk.getDetectionCrossWalkIDs()) { for (const auto& p : crosswalk.getDetectionPoints(c_id).points) { - geometry_msgs::Point detection_point = calcRelativeCoordinate(p, localizer_pose.pose); + geometry_msgs::Point detection_point = calcRelativeCoordinate(p, localizer_pose); tf::Vector3 detection_vector = point2vector(detection_point); detection_vector.setZ(0.0); int stop_count = 0; // the number of points in the detection area - for (const auto& p : points) + for (const auto& p : pcl_points) { tf::Vector3 point_vector(p.x, p.y, 0.0); double distance = tf::tfDistance(point_vector, detection_vector); @@ -230,7 +239,7 @@ EControl crossWalkDetection(const pcl::PointCloud& points, const point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } if (stop_count > points_threshold) return EControl::STOP; @@ -244,20 +253,17 @@ EControl crossWalkDetection(const pcl::PointCloud& points, const return EControl::KEEP; // find no obstacles } -int detectStopObstacle(const pcl::PointCloud& points, const int closest_waypoint, +int detectStopObstacle(const pcl::PointCloud& pcl_points, const int closest_waypoint, const autoware_msgs::Lane& lane, const CrossWalk& crosswalk, double stop_range, - double points_threshold, const geometry_msgs::PoseStamped& localizer_pose, + double points_threshold, const geometry_msgs::Pose localizer_pose, ObstaclePoints* obstacle_points, EObstacleType* obstacle_type, const int wpidx_detection_result_by_other_nodes) { int stop_obstacle_waypoint = -1; *obstacle_type = EObstacleType::NONE; // start search from the closest waypoint - for (int i = closest_waypoint; i < closest_waypoint + STOP_SEARCH_DISTANCE; i++) + for (int i = closest_waypoint; i < closest_waypoint + STOP_SEARCH_DISTANCE && i < static_cast(lane.waypoints.size()); i++) { - // reach the end of waypoints - if (i >= static_cast(lane.waypoints.size())) - break; // detection another nodes if (wpidx_detection_result_by_other_nodes >= 0 && @@ -270,10 +276,11 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c } // Detection for cross walk + // If enable_crosswalk_detection is false, crosswalk.getDetectionWaypoint() returns -1. if (i == crosswalk.getDetectionWaypoint()) { // found an obstacle in the cross walk - if (crossWalkDetection(points, crosswalk, localizer_pose, points_threshold, obstacle_points) == EControl::STOP) + if (crossWalkDetection(pcl_points, crosswalk, localizer_pose, points_threshold, obstacle_points) == EControl::STOP) { stop_obstacle_waypoint = i; *obstacle_type = EObstacleType::ON_CROSSWALK; @@ -281,13 +288,13 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c } } - // waypoint seen by localizer - geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose.pose); + // waypoint in lidar point cloud frame + geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose); tf::Vector3 tf_waypoint = point2vector(waypoint); tf_waypoint.setZ(0); int stop_point_count = 0; - for (const auto& p : points) + for (const auto& p : pcl_points) { tf::Vector3 point_vector(p.x, p.y, 0); @@ -300,7 +307,7 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } } @@ -313,33 +320,27 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c } obstacle_points->clearStopPoints(); - - // check next waypoint... } return stop_obstacle_waypoint; } -int detectDecelerateObstacle(const pcl::PointCloud& points, const int closest_waypoint, +int detectDecelerateObstacle(const pcl::PointCloud& pcl_points, const int closest_waypoint, const autoware_msgs::Lane& lane, const double stop_range, const double deceleration_range, - const double points_threshold, const geometry_msgs::PoseStamped& localizer_pose, + const double points_threshold, const geometry_msgs::Pose localizer_pose, ObstaclePoints* obstacle_points) { int decelerate_obstacle_waypoint = -1; // start search from the closest waypoint - for (int i = closest_waypoint; i < closest_waypoint + DECELERATION_SEARCH_DISTANCE; i++) + for (int i = closest_waypoint; i < closest_waypoint + DECELERATION_SEARCH_DISTANCE && i < static_cast(lane.waypoints.size()); i++) { - // reach the end of waypoints - if (i >= static_cast(lane.waypoints.size())) - break; - // waypoint seen by localizer - geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose.pose); + geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose); tf::Vector3 tf_waypoint = point2vector(waypoint); tf_waypoint.setZ(0); int decelerate_point_count = 0; - for (const auto& p : points) + for (const auto& p : pcl_points) { tf::Vector3 point_vector(p.x, p.y, 0); @@ -352,7 +353,7 @@ int detectDecelerateObstacle(const pcl::PointCloud& points, const point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setDeceleratePoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setDeceleratePoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } } @@ -372,17 +373,17 @@ int detectDecelerateObstacle(const pcl::PointCloud& points, const } // Detect an obstacle by using pointcloud -EControl pointsDetection(const pcl::PointCloud& points, const int closest_waypoint, +EControl pointsDetection(const pcl::PointCloud& pcl_points, const int closest_waypoint, const autoware_msgs::Lane& lane, const CrossWalk& crosswalk, const VelocitySetInfo& vs_info, int* obstacle_waypoint, ObstaclePoints* obstacle_points) { // no input for detection || no closest waypoint - if ((points.empty() == true && vs_info.getDetectionResultByOtherNodes() == -1) || closest_waypoint < 0) + if ((pcl_points.empty() && vs_info.getDetectionResultByOtherNodes() == -1) || closest_waypoint < 0) return EControl::KEEP; EObstacleType obstacle_type = EObstacleType::NONE; int stop_obstacle_waypoint = - detectStopObstacle(points, closest_waypoint, lane, crosswalk, vs_info.getStopRange(), + detectStopObstacle(pcl_points, closest_waypoint, lane, crosswalk, vs_info.getStopRange(), vs_info.getPointsThreshold(), vs_info.getLocalizerPose(), obstacle_points, &obstacle_type, vs_info.getDetectionResultByOtherNodes()); @@ -401,7 +402,7 @@ EControl pointsDetection(const pcl::PointCloud& points, const int } int decelerate_obstacle_waypoint = - detectDecelerateObstacle(points, closest_waypoint, lane, vs_info.getStopRange(), vs_info.getDecelerationRange(), + detectDecelerateObstacle(pcl_points, closest_waypoint, lane, vs_info.getStopRange(), vs_info.getDecelerationRange(), vs_info.getPointsThreshold(), vs_info.getLocalizerPose(), obstacle_points); // stop obstacle was not found @@ -465,7 +466,7 @@ EControl obstacleDetection(int closest_waypoint, const autoware_msgs::Lane& lane { false_count++; - if (false_count < LOOP_RATE / 2) + if (false_count < 5) { *obstacle_waypoint = prev_obstacle_waypoint; displayObstacle(EControl::OTHERS, obstacle_points, obstacle_pub); @@ -481,41 +482,34 @@ EControl obstacleDetection(int closest_waypoint, const autoware_msgs::Lane& lane } void changeWaypoints(const VelocitySetInfo& vs_info, const EControl& detection_result, int closest_waypoint, - int obstacle_waypoint, const ros::Publisher& final_waypoints_pub, VelocitySetPath* vs_path) + int obstacle_waypoint, VelocitySetPath* vs_path) { + double deceleration = 0.0; + double velocity_change_limit = vs_info.getVelocityChangeLimit(); + if (detection_result == EControl::STOP || detection_result == EControl::STOPLINE) - { // STOP for obstacle/stopline + { + // STOP for obstacle/stopline // stop_waypoint is about stop_distance meter away from obstacles/stoplines int stop_distance = (detection_result == EControl::STOP) ? vs_info.getStopDistanceObstacle() : vs_info.getStopDistanceStopline(); - double deceleration = (detection_result == EControl::STOP) + deceleration = (detection_result == EControl::STOP) ? vs_info.getDecelerationObstacle() : vs_info.getDecelerationStopline(); int stop_waypoint = calcWaypointIndexReverse(vs_path->getPrevWaypoints(), obstacle_waypoint, stop_distance); // change waypoints to stop by the stop_waypoint vs_path->changeWaypointsForStopping(stop_waypoint, obstacle_waypoint, closest_waypoint, deceleration); - vs_path->avoidSuddenAcceleration(deceleration, closest_waypoint); - vs_path->avoidSuddenDeceleration(vs_info.getVelocityChangeLimit(), deceleration, closest_waypoint); - vs_path->setTemporalWaypoints(vs_info.getTemporalWaypointsSize(), closest_waypoint, vs_info.getControlPose()); - final_waypoints_pub.publish(vs_path->getTemporalWaypoints()); - } - else if (detection_result == EControl::DECELERATE) - { // DECELERATE for obstacles - vs_path->initializeNewWaypoints(); - vs_path->changeWaypointsForDeceleration(vs_info.getDecelerationObstacle(), closest_waypoint, obstacle_waypoint); - vs_path->avoidSuddenDeceleration(vs_info.getVelocityChangeLimit(), vs_info.getDecelerationObstacle(), closest_waypoint); - vs_path->avoidSuddenAcceleration(vs_info.getDecelerationObstacle(), closest_waypoint); - vs_path->setTemporalWaypoints(vs_info.getTemporalWaypointsSize(), closest_waypoint, vs_info.getControlPose()); - final_waypoints_pub.publish(vs_path->getTemporalWaypoints()); } else - { // ACCELERATE or KEEP + { // ACCELERATE, KEEP, or DECELERATE for obstacles vs_path->initializeNewWaypoints(); - vs_path->avoidSuddenAcceleration(vs_info.getDecelerationObstacle(), closest_waypoint); - vs_path->avoidSuddenDeceleration(vs_info.getVelocityChangeLimit(), vs_info.getDecelerationObstacle(), closest_waypoint); - vs_path->setTemporalWaypoints(vs_info.getTemporalWaypointsSize(), closest_waypoint, vs_info.getControlPose()); - final_waypoints_pub.publish(vs_path->getTemporalWaypoints()); + deceleration = vs_info.getDecelerationObstacle(); + if (detection_result == EControl::DECELERATE) { + vs_path->changeWaypointsForDeceleration(deceleration, closest_waypoint, obstacle_waypoint); + } } + vs_path->avoidSuddenAcceleration(deceleration, closest_waypoint); + vs_path->avoidSuddenDeceleration(velocity_change_limit, deceleration, closest_waypoint); } } // end namespace @@ -527,59 +521,77 @@ int main(int argc, char** argv) ros::NodeHandle nh; ros::NodeHandle private_nh("~"); - bool use_crosswalk_detection; + double update_rate; + bool enable_crosswalk_detection; bool enable_multiple_crosswalk_detection; - std::string points_topic; - private_nh.param("use_crosswalk_detection", use_crosswalk_detection, true); - private_nh.param("enable_multiple_crosswalk_detection", enable_multiple_crosswalk_detection, true); - + private_nh.param("update_rate", update_rate, 10.0); + private_nh.param("use_crosswalk_detection", enable_crosswalk_detection, true); + private_nh.param("enable_multiple_crosswalk_detection", enable_multiple_crosswalk_detection, true); private_nh.param("points_topic", points_topic, "points_lanes"); - // class CrossWalk crosswalk; VelocitySetPath vs_path; VelocitySetInfo vs_info; - // velocity set subscriber + // velocity set path subscriber ros::Subscriber waypoints_sub = nh.subscribe("safety_waypoints", 1, &VelocitySetPath::waypointsCallback, &vs_path); ros::Subscriber current_vel_sub = - nh.subscribe("current_velocity", 1, &VelocitySetPath::currentVelocityCallback, &vs_path); - - + nh.subscribe("current_velocity", 1, &VelocitySetPath::currentVelocityCallback, &vs_path); // velocity set info subscriber ros::Subscriber config_sub = nh.subscribe("config/velocity_set", 1, &VelocitySetInfo::configCallback, &vs_info); + // point clouds subscriber and only points within ROI are kept in callback function. ros::Subscriber points_sub = nh.subscribe(points_topic, 1, &VelocitySetInfo::pointsCallback, &vs_info); - ros::Subscriber localizer_sub = nh.subscribe("localizer_pose", 1, &VelocitySetInfo::localizerPoseCallback, &vs_info); + // localizer_pose represents the lidar's pose. + // current_pose represents the ego-vehicle's pose at the center of rear axle. ros::Subscriber control_pose_sub = nh.subscribe("current_pose", 1, &VelocitySetInfo::controlPoseCallback, &vs_info); ros::Subscriber detectionresult_sub = nh.subscribe("/state/stopline_wpidx", 1, &VelocitySetInfo::detectionCallback, &vs_info); - // vector map subscriber - ros::Subscriber sub_dtlane = nh.subscribe("vector_map_info/cross_walk", 1, &CrossWalk::crossWalkCallback, &crosswalk); - ros::Subscriber sub_area = nh.subscribe("vector_map_info/area", 1, &CrossWalk::areaCallback, &crosswalk); - ros::Subscriber sub_line = nh.subscribe("vector_map_info/line", 1, &CrossWalk::lineCallback, &crosswalk); - ros::Subscriber sub_point = nh.subscribe("vector_map_info/point", 1, &CrossWalk::pointCallback, &crosswalk); + // vector map subscribers + if (enable_crosswalk_detection) + { + crosswalk.setMultipleDetectionFlag(enable_multiple_crosswalk_detection); + ros::Subscriber sub_dtlane = + nh.subscribe("vector_map_info/cross_walk", 1, &CrossWalk::crossWalkCallback, &crosswalk); + ros::Subscriber sub_area = nh.subscribe("vector_map_info/area", 1, &CrossWalk::areaCallback, &crosswalk); + ros::Subscriber sub_line = nh.subscribe("vector_map_info/line", 1, &CrossWalk::lineCallback, &crosswalk); + ros::Subscriber sub_point = nh.subscribe("vector_map_info/point", 1, &CrossWalk::pointCallback, &crosswalk); + } + + // TF Listener + tf2_ros::Buffer tfBuffer; + tf2_ros::TransformListener tfListener(tfBuffer); // publisher - ros::Publisher detection_range_pub = nh.advertise("detection_range", 1); - ros::Publisher obstacle_pub = nh.advertise("obstacle", 1); + ros::Publisher detection_range_markers_pub = nh.advertise("detection_range", 1); + ros::Publisher obstacle_marker_pub = nh.advertise("obstacle", 1); ros::Publisher obstacle_waypoint_pub = nh.advertise("obstacle_waypoint", 1, true); ros::Publisher stopline_waypoint_pub = nh.advertise("stopline_waypoint", 1, true); + ros::Publisher final_waypoints_pub = nh.advertise("final_waypoints", 1, true); - ros::Publisher final_waypoints_pub; - final_waypoints_pub = nh.advertise("final_waypoints", 1, true); - - ros::Rate loop_rate(LOOP_RATE); + ros::Rate loop_rate(update_rate); while (ros::ok()) { ros::spinOnce(); - int closest_waypoint = 0; + try + { + geometry_msgs::TransformStamped map_to_lidar_tf = tfBuffer.lookupTransform( + "map", "velodyne", ros::Time::now(), ros::Duration(2.0)); + vs_info.setLocalizerPose(map_to_lidar_tf); + } + catch(tf2::TransformException &ex) + { + ROS_WARN("Failed to get map->lidar transform. skip computation: %s", ex.what()); + continue; + } - if (crosswalk.loaded_all && !crosswalk.set_points) - crosswalk.setCrossWalkPoints(); + // Since the index 0 of safety_waypoints from astar_avoid node holds the closest waypoint, it is set to 0. + int32_t current_closest_waypoint = 0; + // Initialize it to -1 which indicates no closest_crosswalk_waypoint is found. + int32_t closest_crosswalk_waypoint = -1; if (!vs_info.getSetPose() || !vs_path.getSetPath() || vs_path.getPrevWaypointsSize() == 0) { @@ -587,33 +599,42 @@ int main(int argc, char** argv) continue; } - crosswalk.setMultipleDetectionFlag(enable_multiple_crosswalk_detection); + if (enable_crosswalk_detection) + { + if (crosswalk.loaded_all && !crosswalk.set_points) + { + crosswalk.setCrossWalkPoints(); + } + // if crosswalk.loaded_all is false, the closest_crosswalk_waypoint is set to -1. + closest_crosswalk_waypoint = crosswalk.findClosestCrosswalk(current_closest_waypoint, vs_path.getPrevWaypoints(), STOP_SEARCH_DISTANCE); + } + crosswalk.setDetectionWaypoint(closest_crosswalk_waypoint); - if (use_crosswalk_detection) - crosswalk.setDetectionWaypoint( - crosswalk.findClosestCrosswalk(closest_waypoint, vs_path.getPrevWaypoints(), STOP_SEARCH_DISTANCE)); + int32_t traffic_waypoint_idx = -1; + EControl detection_result = obstacleDetection(current_closest_waypoint, vs_path.getPrevWaypoints(), crosswalk, vs_info, + detection_range_markers_pub, obstacle_marker_pub, &traffic_waypoint_idx); - int obstacle_waypoint = -1; - EControl detection_result = obstacleDetection(closest_waypoint, vs_path.getPrevWaypoints(), crosswalk, vs_info, - detection_range_pub, obstacle_pub, &obstacle_waypoint); + // Update waypoints' velocity profile based on obtacle detection results. + changeWaypoints(vs_info, detection_result, current_closest_waypoint, traffic_waypoint_idx, &vs_path); - changeWaypoints(vs_info, detection_result, closest_waypoint, - obstacle_waypoint, final_waypoints_pub, &vs_path); + // Only retrieve a limited number of updated waypoints ahead of the ego-vehicle. + vs_path.setTemporalWaypoints(vs_info.getTemporalWaypointsSize(), current_closest_waypoint, vs_info.getControlPose()); - vs_info.clearPoints(); + // publish final waypoints + final_waypoints_pub.publish(vs_path.getTemporalWaypoints()); - // publish obstacle waypoint index + // publish obstacle and stopline waypoint index std_msgs::Int32 obstacle_waypoint_index; std_msgs::Int32 stopline_waypoint_index; if (detection_result == EControl::STOP) { - obstacle_waypoint_index.data = obstacle_waypoint; + obstacle_waypoint_index.data = traffic_waypoint_idx; stopline_waypoint_index.data = -1; } else if (detection_result == EControl::STOPLINE) { obstacle_waypoint_index.data = -1; - stopline_waypoint_index.data = obstacle_waypoint; + stopline_waypoint_index.data = traffic_waypoint_idx; } else { @@ -624,6 +645,7 @@ int main(int argc, char** argv) stopline_waypoint_pub.publish(stopline_waypoint_index); vs_path.resetFlag(); + vs_info.clearPoints(); loop_rate.sleep(); } diff --git a/core_planning/waypoint_planner/src/velocity_set/velocity_set_info.cpp b/core_planning/waypoint_planner/src/velocity_set/velocity_set_info.cpp index d84e9e1fcad..70e42a99fd5 100644 --- a/core_planning/waypoint_planner/src/velocity_set/velocity_set_info.cpp +++ b/core_planning/waypoint_planner/src/velocity_set/velocity_set_info.cpp @@ -16,14 +16,6 @@ #include -void joinPoints(const pcl::PointCloud& points1, pcl::PointCloud* points2) -{ - for (const auto& p : points1) - { - points2->push_back(p); - } -} - VelocitySetInfo::VelocitySetInfo() : stop_range_(1.3), deceleration_range_(0), @@ -36,8 +28,8 @@ VelocitySetInfo::VelocitySetInfo() deceleration_stopline_(0.6), velocity_change_limit_(2.77), temporal_waypoints_size_(100), - set_pose_(false), - wpidx_detectionResultByOtherNodes_(-1) + wpidx_detectionResultByOtherNodes_(-1), + set_pose_(false) { ros::NodeHandle private_nh_("~"); ros::NodeHandle nh; @@ -62,10 +54,6 @@ VelocitySetInfo::VelocitySetInfo() health_checker_ptr_->ENABLE(); } -VelocitySetInfo::~VelocitySetInfo() -{ -} - void VelocitySetInfo::clearPoints() { points_.clear(); @@ -107,7 +95,6 @@ void VelocitySetInfo::pointsCallback(const sensor_msgs::PointCloud2ConstPtr &msg points_.push_back(v); } - } void VelocitySetInfo::detectionCallback(const std_msgs::Int32 &msg) @@ -123,9 +110,10 @@ void VelocitySetInfo::controlPoseCallback(const geometry_msgs::PoseStampedConstP set_pose_ = true; } -void VelocitySetInfo::localizerPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg) +void VelocitySetInfo::setLocalizerPose(const geometry_msgs::TransformStamped &map_to_lidar_tf) { - health_checker_ptr_->NODE_ACTIVATE(); - health_checker_ptr_->CHECK_RATE("topic_rate_localizer_pose_slow", 8, 5, 1, "topic localizer_pose subscribe rate slow."); - localizer_pose_ = *msg; + localizer_pose_.position.x = map_to_lidar_tf.transform.translation.x; + localizer_pose_.position.y = map_to_lidar_tf.transform.translation.y; + localizer_pose_.position.z = map_to_lidar_tf.transform.translation.z; + localizer_pose_.orientation = map_to_lidar_tf.transform.rotation; } diff --git a/core_planning/waypoint_planner/src/velocity_set/velocity_set_path.cpp b/core_planning/waypoint_planner/src/velocity_set/velocity_set_path.cpp index e13f99f6494..bffd7c0b16a 100644 --- a/core_planning/waypoint_planner/src/velocity_set/velocity_set_path.cpp +++ b/core_planning/waypoint_planner/src/velocity_set/velocity_set_path.cpp @@ -17,22 +17,16 @@ #include VelocitySetPath::VelocitySetPath() - : set_path_(false), - current_vel_(0) { ros::NodeHandle private_nh_("~"); private_nh_.param("velocity_offset", velocity_offset_, 1.2); private_nh_.param("decelerate_vel_min", decelerate_vel_min_, 1.3); } -VelocitySetPath::~VelocitySetPath() -{ -} - // check if waypoint number is valid -bool VelocitySetPath::checkWaypoint(int num, const char *name) const +bool VelocitySetPath::checkWaypoint(int wp_num) const { - if (num < 0 || num >= getPrevWaypointsSize()) + if (wp_num < 0 || wp_num >= getPrevWaypointsSize()) { return false; } @@ -46,22 +40,23 @@ void VelocitySetPath::setTemporalWaypoints(int temporal_waypoints_size, int clos return; temporal_waypoints_.waypoints.clear(); - temporal_waypoints_.header = new_waypoints_.header; - temporal_waypoints_.increment = new_waypoints_.increment; + temporal_waypoints_.header = updated_waypoints_.header; + temporal_waypoints_.increment = updated_waypoints_.increment; // push current pose autoware_msgs::Waypoint current_point; current_point.pose = control_pose; - current_point.twist = new_waypoints_.waypoints[closest_waypoint].twist; - current_point.dtlane = new_waypoints_.waypoints[closest_waypoint].dtlane; - temporal_waypoints_.waypoints.push_back(current_point); + current_point.twist = updated_waypoints_.waypoints[closest_waypoint].twist; + current_point.dtlane = updated_waypoints_.waypoints[closest_waypoint].dtlane; + temporal_waypoints_.waypoints.push_back(std::move(current_point)); + int total_waypoints = getNewWaypointsSize(); for (int i = 0; i < temporal_waypoints_size; i++) { - if (closest_waypoint + i >= getNewWaypointsSize()) + if (closest_waypoint + i >= total_waypoints) return; - temporal_waypoints_.waypoints.push_back(new_waypoints_.waypoints[closest_waypoint + i]); + temporal_waypoints_.waypoints.push_back(updated_waypoints_.waypoints[closest_waypoint + i]); } return; @@ -86,16 +81,18 @@ void VelocitySetPath::changeWaypointsForDeceleration(double deceleration, int cl // decelerate with constant deceleration for (int index = obstacle_waypoint + extra; index >= closest_waypoint; index--) { - if (!checkWaypoint(index, __FUNCTION__)) + if (!checkWaypoint(index)) continue; // v = sqrt( (v0)^2 + 2ax ) + // Keep the car at decelerate_vel_min_ when approaching the obstacles. + // without decelerate_vel_min_ term, changed_vel becomes zero if index == obstacle_waypoint. std::array range = {index, obstacle_waypoint}; double changed_vel = calcChangedVelocity(decelerate_vel_min_, deceleration, range); - double prev_vel = prev_waypoints_.waypoints[index].twist.twist.linear.x; + double prev_vel = original_waypoints_.waypoints[index].twist.twist.linear.x; const int sgn = (prev_vel < 0) ? -1 : 1; - new_waypoints_.waypoints[index].twist.twist.linear.x = sgn * std::min(std::abs(prev_vel), changed_vel); + updated_waypoints_.waypoints[index].twist.twist.linear.x = sgn * std::min(std::abs(prev_vel), changed_vel); } } @@ -104,21 +101,22 @@ void VelocitySetPath::avoidSuddenAcceleration(double deceleration, int closest_w { for (int i = 0;; i++) { - if (!checkWaypoint(closest_waypoint + i, __FUNCTION__)) + if (!checkWaypoint(closest_waypoint + i)) return; // accelerate with constant acceleration // v = root((v0)^2 + 2ax) + // Without velocity_offset_ term, changed_vel becomes current_vel_ when i == 0. For example, the car will not move if current_vel_ == 0. std::array range = {closest_waypoint, closest_waypoint + i}; double changed_vel = calcChangedVelocity(current_vel_, deceleration, range) + velocity_offset_; - const double& target_vel = new_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x; + const double target_vel = updated_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x; // Don't exceed original velocity if (changed_vel > std::abs(target_vel)) return; const int sgn = (target_vel < 0) ? -1 : 1; - new_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x = sgn * changed_vel; + updated_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x = sgn * changed_vel; } return; @@ -129,28 +127,33 @@ void VelocitySetPath::avoidSuddenDeceleration(double velocity_change_limit, doub if (closest_waypoint < 0) return; - const double& closest_vel = new_waypoints_.waypoints[closest_waypoint].twist.twist.linear.x; - // not avoid braking + const double closest_vel = updated_waypoints_.waypoints[closest_waypoint].twist.twist.linear.x; + + // if accelerating, do not modify the speed profile. + if ((current_vel_ >= 0.0 && current_vel_ <= closest_vel) || (current_vel_ < 0.0 && current_vel_ > closest_vel)) + return; + + // accelerate or decelerate within the limit if (std::abs(current_vel_ - closest_vel) < velocity_change_limit) return; - //std::cout << "avoid sudden braking!" << std::endl; + // bring up the forward waypoints' velocity to avoid sudden deceleration. for (int i = 0;; i++) { - if (!checkWaypoint(closest_waypoint + i, __FUNCTION__)) + if (!checkWaypoint(closest_waypoint + i)) return; // sqrt(v^2 - 2ax) std::array range = {closest_waypoint, closest_waypoint + i}; double changed_vel = calcChangedVelocity(std::abs(current_vel_) - velocity_change_limit, -deceleration, range); - const double& target_vel = new_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x; + const double target_vel = updated_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x; if (std::isnan(changed_vel)) { break; } const int sgn = (target_vel < 0) ? -1 : 1; - new_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x = sgn * changed_vel; + updated_waypoints_.waypoints[closest_waypoint + i].twist.twist.linear.x = sgn * changed_vel; } } @@ -163,49 +166,46 @@ void VelocitySetPath::changeWaypointsForStopping(int stop_waypoint, int obstacle // decelerate with constant deceleration for (int index = stop_waypoint; index >= closest_waypoint; index--) { - if (!checkWaypoint(index, __FUNCTION__)) + if (!checkWaypoint(index)) continue; // v = (v0)^2 + 2ax, and v0 = 0 std::array range = {index, stop_waypoint}; - double changed_vel = calcChangedVelocity(0.0, deceleration, range); - - double prev_vel = prev_waypoints_.waypoints[index].twist.twist.linear.x; + const double changed_vel = calcChangedVelocity(0.0, deceleration, range); + const double prev_vel = original_waypoints_.waypoints[index].twist.twist.linear.x; const int sgn = (prev_vel < 0) ? -1 : 1; - new_waypoints_.waypoints[index].twist.twist.linear.x = sgn * std::min(std::abs(prev_vel), changed_vel); + updated_waypoints_.waypoints[index].twist.twist.linear.x = sgn * std::min(std::abs(prev_vel), changed_vel); } - // fill velocity with 0 for stopping - for (int i = stop_waypoint; i <= obstacle_waypoint; i++) - { - new_waypoints_.waypoints[i].twist.twist.linear.x = 0; + // fill velocity with 0 for stopping waypoint and the rest. + for(auto it = updated_waypoints_.waypoints.begin() + stop_waypoint; it != updated_waypoints_.waypoints.end(); ++it) { + it->twist.twist.linear.x = 0.0; } - } void VelocitySetPath::initializeNewWaypoints() { - new_waypoints_ = prev_waypoints_; + updated_waypoints_ = original_waypoints_; } double VelocitySetPath::calcInterval(const int begin, const int end) const { // check index - if (begin < 0 || begin >= getPrevWaypointsSize() || end < 0 || end >= getPrevWaypointsSize()) + if (begin < 0 || begin >= getPrevWaypointsSize() || end < 0 || end >= getPrevWaypointsSize() || begin > end) { - ROS_WARN("Invalid index"); - return 0; + ROS_WARN_THROTTLE(1, "Invalid input index range"); + return 0.0; } // Calculate the inteval of waypoints - double dist_sum = 0; + double dist_sum = 0.0; for (int i = begin; i < end; i++) { - tf::Vector3 v1(prev_waypoints_.waypoints[i].pose.pose.position.x, - prev_waypoints_.waypoints[i].pose.pose.position.y, 0); + tf::Vector3 v1(original_waypoints_.waypoints[i].pose.pose.position.x, + original_waypoints_.waypoints[i].pose.pose.position.y, 0); - tf::Vector3 v2(prev_waypoints_.waypoints[i + 1].pose.pose.position.x, - prev_waypoints_.waypoints[i + 1].pose.pose.position.y, 0); + tf::Vector3 v2(original_waypoints_.waypoints[i + 1].pose.pose.position.x, + original_waypoints_.waypoints[i + 1].pose.pose.position.y, 0); dist_sum += tf::tfDistance(v1, v2); } @@ -221,9 +221,9 @@ void VelocitySetPath::resetFlag() void VelocitySetPath::waypointsCallback(const autoware_msgs::LaneConstPtr& msg) { - prev_waypoints_ = *msg; + original_waypoints_ = *msg; // temporary, edit waypoints velocity later - new_waypoints_ = *msg; + updated_waypoints_ = *msg; set_path_ = true; } diff --git a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp index b37d1addbe5..560d7e9a134 100644 --- a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp +++ b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp @@ -33,7 +33,6 @@ #include #include #include -#include #include #include @@ -172,7 +171,7 @@ int findClosestCrosswalk(const lanelet::ConstLanelets& crosswalks, const int clo // return EControl::Keep otherwise EControl crossWalkDetection(const pcl::PointCloud& points, const lanelet::ConstLanelets& closest_crosswalks, - const geometry_msgs::PoseStamped& localizer_pose, const int points_threshold, + const geometry_msgs::Pose localizer_pose, const int points_threshold, ObstaclePoints* obstacle_points) { for (auto lli = closest_crosswalks.begin(); lli != closest_crosswalks.end(); lli++) @@ -185,7 +184,7 @@ EControl crossWalkDetection(const pcl::PointCloud& points, { geometry_msgs::Point point_geom, transformed_point_geom; lanelet::utils::conversion::toGeomMsgPt(point, &point_geom); - transformed_point_geom = calcRelativeCoordinate(point_geom, localizer_pose.pose); + transformed_point_geom = calcRelativeCoordinate(point_geom, localizer_pose); lanelet::BasicPoint2d transformed_point2d(transformed_point_geom.x, transformed_point_geom.y); transformed_poly2d.push_back(transformed_point2d); } @@ -203,7 +202,7 @@ EControl crossWalkDetection(const pcl::PointCloud& points, point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } if (stop_count > points_threshold) { @@ -220,7 +219,7 @@ EControl crossWalkDetection(const pcl::PointCloud& points, // same as velocity_set.cpp - except for no reference to vector maps or crosswalk int detectStopObstacle(const pcl::PointCloud& points, const int closest_waypoint, int detection_waypoint, const autoware_msgs::Lane& lane, const lanelet::ConstLanelets& closest_crosswalks, - double stop_range, double points_threshold, const geometry_msgs::PoseStamped& localizer_pose, + double stop_range, double points_threshold, const geometry_msgs::Pose localizer_pose, ObstaclePoints* obstacle_points, EObstacleType* obstacle_type, const int wpidx_detection_result_by_other_nodes) { @@ -256,7 +255,7 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c } // waypoint seen by localizer - geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose.pose); + geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose); tf::Vector3 tf_waypoint = point2vector(waypoint); tf_waypoint.setZ(0); @@ -274,7 +273,7 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setStopPoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } } @@ -297,7 +296,7 @@ int detectStopObstacle(const pcl::PointCloud& points, const int c // same as velocity_set.cpp - expect for no reference to vector maps int detectDecelerateObstacle(const pcl::PointCloud& points, const int closest_waypoint, const autoware_msgs::Lane& lane, const double stop_range, const double deceleration_range, - const double points_threshold, const geometry_msgs::PoseStamped& localizer_pose, + const double points_threshold, const geometry_msgs::Pose localizer_pose, ObstaclePoints* obstacle_points) { int decelerate_obstacle_waypoint = -1; @@ -309,7 +308,7 @@ int detectDecelerateObstacle(const pcl::PointCloud& points, const break; // waypoint seen by localizer - geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose.pose); + geometry_msgs::Point waypoint = calcRelativeCoordinate(lane.waypoints[i].pose.pose.position, localizer_pose); tf::Vector3 tf_waypoint = point2vector(waypoint); tf_waypoint.setZ(0); @@ -327,7 +326,7 @@ int detectDecelerateObstacle(const pcl::PointCloud& points, const point_temp.x = p.x; point_temp.y = p.y; point_temp.z = p.z; - obstacle_points->setDeceleratePoint(calcAbsoluteCoordinate(point_temp, localizer_pose.pose)); + obstacle_points->setDeceleratePoint(calcAbsoluteCoordinate(point_temp, localizer_pose)); } } @@ -630,7 +629,7 @@ int main(int argc, char** argv) { g_loaded_lanelet_map = false; - ros::init(argc, argv, "lanelet_vs_node"); + ros::init(argc, argv, "velocity_set"); ros::NodeHandle rosnode; ros::NodeHandle private_rosnode("~"); @@ -661,14 +660,16 @@ int main(int argc, char** argv) // velocity set info subscriber ros::Subscriber config_sub = rosnode.subscribe("config/velocity_set", 1, &VelocitySetInfo::configCallback, &vs_info); ros::Subscriber points_sub = rosnode.subscribe(points_topic, 1, &VelocitySetInfo::pointsCallback, &vs_info); - ros::Subscriber localizer_sub = - rosnode.subscribe("localizer_pose", 1, &VelocitySetInfo::localizerPoseCallback, &vs_info); ros::Subscriber control_pose_sub = rosnode.subscribe("current_pose", 1, &VelocitySetInfo::controlPoseCallback, &vs_info); ros::Subscriber detectionresult_sub = rosnode.subscribe("state/stopline_wpidx", 1, &VelocitySetInfo::detectionCallback, &vs_info); - // publisher + // TF Listener + tf2_ros::Buffer tfBuffer; + tf2_ros::TransformListener tfListener(tfBuffer); + + // publisher ros::Publisher detection_range_pub = rosnode.advertise("detection_range", 1); ros::Publisher obstacle_pub = rosnode.advertise("obstacle", 1); ros::Publisher obstacle_waypoint_pub = rosnode.advertise("obstacle_waypoint", 1, true); @@ -682,6 +683,18 @@ int main(int argc, char** argv) { ros::spinOnce(); + try + { + geometry_msgs::TransformStamped map_to_lidar_tf = tfBuffer.lookupTransform( + "map", "velodyne", ros::Time::now(), ros::Duration(2.0)); + vs_info.setLocalizerPose(map_to_lidar_tf); + } + catch(tf2::TransformException &ex) + { + ROS_WARN("Failed to get map->lidar transform. skip computation: %s", ex.what()); + continue; + } + int closest_waypoint = 0; if (!vs_info.getSetPose() || !vs_path.getSetPath()) diff --git a/drivers/as/nodes/ssc_interface/ssc_interface.cpp b/drivers/as/nodes/ssc_interface/ssc_interface.cpp index 216188a2bbf..195496851dd 100644 --- a/drivers/as/nodes/ssc_interface/ssc_interface.cpp +++ b/drivers/as/nodes/ssc_interface/ssc_interface.cpp @@ -179,26 +179,26 @@ void SSCInterface::callbackFromSSCFeedbacks(const automotive_platform_msgs::Velo // steering angle [rad] vehicle_status.angle = std::atan(curvature * wheel_base_); - // gearshift + // gearshift if (msg_gear->current_gear.gear == automotive_platform_msgs::Gear::NONE) { - vehicle_status.gearshift = 0; + vehicle_status.current_gear.gear = automotive_platform_msgs::Gear::NONE; } else if (msg_gear->current_gear.gear == automotive_platform_msgs::Gear::PARK) { - vehicle_status.gearshift = 3; + vehicle_status.current_gear.gear = automotive_platform_msgs::Gear::PARK; } else if (msg_gear->current_gear.gear == automotive_platform_msgs::Gear::REVERSE) { - vehicle_status.gearshift = 2; + vehicle_status.current_gear.gear= automotive_platform_msgs::Gear::REVERSE; } else if (msg_gear->current_gear.gear == automotive_platform_msgs::Gear::NEUTRAL) { - vehicle_status.gearshift = 4; + vehicle_status.current_gear.gear = automotive_platform_msgs::Gear::NEUTRAL; } else if (msg_gear->current_gear.gear == automotive_platform_msgs::Gear::DRIVE) { - vehicle_status.gearshift = 1; + vehicle_status.current_gear.gear = automotive_platform_msgs::Gear::DRIVE; } // lamp/light cannot be obtain from SSC diff --git a/drivers/ymc/CMakeLists.txt b/drivers/ymc/CMakeLists.txt index a2fa86f1327..ab249ef5366 100644 --- a/drivers/ymc/CMakeLists.txt +++ b/drivers/ymc/CMakeLists.txt @@ -1,25 +1,18 @@ cmake_minimum_required(VERSION 2.8.3) project(ymc) +find_package(autoware_build_flags REQUIRED) find_package( catkin REQUIRED COMPONENTS - autoware_build_flags - roscpp - geometry_msgs - rosconsole - autoware_msgs - ds4_msgs - ros_observer + autoware_msgs + ds4_msgs + geometry_msgs + ros_observer + rosconsole + roscpp ) -catkin_package( - CATKIN_DEPENDS - roscpp - geometry_msgs - rosconsole - autoware_msgs - ds4_msgs -) +catkin_package() IF("${CMAKE_SYSTEM_PROCESSOR}" STREQUAL "aarch64") set(LIB_ARCH _aarch64) @@ -48,15 +41,18 @@ target_link_libraries(g30esli_interface ) install(TARGETS g30esli_interface - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) install(DIRECTORY scripts/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts - USE_SOURCE_PERMISSIONS - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts + USE_SOURCE_PERMISSIONS + PATTERN ".svn" EXCLUDE +) diff --git a/drivers/ymc/include/g30esli_interface.h b/drivers/ymc/include/g30esli_interface.h index 8a7e5c0b665..9531bde3436 100644 --- a/drivers/ymc/include/g30esli_interface.h +++ b/drivers/ymc/include/g30esli_interface.h @@ -45,6 +45,7 @@ class G30esliInterface // ros param std::string device_; bool use_ds4_; + bool enable_reverse_motion_; double steering_offset_deg_; double command_timeout_; double brake_threshold_; diff --git a/drivers/ymc/include/g30esli_ros.h b/drivers/ymc/include/g30esli_ros.h index c58d669b88c..08584dab5af 100644 --- a/drivers/ymc/include/g30esli_ros.h +++ b/drivers/ymc/include/g30esli_ros.h @@ -26,6 +26,7 @@ #include #include #include +#include #include #include "cansend.h" diff --git a/drivers/ymc/launch/g30esli_interface.launch b/drivers/ymc/launch/g30esli_interface.launch index 4ecae1c1c09..ad89a4448a0 100644 --- a/drivers/ymc/launch/g30esli_interface.launch +++ b/drivers/ymc/launch/g30esli_interface.launch @@ -5,6 +5,7 @@ + @@ -12,6 +13,7 @@ + diff --git a/drivers/ymc/node/g30esli_interface/g30esli_interface.cpp b/drivers/ymc/node/g30esli_interface/g30esli_interface.cpp index 02476292f40..3240c14445e 100644 --- a/drivers/ymc/node/g30esli_interface/g30esli_interface.cpp +++ b/drivers/ymc/node/g30esli_interface/g30esli_interface.cpp @@ -22,6 +22,7 @@ G30esliInterface::G30esliInterface() : nh_(), private_nh_("~") // rosparam private_nh_.param("device", device_, "can0"); private_nh_.param("use_ds4", use_ds4_, false); + private_nh_.param("enable_reverse_motion", enable_reverse_motion_, false); private_nh_.param("steering_offset_deg", steering_offset_deg_, 0.0); private_nh_.param("command_timeout", command_timeout_, 1000); private_nh_.param("brake_threshold", brake_threshold_, 0.1); @@ -68,6 +69,11 @@ G30esliInterface::~G30esliInterface() // generate command by autoware void G30esliInterface::vehicleCmdCallback(const autoware_msgs::VehicleCmdConstPtr& msg) { + if (!enable_reverse_motion_ && msg->ctrl_cmd.linear_velocity < 0) + { + ROS_WARN("Command velocity is negative, but enable reverse motion is false..."); + return; + } g30esli_ros_.updateAutoCommand(*msg, engage_, steering_offset_deg_, brake_threshold_); } diff --git a/drivers/ymc/node/g30esli_interface/g30esli_ros.cpp b/drivers/ymc/node/g30esli_interface/g30esli_ros.cpp index 4603be665e4..ba73d6eaf1e 100644 --- a/drivers/ymc/node/g30esli_interface/g30esli_ros.cpp +++ b/drivers/ymc/node/g30esli_interface/g30esli_ros.cpp @@ -40,7 +40,7 @@ void G30esliROS::updateAutoCommand(const autoware_msgs::VehicleCmd& msg, const b // speed double speed_kmph = msg.ctrl_cmd.linear_velocity * 3.6; // [m/s] -> [km/h] - cmd.command.speed = (engage && !reset_command_) ? speed_kmph : 0.0; + cmd.command.speed = (engage && !reset_command_) ? fabs(speed_kmph) : 0.0; // steer double steering_angle_deg = msg.ctrl_cmd.steering_angle / M_PI * 180.0; // [rad] -> [deg] @@ -64,19 +64,28 @@ void G30esliROS::updateAutoCommand(const autoware_msgs::VehicleCmd& msg, const b } // shift - if (msg.gear == 1) + bool is_valid_gear = (msg.gear_cmd.gear == autoware_msgs::Gear::DRIVE && msg.ctrl_cmd.linear_velocity >= 0.0) || + (msg.gear_cmd.gear == autoware_msgs::Gear::REVERSE && msg.ctrl_cmd.linear_velocity <= 0.0); + if (is_valid_gear) { - cmd.command.shift = G30ESLI_SHIFT_DRIVE; - } - else if (msg.gear == 2) - { - cmd.command.shift = G30ESLI_SHIFT_REVERSE; + if (msg.gear_cmd.gear == autoware_msgs::Gear::DRIVE) + { + cmd.command.shift = G30ESLI_SHIFT_DRIVE; + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::REVERSE) + { + cmd.command.shift = G30ESLI_SHIFT_REVERSE; + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::NEUTRAL) + { + cmd.command.shift = G30ESLI_SHIFT_NEUTRAL; + } } - else if (msg.gear == 4) + else { cmd.command.shift = G30ESLI_SHIFT_NEUTRAL; } - + // flasher if (msg.lamp_cmd.l == 0 && msg.lamp_cmd.r == 0) { @@ -162,9 +171,10 @@ void G30esliROS::receiveStatus(const double& steering_offset_deg) g30esli_.readStatus(status_.status); ros::Time now = ros::Time::now(); + double sign = status_.status.shift != G30ESLI_SHIFT_REVERSE ? 1.0 : -1.0; // update twist - double lv = status_.status.speed.actual / 3.6; // [km/h] -> [m/s] + double lv = sign * status_.status.speed.actual / 3.6; // [km/h] -> [m/s] double th = (-status_.status.steer.actual - steering_offset_deg) * M_PI / 180.0; // [deg] -> [rad] double az = std::tan(th) * lv / G30ESLI_WHEEL_BASE; // [rad] -> [rad/s] current_twist_.header.frame_id = "base_link"; @@ -190,19 +200,19 @@ void G30esliROS::receiveStatus(const double& steering_offset_deg) // gearshift if (status_.status.shift == G30ESLI_SHIFT_DRIVE) { - vehicle_status_.gearshift = 1; + vehicle_status_.current_gear.gear = autoware_msgs::Gear::DRIVE; } else if (status_.status.shift == G30ESLI_SHIFT_REVERSE) { - vehicle_status_.gearshift = 2; + vehicle_status_.current_gear.gear = autoware_msgs::Gear::REVERSE; } else if (status_.status.shift == G30ESLI_SHIFT_NEUTRAL) { - vehicle_status_.gearshift = 4; + vehicle_status_.current_gear.gear = autoware_msgs::Gear::NEUTRAL; } // speed - vehicle_status_.speed = status_.status.speed.actual; // [kmph] + vehicle_status_.speed = sign * status_.status.speed.actual; // [kmph] // drivepedal vehicle_status_.drivepedal = status_.status.override.accel; // [-] @@ -265,7 +275,7 @@ void G30esliROS::checkRestart(const MODE& mode) Command& cmd = commands_[(int)mode]; bool is_positive_command = (cmd.command.speed > 0.0); - bool is_stopped = (vehicle_status_.speed < 0.01); + bool is_stopped = (fabs(vehicle_status_.speed) < 0.01); if (!reset_command_) { diff --git a/drivers/ymc/package.xml b/drivers/ymc/package.xml index 0d672d0d52c..42ba3ccf828 100644 --- a/drivers/ymc/package.xml +++ b/drivers/ymc/package.xml @@ -14,10 +14,10 @@ autoware_msgs ds4_msgs geometry_msgs + ros_observer rosconsole roscpp std_msgs - ros_observer can-utils diff --git a/lanelet2/.clang-tidy b/lanelet2/.clang-tidy index e85b9119b19..3c6c052f86e 100644 --- a/lanelet2/.clang-tidy +++ b/lanelet2/.clang-tidy @@ -1,5 +1,5 @@ # clang tidy file installed by mrt_tools. Do not modify: This file will be overwritten. -Checks: '-*,mrt*,clang-analyzer-core*,clang-analyzer-deadcode*,clang-analyzer-unix*,clang-analyzer-cplusplus*,-clang-analyzer-cplusplus.NewDeleteLeaks,cppcoreguidelines-*,-cppcoreguidelines-pro-bounds-array-to-pointer-decay,-cppcoreguidelines-owning-memory,-cppcoreguidelines-pro-type-vararg,google-explicit-constructor,google-global-names-in-headers,google-readability-casting,google-readability-namespace-comments,google-runtime-int,bugprone-*,-bugprone-exception-escape,performance-*,readability-*,modernize-*,misc-*' +Checks: '-*,mrt*,bugprone-*,-bugprone-exception-escape,clang-analyzer-apiModeling*,clang-analyzer-core*,-clang-analyzer-core.UndefinedBinaryOperatorResult,clang-analyzer-deadcode*,clang-analyzer-unix*,clang-analyzer-cplusplus*,-clang-analyzer-cplusplus.NewDelete,cppcoreguidelines-*,-cppcoreguidelines-pro-bounds-array-to-pointer-decay,-cppcoreguidelines-owning-memory,-cppcoreguidelines-pro-type-vararg,-cppcoreguidelines-avoid-magic-numbers,-cppcoreguidelines-avoid-c-arrays,google-explicit-constructor,google-global-names-in-headers,google-readability-casting,google-readability-namespace-comments,google-global-names-in-headers,google-build-namespaces,performance-*,readability-*,-readability-uppercase-literal-suffix,-readability-magic-numbers,modernize-*,-modernize-use-trailing-return-type,-modernize-use-nodiscard,-modernize-concat-nested-namespaces,-modernize-avoid-c-arrays,misc-*,-misc-non-private-member-variables-in-classes' HeaderFilterRegex: '^(?!\/usr)(?!\/opt).*\/src\/.*' AnalyzeTemporaryDtors: false CheckOptions: @@ -142,4 +142,8 @@ CheckOptions: value: lower_case - key: readability-identifier-naming.InlineNamespaceCase value: lower_case + + + - key: readability-identifier-naming.IgnoreMacros + value: 1 diff --git a/lanelet2/.gitlab-ci.yml b/lanelet2/.gitlab-ci.yml index a0191267187..477014127b7 100644 --- a/lanelet2/.gitlab-ci.yml +++ b/lanelet2/.gitlab-ci.yml @@ -1,28 +1,11 @@ -variables: - GIT_STRATEGY: none - LANELET2_PACKAGES: lanelet2_core lanelet2_io lanelet2_projection lanelet2_python lanelet2_routing lanelet2_traffic_rules lanelet2_validation -# Cache build results between building and testing -cache: - paths: - - catkin_ws/ -stages: - - build - - test - - deploy - -# Prepare workspace and checkout the code. This will be executed before every stage -before_script: - # Environment variablen setzen - - export SHELL="/bin/bash" - # Prepare workspace (in folder catkin_ws) - - sudo apt-get update && sudo apt-get upgrade -y - - mrt ci prepare $CI_PROJECT_NAME -c $CI_COMMIT_SHA - - cd catkin_ws - # set current branch name to branch management - - mrt ws branches set $CI_COMMIT_REF_NAME +#version=1.6 +include: + - project: 'pub/mrt_build_config' + ref: master + file: '/ci_templates/default_catkin_project.yml' # Tests installing on a plain system without mrt stuff using the provided Docker image -.build_docker: &build_docker +.build_docker: stage: build image: docker:18.09 only: @@ -33,162 +16,65 @@ before_script: services: - docker:18.09-dind script: - - export IMAGE_NAME=$CI_REGISTRY_IMAGE:$DISTRIBUTION + - export IMAGE_NAME=$CI_REGISTRY_IMAGE:$TAG - docker login -u $CI_REGISTRY_USER -p $CI_REGISTRY_PASSWORD $CI_REGISTRY - - docker build --cache-from $IMAGE_NAME -t $IMAGE_NAME --build-arg=DISTRIBUTION=$DISTRIBUTION --build-arg=ROS_DISTRO=$ROS_DISTRO . + - docker build --cache-from $IMAGE_NAME -t $IMAGE_NAME --build-arg=DISTRIBUTION=$DISTRIBUTION --build-arg=ROS_DISTRO=$ROS_DISTRO --build-arg ROS=$ROS . - docker login -u $CI_REGISTRY_USER -p $CI_REGISTRY_PASSWORD $CI_REGISTRY - if [ "$CI_COMMIT_REF_NAME" = "master" ]; then docker push $IMAGE_NAME; fi build_docker_xenial: - <<: *build_docker + extends: .build_docker variables: DISTRIBUTION: "16.04" + TAG: "16.04" ROS_DISTRO: kinetic DOCKER_DRIVER: overlay2 GIT_STRATEGY: fetch + ROS: ros build_docker_bionic: - <<: *build_docker + extends: .build_docker variables: DISTRIBUTION: "18.04" + TAG: "18.04" ROS_DISTRO: melodic DOCKER_DRIVER: overlay2 GIT_STRATEGY: fetch + ROS: ros -build_mrt: - stage: build - only: [branches, tags, merge_requests] # means "always" - script: - # Build project and resolve deps at the same time in debug mode - - mrt catkin build -s -rd --debug --default_yes --no-status $CI_PROJECT_NAME - # generate documentation - - mrt doc clean && mrt doc build - - cp -r build_debug/workspace_doc_* ../doxygen - # make doxygen documentation available in gitlab - artifacts: - name: doxygen - paths: - - doxygen - expire_in: 6 mos - -general_code_quality: - stage: build - only: [master, merge_requests] - allow_failure: true - cache: {} - image: - name: ${CI_REGISTRY}/mrt/misc/mrt_build/gl_codequality - entrypoint: [""] +# disabled as long as https://github.com/catkin/catkin_tools/issues/594 persists +.build_docker_focal: + extends: .build_docker variables: + DISTRIBUTION: "20.04" + TAG: "20.04" + ROS_DISTRO: noetic + DOCKER_DRIVER: overlay2 GIT_STRATEGY: fetch - SOURCE_CODE: $CI_PROJECT_DIR - CODECLIMATE_DEBUG: "True" - before_script: [] - script: - - /run.sh . - - chmod a+rw gl-code-quality-report.json - artifacts: - paths: [gl-code-quality-report.json] - -.test: &test_job - stage: test - coverage: '/lines......: \d+.\d+\%/' - only: [branches, tags, merge_requests] # means "always" - cache: - paths: - - catkin_ws/ - policy: pull - script: - # Build code again, in case caching didn't work - - mrt catkin build -s -rd --debug --default_yes --no-status $PACKAGE - # Run tests - - source devel_debug/setup.bash - - mrt catkin run_tests --no-status $PACKAGE --no-deps - # Summarize results - - catkin_test_results --verbose build_debug/$PACKAGE - - mkdir ../coverage - - cp -r build_debug/$PACKAGE/coverage ../coverage/$PACKAGE || true - # make coverage information available in gitlab - artifacts: - name: coverage - paths: - - coverage - expire_in: 6 mos - reports: - junit: catkin_ws/build_debug/$PACKAGE/test_results/$PACKAGE/*.xml - -test_lanelet2_core: - <<: *test_job - variables: - PACKAGE: lanelet2_core - -test_lanelet2_io: - <<: *test_job - variables: - PACKAGE: lanelet2_io - -test_lanelet2_projection: - <<: *test_job - variables: - PACKAGE: lanelet2_projection - -test_lanelet2_python: - <<: *test_job - variables: - PACKAGE: lanelet2_python + ROS: ros -test_lanelet2_routing: - <<: *test_job +build_docker_ros2: + extends: .build_docker variables: - PACKAGE: lanelet2_routing - -test_lanelet2_traffic_rules: - <<: *test_job - variables: - PACKAGE: lanelet2_traffic_rules - -test_lanelet2_validation: - <<: *test_job - variables: - PACKAGE: lanelet2_validation + DISTRIBUTION: "18.04" + TAG: ros2 + ROS_DISTRO: dashing + DOCKER_DRIVER: overlay2 + GIT_STRATEGY: fetch + ROS: ros2 -test_lanelet2_examples: - <<: *test_job +build_conan: + stage: build + image: ubuntu:20.04 variables: - PACKAGE: lanelet2_examples - -code_quality: - allow_failure: true - only: [master, merge_requests] - cache: - paths: - - catkin_ws/ - policy: pull - artifacts: - paths: [gl-code-quality-report.json] - script: - # Build code again, in case caching didn't work - - mrt catkin build -s -rd --debug --default_yes --no-status $CI_PROJECT_NAME - - source devel_debug/setup.bash - - cd src/$CI_PROJECT_NAME - - rm codeclimate.json || true - - cp ../../../gl-code-quality-report.json codeclimate.json || true - - mrt ci codequality $LANELET2_PACKAGES - - cp codeclimate.json ../../../gl-code-quality-report.json - - -pages: - before_script: [] - stage: deploy - script: - # everything in the public folder will be available as website - - mkdir public - - cp -r coverage public/ || true - - cp -r doxygen public/ - artifacts: - paths: - - public + GIT_STRATEGY: fetch only: - # only execute for master branch - master - + - merge_requests + before_script: [] + script: + - apt update && env DEBIAN_FRONTEND=noninteractive apt install -y python3-pip git cmake python3-dev + - pip3 install conan catkin_pkg numpy + - conan remote add bincrafters https://api.bintray.com/conan/bincrafters/public-conan + - conan source . + - conan create . lanelet2/stable --build=missing diff --git a/lanelet2/.travis.yml b/lanelet2/.travis.yml index 953855408fc..d26ae4d015b 100644 --- a/lanelet2/.travis.yml +++ b/lanelet2/.travis.yml @@ -2,23 +2,50 @@ sudo: required services: docker -# Build this with both 18.04 and 16.04 -matrix: +# Start the lanelet2 docker container and test +_ros_build: &ros_build + script: + - docker run -dit --name lanelet2 -v `pwd`:/home/developer/workspace/src/lanelet2 --rm lanelet2_deps bash + - docker exec -ti lanelet2 /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && catkin build --no-status" + - docker exec -ti lanelet2 catkin build --catkin-make-args run_tests -- --no-status + - docker exec -ti lanelet2 /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && catkin_test_results --verbose" + - docker stop lanelet2 + +_ros2_build: &ros2_build + script: + - docker run -dit --name lanelet2 -v `pwd`:/home/developer/workspace/src/lanelet2 --rm lanelet2_deps bash + - docker exec -ti lanelet2 /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && colcon build --symlink-install" + - docker exec -ti lanelet2 colcon test + - docker stop lanelet2 + + +# Build this with the distributions we support +jobs: include: - - env: + - name: Bionic ROS1 + env: - DISTRIBUTION=18.04 - ROS_DISTRO=melodic - - env: + - ROS=ros + <<: *ros_build + - name: Xenial ROS1 + env: - DISTRIBUTION=16.04 - ROS_DISTRO=kinetic + - ROS=ros + <<: *ros_build + - name: Bionic ROS2 + env: + - DISTRIBUTION=18.04 + - ROS_DISTRO=eloquent + - ROS=ros2 + <<: *ros2_build + - name: Focal ROS2 + env: + - DISTRIBUTION=20.04 + - ROS_DISTRO=foxy + - ROS=ros2 + <<: *ros2_build # setup the container with dependencies -install: docker build --target lanelet2_deps -t lanelet2_deps --build-arg=DISTRIBUTION=$DISTRIBUTION --build-arg=ROS_DISTRO=$ROS_DISTRO . - -# start the container with the code, build and test -script: -- docker run -dit --name lanelet2 -v `pwd`:/home/developer/workspace/src/lanelet2 --rm lanelet2_deps bash -- docker exec -ti lanelet2 /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && catkin build --no-status" -- docker exec -ti lanelet2 catkin build --catkin-make-args run_tests -- --no-status -- docker exec -ti lanelet2 /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && catkin_test_results --verbose" -- docker stop lanelet2 +install: docker build --target lanelet2_deps -t lanelet2_deps --build-arg=DISTRIBUTION=$DISTRIBUTION --build-arg=ROS_DISTRO=$ROS_DISTRO --build-arg ROS=$ROS . diff --git a/lanelet2/CODEOWNERS b/lanelet2/CODEOWNERS index 4ff5fc880ee..55de334c19f 100644 --- a/lanelet2/CODEOWNERS +++ b/lanelet2/CODEOWNERS @@ -1 +1,3 @@ -* fabian.poggenhans@kit.edu \ No newline at end of file +* fabian.poggenhans@kit.edu frank.bieder@kit.edu +lanelet2_projection/* jan-hendrik.pauls@kit.edu +lanelet2_matching/* maximilian.naumann@kit.edu diff --git a/lanelet2/Dockerfile b/lanelet2/Dockerfile index 34290f9bff8..10f72d82d8e 100644 --- a/lanelet2/Dockerfile +++ b/lanelet2/Dockerfile @@ -2,50 +2,71 @@ ARG DISTRIBUTION=18.04 FROM ubuntu:${DISTRIBUTION} AS lanelet2_deps ARG ROS_DISTRO=melodic +ARG ROS=ros +SHELL ["/bin/bash", "-c"] # basics -RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y \ - bash-completion \ +RUN if [ "${ROS_DISTRO}" = "melodic" ] || [ "${ROS_DISTRO}" = "kinetic" ]; \ + then export PY_VERSION=python; \ + else export PY_VERSION=python3; \ + fi; \ + apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y \ + bash-completion \ build-essential \ - curl \ + curl \ git \ cmake \ - ipython \ - keyboard-configuration \ - locales \ + i${PY_VERSION} \ + keyboard-configuration \ + locales \ lsb-core \ nano \ - python-dev \ + lib${PY_VERSION}-dev \ software-properties-common \ sudo \ - wget \ - && locale-gen en_US.UTF-8 \ - && apt-get clean && rm -rf /var/lib/apt/lists/* + wget \ + && locale-gen en_US.UTF-8 \ + && apt-get clean && rm -rf /var/lib/apt/lists/* # locale ENV LANG=en_US.UTF-8 \ LANGUAGE=en_US:en \ LC_ALL=en_US.UTF-8 \ - ROS_DISTRO=${ROS_DISTRO} + ROS_DISTRO=${ROS_DISTRO} \ + ROS=${ROS} # install ROS -RUN echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list \ +RUN echo "deb http://packages.ros.org/${ROS}/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list \ && (apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 \ || apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654) # dependencies for lanelet2 -RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y \ +RUN if [ "${ROS_DISTRO}" = "melodic" ] || [ "${ROS_DISTRO}" = "kinetic" ]; \ + then export PY_VERSION=python; \ + else export PY_VERSION=python3; \ + fi; \ + apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y \ + libgtest-dev \ libboost-all-dev \ libeigen3-dev \ libgeographic-dev \ libpugixml-dev \ - libpython-dev \ libboost-python-dev \ - python-catkin-tools \ - ros-$ROS_DISTRO-catkin \ - ros-$ROS_DISTRO-rosbash \ - ros-$ROS_DISTRO-ros-environment # missing dep of rospack on xenial \ - && apt-get clean && rm -rf /var/lib/apt/lists/* + ${PY_VERSION}-rospkg \ + ros-$ROS_DISTRO-ros-environment \ + && apt-get clean && rm -rf /var/lib/apt/lists/* + +# ros version specific dependencies +RUN if [ "${ROS_DISTRO}" = "melodic" ] || [ "${ROS_DISTRO}" = "kinetic" ]; \ + then export PY_VERSION=python; \ + else export PY_VERSION=python3; \ + fi; \ + if [ "$ROS" = "ros" ]; \ + then export ROS_DEPS="ros-$ROS_DISTRO-catkin ros-$ROS_DISTRO-rosbash ${PY_VERSION}-catkin-tools"; \ + else export ROS_DEPS="ros-$ROS_DISTRO-ament-cmake python3-colcon-ros ros-$ROS_DISTRO-ros2cli"; \ + fi; \ + apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y $ROS_DEPS \ + && apt-get clean && rm -rf /var/lib/apt/lists/* # create a user RUN useradd --create-home --groups sudo --shell /bin/bash developer \ @@ -60,17 +81,21 @@ ENV HOME /home/developer WORKDIR /home/developer/workspace RUN sudo chown -R developer:developer /home/developer \ - && echo "export ROS_HOSTNAME=localhost" >> /home/developer/.bashrc \ + && echo "export ROS_HOSTNAME=localhost" > /home/developer/.bashrc \ && echo "source /opt/ros/$ROS_DISTRO/setup.bash" >> /home/developer/.bashrc \ - && echo "source /home/developer/workspace/devel/setup.bash" >> /home/developer/.bashrc + && echo "source /home/developer/workspace/devel/setup.bash || true" >> /home/developer/.bashrc # setup workspace, add dependencies -RUN cd /home/developer/workspace \ - && /bin/bash -c "source /home/developer/.bashrc && catkin init && catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo" \ +RUN if [ "$ROS" = "ros" ]; \ + then export CATKIN_INIT="source /home/developer/.bashrc && catkin init && catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo"; \ + fi; \ + cd /home/developer/workspace \ + && mkdir -p /home/developer/workspace/src \ + && /bin/bash -c "$CATKIN_INIT" \ && git clone https://github.com/KIT-MRT/mrt_cmake_modules.git /home/developer/workspace/src/mrt_cmake_modules # second stage: get the code and build the image -FROM lanelet2_deps As lanelet2 +FROM lanelet2_deps AS lanelet2 # bring in the code COPY --chown=developer:developer . /home/developer/workspace/src/lanelet2 @@ -79,5 +104,9 @@ COPY --chown=developer:developer . /home/developer/workspace/src/lanelet2 RUN git -C /home/developer/workspace/src/mrt_cmake_modules pull # build -RUN /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && catkin build --no-status" +RUN if [ "$ROS" = "ros" ]; \ + then export BUILD_CMD="catkin build --no-status"; \ + else export BUILD_CMD="colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo"; \ + fi; \ + /bin/bash -c "source /opt/ros/$ROS_DISTRO/setup.bash && env && echo $ROS && $BUILD_CMD" diff --git a/lanelet2/README.md b/lanelet2/README.md index aa08ce5c45b..62803232c0a 100644 --- a/lanelet2/README.md +++ b/lanelet2/README.md @@ -20,6 +20,7 @@ Features: - **Python** bindings for the whole C++ interface - **Boost Geometry** support for all thinkable kinds of geometry calculations on map primitives - Released under the [**BSD 3-Clause license**](LICENSE) +- Support for **ROS1, ROS2, Docker and Conan** (see instructions below) ![](lanelet2_core/doc/images/lanelet2_example_image.png) @@ -36,6 +37,12 @@ You can find more documentation in the individual packages and in doxygen commen ## Installation +### Within ROS +Lanelet2 has been released for ROS. Just install `ros-[distribution]-lanelet2`, e.g.: +``` +sudo apt install ros-noetic-lanelet2 +``` + ### Using Docker There is a Docker container from which you can test things out: @@ -52,9 +59,9 @@ The docker image contains a link to your local lanelet2, so you can work and see In case you want to build it in your own way (without the above Docker image) use these instructions. -Lanelet2 uses [Catkin](https://catkin-tools.readthedocs.io/en/latest/index.html) for building and is targeted towards Linux. +Lanelet2 relies mainly on [Catkin](https://catkin-tools.readthedocs.io/en/latest/index.html) for building and is targeted towards Linux. -At least C++14 is required. +At least **C++14** is required. ### Dependencies Besides [Catkin](https://catkin-tools.readthedocs.io/en/latest/index.html), the dependencies are @@ -67,12 +74,18 @@ Besides [Catkin](https://catkin-tools.readthedocs.io/en/latest/index.html), the * `rosbash` (for lanelet2_examples) For Ubuntu, the steps are the following: -* [Set up ROS](http://wiki.ros.org/ROS/Installation), and install at least `rospack` and `catkin` (e.g. `ros-melodic-rospack` and `ros-melodic-catkin`). +* [Set up ROS](http://wiki.ros.org/ROS/Installation), and install at least `rospack`, `catkin` and `mrt_cmake_modules` (e.g. `ros-melodic-rospack`, `ros-melodic-catkin`, `ros-melodic-mrt-cmake-modules`): +``` +sudo apt-get install ros-melodic-rospack ros-melodic-catkin ros-melodic-mrt-cmake-modules +``` + * Install the dependencies above: ```bash sudo apt-get install libboost-dev libeigen3-dev libgeographic-dev libpugixml-dev libpython-dev libboost-python-dev python-catkin-tools ``` +**On 16.04 and below**, `mrt_cmake_modules` is not available in ROS and you have to clone it into your workspace (`git clone https://github.com/KIT-MRT/mrt_cmake_modules.git`). + ### Building As usual with Catkin, after you have sourced the ros installation, you have to create a workspace and clone all required packages there. Then you can build. ```shell @@ -81,7 +94,6 @@ mkdir catkin_ws && cd catkin_ws && mkdir src catkin init catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo # build in release mode (or whatever you prefer) cd src -git clone https://github.com/KIT-MRT/mrt_cmake_modules.git git clone https://github.com/fzi-forschungszentrum-informatik/lanelet2.git cd .. catkin build @@ -89,6 +101,31 @@ catkin build If unsure, see the [Dockerfile](Dockerfile) or the [travis build log](https://travis-ci.org/fzi-forschungszentrum-informatik/Lanelet2). It shows the the full installation process, with subsequent build and test based on a docker image with a clean ubuntu installation. +### Manual, experimental installation using conan +For non-catkin users, we also offer a conan based install proces. Its experimental and might not work on all platforms, expecially Windows. +Since conan handles installing all C++ dependencies, all you need is a cloned repository, conan itself and a few python dependencies: +```bash +pip install conan catkin_pkg numpy +conan remote add bincrafters https://api.bintray.com/conan/bincrafters/public-conan # requried for python bindings +git clone https://github.com/fzi-forschungszentrum-informatik/lanelet2.git +cd lanelet2 +``` + +From here, just use the default conan build/install procedure, e.g.: +```bash +conan source . +conan create . lanelet2/stable --build=missing +``` +Different from the conan defaults, we build lanelet2 and boost as shared libraries, because otherwise the lanelet2's plugin mechanisms as well as boost::python will fail. E.g. loading maps will not be possible and the python API will not be usable. + +To be able to use the python bindings, you have to make conan export the PYTHONPATH for lanelet2: +```bash +conan install lanelet2/0.0.0@lanelet2/stable --build=missing -g virtualenv # replace 0.0.0 with the version shown by conan +source activate.sh +python -c "import lanelet2" # or whatever you want to do +source deactivate.sh +``` + ### Python3 The python bindings are build for your default python installation by default (which currently is python2 on most systems). To build for python3 instead of python2, create a python3 virtualenv before initializing the workspace with `catkin init`. The command `python` should point to `python3`. @@ -108,6 +145,7 @@ Examples and common use cases in both C++ and Python can be found [here](lanelet * **lanelet2_projection** for projecting maps from WGS84 (lat/lon) to local metric coordinates * **lanelet2_routing** implements the routing graph for routing or reachable set or queries as well as collision checking * **lanelet2_maps** provides example maps and functionality to visualize and modify them easily in JOSM +* **lanelet2_matching** provides functions to determine in which lanelet an object is/could be currently located * **lanelet2_python** implements the python interface for lanelet2 * **lanelet2_validation** provides checks to ensure a valid lanelet2 map * **lanelet2_examples** contains tutorials for working with Lanelet2 in C++ and Python diff --git a/lanelet2/conanfile.py b/lanelet2/conanfile.py new file mode 100644 index 00000000000..0f50f0b39f2 --- /dev/null +++ b/lanelet2/conanfile.py @@ -0,0 +1,135 @@ +import os +import sys +import xml.etree.ElementTree as ET +from conans import ConanFile, CMake, tools +from distutils.sysconfig import get_python_lib + +find_mrt_cmake=""" +set(mrt_cmake_modules_FOUND True) +include(${CMAKE_CURRENT_LIST_DIR}/mrt_cmake_modules-extras.cmake) +""" + +cmake_lists=""" +cmake_minimum_required(VERSION 3.5) +project(lanelet2) +if(POLICY CMP0079) + cmake_policy(SET CMP0079 NEW) # allows to do target_link_libraries on targets from subdirs +endif() +set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}) +set(BoostPython_FOUND Yes) +include(${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) +conan_basic_setup(SKIP_STD) + +# hint to gtest +set(MRT_GTEST_DIR ${CMAKE_CURRENT_LIST_DIR}) +enable_testing() + +# declare dependencies +include_directories(lanelet2_core/include lanelet2_io/include lanelet2_projection/include lanelet2_traffic_rules/include + lanelet2_routing/include lanelet2_validation/include) +add_subdirectory(lanelet2_core) +add_subdirectory(lanelet2_io) +add_subdirectory(lanelet2_projection) +add_subdirectory(lanelet2_traffic_rules) +add_subdirectory(lanelet2_routing) +add_subdirectory(lanelet2_validation) +add_subdirectory(lanelet2_examples) +add_subdirectory(lanelet2_python) +add_subdirectory(lanelet2_maps) +add_subdirectory(lanelet2_matching) +# declare dependencies +target_link_libraries(lanelet2_io PUBLIC lanelet2_core) +target_link_libraries(lanelet2_projection PUBLIC lanelet2_core) +target_link_libraries(lanelet2_traffic_rules PUBLIC lanelet2_core) +target_link_libraries(lanelet2_routing PUBLIC lanelet2_core lanelet2_traffic_rules) +target_link_libraries(lanelet2_matching PUBLIC lanelet2_core lanelet2_traffic_rules lanelet2_io lanelet2_projection lanelet2_maps) +target_link_libraries(lanelet2_validation PUBLIC lanelet2_core lanelet2_io lanelet2_routing lanelet2_traffic_rules lanelet2_projection) +target_link_libraries(lanelet2_examples_compiler_flags INTERFACE lanelet2_core lanelet2_io lanelet2_routing lanelet2_traffic_rules lanelet2_projection) +target_link_libraries(lanelet2_python_compiler_flags INTERFACE lanelet2_core lanelet2_io lanelet2_routing lanelet2_traffic_rules lanelet2_projection lanelet2_matching) +""" + +def read_version(): + package = ET.parse('lanelet2_core/package.xml') + return package.find('version').text + +def get_py_version(): + return "{}.{}".format(sys.version_info.major, sys.version_info.minor) + +def get_py_exec(): + return "python3" if sys.version_info.major == 3 else "python" + +class Lanelet2Conan(ConanFile): + name = "lanelet2" + version = read_version() + settings = "os", "compiler", "build_type", "arch" + generators = "cmake" + license = "BSD" + url = "https://github.com/fzi-forschungszentrum-informatik/lanelet2" + description = "Map handling framework for automated driving" + options = {"shared": [True, False], "fPIC": [True]} + default_options = {"shared": True, "fPIC": True, "boost:shared": True, "boost:python_version": get_py_version(), "boost:without_python": False, "python_dev_config:python": get_py_exec()} + + requires = ("python_dev_config/0.6@bincrafters/stable", + "boost/1.75.0", + "eigen/3.3.9", + "geographiclib/1.50.1", + "pugixml/1.11") + + exports_sources = "*" + exports = "lanelet2_core/package.xml" + + proj_list = [ + 'lanelet2_core', + 'lanelet2_io', + 'lanelet2_matching', + 'lanelet2_projection', + 'lanelet2_traffic_rules', + 'lanelet2_routing', + 'lanelet2_validation' + ] + + def _configure_cmake(self): + cmake = CMake(self) + cmake.definitions["PYTHON_VERSION"] = get_py_version() + cmake.definitions["MRT_CMAKE_ENV"] = "sh;env;PYTHONPATH=" + os.path.join(self.package_folder, self._pythonpath()) + cmake.configure() + return cmake + + def _pythonpath(self): + return os.path.relpath(get_python_lib(prefix=self.package_folder), start=self.package_folder) + + def source(self): + if not os.path.exists("mrt_cmake_modules"): + self.run("git clone https://github.com/KIT-MRT/mrt_cmake_modules.git") + mrt_cmake_dir = os.path.join(os.getcwd(), "mrt_cmake_modules") + with open("mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.in") as f: + extras = f.read().replace("@DEVELSPACE@", "True").replace("@PROJECT_SOURCE_DIR@", mrt_cmake_dir).replace("@CMAKE_CURRENT_SOURCE_DIR@", mrt_cmake_dir) + with open("mrt_cmake_modules-extras.cmake", "w") as f: + f.write(extras) + with open("Findmrt_cmake_modules.cmake", "w") as f: + f.write(find_mrt_cmake) + with open("CMakeLists.txt", "w") as f: + f.write(cmake_lists) + if not os.path.exists("googletest"): + self.run("git clone https://github.com/google/googletest.git") + + def build(self): + cmake = self._configure_cmake() + cmake.build() + cmake.test() # not working as long as the pythonpath is not adapted first + cmake.install() + + def package(self): + cmake = self._configure_cmake() + cmake.install() + + def package_info(self): + self.cpp_info.libs = list(reversed(self.proj_list)) + libpath = os.path.join(self.package_folder, "lib") + boost_libpaths = self.deps_cpp_info["boost"].lib_paths + execs = ("lanelet2_examples", "lanelet2_validation", "lanelet2_python") + binpaths = [os.path.join(self.package_folder, "lib", libname) for libname in execs] + self.env_info.PYTHONPATH.append(os.path.join(self.package_folder, self._pythonpath())) + self.env_info.LD_LIBRARY_PATH += [libpath] + boost_libpaths + self.env_info.DYLD_LIBRARY_PATH += [libpath] + boost_libpaths + self.env_info.PATH += binpaths diff --git a/lanelet2/lanelet2/CHANGELOG.rst b/lanelet2/lanelet2/CHANGELOG.rst new file mode 100644 index 00000000000..4206dff0967 --- /dev/null +++ b/lanelet2/lanelet2/CHANGELOG.rst @@ -0,0 +1,27 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2 +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ +* Add missing dependency to ros_environment +* Contributors: Fabian Poggenhans + +1.1.0 (2020-09-06) +------------------ +* lanelet2 is now no longer a metapackage +* Include ROS2 into CI scripts +* Add experimental support for building with colcon on ros2 and ament_cmake +* Updating package.xml files to format 3. +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Add changelogs +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Initial commit +* Contributors: Fabian Poggenhans diff --git a/lanelet2/lanelet2/CMakeLists.txt b/lanelet2/lanelet2/CMakeLists.txt index a3b262a1a56..b26ed0b6945 100644 --- a/lanelet2/lanelet2/CMakeLists.txt +++ b/lanelet2/lanelet2/CMakeLists.txt @@ -1,4 +1,12 @@ cmake_minimum_required(VERSION 2.8.3) project(lanelet2) -find_package(catkin REQUIRED) -catkin_metapackage() +if($ENV{ROS_VERSION} EQUAL 1) + find_package(catkin REQUIRED) + install(FILES package.xml DESTINATION share/lanelet2) +elseif($ENV{ROS_VERSION} EQUAL 2) + if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) + endif() + find_package(ament_cmake_core REQUIRED) + ament_package() +endif() diff --git a/lanelet2/lanelet2/package.xml b/lanelet2/lanelet2/package.xml index 49ee95ec61e..d9a11975afe 100644 --- a/lanelet2/lanelet2/package.xml +++ b/lanelet2/lanelet2/package.xml @@ -1,23 +1,30 @@ - + + + lanelet2 - 0.9.0 + 1.1.1 Meta-package for lanelet2 BSD Fabian Poggenhans Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin + catkin + ament_cmake_core + ros_environment lanelet2_core lanelet2_io lanelet2_traffic_rules lanelet2_routing lanelet2_python lanelet2_maps + lanelet2_matching lanelet2_projection lanelet2_validation lanelet2_examples - + catkin + ament_cmake + diff --git a/lanelet2/lanelet2_core/CHANGELOG.rst b/lanelet2/lanelet2_core/CHANGELOG.rst new file mode 100644 index 00000000000..30c6dfb6f8b --- /dev/null +++ b/lanelet2/lanelet2_core/CHANGELOG.rst @@ -0,0 +1,60 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_core +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Document undocumented parameter in determineCommonLine +* Fix an issue that findNearest returned more results than intended. Add test and clarify doc. + fixes fzi-forschungszentrum-informatik/Lanelet2#142 +* Python functions for distance between CompoundLineStrings and LineStrings +* Removing extra semicolons causing warnings with wpedantic. +* io: Fix random errors in bin serialization when serializing a HybridMap + fixes fzi-forschungszentrum-informatik/Lanelet2#128 +* Add missing std::hash specializations, add __hash__ for python bindings +* Making all includes in lanelet2_core consistent. +* Fix 2d/3d confusions in geometry functions and implemented proper errors. Extended distance3d interface +* Updating package.xml files to format 3. +* Improve and extend determineCommonLine utility function +* Add functionality to create the bounding polygon from a Path +* Remove useless regulatoryElementsAs template function from LineStringOrPolygon +* Apply clang-tidy 10 recommendations +* Contributors: Christian-Eike Framing, Fabian Poggenhans, Johannes Janosovits, Joshua Whitley, Yujie He, harderthan + +1.0.1 (2020-03-24) +------------------ +* Fix build failure if size_t is not unsigned long +* Fix build with boost 1.62 +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add geometry function to compute curvature from three points + Add tests, cleanup the validator that uses it +* Add changelogs +* Format files +* Fix clang-tidy warnings +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Add unittest for findWithin and areas +* Apply clang-tidy fixes +* Add geometry functions convexPartition and triangulate + These handle splitting polygons into convex polygons (or into triangles) +* Improve documentation about Regulatory Elements +* Fix headers missing their include guards +* Fix CompoundLineString2d::rightBound2d() +* Add missing const in Area.h regulatoryElementsAs method +* Add a new class 'LaneletSubmap' that only contains parts of the map and is faster to construct +* Refactored the internal representation of the route. Cleaned up headers that are only supposed to be used internally +* Make sure HybridLineString returns const references instead of copies +* Fix comparison operators for laneletOrArea and LineStringOrPolygon +* Fix constness of search function in lanelet map +* Add a new geometry function that shifts line strings laterally +* Add US traffic signs to JOSM stylesheet and docu +* Add an AllWayStop regulatory element, tests and docs +* Initial commit +* Contributors: Fabian Poggenhans, Florian Kuhnt, Johannes Janosovits, Maximilian Naumann, Piotr Orzechowski diff --git a/lanelet2/lanelet2_core/CMakeLists.txt b/lanelet2/lanelet2_core/CMakeLists.txt index 1612ef118f7..b6c1fa2e20f 100644 --- a/lanelet2/lanelet2_core/CMakeLists.txt +++ b/lanelet2/lanelet2_core/CMakeLists.txt @@ -1,7 +1,8 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_core) + set(MRT_COTIRE_ENABLED 1) set (COTIRE_MINIMUM_NUMBER_OF_TARGET_SOURCES 1) set (COTIRE_MAXIMUM_NUMBER_OF_UNITY_INCLUDES "-j") @@ -86,10 +87,6 @@ mrt_add_library(${PROJECT_NAME} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) -set_target_properties(${PROJECT_NAME} PROPERTIES - CXX_STANDARD 14 - ) - ############# ## Install ## ############# @@ -103,4 +100,4 @@ mrt_install(PROGRAMS scripts FILES res data doc) if (CATKIN_ENABLE_TESTING) mrt_add_tests(test) mrt_add_nosetests(test) -endif() +endif() \ No newline at end of file diff --git a/lanelet2/lanelet2_core/doc/LaneletAndAreaTagging.md b/lanelet2/lanelet2_core/doc/LaneletAndAreaTagging.md index f250559e44a..f77e270f3be 100644 --- a/lanelet2/lanelet2_core/doc/LaneletAndAreaTagging.md +++ b/lanelet2/lanelet2_core/doc/LaneletAndAreaTagging.md @@ -21,11 +21,11 @@ Note that the values in the following table are just the values inferred by defa | **road** | **urban** | A part of a road in urban region | All vehicles and bikes | City speed limit | | **road** | **nonurban** | A part of a road in nonurban region | All vehicles and bikes | Nonurban speed limit | | **highway** | **urban** | A part of a highway in urban region | All vehicles | Urban highway limit | -| **highway | **nonurban** | A part of a highway in nonurban region | All vehicles | Nonurban highway limit | +| **highway** | **nonurban** | A part of a highway in nonurban region | All vehicles | Nonurban highway limit | | **play_street** | **-** | A part of a play street | Vehicles, bikes, pedestrians | play street speed limit | | **emergency_lane** | **-** | Lane for emergency vehicles | Emergency vehicles | Average emergency vehicle speed | | **bus_lane** | **urban** | Lane for buses | Bus, Emergency, Taxi | City speed limit | -| **bus_lane** | **urban** | Lane for buses | Bus, Emergency, Taxi | Nonurban speed limit | +| **bus_lane** | **nonurban** | Lane for buses | Bus, Emergency, Taxi | Nonurban speed limit | | **bicycle_lane** | **-** | A lane that is usable only for bikes | Bikes | Average bike speed | | **exit** | **urban** | Exit area of a house or garage that crosses the crosswalk | Vehicles, bikes, pedestrians | Urban speed limit | | **walkway** | **-** | A part of a way for pedestrians | Pedestrians | Average pedestrian walking speed | diff --git a/lanelet2/lanelet2_core/doc/LaneletPrimitives.md b/lanelet2/lanelet2_core/doc/LaneletPrimitives.md index 73cd029336e..a3de164996b 100644 --- a/lanelet2/lanelet2_core/doc/LaneletPrimitives.md +++ b/lanelet2/lanelet2_core/doc/LaneletPrimitives.md @@ -1,6 +1,6 @@ # Lanelet Primitives -Lanelet2 divides the world into a hierachical structure of six different primitives: Points, linestrings, polygons, lanelets, areas and regulatory elements. +Lanelet2 divides the world into a hierarchical structure of six different primitives: Points, linestrings, polygons, lanelets, areas and regulatory elements. This article focuses on how the primitives are meant to be used, what properties they have and how they are meant to be used. For the technical side, please refer to the [architecture](Architecture.md) page. @@ -64,7 +64,7 @@ For more details on the exact tags of a Lanelet, please read [here](LaneletAndAr ![Area](images/area.png) -An Area has similar properties like a Lanelet, but instead of representing *directed* traffic from entry to exit, an area represents *undirected* traffic within its surface. An Area can have multiple entry and exit points. A typical example of an area would be squares that are used by pedestrians or parking lots and emergency lanes for vehicles. Similar to lanelets, traffic rules must not change on the lanelet. +An Area has similar properties like a Lanelet, but instead of representing *directed* traffic from entry to exit, an area represents *undirected* traffic within its surface. An Area can have multiple entry and exit points. A typical example of an area would be squares that are used by pedestrians or parking lots and emergency lanes for vehicles. Similar to lanelets, traffic rules must not change on the areas. Geometrically, an Area is represented by an ordered list of linestrings that together form the shape of the area in *clockwise* orientation. Areas must share exactly one linestring with an other area to be considered adajacent. For lanelets they either have to share one Linestring (when the lanelet is parallel to the area) or the endpoints of the lanelet are also the endpoints of one of the linestrings of the area (when the lanelet leads into the area). The area of an Area must not be zero and the bounds must not self-intersect. diff --git a/lanelet2/lanelet2_core/doc/RegulatoryElementTagging.md b/lanelet2/lanelet2_core/doc/RegulatoryElementTagging.md index 397010e354d..4c1eef9d5ea 100644 --- a/lanelet2/lanelet2_core/doc/RegulatoryElementTagging.md +++ b/lanelet2/lanelet2_core/doc/RegulatoryElementTagging.md @@ -11,10 +11,11 @@ Regulatory Elements always have `type=regulatory_element`. If this tag is not pr ### Subtype The `subtype` tag helps Lanelet2 to distinguish between the different regulatory elements. For the basic Regulatory Elements this would be: -* *traffic_light* * *traffic_sign* +* *traffic_light* * *speed_limit* * *right_of_way* +* *all_way_stop* ### Other, Optional Tags The following tags can be used to add more information to a Regulatory Element (of course you can add you own to enhance your map and implement a new `TrafficRule` object that implements them). The default values for the tag are highlighted. @@ -70,3 +71,57 @@ The following roles are used in an all way stop: * *refers*: The traffic sign(s) that constitute this rule All lanelets referenced in this regelem also have to reference this regelem. + +## OSM XML Examples + +Below are some examples of regulatory element relations as they might look in lanelet2's OSM XML format. + +### Traffic Light + +```xml + + + + + + + + +``` + +### Speed Limit + +```xml + + + + + + +``` + +### All Way Stop + +Below is an example of a 4-way stop intersection. +```xml + + + + + + + + + + + + + + + + + + + +``` + diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/Attribute.h b/lanelet2/lanelet2_core/include/lanelet2_core/Attribute.h index fd7347c2fe5..6319eda00d4 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/Attribute.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/Attribute.h @@ -5,9 +5,10 @@ #include #include #include -#include "Forward.h" -#include "utility/HybridMap.h" -#include "utility/Optional.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/utility/HybridMap.h" +#include "lanelet2_core/utility/Optional.h" namespace lanelet { namespace internal { @@ -370,7 +371,7 @@ inline std::ostream& operator<<(std::ostream& stream, const Attribute& obj) { re using AttributeMap = HybridMap; inline std::ostream& operator<<(std::ostream& stream, const AttributeMap& obj) { - for (auto& o : obj) { + for (const auto& o : obj) { stream << o.first << ": " << o.second << " "; } return stream; diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/LaneletMap.h b/lanelet2/lanelet2_core/include/lanelet2_core/LaneletMap.h index 0463744785f..aab7c12d60b 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/LaneletMap.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/LaneletMap.h @@ -1,12 +1,13 @@ #pragma once #include -#include "Forward.h" -#include "primitives/Area.h" -#include "primitives/BoundingBox.h" -#include "primitives/Lanelet.h" -#include "primitives/RegulatoryElement.h" -#include "utility/Utilities.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/BoundingBox.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" +#include "lanelet2_core/utility/Utilities.h" namespace lanelet { namespace internal { @@ -603,8 +604,9 @@ using LayerPrimitiveType = typename LayerPrimitive::Type; namespace geometry { /** * @brief returns the nearest n primitives to a point. - * @return vector of the n closest primitives together with their distance in + * @return vector of the n closest primitives together with their distance in 2D space in * ascending order. + * @see findWithin2d, findWithin3d * * Other than than LaneletLayer::nearest, this returns the actually closest * primitives, not only the closest bounding boxes. @@ -621,11 +623,12 @@ std::vector>> findNearest(co const BasicPoint2d& pt, unsigned count); #ifndef LANELET_LAYER_DEFINITION -#define EXTERN_FIND_NEAREST(PRIM) \ - extern template std::vector> findNearest(PrimitiveLayer&, const BasicPoint2d&, unsigned) -#define EXTERN_CONST_FIND_NEAREST(PRIM) \ - extern template std::vector>> findNearest( \ - const PrimitiveLayer&, const BasicPoint2d&, unsigned) +// clang-format off +// NOLINTNEXTLINE +#define EXTERN_FIND_NEAREST(PRIM) extern template std::vector> findNearest(PrimitiveLayer&, const BasicPoint2d&, unsigned) +// NOLINTNEXTLINE +#define EXTERN_CONST_FIND_NEAREST(PRIM) extern template std::vector>> findNearest(const PrimitiveLayer&, const BasicPoint2d&, unsigned) +// clang-format on EXTERN_FIND_NEAREST(Area); EXTERN_FIND_NEAREST(Polygon3d); EXTERN_FIND_NEAREST(Lanelet); diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h index 6e5dc37efa5..1e2bdeca9e6 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Area.h @@ -1,8 +1,8 @@ #pragma once -#include "../primitives/Area.h" -#include "../primitives/Lanelet.h" -#include "Polygon.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { namespace geometry { @@ -71,6 +71,80 @@ inline bool follows(const ConstArea& prev, const ConstLanelet& next); //! Test if two areas are adjacent inline bool adjacent(const ConstArea& area1, const ConstArea& area2); + +/** + * Find line string in area ar that borders Lanelet ll if ar follows ll + * @param ll Lanelet + * @param ar Area that is following ll + * @return LineString3d if it exists + */ +inline Optional determineCommonLinePreceding(const ConstLanelet& ll, const ConstArea& ar); + +/** + * Find line string in area ar that borders Lanelet ll if ar precedes ll + * @param ar Area that is preceding ll + * @param ll Lanelet + * @return LineString3d if it exists + */ +inline Optional determineCommonLineFollowing(const ConstArea& ar, const ConstLanelet& ll); + +/** + * Find line string in area ar that borders Lanelet ll if ar precedes or follows ll + * @param ar Area that is preceding or following ll + * @param ll Lanelet + * @return LineString3d if it exists + */ +inline Optional determineCommonLineFollowingOrPreceding(const ConstArea& ar, const ConstLanelet& ll); + +/** + * Find line string in Lanelet right that borders Area left if ar is left of ll. + * @param left Area that borders ll on the left + * @param right Lanelet + * @return LineString3d in right if it exists + */ +inline Optional determineCommonLineLeft(const ConstLanelet& right, const ConstArea& left); + +/** + * Find line string in Lanelet left that borders Area right if ar is right of ll. + * @param right Area that borders ll on the right + * @param left Lanelet + * @return LineString3d in left if it exists + */ +inline Optional determineCommonLineRight(const ConstLanelet& left, const ConstArea& right); + +/** + * Find line string in Lanelet ll that borders Area ar if ar is left or right of ll. Same as + * determineCommonLineSideways(ar, ll) but returned line string is guaranteed to be in ll + * @param ar Area that borders ll + * @param ll Lanelet + * @return LineString3d in ll if it exists + */ +inline Optional determineCommonLineSideways(const ConstLanelet& ll, const ConstArea& ar); + +/** + * Find line string in Area ar that borders Lanelet ll if ar is left or right of ll. Same as + * determineCommonLineSideways(ll, ar) but returned line string is guaranteed to be in ar + * @param ar Area + * @param ll Lanelet that borders ar + * @return LineString3d in ar if it exists + */ +inline Optional determineCommonLineSideways(const ConstArea& ar, const ConstLanelet& ll); + +/** + * Find line string in area ar that borders Lanelet ll anywhere + * @param ar Area that is adjacent anywhere to ll + * @param ll Lanelet + * @return LineString3d if it exists + */ +inline Optional determineCommonLine(const ConstArea& ar, const ConstLanelet& ll); + +/** + * Find Line String in Area ar1 that is common with Area ar2 + * @param ar1 Area + * @param ar2 Area + * @return LineString3d in Area ar1 if it exists. The inverted line string is part of ar2. + */ +inline Optional determineCommonLine(const ConstArea& ar1, const ConstArea& ar2); } // namespace geometry } // namespace lanelet diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/BoundingBox.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/BoundingBox.h index 08bfa8e2b8d..322c3a22abc 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/BoundingBox.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/BoundingBox.h @@ -1,11 +1,12 @@ #pragma once #include -#include "../primitives/BoundingBox.h" -#include "Point.h" + +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/primitives/BoundingBox.h" // registrations for use with boost::geometry -BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox2d, lanelet::BasicPoint2d, min(), max()); -BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox3d, lanelet::BasicPoint3d, min(), max()); +BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox2d, lanelet::BasicPoint2d, min(), max()) +BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox3d, lanelet::BasicPoint3d, min(), max()) namespace lanelet { namespace geometry { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/GeometryHelper.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/GeometryHelper.h index 3ca416f1e91..144a6343219 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/GeometryHelper.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/GeometryHelper.h @@ -87,18 +87,17 @@ class ProjectedPoint : public boost::geometry::strategy::distance::projected_poi using namespace boost::geometry; assert_dimension_equal(); - using calculation_type = // NOLINT - typename calculation_type::type; + using CalculationResult = typename calculation_type::type; // A projected point of points in Integer coordinates must be able to be // represented in FP. - using fp_point_type = // NOLINT - model::point::value, + using FpVector = // NOLINT + model::point::value, typename coordinate_system::type>; - // For convenience - typedef fp_point_type fp_vector_type; // NOLINT - fp_vector_type v, w, projected; + FpVector v; + FpVector w; + FpVector projected; convert(p2, v); convert(p, w); @@ -109,18 +108,18 @@ class ProjectedPoint : public boost::geometry::strategy::distance::projected_poi Strategy strategy; boost::ignore_unused_variable_warning(strategy); - calculation_type const zero = calculation_type(); - calculation_type const c1 = dot_product(w, v); + auto zero = CalculationResult{}; + CalculationResult const c1 = dot_product(w, v); if (c1 <= zero) { return updateClosestPoint(p1, p2, p1, strategy.apply(p, p1)); } - calculation_type const c2 = dot_product(v, v); + CalculationResult const c2 = dot_product(v, v); if (c2 <= c1) { return updateClosestPoint(p1, p2, p2, strategy.apply(p, p2)); } // See above, c1 > 0 AND c2 > c1 so: c2 != 0 - calculation_type const b = c1 / c2; + CalculationResult const b = c1 / c2; multiply_value(v, b); add_point(projected, v); diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Lanelet.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Lanelet.h index bfbbee56a52..f046185c23b 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Lanelet.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Lanelet.h @@ -1,6 +1,6 @@ #pragma once -#include "../primitives/Lanelet.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { namespace geometry { @@ -165,6 +165,18 @@ IfLL> rightOf(const Lanelet1T& right, const Lan template IfLL> follows(const Lanelet1T& prev, const Lanelet2T& next); +/** + * @brief find a common line string in ll and other. + * @param ll Lanelet + * @param other Lanelet + * @param allowInverted if true, the orientation of the line strings is ignored + * @return line string in ll if it is shared with other + */ +template +IfLL>> determineCommonLine(const Lanelet1T& ll, + const Lanelet2T& other, + bool allowInverted = false); + /** * @brief calculates the maximum velocity without exceding a maximum lateral * acceleration. diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LaneletMap.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LaneletMap.h index cac685734a2..782c96db0df 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LaneletMap.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LaneletMap.h @@ -1,11 +1,11 @@ #pragma once -#include "../LaneletMap.h" -#include "../primitives/BoundingBox.h" -#include "../primitives/Lanelet.h" -#include "BoundingBox.h" -#include "Lanelet.h" -#include "LineString.h" +#include "lanelet2_core/LaneletMap.h" +#include "lanelet2_core/geometry/BoundingBox.h" +#include "lanelet2_core/geometry/Lanelet.h" +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/primitives/BoundingBox.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { namespace geometry { @@ -13,8 +13,11 @@ namespace geometry { * @brief Returns all elements that are closer than maxDist to a geometry in 2d * @param layer for the check (a layer of LaneletMap) * @param geometry to check (any 2d geometry) + * @param maxDist maximum distance to the input geometry. If zero, only primitives containing the element are returned. + * Be aware that rounding errors can affect the result for primitives directly on (or very close to) the boundary. * @return vector of pairs: of all elements of a layer which are closer than maxDist to the * geometry. The return type differs depending on if the layer is const or not. Result sorted in ascending distance. + * @see findNearest */ template auto findWithin2d(LayerT& layer, const GeometryT& geometry, double maxDist = 0.) @@ -24,6 +27,8 @@ auto findWithin2d(LayerT& layer, const GeometryT& geometry, double maxDist = 0.) * @brief Returns all elements that are closer than maxDist to a geometry in 3d * @param layer for the check (a layer of LaneletMap) * @param geometry to check (any 3d geometry) + * @param maxDist maximum distance to the input geometry. If zero, only primitives containing the element are returned. + * Be aware that rounding errors can affect the result for primitives directly on (or very close to) the boundary. * @return vector of pairs: of all elements of a layer which are closer than maxDist to the * geometry. The return type differs depending on if the layer is const or not. Result sorted in ascending distance. */ diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h index 68d97740613..c805b7ffa02 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/LineString.h @@ -3,12 +3,13 @@ #include #include #include -#include "../Forward.h" -#include "../primitives/CompoundLineString.h" -#include "../primitives/LineString.h" -#include "BoundingBox.h" -#include "GeometryHelper.h" -#include "Point.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/geometry/BoundingBox.h" +#include "lanelet2_core/geometry/GeometryHelper.h" +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/primitives/CompoundLineString.h" +#include "lanelet2_core/primitives/LineString.h" /*********************************************************************** * BOOST GEOMETRY REGISTRATIONS * @@ -26,7 +27,7 @@ BOOST_GEOMETRY_REGISTER_LINESTRING(lanelet::CompoundLineString2d) BOOST_GEOMETRY_REGISTER_LINESTRING(lanelet::CompoundLineString3d) BOOST_GEOMETRY_REGISTER_LINESTRING(lanelet::CompoundHybridLineString2d) BOOST_GEOMETRY_REGISTER_LINESTRING(lanelet::CompoundHybridLineString3d) -BOOST_GEOMETRY_REGISTER_SEGMENT_TEMPLATIZED(lanelet::Segment, first, second); +BOOST_GEOMETRY_REGISTER_SEGMENT_TEMPLATIZED(lanelet::Segment, first, second) namespace lanelet { namespace geometry { @@ -97,6 +98,18 @@ double signedDistance(const LineString3dT& lineString, const BasicPoint3d& p); template double signedDistance(const LineString2dT& lineString, const BasicPoint2d& p); +/** + * Calculate the curvature value given 3 consecutive points. + * The curvature value is always positive. + * + * @param p1, p2, p3 are the points + * @return curvature value. + * + * If any 2 of the 3 points duplicate, return infinity. + */ +template +double curvature2d(const Point2dT& p1, const Point2dT& p2, const Point2dT& p3); + /** * * @brief Transform a point to the coordinates of the linestring diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Point.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Point.h index 7ca976a6f24..080539ed343 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Point.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Point.h @@ -1,9 +1,15 @@ #pragma once +#include +#if BOOST_VERSION < 106300 && BOOST_VERSION >= 106200 +// Boost 1.62 is missing an iostream include... +#include +#endif #include #include #include #include -#include "../primitives/Point.h" + +#include "lanelet2_core/primitives/Point.h" /*********************************************************************** * BOOST GEOMETRY REGISTRATIONS * diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h index 0eb76d40978..63c9a73134a 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/Polygon.h @@ -1,8 +1,9 @@ #pragma once #include -#include "../primitives/CompoundPolygon.h" -#include "../primitives/Polygon.h" -#include "LineString.h" + +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/primitives/CompoundPolygon.h" +#include "lanelet2_core/primitives/Polygon.h" /*********************************************************************** * BOOST GEOMETRY REGISTRATIONS * @@ -282,6 +283,61 @@ IfPoly overlaps2d(const Polygon2dT& poly1, const Polygon2dT& p template IfPoly overlaps3d(const Polygon3dT& poly1, const Polygon3dT& poly2, double heightTolerance); + +/** + * + * @brief Split a concave polygon into convex parts + * + * Internally computes a Delaunay triangulation which is greedily merged into convex parts. Guaranteed to deliver a + * partition with at most 2N+1 parts if N is minimum partition. Since boost only allows integral types, the + * triangulation is only millimeter-accurate, even though the resulting points are identical to the input points. + * + * @tparam Polygon2dT Polygon Type + * @param poly Polygon to partition + * @return a list of convex polygons yielding the original polygon if merged. + */ +template +IfPoly convexPartition(const Polygon2dT& poly); +/** + * + * @brief Split a concave polygon into convex parts + * + * Internally computes a Delaunay triangulation which is greedily merged into convex parts. Guaranteed to deliver a + * partition with at most 2N+1 parts if N is minimum partition. Since boost only allows integral types, the + * triangulation is only millimeter-accurate, even though the resulting points are identical to the input points. + * + * @param poly BasicPolygon2d to partition + * @return a list of convex polygons yielding the original polygon if merged. + */ +template <> +IfPoly convexPartition(const BasicPolygon2d& poly); +using IndexedTriangle = std::array; +using IndexedTriangles = std::vector; + +/** + * + * @brief Split a concave polygon into triangles + * + * Internally computes a Delaunay triangulation. + * + * @tparam Polygon2dT Polygon Type + * @param poly Polygon to partition + * @return a list of indices sets. Each set refers to a triangle in the original polygon. + */ +template +IfPoly triangulate(const Polygon2dT& poly); +/** + * + * @brief Split a concave polygon into triangles + * + * Internally computes a Delaunay triangulation. + * + * @param poly Polygon to partition + * @return a list of indices sets. Each set refers to a triangle in the original polygon. + */ +template <> +IfPoly triangulate(const BasicPolygon2d& poly); + } // namespace geometry } // namespace lanelet diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/RegulatoryElement.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/RegulatoryElement.h index 5c256ca1c2d..b193f643255 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/RegulatoryElement.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/RegulatoryElement.h @@ -1,6 +1,6 @@ #pragma once -#include "../primitives/BoundingBox.h" -#include "../primitives/RegulatoryElement.h" +#include "lanelet2_core/primitives/BoundingBox.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" namespace lanelet { namespace geometry { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Area.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Area.h index ac3fe5acece..0edece94651 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Area.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Area.h @@ -1,8 +1,10 @@ #pragma once -#include "../../primitives/Area.h" -#include "../../primitives/Lanelet.h" -#include "../Point.h" -#include "../Polygon.h" +#include + +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { namespace geometry { @@ -39,7 +41,7 @@ IfAr intersects2d(const Area1T& area, const Area2T& otherArea) { template IfAr overlaps2d(const AreaT& area, const AreaT& otherArea) { - return overlaps2d(area.outerBoundPolygon(), otherArea.outerBoundPolygon()); + return overlaps2d(traits::to2D(area.outerBoundPolygon()), traits::to2D(otherArea.outerBoundPolygon())); } template @@ -58,9 +60,7 @@ IfAr> overlaps3d(const AreaT& area, const LaneletT& } inline bool leftOf(const ConstLanelet& right, const ConstArea& left) { - return utils::anyOf(left.outerBound(), [&right](auto& bound) { - return bound == right.leftBound() || bound.invert() == right.leftBound(); - }); + return utils::anyOf(left.outerBound(), [&right](auto& bound) { return bound.invert() == right.leftBound(); }); } inline bool rightOf(const ConstLanelet& left, const ConstArea& area) { return leftOf(left.invert(), area); } @@ -78,7 +78,7 @@ inline bool follows(const ConstArea& prev, const ConstLanelet& next) { return fo inline bool adjacent(const ConstArea& area1, const ConstArea& area2) { auto outer1 = area1.outerBoundPolygon(); auto outer2 = area2.outerBoundPolygon(); - auto rotatedNext = [& ls = outer2](auto iter) { return iter + 1 == ls.end() ? ls.begin() : iter + 1; }; + auto rotatedNext = [&ls = outer2](auto iter) { return iter + 1 == ls.end() ? ls.begin() : iter + 1; }; for (auto i = 0u; i < outer1.numSegments(); ++i) { auto segment = outer1.segment(i); auto second = std::find(outer2.begin(), outer2.end(), segment.second); @@ -88,5 +88,59 @@ inline bool adjacent(const ConstArea& area1, const ConstArea& area2) { } return false; } + +inline Optional determineCommonLinePreceding(const ConstLanelet& ll, const ConstArea& ar) { + return utils::findIf(ar.outerBound(), [p1 = ll.leftBound().back(), p2 = ll.rightBound().back()](auto& boundLs) { + return (boundLs.back() == p1 && boundLs.front() == p2); + }); +} + +inline Optional determineCommonLineFollowing(const ConstArea& ar, const ConstLanelet& ll) { + return determineCommonLinePreceding(ll.invert(), ar); +} + +inline Optional determineCommonLineFollowingOrPreceding(const ConstArea& ar, + const ConstLanelet& ll) { + return utils::findIf(ar.outerBound(), [p1 = ll.leftBound().front(), p2 = ll.rightBound().front(), + p3 = ll.leftBound().back(), p4 = ll.rightBound().back()](auto& boundLs) { + return ((boundLs.back() == p2 && boundLs.front() == p1) || (boundLs.back() == p3 && boundLs.front() == p4)); + }); +} + +inline Optional determineCommonLineSideways(const ConstLanelet& ll, const ConstArea& ar) { + auto res = determineCommonLineLeft(ll, ar); + return res ? res : determineCommonLineRight(ll, ar); +} + +inline Optional determineCommonLineSideways(const ConstArea& ar, const ConstLanelet& ll) { + return utils::findIf(ar.outerBound(), [lb = ll.leftBound(), rb = ll.rightBound()](auto& boundLs) { + return boundLs == lb.invert() || boundLs == rb; + }); +} + +inline Optional determineCommonLine(const ConstArea& ar1, const ConstArea& ar2) { + return utils::findIf(ar1.outerBound(), [&ar2](auto& ar1Bound) { + return !!utils::findIf(ar2.outerBound(), + [ar1Bound = ar1Bound.invert()](auto& ar2Bound) { return ar2Bound == ar1Bound; }); + }); +} + +inline Optional determineCommonLine(const ConstArea& ar, const ConstLanelet& ll) { + auto res = determineCommonLineFollowingOrPreceding(ar, ll); + return res ? res : determineCommonLineSideways(ar, ll); +} + +inline Optional determineCommonLineLeft(const ConstLanelet& right, const ConstArea& left) { + auto res = determineCommonLineRight(right.invert(), left); + if (res) { + return res->invert(); + } + return {}; +} + +inline Optional determineCommonLineRight(const ConstLanelet& left, const ConstArea& right) { + return utils::findIf(right.outerBound(), [&left](auto& bound) { return bound == left.rightBound(); }); +} + } // namespace geometry } // namespace lanelet diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Lanelet.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Lanelet.h index 7685344b017..225aca8bbee 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Lanelet.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Lanelet.h @@ -2,13 +2,14 @@ #include #if BOOST_VERSION > 105800 #include // NOLINT + #include #else #include #endif -#include "../../primitives/Lanelet.h" -#include "../../primitives/LineString.h" -#include "../Polygon.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/LineString.h" namespace lanelet { namespace geometry { @@ -142,6 +143,27 @@ IfLL> follows(const Lanelet1T& prev, const Lane prev.rightBound().back() == next.rightBound().front(); } +template +IfLL>> determineCommonLine(const Lanelet1T& ll, + const Lanelet2T& other, + bool allowInverted) { + if (leftOf(other, ll)) { + return ll.leftBound(); + } + if (rightOf(other, ll)) { + return ll.rightBound(); + } + if (allowInverted) { + if (leftOf(other.invert(), ll)) { + return ll.leftBound(); + } + if (rightOf(other.invert(), ll)) { + return ll.rightBound(); + } + } + return {}; +} + template Velocity maxCurveSpeed(const LaneletT& /*lanelet*/, const BasicPoint2d& /*position*/, const Acceleration& /*maxLateralAcceleration*/) { @@ -153,8 +175,8 @@ template double approximatedLength2d(const LaneletT& lanelet) { double length = 0.; auto line = lanelet.leftBound2d(); - auto step = std::max(1ul, line.size() / 10); - for (auto i1 = 0ul, i2 = step; i2 < line.size(); i1 += step, i2 += step) { + auto step = std::max(size_t{1}, line.size() / 10); + for (auto i1 = size_t{}, i2 = step; i2 < line.size(); i1 += step, i2 += step) { length += distance(line[i1], line[i2]); if (i2 + step >= line.size()) { length += distance(line[i2], line[line.size() - 1]); diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LaneletMap.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LaneletMap.h index f28559f8453..cd287d1832b 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LaneletMap.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LaneletMap.h @@ -1,10 +1,11 @@ #pragma once #include #include -#include "../../LaneletMap.h" -#include "../../primitives/BoundingBox.h" -#include "../../primitives/Lanelet.h" -#include "../../utility/Utilities.h" + +#include "lanelet2_core/LaneletMap.h" +#include "lanelet2_core/primitives/BoundingBox.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/utility/Utilities.h" namespace lanelet { namespace geometry { @@ -38,7 +39,7 @@ auto findWithin3d(LayerT& layer, const GeometryT& geometry, double maxDist) -> std::vector>> { using RetT = std::vector>>; - BoundingBox2d boundingBox = boundingBox2d(geometry); + BoundingBox2d boundingBox = boundingBox2d(traits::to2D(geometry)); if (maxDist > 0.) { boost::geometry::buffer(boundingBox, boundingBox, maxDist); } diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LineString.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LineString.h index ec9d7a74e0c..7086781a896 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LineString.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/LineString.h @@ -1,9 +1,10 @@ #pragma once #include -#include "../../primitives/LineString.h" -#include "../../primitives/Traits.h" -#include "../GeometryHelper.h" -#include "../Point.h" + +#include "lanelet2_core/geometry/GeometryHelper.h" +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Traits.h" namespace lanelet { namespace geometry { @@ -36,6 +37,10 @@ inline auto crossProd(const BasicPoint3d& p1, const BasicPoint3d& p2) { return p inline auto crossProd(const BasicPoint2d& p1, const BasicPoint2d& p2) { return BasicPoint3d(p1.x(), p1.y(), 0.).cross(BasicPoint3d(p2.x(), p2.y(), 0.)).eval(); } +// required for Polygon triangulation +inline auto crossProd(const Eigen::Matrix& p1, const Eigen::Matrix& p2) { + return BasicPoint3d(p1.x(), p1.y(), 0.).cross(BasicPoint3d(p2.x(), p2.y(), 0.)).eval(); +} template auto findPoint(const LineStringT& ls, const BasicPointT& p) { @@ -97,6 +102,18 @@ std::pair projectedPoint3d(const ConstHybridLineStri std::pair projectedPoint3d(const CompoundHybridLineString3d& l1, const CompoundHybridLineString3d& l2); +std::pair projectedPoint3d(const ConstHybridLineString3d& l1, + const CompoundHybridLineString3d& l2); + +std::pair projectedPoint3d(const CompoundHybridLineString3d& l1, + const ConstHybridLineString3d& l2); + +std::pair projectedPoint3d(const ConstHybridLineString3d& l1, const BasicLineString3d& l2); + +std::pair projectedPoint3d(const BasicLineString3d& l1, const ConstHybridLineString3d& l2); + +std::pair projectedPoint3d(const BasicLineString3d& l1, const BasicLineString3d& l2); + template BasicPoint2d fromArcCoords(const HybridLineStringT& hLineString, const BasicPoint2d& projStart, const size_t startIdx, const size_t endIdx, const double distance) { @@ -608,8 +625,8 @@ traits::BasicPointT> interpolatedPointAtDistance( double currentCumulativeLength = 0.0; for (auto first = lineString.begin(), second = std::next(lineString.begin()); second != lineString.end(); ++first, ++second) { - const auto p1 = traits::toBasicPoint(*first); - const auto p2 = traits::toBasicPoint(*second); + auto p1 = traits::toBasicPoint(*first); + auto p2 = traits::toBasicPoint(*second); double currentLength = distance(p1, p2); currentCumulativeLength += currentLength; if (currentCumulativeLength >= dist) { @@ -661,6 +678,20 @@ double signedDistance(const LineString2dT& lineString, const BasicPoint2d& p) { return internal::signedDistanceImpl(lineString, p).first; } +template +double curvature2d(const Point2dT& p1, const Point2dT& p2, const Point2dT& p3) { + // see https://en.wikipedia.org/wiki/Menger_curvature#Definition + const double area = 0.5 * ((p2.x() - p1.x()) * (p3.y() - p1.y()) - (p2.y() - p1.y()) * (p3.x() - p1.x())); + const double side1 = distance(p1, p2); + const double side2 = distance(p1, p3); + const double side3 = distance(p2, p3); + const double product = side1 * side2 * side3; + if (product < 1e-20) { + return std::numeric_limits::infinity(); + } + return std::fabs(4 * area / product); +} + template ArcCoordinates toArcCoordinates(const LineString2dT& lineString, const BasicPoint2d& point) { auto res = internal::signedDistanceImpl(lineString, point); @@ -734,11 +765,12 @@ IfLS intersects3d(const LineString3dT& linestring, const Li template IfLS> projectedPoint3d(const LineString3dT& l1, const LineString3dT& l2) { + static_assert(traits::is3D(), "Please call this function with a 3D type!"); return internal::projectedPoint3d(traits::toHybrid(l1), traits::toHybrid(l2)); } template -IfLS distance3d(const LineString3d1T& l1, const LineString3d2T& l2) { +IfLS2 distance3d(const LineString3d1T& l1, const LineString3d2T& l2) { auto projPoint = internal::projectedPoint3d(traits::toHybrid(traits::to3D(l1)), traits::toHybrid(traits::to3D(l2))); return (projPoint.first - projPoint.second).norm(); } @@ -774,7 +806,8 @@ BasicPoint2d fromArcCoordinates(const LineString2dT& lineString, const ArcCoordi auto hLineString = utils::toHybrid(lineString); auto ratios = accumulatedLengthRatios(lineString); const auto llength = length(lineString); - size_t startIdx{}, endIdx{}; + size_t startIdx{}; + size_t endIdx{}; for (size_t i = 0; i < ratios.size(); ++i) { if (ratios.at(i) * llength > arcCoords.length) { startIdx = i; diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Polygon.h b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Polygon.h index 3eea33b1e6b..8a6bfe505da 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Polygon.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/geometry/impl/Polygon.h @@ -1,7 +1,7 @@ #pragma once -#include "../../primitives/Polygon.h" -#include "../LineString.h" -#include "../Point.h" +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/primitives/Polygon.h" #if BOOST_VERSION > 105800 #include #else @@ -22,16 +22,20 @@ std::pair projectedBorderPoint3d(const ConstHybridPo std::pair projectedBorderPoint3d(const CompoundHybridPolygon3d& l1, const CompoundHybridPolygon3d& l2); +BasicPolygons2d convexPartition(const BasicPolygon2d& poly); +IndexedTriangles triangulate(const BasicPolygon2d& poly); } // namespace internal template IfPoly> projectedBorderPoint3d(const Polygon3dT& l1, const Polygon3dT& l2) { + static_assert(traits::is3D(), "Please call this function with a 3D type!"); return internal::projectedBorderPoint3d(traits::toHybrid(traits::to3D(l1)), traits::toHybrid(traits::to3D(l2))); } template IfPoly distanceToBorder3d(const Polygon3dT& poly1, const Polygon3dT& poly2) { + static_assert(traits::is3D(), "Please call this function with a 3D type!"); auto projPoint = internal::projectedBorderPoint3d(traits::toHybrid(poly1), traits::toHybrid(poly2)); return (projPoint.first - projPoint.second).norm(); } @@ -51,6 +55,7 @@ IfPoly touches2d(const PolygonT& poly1, const PolygonT& poly2) { template IfPoly overlaps2d(const Polygon2dT& poly1, const Polygon2dT& poly2) { + static_assert(traits::is2D(), "Please call this function with a 2D type!"); if (touches2d(poly1, poly2)) { return false; } @@ -65,11 +70,35 @@ IfPoly overlaps2d(const Polygon2dT& poly1, const Polygon2dT& p template IfPoly overlaps3d(const Polygon3dT& poly1, const Polygon3dT& poly2, double heightTolerance) { - if (!overlaps2d(poly1, poly2)) { + static_assert(traits::is3D(), "Please call this function with a 3D type!"); + if (!overlaps2d(traits::to2D(poly1), traits::to2D(poly2))) { return false; } auto points = projectedBorderPoint3d(poly1, poly2); return std::abs(points.first.z() - points.second.z()) < heightTolerance; } + +template +IfPoly convexPartition(const Polygon2dT& poly) { + static_assert(traits::is2D(), "Please call this function with a 2D type!"); + return internal::convexPartition(BasicPolygon2d(poly.basicBegin(), poly.basicEnd())); +} + +template +IfPoly triangulate(const Polygon2dT& poly) { + static_assert(traits::is2D(), "Please call this function with a 2D type!"); + return internal::triangulate(BasicPolygon2d(poly.basicBegin(), poly.basicEnd())); +} + +template <> +inline IfPoly convexPartition(const BasicPolygon2d& poly) { + return internal::convexPartition(poly); +} + +template <> +inline IfPoly triangulate(const BasicPolygon2d& poly) { + return internal::triangulate(poly); +} + } // namespace geometry } // namespace lanelet diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Area.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Area.h index 5e74460a9b2..ab4245800c2 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Area.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Area.h @@ -5,12 +5,13 @@ #include #include -#include "../Forward.h" -#include "../utility/Optional.h" -#include "CompoundPolygon.h" -#include "Point.h" -#include "Polygon.h" -#include "Primitive.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/CompoundPolygon.h" +#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_core/primitives/Polygon.h" +#include "lanelet2_core/primitives/Primitive.h" +#include "lanelet2_core/utility/Optional.h" namespace lanelet { //! @defgroup AreaPrimitives Area @@ -137,9 +138,9 @@ class ConstArea : public ConstPrimitive { * * This is the constructor that you most probably want to use. */ - ConstArea(Id id, LineStrings3d outerBound, InnerBounds innerBounds = InnerBounds(), - AttributeMap attributes = AttributeMap(), - RegulatoryElementPtrs regulatoryElements = RegulatoryElementPtrs()) + ConstArea(Id id, const LineStrings3d& outerBound, const InnerBounds& innerBounds = InnerBounds(), + const AttributeMap& attributes = AttributeMap(), + const RegulatoryElementPtrs& regulatoryElements = RegulatoryElementPtrs()) : ConstPrimitive{std::make_shared(id, outerBound, innerBounds, attributes, regulatoryElements)} {} //! Constructor to construct from the data of a different Area diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BasicRegulatoryElements.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BasicRegulatoryElements.h index 280d5438a96..b93b32153d9 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BasicRegulatoryElements.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BasicRegulatoryElements.h @@ -1,10 +1,11 @@ #pragma once #include -#include "../Forward.h" -#include "LineString.h" -#include "LineStringOrPolygon.h" -#include "RegulatoryElement.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/LineStringOrPolygon.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" namespace lanelet { @@ -293,7 +294,7 @@ class TrafficSign : public RegulatoryElement { bool removeTrafficSign(const LineStringOrPolygon3d& sign); //! Add new cancelling traffic sign - void addCancellingTrafficSign(const TrafficSignsWithType& sign); + void addCancellingTrafficSign(const TrafficSignsWithType& signs); //! remove a cancelling traffic sign, returns true on success bool removeCancellingTrafficSign(const LineStringOrPolygon3d& sign); diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BoundingBox.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BoundingBox.h index 145e48253d9..239af0438da 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BoundingBox.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/BoundingBox.h @@ -6,8 +6,9 @@ #pragma GCC diagnostic ignored "-Wint-in-bool-context" #endif #include -#include "Point.h" -#include "Traits.h" + +#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_core/primitives/Traits.h" #pragma GCC diagnostic pop namespace lanelet { @@ -109,13 +110,13 @@ class BoundingBox2d { inline VectorType&(max)() { return max_; } /** \returns the center of the box */ - inline const BasicPoint2d center() const { return (min_ + max_) / 2; } + inline BasicPoint2d center() const { return (min_ + max_) / 2; } /** \returns the lengths of the sides of the bounding box. * Note that this function does not get the same * result for integral or floating scalar types: see */ - inline const BasicPoint2d sizes() const { return max_ - min_; } + inline BasicPoint2d sizes() const { return max_ - min_; } /** \returns the volume of the bounding box */ inline Scalar volume() const { return sizes().prod(); } diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundLineString.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundLineString.h index 918e7bcc7c7..4a72881b56d 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundLineString.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundLineString.h @@ -1,8 +1,9 @@ #pragma once #include #include -#include "../utility/CompoundIterator.h" -#include "LineString.h" + +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/utility/CompoundIterator.h" namespace lanelet { namespace internal { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundPolygon.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundPolygon.h index ccbabfbb173..750fb033d21 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundPolygon.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/CompoundPolygon.h @@ -1,6 +1,6 @@ #pragma once -#include "CompoundLineString.h" -#include "Polygon.h" +#include "lanelet2_core/primitives/CompoundLineString.h" +#include "lanelet2_core/primitives/Polygon.h" namespace lanelet { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/GPSPoint.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/GPSPoint.h index e6072389e4c..9228e7d7199 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/GPSPoint.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/GPSPoint.h @@ -1,5 +1,5 @@ #pragma once -#include "../Forward.h" +#include "lanelet2_core/Forward.h" namespace lanelet { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Lanelet.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Lanelet.h index 788f4f57392..98d7f24faae 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Lanelet.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Lanelet.h @@ -6,10 +6,11 @@ #include #include #include -#include "../Forward.h" -#include "../utility/Optional.h" -#include "LineString.h" -#include "Primitive.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Primitive.h" +#include "lanelet2_core/utility/Optional.h" namespace lanelet { enum class LaneletType { OneWay, Bidirectional }; @@ -140,8 +141,9 @@ class ConstLanelet : public ConstPrimitive { : ConstLanelet(std::make_shared(id, LineString3d(), LineString3d()), false) {} //! Constructs a lanelet from id, attributes, regulatoryElements and bounds. - ConstLanelet(Id id, LineString3d leftBound, LineString3d rightBound, AttributeMap attributes = AttributeMap(), - RegulatoryElementPtrs regulatoryElements = RegulatoryElementPtrs()) + ConstLanelet(Id id, const LineString3d& leftBound, const LineString3d& rightBound, + const AttributeMap& attributes = AttributeMap(), + const RegulatoryElementPtrs& regulatoryElements = RegulatoryElementPtrs()) : ConstPrimitive{std::make_shared(id, leftBound, rightBound, attributes, regulatoryElements)} {} //! Construct from the data of a different Lanelet diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletOrArea.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletOrArea.h index 028c876f745..b96eaafdbab 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletOrArea.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletOrArea.h @@ -1,7 +1,8 @@ #pragma once #include -#include "Area.h" -#include "Lanelet.h" + +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { @@ -67,7 +68,7 @@ class ConstLaneletOrArea { //! return the managed lanelet Optional lanelet() const { - auto ll = boost::get(&laneletOrArea_); + const auto* ll = boost::get(&laneletOrArea_); if (ll != nullptr) { return *ll; } @@ -76,7 +77,7 @@ class ConstLaneletOrArea { //! get the managed area Optional area() const { - auto ar = boost::get(&laneletOrArea_); + const auto* ar = boost::get(&laneletOrArea_); if (ar != nullptr) { return *ar; } @@ -85,6 +86,14 @@ class ConstLaneletOrArea { //! compares this lanelet or area bool equals(const ConstLaneletOrArea& other) const { return laneletOrArea_ == other.laneletOrArea_; } + //! returns the outer bound if it is an area or the polygon made of the lanelet bounds if it's a lanelet + CompoundPolygon3d boundingPolygon() const { + if (isArea()) { + return area()->outerBoundPolygon(); + } + return lanelet()->polygon3d(); + } + private: boost::variant laneletOrArea_; }; @@ -106,7 +115,7 @@ namespace utils { inline ConstLanelets getAllLanelets(const ConstLaneletOrAreas& lars) { ConstLanelets lanelets; lanelets.reserve(lars.size()); - for (auto& lar : lars) { + for (const auto& lar : lars) { if (lar.isLanelet()) { lanelets.push_back(static_cast(lar)); } @@ -116,7 +125,7 @@ inline ConstLanelets getAllLanelets(const ConstLaneletOrAreas& lars) { inline ConstAreas getAllAreas(const ConstLaneletOrAreas& lars) { ConstAreas lanelets; lanelets.reserve(lars.size()); - for (auto& lar : lars) { + for (const auto& lar : lars) { if (lar.isArea()) { lanelets.push_back(static_cast(lar)); } diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletSequence.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletSequence.h index d3e86834b43..06f9583d9b3 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletSequence.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LaneletSequence.h @@ -1,8 +1,9 @@ #pragma once #include -#include "CompoundLineString.h" -#include "CompoundPolygon.h" -#include "Lanelet.h" + +#include "lanelet2_core/primitives/CompoundLineString.h" +#include "lanelet2_core/primitives/CompoundPolygon.h" +#include "lanelet2_core/primitives/Lanelet.h" namespace lanelet { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineString.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineString.h index 8e6e9cb21e0..2f5e0baa9ab 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineString.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineString.h @@ -1,12 +1,13 @@ #pragma once #include -#include "../Forward.h" -#include "../utility/ReverseAndForwardIterator.h" -#include "../utility/TransformIterator.h" -#include "../utility/Utilities.h" -#include "BoundingBox.h" -#include "Point.h" -#include "Primitive.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/BoundingBox.h" +#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_core/primitives/Primitive.h" +#include "lanelet2_core/utility/ReverseAndForwardIterator.h" +#include "lanelet2_core/utility/TransformIterator.h" +#include "lanelet2_core/utility/Utilities.h" namespace lanelet { @@ -63,7 +64,12 @@ struct LineStringTraits> : public PrimitiveTraits>; }; - +template <> +inline BasicLineString2d to2D(const BasicLineString3d& primitive) { + BasicLineString2d ls2d(primitive.size()); + std::transform(primitive.begin(), primitive.end(), ls2d.begin(), utils::to2D); + return ls2d; +} } // namespace traits namespace internal { @@ -754,6 +760,9 @@ constexpr auto toHybrid(const LineStringT ls) { template using IfLS = std::enable_if_t(), RetT>; +template +using IfLS2 = std::enable_if_t() && traits::isLinestringT(), RetT>; + namespace utils { using traits::toHybrid; @@ -785,4 +794,8 @@ template <> struct hash : public lanelet::HashBase {}; template <> struct hash : public lanelet::HashBase {}; +template <> +struct hash : public lanelet::HashBase {}; +template <> +struct hash : public lanelet::HashBase {}; } // namespace std diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineStringOrPolygon.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineStringOrPolygon.h index df64ffe81e1..ed476351b41 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineStringOrPolygon.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/LineStringOrPolygon.h @@ -1,8 +1,9 @@ #pragma once #include -#include "LineString.h" -#include "Polygon.h" -#include "RegulatoryElement.h" + +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Polygon.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" namespace lanelet { //! Base class for objects that can either refer to linestrings or polygons @@ -57,14 +58,9 @@ class LineStringOrPolygonBase { return applyVisitor([](auto& elem) -> const AttributeMap& { return elem.attributes(); }); } - template - std::vector> regulatoryElementsAs() const { - return applyVisitor([](auto& elem) { return elem.template regulatoryElementAs(); }); - } - //! return the managed linestring Optional lineString() const { - auto ls = boost::get(&lsOrPoly_); + const auto* ls = boost::get(&lsOrPoly_); if (ls != nullptr) { return *ls; } @@ -73,7 +69,7 @@ class LineStringOrPolygonBase { //! get the managed polygon Optional polygon() const { - auto poly = boost::get(&lsOrPoly_); + const auto* poly = boost::get(&lsOrPoly_); if (poly != nullptr) { return *poly; } diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Point.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Point.h index 950cd6583a3..be46c4c33e7 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Point.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Point.h @@ -7,11 +7,12 @@ #include #pragma GCC diagnostic pop #include -#include "../Forward.h" -#include "../utility/TransformIterator.h" -#include "../utility/Utilities.h" -#include "Primitive.h" -#include "Traits.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/Primitive.h" +#include "lanelet2_core/primitives/Traits.h" +#include "lanelet2_core/utility/TransformIterator.h" +#include "lanelet2_core/utility/Utilities.h" namespace lanelet { @@ -104,7 +105,7 @@ struct ArcCoordinates { class PointData : public PrimitiveData { // NOLINT public: PointData(Id id, BasicPoint3d point, const AttributeMap& attributes = AttributeMap()) - : PrimitiveData(id, attributes), point(std::move(point)), point2d_{point.x(), point.y()} {} + : PrimitiveData(id, attributes), point(point), point2d_{point.x(), point.y()} {} PointData(const PointData&) = delete; PointData& operator=(const LineStringData&) = delete; PointData(PointData&&) = default; @@ -117,7 +118,7 @@ class PointData : public PrimitiveData { // NOLINT return point2d_; } - BasicPoint3d point; + BasicPoint3d point; // NOLINT(cppcoreguidelines-non-private-member-variables-in-classes) private: mutable BasicPoint2d point2d_; @@ -159,7 +160,7 @@ class ConstPoint2d : public ConstPrimitive { using ConstPrimitive::ConstPrimitive; //! @brief Construct from an id and a point - ConstPoint2d(Id id, BasicPoint3d point, AttributeMap attributes = AttributeMap()) + ConstPoint2d(Id id, const BasicPoint3d& point, const AttributeMap& attributes = AttributeMap()) : ConstPrimitive{std::make_shared(id, point, attributes)} {} // NOLINT //! @brief Construct from an id and coordinates @@ -168,7 +169,7 @@ class ConstPoint2d : public ConstPrimitive { * point, where z matters. */ explicit ConstPoint2d(Id id = InvalId, double x = 0., double y = 0., double z = 0., - AttributeMap attributes = AttributeMap()) + const AttributeMap& attributes = AttributeMap()) : ConstPrimitive{std::make_shared( // NOLINT id, BasicPoint3d(x, y, z), attributes)} {} diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Polygon.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Polygon.h index 28733c4c7ec..7208c98f05b 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Polygon.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Polygon.h @@ -1,7 +1,7 @@ #pragma once -#include "../Forward.h" -#include "LineString.h" +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/LineString.h" namespace lanelet { @@ -386,6 +386,12 @@ struct PrimitiveTraits { using ThreeDType = BasicPolygon3d; using Category = PolygonTag; }; +template <> +inline BasicPolygon2d to2D(const BasicPolygon3d& primitive) { + BasicPolygon2d p2d(primitive.size()); + std::transform(primitive.begin(), primitive.end(), p2d.begin(), utils::to2D); + return p2d; +} } // namespace traits template using IfPoly = std::enable_if_t(), RetT>; diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Primitive.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Primitive.h index 9447971fb08..088613ada5d 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Primitive.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Primitive.h @@ -4,9 +4,10 @@ #pragma once #include #include -#include "../Attribute.h" -#include "../Exceptions.h" -#include "Traits.h" + +#include "lanelet2_core/Attribute.h" +#include "lanelet2_core/Exceptions.h" +#include "lanelet2_core/primitives/Traits.h" namespace lanelet { //! @defgroup DataObjects lanelet data management @@ -29,7 +30,7 @@ namespace lanelet { */ class PrimitiveData { public: - PrimitiveData() noexcept : id{InvalId} {} + PrimitiveData() noexcept = default; PrimitiveData(PrimitiveData&& rhs) noexcept = default; PrimitiveData& operator=(PrimitiveData&& rhs) noexcept = default; PrimitiveData(const PrimitiveData& rhs) = default; @@ -40,7 +41,7 @@ class PrimitiveData { */ explicit PrimitiveData(Id id, AttributeMap attributes = AttributeMap()) : id{id}, attributes{std::move(attributes)} {} - Id id; //!< Id of this primitive (unique across one map) + Id id{InvalId}; //!< Id of this primitive (unique across one map) AttributeMap attributes; //!< attributes of this primitive protected: @@ -319,7 +320,7 @@ bool isLaneletPrimitiveHelper(NotPrimitive* /*unused*/, long /*unused*/) { // N template constexpr bool isLaneletPrimitive() { - PrimitiveT* v; + PrimitiveT* v = nullptr; return IsLaneletPrimitiveHelper(v, 0); } } // namespace traits diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/RegulatoryElement.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/RegulatoryElement.h index 51af7cdea0d..b6198d47f24 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/RegulatoryElement.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/RegulatoryElement.h @@ -2,14 +2,15 @@ #include #include -#include "../Forward.h" -#include "../utility/HybridMap.h" -#include "Area.h" -#include "Lanelet.h" -#include "LineString.h" -#include "Point.h" -#include "Polygon.h" -#include "Primitive.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_core/primitives/Polygon.h" +#include "lanelet2_core/primitives/Primitive.h" +#include "lanelet2_core/utility/HybridMap.h" namespace lanelet { //! @defgroup RegulatoryElementPrimitives Regulatory Element @@ -433,7 +434,7 @@ template <> inline boost::optional RegulatoryElement::find(Id id) const { for (const auto& params : parameters()) { for (const auto& elem : params.second) { - auto telem = boost::get(&elem); + const auto* telem = boost::get(&elem); if (telem != nullptr && !telem->expired() && telem->lock().id() == id) { return telem->lock(); } @@ -446,7 +447,7 @@ template <> inline boost::optional RegulatoryElement::find(Id id) const { for (const auto& params : parameters()) { for (const auto& elem : params.second) { - auto telem = boost::get(&elem); + const auto* telem = boost::get(&elem); if (telem != nullptr && !telem->expired() && telem->lock().id() == id) { return telem->lock(); } @@ -517,12 +518,5 @@ inline bool operator!=(const RegulatoryElementConstPtr& lhs, const RegulatoryEle // Hash function for usage in containers namespace std { template <> -struct hash{ - size_t operator()(const lanelet::RegulatoryElementPtr& x) const noexcept { return std::hash()(x->id()); } -}; -template <> -struct hash{ - size_t operator()(const lanelet::RegulatoryElementConstPtr& x) const noexcept { return std::hash()(x->id()); } -}; - -} // namespace lanelet +struct hash : public lanelet::HashBase {}; +} // namespace std diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Traits.h b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Traits.h index d3a1b4406ee..fc5d1310532 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Traits.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/primitives/Traits.h @@ -1,5 +1,5 @@ #pragma once -#include "../Forward.h" +#include "lanelet2_core/Forward.h" namespace lanelet { namespace traits { @@ -93,13 +93,13 @@ using ThreeD = typename PrimitiveTraits::ThreeDType; //! Converts a primitive to its matching threeD type template -auto to3D(const PrimitiveT& primitive) -> decltype(ThreeD(primitive)) { +auto to3D(const PrimitiveT& primitive) -> ThreeD { return ThreeD(primitive); } //! Converts a primitive to its matching twoD type template -auto to2D(const PrimitiveT& primitive) -> decltype(TwoD(primitive)) { +auto to2D(const PrimitiveT& primitive) -> TwoD { return TwoD(primitive); } diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/utility/HybridMap.h b/lanelet2/lanelet2_core/include/lanelet2_core/utility/HybridMap.h index 06e37cb4275..9ba57a4e63a 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/utility/HybridMap.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/utility/HybridMap.h @@ -126,21 +126,21 @@ class HybridMap { iterator end() { return m_.end(); } const_iterator begin() const { return m_.begin(); } const_iterator end() const { return m_.end(); } + std::pair insert(const value_type& v) { auto it = m_.insert(v); if (it.second) { - auto attr = Array::findKey(v.first.c_str()); - if (attr != std::end(PairArray)) { // NOLINT - const auto pos = static_cast(attr->second); - if (v_.size() < pos + 1) { - v_.resize(pos + 1, m_.end()); - } - v_[pos] = it.first; - } + updateV(it.first); } return it; } + iterator insert(const_iterator hint, const value_type& v) { + auto it = m_.insert(hint, v); + updateV(it); + return it; + } + iterator erase(const_iterator pos) { auto itV = std::find(v_.begin(), v_.end(), pos); if (itV != v_.end()) { @@ -217,6 +217,16 @@ class HybridMap { bool operator!=(const HybridMap& other) const { return !(*this == other); } private: + void updateV(iterator it) { + auto attr = Array::findKey(it->first.c_str()); + if (attr != std::end(PairArray)) { // NOLINT + const auto pos = static_cast(attr->second); + if (v_.size() < pos + 1) { + v_.resize(pos + 1, m_.end()); + } + v_[pos] = it; + } + } Map m_; Vec v_; }; diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/utility/Units.h b/lanelet2/lanelet2_core/include/lanelet2_core/utility/Units.h index 1438c19fec0..8e83ba310aa 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/utility/Units.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/utility/Units.h @@ -2,7 +2,8 @@ #include #include #include -#include "../Forward.h" + +#include "lanelet2_core/Forward.h" namespace lanelet { namespace units { diff --git a/lanelet2/lanelet2_core/include/lanelet2_core/utility/Utilities.h b/lanelet2/lanelet2_core/include/lanelet2_core/utility/Utilities.h index 6f09a54b5f9..2d4f9334b35 100644 --- a/lanelet2/lanelet2_core/include/lanelet2_core/utility/Utilities.h +++ b/lanelet2/lanelet2_core/include/lanelet2_core/utility/Utilities.h @@ -8,8 +8,9 @@ #include #include #include -#include "../Forward.h" -#include "Optional.h" + +#include "lanelet2_core/Forward.h" +#include "lanelet2_core/utility/Optional.h" namespace lanelet { @@ -316,7 +317,7 @@ std::vector getVariant(const std::vector& v) { std::vector s; s.reserve(v.size()); for (const auto& e : v) { - auto t = boost::get(&e); + const auto* t = boost::get(&e); if (t) { s.push_back(*t); } diff --git a/lanelet2/lanelet2_core/package.xml b/lanelet2/lanelet2_core/package.xml index b03532cc448..9dc881eac6f 100644 --- a/lanelet2/lanelet2_core/package.xml +++ b/lanelet2/lanelet2_core/package.xml @@ -1,21 +1,27 @@ - + + lanelet2_core - 0.9.0 + 1.1.1 Lanelet2 core module BSD Fabian Poggenhans + Frank Bieder Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest eigen boost + catkin + ament_cmake diff --git a/lanelet2/lanelet2_core/res/lanelet_gdb.py b/lanelet2/lanelet2_core/res/lanelet_gdb.py index 6a1eba74f25..616842dabc5 100755 --- a/lanelet2/lanelet2_core/res/lanelet_gdb.py +++ b/lanelet2/lanelet2_core/res/lanelet_gdb.py @@ -21,6 +21,7 @@ import gdb + class LaneletPrinter: def __init__(self, val): self.val = val @@ -167,6 +168,7 @@ def __next__(self): except KeyError: raise StopIteration + class RegulatoryElementPrinter: def __init__(self, val): self.val = val @@ -201,7 +203,7 @@ def __next__(self): def lookup_type(val): - type_and_mod = str(val.type).split(" ") # type and modifiers + type_and_mod = str(val.type).split(" ") # type and modifiers if 'lanelet::Lanelet' in type_and_mod or 'lanelet::ConstLanelet' in type_and_mod: return LaneletPrinter(val) diff --git a/lanelet2/lanelet2_core/res/qtcreator_debugging_helpers.py b/lanelet2/lanelet2_core/res/qtcreator_debugging_helpers.py index 6c6ce964f22..87b15134797 100755 --- a/lanelet2/lanelet2_core/res/qtcreator_debugging_helpers.py +++ b/lanelet2/lanelet2_core/res/qtcreator_debugging_helpers.py @@ -2,44 +2,48 @@ # simply specify its path in qtCreator under Options->Debugger->Locals&Expressionts->Extra debugging helpers. from dumper import * + def vectorSize(vectorValue): innerType = vectorValue.type[0] (start, finish, alloc) = vectorValue.split("ppp") size = int((finish - start) / innerType.size()) return size - + + def mapSize(mapValue): (compare, stuff, parent, left, right, size) = mapValue.split('pppppp') return size - + + def unorderedMapSize(value): try: # gcc ~= 4.7 size = value["_M_element_count"].integer() start = value["_M_before_begin"]["_M_nxt"] - except: + except BaseException: try: # libc++ (Mac) size = value["_M_h"]["_M_element_count"].integer() start = value["_M_h"]["_M_bbegin"]["_M_node"]["_M_nxt"] - except: + except BaseException: try: # gcc 4.9.1 size = value["_M_h"]["_M_element_count"].integer() start = value["_M_h"]["_M_before_begin"]["_M_nxt"] - except: + except BaseException: # gcc 4.6.2 size = value["_M_element_count"].integer() start = value["_M_buckets"].dereference() return size - - + + def displayStringValue(d, value): innerType = value.type[0] (data, size) = value.split("pI") - d.check(0 <= size) #and size <= alloc and alloc <= 100*1000*1000) + d.check(0 <= size) # and size <= alloc and alloc <= 100*1000*1000) d.putCharArrayHelper(data, size, innerType, d.currentItemFormat(), makeExpandable=False) + def qdump__lanelet__LineString2d(d, value): data = value["constData_"]["_M_ptr"].dereference() d.putValue(data["id"].integer()) @@ -51,8 +55,10 @@ def qdump__lanelet__LineString2d(d, value): d.putSubItem("attributes", data["attributes"]) d.putSubItem("points", data["points_"]) + def qdump__lanelet__ConstLineString2d(d, value): - qdump__lanelet__LineString2d(d,value) + qdump__lanelet__LineString2d(d, value) + def qdump__lanelet__LineString3d(d, value): data = value["constData_"]["_M_ptr"].dereference() @@ -65,20 +71,26 @@ def qdump__lanelet__LineString3d(d, value): d.putSubItem("attributes", data["attributes"]) d.putSubItem("points", data["points_"]) + def qdump__lanelet__ConstLineString3d(d, value): - qdump__lanelet__LineString3d(d,value) + qdump__lanelet__LineString3d(d, value) + def qdump__lanelet__Polygon3d(d, value): - qdump__lanelet__LineString3d(d,value) + qdump__lanelet__LineString3d(d, value) + def qdump__lanelet__ConstPolygon3d(d, value): - qdump__lanelet__ConstLineString3d(d,value) + qdump__lanelet__ConstLineString3d(d, value) + def qdump__lanelet__Polygon2d(d, value): - qdump__lanelet__LineString2d(d,value) + qdump__lanelet__LineString2d(d, value) + def qdump__lanelet__ConstPolygon2d(d, value): - qdump__lanelet__ConstLineString2d(d,value) + qdump__lanelet__ConstLineString2d(d, value) + def qdump__lanelet__Point3d(d, value): data = value["constData_"]["_M_ptr"].dereference() @@ -87,29 +99,33 @@ def qdump__lanelet__Point3d(d, value): if d.isExpanded(): p = data["point"] with Children(d): - (x,y,z) = p.split('ddd') + (x, y, z) = p.split('ddd') with SubItem(d, "x"): - d.putValue(x) - d.putType("double") + d.putValue(x) + d.putType("double") with SubItem(d, "y"): - d.putValue(y) - d.putType("double") + d.putValue(y) + d.putType("double") with SubItem(d, "z"): - d.putValue(z) - d.putType("double") + d.putValue(z) + d.putType("double") d.putSubItem("id", data["id"]) d.putSubItem("attributes", data["attributes"]) d.putSubItem("point2d_", data["point2d_"]) - -def qdump__lanelet__Point2d(d, value): + + +def qdump__lanelet__Point2d(d, value): qdump__lanelet__Point3d(d, value) - -def qdump__lanelet__ConstPoint3d(d, value): + + +def qdump__lanelet__ConstPoint3d(d, value): qdump__lanelet__Point3d(d, value) - -def qdump__lanelet__ConstPoint2d(d, value): + + +def qdump__lanelet__ConstPoint2d(d, value): qdump__lanelet__Point3d(d, value) - + + def qdump__lanelet__Lanelet(d, value): data = value["constData_"]["_M_ptr"].dereference() d.putValue(data["id"].integer()) @@ -125,9 +141,10 @@ def qdump__lanelet__Lanelet(d, value): d.putSubItem("inverted", value["inverted_"]) -def qdump__lanelet__ConstLanelet(d, value): +def qdump__lanelet__ConstLanelet(d, value): qdump__lanelet__Lanelet(d, value) - + + def qdump__lanelet__Area(d, value): data = value["constData_"]["_M_ptr"].dereference() d.putValue(data["id"].integer()) @@ -141,19 +158,22 @@ def qdump__lanelet__Area(d, value): d.putSubItem("regulatoryElements", data["regulatoryElements_"]) d.putSubItem("outerBoundPolygon", data["outerBoundPolygon_"]) d.putSubItem("innerBoundPolygons", data["innerBoundPolygons_"]) - -def qdump__lanelet__ConstArea(d,value): - qdump__lanelet__Area(d,value) + + +def qdump__lanelet__ConstArea(d, value): + qdump__lanelet__Area(d, value) + def qdump__lanelet__CompoundPolygon3d(d, value): data = value["data_"]["_M_ptr"].dereference() - + d.putItemCount(vectorSize(data['ls_'])) if d.isExpanded(): with Children(d): d.putSubItem("data", data) - -def qdump__lanelet__HybridMap(d,value): + + +def qdump__lanelet__HybridMap(d, value): d.putItemCount(mapSize(value['m_'])) d.putNumChild(2) if d.isExpanded(): @@ -170,6 +190,7 @@ def qdump__lanelet__Attribute(d, value): d.putSubItem("cache_", value["cache_"]) d.putSubItem("value_", value["value_"]) + def qdump__lanelet__RegulatoryElement(d, value): data = value["constData_"]["_M_ptr"].dereference() d.putValue(data["id"].integer()) @@ -189,9 +210,3 @@ def qdump__lanelet__PrimitiveLayer(d, value): with Children(d): d.putSubItem("elements", umap) d.putSubItem("tree", value["tree_"]) - - - - - - diff --git a/lanelet2/lanelet2_core/src/Attribute.cpp b/lanelet2/lanelet2_core/src/Attribute.cpp index 216640ebeb7..bac48c353c5 100644 --- a/lanelet2/lanelet2_core/src/Attribute.cpp +++ b/lanelet2/lanelet2_core/src/Attribute.cpp @@ -1,9 +1,11 @@ -#include "Attribute.h" -#include +#include "lanelet2_core/Attribute.h" + #include #include #include -#include "utility/Units.h" + +#include "lanelet2_core/Exceptions.h" +#include "lanelet2_core/utility/Units.h" namespace lanelet { namespace { @@ -58,7 +60,7 @@ Attribute::Attribute(const Velocity& value) : value_{std::to_string(units::KmHQu Optional Attribute::asBool() const { // try load from cache - auto val = load(cache_); + auto* val = load(cache_); if (val != nullptr) { return *val; } @@ -78,7 +80,7 @@ Optional Attribute::asBool() const { Optional Attribute::asDouble() const { // try load from cache - auto val = load(cache_); + auto* val = load(cache_); if (val != nullptr) { return *val; } @@ -92,7 +94,7 @@ Optional Attribute::asDouble() const { Optional Attribute::asId() const { // try load from cache - auto val = load(cache_); + auto* val = load(cache_); if (val != nullptr) { return *val; } @@ -106,7 +108,7 @@ Optional Attribute::asId() const { Optional Attribute::asInt() const { // try load from cache - auto val = load(cache_); + auto* val = load(cache_); if (val != nullptr) { return *val; } @@ -120,7 +122,7 @@ Optional Attribute::asInt() const { Optional Attribute::asVelocity() const { // try load from cache - auto val = load(cache_); + auto* val = load(cache_); if (val != nullptr) { return *val; } diff --git a/lanelet2/lanelet2_core/src/BasicRegulatoryElements.cpp b/lanelet2/lanelet2_core/src/BasicRegulatoryElements.cpp index 30058b735b9..d27909e843d 100644 --- a/lanelet2/lanelet2_core/src/BasicRegulatoryElements.cpp +++ b/lanelet2/lanelet2_core/src/BasicRegulatoryElements.cpp @@ -1,10 +1,12 @@ -#include "primitives/BasicRegulatoryElements.h" +#include "lanelet2_core/primitives/BasicRegulatoryElements.h" + #include -#include "Exceptions.h" -#include "primitives/LineString.h" -#include "primitives/Point.h" -#include "primitives/RegulatoryElement.h" -#include "utility/Utilities.h" + +#include "lanelet2_core/Exceptions.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" +#include "lanelet2_core/utility/Utilities.h" namespace std { bool operator==(const lanelet::LaneletDataConstWptr& lhs, const lanelet::LaneletDataConstWptr& rhs) { @@ -56,12 +58,12 @@ LineStringsOrPolygons3d getLsOrPoly(const RuleParameterMap& paramsMap, RoleName } LineStringsOrPolygons3d result; - for (auto& param : params->second) { - auto l = boost::get(¶m); + for (const auto& param : params->second) { + const auto* l = boost::get(¶m); if (l != nullptr) { result.push_back(*l); } - auto p = boost::get(¶m); + const auto* p = boost::get(¶m); if (p != nullptr) { result.push_back(*p); } @@ -333,7 +335,7 @@ SpeedLimit::SpeedLimit(const RegulatoryElementDataPtr& data) : TrafficSign(data) void TrafficSign::addCancellingTrafficSign(const TrafficSignsWithType& signs) { updateTrafficSigns(signs); - for (auto& sign : signs.trafficSigns) { + for (const auto& sign : signs.trafficSigns) { parameters()[RoleName::Cancels].emplace_back(sign.asRuleParameter()); } } diff --git a/lanelet2/lanelet2_core/src/Lanelet.cpp b/lanelet2/lanelet2_core/src/Lanelet.cpp index 78e233532ee..58753ae0c65 100644 --- a/lanelet2/lanelet2_core/src/Lanelet.cpp +++ b/lanelet2/lanelet2_core/src/Lanelet.cpp @@ -1,10 +1,12 @@ -#include "primitives/Lanelet.h" +#include "lanelet2_core/geometry/Lanelet.h" + #include -#include "geometry/Lanelet.h" -#include "geometry/LineString.h" -#include "geometry/Polygon.h" -#include "primitives/CompoundPolygon.h" -#include "primitives/RegulatoryElement.h" + +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/CompoundPolygon.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" namespace lanelet { namespace bg = boost::geometry; @@ -64,7 +66,7 @@ class BoundChecker { } bool secondCrossesBounds(const BasicSegment2d& seg, bool left) const { - auto& segmentTree = left ? leftSegments_ : rightSegments_; + const auto& segmentTree = left ? leftSegments_ : rightSegments_; for (auto it = segmentTree.qbegin(bgi::intersects(seg)); it != segmentTree.qend(); ++it) { using boost::geometry::equals; if (!equals(it->first, seg.second) && !equals(it->second, seg.second)) { @@ -196,8 +198,10 @@ std::shared_ptr calculateCenterline(const ConstLineString2d& ++leftCurrent; } while (leftCurrent != leftBound.end() || rightCurrent != rightBound.end()) { - OptDistance leftCandidateDistance, rightCandidateDistance; - ConstLineString2d::const_iterator leftCandidate, rightCandidate; + OptDistance leftCandidateDistance; + OptDistance rightCandidateDistance; + ConstLineString2d::const_iterator leftCandidate; + ConstLineString2d::const_iterator rightCandidate; // Determine left candidate std::tie(leftCandidate, leftCandidateDistance) = diff --git a/lanelet2/lanelet2_core/src/LaneletMap.cpp b/lanelet2/lanelet2_core/src/LaneletMap.cpp index bcc38b8dccf..d72f9839efb 100644 --- a/lanelet2/lanelet2_core/src/LaneletMap.cpp +++ b/lanelet2/lanelet2_core/src/LaneletMap.cpp @@ -1,15 +1,17 @@ #define LANELET_LAYER_DEFINITION -#include "LaneletMap.h" +#include "lanelet2_core/LaneletMap.h" + #include #include #include #include -#include "geometry/Area.h" -#include "geometry/BoundingBox.h" -#include "geometry/Lanelet.h" -#include "geometry/LineString.h" -#include "geometry/Polygon.h" -#include "geometry/RegulatoryElement.h" + +#include "lanelet2_core/geometry/Area.h" +#include "lanelet2_core/geometry/BoundingBox.h" +#include "lanelet2_core/geometry/Lanelet.h" +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/geometry/RegulatoryElement.h" // boost geometry stuff namespace bgi = boost::geometry::index; @@ -1085,6 +1087,10 @@ LaneletMapUPtr createMap(const Lanelets& fromLanelets, const Areas& fromAreas) { for (auto ll : fromLanelets) { ls.push_back(ll.leftBound()); ls.push_back(ll.rightBound()); + if (ll.hasCustomCenterline()) { + auto center = ll.centerline(); + ls.emplace_back(std::const_pointer_cast(center.constData()), center.inverted()); + } } auto appendMultiLs = [&ls](auto& lsappend) { std::for_each(lsappend.begin(), lsappend.end(), [&ls](auto& l) { ls.push_back(l); }); @@ -1098,11 +1104,11 @@ LaneletMapUPtr createMap(const Lanelets& fromLanelets, const Areas& fromAreas) { auto points = utils::concatenateRange(ls, [](auto ls) { return std::make_pair(ls.begin(), ls.end()); }); auto regelems = utils::concatenateRange(fromLanelets, [](Lanelet llt) { - auto& regelems = llt.regulatoryElements(); + const auto& regelems = llt.regulatoryElements(); return std::make_pair(regelems.begin(), regelems.end()); }); auto areaRegelems = utils::concatenateRange(fromAreas, [](Area area) { - auto& regelems = area.regulatoryElements(); + const auto& regelems = area.regulatoryElements(); return std::make_pair(regelems.begin(), regelems.end()); }); auto map = std::make_unique(toMap(fromLanelets), toMap(fromAreas), RegulatoryElementLayer::Map(), @@ -1166,10 +1172,10 @@ LaneletSubmapUPtr createSubmap(const Areas& fromAreas) { return createSubmap({}, LaneletSubmapUPtr createSubmap(const Lanelets& fromLanelets, const Areas& fromAreas) { auto map = std::make_unique(toMap(fromLanelets), toMap(fromAreas), RegulatoryElementLayer::Map(), PolygonLayer::Map(), LineStringLayer::Map(), PointLayer::Map()); - for (auto& ll : fromLanelets) { + for (const auto& ll : fromLanelets) { utils::forEach(ll.regulatoryElements(), [&](auto& regelem) { map->trackParameters(*regelem); }); } - for (auto& ar : fromAreas) { + for (const auto& ar : fromAreas) { utils::forEach(ar.regulatoryElements(), [&](auto& regelem) { map->trackParameters(*regelem); }); } return map; @@ -1198,13 +1204,17 @@ class NSmallestElements { auto pos = std::lower_bound(values_.begin(), values_.end(), measure, [](auto& v1, double v2) { return v1.first < v2; }); if (pos != values_.end() || values_.size() < n_) { + if (values_.size() >= n_) { + values_.pop_back(); + } values_.emplace(pos, measure, value); return true; } return false; } const auto& values() const { return values_; } - bool full() const { return n_ <= values_.size(); } + auto moveValues() { return std::move(values_); } + bool full() const { return values_.size() >= n_; } bool empty() const { return values_.empty(); } private: @@ -1229,7 +1239,7 @@ auto findNearestImpl(LayerT&& map, const BasicPoint2d& pt, unsigned count) { return false; }; map.nearestUntil(pt, searchFunction); - return closest.values(); + return closest.moveValues(); } } // namespace diff --git a/lanelet2/lanelet2_core/src/LaneletSequence.cpp b/lanelet2/lanelet2_core/src/LaneletSequence.cpp index 336ef2baf82..5712a6288ab 100644 --- a/lanelet2/lanelet2_core/src/LaneletSequence.cpp +++ b/lanelet2/lanelet2_core/src/LaneletSequence.cpp @@ -1,4 +1,4 @@ -#include "primitives/LaneletSequence.h" +#include "lanelet2_core/primitives/LaneletSequence.h" namespace lanelet { diff --git a/lanelet2/lanelet2_core/src/LineStringGeometry.cpp b/lanelet2/lanelet2_core/src/LineStringGeometry.cpp index 202c1af6196..1da26b95a91 100644 --- a/lanelet2/lanelet2_core/src/LineStringGeometry.cpp +++ b/lanelet2/lanelet2_core/src/LineStringGeometry.cpp @@ -1,13 +1,55 @@ +#include +#if BOOST_VERSION < 106300 && BOOST_VERSION >= 106200 +// Boost 1.62 is missing an iostream include... +#include +#endif #include #include #include -#include "geometry/LineString.h" -#include "geometry/Polygon.h" + +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/Polygon.h" namespace lanelet { namespace geometry { -namespace internal { +namespace { using V3d = BasicPoint3d; + +struct LineParams { + double sN; + double sD; + double tN; + double tD; +}; + +constexpr double SmallNum = 1.e-10; + +inline LineParams calculateLineParams(double a, double b, double c, double d, double e, double den) { + // compute the line parameters of the two closest points + if (den < SmallNum) { // the lines are almost parallel + // force using point P0 on segment S1 + // to prevent possible division by 0.0 later + return {0.0, 1.0, e, c}; + } + LineParams lp{}; + lp.sD = den; + lp.tD = den; + // get the closest points on the infinite lines + lp.sN = (b * e - c * d); + lp.tN = (a * e - b * d); + if (lp.sN < 0.0) { // sc < 0 => the s=0 edge is visible + lp.sN = 0.0; + lp.tN = e; + lp.tD = c; + } else if (lp.sN > lp.sD) { // sc > 1 => the s=1 edge is visible + lp.sN = lp.sD; + lp.tN = e + b; + lp.tD = c; + } + + return lp; +} + std::pair projectedPoint3d(const BasicPoint3d& p1, const BasicPoint3d& p2, const BasicPoint3d& q1, const BasicPoint3d& q2) { // see http://geomalgorithms.com/a07-_distance.html @@ -19,59 +61,36 @@ std::pair projectedPoint3d(const BasicPoint3d& p1, c double c = v.dot(v); double d = u.dot(w); double e = v.dot(w); - auto den = a * c - b * b; - constexpr double SmallNum = 1.e-10; - - double sc, sN, sD = den; // sc = sN / sD, default sD = D >= 0 - double tc, tN, tD = den; // tc = tN / tD, default tD = D >= 0 - // compute the line parameters of the two closest points - if (den < SmallNum) { // the lines are almost parallel - sN = 0.0; // force using point P0 on segment S1 - sD = 1.0; // to prevent possible division by 0.0 later - tN = e; - tD = c; - } else { // get the closest points on the infinite lines - sN = (b * e - c * d); - tN = (a * e - b * d); - if (sN < 0.0) { // sc < 0 => the s=0 edge is visible - sN = 0.0; - tN = e; - tD = c; - } else if (sN > sD) { // sc > 1 => the s=1 edge is visible - sN = sD; - tN = e + b; - tD = c; - } - } + auto lp = calculateLineParams(a, b, c, d, e, den); - if (tN < 0.0) { // tc < 0 => the t=0 edge is visible - tN = 0.0; + if (lp.tN < 0.0) { // tc < 0 => the t=0 edge is visible + lp.tN = 0.0; // recompute sc for this edge if (-d < 0.0) { - sN = 0.0; + lp.sN = 0.0; } else if (-d > a) { - sN = sD; + lp.sN = lp.sD; } else { - sN = -d; - sD = a; + lp.sN = -d; + lp.sD = a; } - } else if (tN > tD) { // tc > 1 => the t=1 edge is visible - tN = tD; + } else if (lp.tN > lp.tD) { // tc > 1 => the t=1 edge is visible + lp.tN = lp.tD; // recompute sc for this edge if ((-d + b) < 0.0) { - sN = 0; + lp.sN = 0; } else if ((-d + b) > a) { - sN = sD; + lp.sN = lp.sD; } else { - sN = (-d + b); - sD = a; + lp.sN = (-d + b); + lp.sD = a; } } // finally do the division to get sc and tc - sc = (std::abs(sN) < SmallNum ? 0.0 : sN / sD); - tc = (std::abs(tN) < SmallNum ? 0.0 : tN / tD); + double sc = (std::abs(lp.sN) < SmallNum ? 0.0 : lp.sN / lp.sD); + double tc = (std::abs(lp.tN) < SmallNum ? 0.0 : lp.tN / lp.tD); return {p1 + (sc * u), q1 + (tc * v)}; // return the closest distance } @@ -79,28 +98,22 @@ std::pair projectedPoint3d(const BasicPoint3d& p1, c namespace bg = boost::geometry; namespace bgi = bg::index; namespace bgm = boost::geometry::model; -using Segment = bgm::pointing_segment; +using BasicSegment = bgm::pointing_segment; using Box = bgm::box>; -using Node = std::pair; +using Node = std::pair; using RTree = bgi::rtree>; -template -std::pair projectedPoint3dImpl(const LineStringT& l1, const LineStringT& l2) { - bool swap = l1.size() < l2.size(); - auto* smallerRange = swap ? &l1 : &l2; - auto* greaterRange = swap ? &l2 : &l1; - +template +std::pair projectedPoint3dOrdered(const LineString1T& smallerRange, + const LineString2T& greaterRange) { // catch some degerated cases ConstHybridLineString3d duplicate; - if (smallerRange->size() == 1 && greaterRange->size() == 1) { - std::pair ret(greaterRange->front(), smallerRange->front()); - if (swap) { - std::swap(ret.first, ret.second); - } + if (smallerRange.size() == 1 && greaterRange.size() == 1) { + std::pair ret(greaterRange.front(), smallerRange.front()); return ret; } auto values = - utils::transform(bg::segments_begin(*greaterRange), bg::segments_end(*greaterRange), [](const auto& segm) { + utils::transform(bg::segments_begin(greaterRange), bg::segments_end(greaterRange), [](const auto& segm) { Box box; boost::geometry::envelope(segm, box); return Node(box, segm); @@ -110,20 +123,17 @@ std::pair projectedPoint3dImpl(const LineStringT& l1 bool first = true; double dMin{}; std::pair closestPair; - for (auto it = bg::segments_begin(*smallerRange); it != bg::segments_end(*smallerRange); ++it) { + for (auto it = bg::segments_begin(smallerRange); it != bg::segments_end(smallerRange); ++it) { Box queryBox; bg::envelope(*it, queryBox); - for (auto qIt = tree.qbegin(bgi::nearest(queryBox, greaterRange->size())); qIt != tree.qend(); + for (auto qIt = tree.qbegin(bgi::nearest(queryBox, unsigned(greaterRange.size()))); qIt != tree.qend(); ++qIt, first = false) { - auto& nearest = *qIt; + const auto& nearest = *qIt; auto dBox = boost::geometry::distance(nearest.first, queryBox); if (!first && dBox > dMin) { break; } auto projPair = projectedPoint3d(*nearest.second.first, *nearest.second.second, *it->first, *it->second); - if (swap) { - std::swap(projPair.first, projPair.second); - } auto d = (projPair.first - projPair.second).norm(); if (first || d < dMin) { closestPair = projPair; @@ -134,15 +144,49 @@ std::pair projectedPoint3dImpl(const LineStringT& l1 return closestPair; } +template +std::pair projectedPoint3dImpl(const LineString1T& l1, const LineString2T& l2) { + if (l1.size() < l2.size()) { + return projectedPoint3dOrdered(l1, l2); + } + auto res = projectedPoint3dOrdered(l2, l1); + return {res.second, res.first}; +} +} // namespace + +namespace internal { std::pair projectedPoint3d(const CompoundHybridLineString3d& l1, const CompoundHybridLineString3d& l2) { return projectedPoint3dImpl(l1, l2); } + +std::pair projectedPoint3d(const ConstHybridLineString3d& l1, + const CompoundHybridLineString3d& l2) { + return projectedPoint3dImpl(l1, l2); +} + +std::pair projectedPoint3d(const CompoundHybridLineString3d& l1, + const ConstHybridLineString3d& l2) { + return projectedPoint3dImpl(l1, l2); +} + std::pair projectedPoint3d(const ConstHybridLineString3d& l1, const ConstHybridLineString3d& l2) { return projectedPoint3dImpl(l1, l2); } +std::pair projectedPoint3d(const ConstHybridLineString3d& l1, const BasicLineString3d& l2) { + return projectedPoint3dImpl(l1, l2); +} + +std::pair projectedPoint3d(const BasicLineString3d& l1, const ConstHybridLineString3d& l2) { + return projectedPoint3dImpl(l1, l2); +} + +std::pair projectedPoint3d(const BasicLineString3d& l1, const BasicLineString3d& l2) { + return projectedPoint3dImpl(l1, l2); +} + std::pair projectedBorderPoint3d(const ConstHybridPolygon3d& l1, const ConstHybridPolygon3d& l2) { return projectedPoint3dImpl(l1, l2); diff --git a/lanelet2/lanelet2_core/src/PolygonTriangulationGeometry.cpp b/lanelet2/lanelet2_core/src/PolygonTriangulationGeometry.cpp new file mode 100644 index 00000000000..7635e691aab --- /dev/null +++ b/lanelet2/lanelet2_core/src/PolygonTriangulationGeometry.cpp @@ -0,0 +1,457 @@ +#include + +#include "lanelet2_core/geometry/Polygon.h" + +using VoronoiPrecision = std::int64_t; + +namespace { +VoronoiPrecision toVoronoi(double v) { return static_cast(v * 100); } +} // namespace + +using AlignedBasicPoint2d = Eigen::Matrix; + +namespace boost { +namespace polygon { +template <> +struct geometry_concept { + using type = point_concept; // NOLINT +}; + +// specialize getter +template <> +struct point_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + static inline coordinate_type get(const lanelet::ConstPoint2d& point, const orientation_2d& orient) { + return toVoronoi((orient == HORIZONTAL) ? point.x() : point.y()); + } +}; + +// specialize setter +template <> +struct point_mutable_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + + static inline void set(lanelet::ConstPoint2d& /*point*/, const orientation_2d& /*orient*/, + VoronoiPrecision /*value*/) { + assert(false && "boost polygon should never call this!"); + } +}; + +template <> +struct geometry_concept { + using type = point_concept; // NOLINT +}; + +// specialize getter +template <> +struct point_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + static inline coordinate_type get(const lanelet::BasicPoint2d& point, const orientation_2d& orient) { + return toVoronoi((orient == HORIZONTAL) ? point.x() : point.y()); + } +}; + +// specialize setter +template <> +struct point_mutable_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + + static inline void set(lanelet::BasicPoint2d& /*point*/, const orientation_2d& /*orient*/, + VoronoiPrecision /*value*/) { + assert(false && "boost polygon should never call this!"); + } +}; + +template <> +struct geometry_concept { + using type = point_concept; // NOLINT +}; + +// specialize getter +template <> +struct point_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + static inline coordinate_type get(const AlignedBasicPoint2d& point, const orientation_2d& orient) { + return toVoronoi((orient == HORIZONTAL) ? point.x() : point.y()); + } +}; + +// specialize setter +template <> +struct point_mutable_traits { + using coordinate_type = VoronoiPrecision; // NOLINT + + static inline void set(AlignedBasicPoint2d& /*point*/, const orientation_2d& /*orient*/, VoronoiPrecision /*value*/) { + assert(false && "boost polygon should never call this!"); + } +}; +} // namespace polygon +} // namespace boost + +namespace { +using namespace lanelet; +using namespace lanelet::geometry; + +using IndexedPolygon = std::vector; +using IndexedPolygons = std::vector; + +bool isConnectionConvex(const BasicPoint2d& seg1, const BasicPoint2d& seg2, + const double eps = 4 * std::numeric_limits::epsilon()) { + return lanelet::geometry::internal::crossProd(seg1.normalized(), seg2.normalized()).z() <= eps; +} +using IndexedSegment = std::pair; +using IndexedSegments = std::vector; +using IndexedSegmentPair = std::pair; +IndexedSegment flip(const IndexedSegment& seg) { return std::make_pair(seg.second, seg.first); } +bool isBorder(const IndexedSegment& seg, const size_t polySize) { + const auto distance = seg.first > seg.second ? seg.first - seg.second : seg.second - seg.first; + if (distance == 1) { + return true; + } + return (seg.first == 0 || seg.second == 0) && distance + 1 == polySize; +} + +using PolygonIterator = IndexedPolygon::const_iterator; +using PolygonIteratorPair = std::pair; +using VoronoiGraph = boost::polygon::voronoi_diagram; + +PolygonIteratorPair getAlignedIterators(const IndexedPolygon& poly, const IndexedSegment& segment) { + if (poly.size() < 3) { + throw InvalidInputError("Can't find segment from polygon with less than 3 vertices"); + } + PolygonIteratorPair itPair = std::make_pair(std::find(poly.begin(), poly.end(), segment.first), + std::find(poly.begin(), poly.end(), segment.second)); + if (itPair.first == poly.end() || itPair.second == poly.end()) { + throw InvalidInputError("Index " + std::to_string(segment.first) + "-" + std::to_string(segment.second) + + " not found in indices"); + } + const auto dist = std::distance(itPair.first, itPair.second); + if (dist == -1 || dist == poly.size() - 1) { + std::swap(itPair.first, itPair.second); + } + return itPair; +} + +IndexedSegmentPair getAdjacent(const IndexedPolygon& poly, const IndexedSegment& seg) { + auto itP = getAlignedIterators(poly, seg); + return {{*itP.first, itP.first == poly.begin() ? poly.back() : *std::prev(itP.first)}, + {*itP.second, itP.second == std::prev(poly.end()) ? poly.front() : *std::next(itP.second)}}; +} + +IndexedSegments getSegmentsExcept(const IndexedPolygon& p, const IndexedSegment& excluded) { + IndexedSegments res; + res.reserve(p.size() - 1); + for (size_t i = 0; i < p.size(); ++i) { + IndexedSegment seg{p.at(i), p.at((i + 1) % p.size())}; + if (seg != excluded && seg != flip(excluded)) { + res.emplace_back(seg); + } + } + return res; +} + +IndexedSegments getSegmentIndexesExcept(const IndexedPolygon& p, const IndexedSegment& excluded) { + IndexedSegments res; + res.reserve(p.size() - 1); + for (size_t i = 0; i < p.size(); ++i) { + IndexedSegment seg{p.at(i), p.at((i + 1) % p.size())}; + if (seg != excluded && seg != flip(excluded)) { + res.emplace_back(IndexedSegment{i, (i + 1) % p.size()}); + } + } + return res; +} + +IndexedPolygon removeSegment(const IndexedPolygon& poly, const IndexedSegment& excluded) { + auto itP = getAlignedIterators(poly, excluded); + IndexedPolygon res(std::next(itP.second), std::next(itP.first) == poly.end() ? itP.first : poly.end()); + if (itP.first != std::prev(poly.end())) { + res.insert(res.end(), poly.begin(), itP.first); + } + return res; +} + +struct MergeResult { + IndexedPolygon merged; + IndexedSegments addedSegments; +}; + +void insertPolygonExcept(IndexedPolygon& poly, const IndexedPolygon& toMerge, const IndexedSegment& border) { + auto mergeIt = getAlignedIterators(toMerge, border); + auto npIt = getAlignedIterators(poly, border); + auto noWrap = std::next(mergeIt.first) == toMerge.end(); + poly.insert(npIt.second, std::next(mergeIt.second), noWrap ? mergeIt.first : toMerge.end()); + if (!noWrap) { + poly.insert(std::next(npIt.second, std::distance(std::next(mergeIt.second), toMerge.end())), toMerge.begin(), + mergeIt.first); + } +} + +MergeResult merge(const IndexedPolygon& poly, const IndexedPolygon& toMerge, const IndexedSegment& border) { + MergeResult result{{}, getSegmentsExcept(toMerge, border)}; + result.merged.reserve(poly.size() + toMerge.size()); // das hier ist die einzige Allokation + result.merged = poly; + insertPolygonExcept(result.merged, toMerge, border); + return result; +} + +using MetricSegmentPair = std::pair; + +MetricSegmentPair getMetricAdjacentSegmentPair(const BasicPolygon2d& metricPolygon, const IndexedPolygon& poly, + const IndexedSegment& segment) { + const auto newSegments = getAdjacent(poly, segment); + const BasicPoint2d newFirst = metricPolygon.at(newSegments.first.second) - metricPolygon.at(newSegments.first.first); + const BasicPoint2d newSecond = + metricPolygon.at(newSegments.second.second) - metricPolygon.at(newSegments.second.first); + return {newFirst, newSecond}; +} +double getOpposingAngle(const MetricSegmentPair& segmentPair, const size_t polySize) { + return polySize != 3 ? -1. : segmentPair.first.normalized().dot(segmentPair.second.normalized()); +} +bool connectionConvex(const MetricSegmentPair& local, const MetricSegmentPair& extension) { + return isConnectionConvex(-local.first, extension.second) && isConnectionConvex(-extension.first, local.second); +} +using AdjacentPolygons = std::map; +using Visited = std::set; +struct Gate { + IndexedSegment border; + size_t source; +}; +using Gates = std::vector; +Gates makeGates(const IndexedSegments& borders, const size_t src) { + return utils::transform(borders, [&](auto& b) { return Gate{b, src}; }); +} +struct Head { + IndexedPolygon poly; + Gates gates; // run ccw +}; +using Heads = std::vector; +struct Connection { + IndexedSegment border; + double opposingAngle; + MetricSegmentPair connectors; + size_t newPoly; +}; +using Connections = std::vector; +struct TraversalResult { + std::vector convex; + Visited visited; +}; + +template +class VectorMap { + public: + using KeyType = K; + using ValueType = V; + using ElementType = std::pair; + using ContainerType = std::vector; + + void append(const KeyType& key, const ValueType& value) { + if (frozen_) { + throw std::runtime_error("Can't add to frozen vector map"); + } + storage_.emplace_back(ElementType{key, value}); + } + void append(const ElementType& elem) { + if (frozen_) { + throw std::runtime_error("Can't add to frozen vector map"); + } + storage_.emplace_back(elem); + } + void freeze() { + if (!frozen_) { + std::sort(storage_.begin(), storage_.end()); + frozen_ = true; + } + } + + const ValueType& at(const KeyType& key) const { + if (!frozen_) { + throw std::runtime_error("Can't search in unfrozen vector map"); + } + auto it = std::lower_bound(storage_.begin(), storage_.end(), key, + [](auto& value, const KeyType& k) { return value.first < k; }); + if (it == storage_.end() || key != it->first) { + throw std::runtime_error("Item not found in vector map"); + } + return it->second; + } + + private: + ContainerType storage_; + bool frozen_{false}; +}; +using Adjacencies = VectorMap; + +class SegmentationData { + public: + explicit SegmentationData(const size_t convexPartsSize) { convexParts_.resize(convexPartsSize); } + void addConvex(const IndexedPolygon& convexPoly, const int idx) { convexParts_[idx] = convexPoly; } + void addSegment(const IndexedSegment& segment, const size_t adjacentPolygonIdx) { + adjacent_.append(flip(segment), adjacentPolygonIdx); + } + const Adjacencies& getAdjacencies() const { return adjacent_; } + const IndexedPolygons& getConvexPolygons() const { return convexParts_; } + size_t getDestination(const Gate& gate) const { return adjacent_.at(gate.border); } + const IndexedPolygon& getPolygonByIdx(const size_t idx) const { return convexParts_.at(idx); } + void freeze() { adjacent_.freeze(); } + + private: + Adjacencies adjacent_; + std::vector convexParts_; +}; + +Connections findGates(const BasicPolygon2d& metricPolygon, const Gates& candidates, const Visited& overallVisited, + const SegmentationData& segData) { + Connections gates; + for (const auto& gate : candidates) { + if (isBorder(gate.border, metricPolygon.size())) { + continue; + } + const auto opposingPolygonIdx = segData.getDestination(gate); + if (overallVisited.find(opposingPolygonIdx) != overallVisited.end()) { + continue; + } + const auto& opposingPoly = segData.getPolygonByIdx(opposingPolygonIdx); + auto metricSegPair = getMetricAdjacentSegmentPair(metricPolygon, opposingPoly, gate.border); + gates.emplace_back(Connection{gate.border, getOpposingAngle(metricSegPair, opposingPoly.size()), metricSegPair, + opposingPolygonIdx}); + } + + std::sort(gates.begin(), gates.end(), + [](const auto& lhs, const auto& rhs) { return lhs.opposingAngle < rhs.opposingAngle; }); + return gates; +} + +void updateState(Head& head, TraversalResult& traversalResult, const IndexedPolygon& newPoly, const Connection& conn) { + traversalResult.visited.insert(conn.newPoly); + auto mergeResult = merge(head.poly, newPoly, conn.border); + head.poly = std::move(mergeResult.merged); + head.gates = makeGates(mergeResult.addedSegments, conn.newPoly); +} + +void traverse(const BasicPolygon2d& metricPolygon, Head& head, TraversalResult& traversalResult, + const SegmentationData& segData, const bool isOrigin) { + auto gates = findGates(metricPolygon, head.gates, traversalResult.visited, segData); + std::vector closedGates; + for (const auto& conn : gates) { + if (traversalResult.visited.find(conn.newPoly) != traversalResult.visited.end()) { + continue; + } + const auto headsideAdjacent = getMetricAdjacentSegmentPair(metricPolygon, head.poly, conn.border); + if (connectionConvex(headsideAdjacent, conn.connectors)) { + updateState(head, traversalResult, segData.getPolygonByIdx(conn.newPoly), conn); + traverse(metricPolygon, head, traversalResult, segData, false); + } else { + closedGates.emplace_back(conn); + } + } + if (isOrigin) { + traversalResult.convex.emplace_back(head.poly); + } + for (const auto& conn : closedGates) { + if (traversalResult.visited.find(conn.newPoly) != traversalResult.visited.end()) { + continue; + } + const auto& newPoly = segData.getPolygonByIdx(conn.newPoly); + Head newHead{newPoly, makeGates(getSegmentsExcept(newPoly, conn.border), conn.newPoly)}; + traverse(metricPolygon, newHead, traversalResult, segData, true); + } +} + +std::vector mergeTriangulation(const BasicPolygon2d& metricPolygon, const SegmentationData& segData) { + IndexedSegment init{1, 0}; + auto firstPolyIdx = segData.getAdjacencies().at(init); + const auto& firstPoly = segData.getPolygonByIdx(firstPolyIdx); + TraversalResult t{{}, Visited{firstPolyIdx}}; + Head initHead{firstPoly, makeGates(getSegmentsExcept(firstPoly, init), firstPolyIdx)}; + traverse(metricPolygon, initHead, t, segData, true); + return t.convex; +} + +BasicPolygon2d extractPolygon(const BasicPolygon2d& poly, const std::vector& idxs) { + BasicPolygon2d res(idxs.size()); + for (size_t i{0}; i < idxs.size(); ++i) { + res[i] = poly.at(idxs.at(i)); + } + return res; +} + +void subdivide(IndexedTriangles& target, const IndexedPolygon& poly) { + target.reserve(target.size() + poly.size() - 2); + for (auto first = std::next(poly.begin()), second = std::next(poly.begin(), 2); second != poly.end(); + ++second, ++first) { + target.emplace_back(IndexedTriangle{poly.front(), *first, *second}); + } +} + +bool isTriangular(const IndexedPolygon& poly) { return poly.size() == 3; } + +SegmentationData makeVoronoi(const BasicPolygon2d& poly) { + VoronoiGraph graph; + boost::polygon::construct_voronoi(poly.begin(), poly.end(), &graph); + SegmentationData t(graph.num_vertices()); + auto advance = [](const VoronoiGraph::edge_type*& edge, VoronoiGraph::cell_type::source_index_type& lastIndex, + VoronoiGraph::cell_type::source_index_type& curIndex) { + lastIndex = curIndex; + edge = edge->rot_prev(); + curIndex = edge->cell()->source_index(); + }; + for (size_t i{0}; i < graph.num_vertices(); ++i) { + const auto* const firstEdge = graph.vertices().at(i).incident_edge(); + auto startIdx = firstEdge->cell()->source_index(); + const auto* curEdge = firstEdge->rot_prev(); + auto curIdx = curEdge->cell()->source_index(); + auto lastIdx = startIdx; + IndexedPolygon curPoly{startIdx}; + while (curIdx != startIdx) { + t.addSegment({lastIdx, curIdx}, i); + curPoly.emplace_back(curIdx); + advance(curEdge, lastIdx, curIdx); + } + t.addSegment({lastIdx, curIdx}, i); + t.addConvex(curPoly, i); + } + return t; +} + +BasicPolygons2d convexPartitionImpl(const BasicPolygon2d& poly) { + if (poly.size() < 3) { + throw GeometryError("Can't partition a polygon with less than 3 points"); + } + BasicPolygons2d res; + auto segData = makeVoronoi(poly); + segData.freeze(); + auto indexed = mergeTriangulation(poly, segData); + for (const auto& i : indexed) { + res.emplace_back(extractPolygon(poly, i)); + } + return res; +} + +IndexedTriangles triangulateImpl(const BasicPolygon2d& poly) { + if (poly.size() < 3) { + throw GeometryError("Can't triangulate a polygon with less than 3 points"); + } + IndexedTriangles res; + res.reserve(poly.size() - 2); + auto segData = makeVoronoi(poly); + for (const auto& i : segData.getConvexPolygons()) { + if (isTriangular(i)) { + res.emplace_back(IndexedTriangle{i.at(0), i.at(1), i.at(2)}); + } else { + subdivide(res, i); + } + } + return res; +} +} // namespace + +namespace lanelet { +namespace geometry { +namespace internal { +BasicPolygons2d convexPartition(const BasicPolygon2d& poly) { return convexPartitionImpl(poly); } +IndexedTriangles triangulate(const BasicPolygon2d& poly) { return triangulateImpl(poly); } +} // namespace internal +} // namespace geometry +} // namespace lanelet diff --git a/lanelet2/lanelet2_core/src/RegulatoryElement.cpp b/lanelet2/lanelet2_core/src/RegulatoryElement.cpp index 4f91389f610..37679656f03 100644 --- a/lanelet2/lanelet2_core/src/RegulatoryElement.cpp +++ b/lanelet2/lanelet2_core/src/RegulatoryElement.cpp @@ -1,36 +1,38 @@ -#include "primitives/RegulatoryElement.h" -#include "primitives/Area.h" -#include "primitives/BasicRegulatoryElements.h" -#include "primitives/Lanelet.h" -#include "primitives/LineString.h" -#include "primitives/Point.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" + +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/BasicRegulatoryElements.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/LineString.h" +#include "lanelet2_core/primitives/Point.h" namespace lanelet { namespace { class HasIdVisitor : public RuleParameterVisitor { public: explicit HasIdVisitor(Id id) : id_{id} {} - void operator()(const ConstPoint3d& p) override { found |= p.id() == id_; } - void operator()(const ConstLineString3d& l) override { found |= l.id() == id_ || utils::has(l, id_); } - void operator()(const ConstPolygon3d& p) override { found |= p.id() == id_ || utils::has(p, id_); } + void operator()(const ConstPoint3d& p) override { found_ |= p.id() == id_; } + void operator()(const ConstLineString3d& l) override { found_ |= l.id() == id_ || utils::has(l, id_); } + void operator()(const ConstPolygon3d& p) override { found_ |= p.id() == id_ || utils::has(p, id_); } void operator()(const ConstWeakLanelet& ll) override { if (ll.expired()) { return; } ConstLanelet llet(ll.lock()); - found |= llet.id() == id_ || utils::has(llet, id_); + found_ |= llet.id() == id_ || utils::has(llet, id_); } void operator()(const ConstWeakArea& ar) override { if (ar.expired()) { return; } ConstArea area(ar.lock()); - found |= area.id() == id_ || utils::has(area, id_); + found_ |= area.id() == id_ || utils::has(area, id_); } - bool found{false}; + bool operator!() const { return !found_; } private: Id id_; + bool found_{false}; }; class GetIdVisitor : public RuleParameterVisitor { @@ -160,9 +162,9 @@ void RegulatoryElement::applyVisitor(lanelet::internal::MutableParameterVisitor& } bool utils::has(const RegulatoryElement& regElem, Id id) { - HasIdVisitor visitor(id); - regElem.applyVisitor(visitor); - return visitor.found; + HasIdVisitor hasId(id); + regElem.applyVisitor(hasId); + return !!hasId; } template <> diff --git a/lanelet2/lanelet2_core/src/RegulatoryElementGeometry.cpp b/lanelet2/lanelet2_core/src/RegulatoryElementGeometry.cpp index 52458e73e62..8ce4e476c42 100644 --- a/lanelet2/lanelet2_core/src/RegulatoryElementGeometry.cpp +++ b/lanelet2/lanelet2_core/src/RegulatoryElementGeometry.cpp @@ -1,10 +1,11 @@ #include -#include "geometry/Area.h" -#include "geometry/BoundingBox.h" -#include "geometry/Lanelet.h" -#include "geometry/LineString.h" -#include "geometry/RegulatoryElement.h" -#include "primitives/Traits.h" + +#include "lanelet2_core/geometry/Area.h" +#include "lanelet2_core/geometry/BoundingBox.h" +#include "lanelet2_core/geometry/Lanelet.h" +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/RegulatoryElement.h" +#include "lanelet2_core/primitives/Traits.h" namespace lanelet { namespace geometry { diff --git a/lanelet2/lanelet2_core/test/lanelet_map_test_case.h b/lanelet2/lanelet2_core/test/lanelet_map_test_case.h index 689d658c899..9aa02aecb80 100644 --- a/lanelet2/lanelet2_core/test/lanelet_map_test_case.h +++ b/lanelet2/lanelet2_core/test/lanelet_map_test_case.h @@ -1,5 +1,5 @@ #pragma once -#include "LaneletMap.h" +#include "lanelet2_core/LaneletMap.h" namespace lanelet { namespace test_cases { @@ -16,7 +16,7 @@ std::unordered_map makeMap(const std::initializer_list& vec) { } template <> -std::unordered_map makeMap(const std::initializer_list& vec) { +inline std::unordered_map makeMap(const std::initializer_list& vec) { std::unordered_map map; for (const auto& elem : vec) { map.insert(std::make_pair(elem->id(), elem)); @@ -29,9 +29,9 @@ class LaneletMapTestCase { LaneletMapTestCase() { /** p1------left-------p2 - + |front | p5------p6--other--p7 - + | | rear p3------right------p4 diff --git a/lanelet2/lanelet2_core/test/test_area.cpp b/lanelet2/lanelet2_core/test/test_area.cpp index 54e29367976..d532302e19b 100644 --- a/lanelet2/lanelet2_core/test/test_area.cpp +++ b/lanelet2/lanelet2_core/test/test_area.cpp @@ -1,52 +1,67 @@ #include -#include "geometry/Area.h" -#include "geometry/Lanelet.h" -#include "primitives/Area.h" -#include "primitives/Lanelet.h" -#include "primitives/RegulatoryElement.h" -using namespace lanelet; - -Point3d makePoint(double x, double y) { - static Id id{1}; - return Point3d(id++, x, y); -} +#include "lanelet2_core/geometry/Area.h" +#include "lanelet2_core/geometry/Lanelet.h" +#include "lanelet2_core/primitives/Area.h" +#include "lanelet2_core/primitives/Lanelet.h" +#include "lanelet2_core/primitives/RegulatoryElement.h" -namespace lanelet { -namespace geometry {} // namespace geometry -} // namespace lanelet +using namespace lanelet; +/* 1 f1 3 s1 5 tl1 7 + * X------>X------>X------>X + * | llU | + * |f2 h |s2 llF + * a1/3 V a2/4 V + * X<------X<------X------>X + * 2 f3 4 s3 6 tl2 8 + * + * llB/R + * X-------X + * rightLine + * y ^ + * | + * O---> + * x + */ class TestArea : public testing::Test { public: TestArea() { for (auto i = 0u; i < 4; ++i) { - pointsLeft.push_back(Point3d(++id, i, 1)); - pointsRight.push_back(Point3d(++id, i, 0)); + pointsLeft.push_back(Point3d(++id, i, 1)); // 1, 3, 5, 7 + pointsRight.push_back(Point3d(++id, i, 0)); // 2, 4, 6, 8 } - firstCircle = LineString3d(++id, {pointsLeft[0], pointsLeft[1], pointsRight[1], pointsRight[0]}); - secondCircle1 = LineString3d(++id, {pointsLeft[1], pointsLeft[2]}); - secondCircle2 = LineString3d(++id, {pointsLeft[2], pointsRight[2]}); - secondCircle3 = LineString3d(++id, {pointsRight[2], pointsRight[1]}); - auto holeId = ++id; + firstCircle = LineString3d(++id, {pointsLeft[0], pointsLeft[1], pointsRight[1], pointsRight[0]}); // 9 + firstCircle1 = LineString3d(++id, {pointsLeft[0], pointsLeft[1]}); // 10 + firstCircle2 = LineString3d(++id, {pointsLeft[1], pointsRight[1]}); // 11 + firstCircle3 = LineString3d(++id, {pointsRight[1], pointsRight[0]}); // 12 + secondCircle1 = LineString3d(++id, {pointsLeft[1], pointsLeft[2]}); // 13 + secondCircle2 = LineString3d(++id, {pointsLeft[2], pointsRight[2]}); // 14 + secondCircle3 = LineString3d(++id, {pointsRight[2], pointsRight[1]}); // 15 + auto holeId = ++id; // 16 hole = LineString3d(holeId, {Point3d(++id, 1.25, 0.25), Point3d(++id, 1.75, 0.25), Point3d(++id, 1.75, 0.75), - Point3d(++id, 1.25, 0.75)}); - thirdLine1 = LineString3d(++id, {pointsLeft[2], pointsLeft[3]}); - thirdLine2 = LineString3d(++id, {pointsRight[2], pointsRight[3]}); - auto lineId = ++id; - rightLine = LineString3d(lineId, {Point3d(++id, 1, -1), Point3d(++id, 2, -1)}); - area1 = Area(++id, {firstCircle}); - area2 = Area(++id, {secondCircle1, secondCircle2, secondCircle3}, {{hole}}); - laneletFollowing = Lanelet(++id, thirdLine1, thirdLine2); - laneletRight = Lanelet(++id, secondCircle2.invert(), rightLine); - regelem = std::make_shared(++id); + Point3d(++id, 1.25, 0.75)}); // 17, 18, 19, 20 + thirdLine1 = LineString3d(++id, {pointsLeft[2], pointsLeft[3]}); // 21 + thirdLine2 = LineString3d(++id, {pointsRight[2], pointsRight[3]}); // 22 + auto lineId = ++id; // 23 + rightLine = LineString3d(lineId, {Point3d(++id, 1, -1), Point3d(++id, 2, -1)}); // 24, 25 + area1 = Area(++id, {firstCircle}); // 26 + area2 = Area(++id, {secondCircle1, secondCircle2, secondCircle3}, {{hole}}); // 27 + area3 = Area(++id, {firstCircle1, firstCircle2, firstCircle3}); // 28 + area4 = Area(++id, {secondCircle1, secondCircle2, secondCircle3, firstCircle2.invert()}); // 29 + laneletFollowing = Lanelet(++id, thirdLine1, thirdLine2); // 30 + laneletRight = Lanelet(++id, secondCircle2.invert(), rightLine); // 31 + regelem = std::make_shared(++id); // 32 + laneletBelow = Lanelet(++id, secondCircle3.invert(), rightLine); // 33 + laneletUpwards = Lanelet(++id, firstCircle2.invert(), secondCircle2.invert()); // 34 } - public: Id id{0}; Points3d pointsLeft, pointsRight; - LineString3d firstCircle, secondCircle1, secondCircle2, secondCircle3, hole, thirdLine1, thirdLine2, rightLine; - Area area1, area2; - Lanelet laneletFollowing, laneletRight; + LineString3d firstCircle, firstCircle1, firstCircle2, firstCircle3, secondCircle1, secondCircle2, secondCircle3, hole, + thirdLine1, thirdLine2, rightLine; + Area area1, area2, area3, area4; + Lanelet laneletFollowing, laneletRight, laneletBelow, laneletUpwards; RegulatoryElementPtr regelem; }; @@ -76,27 +91,27 @@ TEST_F(TestArea, inside) { // NOLINT TEST_F(TestArea, distance2d) { // NOLINT auto d = geometry::distance2d(area2, utils::to2D(pointsLeft[3].basicPoint())); - EXPECT_FLOAT_EQ(1, d); + EXPECT_DOUBLE_EQ(1, d); } TEST_F(TestArea, distance2dWithHole) { // NOLINT auto d = geometry::distance2d(area2, BasicPoint2d(1.5, 0.5)); - EXPECT_FLOAT_EQ(0.25, d); + EXPECT_DOUBLE_EQ(0.25, d); } TEST_F(TestArea, distance3dWithHole) { // NOLINT auto d = geometry::distance3d(area2, BasicPoint3d(1.5, 0.5, 1)); - EXPECT_FLOAT_EQ(std::sqrt(0.25 * 0.25 + 1), d); + EXPECT_DOUBLE_EQ(std::sqrt(0.25 * 0.25 + 1), d); } TEST_F(TestArea, area) { // NOLINT auto area = geometry::area(area1.basicPolygonWithHoles2d()); - EXPECT_FLOAT_EQ(1, area); + EXPECT_DOUBLE_EQ(1, area); } TEST_F(TestArea, areaWithHole) { // NOLINT auto area = geometry::area(area2.basicPolygonWithHoles2d()); - EXPECT_FLOAT_EQ(0.75, area); + EXPECT_DOUBLE_EQ(0.75, area); } TEST_F(TestArea, boundingBox) { // NOLINT @@ -131,8 +146,116 @@ TEST_F(TestArea, leftOf) { // NOLINT EXPECT_FALSE(geometry::leftOf(laneletRight.invert(), area2)); EXPECT_FALSE(geometry::leftOf(laneletRight, area1)); } + TEST_F(TestArea, rightOf) { // NOLINT EXPECT_FALSE(geometry::rightOf(laneletRight, area2)); EXPECT_TRUE(geometry::rightOf(laneletRight.invert(), area2)); EXPECT_FALSE(geometry::rightOf(laneletRight, area1)); } + +TEST_F(TestArea, determineCommonLinePreceding) { + auto res = geometry::determineCommonLinePreceding(laneletFollowing.invert(), area2); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + EXPECT_FALSE(!!geometry::determineCommonLinePreceding(laneletFollowing, area2)); + EXPECT_FALSE(!!geometry::determineCommonLinePreceding(laneletFollowing.invert(), area1)); +} + +TEST_F(TestArea, determineCommonLineFollowing) { + auto res = geometry::determineCommonLineFollowing(area2, laneletFollowing); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + EXPECT_FALSE(!!geometry::determineCommonLineFollowing(area2, laneletFollowing.invert())); + EXPECT_FALSE(!!geometry::determineCommonLineFollowing(area1, laneletFollowing)); +} + +TEST_F(TestArea, determineCommonLineFollowingOrPreceding) { + auto res = geometry::determineCommonLineFollowingOrPreceding(area2, laneletFollowing); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + res = geometry::determineCommonLineFollowingOrPreceding(area2, laneletFollowing.invert()); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletFollowing.invert())); + EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletFollowing)); + EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area2, laneletRight)); + EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area1, laneletBelow)); + EXPECT_FALSE(!!geometry::determineCommonLineFollowingOrPreceding(area2, laneletBelow)); +} + +TEST_F(TestArea, determineCommonLineLeft) { + auto res = geometry::determineCommonLineLeft(laneletUpwards, area3); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_TRUE(res->inverted()); + EXPECT_FALSE(!!geometry::determineCommonLineLeft(laneletUpwards, area2)); + EXPECT_FALSE(!!geometry::determineCommonLineLeft(laneletUpwards, area4)); +} + +TEST_F(TestArea, determineCommonLineRight) { + auto res = geometry::determineCommonLineRight(laneletUpwards.invert(), area3); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_FALSE(res->inverted()); + EXPECT_FALSE(!!geometry::determineCommonLineRight(laneletUpwards.invert(), area2)); + EXPECT_FALSE(!!geometry::determineCommonLineRight(laneletUpwards.invert(), area4)); +} + +TEST_F(TestArea, determineCommonLineSidewaysLanelet) { + auto res = geometry::determineCommonLineSideways(laneletUpwards, area3); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_TRUE(res->inverted()); + res = geometry::determineCommonLineSideways(laneletUpwards.invert(), area3); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_FALSE(res->inverted()); + EXPECT_FALSE(!!geometry::determineCommonLineSideways(laneletUpwards, area2)); + EXPECT_FALSE(!!geometry::determineCommonLineSideways(laneletUpwards, area4)); +} + +TEST_F(TestArea, determineCommonLineSidewaysArea) { + auto res = geometry::determineCommonLineSideways(area3, laneletUpwards); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_FALSE(res->inverted()); + res = geometry::determineCommonLineSideways(area3, laneletUpwards.invert()); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_FALSE(res->inverted()); + EXPECT_FALSE(!!geometry::determineCommonLineSideways(area2, laneletUpwards)); + EXPECT_FALSE(!!geometry::determineCommonLineSideways(area4, laneletUpwards)); +} + +TEST_F(TestArea, determineCommonLineInArea) { + auto res = geometry::determineCommonLine(area2, laneletBelow); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 15); + EXPECT_FALSE(res->inverted()); + res = geometry::determineCommonLine(area2, laneletFollowing); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + EXPECT_FALSE(res->inverted()); +} + +TEST_F(TestArea, determineCommonLineInAreaInverted) { + auto res = geometry::determineCommonLine(area2, laneletBelow.invert()); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 15); + EXPECT_FALSE(res->inverted()); + res = geometry::determineCommonLine(area2, laneletFollowing.invert()); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 14); + EXPECT_FALSE(res->inverted()); +} + +TEST_F(TestArea, determineCommonLineArea) { + auto res = geometry::determineCommonLine(area3, area4); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_FALSE(res->inverted()); + res = geometry::determineCommonLine(area4, area3); + ASSERT_TRUE(!!res); + EXPECT_EQ(res->id(), 11); + EXPECT_TRUE(res->inverted()); +} diff --git a/lanelet2/lanelet2_core/test/test_attribute.cpp b/lanelet2/lanelet2_core/test/test_attribute.cpp index 535cc710bfb..72c146c66cc 100644 --- a/lanelet2/lanelet2_core/test/test_attribute.cpp +++ b/lanelet2/lanelet2_core/test/test_attribute.cpp @@ -1,7 +1,8 @@ -#include -#include #include -#include "utility/Units.h" + +#include "lanelet2_core/Attribute.h" +#include "lanelet2_core/Exceptions.h" +#include "lanelet2_core/utility/Units.h" using namespace std::string_literals; using namespace lanelet; diff --git a/lanelet2/lanelet2_core/test/test_lanelet.cpp b/lanelet2/lanelet2_core/test/test_lanelet.cpp index 3bffcb567a6..e611e3c4b74 100644 --- a/lanelet2/lanelet2_core/test/test_lanelet.cpp +++ b/lanelet2/lanelet2_core/test/test_lanelet.cpp @@ -1,10 +1,12 @@ #include + #include -#include "geometry/Area.h" -#include "geometry/Lanelet.h" -#include "geometry/LineString.h" -#include "geometry/Polygon.h" -#include "primitives/Lanelet.h" + +#include "lanelet2_core/geometry/Area.h" +#include "lanelet2_core/geometry/Lanelet.h" +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/Lanelet.h" using namespace std::literals; using namespace lanelet; @@ -247,6 +249,26 @@ TEST_F(LaneletTest, weakLanelet) { // NOLINT EXPECT_EQ(wll.lock(), ritterLanelet); } +TEST_F(LaneletTest, determineCommonLine) { // NOLINT + Lanelet rightLL(++id, right, outside); + auto res = geometry::determineCommonLine(ritterLanelet, rightLL); + ASSERT_TRUE(!!res); + EXPECT_EQ(*res, right); + res = geometry::determineCommonLine(rightLL, ritterLanelet); + ASSERT_TRUE(!!res); + EXPECT_EQ(*res, right); + res = geometry::determineCommonLine(rightLL.invert(), ritterLanelet); + ASSERT_FALSE(!!res); + res = geometry::determineCommonLine(rightLL, ritterLanelet.invert()); + ASSERT_FALSE(!!res); + res = geometry::determineCommonLine(rightLL.invert(), ritterLanelet, true); + ASSERT_TRUE(!!res); + EXPECT_EQ(*res, right.invert()); + res = geometry::determineCommonLine(rightLL, ritterLanelet.invert(), true); + ASSERT_TRUE(!!res); + EXPECT_EQ(*res, right); +} + TEST(LaneletBasic, emptyLanelet) { // NOLINT Lanelet empty; EXPECT_EQ(empty.polygon2d().size(), 0ul); @@ -262,28 +284,26 @@ Lanelet buildComplexTestCase() { * |___________| * */ - Point3d p11, p12, p13, p14, p15, p21, p22, p23, p24; - LineString3d left, right; - Lanelet lanelet; Id id{1}; - p11 = Point3d(++id, 1., 5.); - p12 = Point3d(++id, 2., 8.); - p13 = Point3d(++id, 3., 2.); - p14 = Point3d(++id, 4., 10.); - p15 = Point3d(++id, 5., 4.); - p21 = Point3d(++id, 0., 10.); - p22 = Point3d(++id, 0., 0.); - p23 = Point3d(++id, 6., 0.); - p24 = Point3d(++id, 6., 10.); - left = LineString3d(++id, Points3d{p11, p12, p13, p14, p15}); - right = LineString3d(++id, Points3d{p21, p22, p23, p24}); - lanelet = Lanelet(++id, left, right); + auto p11 = Point3d(++id, 1., 5.); + auto p12 = Point3d(++id, 2., 8.); + auto p13 = Point3d(++id, 3., 2.); + auto p14 = Point3d(++id, 4., 10.); + auto p15 = Point3d(++id, 5., 4.); + auto p21 = Point3d(++id, 0., 10.); + auto p22 = Point3d(++id, 0., 0.); + auto p23 = Point3d(++id, 6., 0.); + auto p24 = Point3d(++id, 6., 10.); + auto left = LineString3d(++id, Points3d{p11, p12, p13, p14, p15}); + auto right = LineString3d(++id, Points3d{p21, p22, p23, p24}); + auto lanelet = Lanelet(++id, left, right); return lanelet; } Lanelet buildLinearTestCase(size_t numPoints) { Id id{1}; - LineString3d left(++id), right(++id); + LineString3d left(++id); + LineString3d right(++id); for (auto i = 0u; i < numPoints; i++) { left.push_back(Point3d(++id, i, 1, 0)); right.push_back(Point3d(++id, i, 0, 0)); diff --git a/lanelet2/lanelet2_core/test/test_lanelet_map.cpp b/lanelet2/lanelet2_core/test/test_lanelet_map.cpp index 0c2856d6574..6c2bc244103 100644 --- a/lanelet2/lanelet2_core/test/test_lanelet_map.cpp +++ b/lanelet2/lanelet2_core/test/test_lanelet_map.cpp @@ -1,6 +1,8 @@ #include + #include -#include "LaneletMap.h" + +#include "lanelet2_core/LaneletMap.h" #include "lanelet_map_test_case.h" using namespace lanelet; @@ -282,6 +284,12 @@ TEST_F(LaneletMapTest, findUsagesInPolygon) { // NOLINT }); } +TEST_F(LaneletMapTest, createMapWithCustomCenterline) { // NOLINT + ll1.setCenterline(front); + auto map = utils::createConstMap(ConstLanelets{ll1}, {}); + EXPECT_TRUE(map->lineStringLayer.exists(front.id())); +} + TEST_F(LaneletMapTest, createConstMap) { // NOLINT auto map = utils::createConstMap(ConstLanelets{ll1, ll2}, ConstAreas{ar1}); EXPECT_TRUE(map->laneletLayer.exists(ll1.id())); diff --git a/lanelet2/lanelet2_core/test/test_lanelet_map_geometry.cpp b/lanelet2/lanelet2_core/test/test_lanelet_map_geometry.cpp index 1e40d59908b..b64e33efe86 100644 --- a/lanelet2/lanelet2_core/test/test_lanelet_map_geometry.cpp +++ b/lanelet2/lanelet2_core/test/test_lanelet_map_geometry.cpp @@ -1,13 +1,47 @@ #include + #include -#include "geometry/BoundingBox.h" -#include "geometry/LaneletMap.h" +#include + +#include "lanelet2_core/geometry/Area.h" +#include "lanelet2_core/geometry/BoundingBox.h" +#include "lanelet2_core/geometry/LaneletMap.h" #include "lanelet_map_test_case.h" using namespace lanelet; class LaneletMapGeometryTest : public ::testing::Test, public test_cases::LaneletMapTestCase {}; +LineStrings3d getRandomLinestringsSortedByDistanceToOrigin(size_t num, std::mt19937& rng) { + auto getLinestring = [&rng, dist = std::uniform_real_distribution{}, id = 0L]() mutable { + id += 3; + return LineString3d(id - 2, {Point3d(id - 1, dist(rng), dist(rng)), Point3d(id, dist(rng), dist(rng))}); + }; + auto byDistanceToOrigin = [](const LineString3d& ls1, const LineString3d& ls2) { + using utils::to2D; + return geometry::distance(BasicPoint2d(0, 0), to2D(ls1)) < geometry::distance(BasicPoint2d(0, 0), to2D(ls2)); + }; + LineStrings3d lss(num); + std::generate(lss.begin(), lss.end(), getLinestring); + std::sort(lss.begin(), lss.end(), byDistanceToOrigin); + return lss; +} + +TEST_F(LaneletMapGeometryTest, findNearestWorksForRandomLinestrings) { // NOLINT + constexpr auto NumSearch = 5; + std::mt19937 rng(1337); + for (auto i = 0; i < 100; ++i) { + auto lss = getRandomLinestringsSortedByDistanceToOrigin(10, rng); + this->map = utils::createMap(lss); + auto exp = ConstLineStrings3d(lss.begin(), lss.begin() + NumSearch); + testConstAndNonConst([&](auto& map) { + auto nearest = geometry::findNearest(map->lineStringLayer, BasicPoint2d(0, 0), NumSearch); + auto nearestLs = utils::transform(nearest, [](auto& ls) -> ConstLineString3d { return ls.second; }); + EXPECT_EQ(exp, nearestLs) << "i=" << i; + }); + } +} + TEST_F(LaneletMapGeometryTest, findWithin2dPoint) { // NOLINT map->add(ll2); EXPECT_EQ(2ul, map->laneletLayer.size()); @@ -54,7 +88,17 @@ TEST_F(LaneletMapGeometryTest, findWithin2dLanelet) { // NOLINT testConstAndNonConst([this](auto& map) { auto llts = geometry::findWithin2d(map->pointLayer, this->ll2); ASSERT_LE(1ul, llts.size()); - utils::contains(utils::transform(llts, [](auto& t) { return t.second; }), this->p6); + EXPECT_TRUE(utils::contains(utils::transform(llts, [](auto& t) { return t.second; }), this->p6)); + }); +} + +TEST_F(LaneletMapGeometryTest, findWithin2dArea) { // NOLINT + map->add(ll2); + EXPECT_EQ(2ul, map->laneletLayer.size()); + testConstAndNonConst([this](auto& map) { + auto areas = geometry::findWithin2d(map->areaLayer, utils::to2D(this->p8), 1.5); + ASSERT_EQ(1ul, areas.size()); + EXPECT_EQ(areas.front().second, this->ar1); }); } @@ -97,3 +141,13 @@ TEST_F(LaneletMapGeometryTest, findWithin3dLanelet) { // NOLINT utils::contains(utils::transform(llts, [](auto& t) { return t.second; }), this->p6); }); } + +TEST_F(LaneletMapGeometryTest, findWithin3dArea) { // NOLINT + map->add(ll2); + EXPECT_EQ(2ul, map->laneletLayer.size()); + testConstAndNonConst([this](auto& map) { + auto areas = geometry::findWithin3d(map->areaLayer, this->p8, 1.5); + ASSERT_EQ(1ul, areas.size()); + EXPECT_EQ(areas.front().second, this->ar1); + }); +} diff --git a/lanelet2/lanelet2_core/test/test_lanelet_or_area.cpp b/lanelet2/lanelet2_core/test/test_lanelet_or_area.cpp index 17002fbfb50..8db9a3cb816 100644 --- a/lanelet2/lanelet2_core/test/test_lanelet_or_area.cpp +++ b/lanelet2/lanelet2_core/test/test_lanelet_or_area.cpp @@ -1,5 +1,6 @@ #include -#include "primitives/LaneletOrArea.h" + +#include "lanelet2_core/primitives/LaneletOrArea.h" using namespace lanelet; @@ -40,3 +41,16 @@ TEST_F(TestLaneletOrArea, getArea) { // NOLINT EXPECT_EQ(ar, area); EXPECT_NE(ar, lanelet); } + +TEST_F(TestLaneletOrArea, boundingPolygon) { // NOLINT + auto poly = getArea().boundingPolygon(); + ASSERT_EQ(poly.size(), area.outerBoundPolygon().size()); + for (size_t i = 0; i < poly.size(); ++i) { + EXPECT_EQ(poly[i], area.outerBoundPolygon()[i]); + } + poly = getLanelet().boundingPolygon(); + ASSERT_EQ(poly.size(), lanelet.polygon3d().size()); + for (size_t i = 0; i < poly.size(); ++i) { + EXPECT_EQ(poly[i], lanelet.polygon3d()[i]); + } +} diff --git a/lanelet2/lanelet2_core/test/test_lanelet_sequence.cpp b/lanelet2/lanelet2_core/test/test_lanelet_sequence.cpp index 79cdf74598f..2a30b827ce6 100644 --- a/lanelet2/lanelet2_core/test/test_lanelet_sequence.cpp +++ b/lanelet2/lanelet2_core/test/test_lanelet_sequence.cpp @@ -1,10 +1,12 @@ #include -#include + #include -#include "geometry/LineString.h" -#include "geometry/RegulatoryElement.h" -#include "primitives/BasicRegulatoryElements.h" -#include "primitives/LaneletSequence.h" + +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/geometry/RegulatoryElement.h" +#include "lanelet2_core/primitives/BasicRegulatoryElements.h" +#include "lanelet2_core/primitives/LaneletSequence.h" +#include "lanelet2_core/utility/Utilities.h" using namespace std::literals; using namespace lanelet; @@ -69,7 +71,8 @@ TEST_F(LaneletSequenceTest, LaneletsAreOk) { // NOLINT } TEST_F(LaneletSequenceTest, ConstructFromLaneletSequences) { // NOLINT - LaneletSequence cl1{{ll1}}, cl2{{ll2}}; + LaneletSequence cl1{{ll1}}; + LaneletSequence cl2{{ll2}}; LaneletSequence ccl{{cl1, cl2}}; EXPECT_EQ(ccl, cll); } diff --git a/lanelet2/lanelet2_core/test/test_linestring.cpp b/lanelet2/lanelet2_core/test/test_linestring.cpp index cbfe7ee241d..3ef2c111d9b 100644 --- a/lanelet2/lanelet2_core/test/test_linestring.cpp +++ b/lanelet2/lanelet2_core/test/test_linestring.cpp @@ -1,6 +1,7 @@ #include -#include "geometry/LineString.h" -#include "primitives/LineString.h" + +#include "lanelet2_core/geometry/LineString.h" +#include "lanelet2_core/primitives/LineString.h" using namespace lanelet; class LineStringPoints : public ::testing::Test { @@ -26,6 +27,22 @@ class LineStringPoints : public ::testing::Test { Point3d p43; }; +template +class Point2dTypeTest : public ::testing::Test { + protected: + using Point2dT = T; + void SetUp() override { + Id id{1}; + p1 = Point2d(++id, 1., 0., 0.); + p2 = Point2d(++id, 0., 1., 0.); + p3 = Point2d(++id, -1., 0., 0.); + p4 = Point2d(++id, 0., 1., 0.); + } + + public: + Point2dT p1, p2, p3, p4; +}; + template class LineStringTypeTest : public LineStringPoints { protected: @@ -111,8 +128,12 @@ class ThreeDLineStringsTest : public LineStringTypeTest {}; template class TwoDLineStringsTest : public LineStringTypeTest {}; +template +class TwoDPointsTest : public Point2dTypeTest {}; + template class BasicLineStringsTest : public LineStringTypeTest {}; +using TwoDPoints = testing::Types; using AllLineStrings = testing::Types; @@ -131,6 +152,7 @@ using HybridLineStrings = testing::Types; +TYPED_TEST_CASE(TwoDPointsTest, TwoDPoints); TYPED_TEST_CASE(AllLineStringsTest, AllLineStrings); TYPED_TEST_CASE(TwoDLineStringsTest, TwoDLineStrings); TYPED_TEST_CASE(ThreeDLineStringsTest, ThreeDLineStrings); @@ -329,6 +351,11 @@ TYPED_TEST(AllLineStringsTest, segmentsInverse) { // NOLINT EXPECT_EQ(segment.second, lsInv[1]); } +TYPED_TEST(TwoDPointsTest, checkCurvature) { + EXPECT_DOUBLE_EQ(1., geometry::curvature2d(this->p1, this->p2, this->p3)); + EXPECT_DOUBLE_EQ(std::numeric_limits::infinity(), geometry::curvature2d(this->p1, this->p2, this->p4)); +} + TYPED_TEST(TwoDLineStringsTest, signedDistance) { // NOLINT auto isLeft = [this](const BasicPoint2d& p) { return geometry::signedDistance(this->ls2, p) > 0; }; auto d = geometry::signedDistance(this->ls2, BasicPoint2d(2, -1)); @@ -480,15 +507,14 @@ TYPED_TEST(TwoDLineStringsTest, shiftLateral) { * O O */ TEST(TwoDLineStringsTest, removeSelfIntersections) { - BasicPoint2d p1, p2, p3, p4, p5, p6, p7, p8; - p1 = BasicPoint2d(2, 0); - p2 = BasicPoint2d(2, 2); - p3 = BasicPoint2d(3, 1); - p4 = BasicPoint2d(0, 1); - p5 = BasicPoint2d(1, 2); - p6 = BasicPoint2d(1, 0); - p7 = BasicPoint2d(2, 1); - p8 = BasicPoint2d(1, 1); + auto p1 = BasicPoint2d(2, 0); + auto p2 = BasicPoint2d(2, 2); + auto p3 = BasicPoint2d(3, 1); + auto p4 = BasicPoint2d(0, 1); + auto p5 = BasicPoint2d(1, 2); + auto p6 = BasicPoint2d(1, 0); + auto p7 = BasicPoint2d(2, 1); + auto p8 = BasicPoint2d(1, 1); BasicLineString2d l1{p1, p2, p3, p4, p5, p6}; BasicLineString2d l2{p1, p7, p8, p6}; auto ret = geometry::internal::removeSelfIntersections(l1); @@ -496,18 +522,17 @@ TEST(TwoDLineStringsTest, removeSelfIntersections) { } TEST(TwoDLineStringsTest, extractConvex) { - BasicPoint2d p1, p2, p3, p3a, p3b, p4, p5, p6, p7, p8, p9; - p1 = BasicPoint2d(1, 0); - p2 = BasicPoint2d(1, 1); - p3 = BasicPoint2d(0, 1); - p3a = BasicPoint2d(2, 1); - p3b = BasicPoint2d(0, 0); - p4 = BasicPoint2d(0.5, 0); - p5 = BasicPoint2d(0.5, 1); - p6 = BasicPoint2d(1, 0.5); - p7 = BasicPoint2d(0, 0.5); - p8 = BasicPoint2d(0.5, 1.5); - p9 = BasicPoint2d(2, 1.5); + auto p1 = BasicPoint2d(1, 0); + auto p2 = BasicPoint2d(1, 1); + auto p3 = BasicPoint2d(0, 1); + auto p3a = BasicPoint2d(2, 1); + auto p3b = BasicPoint2d(0, 0); + auto p4 = BasicPoint2d(0.5, 0); + auto p5 = BasicPoint2d(0.5, 1); + auto p6 = BasicPoint2d(1, 0.5); + auto p7 = BasicPoint2d(0, 0.5); + auto p8 = BasicPoint2d(0.5, 1.5); + auto p9 = BasicPoint2d(2, 1.5); BasicLineString2d l1{p1, p2, p3}; BasicLineString2d l2{p1, p2, p3a}; @@ -536,14 +561,13 @@ TEST(TwoDLineStringsTest, extractConvex) { */ TEST(TwoDLineStringsTest, checkInversion) { - BasicPoint2d p1, p2, p3, p4, p5; - p1 = BasicPoint2d(3, 3); - p2 = BasicPoint2d(3, 5); - p3 = BasicPoint2d(0, 5); - p4 = BasicPoint2d(0, 0); - p5 = BasicPoint2d(4, 0); + auto p1 = BasicPoint2d(3, 3); + auto p2 = BasicPoint2d(3, 5); + auto p3 = BasicPoint2d(0, 5); + auto p4 = BasicPoint2d(0, 0); + auto p5 = BasicPoint2d(4, 0); BasicLineString2d l1{p1, p2, p3, p4, p5}; EXPECT_THROW(geometry::offset(l1, 2), GeometryError); // NOLINT - EXPECT_NO_THROW(geometry::offset(l1, 1)); + EXPECT_NO_THROW(geometry::offset(l1, 1)); // NOLINT } diff --git a/lanelet2/lanelet2_core/test/test_point.cpp b/lanelet2/lanelet2_core/test/test_point.cpp index 0072414e3f2..87911289311 100644 --- a/lanelet2/lanelet2_core/test/test_point.cpp +++ b/lanelet2/lanelet2_core/test/test_point.cpp @@ -1,7 +1,9 @@ #include + #include -#include "geometry/Point.h" -#include "primitives/Point.h" + +#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_core/primitives/Point.h" using namespace lanelet; diff --git a/lanelet2/lanelet2_core/test/test_polygon.cpp b/lanelet2/lanelet2_core/test/test_polygon.cpp index 4e51f8f9448..253d48ec61f 100644 --- a/lanelet2/lanelet2_core/test/test_polygon.cpp +++ b/lanelet2/lanelet2_core/test/test_polygon.cpp @@ -1,8 +1,11 @@ #include + #include -#include "geometry/Polygon.h" -#include "primitives/CompoundPolygon.h" -#include "primitives/Polygon.h" +#include + +#include "lanelet2_core/geometry/Polygon.h" +#include "lanelet2_core/primitives/CompoundPolygon.h" +#include "lanelet2_core/primitives/Polygon.h" using namespace lanelet; template @@ -40,11 +43,21 @@ class PolygonPoints : public ::testing::Test { p32 = Point3d(++id, 1., 1., 2.); p33 = Point3d(++id, 2., 1., 2.); p34 = Point3d(++id, 2., 0., 2.); + /* + * p42 X + * / \ + * / X \ + * / -/ p44 \- \ + * p41 X/ \X p43 + */ + p41 = Point3d(++id, 1.5, 1.5, 2.); + p42 = Point3d(++id, 1.5, 0.5, 2.); } Point3d p11, p12, p13; Point3d p21, p22, p23; Point3d p31, p32, p33, p34; + Point3d p41, p42; }; template @@ -52,14 +65,39 @@ class PolygonTypeTest : public PolygonPoints { public: using PolygonT = T; PolygonTypeTest() { - Id id{10}; + Id id{20}; AttributeMap poly1Attrs{{AttributeNamesString::Type, AttributeValueString::Curbstone}}; poly1 = toPolygon(Polygon3d{++id, {p11, p12, p13}, poly1Attrs}); poly2 = toPolygon(Polygon3d{++id, {p21, p22, p23}}); poly3 = toPolygon(Polygon3d{++id, {p31, p32, p33, p34}}); + Polygon3d temp{++id, {p31, p41, p34, p42}}; + simpleStar = toPolygon(temp); + subdivide(temp, 2, ++id); + fancyStar = toPolygon(temp); } - PolygonT poly1, poly2, poly3; + PolygonT poly1, poly2, poly3, fancyStar, simpleStar; // NOLINT + + private: + void randomSubdivide(Polygon3d& poly, const size_t after, const int nNew, Id id) const { + BasicPoint3d delta = + (utils::toBasicPoint(poly[(after + 1) % poly.size()]) - utils::toBasicPoint(poly[after])) / (2 * nNew + 1); + std::vector points; + points.reserve(size_t(nNew)); + for (int i = 0; i < nNew; ++i) { + points.emplace_back(Point3d(++id, utils::toBasicPoint(poly[after]) + (2 * double(i) + randomNum_() + 1) * delta)); + } + Polygon3d newLs(++id, points); + poly.insert(poly.begin() + long((after + 1) % poly.size()), newLs.begin(), newLs.end()); + } + void subdivide(Polygon3d& poly, const int n, Id id) { + auto initSize = poly.size(); + for (size_t i = 0; i < initSize; ++i) { + randomSubdivide(poly, (n + 1) * i, n, id); + } + } + std::function randomNum_ = [distr = std::uniform_real_distribution(-0.5, 0.5), + gen = std::mt19937(133769420)]() mutable { return distr(gen); }; }; template @@ -78,13 +116,18 @@ class CompoundPolygonTypeTest : public PolygonPoints { ConstLineString3d tempLs22{++id, {p22, p23}}; ConstLineString3d tempLs31{++id, {p31, p32}}; ConstLineString3d tempLs32{++id, {p33, p34}}; + ConstLineString3d tempStar1{++id, {p31, p41, p34}}; + ConstLineString3d tempStar2{++id, {p34, p42}}; + poly1 = PolygonT({tempLs11}); poly2 = PolygonT({tempLs21, tempLs22}); poly3 = PolygonT({tempLs31, tempLs32}); + simpleStar = PolygonT({tempStar1, tempStar2}); + fancyStar = simpleStar; } public: - PolygonT poly1, poly2, poly3; + PolygonT poly1, poly2, poly3, fancyStar, simpleStar; }; template @@ -235,3 +278,72 @@ TYPED_TEST(TwoDPolygonsTest, toBasicPolygon) { // NOLINT EXPECT_EQ(4, boost::geometry::perimeter(pBasic)); EXPECT_EQ(4ul, pBasic.size()); } + +inline auto crossProd(const Eigen::Matrix& p1, const Eigen::Matrix& p2) { + return BasicPoint3d(p1.x(), p1.y(), 0.).cross(BasicPoint3d(p2.x(), p2.y(), 0.)).eval(); +} + +bool isConnectionConvex(const BasicPoint2d& seg1, const BasicPoint2d& seg2, + const double eps = 4 * std::numeric_limits::epsilon()) { + return crossProd(seg1.normalized(), seg2.normalized()).z() <= eps; +} + +bool isConvex(const BasicPolygon2d& poly) { + for (size_t i = 2; i < poly.size(); ++i) { + if (!isConnectionConvex(poly.at(i - 1) - poly.at(i - 2), poly.at(i) - poly.at(i - 1))) { + return false; + } + } + return (isConnectionConvex(poly.back() - poly.at(poly.size() - 2), poly.front() - poly.back()) && + isConnectionConvex(poly.front() - poly.back(), poly.at(1) - poly.front())); +} + +void checkPartitionConsistency(const BasicPolygon2d& poly, const BasicPolygons2d& parts) { + double areaSum{0.}; + for (auto i = 0ul; i < parts.size(); ++i) { + areaSum += boost::geometry::area(parts.at(i)); + for (auto j = i + 1; j < parts.size(); ++j) { + BasicPolygon2d intersection; + boost::geometry::intersection(parts.at(i), parts.at(j), intersection); + EXPECT_DOUBLE_EQ(boost::geometry::area(intersection), 0.); + } + for (const auto& p : parts.at(i)) { + Eigen::Matrix pCopy(p.x(), p.y()); + EXPECT_DOUBLE_EQ(boost::geometry::distance(pCopy, poly), 0.); + } + } + EXPECT_DOUBLE_EQ(areaSum, boost::geometry::area(poly)); +} + +TYPED_TEST(TwoDPolygonsTest, convexPartition) { + auto t1 = lanelet::geometry::convexPartition(this->poly3); + EXPECT_EQ(t1.size(), 1ul); + EXPECT_TRUE(isConvex(t1.front())); + checkPartitionConsistency(BasicPolygon2d(this->poly3.basicBegin(), this->poly3.basicEnd()), t1); + auto t2 = lanelet::geometry::convexPartition(this->simpleStar); + EXPECT_EQ(t2.size(), 2ul); + for (const auto& poly : t2) { + EXPECT_TRUE(isConvex(poly)); + } + checkPartitionConsistency(BasicPolygon2d(this->simpleStar.basicBegin(), this->simpleStar.basicEnd()), t2); + auto t3 = lanelet::geometry::convexPartition(this->fancyStar); + EXPECT_EQ(t3.size(), 2ul); + for (const auto& poly : t3) { + EXPECT_TRUE(isConvex(poly)); + } + checkPartitionConsistency(BasicPolygon2d(this->fancyStar.basicBegin(), this->fancyStar.basicEnd()), t3); +} + +TYPED_TEST(TwoDAndBasicPolygonsTest, triangulate) { + auto isIn = [](const geometry::IndexedTriangle& p, const size_t idx) { + return std::find(p.begin(), p.end(), idx) != p.end(); + }; + auto res = lanelet::geometry::triangulate(this->poly3); + ASSERT_EQ(res.size(), 2ul); + EXPECT_EQ(res.front().size(), 3ul); + EXPECT_EQ(res.back().size(), 3ul); + const auto& t1 = res.front(); + const auto& t2 = res.back(); + EXPECT_TRUE((isIn(t1, 1) && isIn(t1, 3) && isIn(t2, 1) && isIn(t2, 3)) || + (isIn(t1, 0) && isIn(t1, 2) && isIn(t2, 0) && isIn(t2, 2))); +} diff --git a/lanelet2/lanelet2_core/test/test_regulatory_element.cpp b/lanelet2/lanelet2_core/test/test_regulatory_element.cpp index cbb8f0bb825..8679c366f9e 100644 --- a/lanelet2/lanelet2_core/test/test_regulatory_element.cpp +++ b/lanelet2/lanelet2_core/test/test_regulatory_element.cpp @@ -1,7 +1,10 @@ #include -#include -#include "geometry/RegulatoryElement.h" -#include "primitives/BasicRegulatoryElements.h" + +#include + +#include "lanelet2_core/geometry/RegulatoryElement.h" +#include "lanelet2_core/primitives/BasicRegulatoryElements.h" +#include "lanelet2_core/utility/Utilities.h" using namespace lanelet; diff --git a/lanelet2/lanelet2_examples/CHANGELOG.rst b/lanelet2/lanelet2_examples/CHANGELOG.rst new file mode 100644 index 00000000000..2f3e92986eb --- /dev/null +++ b/lanelet2/lanelet2_examples/CHANGELOG.rst @@ -0,0 +1,32 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_examples +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Make all includes of lanelet2_examples consistent +* Updating package.xml files to format 3. +* Apply clang-tidy 10 recommendations +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* RoutingGraph and Route now use the new LaneletSubmap to store the lanelets they are using + their member functions laneletMap() and passableMap() are now deprecated and should be replaced by laneletSubmap() and passableSubmap() respectively. These functions have less overhead and are less likely to be misinterpreted as 'maps containing only the lanelets you need' +* Add a new class 'LaneletSubmap' that only contains parts of the map and is faster to construct +* Routing graph and route object now support queries with a custom search function +* Improve c++17 support, supress warnings and clang-tidy 7 issues +* Simplified definition of origin in python, adapted examples +* Add examples package +* Contributors: Fabian Poggenhans, Maximilian Naumann, Sascha Wirges diff --git a/lanelet2/lanelet2_examples/CMakeLists.txt b/lanelet2/lanelet2_examples/CMakeLists.txt index 4fda64e3bcd..7371df215b4 100644 --- a/lanelet2/lanelet2_examples/CMakeLists.txt +++ b/lanelet2/lanelet2_examples/CMakeLists.txt @@ -1,54 +1,36 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_examples) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -add_definitions(-DPKG_DIR="${CMAKE_CURRENT_LIST_DIR}") -set(MRT_FORCE_PYTHON_COVERAGE 1) +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -################################### -## catkin specific configuration ## -################################### -catkin_package( - ) - ########### ## Build ## ########### -# Add include and library directories -include_directories( - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - glob_folders(SRC_DIRECTORIES "${CMAKE_CURRENT_SOURCE_DIR}/src") if (SRC_DIRECTORIES) # Found subfolders, add executable for each subfolder @@ -63,8 +45,9 @@ endif() ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_examples/README.md b/lanelet2/lanelet2_examples/README.md index f3197ea79d1..f3ca3b1dd54 100644 --- a/lanelet2/lanelet2_examples/README.md +++ b/lanelet2/lanelet2_examples/README.md @@ -1,6 +1,6 @@ # Lanelet2 Examples -This package contains executable usage examples for people who would like to konw how to work with a lanelet2 map. Simply look at the code in the individual lessons. They are equipped with lots of explaining comments. You can also build and run them to see them in action. +This package contains executable usage examples for people who would like to know how to work with a lanelet2 map. Simply look at the code in the individual lessons. They are equipped with lots of explaining comments. You can also build and run them to see them in action. The examples are divided into individual lessons that help you step by step to understand lanelet2. Simply look [here](src) for an overview on the C++ tutorials. diff --git a/lanelet2/lanelet2_examples/custom.cmake b/lanelet2/lanelet2_examples/custom.cmake new file mode 100644 index 00000000000..5e8cc3aeb86 --- /dev/null +++ b/lanelet2/lanelet2_examples/custom.cmake @@ -0,0 +1 @@ +target_compile_definitions(lanelet2_examples_private_compiler_flags INTERFACE PKG_DIR="${CMAKE_CURRENT_LIST_DIR}") diff --git a/lanelet2/lanelet2_examples/src/ExampleHelpers.h b/lanelet2/lanelet2_examples/include/lanelet2_examples/internal/ExampleHelpers.h similarity index 93% rename from lanelet2/lanelet2_examples/src/ExampleHelpers.h rename to lanelet2/lanelet2_examples/include/lanelet2_examples/internal/ExampleHelpers.h index a27bdcc123d..67ba1cb9caa 100644 --- a/lanelet2/lanelet2_examples/src/ExampleHelpers.h +++ b/lanelet2/lanelet2_examples/include/lanelet2_examples/internal/ExampleHelpers.h @@ -15,7 +15,9 @@ inline LineString3d getLineStringAtY(double y) { } inline Polygon3d getAPolygon() { - Point3d p1{utils::getId(), 0, 0, 0}, p2{utils::getId(), 2, 0, 0}, p3{utils::getId(), 2, -2, 0}; + Point3d p1{utils::getId(), 0, 0, 0}; + Point3d p2{utils::getId(), 2, 0, 0}; + Point3d p3{utils::getId(), 2, -2, 0}; return Polygon3d(utils::getId(), {p1, p2, p3}); } diff --git a/lanelet2/lanelet2_examples/package.xml b/lanelet2/lanelet2_examples/package.xml index 9ad511c2c35..48e9ad7c05c 100644 --- a/lanelet2/lanelet2_examples/package.xml +++ b/lanelet2/lanelet2_examples/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_examples - 0.9.0 + 1.1.1 Examples for working with Lanelet2 BSD @@ -9,8 +10,10 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules lanelet2_core lanelet2_io lanelet2_python @@ -18,8 +21,11 @@ lanelet2_routing lanelet2_projection gtest - rosbash + rosbash + ros2cli + catkin + ament_cmake diff --git a/lanelet2/lanelet2_examples/scripts/tutorial.py b/lanelet2/lanelet2_examples/scripts/tutorial.py index 2bdaa9593e6..3c49803b227 100755 --- a/lanelet2/lanelet2_examples/scripts/tutorial.py +++ b/lanelet2/lanelet2_examples/scripts/tutorial.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python import lanelet2 import tempfile import os @@ -7,6 +7,10 @@ from lanelet2.projection import UtmProjector example_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), "../../lanelet2_maps/res/mapping_example.osm") +if not os.path.exists(example_file): + # location after installing + example_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), + "../../share/lanelet2_maps/res/mapping_example.osm") def tutorial(): @@ -131,7 +135,7 @@ def part6routing(): def hasPathFromTo(graph, start, target): - class TargetFound(Exception): + class TargetFound(BaseException): pass def raiseIfDestination(visitInformation): diff --git a/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp b/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp index 8f641dad609..7cc55fd4d1d 100644 --- a/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp +++ b/lanelet2/lanelet2_examples/src/01_dealing_with_lanelet_primitives/main.cpp @@ -7,7 +7,9 @@ #include #include #include -#include "../ExampleHelpers.h" + +#include "lanelet2_examples/internal/ExampleHelpers.h" + // we want assert statements to work in release mode #undef NDEBUG @@ -150,7 +152,9 @@ void part1Points() { void part2LineStrings() { using namespace lanelet; // LineStrings are created from a set of points with linear interpolation between them. - Point3d p1{utils::getId(), 0, 0, 0}, p2{utils::getId(), 1, 0, 0}, p3{utils::getId(), 2, 0, 0}; + Point3d p1{utils::getId(), 0, 0, 0}; + Point3d p2{utils::getId(), 1, 0, 0}; + Point3d p3{utils::getId(), 2, 0, 0}; LineString3d ls(utils::getId(), {p1, p2, p3}); // conceptually, linestrings are similar to an std::vector. You can access individal points or loop over them. @@ -217,7 +221,9 @@ void part3Polygons() { using namespace lanelet; // polygons are very, very similar to linestrings. the only actual difference is that there is a last, implicit // segment between the last and the first point that closes the polygon. The interface is basically the same: - Point3d p1{utils::getId(), 0, 0, 0}, p2{utils::getId(), 1, 0, 0}, p3{utils::getId(), 2, -1, 0}; + Point3d p1{utils::getId(), 0, 0, 0}; + Point3d p2{utils::getId(), 1, 0, 0}; + Point3d p3{utils::getId(), 2, -1, 0}; Polygon3d poly(utils::getId(), {p1, p2, p3}); assert(poly.size() == 3); @@ -379,8 +385,5 @@ void part6Geometry() { // if you want more than an estimation you can use the primitives directly. Overlaps only returns true if the shared // area of the two primitives is >0. In 3d, the distance in z must also be smaller than a margin. - -#if 0 assert(geometry::overlaps3d(area, lanelet, 3)); -#endif } diff --git a/lanelet2/lanelet2_examples/src/02_regulatory_elements/main.cpp b/lanelet2/lanelet2_examples/src/02_regulatory_elements/main.cpp index d8a6c037533..83cb90cd776 100644 --- a/lanelet2/lanelet2_examples/src/02_regulatory_elements/main.cpp +++ b/lanelet2/lanelet2_examples/src/02_regulatory_elements/main.cpp @@ -1,7 +1,8 @@ #include #include #include -#include "../ExampleHelpers.h" + +#include "lanelet2_examples/internal/ExampleHelpers.h" // we want assert statements to work in release mode #undef NDEBUG diff --git a/lanelet2/lanelet2_examples/src/03_lanelet_map/main.cpp b/lanelet2/lanelet2_examples/src/03_lanelet_map/main.cpp index c25677314b4..4392a957fa8 100644 --- a/lanelet2/lanelet2_examples/src/03_lanelet_map/main.cpp +++ b/lanelet2/lanelet2_examples/src/03_lanelet_map/main.cpp @@ -2,7 +2,8 @@ #include #include #include -#include "../ExampleHelpers.h" + +#include "lanelet2_examples/internal/ExampleHelpers.h" #pragma GCC diagnostic ignored "-Wunused-variable" diff --git a/lanelet2/lanelet2_examples/src/04_reading_and_writing/main.cpp b/lanelet2/lanelet2_examples/src/04_reading_and_writing/main.cpp index 9cc2d0d8c80..f65d8685375 100644 --- a/lanelet2/lanelet2_examples/src/04_reading_and_writing/main.cpp +++ b/lanelet2/lanelet2_examples/src/04_reading_and_writing/main.cpp @@ -3,6 +3,7 @@ #include #include #include + #include #pragma GCC diagnostic ignored "-Wunused-but-set-variable" @@ -15,7 +16,7 @@ std::string exampleMapPath = std::string(PKG_DIR) + "/../lanelet2_maps/res/mappi std::string tempfile(const std::string& name) { char tmpDir[] = "/tmp/lanelet2_example_XXXXXX"; - auto file = mkdtemp(tmpDir); + auto* file = mkdtemp(tmpDir); if (file == nullptr) { throw lanelet::IOError("Failed to open a temporary file for writing"); } diff --git a/lanelet2/lanelet2_examples/src/05_traffic_rules/main.cpp b/lanelet2/lanelet2_examples/src/05_traffic_rules/main.cpp index 8b7001779e0..dbb79a9b243 100644 --- a/lanelet2/lanelet2_examples/src/05_traffic_rules/main.cpp +++ b/lanelet2/lanelet2_examples/src/05_traffic_rules/main.cpp @@ -4,7 +4,8 @@ #include #include #include -#include "../ExampleHelpers.h" + +#include "lanelet2_examples/internal/ExampleHelpers.h" // we want assert statements to work in release mode #undef NDEBUG @@ -22,8 +23,9 @@ void part1UsingTrafficRules() { using namespace lanelet::units::literals; // first lets construct a sequence of lanelets. left is left of right, next follows right. - LineString3d leftLs{examples::getLineStringAtY(3)}, middleLs{examples::getLineStringAtY(2)}, - rightLs{examples::getLineStringAtY(0)}; + LineString3d leftLs{examples::getLineStringAtY(3)}; + LineString3d middleLs{examples::getLineStringAtY(2)}; + LineString3d rightLs{examples::getLineStringAtY(0)}; LineString3d nextLeftLs{utils::getId(), {middleLs.back(), Point3d(utils::getId(), middleLs.back().x() + 1., middleLs.back().y())}}; LineString3d nextRightLs{utils::getId(), diff --git a/lanelet2/lanelet2_examples/test/test_examples.py b/lanelet2/lanelet2_examples/test/test_examples.py index c7fea5f8295..3e784dcc9cf 100644 --- a/lanelet2/lanelet2_examples/test/test_examples.py +++ b/lanelet2/lanelet2_examples/test/test_examples.py @@ -1,25 +1,28 @@ import unittest import os +import sys import subprocess class Lanelet2ExamplesTestCase(unittest.TestCase): def test_run_all_examples(self): + ros2 = os.environ.get("ROS_VERSION", "") == "2" + run_cmd = "rosrun lanelet2_examples {}" if not ros2 else "ros2 run lanelet2_examples {}" src = "../src" examples = [o for o in os.listdir(src) if os.path.isdir(os.path.join(src, o))] devnull = open(os.devnull, 'w') for example in examples: print("running " + example) - result = subprocess.call("rosrun lanelet2_examples {}".format(example), shell=True, stdout=devnull) + result = subprocess.call(run_cmd.format(example), shell=True) self.assertEqual(result, 0, "Failed to execute {}".format(example)) def test_run_py_examples(self): scripts = "../scripts" - examples = [o for o in os.listdir(scripts) if not os.path.isdir(os.path.join(scripts, o))] + examples = [os.path.join(scripts, o) for o in os.listdir(scripts) if o.endswith(".py")] devnull = open(os.devnull, 'w') for example in examples: print("running " + example) - result = subprocess.call("rosrun lanelet2_examples {}".format(example), shell=True, stdout=devnull) + result = subprocess.call([sys.executable, example]) self.assertEqual(result, 0, "Failed to execute {}".format(example)) diff --git a/lanelet2/lanelet2_io/CHANGELOG.rst b/lanelet2/lanelet2_io/CHANGELOG.rst new file mode 100644 index 00000000000..a6ae096f7a0 --- /dev/null +++ b/lanelet2/lanelet2_io/CHANGELOG.rst @@ -0,0 +1,38 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_io +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Format files with clang-format 10 +* io: Fix random errors in bin serialization when serializing a HybridMap + fixes fzi-forschungszentrum-informatik/Lanelet2#128 +* Making all includes in lanelet2_io consistent. +* Updating package.xml files to format 3. +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Improve warning if wrong decimal symbol is set, also report it when loading +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Add a new class 'LaneletSubmap' that only contains parts of the map and is faster to construct +* IO: Implement warning for cases where the decimal point is overridden by a different locale + resolves MRT/released/lanelet2#91 +* Fix loading of polygons that have been written without an area tag + resolves MRT/released/lanelet2#113 +* Refactored osm parser so that parsed roles in relations keep their + positions +* Improve c++17 support, supress warnings and clang-tidy 7 issues +* IO now complains when loading georeferenced maps with a default origin (resolves #71) +* Initial commit +* Contributors: Fabian Poggenhans, Maximilian Naumann diff --git a/lanelet2/lanelet2_io/CMakeLists.txt b/lanelet2/lanelet2_io/CMakeLists.txt index 2bf109d7393..66323e9ec97 100644 --- a/lanelet2/lanelet2_io/CMakeLists.txt +++ b/lanelet2/lanelet2_io/CMakeLists.txt @@ -1,4 +1,4 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! cmake_minimum_required(VERSION 2.8.12) project(lanelet2_io) @@ -95,4 +95,4 @@ mrt_install(PROGRAMS scripts FILES res data) if (CATKIN_ENABLE_TESTING) mrt_add_tests(test) mrt_add_nosetests(test) -endif() +endif() \ No newline at end of file diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/Configuration.h b/lanelet2/lanelet2_io/include/lanelet2_io/Configuration.h index 141e0c4a95e..d93eade4efd 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/Configuration.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/Configuration.h @@ -1,5 +1,6 @@ #pragma once #include + #include #include namespace lanelet { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/Exceptions.h b/lanelet2/lanelet2_io/include/lanelet2_io/Exceptions.h index ae3255e096e..8b73cd7e86b 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/Exceptions.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/Exceptions.h @@ -1,5 +1,6 @@ #pragma once #include + #include namespace lanelet { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/Io.h b/lanelet2/lanelet2_io/include/lanelet2_io/Io.h index 8d78aa53460..04568268401 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/Io.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/Io.h @@ -1,9 +1,11 @@ #pragma once #include + #include #include -#include "Configuration.h" -#include "Projection.h" + +#include "lanelet2_io/Configuration.h" +#include "lanelet2_io/Projection.h" namespace lanelet { using ErrorMessages = std::vector; diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/Projection.h b/lanelet2/lanelet2_io/include/lanelet2_io/Projection.h index 8697caa924a..acd6672bf35 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/Projection.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/Projection.h @@ -1,6 +1,7 @@ #pragma once #include #include + #include #include diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/BinHandler.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/BinHandler.h index 27c939191fd..b5831ee0dcf 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/BinHandler.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/BinHandler.h @@ -1,6 +1,6 @@ #pragma once -#include "Parser.h" -#include "Writer.h" +#include "lanelet2_io/io_handlers/Parser.h" +#include "lanelet2_io/io_handlers/Writer.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Factory.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Factory.h index 6a16a1b6592..74b10dad362 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Factory.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Factory.h @@ -1,13 +1,15 @@ #pragma once #include + #include #include #include #include -#include "../Configuration.h" -#include "../Projection.h" -#include "Parser.h" -#include "Writer.h" + +#include "lanelet2_io/Configuration.h" +#include "lanelet2_io/Projection.h" +#include "lanelet2_io/io_handlers/Parser.h" +#include "lanelet2_io/io_handlers/Writer.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/IoHandler.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/IoHandler.h index d2d21204755..849e4df2436 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/IoHandler.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/IoHandler.h @@ -1,7 +1,8 @@ #pragma once #include -#include "../Configuration.h" -#include "../Projection.h" + +#include "lanelet2_io/Configuration.h" +#include "lanelet2_io/Projection.h" namespace lanelet { using ErrorMessages = std::vector; @@ -37,7 +38,7 @@ class IOHandler { // NOLINT return *projector_; } - const io::Configuration config() { return *config_; } + io::Configuration config() { return *config_; } protected: IOHandler() = default; // workaround for gcc5 bug diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmFile.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmFile.h index 0aa3464e1f9..a539bf11212 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmFile.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmFile.h @@ -1,6 +1,7 @@ #pragma once #include #include + #include #include #include diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmHandler.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmHandler.h index 3d2eb22f9da..fe9a895bba0 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmHandler.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/OsmHandler.h @@ -1,7 +1,7 @@ #pragma once -#include "OsmFile.h" -#include "Parser.h" -#include "Writer.h" +#include "lanelet2_io/io_handlers/OsmFile.h" +#include "lanelet2_io/io_handlers/Parser.h" +#include "lanelet2_io/io_handlers/Writer.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Parser.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Parser.h index 812df8205ae..485cd7abb75 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Parser.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Parser.h @@ -1,9 +1,11 @@ #pragma once #include + #include -#include "../Exceptions.h" -#include "../Projection.h" -#include "IoHandler.h" + +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/Projection.h" +#include "lanelet2_io/io_handlers/IoHandler.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Serialize.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Serialize.h index 6a6a591bf5b..cb5c16d447a 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Serialize.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Serialize.h @@ -1,5 +1,7 @@ #pragma once #include + +#include #include #include #include @@ -48,58 +50,24 @@ void save(Archive& ar, const lanelet::Attribute& p, unsigned int /*version*/) { ar& p.value(); } -template -void serialize(Archive& ar, std::pair& p, unsigned int /*version*/) { - ar& p.first; - ar& p.second; -} - -template -void serialize(Archive& ar, std::pair& p, unsigned int /*version*/) { - ar& p.first; - ar& p.second; -} - template void load(Archive& ar, lanelet::AttributeMap& p, unsigned int /*version*/) { - size_t size; - ar& size; - for (auto i = 0u; i < size; ++i) { - std::pair val; - ar& val; - p.insert(std::move(val)); - } + boost::serialization::load_map_collection(ar, p); } template void save(Archive& ar, const lanelet::AttributeMap& p, unsigned int /*version*/) { - auto size = p.size(); - ar& size; - for (auto& elem : p) { - std::pair val = elem; - ar& val; - } + boost::serialization::stl::save_collection(ar, p); } template void load(Archive& ar, lanelet::RuleParameterMap& p, unsigned int /*version*/) { - size_t size; - ar& size; - for (auto i = 0u; i < size; ++i) { - std::pair val; - ar& val; - p.insert(std::move(val)); - } + boost::serialization::load_map_collection(ar, p); } template void save(Archive& ar, const lanelet::RuleParameterMap& p, unsigned int /*version*/) { - size_t size = p.size(); - ar& size; - for (auto& elem : p) { - std::pair val = elem; - ar& val; - } + boost::serialization::stl::save_collection(ar, p); } //! lanelet +data @@ -126,13 +94,14 @@ template inline void load_construct_data(Archive& ar, lanelet::LaneletData* llt, unsigned int /*version*/ ) { using namespace lanelet; - Id id; + Id id = 0; AttributeMap attrs; - LineString3d left, right; + LineString3d left; + LineString3d right; ar >> id >> attrs >> left >> right; new (llt) LaneletData(id, left, right, attrs); lanelet::impl::loadRegelems(ar, llt->regulatoryElements()); // must happen directly to the correct memory location - bool hasCenterline; + bool hasCenterline = false; ar >> hasCenterline; if (hasCenterline) { LineString3d centerline; @@ -150,7 +119,7 @@ void save(Archive& ar, const lanelet::Lanelet& l, unsigned int /*version*/) { template void load(Archive& ar, lanelet::Lanelet& l, unsigned int /*version*/) { std::shared_ptr ptr; - bool inv; + bool inv = false; ar >> inv >> ptr; l = lanelet::Lanelet(ptr, inv); } @@ -164,7 +133,7 @@ void save(Archive& ar, const lanelet::ConstLanelet& l, unsigned int /*version*/) template void load(Archive& ar, lanelet::ConstLanelet& l, unsigned int /*version*/) { std::shared_ptr ptr; - bool inv; + bool inv = false; ar >> inv >> ptr; l = lanelet::Lanelet(ptr, inv); } @@ -198,7 +167,7 @@ template // NOLINTNEXTLINE inline void load_construct_data(Archive& ar, lanelet::LineStringData* l, unsigned int /*version*/) { using namespace lanelet; - Id id; + Id id = 0; AttributeMap attr; Points3d points; ar >> id >> attr >> points; @@ -269,7 +238,7 @@ template // NOLINTNEXTLINE inline void load_construct_data(Archive& ar, lanelet::PointData* p, unsigned int /*version*/) { using namespace lanelet; - Id id; + Id id = 0; AttributeMap attrs; BasicPoint3d pt; ar >> id >> attrs >> pt.x() >> pt.y() >> pt.z(); @@ -316,7 +285,7 @@ template // NOLINTNEXTLINE inline void load_construct_data(Archive& ar, lanelet::AreaData* a, unsigned int /*version*/) { using namespace lanelet; - Id id; + Id id = 0; AttributeMap attrs; InnerBounds inner; LineStrings3d outer; @@ -423,7 +392,7 @@ template // NOLINTNEXTLINE inline void load_construct_data(Archive& ar, lanelet::RegulatoryElementData* r, unsigned int /*version*/) { using namespace lanelet; - Id id; + Id id = 0; AttributeMap attr; RuleParameterMap params; ar >> id >> attr >> params; @@ -445,7 +414,7 @@ void save(Archive& ar, const lanelet::RegulatoryElementPtr& r, unsigned int /*ve template void load(Archive& ar, lanelet::RegulatoryElementPtr& r, unsigned int /*version*/) { auto& helper = ar.template get_helper(&ar); - lanelet::Id id; + lanelet::Id id = 0; ar >> id; if (helper.currentlyDeserializing(id, r)) { return; @@ -490,7 +459,7 @@ template void load(Archive& ar, lanelet::LaneletMap& m, unsigned int /*version*/) { auto loadLayer = [&ar](auto& layerMap) { using Prim = typename std::decay_t::mapped_type; - size_t size; + size_t size = 0; ar >> size; for (auto i = 0u; i < size; ++i) { Prim p; @@ -516,18 +485,18 @@ void load(Archive& ar, lanelet::LaneletMap& m, unsigned int /*version*/) { } // namespace serialization } // namespace boost -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::AttributeMap); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Attribute); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakArea); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Area); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakLanelet); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Lanelet); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Point3d); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstPoint3d); // NOLINT -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LineString3d); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstLineString3d); // NOLINT -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Polygon3d); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RuleParameterMap); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementPtr); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementConstPtr); -BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LaneletMap); +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::AttributeMap) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Attribute) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakArea) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Area) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakLanelet) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Lanelet) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Point3d) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstPoint3d) // NOLINT +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LineString3d) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstLineString3d) // NOLINT +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Polygon3d) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RuleParameterMap) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementPtr) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementConstPtr) +BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LaneletMap) diff --git a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Writer.h b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Writer.h index 3f4835d29bd..2e6d90a57bf 100644 --- a/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Writer.h +++ b/lanelet2/lanelet2_io/include/lanelet2_io/io_handlers/Writer.h @@ -1,9 +1,11 @@ #pragma once #include + #include #include -#include "../Projection.h" -#include "IoHandler.h" + +#include "lanelet2_io/Projection.h" +#include "lanelet2_io/io_handlers/IoHandler.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/package.xml b/lanelet2/lanelet2_io/package.xml index b3110b4bde7..1c52485db4c 100644 --- a/lanelet2/lanelet2_io/package.xml +++ b/lanelet2/lanelet2_io/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_io - 0.9.0 + 1.1.1 Parser/Writer module for lanelet2 BSD @@ -9,14 +10,18 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest boost lanelet2_core pugixml-dev + catkin + ament_cmake diff --git a/lanelet2/lanelet2_io/src/BinHandler.cpp b/lanelet2/lanelet2_io/src/BinHandler.cpp index cc6802800d4..3f30210d092 100644 --- a/lanelet2/lanelet2_io/src/BinHandler.cpp +++ b/lanelet2/lanelet2_io/src/BinHandler.cpp @@ -1,10 +1,12 @@ -#include "io_handlers/BinHandler.h" +#include "lanelet2_io/io_handlers/BinHandler.h" + #include #include #include -#include "Exceptions.h" -#include "io_handlers/Factory.h" -#include "io_handlers/Serialize.h" + +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/io_handlers/Factory.h" +#include "lanelet2_io/io_handlers/Serialize.h" namespace lanelet { namespace io_handlers { @@ -35,7 +37,7 @@ std::unique_ptr BinParser::parse(const std::string& filename, ErrorM std::unique_ptr laneletMap = std::make_unique(); boost::archive::binary_iarchive ia(fs); ia >> *laneletMap; - Id idCounter; + Id idCounter = 0; ia >> idCounter; utils::registerId(idCounter); return laneletMap; diff --git a/lanelet2/lanelet2_io/src/Factory.cpp b/lanelet2/lanelet2_io/src/Factory.cpp index 0c0604e9a14..9f4aaec3dd5 100644 --- a/lanelet2/lanelet2_io/src/Factory.cpp +++ b/lanelet2/lanelet2_io/src/Factory.cpp @@ -1,5 +1,6 @@ -#include "io_handlers/Factory.h" -#include "Exceptions.h" +#include "lanelet2_io/io_handlers/Factory.h" + +#include "lanelet2_io/Exceptions.h" namespace lanelet { namespace io_handlers { diff --git a/lanelet2/lanelet2_io/src/Io.cpp b/lanelet2/lanelet2_io/src/Io.cpp index 7f1bab37cfc..138ce9b3df2 100644 --- a/lanelet2/lanelet2_io/src/Io.cpp +++ b/lanelet2/lanelet2_io/src/Io.cpp @@ -1,7 +1,9 @@ -#include "Io.h" +#include "lanelet2_io/Io.h" + #include -#include "Exceptions.h" -#include "io_handlers/Factory.h" + +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/io_handlers/Factory.h" namespace fs = boost::filesystem; diff --git a/lanelet2/lanelet2_io/src/OsmFile.cpp b/lanelet2/lanelet2_io/src/OsmFile.cpp index b1d2883015d..0d1235293fd 100644 --- a/lanelet2/lanelet2_io/src/OsmFile.cpp +++ b/lanelet2/lanelet2_io/src/OsmFile.cpp @@ -1,5 +1,7 @@ -#include "io_handlers/OsmFile.h" +#include "lanelet2_io/io_handlers/OsmFile.h" + #include + #include #include @@ -94,19 +96,18 @@ void removeAndFixPlaceholders(Primitive** toRemove, Roles& fromRoles, std::vecto class OsmFileWriter { public: static std::unique_ptr write(const File& osmFile) { - OsmFileWriter osmIo; auto xml = std::make_unique(); auto osmNode = xml->append_child(keyword::Osm); osmNode.append_attribute("version") = "0.6"; osmNode.append_attribute("generator") = "lanelet2"; - osmIo.writeNodes(osmNode, osmFile.nodes); - osmIo.writeWays(osmNode, osmFile.ways); - osmIo.writeRelations(osmNode, osmFile.relations); + lanelet::osm::OsmFileWriter::writeNodes(osmNode, osmFile.nodes); + lanelet::osm::OsmFileWriter::writeWays(osmNode, osmFile.ways); + lanelet::osm::OsmFileWriter::writeRelations(osmNode, osmFile.relations); return xml; } private: - void writeAttributes(pugi::xml_node& elemNode, const Attributes& attributes) { + static void writeAttributes(pugi::xml_node& elemNode, const Attributes& attributes) { for (const auto& attribute : attributes) { auto tagNode = elemNode.append_child(keyword::Tag); tagNode.append_attribute(keyword::Key) = attribute.first.c_str(); @@ -114,7 +115,7 @@ class OsmFileWriter { } } - void writeNodes(pugi::xml_node& osmNode, const Nodes& nodes) { + static void writeNodes(pugi::xml_node& osmNode, const Nodes& nodes) { for (const auto& node : nodes) { auto xmlNode = osmNode.append_child(keyword::Node); xmlNode.append_attribute(keyword::Id) = LongLong(node.second.id); @@ -134,7 +135,7 @@ class OsmFileWriter { } } - void writeWays(pugi::xml_node& osmNode, const Ways& ways) { + static void writeWays(pugi::xml_node& osmNode, const Ways& ways) { for (const auto& wayElem : ways) { const auto& way = wayElem.second; auto xmlNode = osmNode.append_child(keyword::Way); @@ -151,7 +152,7 @@ class OsmFileWriter { } } - void writeRelations(pugi::xml_node& osmNode, const Relations& relations) { + static void writeRelations(pugi::xml_node& osmNode, const Relations& relations) { for (const auto& relationElem : relations) { const auto& relation = relationElem.second; auto xmlNode = osmNode.append_child(keyword::Relation); @@ -178,7 +179,7 @@ class OsmFileParser { OsmFileParser osmParser; File file; auto osmNode = fileNode.child(keyword::Osm); - file.nodes = osmParser.readNodes(osmNode); + file.nodes = lanelet::osm::OsmFileParser::readNodes(osmNode); file.ways = osmParser.readWays(osmNode, file.nodes); file.relations = osmParser.readRelations(osmNode, file.nodes, file.ways); if (errors != nullptr) { @@ -188,7 +189,7 @@ class OsmFileParser { } private: - Nodes readNodes(const pugi::xml_node& osmNode) { + static Nodes readNodes(const pugi::xml_node& osmNode) { Nodes nodes; for (auto node = osmNode.child(keyword::Node); node; // NOLINT node = node.next_sibling(keyword::Node)) { diff --git a/lanelet2/lanelet2_io/src/OsmHandlerLoad.cpp b/lanelet2/lanelet2_io/src/OsmHandlerLoad.cpp index 82881fc8a08..4e1f6a63d9f 100644 --- a/lanelet2/lanelet2_io/src/OsmHandlerLoad.cpp +++ b/lanelet2/lanelet2_io/src/OsmHandlerLoad.cpp @@ -1,15 +1,16 @@ -#include -#include "io_handlers/OsmHandler.h" - #include #include + #include #include +#include #include #include -#include "Exceptions.h" -#include "io_handlers/Factory.h" -#include "io_handlers/OsmFile.h" + +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/io_handlers/Factory.h" +#include "lanelet2_io/io_handlers/OsmFile.h" +#include "lanelet2_io/io_handlers/OsmHandler.h" using namespace std::string_literals; @@ -43,7 +44,7 @@ RegulatoryElementPtr getDummy(Id id) { return std::make_shared(std::make_shared(id)); } -Errors buildErrorMessage(const std::string& errorIntro, Errors errors) { +Errors buildErrorMessage(const std::string& errorIntro, const Errors& errors) { if (errors.empty()) { return {}; } @@ -225,7 +226,7 @@ class FromFileLoader { // NOLINT return attr != relation.attributes.end() && attr->second == Type; } - lanelet::AttributeMap getAttributes(const lanelet::osm::Attributes& osmAttributes) { + static lanelet::AttributeMap getAttributes(const lanelet::osm::Attributes& osmAttributes) { lanelet::AttributeMap attributes; for (const auto& osmAttr : osmAttributes) { attributes.insert(std::make_pair(osmAttr.first, lanelet::Attribute(osmAttr.second))); @@ -405,6 +406,17 @@ void registerIds(const MapT& map) { utils::registerId(map.rbegin()->first); } } + +void testAndPrintLocaleWarning(ErrorMessages& errors) { + auto* decimalPoint = std::localeconv()->decimal_point; + if (decimalPoint == nullptr || *decimalPoint != '.') { + std::stringstream ss; + ss << "Warning: Current decimal point of the C locale is set to \"" + << (decimalPoint == nullptr ? ' ' : *decimalPoint) << "\". The loaded map will have wrong coordinates!\n"; + errors.emplace_back(ss.str()); + std::cerr << errors.back(); + } +} } // namespace std::unique_ptr OsmParser::parse(const std::string& filename, ErrorMessages& errors) const { @@ -415,6 +427,7 @@ std::unique_ptr OsmParser::parse(const std::string& filename, ErrorM throw lanelet::ParseError("Errors occured while parsing osm file: "s + result.description()); } osm::Errors osmReadErrors; + testAndPrintLocaleWarning(osmReadErrors); auto file = lanelet::osm::read(doc, &osmReadErrors); auto map = fromOsmFile(file, errors); // make sure ids in the file are known to Lanelet2 id management. diff --git a/lanelet2/lanelet2_io/src/OsmHandlerWrite.cpp b/lanelet2/lanelet2_io/src/OsmHandlerWrite.cpp index 0aa7d715478..9313033f3ce 100644 --- a/lanelet2/lanelet2_io/src/OsmHandlerWrite.cpp +++ b/lanelet2/lanelet2_io/src/OsmHandlerWrite.cpp @@ -1,9 +1,10 @@ #include #include -#include "Exceptions.h" -#include "io_handlers/Factory.h" -#include "io_handlers/OsmFile.h" -#include "io_handlers/OsmHandler.h" + +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/io_handlers/Factory.h" +#include "lanelet2_io/io_handlers/OsmFile.h" +#include "lanelet2_io/io_handlers/OsmHandler.h" using namespace std::string_literals; @@ -69,7 +70,7 @@ class ToFileWriter { } private: - ToFileWriter() : file_{std::make_unique()} {} + ToFileWriter() = default; // writers for every primitive void writeNodes(const LaneletMap& map, const Projector& projector) { @@ -158,7 +159,7 @@ class ToFileWriter { errors_.push_back("Error writing primitive "s + std::to_string(id) + ": " + what); } - osm::Attributes getAttributes(const AttributeMap& attributes) { + static osm::Attributes getAttributes(const AttributeMap& attributes) { osm::Attributes osmAttributes; for (const auto& attr : attributes) { osmAttributes.emplace(attr.first, attr.second.value()); @@ -175,7 +176,7 @@ class ToFileWriter { } try { const auto wayNodes = - utils::transform(mapWay, [& nodes = file_->nodes](const auto& elem) { return &nodes.at(elem.id()); }); + utils::transform(mapWay, [&nodes = file_->nodes](const auto& elem) { return &nodes.at(elem.id()); }); osmWays.emplace(id, osm::Way(id, std::move(wayAttributes), std::move(wayNodes))); } catch (NoSuchPrimitiveError& e) { writeError(id, "Way has points that are not point layer: "s + e.what()); @@ -273,29 +274,32 @@ class ToFileWriter { errs.clear(); if (!errors_.empty()) { errs.reserve(errors_.size() + 1); - errs.emplace_back("Errors ocurred while parsing Lanelet Map:"); + errs.emplace_back("Errors ocurred while writing Lanelet Map:"); for (const auto& err : errors_) { errs.emplace_back("\t- " + err); } } } Errors errors_; - std::unique_ptr file_; + std::unique_ptr file_{std::make_unique()}; }; -void testAndPrintLocaleWarning() { - auto decimalPoint = std::localeconv()->decimal_point; +void testAndPrintLocaleWarning(ErrorMessages& errors) { + auto* decimalPoint = std::localeconv()->decimal_point; if (decimalPoint == nullptr || *decimalPoint != '.') { - std::cerr << "Warning: Current decimal point of the C locale is set to \"" - << (decimalPoint == nullptr ? ' ' : *decimalPoint) << "\". This will lead to invalid osm output!\n"; + std::stringstream ss; + ss << "Warning: Current decimal point of the C locale is set to \"" + << (decimalPoint == nullptr ? ' ' : *decimalPoint) << "\". This will lead to invalid osm output!\n"; + errors.emplace_back(ss.str()); + std::cerr << errors.back(); } } } // namespace void OsmWriter::write(const std::string& filename, const LaneletMap& laneletMap, ErrorMessages& errors) const { + testAndPrintLocaleWarning(errors); auto file = toOsmFile(laneletMap, errors); auto doc = osm::write(*file); - testAndPrintLocaleWarning(); auto res = doc->save_file(filename.c_str(), " "); if (!res) { throw ParseError("Pugixml failed to write the map (unable to create file?)"); diff --git a/lanelet2/lanelet2_io/test/TestBinHandler.cpp b/lanelet2/lanelet2_io/test/TestBinHandler.cpp index 852ec8b428a..c9868ab79af 100644 --- a/lanelet2/lanelet2_io/test/TestBinHandler.cpp +++ b/lanelet2/lanelet2_io/test/TestBinHandler.cpp @@ -1,11 +1,12 @@ -#include #include #include #include #include -#include "Io.h" + #include "TestSetup.h" #include "gtest/gtest.h" +#include "lanelet2_io/Io.h" +#include "lanelet2_io/io_handlers/Serialize.h" using namespace lanelet; @@ -97,19 +98,19 @@ TEST_F(SerializeTest, LaneletMap) { // NOLINT } TEST(BinHandler, extension) { // NOLINT - std::string filename = std::tmpnam(nullptr) + std::string(".bin"); + lanelet::test_setup::Tempfile t("file.bin"); auto map = std::make_shared(); - lanelet::write(filename, *map); + lanelet::write(t.get().string(), *map); - auto mapLoad = lanelet::load(filename); + auto mapLoad = lanelet::load(t.get().string()); } TEST(BinHandler, explicitIO) { // NOLINT - std::string filename = std::tmpnam(nullptr) + std::string(".bin"); + lanelet::test_setup::Tempfile t("file.bin"); auto map = std::make_shared(); - lanelet::write(filename, *map, "bin_handler"); + lanelet::write(t.get().string(), *map, "bin_handler"); - auto mapLoad = lanelet::load(filename, "bin_handler"); + auto mapLoad = lanelet::load(t.get().string(), "bin_handler"); } TEST(BinHandler, fullMap) { diff --git a/lanelet2/lanelet2_io/test/TestLanelet2Io.cpp b/lanelet2/lanelet2_io/test/TestLanelet2Io.cpp index 9e947c9accf..5040055b553 100644 --- a/lanelet2/lanelet2_io/test/TestLanelet2Io.cpp +++ b/lanelet2/lanelet2_io/test/TestLanelet2Io.cpp @@ -1,7 +1,7 @@ +#include "TestSetup.h" #include "gtest/gtest.h" - -#include "Exceptions.h" -#include "Io.h" +#include "lanelet2_io/Exceptions.h" +#include "lanelet2_io/Io.h" TEST(lanelet2_io, registryTest) { // NOLINT auto parseExtensions = lanelet::supportedParserExtensions(); @@ -14,11 +14,9 @@ TEST(lanelet2_io, registryTest) { // NOLINT } TEST(lanelet2_io, exceptionTest) { // NOLINT - auto nonsenseExtension = std::string(std::tmpnam(nullptr)) + ".unsupported_extension"; - std::FILE* tmpf = std::fopen(nonsenseExtension.c_str(), "wb+"); - EXPECT_THROW(lanelet::load(nonsenseExtension), lanelet::UnsupportedExtensionError); // NOLINT - EXPECT_THROW(lanelet::load(nonsenseExtension, "nonexisting_parser"), lanelet::UnsupportedIOHandlerError); // NOLINT - EXPECT_THROW(lanelet::load("/nonexisting/file/with/known/extension.osm"), lanelet::FileNotFoundError); // NOLINT - std::fclose(tmpf); - std::remove(nonsenseExtension.c_str()); + lanelet::test_setup::Tempfile file("file_with.unsupported_extension"); + file.touch(); + EXPECT_THROW(lanelet::load(file.get().string()), lanelet::UnsupportedExtensionError); // NOLINT + EXPECT_THROW(lanelet::load(file.get().string(), "nonexisting_parser"), lanelet::UnsupportedIOHandlerError); // NOLINT + EXPECT_THROW(lanelet::load("/nonexisting/file/with/known/extension.osm"), lanelet::FileNotFoundError); // NOLINT } diff --git a/lanelet2/lanelet2_io/test/TestOsmFile.cpp b/lanelet2/lanelet2_io/test/TestOsmFile.cpp index ceb3840e6c9..2859fb804f5 100644 --- a/lanelet2/lanelet2_io/test/TestOsmFile.cpp +++ b/lanelet2/lanelet2_io/test/TestOsmFile.cpp @@ -1,6 +1,7 @@ #include + #include "gtest/gtest.h" -#include "io_handlers/OsmFile.h" +#include "lanelet2_io/io_handlers/OsmFile.h" using namespace lanelet::osm; diff --git a/lanelet2/lanelet2_io/test/TestOsmHandler.cpp b/lanelet2/lanelet2_io/test/TestOsmHandler.cpp index 4988c09430d..8ff4c25dae4 100644 --- a/lanelet2/lanelet2_io/test/TestOsmHandler.cpp +++ b/lanelet2/lanelet2_io/test/TestOsmHandler.cpp @@ -1,10 +1,12 @@ #include #include #include + #include -#include "Io.h" + #include "TestSetup.h" -#include "io_handlers/OsmHandler.h" +#include "lanelet2_io/Io.h" +#include "lanelet2_io/io_handlers/OsmHandler.h" using namespace lanelet; @@ -89,8 +91,8 @@ TEST(OsmHandler, writeMapWithIncompleteRegelem) { // NOLINT auto regElem = test_setup::setUpRegulatoryElement(num); lanelet::LaneletMap map({}, {}, {{regElem->id(), regElem}}, {}, {}, {}); ErrorMessages errsWrite; - io_handlers::OsmWriter parser(defaultProjection(Origin({0, 0, 0}))); - auto file = parser.toOsmFile(map, errsWrite); + auto projector = defaultProjection(Origin({0, 0, 0})); + auto file = io_handlers::OsmWriter(projector).toOsmFile(map, errsWrite); EXPECT_GT(errsWrite.size(), 0ul); } @@ -99,8 +101,8 @@ TEST(OsmHandler, writeMapWithIncompleteLanelet) { // NOLINT auto llt = test_setup::setUpLanelet(num); lanelet::LaneletMap map({{llt.id(), llt}}, {}, {}, {}, {}, {}); ErrorMessages errsWrite; - io_handlers::OsmWriter parser(defaultProjection(Origin({0, 0, 0}))); - auto file = parser.toOsmFile(map, errsWrite); + auto projector = defaultProjection(Origin({0, 0, 0})); + auto file = io_handlers::OsmWriter(projector).toOsmFile(map, errsWrite); EXPECT_GT(errsWrite.size(), 0ul); } @@ -111,8 +113,8 @@ TEST(OsmHandler, writeMapWithLaneletAndAreaToFile) { // NOLINT auto ll = test_setup::setUpLanelet(num); map->add(ar); map->add(ll); - auto filename = std::string(std::tmpnam(nullptr)) + ".osm"; // NOLINT + lanelet::test_setup::Tempfile file("file.osm"); Origin origin({49, 8.4, 0}); - write(filename, *map, origin); - EXPECT_NO_THROW(load(filename, origin)); // NOLINT + write(file.get().string(), *map, origin); + EXPECT_NO_THROW(load(file.get().string(), origin)); // NOLINT } diff --git a/lanelet2/lanelet2_io/test/TestSetup.h b/lanelet2/lanelet2_io/test/TestSetup.h index db18b2e0858..67652af74c8 100644 --- a/lanelet2/lanelet2_io/test/TestSetup.h +++ b/lanelet2/lanelet2_io/test/TestSetup.h @@ -1,6 +1,12 @@ #pragma once #include #include +#include + +#include +#include + +namespace fs = boost::filesystem; namespace lanelet { inline bool operator==(const PointData& lhs, const PointData& rhs) { @@ -115,5 +121,29 @@ inline Area setUpArea(int& num, const std::string& type = AttributeValueString:: AttributeMap{{AttributeNamesString::Subtype, type}}, {regelem}); } +class Tempfile { + public: + explicit Tempfile(std::string name) { + char dir[] = {"/tmp/lanelet2_io_test.XXXXXX"}; + auto* res = mkdtemp(dir); + if (res == nullptr) { + throw lanelet::LaneletError("Failed to crate temporary directory"); + } + dir_ = dir; + path_ = fs::path(dir_) / name; + } + Tempfile(Tempfile&& rhs) noexcept = delete; + Tempfile& operator=(Tempfile&& rhs) noexcept = delete; + Tempfile(const Tempfile& rhs) = delete; + Tempfile& operator=(const Tempfile& rhs) = delete; + ~Tempfile() { fs::remove_all(path_); } + + const fs::path& get() const { return path_; } + void touch() { std::ofstream(path_.string()); } + + private: + std::string dir_; + fs::path path_; +}; } // namespace test_setup } // namespace lanelet diff --git a/lanelet2/lanelet2_io/test/TestSimpleUsage.cpp b/lanelet2/lanelet2_io/test/TestSimpleUsage.cpp index 72254809d61..792f69d822d 100644 --- a/lanelet2/lanelet2_io/test/TestSimpleUsage.cpp +++ b/lanelet2/lanelet2_io/test/TestSimpleUsage.cpp @@ -1,6 +1,6 @@ +#include "TestSetup.h" #include "gtest/gtest.h" - -#include "Io.h" +#include "lanelet2_io/Io.h" TEST(lanelet2_io, exampleUsage) { // NOLINT using namespace lanelet; @@ -8,7 +8,7 @@ TEST(lanelet2_io, exampleUsage) { // NOLINT std::string filenameIn = "../../lanelet2_maps/res/mapping_example.osm"; LaneletMapPtr laneletMap = lanelet::load(filenameIn, origin); - std::string filenameOut = std::string(std::tmpnam(nullptr)) + ".osm"; // NOLINT - lanelet::write(filenameOut, *laneletMap, origin); - LaneletMapPtr laneletMapAgain = lanelet::load(filenameOut, origin); + lanelet::test_setup::Tempfile file("file.osm"); + lanelet::write(file.get().string(), *laneletMap, origin); + LaneletMapPtr laneletMapAgain = lanelet::load(file.get().string(), origin); } diff --git a/lanelet2/lanelet2_maps/CHANGELOG.rst b/lanelet2/lanelet2_maps/CHANGELOG.rst new file mode 100644 index 00000000000..49a9132dca6 --- /dev/null +++ b/lanelet2/lanelet2_maps/CHANGELOG.rst @@ -0,0 +1,31 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_maps +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Updating package.xml files to format 3. +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Improve presets and lanelet visualization +* added swedish traffic signs +* Clean up JOSM style sheet +* Add US traffic signs to JOSM stylesheet and docu +* Improve documentation on how traffic lights/signs should be mapped +* Add documentation +* Fix example map +* Initial commit +* Contributors: Fabian Poggenhans, Lingguang Wang, Maximilian Naumann diff --git a/lanelet2/lanelet2_maps/CMakeLists.txt b/lanelet2/lanelet2_maps/CMakeLists.txt index e6c1a11ca9c..47ceb689f0f 100644 --- a/lanelet2/lanelet2_maps/CMakeLists.txt +++ b/lanelet2/lanelet2_maps/CMakeLists.txt @@ -1,34 +1,34 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_maps) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -file(GLOB PROJECT_PYTHON_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "python_api/*.cpp") +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") if (PROJECT_PYTHON_SOURCE_FILES_SRC) # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project mrt_add_python_api( ${PROJECT_NAME} @@ -37,56 +37,27 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC) endif() ############################ -## read source code files ## +## Read source code files ## ############################ -file(GLOB_RECURSE PROJECT_HEADER_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "include/*.h" "include/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.h" "src/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.cpp") - -if (PROJECT_SOURCE_FILES_SRC) - set(LIBRARY_NAME ${PROJECT_NAME}) -endif() - -################################### -## catkin specific configuration ## -################################### -# The catkin_package macro generates cmake config files for your package -# Declare things to be passed to dependent projects -# INCLUDE_DIRS: uncomment this if you package contains header files -# LIBRARIES: libraries you create in this project that dependent projects also need -# CATKIN_DEPENDS: catkin_packages dependent projects also need -# DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include ${mrt_EXPORT_INCLUDE_DIRS} - LIBRARIES ${LIBRARY_NAME} ${mrt_EXPORT_LIBRARIES} - CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} - ) +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") ########### ## Build ## ########### -# Add include and library directories -include_directories( - include/${PROJECT_NAME} - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - # Declare a cpp library mrt_add_library(${PROJECT_NAME} - INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data josm) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_maps/README.md b/lanelet2/lanelet2_maps/README.md index ff1318217ac..dd5de2ef593 100644 --- a/lanelet2/lanelet2_maps/README.md +++ b/lanelet2/lanelet2_maps/README.md @@ -29,9 +29,13 @@ LineStrings are transformed to OSM *Ways*. Polygons are OSM *Ways* as well but are identified by a tag *area=yes*. Start point = end point is not sufficient and also not necessary. ### Lanelets -Lanelets are represented as OSM *relations* with a tag `type=lanelet`. The right bound is a relation with role `right`, the left bound is a role with role `left`, the centerline (if present) is a relation with role `centerline` and all regulatory elements are relations with the role `regulatory_element`. +Lanelets are represented as OSM *relations* with a tag `type=lanelet`. +- The right bound is a relation member of type *way* with role `right` +- The left bound is a relation member of type *way* with role `left` +- The centerline (if present) is a relation member of type *way* with role `centerline` +- All regulatory elements are relation members of type *relation* with the role `regulatory_element` -If there are more relations than the mentioned ones, Lanelet2 will raise an error. +If there are more members to the lanelet relation than the mentioned ones, Lanelet2 will raise an error. ### Areas Areas are represented as OSM *relations* by making use of the *multipolygon* representation. They have a tag `type=multipolygon`. The outer bound is an ordered list of relations with the role `outer`, the inner bounds are an ordered list of relations with the role `inner`. Lanelet2 parses the inner bounds in this order and starts a new hole whenever the last point of one linestring matches the first one. diff --git a/lanelet2/lanelet2_maps/package.xml b/lanelet2/lanelet2_maps/package.xml index 9beae7a0402..feb36d92897 100644 --- a/lanelet2/lanelet2_maps/package.xml +++ b/lanelet2/lanelet2_maps/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_maps - 0.9.0 + 1.1.1 Example maps in the lanelet2-format BSD @@ -9,7 +10,13 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules lanelet2_core + + catkin + ament_cmake + diff --git a/lanelet2/lanelet2_matching/CMakeLists.txt b/lanelet2/lanelet2_matching/CMakeLists.txt new file mode 100644 index 00000000000..54c5dceec91 --- /dev/null +++ b/lanelet2/lanelet2_matching/CMakeLists.txt @@ -0,0 +1,69 @@ +set(MRT_PKG_VERSION 4.0.0) +# Modify only if you know what you are doing! +cmake_minimum_required(VERSION 3.5.1) +project(lanelet2_matching) + +################### +## Find packages ## +################### +find_package(mrt_cmake_modules REQUIRED) +include(UseMrtStdCompilerFlags) +include(GatherDeps) + +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() + +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) + +mrt_parse_package_xml() + +######################## +## Add python modules ## +######################## +# This adds a python module if located under src/{PROJECT_NAME) +mrt_python_module_setup() + +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") +if (PROJECT_PYTHON_SOURCE_FILES_SRC) + # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project + mrt_add_python_api( ${PROJECT_NAME} + FILES ${PROJECT_PYTHON_SOURCE_FILES_SRC} + ) +endif() + +############################ +## Read source code files ## +############################ +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") + +########### +## Build ## +########### +# Declare a cpp library +mrt_add_library(${PROJECT_NAME} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + SOURCES ${PROJECT_SOURCE_FILES_SRC} + ) + +############# +## Install ## +############# +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) + +############# +## Testing ## +############# +# Add test targets for cpp and python tests +if (CATKIN_ENABLE_TESTING) + mrt_add_tests(test) + mrt_add_nosetests(test) +endif() diff --git a/lanelet2/lanelet2_matching/README.md b/lanelet2/lanelet2_matching/README.md new file mode 100644 index 00000000000..d26a87ebf45 --- /dev/null +++ b/lanelet2/lanelet2_matching/README.md @@ -0,0 +1,57 @@ +# Lanelet2 Matching Module + +This module provides functions to determine in which lanelet an object is/could be currently located. + +## Matching functions + +* **Deterministic matching**: Find all lanelets to which an object has less than a certain Euclidean distance. + * as lanelets have an orientation, every lanelet is considered twice: regular and inverted, but with the same distance +* **Probabilistic matching**: Compute the squared Mahalanobis distance of the object pose to the lanelet to reason about the probability of that match, as suggested by Petrich et al. ([DOI:0.1109/ITSC.2013.6728549](https://doi.org/10.1109/ITSC.2013.6728549)) + * this distance includes the orientation, thus every lanelet is considered twice: regular and inverted, but with different distances +* **Accounting for traffic rules**: In case you expect traffic rule compliant behavior, you can remove non compliant matches by providing a traffic rules element for the participant you were matching (such as pedestrian lanelets for vehicles or inverted one way lanelets, which means driving in the wrong direction). + +## Usage + +### C++ + +```cpp +#include + +// create objects to match +lanelet::matching::Object2d obj; // deterministic +lanelet::matching::ObjectWithCovariance2d obj2; // considering uncertainty + +// retrieve lanelet matches from map +auto detMatches = getDeterministicMatches(laneletMap, obj, 4.); // max distance = 4m +auto probMatches = getProbabilisticMatches(laneletMap, obj2, 4.); // max distance = 4m + +// remove non-compliant matches (such as driving in the wrong direction) +auto compliantDetMatches = removeNonRuleCompliantMatches(detMatches, trafficRulesPtr); +auto compliantProbMatches = removeNonRuleCompliantMatches(probMatches, trafficRulesPtr); +``` + +have a look at the [C++ unittests](test/lanelet2_matching.cpp) for more examples + +### Python + +```python +import lanelet2 +# Note: in the standalone version of lanelet2_matching, the python module was named +# "lanelet2_matching". Now it is a submodule of lanelet2: "lanelet2.matching" + +# create objects to match +obj = lanelet2.matching.Object2d() + +# retrieve lanelet matches from map +matches = lanelet2.matching.getDeterministicMatches(lanelet_map, obj, 4.) # max distance = 4m + +# remove non-compliant matches (such as driving in the wrong direction) +compliant_matches = lanelet2.matching.removeNonRuleCompliantMatches(matches, traffic_rules) + +``` + +have a look at the [python unittests](../lanelet2_python/test/test_lanelet2_matching.py) for more examples, also supports uncertainty + + +## License +This package is distributed under the 3-Clause BSD License, see [LICENSE](LICENSE). diff --git a/lanelet2/lanelet2_matching/custom.cmake b/lanelet2/lanelet2_matching/custom.cmake new file mode 100644 index 00000000000..4d99855002a --- /dev/null +++ b/lanelet2/lanelet2_matching/custom.cmake @@ -0,0 +1 @@ +add_definitions(-DPKG_DIR="${CMAKE_CURRENT_LIST_DIR}") diff --git a/lanelet2/lanelet2_matching/include/lanelet2_matching/Exceptions.h b/lanelet2/lanelet2_matching/include/lanelet2_matching/Exceptions.h new file mode 100644 index 00000000000..56ac75a311a --- /dev/null +++ b/lanelet2/lanelet2_matching/include/lanelet2_matching/Exceptions.h @@ -0,0 +1,47 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#include + +#include + +namespace lanelet { + +/** + * @brief Thrown when matching is not possible. + */ +class MatchingError : public LaneletError { + using LaneletError::LaneletError; +}; + +} // namespace lanelet diff --git a/lanelet2/lanelet2_matching/include/lanelet2_matching/LaneletMatching.h b/lanelet2/lanelet2_matching/include/lanelet2_matching/LaneletMatching.h new file mode 100644 index 00000000000..08ca6f7aa89 --- /dev/null +++ b/lanelet2/lanelet2_matching/include/lanelet2_matching/LaneletMatching.h @@ -0,0 +1,98 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#include + +#include "Exceptions.h" +#include "Types.h" +#include "Utilities.h" + +namespace lanelet { +namespace matching { + +/** + * @brief get deterministic lanelet matches of an object with a maximum distance of maxDist, sorted ascending by + * distance + */ +std::vector getDeterministicMatches(LaneletMap& map, const Object2d& obj, double maxDist); +std::vector getDeterministicMatches(const LaneletMap& map, const Object2d& obj, double maxDist); + +/** + * @brief get probabilistic lanelet matches of an object with a maximum deterministic euler distance of maxDist, sorted + * ascending by Mahalanobis distance + * @throws MatchingError if the orientationCovarianceRadians or the determinant of the position covariance is zero + * + * for the distance computation see D. Petrich, T. Dang, D. Kasper, G. Breuel and C. Stiller, + * "Map-based long term motion prediction for vehicles in traffic environments," + * 16th International IEEE Conference on Intelligent Transportation Systems (ITSC 2013), + * The Hague, 2013, pp. 2166-2172. doi: 10.1109/ITSC.2013.6728549 + * https://ieeexplore.ieee.org/document/6728549 + */ +std::vector getProbabilisticMatches(LaneletMap& map, const ObjectWithCovariance2d& obj, + double maxDist); +std::vector getProbabilisticMatches(const LaneletMap& map, + const ObjectWithCovariance2d& obj, double maxDist); + +/** + * @brief Determine whether an object is within a maximum distance to any primitive of the layer + */ +template +bool isCloseTo(const LayerT& map, const Object2d& obj, double maxDist) { + auto closePrimitives = utils::findWithin(map, obj, maxDist); + return !closePrimitives.empty(); +} + +/** + * @brief Determine whether an object is (at least partially) within any primitive of the layer + */ +template +bool isWithin(const LayerT& map, const Object2d& obj) { + return isCloseTo(map, obj, 0.); +} + +/** + * @brief Remove non traffic rule compliant probabilistic lanelet matches + */ +template +MatchVectorT removeNonRuleCompliantMatches(const MatchVectorT& matches, + const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) { + MatchVectorT compliantMatches = matches; + compliantMatches.erase( + std::remove_if(compliantMatches.begin(), compliantMatches.end(), + [&trafficRulesPtr](auto& match) { return !trafficRulesPtr->canPass(match.lanelet); }), + compliantMatches.end()); + return compliantMatches; +} + +} // namespace matching +} // namespace lanelet diff --git a/lanelet2/lanelet2_matching/include/lanelet2_matching/Types.h b/lanelet2/lanelet2_matching/include/lanelet2_matching/Types.h new file mode 100644 index 00000000000..98810053fac --- /dev/null +++ b/lanelet2/lanelet2_matching/include/lanelet2_matching/Types.h @@ -0,0 +1,83 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#include +#include +#include + +#include +#include + +namespace lanelet { +namespace matching { + +using Pose2d = Eigen::Transform; //!< a 2d pose +using PositionCovariance2d = Eigen::Matrix; //!< a covariance of a 2d position +using Hull2d = BasicPolygon2d; //!< a hull of 2d-points, as + //! objects are usually closed rings, + //! closing the ring by + //! appending the first point + //! of the polygon as last + //! point again is suggested + +struct Object2d { + Id objectId{InvalId}; //!< Id as convenience for the user, not used by this library + Pose2d pose{Pose2d::Identity()}; //!< Pose of the object in map coordinates + Hull2d absoluteHull; //!< Hull of the object in map coordinates, position is used for matching when hull is empty +}; + +struct ObjectWithCovariance2d : Object2d { + PositionCovariance2d positionCovariance{PositionCovariance2d::Zero()}; + double vonMisesKappa{0.}; //!< kappa as defined in https://en.wikipedia.org/wiki/Von_Mises_distribution +}; + +struct LaneletMatch { + Lanelet lanelet; + double distance{0.}; //!< euclidean distance to lanelet +}; + +struct ConstLaneletMatch { + ConstLanelet lanelet; + double distance{0.}; //!< euclidean distance to lanelet +}; + +struct LaneletMatchProbabilistic : LaneletMatch { + double mahalanobisDistSq{0.}; //!< squared Mahalanobis distance to closest point on centerline of lanelet +}; + +struct ConstLaneletMatchProbabilistic : ConstLaneletMatch { + double mahalanobisDistSq{0.}; //!< squared Mahalanobis distance to closest point on centerline of lanelet +}; + +} // namespace matching +} // namespace lanelet diff --git a/lanelet2/lanelet2_matching/include/lanelet2_matching/Utilities.h b/lanelet2/lanelet2_matching/include/lanelet2_matching/Utilities.h new file mode 100644 index 00000000000..fb82595f10f --- /dev/null +++ b/lanelet2/lanelet2_matching/include/lanelet2_matching/Utilities.h @@ -0,0 +1,72 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#include +#include + +#include "Exceptions.h" +#include "Types.h" + +namespace lanelet { +namespace matching { +namespace utils { + +/** + * @brief Find all primitives as close as or closer than maxDist to an object + */ +template +auto findWithin(LayerT& map, const Object2d& obj, double maxDist) + -> std::vector>> { + if (obj.absoluteHull.empty()) { + return lanelet::geometry::findWithin2d(map, lanelet::BasicPoint2d{obj.pose.translation()}, maxDist); + } + return lanelet::geometry::findWithin2d(map, lanelet::BasicPolygon2d{obj.absoluteHull}, maxDist); +} + +/** + * @brief Compute squared mahalanobis distance based on pose and covariance, hull is not used + * @throws MatchingError if the orientationCovarianceRadians or the determinant of the position covariance is zero + * + * see D. Petrich, T. Dang, D. Kasper, G. Breuel and C. Stiller, + * "Map-based long term motion prediction for vehicles in traffic environments," + * 16th International IEEE Conference on Intelligent Transportation Systems (ITSC 2013), + * The Hague, 2013, pp. 2166-2172. doi: 10.1109/ITSC.2013.6728549 + * https://ieeexplore.ieee.org/document/6728549 + * + * uses approximation orientationCovariance = 1./obj.vonMisesKappa + */ +double getMahalanobisDistSq(const ConstLanelet& lanelet, const ObjectWithCovariance2d& obj); + +} // namespace utils +} // namespace matching +} // namespace lanelet diff --git a/mrt_cmake_modules/src/mrt_cmake_modules/__init__.py b/lanelet2/lanelet2_matching/include/lanelet2_matching/internal/.gitignore similarity index 100% rename from mrt_cmake_modules/src/mrt_cmake_modules/__init__.py rename to lanelet2/lanelet2_matching/include/lanelet2_matching/internal/.gitignore diff --git a/lanelet2/lanelet2_matching/package.xml b/lanelet2/lanelet2_matching/package.xml new file mode 100644 index 00000000000..061f707a619 --- /dev/null +++ b/lanelet2/lanelet2_matching/package.xml @@ -0,0 +1,31 @@ + + + + lanelet2_matching + 1.1.1 + Library to match objects to lanelets + + BSD + Maximilian Naumann + Maximilian Naumann + https://github.com/fzi-forschungszentrum-informatik/lanelet2.git + + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules + gtest + + lanelet2_core + lanelet2_traffic_rules + + lanelet2_io + lanelet2_projection + lanelet2_maps + + + catkin + ament_cmake + + + diff --git a/lanelet2/lanelet2_matching/src/.gitignore b/lanelet2/lanelet2_matching/src/.gitignore new file mode 100644 index 00000000000..e69de29bb2d diff --git a/lanelet2/lanelet2_matching/src/LaneletMatching.cpp b/lanelet2/lanelet2_matching/src/LaneletMatching.cpp new file mode 100644 index 00000000000..d39b4c4241d --- /dev/null +++ b/lanelet2/lanelet2_matching/src/LaneletMatching.cpp @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "LaneletMatching.h" + +#include +#include + +#include "Utilities.h" + +namespace { +template +std::vector toMatchVector(std::vector> pairVec) { + std::vector matchVec; + matchVec.reserve(2 * pairVec.size()); + for (const auto& pair : pairVec) { + MatchT match; + match.distance = pair.first; + match.lanelet = pair.second; + matchVec.push_back(match); + match.lanelet = pair.second.invert(); + matchVec.push_back(match); + } + + // sort ascending by distance + std::sort(matchVec.begin(), matchVec.end(), + [](const auto& lhs, const auto& rhs) { return lhs.distance < rhs.distance; }); + + return matchVec; +} + +template +std::vector getProbabilisticMatchesImpl(const std::vector>& pairVec, + const lanelet::matching::ObjectWithCovariance2d& obj) { + std::vector matchVec; + matchVec.reserve(2 * pairVec.size()); + for (const auto& pair : pairVec) { + MatchT match; + match.distance = pair.first; + match.lanelet = pair.second; + match.mahalanobisDistSq = lanelet::matching::utils::getMahalanobisDistSq(match.lanelet, obj); + matchVec.push_back(match); + match.lanelet = pair.second.invert(); + match.mahalanobisDistSq = lanelet::matching::utils::getMahalanobisDistSq(match.lanelet, obj); + matchVec.push_back(match); + } + + // sort ascending by mahalanobisDistSq + std::sort(matchVec.begin(), matchVec.end(), + [](const auto& lhs, const auto& rhs) { return lhs.mahalanobisDistSq < rhs.mahalanobisDistSq; }); + + return matchVec; +} +} // namespace + +namespace lanelet { +namespace matching { + +std::vector getDeterministicMatches(LaneletMap& map, const Object2d& obj, double maxDist) { + return toMatchVector(utils::findWithin(map.laneletLayer, obj, maxDist)); +} + +std::vector getDeterministicMatches(const LaneletMap& map, const Object2d& obj, double maxDist) { + return toMatchVector(utils::findWithin(map.laneletLayer, obj, maxDist)); +} + +std::vector getProbabilisticMatches(LaneletMap& map, const ObjectWithCovariance2d& obj, + double maxDist) { + auto pairVec = utils::findWithin(map.laneletLayer, obj, maxDist); + return getProbabilisticMatchesImpl(pairVec, obj); +} + +std::vector getProbabilisticMatches(const LaneletMap& map, + const ObjectWithCovariance2d& obj, double maxDist) { + auto pairVec = utils::findWithin(map.laneletLayer, obj, maxDist); + return getProbabilisticMatchesImpl(pairVec, obj); +} + +} // namespace matching +} // namespace lanelet diff --git a/lanelet2/lanelet2_matching/src/Utilities.cpp b/lanelet2/lanelet2_matching/src/Utilities.cpp new file mode 100644 index 00000000000..6e615435032 --- /dev/null +++ b/lanelet2/lanelet2_matching/src/Utilities.cpp @@ -0,0 +1,103 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "Utilities.h" + +#include +#include + +#include + +namespace { + +// from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp +// Result is always positive; not similar to fmod() +double positiveFloatModulo(double x, double y) { + double fmod = std::fmod(x, y); + if (fmod > 0.) { + return fmod; + } + double fmodPositive = fmod + std::abs(y); + assert(fmodPositive > 0.); + return fmodPositive; +} + +// from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp +double normalizeAngleRadians(double x) { return positiveFloatModulo((x + M_PI), 2.0 * M_PI) - M_PI; } + +// from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp +double angleDifference(double targetAngle, double sourceAngle) { + double angleDiff = targetAngle - sourceAngle; + return normalizeAngleRadians(angleDiff); +} + +// from https://github.com/coincar-sim/util_eigen_geometry/blob/release/src/util_eigen_geometry.cpp +double yawFromIsometry2d(const Eigen::Isometry2d& pose) { + Eigen::Rotation2D rot; + rot.fromRotationMatrix(pose.linear()); + return rot.smallestAngle(); +} +} // namespace + +namespace lanelet { +namespace matching { +namespace utils { + +double getMahalanobisDistSq(const ConstLanelet& lanelet, const ObjectWithCovariance2d& obj) { + if (obj.positionCovariance.isZero()) { + throw MatchingError("Covariance must not be zero"); + } + if (fabs(obj.positionCovariance.determinant()) < 10e-9) { + throw MatchingError("Determinant must not be zero"); + } + auto centerline2d = lanelet::utils::to2D(lanelet.centerline()); + ArcCoordinates closestOnCenter = geometry::toArcCoordinates(centerline2d, obj.pose.translation()); + BasicPoint2d pAt = geometry::interpolatedPointAtDistance(centerline2d, closestOnCenter.length); + BasicPoint2d pBefore = + geometry::interpolatedPointAtDistance(centerline2d, std::max(closestOnCenter.length - 0.5, 0.)); + BasicPoint2d pAfter = geometry::interpolatedPointAtDistance(centerline2d, closestOnCenter.length + 0.5); + BasicPoint2d pDirection = pAfter - pBefore; + + double yawCenter = normalizeAngleRadians(std::atan2(pDirection.y(), pDirection.x())); + double yawObj = normalizeAngleRadians(yawFromIsometry2d(obj.pose)); + double yawDiff = angleDifference(yawCenter, yawObj); + + // using approximation orientationCovariance = 1./obj.vonMisesKappa + double mahaDistYawSq = (yawDiff * yawDiff) * (obj.vonMisesKappa * obj.vonMisesKappa); + + BasicPoint2d pDiff = obj.pose.translation() - pAt; + double mahaDistPosSq = pDiff.transpose() * obj.positionCovariance.inverse() * pDiff; + + return mahaDistYawSq + mahaDistPosSq; +} + +} // namespace utils +} // namespace matching +} // namespace lanelet diff --git a/lanelet2/lanelet2_matching/test/lanelet2_matching.cpp b/lanelet2/lanelet2_matching/test/lanelet2_matching.cpp new file mode 100644 index 00000000000..c47194e8efc --- /dev/null +++ b/lanelet2/lanelet2_matching/test/lanelet2_matching.cpp @@ -0,0 +1,260 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +#include "LaneletMatching.h" +#include "gtest/gtest.h" + +using namespace lanelet; + +namespace { +template +std::string toString(const MatchVectorT& matchVector) { + std::string out; + for (auto& match : matchVector) { + out += std::to_string(match.lanelet.id()); + if (match.lanelet.inverted()) { + out += "inv"; + } + out += " "; + } + return out; +} + +inline BasicPolygon2d absoluteHull(const BasicPolygon2d& relativeHull, const matching::Pose2d& pose) { + BasicPolygon2d hullPoints; + hullPoints.reserve(relativeHull.size()); + for (const auto& hullPt : relativeHull) { + hullPoints.push_back(pose * hullPt); + } + return hullPoints; +} +} // namespace + +class MatchingUtilitiesBase : public ::testing::Test { + using Attr = lanelet::AttributeName; + using AttrStr = lanelet::AttributeNamesString; + using Value = lanelet::AttributeValueString; + using Participants = lanelet::Participants; + /* looks like this: + * + * p1----ls11->---p2 p5----ls15->--p6 + * | | + * | | + * ls13 ls14 ... + * | | + * v v + * | | + * p3----ls12->---p4 p7----ls16->--p8 + * + * right: ll21 right: ll23 + * down: ll22 (pedestrian) + * + */ + public: + MatchingUtilitiesBase() { + map = std::make_shared(); + map->add(ll21); + map->add(ll22); + map->add(ll23); + } + LaneletMapPtr map; + + lanelet::Point3d p1{1, 0, 0}, p2{2, 2, 0}, p3{3, 0, 2}, p4{4, 2, 2}; + lanelet::Point3d p5{1, 100, 0}, p6{2, 102, 0}, p7{3, 100, 2}, p8{4, 102, 2}; + lanelet::LineString3d ls11{11, {p1, p2}}, ls12{12, {p3, p4}}, ls13{13, {p1, p3}}, ls14{14, {p2, p4}}; + lanelet::LineString3d ls15{15, {p5, p6}}, ls16{16, {p7, p8}}; + lanelet::AttributeMap vehicleAttr{{AttrStr::Subtype, Value::Road}, {AttrStr::Location, Value::Urban}}; + lanelet::AttributeMap pedestrianAttr{{AttrStr::Subtype, Value::Walkway}, {AttrStr::Location, Value::Urban}}; + lanelet::Lanelet ll21{21, ls11, ls12, vehicleAttr}, ll22{22, ls14, ls13, pedestrianAttr}; + lanelet::Lanelet ll23{23, ls15, ls16, vehicleAttr}; +}; + +TEST_F(MatchingUtilitiesBase, fixtureSetupSuccessful) { // NOLINT + EXPECT_TRUE(map->laneletLayer.exists(21)); + EXPECT_TRUE(map->laneletLayer.exists(22)); + EXPECT_TRUE(map->laneletLayer.exists(23)); + EXPECT_EQ(3ul, map->laneletLayer.size()); +} + +TEST_F(MatchingUtilitiesBase, absoluteHull) { // NOLINT + matching::Object2d obj; + + obj.pose.translation() = BasicPoint2d{10, 0}; //!< at point x=10 y=0 + obj.pose.linear() = Eigen::Rotation2D(-1.5 * M_PI).matrix(); //!< rotated by pi/2 (=-3pi/2) + + obj.absoluteHull = absoluteHull(matching::Hull2d{BasicPoint2d{-0.5, -1}, BasicPoint2d{2, 1}}, obj.pose); + + EXPECT_DOUBLE_EQ(10 + 1, obj.absoluteHull.at(0).x()); + EXPECT_DOUBLE_EQ(0 - 0.5, obj.absoluteHull.at(0).y()); + + EXPECT_DOUBLE_EQ(10 - 1, obj.absoluteHull.at(1).x()); + EXPECT_DOUBLE_EQ(0 + 2, obj.absoluteHull.at(1).y()); +} + +TEST_F(MatchingUtilitiesBase, findWithin) { // NOLINT + matching::Object2d obj; + obj.pose.translation() = lanelet::BasicPoint2d(2.05, 1.); + obj.pose.linear() = Eigen::Rotation2D(150. / 180. * M_PI).matrix(); + + EXPECT_EQ(2ul, matching::utils::findWithin(map->laneletLayer, obj, 0.1).size()); + + obj.absoluteHull = absoluteHull( + matching::Hull2d{BasicPoint2d{-1, -0.9}, BasicPoint2d{2, -0.9}, BasicPoint2d{2, 0.9}, BasicPoint2d{1, 0.9}}, + obj.pose); + + std::vector> laneletsWithDistance = + matching::utils::findWithin(map->laneletLayer, obj, 100); + + EXPECT_EQ(3ul, laneletsWithDistance.size()); +} + +TEST_F(MatchingUtilitiesBase, getMahalanobisDistSq) { // NOLINT + matching::ObjectWithCovariance2d obj; + obj.pose.translation() = lanelet::BasicPoint2d(2.05, 1.); + obj.pose.linear() = Eigen::Rotation2D(1. / 180. * M_PI).matrix(); // one degree orientation + obj.absoluteHull = absoluteHull( + matching::Hull2d{BasicPoint2d{-1, -0.9}, BasicPoint2d{2, -0.9}, BasicPoint2d{2, 0.9}, BasicPoint2d{1, 0.9}}, + obj.pose); + + using namespace matching::utils; + obj.vonMisesKappa = 0.5; + EXPECT_THROW(getMahalanobisDistSq(map->laneletLayer.get(21), obj), MatchingError) // NOLINT + << "should throw on covariance = zero"; + + obj.positionCovariance = matching::PositionCovariance2d::Ones(); + EXPECT_THROW(getMahalanobisDistSq(map->laneletLayer.get(21), obj), MatchingError) // NOLINT + << "should throw on determinant = zero"; + + obj.positionCovariance = matching::PositionCovariance2d::Identity() * 2.; + obj.vonMisesKappa = 1. / (10. / 180. * M_PI); // covariance of 10 degrees + + double mahaDist21 = getMahalanobisDistSq(map->laneletLayer.get(21), obj); + EXPECT_NEAR(0.011, mahaDist21, 10e-2); + + double mahaDist21inv = getMahalanobisDistSq(map->laneletLayer.get(21).invert(), obj); + EXPECT_NEAR(320.411, mahaDist21inv, 10e-2); +} + +class MatchingBase : public MatchingUtilitiesBase { + public: + MatchingBase() { + obj.pose.translation() = lanelet::BasicPoint2d(1., 1.); + obj.pose.linear() = Eigen::Rotation2D(90.1 / 180. * M_PI).matrix(); + obj.absoluteHull = absoluteHull( + matching::Hull2d{BasicPoint2d{-1, -0.9}, BasicPoint2d{2, -0.9}, BasicPoint2d{2, 0.9}, BasicPoint2d{1, 0.9}}, + obj.pose); + obj.positionCovariance = matching::PositionCovariance2d::Identity() * 2.; + obj.vonMisesKappa = 1. / (10. / 180. * M_PI); // covariance of 10 degrees + } + matching::ObjectWithCovariance2d obj; +}; + +TEST_F(MatchingBase, deterministicNonConst) { // NOLINT + using namespace lanelet::matching; + auto matches = getDeterministicMatches(*map, obj, 4.); + for (size_t i = 1; i < matches.size(); i++) { + EXPECT_TRUE(matches.at(i).distance >= matches.at(i - 1).distance) + << "Not sorted: at i=" << i - 1 << " dist = " << matches.at(i - 1).distance << "at i=" << i + << " dist = " << matches.at(i).distance; + } + EXPECT_EQ(4ul, matches.size()); + EXPECT_NEAR(0., matches.at(0).distance, 0.1); +} + +TEST_F(MatchingBase, deterministicConst) { // NOLINT + using namespace lanelet::matching; + const LaneletMap& constMap = *map; + auto matches = getDeterministicMatches(constMap, obj, 4.); + EXPECT_EQ(4ul, matches.size()); +} + +TEST_F(MatchingBase, probabilisticNonConst) { // NOLINT + using namespace lanelet::matching; + auto matches = getProbabilisticMatches(*map, obj, 4.); + // NOLINTNEXTLINE(clang-analyzer-cplusplus.NewDelete) + for (size_t i = 1; i < matches.size(); i++) { + EXPECT_TRUE(matches.at(i).mahalanobisDistSq >= matches.at(i - 1).mahalanobisDistSq) << "Not sorted at i=" << i; + } + EXPECT_NEAR(0.0, matches.at(0).mahalanobisDistSq, 0.001); + EXPECT_EQ(22, matches.at(0).lanelet.id()); + EXPECT_FALSE(matches.at(0).lanelet.inverted()) << "best match must be non inverted 21"; + EXPECT_EQ(4ul, matches.size()); +} + +TEST_F(MatchingBase, probabilisticConst) { // NOLINT + using namespace lanelet::matching; + const LaneletMap& constMap = *map; + auto matches = getProbabilisticMatches(constMap, obj, 4.); + EXPECT_EQ(4ul, matches.size()); +} + +TEST_F(MatchingBase, isCloseTo) { // NOLINT + using namespace lanelet::matching; + + LaneletLayer emptyLayer; + EXPECT_TRUE(isCloseTo(map->laneletLayer, obj, 4.)); + EXPECT_FALSE(isCloseTo(emptyLayer, obj, 4.)); + + EXPECT_TRUE(isWithin(map->laneletLayer, obj)); + EXPECT_FALSE(isWithin(emptyLayer, obj)); + + Object2d objWithEmptyHull; + objWithEmptyHull.pose.translation() = obj.pose.translation(); + EXPECT_TRUE(matching::isCloseTo(map->laneletLayer, objWithEmptyHull, 1.)); +} + +TEST_F(MatchingBase, filterNonCompliantProbabilistic) { // NOLINT + using namespace lanelet::matching; + auto matches = getProbabilisticMatches(*map, obj, 4.); + EXPECT_EQ(4ul, matches.size()); + EXPECT_EQ("22 21inv 21 22inv ", toString(matches)); + + lanelet::traffic_rules::TrafficRulesPtr trafficRulesPtr = + lanelet::traffic_rules::TrafficRulesFactory::create(lanelet::Locations::Germany, lanelet::Participants::Vehicle); + auto compliantMatches = removeNonRuleCompliantMatches(matches, trafficRulesPtr); + EXPECT_EQ(1ul, compliantMatches.size()) << "should exclude pedestrian lanelets and inverted one-way lanelets"; + EXPECT_EQ("21 ", toString(compliantMatches)); +} + +TEST_F(MatchingBase, filterNonCompliantDeterminstic) { // NOLINT + using namespace lanelet::matching; + auto matches = getDeterministicMatches(*map, obj, 4.); + EXPECT_EQ(4ul, matches.size()); + + lanelet::traffic_rules::TrafficRulesPtr trafficRulesPtr = + lanelet::traffic_rules::TrafficRulesFactory::create(lanelet::Locations::Germany, lanelet::Participants::Vehicle); + auto compliantMatches = removeNonRuleCompliantMatches(matches, trafficRulesPtr); + EXPECT_EQ(1ul, compliantMatches.size()) << "filterNonCompliantProbabilistic for details"; +} diff --git a/lanelet2/lanelet2_matching/test/lanelet2_matching_integration.cpp b/lanelet2/lanelet2_matching/test/lanelet2_matching_integration.cpp new file mode 100644 index 00000000000..d5b5b3a28cf --- /dev/null +++ b/lanelet2/lanelet2_matching/test/lanelet2_matching_integration.cpp @@ -0,0 +1,169 @@ +/* + * Copyright (c) 2019 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +#include "LaneletMatching.h" +#include "gtest/gtest.h" + +using namespace lanelet; + +namespace { +template +std::string toString(const MatchVectorT& matchVector) { + std::string out; + for (auto& match : matchVector) { + out += std::to_string(match.lanelet.id()); + if (match.lanelet.inverted()) { + out += "inv"; + } + out += " "; + } + return out; +} + +inline BasicPolygon2d absoluteHull(const BasicPolygon2d& relativeHull, const matching::Pose2d& pose) { + BasicPolygon2d hullPoints; + hullPoints.reserve(relativeHull.size()); + for (const auto& hullPt : relativeHull) { + hullPoints.push_back(pose * hullPt); + } + return hullPoints; +} +} // namespace + +class MatchingIntegrationTest : public ::testing::Test { + public: + MatchingIntegrationTest() { + map = load(exampleMapPath, projector); + + obj.pose.translation() = map->pointLayer.get(41656).basicPoint2d(); + obj.pose.linear() = Eigen::Rotation2D(150. / 180. * M_PI).matrix(); + obj.absoluteHull = absoluteHull( + matching::Hull2d{BasicPoint2d{-1, -0.9}, BasicPoint2d{2, -0.9}, BasicPoint2d{2, 0.9}, BasicPoint2d{1, 0.9}}, + obj.pose); + obj.positionCovariance = matching::PositionCovariance2d::Identity() * 2.; + obj.vonMisesKappa = 1. / (10. / 180. * M_PI); // covariance of 10 degrees + } + matching::ObjectWithCovariance2d obj; + std::string exampleMapPath = std::string(PKG_DIR) + "/test/mapping_example.osm"; + projection::UtmProjector projector{Origin({49, 8.4})}; + LaneletMapPtr map; +}; + +TEST_F(MatchingIntegrationTest, fixtureSetupSuccessful) { // NOLINT + EXPECT_TRUE(map->laneletLayer.exists(42440)); +} + +TEST_F(MatchingIntegrationTest, deterministicNonConst) { // NOLINT + using namespace lanelet::matching; + auto matches = getDeterministicMatches(*map, obj, 4.); + for (size_t i = 1; i < matches.size(); i++) { + EXPECT_TRUE(matches.at(i).distance >= matches.at(i - 1).distance) + << "Not sorted: at i=" << i - 1 << " dist = " << matches.at(i - 1).distance << "at i=" << i + << " dist = " << matches.at(i).distance; + } + EXPECT_EQ(14ul, matches.size()); + EXPECT_NEAR(0.69, matches.at(8).distance, 0.1); + EXPECT_EQ(45330, matches.at(8).lanelet.id()); + EXPECT_NEAR(0.69, matches.at(9).distance, 0.1); + EXPECT_EQ(45330, matches.at(9).lanelet.id()); +} + +TEST_F(MatchingIntegrationTest, deterministicConst) { // NOLINT + using namespace lanelet::matching; + const LaneletMap& constMap = *map; + auto matches = getDeterministicMatches(constMap, obj, 4.); + EXPECT_EQ(14ul, matches.size()); +} + +TEST_F(MatchingIntegrationTest, probabilisticNonConst) { // NOLINT + using namespace lanelet::matching; + auto matches = getProbabilisticMatches(*map, obj, 4.); + // NOLINTNEXTLINE(clang-analyzer-cplusplus.NewDelete) + for (size_t i = 1; i < matches.size(); i++) { + EXPECT_TRUE(matches.at(i).mahalanobisDistSq >= matches.at(i - 1).mahalanobisDistSq) << "Not sorted at i=" << i; + } + EXPECT_NEAR(0.288177, matches.at(0).mahalanobisDistSq, 0.001); + EXPECT_EQ(45334, matches.at(0).lanelet.id()); + EXPECT_FALSE(matches.at(0).lanelet.inverted()) << "best match must be non inverted 45334"; + EXPECT_EQ(14ul, matches.size()); +} + +TEST_F(MatchingIntegrationTest, probabilisticConst) { // NOLINT + using namespace lanelet::matching; + const LaneletMap& constMap = *map; + auto matches = getProbabilisticMatches(constMap, obj, 4.); + EXPECT_EQ(14ul, matches.size()); +} + +TEST_F(MatchingIntegrationTest, isCloseTo) { // NOLINT + using namespace lanelet::matching; + + LaneletLayer emptyLayer; + EXPECT_TRUE(isCloseTo(map->laneletLayer, obj, 4.)); + EXPECT_FALSE(isCloseTo(emptyLayer, obj, 4.)); + + EXPECT_TRUE(isWithin(map->laneletLayer, obj)); + EXPECT_FALSE(isWithin(emptyLayer, obj)); + + Object2d objWithEmptyHull; + objWithEmptyHull.pose.translation() = map->pointLayer.get(41656).basicPoint2d(); + EXPECT_TRUE(matching::isCloseTo(map->laneletLayer, objWithEmptyHull, 1.)); +} + +TEST_F(MatchingIntegrationTest, filterNonCompliantProbabilistic) { // NOLINT + using namespace lanelet::matching; + auto matches = getProbabilisticMatches(*map, obj, 4.); + EXPECT_EQ(14ul, matches.size()); + EXPECT_EQ("45334 45356inv 45358inv 45328inv 45332 45344 45330 45344inv 45330inv 45332inv 45328 45356 45358 45334inv ", + toString(matches)); + + lanelet::traffic_rules::TrafficRulesPtr trafficRulesPtr = + lanelet::traffic_rules::TrafficRulesFactory::create(lanelet::Locations::Germany, lanelet::Participants::Vehicle); + auto compliantMatches = removeNonRuleCompliantMatches(matches, trafficRulesPtr); + EXPECT_EQ(8ul, compliantMatches.size()) + << "see list below: should exclude zebra crossing (pedestrian only) and inverted one way lanelets"; + EXPECT_EQ("45334 45356inv 45358inv 45332 45330 45328 45356 45358 ", toString(compliantMatches)); +} + +TEST_F(MatchingIntegrationTest, filterNonCompliantDeterminstic) { // NOLINT + using namespace lanelet::matching; + auto matches = getDeterministicMatches(*map, obj, 4.); + EXPECT_EQ(14ul, matches.size()); + + lanelet::traffic_rules::TrafficRulesPtr trafficRulesPtr = + lanelet::traffic_rules::TrafficRulesFactory::create(lanelet::Locations::Germany, lanelet::Participants::Vehicle); + auto compliantMatches = removeNonRuleCompliantMatches(matches, trafficRulesPtr); + EXPECT_EQ(8ul, compliantMatches.size()) << "filterNonCompliantProbabilistic for details"; +} diff --git a/lanelet2/lanelet2_matching/test/mapping_example.osm b/lanelet2/lanelet2_matching/test/mapping_example.osm new file mode 100644 index 00000000000..f996ef62c95 --- /dev/null +++ b/lanelet2/lanelet2_matching/test/mapping_example.osm @@ -0,0 +1,14535 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lanelet2/lanelet2_projection/CHANGELOG.rst b/lanelet2/lanelet2_projection/CHANGELOG.rst new file mode 100644 index 00000000000..0bbd8b3265f --- /dev/null +++ b/lanelet2/lanelet2_projection/CHANGELOG.rst @@ -0,0 +1,27 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_projection +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Making all includes in lanelet2_projection consistent. +* Updating package.xml files to format 3. +* Apply clang-tidy 10 recommendations +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Improved readmes and corrected typos +* Initial commit +* Contributors: Fabian Poggenhans diff --git a/lanelet2/lanelet2_projection/CMakeLists.txt b/lanelet2/lanelet2_projection/CMakeLists.txt index 723d62d4073..648ff82a40f 100644 --- a/lanelet2/lanelet2_projection/CMakeLists.txt +++ b/lanelet2/lanelet2_projection/CMakeLists.txt @@ -1,34 +1,34 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_projection) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -file(GLOB PROJECT_PYTHON_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "python_api/*.cpp") +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") if (PROJECT_PYTHON_SOURCE_FILES_SRC) # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project mrt_add_python_api( ${PROJECT_NAME} @@ -37,56 +37,27 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC) endif() ############################ -## read source code files ## +## Read source code files ## ############################ -file(GLOB_RECURSE PROJECT_HEADER_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "include/*.h" "include/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.h" "src/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.cpp") - -if (PROJECT_SOURCE_FILES_SRC) - set(LIBRARY_NAME ${PROJECT_NAME}) -endif() - -################################### -## catkin specific configuration ## -################################### -# The catkin_package macro generates cmake config files for your package -# Declare things to be passed to dependent projects -# INCLUDE_DIRS: uncomment this if you package contains header files -# LIBRARIES: libraries you create in this project that dependent projects also need -# CATKIN_DEPENDS: catkin_packages dependent projects also need -# DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include ${mrt_EXPORT_INCLUDE_DIRS} - LIBRARIES ${LIBRARY_NAME} ${mrt_EXPORT_LIBRARIES} - CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} - ) +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") ########### ## Build ## ########### -# Add include and library directories -include_directories( - include/${PROJECT_NAME} - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - # Declare a cpp library mrt_add_library(${PROJECT_NAME} - INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_projection/package.xml b/lanelet2/lanelet2_projection/package.xml index 489d8fb3e08..8bbfc0e5e38 100644 --- a/lanelet2/lanelet2_projection/package.xml +++ b/lanelet2/lanelet2_projection/package.xml @@ -1,22 +1,28 @@ - + + lanelet2_projection - 0.9.0 + 1.1.1 Lanelet2 projection library for lat/lon to local x/y conversion BSD Jan-Hendrik Pauls + Maximilian Naumann + Fabian Poggenhans Jan-Hendrik Pauls https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest lanelet2_io geographiclib - + catkin + ament_cmake diff --git a/lanelet2/lanelet2_projection/src/UTM.cpp b/lanelet2/lanelet2_projection/src/UTM.cpp index e529353e836..a19079d39a8 100644 --- a/lanelet2/lanelet2_projection/src/UTM.cpp +++ b/lanelet2/lanelet2_projection/src/UTM.cpp @@ -1,4 +1,5 @@ -#include "UTM.h" +#include "lanelet2_projection/UTM.h" + #include namespace lanelet { @@ -6,7 +7,8 @@ namespace projection { UtmProjector::UtmProjector(Origin origin, const bool useOffset, const bool throwInPaddingArea) : Projector(origin), useOffset_{useOffset}, throwInPaddingArea_{throwInPaddingArea} { - double x, y; + double x = 0; + double y = 0; GeographicLib::UTMUPS::Forward(this->origin().position.lat, this->origin().position.lon, zone_, isInNorthernHemisphere_, x, y); if (useOffset_) { @@ -30,8 +32,9 @@ BasicPoint3d UtmProjector::forward(const GPSPoint& gps) const { throw ForwardProjectionError("You have left the UTM zone or changed the hemisphere!"); } // try to transfer to the desired zone - double xAfterTransfer, yAfterTransfer; - int zoneAfterTransfer; + double xAfterTransfer = 0; + double yAfterTransfer = 0; + int zoneAfterTransfer = 0; try { GeographicLib::UTMUPS::Transfer(zone, northp, utm.x(), utm.y(), zone_, isInNorthernHemisphere_, xAfterTransfer, yAfterTransfer, zoneAfterTransfer); diff --git a/lanelet2/lanelet2_projection/test/test_Mercator.cpp b/lanelet2/lanelet2_projection/test/test_Mercator.cpp index 3105d9dbc03..ceafa3e579c 100644 --- a/lanelet2/lanelet2_projection/test/test_Mercator.cpp +++ b/lanelet2/lanelet2_projection/test/test_Mercator.cpp @@ -1,5 +1,6 @@ #include -#include "Mercator.h" + +#include "lanelet2_projection/Mercator.h" TEST(Mercator, origin) { // NOLINT lanelet::projection::Mercator mercatorProjection(lanelet::Origin{{45, 45, 0}}); diff --git a/lanelet2/lanelet2_projection/test/test_UTM.cpp b/lanelet2/lanelet2_projection/test/test_UTM.cpp index e3a62104ecd..435e879408e 100644 --- a/lanelet2/lanelet2_projection/test/test_UTM.cpp +++ b/lanelet2/lanelet2_projection/test/test_UTM.cpp @@ -1,5 +1,5 @@ -#include "UTM.h" #include "gtest/gtest.h" +#include "lanelet2_projection/UTM.h" using namespace lanelet; using UtmProjector = lanelet::projection::UtmProjector; diff --git a/lanelet2/lanelet2_python/CHANGELOG.rst b/lanelet2/lanelet2_python/CHANGELOG.rst new file mode 100644 index 00000000000..b4fc6ecf731 --- /dev/null +++ b/lanelet2/lanelet2_python/CHANGELOG.rst @@ -0,0 +1,55 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_python +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add parameter to left/right/adjacentLeft/adjacentRight so that they can be queried based on routing cost id +* Add experimental support for building with colcon on ros2 and ament_cmake +* Format files with clang-format 10 +* Add interpolatedPointAtDistance for BasicLineString +* Expose readwrite struct members to python +* Python functions for distance between CompoundLineStrings and LineStrings +* Python geometry interface for CompoundLineStrings +* Making all includes in lanelet2_python consistent. +* Add __hash__ for python bindings +* Add bindings for findWithin geometry function +* Updating package.xml files to format 3. +* Fix bindings for shortestPath function +* Fix memory leak in list->vector conversion + closes fzi-forschungszentrum-informatik/Lanelet2#111 +* SpeedLimitInformation now also offers m/s +* Fix const ptr issue in ConstLanelet.RightOfWay +* Contributors: Christian-Eike Framing, Fabian Poggenhans, Joshua Whitley, Maximilian Naumann + +1.0.1 (2020-03-24) +------------------ +* Fix python bindings for lanelet submap +* lanelet2_python: Register constructor for SpeedLimits +* Register more geometry functions (#96, #97) +* Register Lanelet::resetCache in python +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Apply clang-tidy fixes +* lanelet2_python: move converter header to internal include dir +* added equals for points +* Python: Fix registration of LaneletMap::add(Point3d) +* lanelet2_python: Fix wrongly registered RoutingCostDistance +* Fix default values for lane changes in RoutingGraph +* RoutingGraph and Route now use the new LaneletSubmap to store the lanelets they are using +* Add a new class 'LaneletSubmap' that only contains parts of the map and is faster to construct +* Routing graph and route object now support queries with a custom search function +* Extended and simplified the reachablePath/Set functions +* Refactored the internal representation of the route. Cleaned up headers that are only supposed to be used internally +* Offer reverse routing (possibleRoutesTowards), bindings, unittests +* Refactor FilteredGraphs and RelationTypes to use bitmasks +* Improve the distance2d and distance3d to support generic distance computations +* Initial commit +* Contributors: Fabian Poggenhans, Johannes Janosovits, Maximilian Naumann diff --git a/lanelet2/lanelet2_python/CMakeLists.txt b/lanelet2/lanelet2_python/CMakeLists.txt index c12a41f7d06..00e06d76a0e 100644 --- a/lanelet2/lanelet2_python/CMakeLists.txt +++ b/lanelet2/lanelet2_python/CMakeLists.txt @@ -1,33 +1,34 @@ -set(MRT_PKG_VERSION 2.2) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_python) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) + +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -file(GLOB PROJECT_PYTHON_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "python_api/*.cpp") +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") if (PROJECT_PYTHON_SOURCE_FILES_SRC) # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project mrt_add_python_api( lanelet2 @@ -36,55 +37,27 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC) endif() ############################ -## read source code files ## +## Read source code files ## ############################ -file(GLOB_RECURSE PROJECT_HEADER_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "include/*.h" "include/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.h" "src/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.cpp") - -if (PROJECT_SOURCE_FILES_SRC) - set(LIBRARY_NAME ${PROJECT_NAME}) -endif() - -################################### -## catkin specific configuration ## -################################### -# The catkin_package macro generates cmake config files for your package -# Declare things to be passed to dependent projects -# INCLUDE_DIRS: uncomment this if you package contains header files -# LIBRARIES: libraries you create in this project that dependent projects also need -# CATKIN_DEPENDS: catkin_packages dependent projects also need -# DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS ${mrt_EXPORT_INCLUDE_DIRS} - LIBRARIES ${LIBRARY_NAME} ${mrt_EXPORT_LIBRARIES} - CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} - ) +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") ########### ## Build ## ########### -# Add include and library directories -include_directories( - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - # Declare a cpp library mrt_add_library(${PROJECT_NAME} - INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_python/python_api/converter.h b/lanelet2/lanelet2_python/include/lanelet2_python/internal/converter.h similarity index 96% rename from lanelet2/lanelet2_python/python_api/converter.h rename to lanelet2/lanelet2_python/include/lanelet2_python/internal/converter.h index 6d3a18269b4..e2977b10f35 100644 --- a/lanelet2/lanelet2_python/python_api/converter.h +++ b/lanelet2/lanelet2_python/include/lanelet2_python/internal/converter.h @@ -1,6 +1,7 @@ // FROM // https://github.com/drodri/cppcon2016/blob/master/pythoncpp/boost/converter.h #include + #include #include #include @@ -65,7 +66,17 @@ struct IterableConverter { } /// @brief Check if PyObject is iterable. - static void* convertible(PyObject* object) { return PyObject_GetIter(object) != nullptr ? object : nullptr; } + static void* convertible(PyObject* object) { + auto* it = PyObject_GetIter(object); + if (it != nullptr) { + Py_DECREF(it); + return object; + } + if (PyErr_ExceptionMatches(PyExc_TypeError) != 0) { + PyErr_Clear(); + } + return nullptr; + } /// @brief Convert iterable PyObject to C++ container type. /// @@ -116,9 +127,6 @@ struct ToOptionalConverter { template static void construct(PyObject* object, boost::python::converter::rvalue_from_python_stage1_data* data) { namespace python = boost::python; - // Object is a borrowed reference, so create a handle indicting it is - // borrowed for proper reference counting. - python::handle<> handle(python::borrowed(object)); using StorageType = python::converter::rvalue_from_python_storage>; void* storage = reinterpret_cast(data)->storage.bytes; // NOLINT diff --git a/lanelet2/lanelet2_python/package.xml b/lanelet2/lanelet2_python/package.xml index 287e27a1b46..7349f3b80c7 100644 --- a/lanelet2/lanelet2_python/package.xml +++ b/lanelet2/lanelet2_python/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_python - 0.9.0 + 1.1.1 Python bindings for lanelet2 BSD @@ -9,15 +10,20 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest lanelet2_core lanelet2_io lanelet2_routing lanelet2_traffic_rules lanelet2_projection - libboost-python + lanelet2_matching + libboost-python-dev + catkin + ament_cmake diff --git a/lanelet2/lanelet2_python/python_api/core.cpp b/lanelet2/lanelet2_python/python_api/core.cpp index ad6d880d126..0a8fffc9e5b 100644 --- a/lanelet2/lanelet2_python/python_api/core.cpp +++ b/lanelet2/lanelet2_python/python_api/core.cpp @@ -1,15 +1,16 @@ -#include -#include -#include -#include - #include #include #include #include #include #include -#include "converter.h" + +#include +#include +#include +#include + +#include "lanelet2_python/internal/converter.h" using namespace boost::python; using namespace lanelet; @@ -214,6 +215,8 @@ class IsPrimitive : public def_visitor> { c.def(self == self); // NOLINT c.def(self != self); // NOLINT c.def(self_ns::str(self_ns::self)); + c.def( + "__hash__", +[](const PrimT& self) { return std::hash()(self); }); } }; @@ -224,13 +227,14 @@ class IsConstPrimitive : public def_visitor> { public: template void visit(ClassT& c) const { - namespace py = boost::python; c.add_property("id", &PrimT::id); const AttributeMap& (PrimT::*attr)() const = &PrimT::attributes; c.add_property("attributes", getRefFunc(attr)); c.def(self == self); // NOLINT c.def(self != self); // NOLINT c.def(self_ns::str(self_ns::self)); + c.def( + "__hash__", +[](const PrimT& self) { return std::hash()(self); }); } }; @@ -325,7 +329,7 @@ template using SetAttrSig = void (T::*)(const std::string&, const Attribute&); template -using GetAttrSig = const Attribute& (ConstPrimitive::*)(const std::string&)const; +using GetAttrSig = const Attribute& (ConstPrimitive::*)(const std::string&) const; template auto wrapLayer(const char* layerName) { @@ -338,7 +342,8 @@ auto wrapLayer(const char* layerName) { .def("get", get, "Gets a point with specified Id") .def("__iter__", iterator()) .def("__len__", &LayerT::size) - .def("__getitem__", +[](LayerT& self, Id idx) { return self.get(idx); }) + .def( + "__getitem__", +[](LayerT& self, Id idx) { return self.get(idx); }) .def("search", search, "Search in a search area") .def("nearest", nearest, "Get nearest n points") .def("uniqueId", &LayerT::uniqueId); @@ -359,8 +364,9 @@ std::vector> regelemAs(Lanelet& llt) { } template -std::vector> constRegelemAs(ConstLanelet& llt) { - return llt.regulatoryElementsAs(); +std::vector> constRegelemAs(ConstLanelet& llt) { + return utils::transform(llt.regulatoryElementsAs(), + [](auto& e) { return std::const_pointer_cast(e); }); } template @@ -410,12 +416,16 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def(self_ns::str(self_ns::self)); class_("BoundingBox2d", init("BoundingBox2d(minPoint, maxPoint")) - .add_property("min", +[](BoundingBox2d& self) { return self.min(); }) - .add_property("max", +[](BoundingBox2d& self) { return self.max(); }); + .add_property( + "min", +[](BoundingBox2d& self) { return self.min(); }) + .add_property( + "max", +[](BoundingBox2d& self) { return self.max(); }); class_("BoundingBox3d", init("BoundingBox3d(minPoint, maxPoint")) - .add_property("min", +[](BoundingBox3d& self) { return self.min(); }) - .add_property("max", +[](BoundingBox3d& self) { return self.max(); }); + .add_property( + "min", +[](BoundingBox3d& self) { return self.min(); }) + .add_property( + "max", +[](BoundingBox3d& self) { return self.max(); }); boost::python::to_python_converter(); @@ -459,6 +469,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT VectorToListConverter(); VectorToListConverter(); VectorToListConverter(); + VectorToListConverter(); VectorToListConverter>(); VectorToListConverter>(); VectorToListConverter>(); @@ -586,9 +597,9 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT return std::make_shared(GPSPoint({lat, lon, alt})); }, default_call_policies(), (arg("lat") = 0., arg("lon") = 0., arg("alt") = 0))) - .add_property("lat", &GPSPoint::lat) - .add_property("lon", &GPSPoint::lon) - .add_property("alt", &GPSPoint::ele); + .def_readwrite("lat", &GPSPoint::lat) + .def_readwrite("lon", &GPSPoint::lon) + .def_readwrite("alt", &GPSPoint::ele); class_("ConstLineString2d", "Immutable 2d lineString primitive", init("ConstLineString2d(ConstLineString3d)")) @@ -698,7 +709,9 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("invert", &ConstLanelet::invert, "Returns inverted lanelet (flipped left/right bound, etc") .def("inverted", &ConstLanelet::inverted, "Returns whether this lanelet has been inverted") .def("polygon2d", &ConstLanelet::polygon2d, "Outline of this lanelet as 2d polygon") - .def("polygon3d", &ConstLanelet::polygon3d, "Outline of this lanelet as 3d polygon"); + .def("polygon3d", &ConstLanelet::polygon3d, "Outline of this lanelet as 3d polygon") + .def("resetCache", &ConstLanelet::resetCache, + "Reset the cache. Forces update of the centerline if points have chagned"); auto left = static_cast(&Lanelet::leftBound); auto right = static_cast(&Lanelet::rightBound); @@ -759,18 +772,19 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("outerBoundPolygon", &ConstArea::outerBoundPolygon) .def("innerBoundPolygon", &ConstArea::innerBoundPolygons); - auto outerBound = static_cast(&Area::outerBound); - auto innerBounds = static_cast& (Area::*)()>(&Area::innerBounds); class_>("Area", "Represents an area, potentially with holes, in the map", boost::python::init( "Lanelet(id, outerBound, innerBounds, attributes")) .def(init("Lanelet(id, outerBound, innerBounds")) .def(init("Lanelet(id, outerBound")) .def(IsPrimitive()) - .add_property("outerBound", getRefFunc(outerBound), &Area::setOuterBound) - .add_property("innerBounds", getRefFunc(innerBounds), &Area::setInnerBounds) - .add_property("regulatoryElements", +[](Area& self) { return self.regulatoryElements(); }, - "Regulatory elements of the area") + .add_property( + "outerBound", +[](Area& self) { return self.outerBound(); }, &Area::setOuterBound) + .add_property( + "innerBounds", +[](Area& self) { return self.innerBounds(); }, &Area::setInnerBounds) + .add_property( + "regulatoryElements", +[](Area& self) { return self.regulatoryElements(); }, + "Regulatory elements of the area") .def("addRegulatoryElement", &Area::addRegulatoryElement) .def("removeRegulatoryElement", &Area::removeRegulatoryElement) .def("outerBoundPolygon", &Area::outerBoundPolygon) @@ -795,8 +809,10 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__init__", make_constructor(&TrafficLight::make, default_call_policies(), (arg("id"), arg("attributes"), arg("trafficLights"), arg("stopLine") = Optional()))) - .add_property("stopLine", +[](TrafficLight& self) { return self.stopLine(); }, &TrafficLight::setStopLine) - .add_property("trafficLights", +[](TrafficLight& self) { return self.trafficLights(); }) + .add_property( + "stopLine", +[](TrafficLight& self) { return self.stopLine(); }, &TrafficLight::setStopLine) + .add_property( + "trafficLights", +[](TrafficLight& self) { return self.trafficLights(); }) .def("addTrafficLight", &TrafficLight::addTrafficLight) .def("removeTrafficLight", &TrafficLight::removeTrafficLight); implicitly_convertible, RegulatoryElementPtr>(); @@ -812,13 +828,16 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__init__", make_constructor(&RightOfWay::make, default_call_policies(), (arg("id"), arg("attributes"), arg("rightOfWayLanelets"), arg("yieldLanelets"), arg("stopLine") = Optional{}))) - .add_property("stopLine", +[](RightOfWay& self) { return self.stopLine(); }, &RightOfWay::setStopLine) + .add_property( + "stopLine", +[](RightOfWay& self) { return self.stopLine(); }, &RightOfWay::setStopLine) .def("removeStopLine", &RightOfWay::removeStopLine) .def("getManeuver", &RightOfWay::getManeuver, "get maneuver for a lanelet") - .def("rightOfWayLanelets", +[](RightOfWay& self) { return self.rightOfWayLanelets(); }) + .def( + "rightOfWayLanelets", +[](RightOfWay& self) { return self.rightOfWayLanelets(); }) .def("addRightOfWayLanelet", &RightOfWay::addRightOfWayLanelet) .def("removeRightOfWayLanelet", &RightOfWay::removeRightOfWayLanelet) - .def("yieldLanelets", +[](RightOfWay& self) { return self.yieldLanelets(); }) + .def( + "yieldLanelets", +[](RightOfWay& self) { return self.yieldLanelets(); }) .def("addYieldLanelet", &RightOfWay::addYieldLanelet) .def("removeYieldLanelet", &RightOfWay::removeYieldLanelet); implicitly_convertible, RegulatoryElementPtr>(); @@ -828,9 +847,12 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__init__", make_constructor(&AllWayStop::make, default_call_policies(), (arg("id"), arg("attributes"), arg("lltsWithStop"), arg("signs") = Optional{}))) - .def("lanelets", +[](AllWayStop& self) { return self.lanelets(); }) - .def("stopLines", +[](AllWayStop& self) { return self.stopLines(); }) - .def("trafficSigns", +[](AllWayStop& self) { return self.trafficSigns(); }) + .def( + "lanelets", +[](AllWayStop& self) { return self.lanelets(); }) + .def( + "stopLines", +[](AllWayStop& self) { return self.stopLines(); }) + .def( + "trafficSigns", +[](AllWayStop& self) { return self.trafficSigns(); }) .def("addTrafficSign", &AllWayStop::addTrafficSign) .def("removeTrafficSign", &AllWayStop::removeTrafficSign) .def("addLanelet", &AllWayStop::addLanelet) @@ -839,13 +861,13 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT class_>("TrafficSignsWithType", no_init) .def("__init__", make_constructor(+[](LineStringsOrPolygons3d ls) { - return std::make_shared(TrafficSignsWithType{ls}); + return std::make_shared(TrafficSignsWithType{std::move(ls)}); })) .def("__init__", make_constructor(+[](LineStringsOrPolygons3d ls, std::string type) { - return std::make_shared(TrafficSignsWithType{ls, type}); + return std::make_shared(TrafficSignsWithType{std::move(ls), std::move(type)}); })) - .add_property("trafficSigns", &TrafficSignsWithType::trafficSigns) - .add_property("type", &TrafficSignsWithType::type); + .def_readwrite("trafficSigns", &TrafficSignsWithType::trafficSigns) + .def_readwrite("type", &TrafficSignsWithType::type); class_, bases>( "TrafficSign", "A traffic sign regulatory element", no_init) @@ -853,10 +875,14 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT (arg("id"), arg("attributes"), arg("trafficSigns"), arg("cancellingTrafficSigns") = TrafficSignsWithType{}, arg("refLines") = LineStrings3d(), arg("cancelLines") = LineStrings3d()))) - .def("trafficSigns", +[](TrafficSign& self) { return self.trafficSigns(); }) - .def("cancellingTrafficSigns", +[](TrafficSign& self) { return self.cancellingTrafficSigns(); }) - .def("refLines", +[](TrafficSign& self) { return self.refLines(); }) - .def("cancelLines", +[](TrafficSign& self) { return self.cancelLines(); }) + .def( + "trafficSigns", +[](TrafficSign& self) { return self.trafficSigns(); }) + .def( + "cancellingTrafficSigns", +[](TrafficSign& self) { return self.cancellingTrafficSigns(); }) + .def( + "refLines", +[](TrafficSign& self) { return self.refLines(); }) + .def( + "cancelLines", +[](TrafficSign& self) { return self.cancelLines(); }) .def("addTrafficSign", &TrafficSign::addTrafficSign) .def("removeTrafficSign", &TrafficSign::removeTrafficSign) .def("addRefLine", &TrafficSign::addRefLine) @@ -873,23 +899,31 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT implicitly_convertible, RegulatoryElementPtr>(); class_, bases>( // NOLINT - "SpeedLimit", "A speed limit regulatory element", no_init); + "SpeedLimit", "A speed limit regulatory element", no_init) + .def("__init__", make_constructor(&TrafficSign::make, default_call_policies(), + (arg("id"), arg("attributes"), arg("trafficSigns"), + arg("cancellingTrafficSigns") = TrafficSignsWithType{}, + arg("refLines") = LineStrings3d(), arg("cancelLines") = LineStrings3d()))); class_, boost::noncopyable>("PrimitiveLayerArea", no_init); // NOLINT class_, boost::noncopyable>("PrimitiveLayerLanelet", no_init); // NOLINT wrapLayer>>("AreaLayer") - .def("findUsages", +[](AreaLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }) - .def("findUsages", +[](AreaLayer& self, LineString3d& ls) { return self.findUsages(ls); }); + .def( + "findUsages", +[](AreaLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }) + .def( + "findUsages", +[](AreaLayer& self, ConstLineString3d& ls) { return self.findUsages(ls); }); wrapLayer>>("LaneletLayer") - .def("findUsages", +[](LaneletLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }) - .def("findUsages", +[](LaneletLayer& self, LineString3d& ls) { return self.findUsages(ls); }); - wrapLayer("PolygonLayer").def("findUsages", +[](PolygonLayer& self, Point3d& p) { - return self.findUsages(p); - }); - wrapLayer("LineStringLayer").def("findUsages", +[](LineStringLayer& self, Point3d& p) { - return self.findUsages(p); - }); + .def( + "findUsages", +[](LaneletLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }) + .def( + "findUsages", +[](LaneletLayer& self, ConstLineString3d& ls) { return self.findUsages(ls); }); + wrapLayer("PolygonLayer") + .def( + "findUsages", +[](PolygonLayer& self, ConstPoint3d& p) { return self.findUsages(p); }); + wrapLayer("LineStringLayer") + .def( + "findUsages", +[](LineStringLayer& self, ConstPoint3d& p) { return self.findUsages(p); }); wrapLayer("PointLayer"); wrapLayer("RegulatoryElementLayer"); @@ -903,7 +937,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT class_, LaneletMapPtr, boost::noncopyable>( "LaneletMap", "Object for managing a lanelet map", init<>("LaneletMap()")) - .def("add", selectSubmapAdd()) + .def("add", selectAdd()) .def("add", selectAdd()) .def("add", selectAdd()) .def("add", selectAdd()) @@ -913,7 +947,8 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT class_, LaneletSubmapPtr, boost::noncopyable>( "LaneletSubmap", "Object for managing parts of a lanelet map", init<>("LaneletSubmap()")) - .def("laneletMap", +[](LaneletSubmap& self) { return self.laneletMap(); }) + .def( + "laneletMap", +[](LaneletSubmap& self) { return LaneletMapPtr{self.laneletMap()}; }) .def("add", selectSubmapAdd()) .def("add", selectSubmapAdd()) .def("add", selectSubmapAdd()) diff --git a/lanelet2/lanelet2_python/python_api/geometry.cpp b/lanelet2/lanelet2_python/python_api/geometry.cpp index 181d1531d32..c66048af58f 100644 --- a/lanelet2/lanelet2_python/python_api/geometry.cpp +++ b/lanelet2/lanelet2_python/python_api/geometry.cpp @@ -1,16 +1,20 @@ #include #include #include +#include #include #include #include + #include #include -#include "converter.h" -BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d); -BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstLineStrings2d); -BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstHybridLineStrings2d); +#include "lanelet2_python/internal/converter.h" + +BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d) +BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstLineStrings2d) +BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstHybridLineStrings2d) +BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::CompoundLineStrings2d) using namespace boost::python; using namespace lanelet; @@ -27,6 +31,22 @@ auto wrapFindNearest() { converters::VectorToListConverter(); return def("findNearest", func); } +template +auto wrapFindWithin2d() { + using ResultT = std::vector>; + using Sig = ResultT (*)(PrimitiveLayer&, const GeometryT&, double); + auto func = static_cast(lanelet::geometry::findWithin2d); + return def("findWithin2d", func, (arg("layer"), arg("geometry"), arg("maxDist") = 0), + "returns all elements that are closer than maxDist to a geometry in 2d"); +} +template +auto wrapFindWithin3d() { + using ResultT = std::vector>; + using Sig = ResultT (*)(PrimitiveLayer&, const GeometryT&, double); + auto func = static_cast(lanelet::geometry::findWithin3d); + return def("findWithin3d", func, (arg("layer"), arg("geometry"), arg("maxDist") = 0), + "returns all elements that are closer than maxDist to a geometry in 3d"); +} std::vector toBasicVector(const BasicPoints2d& pts) { return utils::transform(pts, [](auto& p) { return BasicPoint2d(p.x(), p.y()); }); @@ -42,18 +62,20 @@ lanelet::BoundingBox3d boundingBox3dFor(const T& t) { return lanelet::geometry::boundingBox3d(t); } +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define TO2D_AS(X) \ if (extract(o).check()) { \ return object(to2D(extract(o)())); \ } +// NOLINTNEXTLINE(cppcoreguidelines-macro-usage) #define TO3D_AS(X) \ if (extract(o).check()) { \ return object(to3D(extract(o)())); \ } template -double distancePointToLss(const PtT& p, object lss) { +double distancePointToLss(const PtT& p, const object& lss) { auto distance = [](PtT p, auto range) { return boost::geometry::distance(p, utils::transform(range, [](auto& v) { return utils::toHybrid(v); })); }; @@ -65,27 +87,29 @@ double distancePointToLss(const PtT& p, object lss) { object to2D(object o) { using utils::to2D; - TO2D_AS(Point3d); - TO2D_AS(BasicPoint3d); - TO2D_AS(ConstPoint3d); - TO2D_AS(LineString3d); - TO2D_AS(LineString3d); - TO2D_AS(ConstLineString3d); - TO2D_AS(Polygon3d); - TO2D_AS(ConstPolygon3d); + TO2D_AS(Point3d) + TO2D_AS(BasicPoint3d) + TO2D_AS(ConstPoint3d) + TO2D_AS(LineString3d) + TO2D_AS(LineString3d) + TO2D_AS(ConstLineString3d) + TO2D_AS(Polygon3d) + TO2D_AS(ConstPolygon3d) + TO2D_AS(CompoundLineString3d) return o; } object to3D(object o) { using utils::to3D; - TO3D_AS(Point2d); - TO3D_AS(BasicPoint2d); - TO3D_AS(ConstPoint2d); - TO3D_AS(LineString2d); - TO3D_AS(LineString2d); - TO3D_AS(ConstLineString2d); - TO3D_AS(Polygon2d); - TO3D_AS(ConstPolygon2d); + TO3D_AS(Point2d) + TO3D_AS(BasicPoint2d) + TO3D_AS(ConstPoint2d) + TO3D_AS(LineString2d) + TO3D_AS(LineString2d) + TO3D_AS(ConstLineString2d) + TO3D_AS(Polygon2d) + TO3D_AS(ConstPolygon2d) + TO3D_AS(CompoundLineString2d) return o; } #undef TO2D_AS @@ -106,38 +130,77 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT // p2l def("distance", lg::distance); def("distance", lg::distance); + def("distance", lg::distance); + def("distance", lg::distance); def("distance", lg::distance); def("distance", lg::distance); + def("distance", lg::distance); + def("distance", lg::distance); def("distance", lg::distance); def("distance", lg::distance); + def("distance", lg::distance); + def("distance", lg::distance); // l2l - def("distance", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); }); + def( + "distance", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); }); def("distance", lg::distance); + def( + "distance", + +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); }); + def( + "distance", + +[](const ConstLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); }); + def( + "distance", + +[](const CompoundLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); }); // poly2p def("distance", lg::distance); - def("distance", +[](const ConstPolygon2d& p1, const BasicPoint2d& p2) { return lg::distance2d(p1, p2); }); - def("distance", + def( + "distance", +[](const ConstPolygon2d& p1, const BasicPoint2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const ConstPolygon2d& p1, const ConstPoint2d& p2) { return lg::distance2d(p1, p2.basicPoint()); }); // poly2ls - def("distance", +[](const ConstPolygon2d& p1, const ConstLineString2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const ConstPolygon2d& p1, const ConstLineString2d& p2) { return lg::distance2d(p1, p2); }); def("distance", lg::distance); + def( + "distance", +[](const ConstLineString2d& p2, const ConstPolygon2d& p1) { return lg::distance2d(p1, p2); }); + def("distance", lg::distance); + def( + "distance", +[](const ConstPolygon2d& p1, const CompoundLineString2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const CompoundLineString2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); // poly2poly def("distance", lg::distance); - def("distance", +[](const ConstPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); - def("distance", +[](const ConstHybridPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); - def("distance", +[](const CompoundPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); - def("distance", +[](const ConstPolygon2d& p1, const ConstHybridPolygon2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const ConstPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const ConstHybridPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const CompoundPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); }); + def( + "distance", +[](const ConstPolygon2d& p1, const ConstHybridPolygon2d& p2) { return lg::distance2d(p1, p2); }); // p2llt - def("distance", +[](const ConstLanelet& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); }); - def("distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); }); + def( + "distance", +[](const ConstLanelet& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); }); + def( + "distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); }); + def( + "distance", +[](const BasicPoint2d& p, const ConstLanelet& llt) { return lg::distance2d(llt, p); }); + def( + "distance", +[](const ConstLanelet& llt2, const ConstLanelet& llt1) { return lg::distance2d(llt1, llt2); }); // p2area - def("distance", +[](const ConstArea& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); }); + def( + "distance", +[](const ConstArea& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); }); + def( + "distance", +[](const BasicPoint2d& p, const ConstArea& llt) { return lg::distance2d(llt, p); }); // 3d // p2p @@ -149,8 +212,12 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT // p2l def("distance", lg::distance); def("distance", lg::distance); + def("distance", lg::distance); + def("distance", lg::distance); def("distance", lg::distance); def("distance", lg::distance); + def("distance", lg::distance); + def("distance", lg::distance); // p2lines def("distanceToLines", distancePointToLss); @@ -159,14 +226,41 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT def("distanceToLines", distancePointToLss); // l2l - def("distance", +[](const ConstLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); }); - def("distance", +[](const HybridLs3d& ls1, const HybridLs3d& ls2) { return lg::distance3d(ls1, ls2); }); + def( + "distance", +[](const ConstLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); }); + def( + "distance", +[](const HybridLs3d& ls1, const HybridLs3d& ls2) { return lg::distance3d(ls1, ls2); }); + def( + "distance", + +[](const CompoundLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); }); + def( + "distance", + +[](const ConstLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); }); + def( + "distance", + +[](const CompoundLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); }); // p2llt def("distance", lg::distance3d); + def("distance", lg::distance3d); // p2area - def("distance", +[](const ConstArea& llt, const BasicPoint3d& p) { return lg::distance3d(llt, p); }); + def( + "distance", +[](const ConstArea& llt, const BasicPoint3d& p) { return lg::distance3d(llt, p); }); + def( + "distance", +[](const BasicPoint3d& p, const ConstArea& llt) { return lg::distance3d(llt, p); }); + + // equals 2d + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); + + // equals 3d + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); + def("equals", boost::geometry::equals); def("boundingBox2d", boundingBox2dFor, "Get the surrounding axis-aligned bounding box in 2d"); def("boundingBox2d", boundingBox2dFor); @@ -177,6 +271,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT def("boundingBox2d", boundingBox2dFor); def("boundingBox2d", boundingBox2dFor); def("boundingBox2d", boundingBox2dFor); + def("boundingBox2d", boundingBox2dFor); def("boundingBox3d", boundingBox3dFor, "Get the surrounding axis-aligned bounding box in 3d"); def("boundingBox3d", boundingBox3dFor); @@ -187,25 +282,42 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT def("boundingBox3d", boundingBox3dFor); def("boundingBox3d", boundingBox3dFor); def("boundingBox3d", boundingBox3dFor); + def("boundingBox3d", boundingBox3dFor); + + // area + def("area", boost::geometry::area); + def("area", boost::geometry::area); class_("ArcCoordinates", "Coordinates along an arc", init<>()) - .add_property("length", &ArcCoordinates::length, "lenght along arc") - .add_property("distance", &ArcCoordinates::distance, "signed distance to arc (left is positive"); + .def_readwrite("length", &ArcCoordinates::length, "length along arc") + .def_readwrite("distance", &ArcCoordinates::distance, "signed distance to arc (left is positive"); def("toArcCoordinates", lg::toArcCoordinates, "Project a point into arc coordinates of the linestring"); + def("toArcCoordinates", lg::toArcCoordinates, + "Project a point into arc coordinates of the linestring"); def("length", lg::length); def("length", lg::length); + def("length", lg::length); + def("length", lg::length); + def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); + def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); + def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); + def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance); def("nearestPointAtDistance", lg::nearestPointAtDistance); def("nearestPointAtDistance", lg::nearestPointAtDistance); + def("nearestPointAtDistance", lg::nearestPointAtDistance); + def("nearestPointAtDistance", lg::nearestPointAtDistance); def("project", lg::project, "Project a point onto the linestring"); def("project", lg::project, "Project a point onto the linestring"); + def("project", lg::project, "Project a point onto the linestring"); + def("project", lg::project, "Project a point onto the linestring"); def("projectedPoint3d", lg::projectedPoint3d, "Returns the respective projected points of the closest distance of two " @@ -213,20 +325,32 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT def("projectedPoint3d", lg::projectedPoint3d, "Returns the respective projected points of the closest distance of two " "linestrings"); + def("projectedPoint3d", lg::projectedPoint3d, + "Returns the respective projected points of the closest distance of two " + "compound linestrings"); - def("intersects2d", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { - return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2)); - }); + def( + "intersects2d", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { + return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2)); + }); def("intersects2d", lg::intersects); - def("intersects2d", +[](const ConstPolygon2d& ls1, const ConstPolygon2d& ls2) { - return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2)); - }); + def( + "intersects2d", +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) { + return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2)); + }); + def( + "intersects2d", +[](const ConstPolygon2d& ls1, const ConstPolygon2d& ls2) { + return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2)); + }); def("intersects2d", lg::intersects); + def("intersects2d", lg::intersects); def("intersects2d", lg::intersects2d); def("intersects2d", lg::intersects2d); def("intersects3d", lg::intersects3d); + def("intersects3d", lg::intersects); def("intersects3d", lg::intersects3d); + def("intersects3d", lg::intersects3d); def("intersects3d", lg::intersects3d, "Approximates if two lanelets intersect (touch or area >0) in 3d", (arg("lanelet1"), arg("lanelet2"), arg("heightTolerance") = 3.)); @@ -241,9 +365,10 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT def("overlaps2d", lg::overlaps2d, "Returns true if shared area of two lanelets is >0"); def("overlaps3d", lg::overlaps3d, "Approximates if two lanelets overlap (area >0) in 3d", (arg("lanelet1"), arg("lanelet2"), arg("heightTolerance") = 3.)); - def("intersectCenterlines2d", +[](const ConstLanelet& ll1, const ConstLanelet& ll2) { - return toBasicVector(lg::intersectCenterlines2d(ll1, ll2)); - }); + def( + "intersectCenterlines2d", +[](const ConstLanelet& ll1, const ConstLanelet& ll2) { + return toBasicVector(lg::intersectCenterlines2d(ll1, ll2)); + }); def("leftOf", lg::leftOf, "Returns if first lanelet is directly left of second"); def("rightOf", lg::rightOf, "Returns if first lanelet is directly right of second"); @@ -255,4 +380,82 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT wrapFindNearest(); wrapFindNearest(); wrapFindNearest(); + + // find within, point layer + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + + // linestring layer + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + + // polygon layer + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + + // lanelet layer + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin3d(); + wrapFindWithin3d(); + + // area layer + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin2d(); + wrapFindWithin3d(); + wrapFindWithin3d(); } diff --git a/lanelet2/lanelet2_python/python_api/io.cpp b/lanelet2/lanelet2_python/python_api/io.cpp index b1736dc29dc..f1c2f033b0e 100644 --- a/lanelet2/lanelet2_python/python_api/io.cpp +++ b/lanelet2/lanelet2_python/python_api/io.cpp @@ -1,4 +1,5 @@ #include + #include namespace py = boost::python; @@ -42,7 +43,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT return std::make_shared(GPSPoint{lat, lon, alt}); }, default_call_policies(), (arg("lat") = 0., arg("lon") = 0., arg("lon") = 0))) - .add_property("position", &Origin::position); + .def_readwrite("position", &Origin::position); def("load", loadProjectorWrapper, (arg("filename"), arg("projector") = DefaultProjector())); def("load", loadWrapper, (arg("filename"), arg("origin"))); diff --git a/lanelet2/lanelet2_python/python_api/matching.cpp b/lanelet2/lanelet2_python/python_api/matching.cpp new file mode 100644 index 00000000000..4a451e752a5 --- /dev/null +++ b/lanelet2/lanelet2_python/python_api/matching.cpp @@ -0,0 +1,187 @@ +/* + * Copyright (c) 2020 + * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de) + * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu) + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "lanelet2_python/internal/converter.h" + +namespace { +using namespace boost::python; +using namespace lanelet; +using namespace lanelet::matching; + +std::string printPoseWrapper(const Pose2d& p) { + std::ostringstream oss; + oss << "x: " << p.translation().x() << "\ny: " << p.translation().y() + << "\nphi: " << Eigen::Rotation2Dd(p.rotation()).angle(); + return oss.str(); +} + +boost::shared_ptr createPose(const double x, const double y, const double phi) { + Eigen::Rotation2Dd rot(phi); + auto ptr = boost::make_shared(rot); + ptr->translation() = Eigen::Vector2d(x, y); + return ptr; +} + +Hull2d hullFromList(const boost::python::list& l) { + Hull2d poly{boost::python::stl_input_iterator(l), boost::python::stl_input_iterator()}; + return poly; +} + +void clearPythonErrors() { + PyObject *ptype, *pvalue, *ptraceback; // NOLINT + PyErr_Fetch(&ptype, &pvalue, &ptraceback); + // create boost python objects from objects behind pointer, such that python does garbage collection + if (!!ptype) { // NOLINT + object(handle<>(ptype)); + } + if (!!pvalue) { // NOLINT + object(handle<>(pvalue)); + } + if (!!ptraceback) { // NOLINT + object(handle<>(ptraceback)); + } +} + +template +std::vector removeNonRuleCompliantMatchesImpl(const boost::python::list& matchesList, + const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) { + // convert list to a vector of type T (throws a python exception if not possible) + std::vector matchesVector{boost::python::stl_input_iterator(matchesList), + boost::python::stl_input_iterator()}; + return removeNonRuleCompliantMatches>(matchesVector, trafficRulesPtr); +} + +object ruleCheckWrapper(const boost::python::list& matches, + const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) { + try { + return object(removeNonRuleCompliantMatchesImpl(matches, trafficRulesPtr)); + } catch (const boost::python::error_already_set&) { + clearPythonErrors(); + } + try { + return object(removeNonRuleCompliantMatchesImpl(matches, trafficRulesPtr)); + } catch (const boost::python::error_already_set&) { + clearPythonErrors(); + } + throw std::runtime_error("Matches must be a list of ConstLaneletMatch(es) or ConstLaneletMatch(es)Probabilistic"); +} + +boost::shared_ptr covFromVarXVarYCovXY(const double varX, const double varY, const double covXY) { + PositionCovariance2d cov; + cov << varX, covXY, covXY, varY; + return boost::make_shared(cov); +} + +std::vector (*funcWrapperDeterministic)(const LaneletMap&, const Object2d&, + const double) = &getDeterministicMatches; +std::vector (*funcWrapperProbabilistic)(const LaneletMap&, + const ObjectWithCovariance2d&, + const double) = &getProbabilisticMatches; +} // namespace +using ::converters::VectorToListConverter; + +BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT + auto core = import("lanelet2.core"); + + class_("Pose2d", "2D Isometric Transformation", no_init) + .def("__init__", + make_constructor(&createPose, default_call_policies(), (arg("x") = 0., arg("y") = 0, arg("yaw") = 0.))) + .def("__str__", &printPoseWrapper); + + class_("Object2d", "Object with pose, hull and ID", no_init) + .def("__init__", make_constructor( + +[](lanelet::Id objectId, const Pose2d& pose, const boost::python::list& absoluteHull) { + return boost::make_shared(Object2d{objectId, pose, hullFromList(absoluteHull)}); + }, + default_call_policies(), + (arg("objectId") = lanelet::InvalId, arg("pose") = Pose2d::Identity(), + arg("absoluteHull") = boost::python::list()))) + .add_property( + "absoluteHull", +[](Object2d& self) { return self.absoluteHull; }, &hullFromList, + "hull in absolute coordinates (not relative to the object's pose)") + .def_readwrite("pose", &Object2d::pose) + .def_readwrite("objectId", &Object2d::objectId); + + class_("PositionCovariance2d", init<>()) + .def("__init__", make_constructor(&covFromVarXVarYCovXY, default_call_policies(), + (arg("varX") = 0., arg("varY") = 0., arg("covXY") = 0.))) + .def(self_ns::str(self_ns::self)); + + class_>("ObjectWithCovariance2d", "Object with pose, covariance, hull and ID", + no_init) + .def("__init__", make_constructor( + +[](lanelet::Id objectId, const Pose2d& pose, const boost::python::list& absoluteHull, + const PositionCovariance2d& positionCovariance, double vonMisesKappa) { + ObjectWithCovariance2d obj; + obj.objectId = objectId; + obj.pose = pose; + obj.absoluteHull = hullFromList(absoluteHull); + obj.positionCovariance = positionCovariance; + obj.vonMisesKappa = vonMisesKappa; + return boost::make_shared(obj); + // initializer list construction of derived struct requires cpp17 + // return boost::make_shared(ObjectWithCovariance2d{ + // objectId, pose, hullFromList(absoluteHull), positionCovariance, vonMisesKappa}); + }, + default_call_policies(), + (arg("objectId") = lanelet::InvalId, arg("pose") = Pose2d::Identity(), + arg("absoluteHull") = boost::python::list(), + arg("positionCovariance") = PositionCovariance2d(), arg("vonMisesKappa") = 0.))) + .def_readwrite("vonMisesKappa", &ObjectWithCovariance2d::vonMisesKappa) + .def_readwrite("positionCovariance", &ObjectWithCovariance2d::positionCovariance); + + class_("ConstLaneletMatch", "Results from matching objects to lanelets", no_init) + .def_readwrite("lanelet", &ConstLaneletMatch::lanelet) + .def_readwrite("distance", &ConstLaneletMatch::distance); + + class_>("ConstLaneletMatchProbabilistic", + "Results from matching objects to lanelets", no_init) + .def_readwrite("mahalanobisDistSq", &ConstLaneletMatchProbabilistic::mahalanobisDistSq); + + VectorToListConverter>(); + VectorToListConverter>(); + + def("getDeterministicMatches", funcWrapperDeterministic); + def("getProbabilisticMatches", funcWrapperProbabilistic); + def("removeNonRuleCompliantMatches", ruleCheckWrapper); +} diff --git a/lanelet2/lanelet2_python/python_api/projection.cpp b/lanelet2/lanelet2_python/python_api/projection.cpp index dd1efe37406..84be0df0469 100644 --- a/lanelet2/lanelet2_python/python_api/projection.cpp +++ b/lanelet2/lanelet2_python/python_api/projection.cpp @@ -1,4 +1,5 @@ #include + #include using namespace lanelet; diff --git a/lanelet2/lanelet2_python/python_api/routing.cpp b/lanelet2/lanelet2_python/python_api/routing.cpp index 701811942c2..a4c39627342 100644 --- a/lanelet2/lanelet2_python/python_api/routing.cpp +++ b/lanelet2/lanelet2_python/python_api/routing.cpp @@ -1,7 +1,10 @@ #include #include + +#include #include -#include "converter.h" + +#include "lanelet2_python/internal/converter.h" using namespace boost::python; using namespace lanelet; @@ -40,6 +43,16 @@ routing::RoutingGraphPtr makeRoutingGraphSubmap(LaneletSubmap& laneletMap, return routing::RoutingGraph::build(laneletMap, trafficRules, routingCosts); } +template +object optionalToObject(const Optional& v) { + return v ? object(*v) : object(); +} + +template +Optional objectToOptional(const object& o) { + return o == object() ? Optional{} : Optional{extract(o)()}; +} + BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT auto trafficRules = import("lanelet2.traffic_rules"); using namespace lanelet::routing; @@ -80,12 +93,17 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT &RoutingGraph::possiblePaths); auto possPLen = static_cast( &RoutingGraph::possiblePaths); + auto possPParam = static_cast( + &RoutingGraph::possiblePaths); auto possPToCost = static_cast( &RoutingGraph::possiblePathsTowards); auto possPToLen = static_cast( &RoutingGraph::possiblePathsTowards); + auto possPToParam = + static_cast( + &RoutingGraph::possiblePathsTowards); class_("LaneletPath", "A set of consecutive lanelets connected in straight " @@ -94,34 +112,65 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__iter__", iterator()) .def("__len__", &LaneletPath::size) .def("__getitem__", wrappers::getItem, return_internal_reference<>()) - .def("getRemainingLane", +[](const LaneletPath& self, ConstLanelet llt) { return self.getRemainingLane(llt); }, - "get the sequence of remaining lanelets without a lane change") + .def( + "getRemainingLane", + +[](const LaneletPath& self, const ConstLanelet& llt) { return self.getRemainingLane(llt); }, + "get the sequence of remaining lanelets without a lane change") .def(self == self) // NOLINT .def(self != self); // NOLINT class_("LaneletVisitInformation", "Object passed as input for the forEachSuccessor function of the routing graph") - .add_property("lanelet", &LaneletVisitInformation::lanelet, "the currently visited lanelet") - .add_property("predecessor", &LaneletVisitInformation::predecessor, "the predecessor within the shortest path") - .add_property("length", &LaneletVisitInformation::length, - "The length of the shortest path to this lanelet (including lanelet") - .add_property("cost", &LaneletVisitInformation::cost, "The cost along the shortest path") - .add_property("numLaneChanges", &LaneletVisitInformation::numLaneChanges, - "The number of lane changes necessary along the shortest path"); + .def_readwrite("lanelet", &LaneletVisitInformation::lanelet, "the currently visited lanelet") + .def_readwrite("predecessor", &LaneletVisitInformation::predecessor, "the predecessor within the shortest path") + .def_readwrite("length", &LaneletVisitInformation::length, + "The length of the shortest path to this lanelet (including lanelet") + .def_readwrite("cost", &LaneletVisitInformation::cost, "The cost along the shortest path") + .def_readwrite("numLaneChanges", &LaneletVisitInformation::numLaneChanges, + "The number of lane changes necessary along the shortest path"); class_( "LaneletOrAreaVisitInformation", "Object passed as input for the forEachSuccessorIncludingAreas function of the routing graph") - .add_property("laneletOrArea", &LaneletOrAreaVisitInformation::laneletOrArea, - "the currently visited lanelet/area") - .add_property("predecessor", &LaneletOrAreaVisitInformation::predecessor, - "the predecessor within the shortest path") - .add_property("length", &LaneletOrAreaVisitInformation::length, - "The length of the shortest path to this lanelet (including lanelet") - .add_property("cost", &LaneletOrAreaVisitInformation::cost, "The cost along the shortest path") - .add_property("numLaneChanges", &LaneletOrAreaVisitInformation::numLaneChanges, - "The number of lane changes necessary along the shortest path"); + .def_readwrite("laneletOrArea", &LaneletOrAreaVisitInformation::laneletOrArea, + "the currently visited lanelet/area") + .def_readwrite("predecessor", &LaneletOrAreaVisitInformation::predecessor, + "the predecessor within the shortest path") + .def_readwrite("length", &LaneletOrAreaVisitInformation::length, + "The length of the shortest path to this lanelet (including lanelet") + .def_readwrite("cost", &LaneletOrAreaVisitInformation::cost, "The cost along the shortest path") + .def_readwrite("numLaneChanges", &LaneletOrAreaVisitInformation::numLaneChanges, + "The number of lane changes necessary along the shortest path"); + class_( + "PossiblePathsParams", "Parameters for configuring the behaviour of the possible path algorithms of RoutingGraph") + .def("__init__", + make_constructor( + +[](const object& costLimit, const object& elemLimit, RoutingCostId costId, bool includeLc, + bool includeShorter) { + return boost::make_shared(PossiblePathsParams{ + objectToOptional(costLimit), objectToOptional(elemLimit), costId, includeLc, + includeShorter}); + }, + default_call_policies{}, + (arg("routingCostLimit") = object(), arg("elementLimit") = object(), arg("routingCostId") = 0, + arg("includeLaneChanges") = false, arg("includeShorterPaths") = false))) + .add_property( + "routingCostLimit", +[](const PossiblePathsParams& self) { return optionalToObject(self.routingCostLimit); }, + +[](PossiblePathsParams& self, const object& value) { + self.routingCostLimit = objectToOptional(value); + }) + .add_property( + "elementLimit", +[](const PossiblePathsParams& self) { return optionalToObject(self.elementLimit); }, + +[](PossiblePathsParams& self, const object& value) { + self.elementLimit = objectToOptional(value); + }) + .def_readwrite("routingCostId", &PossiblePathsParams::routingCostId) + .def_readwrite("includeLaneChanges", &PossiblePathsParams::includeLaneChanges) + .def_readwrite("includeShorterPaths", &PossiblePathsParams::includeShorterPaths); + + auto lltAndLc = (arg("lanelet"), arg("withLaneChanges") = false); + auto lltAndRoutingCost = (arg("lanelet"), arg("routingCostId") = 0); class_( "RoutingGraph", "Main class of the routing module that holds routing information and can " @@ -137,37 +186,33 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Initialization from a submap") .def("getRoute", getRouteWrapper, "driving route from 'start' to 'end' lanelet", (arg("from"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true)) - .def("getRouteVia", getRouteWrapper, "driving route from 'start' to 'end' lanelet using the 'via' lanelets", + .def("getRouteVia", getRouteViaWrapper, "driving route from 'start' to 'end' lanelet using the 'via' lanelets", (arg("from"), arg("via"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true)) .def("shortestPath", &RoutingGraph::shortestPath, "shortest path between 'start' and 'end'", - (arg("from"), arg("to"), arg("routingCostId") = 0)) + (arg("from"), arg("to"), arg("routingCostId") = 0, arg("withLaneChanges") = true)) .def("shortestPathWithVia", &RoutingGraph::shortestPathVia, "shortest path between 'start' and 'end' using intermediate points", - (arg("start"), arg("via"), arg("end"), arg("routingCostId") = 0)) + (arg("start"), arg("via"), arg("end"), arg("routingCostId") = 0, arg("withLaneChanges") = true)) .def("routingRelation", &RoutingGraph::routingRelation, "relation between two lanelets excluding 'conflicting'", (arg("from"), arg("to"))) - .def("following", &RoutingGraph::following, "lanelets that can be reached from this lanelet", - (arg("lanelet"), arg("withLaneChanges") = false)) - .def("followingRelations", &RoutingGraph::followingRelations, "relations to following lanelets", - (arg("lanelet"), arg("withLaneChanges") = false)) - .def("previous", &RoutingGraph::previous, "previous lanelets of this lanelet", - (arg("lanelet"), arg("withLaneChanges") = false)) - .def("previousRelations", &RoutingGraph::previousRelations, "relations to preceding lanelets", - (arg("lanelet"), arg("withLaneChanges") = false)) + .def("following", &RoutingGraph::following, "lanelets that can be reached from this lanelet", lltAndLc) + .def("followingRelations", &RoutingGraph::followingRelations, "relations to following lanelets", lltAndLc) + .def("previous", &RoutingGraph::previous, "previous lanelets of this lanelet", lltAndLc) + .def("previousRelations", &RoutingGraph::previousRelations, "relations to preceding lanelets", lltAndLc) .def("besides", &RoutingGraph::besides, "all reachable left and right lanelets, including lanelet, from " "left to right", - (arg("lanelet"))) - .def("left", &RoutingGraph::left, "left (routable)lanelet, if exists", (arg("lanelet"))) - .def("right", &RoutingGraph::right, "right (routable)lanelet, if it exists", (arg("lanelet"))) - .def("adjacentLeft", &RoutingGraph::adjacentLeft, "left non-routable lanelet", arg("lanelet")) - .def("adjacentRight", &RoutingGraph::adjacentRight, "right non-routable lanelet", arg("lanelet")) - .def("lefts", &RoutingGraph::lefts, "all left (routable) lanelets", arg("lanelet")) - .def("rights", &RoutingGraph::rights, "all right (routable) lanelets", arg("lanelet")) - .def("adjacentLefts", &RoutingGraph::adjacentLefts, "all left (non-routable) lanelets", arg("lanelet")) - .def("adjacentRights", &RoutingGraph::adjacentRights, "all right (non-routable) lanelets", arg("lanelet")) - .def("leftRelations", &RoutingGraph::leftRelations, "relations to left lanelets", arg("lanelet")) - .def("rightRelations", &RoutingGraph::rightRelations, "relations to right lanelets", arg("lanelet")) + lltAndRoutingCost) + .def("left", &RoutingGraph::left, "left (routable)lanelet, if exists", lltAndRoutingCost) + .def("right", &RoutingGraph::right, "right (routable)lanelet, if it exists", lltAndRoutingCost) + .def("adjacentLeft", &RoutingGraph::adjacentLeft, "left non-routable lanelet", lltAndRoutingCost) + .def("adjacentRight", &RoutingGraph::adjacentRight, "right non-routable lanelet", lltAndRoutingCost) + .def("lefts", &RoutingGraph::lefts, "all left (routable) lanelets", lltAndRoutingCost) + .def("rights", &RoutingGraph::rights, "all right (routable) lanelets", lltAndRoutingCost) + .def("adjacentLefts", &RoutingGraph::adjacentLefts, "all left (non-routable) lanelets", lltAndRoutingCost) + .def("adjacentRights", &RoutingGraph::adjacentRights, "all right (non-routable) lanelets", lltAndRoutingCost) + .def("leftRelations", &RoutingGraph::leftRelations, "relations to left lanelets", lltAndRoutingCost) + .def("rightRelations", &RoutingGraph::rightRelations, "relations to right lanelets", lltAndRoutingCost) .def("conflicting", &RoutingGraph::conflicting, "Conflicting lanelets", arg("lanelet")) .def("reachableSet", &RoutingGraph::reachableSet, "set of lanelets that can be reached from a given lanelet", (arg("lanelet"), arg("maxRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = true)) @@ -176,47 +221,57 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("possiblePaths", possPCost, "possible paths from a given start lanelet that are 'minRoutingCost'-long", (arg("lanelet"), arg("minRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = false, arg("routingCostId") = 0)) + .def("possiblePaths", possPParam, "possible paths from a given start lanelet as configured in parameters", + (arg("lanelet"), arg("parameters"))) .def("possiblePathsTowards", possPToCost, "possible paths to a given start lanelet that are 'minRoutingCost'-long", (arg("lanelet"), arg("minRoutingCost"), arg("RoutingCostId") = 0, arg("allowLaneChanges") = false, arg("routingCostId") = 0)) + .def("possiblePathsTowards", possPToParam, "possible paths to a given lanelet as configured in parameters", + (arg("lanelet"), arg("parameters"))) .def("possiblePathsMinLen", possPLen, "possible routes from a given start lanelet that are 'minLanelets'-long", (arg("lanelet"), arg("minLanelets"), arg("allowLaneChanges") = false, arg("routingCostId") = 0)) .def("possiblePathsTowardsMinLen", possPToLen, "possible routes from a given start lanelet that are 'minLanelets'-long", (arg("lanelet"), arg("minLanelets"), arg("allowLaneChanges") = false, arg("routingCostId") = 0)) - .def("forEachSuccessor", - +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) { - self.forEachSuccessor(from, func, lc, costId); - }, - "calls a function on each successor of lanelet with increasing cost. The function must receives a " - "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet " - "should be visited as well. The function can raise an exception if an early exit is desired", - (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) - .def("forEachSuccessorIncludingAreas", - +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) { - self.forEachSuccessorIncludingAreas(from, func, lc, costId); - }, - "similar to forEachSuccessor but also includes areas into the search", - (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) - .def("forEachPredecessor", - +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) { - self.forEachPredecessor(from, func, lc, costId); - }, - "similar to forEachSuccessor but instead goes backwards along the routing graph", - (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) - .def("forEachPredecessorIncludingAreas", - +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) { - self.forEachPredecessorIncludingAreas(from, func, lc, costId); - }, - "calls a function on each successor of lanelet. The function must receives a LaneletVisitInformation object " - "as input and must return a bool whether followers of the current lanelet should be visited as well. The " - "function can throw an exception if an early exit is desired", - (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) - .def("exportGraphML", +[](RoutingGraph& self, const std::string& path) { self.exportGraphML(path); }, - "Export the internal graph to graphML (xml-based) file format") - .def("exportGraphViz", +[](RoutingGraph& self, const std::string& path) { self.exportGraphViz(path); }, - "Export the internal graph to graphViz (DOT) file format") + .def( + "forEachSuccessor", + +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) { + self.forEachSuccessor(from, std::move(func), lc, costId); + }, + "calls a function on each successor of lanelet with increasing cost. The function must receives a " + "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet " + "should be visited as well. The function can raise an exception if an early exit is desired", + (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) + .def( + "forEachSuccessorIncludingAreas", + +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) { + self.forEachSuccessorIncludingAreas(from, std::move(func), lc, costId); + }, + "similar to forEachSuccessor but also includes areas into the search", + (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) + .def( + "forEachPredecessor", + +[](RoutingGraph& self, const ConstLanelet& from, object func, bool lc, RoutingCostId costId) { + self.forEachPredecessor(from, std::move(func), lc, costId); + }, + "similar to forEachSuccessor but instead goes backwards along the routing graph", + (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) + .def( + "forEachPredecessorIncludingAreas", + +[](RoutingGraph& self, const ConstLaneletOrArea& from, object func, bool lc, RoutingCostId costId) { + self.forEachPredecessorIncludingAreas(from, std::move(func), lc, costId); + }, + "calls a function on each successor of lanelet. The function must receives a LaneletVisitInformation object " + "as input and must return a bool whether followers of the current lanelet should be visited as well. The " + "function can throw an exception if an early exit is desired", + (arg("lanelet"), arg("func"), arg("allowLaneChanges") = true, arg("routingCostId") = 0)) + .def( + "exportGraphML", +[](RoutingGraph& self, const std::string& path) { self.exportGraphML(path); }, + "Export the internal graph to graphML (xml-based) file format") + .def( + "exportGraphViz", +[](RoutingGraph& self, const std::string& path) { self.exportGraphViz(path); }, + "Export the internal graph to graphViz (DOT) file format") .def("getDebugLaneletMap", &RoutingGraph::getDebugLaneletMap, "abstract lanelet map holding the information of the routing graph", (arg("routingCostId") = 0, arg("includeAdjacent") = false, arg("includeConflicting") = false)) @@ -225,8 +280,8 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT (arg("throwOnError") = true)); class_("LaneletRelation") - .add_property("lanelet", &LaneletRelation::lanelet) - .add_property("relationType", &LaneletRelation::relationType); + .def_readwrite("lanelet", &LaneletRelation::lanelet) + .def_readwrite("relationType", &LaneletRelation::relationType); enum_("RelationType") .value("Successor", RelationType::Successor) @@ -249,8 +304,9 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Returns all lanelets on the shortest path that follow the input lanelet") .def("length2d", &Route::length2d, "2d length of shortest path") .def("numLanes", &Route::numLanes, "Number of inidividual lanes") - .def("laneletSubmap", +[](const Route& r) { return std::const_pointer_cast(r.laneletSubmap()); }, - "laneletSubmap with all lanelets that are part of the route") + .def( + "laneletSubmap", +[](const Route& r) { return std::const_pointer_cast(r.laneletSubmap()); }, + "laneletSubmap with all lanelets that are part of the route") .def("getDebugLaneletMap", &Route::getDebugLaneletMap, "laneletMap that represents the Lanelets of the Route and their relationship") .def("size", &Route::size, "Number of lanelets") @@ -265,15 +321,17 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "conflicting lanelets of a lanelet within all passable lanelets in the laneletMap") .def("allConflictingInMap", &Route::allConflictingInMap, "all lanelets in the map that conflict with any lanelet in the route") - .def("forEachSuccessor", - +[](Route& self, const ConstLanelet& from, object func) { self.forEachSuccessor(from, func); }, - "calls a function on each successor of lanelet with increasing cost. The function must receives a " - "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet " - "should be visited as well. The function can raise an exception if an early exit is desired", - (arg("lanelet"), arg("func"))) - .def("forEachPredecessor", - +[](Route& self, const ConstLanelet& from, object func) { self.forEachPredecessor(from, func); }, - "similar to forEachSuccessor but instead goes backwards along the routing graph", - (arg("lanelet"), arg("func"))) + .def( + "forEachSuccessor", + +[](Route& self, const ConstLanelet& from, object func) { self.forEachSuccessor(from, std::move(func)); }, + "calls a function on each successor of lanelet with increasing cost. The function must receives a " + "LaneletVisitInformation object as input and must return a bool whether followers of the current lanelet " + "should be visited as well. The function can raise an exception if an early exit is desired", + (arg("lanelet"), arg("func"))) + .def( + "forEachPredecessor", + +[](Route& self, const ConstLanelet& from, object func) { self.forEachPredecessor(from, std::move(func)); }, + "similar to forEachSuccessor but instead goes backwards along the routing graph", + (arg("lanelet"), arg("func"))) .def("checkValidity", &Route::checkValidity, "perform sanity check on the route"); } diff --git a/lanelet2/lanelet2_python/python_api/std_map_indexing.h b/lanelet2/lanelet2_python/python_api/std_map_indexing.h deleted file mode 100644 index 9b637da3bdf..00000000000 --- a/lanelet2/lanelet2_python/python_api/std_map_indexing.h +++ /dev/null @@ -1,350 +0,0 @@ -// (C) Copyright Joel de Guzman 2003. -// Distributed under the Boost Software License, Version 1.0. (See -// accompanying file LICENSE_1_0.txt or copy at -// http://www.boost.org/LICENSE_1_0.txt) -// Modified by Troy D. Straszheim and Jakob van Santen, 2009-03-26 - -#ifndef STD_MAP_INDEXING_SUITE_JDG20038_HPP -#define STD_MAP_INDEXING_SUITE_JDG20038_HPP - -#include -#include -#include -#include -#include - -namespace bp = boost::python; - -namespace boost { -namespace python { - -// Forward declaration -template -class std_map_indexing_suite; - -namespace detail { -template -class final_std_map_derived_policies - : public std_map_indexing_suite > {}; -} // namespace detail - -// The map_indexing_suite class is a predefined indexing_suite derived -// class for wrapping std::vector (and std::vector like) classes. It provides -// all the policies required by the indexing_suite (see indexing_suite). -// Example usage: -// -// class X {...}; -// -// ... -// -// class_ >("XMap") -// .def(map_indexing_suite >()) -// ; -// -// By default indexed elements are returned by proxy. This can be -// disabled by supplying *true* in the NoProxy template parameter. -// -template > -class std_map_indexing_suite - : public indexing_suite { - public: - typedef typename Container::value_type value_type; - typedef typename Container::value_type::second_type data_type; - typedef typename Container::key_type key_type; - typedef typename Container::key_type index_type; - typedef typename Container::size_type size_type; - typedef typename Container::difference_type difference_type; - typedef typename Container::const_iterator const_iterator; - - // __getitem__ for std::pair - static object pair_getitem(value_type const& x, int i) { - if (i == 0 || i == -2) - return object(x.first); - else if (i == 1 || i == -1) - return object(x.second); - else { - PyErr_SetString(PyExc_IndexError, "Index out of range."); - throw_error_already_set(); - return object(); // None - } - } - // __len__ std::pair = 2 - static int pair_len(value_type const& x) { return 2; } - - // return a list of keys - static bp::list keys(Container const& x) { - bp::list t; - for (typename Container::const_iterator it = x.begin(); it != x.end(); it++) t.append(it->first); - return t; - } - // return a list of values - static bp::list values(Container const& x) { - bp::list t; - for (typename Container::const_iterator it = x.begin(); it != x.end(); it++) t.append(it->second); - return t; - } - // return a list of (key,value) tuples - static bp::list items(Container const& x) { - bp::list t; - for (typename Container::const_iterator it = x.begin(); it != x.end(); it++) - t.append(make_tuple(it->first, it->second)); - return t; - } - - // return a shallow copy of the map - // FIXME: is this actually a shallow copy, or did i duplicate the pairs? - static Container copy(Container const& x) { - Container newmap = Container(); - for (const_iterator it = x.begin(); it != x.end(); it++) newmap.insert(*it); - return newmap; - } - - // get with default value - static object dict_get(Container const& x, index_type const& k, object const& default_val = object()) { - const_iterator it = x.find(k); - if (it != x.end()) - return object(it->second); - else - return default_val; - } - // preserve default value info - BOOST_PYTHON_FUNCTION_OVERLOADS(dict_get_overloads, dict_get, 2, 3); - - // pop map[key], or throw an error if it doesn't exist - static object dict_pop(Container& x, index_type const& k) { - const_iterator it = x.find(k); - object result; - if (it != x.end()) { - result = object(it->second); - x.erase(it->first); - return result; - } else { - PyErr_SetString(PyExc_KeyError, "Key not found."); - throw_error_already_set(); - return object(); // None - }; - } - - // pop map[key], or return default_val if it doesn't exist - static object dict_pop_default(Container& x, index_type const& k, object const& default_val) { - const_iterator it = x.find(k); - object result; - if (it != x.end()) { - result = object(it->second); - x.erase(it->first); - return result; - } else - return default_val; - } - - // pop a tuple, or throw an error if empty - static object dict_pop_item(Container& x) { - const_iterator it = x.begin(); - object result; - if (it != x.end()) { - result = make_tuple(it->first, it->second); - x.erase(it->first); - return result; - } else { - PyErr_SetString(PyExc_KeyError, "No more items to pop"); - throw_error_already_set(); - return object(); // None - }; - } - - // create a new map with given keys, initialialized to value - static object dict_fromkeys(object const& keys, object const& value) { - object newmap = object(Container()); - int numkeys = extract(keys.attr("__len__")()); - for (int i = 0; i < numkeys; i++) { // 'cuz python is more fun in C++... - newmap.attr("__setitem__")(keys.attr("__getitem__")(i), value); - } - return newmap; - } - - // spice up the constructors a bit - template - struct init_factory { - typedef typename PyClassT::metadata::holder Holder; - typedef bp::objects::instance instance_t; - - // connect the PyObject to a wrapped C++ instance - // borrowed from boost/python/object/make_holder.hpp - static void make_holder(PyObject* p) { - void* memory = Holder::allocate(p, offsetof(instance_t, storage), sizeof(Holder)); - - try { - // this only works for blank () constructors - (new (memory) Holder(p))->install(p); - } catch (...) { - Holder::deallocate(p, memory); - throw; - } - } - static void from_dict(PyObject* p, bp::dict const& dict) { - make_holder(p); - object newmap = object(bp::handle<>(borrowed(p))); - newmap.attr("update")(dict); - } - static void from_list(PyObject* p, bp::list const& list) { - make_holder(p); - object newmap = object(bp::handle<>(borrowed(p))); - newmap.attr("update")(bp::dict(list)); - } - }; - - // copy keys and values from dictlike object (anything with keys()) - static void dict_update(object& x, object const& dictlike) { - object key; - object keys = dictlike.attr("keys")(); - int numkeys = extract(keys.attr("__len__")()); - for (int i = 0; i < numkeys; i++) { - key = keys.attr("__getitem__")(i); - x.attr("__setitem__")(key, dictlike.attr("__getitem__")(key)); - } - } - - // set up operators to extract the key, value, or a tuple from a std::pair - struct iterkeys { - typedef key_type result_type; - - result_type operator()(value_type const& x) const { return x.first; } - }; - - struct itervalues { - typedef data_type result_type; - - result_type operator()(value_type const& x) const { return x.second; } - }; - - struct iteritems { - typedef tuple result_type; - - result_type operator()(value_type const& x) const { return make_tuple(x.first, x.second); } - }; - - template - struct make_transform_impl { - typedef boost::transform_iterator iterator; - - static iterator begin(const Container& m) { return boost::make_transform_iterator(m.begin(), Transform()); } - static iterator end(const Container& m) { return boost::make_transform_iterator(m.end(), Transform()); } - - static bp::object range() { return bp::range(&begin, &end); } - }; - - template - static bp::object make_transform() { - return make_transform_impl::range(); - } - - static object print_elem(typename Container::value_type const& e) { - return "(%s, %s)" % python::make_tuple(e.first, e.second); - } - - static typename mpl::if_, data_type&, data_type>::type get_data( - typename Container::value_type& e) { - return e.second; - } - - static typename Container::key_type get_key(typename Container::value_type& e) { return e.first; } - - static data_type& get_item(Container& container, index_type i_) { - typename Container::iterator i = container.find(i_); - if (i == container.end()) { - PyErr_SetString(PyExc_KeyError, "Invalid key"); - throw_error_already_set(); - } - return i->second; - } - - static void set_item(Container& container, index_type i, data_type const& v) { container[i] = v; } - - static void delete_item(Container& container, index_type i) { container.erase(i); } - - static size_t size(Container& container) { return container.size(); } - - static bool contains(Container& container, key_type const& key) { return container.find(key) != container.end(); } - - static bool compare_index(Container& container, index_type a, index_type b) { return container.key_comp()(a, b); } - - static index_type convert_index(Container& container, PyObject* i_) { - extract i(i_); - if (i.check()) { - return i(); - } else { - extract i(i_); - if (i.check()) return i(); - } - - PyErr_SetString(PyExc_TypeError, "Invalid index type"); - throw_error_already_set(); - return index_type(); - } - - template - static void extension_def(Class& cl) { - // Wrap the map's element (value_type) - std::string elem_name = "std_map_indexing_suite_"; - std::string cl_name; - object class_name(cl.attr("__name__")); - extract class_name_extractor(class_name); - cl_name = class_name_extractor(); - elem_name += cl_name; - elem_name += "_entry"; - - typedef typename mpl::if_, return_internal_reference<>, default_call_policies>::type - get_data_return_policy; - - class_(elem_name.c_str()) - .def("__repr__", &DerivedPolicies::print_elem) - .def("data", &DerivedPolicies::get_data, get_data_return_policy(), - "K.data() -> the value associated with this pair.\n") - .def("key", &DerivedPolicies::get_key, "K.key() -> the key associated with this pair.\n") - .def("__getitem__", &pair_getitem) - .def("__len__", &pair_len) - .add_property("first", &DerivedPolicies::get_key, "K.first() -> the first item in this pair.\n") - .add_property("second", &DerivedPolicies::get_data, // get_data_return_policy(), - "K.second() -> the second item in this pair.\n"); - // add convenience methods to the map - - cl - // declare constructors in descending order of arity - .def("__init__", init_factory::from_list, - "Initialize with keys and values from a Python dictionary: {'key':'value'}\n") - .def("__init__", init_factory::from_dict, - "Initialize with keys and values as tuples in a Python list: [('key','value')]\n") - .def(init<>()) // restore default constructor - - .def("keys", &keys, "D.keys() -> list of D's keys\n") - .def("has_key", &contains, "D.has_key(k) -> True if D has a key k, else False\n") // don't re-invent the wheel - .def("values", &values, "D.values() -> list of D's values\n") - .def("items", &items, "D.items() -> list of D's (key, value) pairs, as 2-tuples\n") - .def("clear", &Container::clear, "D.clear() -> None. Remove all items from D.\n") - .def("copy", ©, "D.copy() -> a shallow copy of D\n") - .def("get", dict_get, - dict_get_overloads(args("default_val"), "D.get(k[,d]) -> D[k] if k in D, else d. d defaults to None.\n")) - .def("pop", &dict_pop) - .def("pop", &dict_pop_default, - "D.pop(k[,d]) -> v, remove specified key and return the corresponding value\nIf key is not found, d is " - "returned if given, otherwise KeyError is raised\n") - .def("popitem", &dict_pop_item, - "D.popitem() -> (k, v), remove and return some (key, value) pair as a\n2-tuple; but raise KeyError if D " - "is empty\n") - .def("fromkeys", &dict_fromkeys, - (cl_name + ".fromkeys(S,v) -> New " + cl_name + " with keys from S and values equal to v.\n").c_str()) - .staticmethod("fromkeys") - .def("update", &dict_update, "D.update(E) -> None. Update D from E: for k in E: D[k] = E[k]\n") - .def("iteritems", make_transform(), - "D.iteritems() -> an iterator over the (key, value) items of D\n") - .def("iterkeys", make_transform(), "D.iterkeys() -> an iterator over the keys of D\n") - .def("itervalues", make_transform(), "D.itervalues() -> an iterator over the values of D\n"); - } -}; - -} // namespace python -} // namespace boost - -#endif // STD_MAP_INDEXING_SUITE_JDG20038_HPP diff --git a/lanelet2/lanelet2_python/python_api/traffic_rules.cpp b/lanelet2/lanelet2_python/python_api/traffic_rules.cpp index e7b102da1ac..1cc6a56676c 100644 --- a/lanelet2/lanelet2_python/python_api/traffic_rules.cpp +++ b/lanelet2/lanelet2_python/python_api/traffic_rules.cpp @@ -2,6 +2,7 @@ #include #include #include + #include using namespace boost::python; @@ -18,6 +19,12 @@ void setVelocity(SpeedLimitInformation& self, double velocityKmh) { self.speedLimit = Velocity(velocityKmh * units::KmH()); } +double getVelocityMPS(const SpeedLimitInformation& self) { return units::MPSQuantity(self.speedLimit).value(); } + +void setVelocityMPS(SpeedLimitInformation& self, double velocityMps) { + self.speedLimit = Velocity(velocityMps * units::MPS()); +} + template bool canPassWrapper(const TrafficRules& self, const T& llt) { return self.canPass(llt); @@ -51,8 +58,10 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Initialize from speed limit [m/s] and bool if speedlimit is " "mandatory") .add_property("speedLimit", getVelocity, setVelocity, "velocity in km/h") - .add_property("isMandatory", &SpeedLimitInformation::isMandatory, - "True if speedlimit is not just a recommendation") + .add_property("speedLimitKmH", getVelocity, setVelocity, "velocity in km/h") + .add_property("speedLimitMPS", getVelocityMPS, setVelocityMPS, "velocity in m/s") + .def_readwrite("isMandatory", &SpeedLimitInformation::isMandatory, + "True if speedlimit is not just a recommendation") .def(self_ns::str(self_ns::self)); class_>("TrafficRules", no_init) diff --git a/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py b/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py index 18d33d3c2ab..bda01db78a1 100755 --- a/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py +++ b/lanelet2/lanelet2_python/scripts/create_debug_routing_graph.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python import lanelet2 import sys diff --git a/lanelet2/lanelet2_python/scripts/make_ids_positive.py b/lanelet2/lanelet2_python/scripts/make_ids_positive.py index 251290004c6..538c191ec60 100755 --- a/lanelet2/lanelet2_python/scripts/make_ids_positive.py +++ b/lanelet2/lanelet2_python/scripts/make_ids_positive.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python import lanelet2 import sys diff --git a/lanelet2/lanelet2_python/scripts/print_ids.py b/lanelet2/lanelet2_python/scripts/print_ids.py index 15d95b55c8e..d2435f9b522 100755 --- a/lanelet2/lanelet2_python/scripts/print_ids.py +++ b/lanelet2/lanelet2_python/scripts/print_ids.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python import lanelet2 import sys diff --git a/lanelet2/lanelet2_python/test/test_lanelet2_matching.py b/lanelet2/lanelet2_python/test/test_lanelet2_matching.py new file mode 100644 index 00000000000..876b80205b2 --- /dev/null +++ b/lanelet2/lanelet2_python/test/test_lanelet2_matching.py @@ -0,0 +1,94 @@ +import unittest +import lanelet2 # if we fail here, there is something wrong with lanelet2 registration +from lanelet2.core import AttributeMap, getId, BasicPoint2d, Point3d, LineString3d, Lanelet, RegulatoryElement, TrafficLight, LaneletMap, createMapFromLanelets, ConstLanelet, ConstLineString3d +from lanelet2.geometry import distance, intersects2d, boundingBox2d, to2D, equals +from lanelet2.matching import Pose2d, getDeterministicMatches, getProbabilisticMatches, Object2d, ObjectWithCovariance2d, PositionCovariance2d, removeNonRuleCompliantMatches +from lanelet2.matching import ConstLaneletMatch, ConstLaneletMatchProbabilistic + + +def get_sample_lanelet_map(): + mymap = LaneletMap() + x_left = 2 + x_right = 0 + ls_left = LineString3d(getId(), [Point3d(getId(), x_left, i, 0) for i in range(0, 3)]) + ls_right = LineString3d(getId(), [Point3d(getId(), x_right, i, 0) for i in range(0, 3)]) + llet = Lanelet(getId(), ls_left, ls_right) + mymap.add(llet) + return mymap + + +class ObjectsApiTestCase(unittest.TestCase): + def test_default_init(self): + obj_2d = Object2d() + self.assertTrue(isinstance(obj_2d, Object2d)) + self.assertEqual(len(obj_2d.absoluteHull), 0) + + obj_with_cov_2d = ObjectWithCovariance2d() + self.assertTrue(isinstance(obj_with_cov_2d, ObjectWithCovariance2d)) + self.assertEqual(len(obj_with_cov_2d.absoluteHull), 0) + self.assertEqual(obj_with_cov_2d.vonMisesKappa, 0) + + pos_cov_2d = PositionCovariance2d() + self.assertTrue(isinstance(pos_cov_2d, PositionCovariance2d)) + + pose_2d = Pose2d() + self.assertTrue(isinstance(pose_2d, Pose2d)) + + def test_custom_init(self): + obj_2d = Object2d(1, Pose2d(), []) + self.assertTrue(isinstance(obj_2d, Object2d)) + self.assertEqual(len(obj_2d.absoluteHull), 0) + + obj_with_cov_2d = ObjectWithCovariance2d(1, Pose2d(), [], PositionCovariance2d(), 2) + self.assertTrue(isinstance(obj_with_cov_2d, ObjectWithCovariance2d)) + self.assertEqual(len(obj_with_cov_2d.absoluteHull), 0) + self.assertEqual(obj_with_cov_2d.vonMisesKappa, 2) + + pos_cov_2d = PositionCovariance2d(1., 2., 3.) + self.assertTrue(isinstance(pos_cov_2d, PositionCovariance2d)) + self.assertEqual("1 3\n3 2", str(pos_cov_2d)) + + pose_2d = Pose2d(1., 2., 3.) + self.assertTrue(isinstance(pose_2d, Pose2d)) + self.assertEqual("x: 1\ny: 2\nphi: 3", str(pose_2d)) + + +class MatchingApiTestCase(unittest.TestCase): + def test_matching(self): + mymap = get_sample_lanelet_map() + + obj = Object2d(1, Pose2d(1, 1, 0), []) + obj_with_cov = ObjectWithCovariance2d(1, Pose2d(1, 1, 0), [], PositionCovariance2d(1., 1., 0.), 2) + + obj_matches = getDeterministicMatches(mymap, obj, 1.) + self.assertEqual(len(obj_matches), 2) # lanelet in both directions + self.assertTrue(isinstance(obj_matches[0], ConstLaneletMatch)) + + obj_with_cov_matches = getProbabilisticMatches(mymap, obj_with_cov, 1.) + self.assertEqual(len(obj_with_cov_matches), 2) # lanelet in both directions + self.assertTrue(isinstance(obj_with_cov_matches[0], ConstLaneletMatchProbabilistic)) + + traffic_rules = lanelet2.traffic_rules.create(lanelet2.traffic_rules.Locations.Germany, + lanelet2.traffic_rules.Participants.Vehicle) + + obj_matches_rule_compliant = removeNonRuleCompliantMatches(obj_matches, traffic_rules) + self.assertEqual(len(obj_matches_rule_compliant), 1) # lanelet only in one direction + self.assertTrue(isinstance(obj_matches_rule_compliant[0], ConstLaneletMatch)) + + obj_with_cov_matches_rule_compliant = removeNonRuleCompliantMatches(obj_with_cov_matches, traffic_rules) + self.assertEqual(len(obj_with_cov_matches_rule_compliant), 1) # lanelet only in one direction + self.assertTrue(isinstance(obj_with_cov_matches_rule_compliant[0], ConstLaneletMatchProbabilistic)) + self.assertTrue(isinstance(obj_with_cov_matches_rule_compliant[0].lanelet, ConstLanelet)) + self.assertEqual(obj_with_cov_matches_rule_compliant[0].distance, 0) + self.assertTrue(isinstance(obj_with_cov_matches_rule_compliant[0].mahalanobisDistSq, float)) + + # empty matches list + empty_matches_rule_compliant = removeNonRuleCompliantMatches(list(), traffic_rules) + self.assertEqual(len(empty_matches_rule_compliant), 0) + + # list of neither matches nor probabilistic matches + self.assertRaises(RuntimeError, removeNonRuleCompliantMatches, [obj], traffic_rules) + + +if __name__ == '__main__': + unittest.main() diff --git a/lanelet2/lanelet2_routing/CHANGELOG.rst b/lanelet2/lanelet2_routing/CHANGELOG.rst new file mode 100644 index 00000000000..c96918216e6 --- /dev/null +++ b/lanelet2/lanelet2_routing/CHANGELOG.rst @@ -0,0 +1,61 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_routing +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Implement more flexible configuration for obtaining possible paths. Still lacking proper tests +* Add parameter to left/right/adjacentLeft/adjacentRight so that they can be queried based on routing cost id +* Fix routing for lane changes, add tests for it +* Fix wrong route in circles +* Fix unittests that rely on a non-writable root directory +* Add experimental support for building with colcon on ros2 and ament_cmake +* Fix the documentation about how to create a routing graph +* Removing extra semicolons causing warnings with wpedantic. +* Making all includes in lanelet2_routing consistent. +* Updating package.xml files to format 3. +* Fix use of equals in older boost versions +* Arbitrary lanelet and area adjacencies in LaneletPaths +* Add functionality to create the bounding polygon from a Path +* Contributors: Fabian Poggenhans, Johannes Janosovits, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Mention laneletSubmap in README +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Fix clang-tidy warnings +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Routing: Add shortest path search based on areas +* Fix default values for lane changes in RoutingGraph +* RoutingGraph and Route now use the new LaneletSubmap to store the lanelets they are using + their member functions laneletMap() and passableMap() are now deprecated and should be replaced by laneletSubmap() and passableSubmap() respectively. These functions have less overhead and are less likely to be misinterpreted as 'maps containing only the lanelets you need' +* Edges with nonfinite costs are no longer added to the graph to avoid overflows. + If a cost function returns infinite costs, no edge will be added and the connection will not be available to the routing graph +* Introduce proper namespacing for internal objects +* Update documentation +* Routing graph and route object now support queries with a custom search function + Routing graph and route object now both have a function forEachSuccessor (and more) for doing more advanced queries. Added doc tests and python bindings +* Update the shortest path algorithm to use the new dijktra search +* Extended and simplified the reachablePath/Set functions + by using boost graphs implementation of dijkstras shortest paths +* Refactored the internal representation of the route. Cleaned up headers that are only supposed to be used internally +* Complete rewrite of the route builder using boost graph +* Removed the "diverging" and "merging" classification from the routing + graph and update the doc + They are now all represented with the "succeeding" relation. Information + about merging or diverging can now be obtained simply by querying the + number of following/preceding lanelets. + As a consequence, the route object no longer caches queried "lanes". The + responsible functions are now const. +* Fix compiler errors with gcc 5 +* Fix image paths in routing doc +* Initial commit +* Contributors: Fabian Poggenhans, Johannes Janosovits, Maximilian Naumann diff --git a/lanelet2/lanelet2_routing/CMakeLists.txt b/lanelet2/lanelet2_routing/CMakeLists.txt index b0d97e7208e..8b60fa6deeb 100644 --- a/lanelet2/lanelet2_routing/CMakeLists.txt +++ b/lanelet2/lanelet2_routing/CMakeLists.txt @@ -1,8 +1,7 @@ -set(MRT_PKG_VERSION 2.2) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_routing) -set(MRT_COTIRE_ENABLED 1) ################### ## find packages ## @@ -95,4 +94,4 @@ mrt_install(PROGRAMS scripts FILES res data) if (CATKIN_ENABLE_TESTING) mrt_add_tests(test) # TODO Figure out why this can't build on kinetic mrt_add_nosetests(test) # TODO Figure out why this can't build on kinetic -endif() +endif() \ No newline at end of file diff --git a/lanelet2/lanelet2_routing/README.md b/lanelet2/lanelet2_routing/README.md index cdced57f4ed..c971680ca23 100644 --- a/lanelet2/lanelet2_routing/README.md +++ b/lanelet2/lanelet2_routing/README.md @@ -70,7 +70,7 @@ RoutingGraph::Configuration routingGraphConf; routingGraphConf.emplace(std::make_pair(RoutingGraph::ParticipantHeight, Attribute("2."))); // Create routing graph -RoutingGraphPtr graph = std::make_shared(map, trafficRules /*, costPtrs, routingGraphConf*/); +RoutingGraphPtr graph = RoutingGraph::build(map, trafficRules /*, costPtrs, routingGraphConf*/); ``` - The traffic rules object represents the view from which the map will be interpreted. Doing routing with vehicle traffic rules will yield different results than routing with e.g. bicycle traffic rules. @@ -102,17 +102,25 @@ In python, shortestPath simply returns `None` if there is no path. ```cpp Optional route = graph->getRoute(fromLanelet, toLanelet, routingCostId); if (route) { - write("route.osm", *route->laneletMap(), Origin({49, 8})); + LaneletSubmapConstPtr routeMap = route->laneletSubmap(); + write("route.osm", *routeMap->laneletMap(), Origin({49, 8})); } ``` * `Optional` will be uninitialized (false) if there's no route -* This lanelet map will include all lanelets that are part of the route + +Note that there is a semantic difference between a `LaneletSubmap` and a `LaneletMap`. While a LaneletSubmap only contains +the things you explicitly added, the `LaneletMap` also contains all the things referred by them (the Points, Linestrings, things referred by RegulatoryElements). +The `LaneletSubmap` in this case only contains the Lanelets of the route. But since this is not sufficient for writing, you need to transform it into a regular `LaneletMap` first. + +The written map will therefore not only contain the Lanelets but also their RegulatoryElements. +If these RegulatoryElements contain other Lanelets, these Lanelets will be part of the written map as well, even if they are not on the route. in python: ```python route = graph.getRoute(fromLanelet, toLanelet, routingCostId) if route: - lanelet2.io.write("route.osm", route.laneletMap(), lanelet2.io.Origin(49, 8))) + laneletSubmap = route.laneletSubmap() + lanelet2.io.write("route.osm", laneletSubmap.laneletMap(), lanelet2.io.Origin(49, 8))) ``` ## Get a reachable set of lanelets diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/Forward.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/Forward.h index d151a3b3bdb..910ba7fc059 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/Forward.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/Forward.h @@ -1,6 +1,7 @@ #pragma once #include + #include #include #include @@ -114,7 +115,6 @@ inline std::string relationToColor(RelationType type) { case RelationType::Conflicting: return "red"; case RelationType::AdjacentLeft: - return "black"; case RelationType::AdjacentRight: return "black"; case RelationType::Area: diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/LaneletPath.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/LaneletPath.h index 286811bbb29..f69642a33ff 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/LaneletPath.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/LaneletPath.h @@ -3,7 +3,8 @@ #include #include #include -#include "Forward.h" + +#include "lanelet2_routing/Forward.h" namespace lanelet { namespace routing { @@ -72,5 +73,13 @@ class LaneletOrAreaPath { private: ConstLaneletOrAreas laneletsOrAreas_; }; + +/** + * finds the Polygon containing all Lanelets and Areas in Path. All points on the polygon will be identical to points + * of primitives in path. + * @param path Path to merge + * @return Polygon containing all Lanelets and Areas in Path + */ +BasicPolygon3d getEnclosingPolygon3d(const LaneletOrAreaPath& path); } // namespace routing } // namespace lanelet diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/Route.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/Route.h index d333e12313c..566590b919d 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/Route.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/Route.h @@ -2,12 +2,14 @@ #include #include #include + #include #include #include -#include "Forward.h" -#include "LaneletPath.h" -#include "Types.h" + +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/LaneletPath.h" +#include "lanelet2_routing/Types.h" namespace lanelet { namespace routing { @@ -213,5 +215,5 @@ class Route { LaneletSubmapConstPtr laneletSubmap_; ///< LaneletSubmap with all lanelets that are part of the route lanelet::ConstPoint3d end_point_; ///< Endpoint of route }; -}; // namespace routing -}; // namespace lanelet \ No newline at end of file +} // namespace routing +} // namespace lanelet diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingCost.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingCost.h index 5f935cfdb7f..789d123e158 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingCost.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingCost.h @@ -4,7 +4,8 @@ #include #include #include -#include "Forward.h" + +#include "lanelet2_routing/Forward.h" namespace lanelet { namespace routing { @@ -70,8 +71,8 @@ class RoutingCostDistance : public RoutingCost { } private: - double length(const ConstLanelet& ll) const noexcept; - double length(const ConstArea& ar) const noexcept; + static double length(const ConstLanelet& ll) noexcept; + static double length(const ConstArea& ar) noexcept; const double laneChangeCost_, minChangeLength_; // NOLINT }; @@ -111,8 +112,8 @@ class RoutingCostTravelTime : public RoutingCost { } private: - double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstLanelet& ll) const; - double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstArea& ar) const; + static double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstLanelet& ll); + static double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstArea& ar); const Velocity maxSpeed_; // NOLINT const double laneChangeCost_, minChangeTime_; // NOLINT }; diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraph.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraph.h index de811a99ff8..b527da41782 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraph.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraph.h @@ -2,15 +2,59 @@ #include #include #include +#include #include + #include -#include "Forward.h" -#include "LaneletPath.h" -#include "RoutingCost.h" -#include "Types.h" + +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/LaneletPath.h" +#include "lanelet2_routing/RoutingCost.h" +#include "lanelet2_routing/Types.h" namespace lanelet { namespace routing { + +/** + * @brief Controls the behaviour of the different possible path algorithms in RoutingGraph + * + * Consider the following graph (- or \ connects followers, | is a lane change): + * ``` + * 1-2-3-4-5 + * \ / + * 6-7 + * | | + * 8-9 + * ``` + * Assuming we are using lanelet 1 as start of the search you can get the following results: + * - routingCostLimit=50 (and the rest the default): Will give you all optimal paths that are at least 50 + * long (wrt to routing cost module zero, i.e. the first routing cost object from the "routingCosts" + * parameter that the routing graph was crated with), does not include lane changes. The paths end + * with the first lanelet that exceeds the 50 cost limit. Depending on the costs, the returned paths + * might be only the path 1-2-3 (assuming 1-6-7 is too short). + * - routingCostLimit=70: Will give you only 1-2-3-4, because 1-6-7-4 is a suboptimal path and 1-6-7 is too short. + * - routingCostLimit=70, includeShorterPaths=True: Will give you 1-2-3-4 and 1-6-7. 1-6-7-4 is not included because the + * path to 4 is suboptimal + * - elementLimit=3: Will give you all optimal paths with exactly 3 lanelets (excluding lane changes). The result + * will be 1-2-3 and 1-6-7 + * - elementLimit=4: Will give you only 1-2-3-4, also because 1-6-7-4 is suboptimal + * - elementLimit=5, includeShorterPaths=true, includeLaneChanges=true: Will give you all optimal paths that + * are at most 5 lanelets/areas long, including lane changes. The result might be 1-2-3-4-5, 1-6-7, + * 1-8-9. + * - routingCostLimit=50, elementLimit=3, includeLaneChanges=true: Will give you all optimal paths (including lane + * changes) where the last lanelet/area exceeds the 50 cost limit or that are 3 lanelets/areas long (whatever occurs + * first). The result might be 1-2-3, 1-6-7 and 1-8-9 + * - routingCostLimit=70, elementLimit=4, includeShorterPaths=true: Will give you all optimal paths as above but also + * include shorter/cheaper paths. Result: 1-2-3-4, 1-6-7, 1-8-9. + */ +struct PossiblePathsParams { + Optional routingCostLimit; //!< cost limit for every path. Either that or maxElements must be valid. + Optional elementLimit; //!< element limit for every path. Effect depends on includeShorterPaths + RoutingCostId routingCostId{}; //!< the routing cost module to be used for the costs + bool includeLaneChanges{false}; //!< if true, returned paths will include lane changes + bool includeShorterPaths{false}; //!< also return paths that do not reach the limits +}; + /** @brief Main class of the routing module that holds routing information and can be queried. * The RoutingGraph class is the central object of this module and is initialized with a LaneletMap, TrafficRules and * RoutingCost. @@ -89,6 +133,19 @@ class RoutingGraph { Optional shortestPath(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId = {}, bool withLaneChanges = true) const; + /** @brief Retrieve a shortest path between 'start' and 'end' that may contain Areas. + * + * Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the + * routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, + * i.e. lanelets that are parallel and not only adjacent. + * @param from Start lanelet or area to find a shortest path + * @param to End lanelet or area to find a shortest path to + * @param routingCostId ID of RoutingCost module to determine shortest path + * @param withLaneChanges if false, the shortest path will not contain lane changes */ + Optional shortestPathIncludingAreas(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to, + RoutingCostId routingCostId = {}, + bool withLaneChanges = true) const; + /** @brief Retrieve a shortest path between 'start' and 'end' using intermediate points. * Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the * routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, @@ -102,6 +159,22 @@ class RoutingGraph { Optional shortestPathVia(const ConstLanelet& start, const ConstLanelets& via, const ConstLanelet& end, RoutingCostId routingCostId = {}, bool withLaneChanges = true) const; + /** @brief Retrieve a shortest path between 'start' and 'end' using intermediate points. + * Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the + * routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, + * i.e. lanelets that are parallel and not only adjacent. + * @param start Start lanelet or area to find a shortest path + * @param via Intermediate lanelets or areas that have to be passed + * @param end End lanelet or area to find a shortest path + * @param routingCostId ID of RoutingCost module to determine shortest path + * @param withLaneChanges if false, the shortest path will not contain lane changes + * @see shortestPath */ + Optional shortestPathIncludingAreasVia(const ConstLaneletOrArea& start, + const ConstLaneletOrAreas& via, + const ConstLaneletOrArea& end, + RoutingCostId routingCostId = {}, + bool withLaneChanges = true) const; + /** @brief Determines the relation between two lanelets * @param from Start lanelet * @param to Goal lanelet @@ -141,68 +214,90 @@ class RoutingGraph { /** @brief Retrieve all reachable left and right lanelets * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return All left and right lanelets that can be reached, including lanelet, ordered left to right. */ - ConstLanelets besides(const ConstLanelet& lanelet) const; + ConstLanelets besides(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get left (routable) lanelet of a given lanelet if it exists. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Left lanelet if it exists. Nothing if it doesn't. * @see adjacentLeft, lefts, adjacentLefts */ - Optional left(const ConstLanelet& lanelet) const; + Optional left(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get adjacent left (non-routable) lanelet of a given lanelet if it exists. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Adjacent left lanelet if it exists. Nothing if it doesn't. * @see left, lefts, adjacentLefts */ - Optional adjacentLeft(const ConstLanelet& lanelet) const; + Optional adjacentLeft(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get right (routable) lanelet of a given lanelet if it exists. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Right lanelet if it exists. Nothing if it doesn't. * @see adjacentRight, rights, adjacentRights */ - Optional right(const ConstLanelet& lanelet) const; + Optional right(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get adjacent right (non-routable) lanelet of a given lanelet if it exists. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Adjacent right lanelet if it exists. Nothing if it doesn't. * @see right, rights, adjacentRights */ - Optional adjacentRight(const ConstLanelet& lanelet) const; + Optional adjacentRight(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get all left (routable) lanelets of a given lanelet if they exist. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Left lanelets if they exists. Empty if they don't. * @see adjacentLeft, left, adjacentLefts */ - ConstLanelets lefts(const ConstLanelet& lanelet) const; + ConstLanelets lefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get all adjacent left (non-routable) lanelets of a given lanelet if they exist. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Adjacent left lanelets if they exists. Empty if they don't. * @see adjacentLeft, left, lefts */ - ConstLanelets adjacentLefts(const ConstLanelet& lanelet) const; + ConstLanelets adjacentLefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Retrieve all lanelets and relations left of a given lanelet. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return All lanelets and relations left of a given lanelet. * @see lefts, adjacentLefts */ - LaneletRelations leftRelations(const ConstLanelet& lanelet) const; + LaneletRelations leftRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get all right (routable) lanelets of a given lanelet if they exist. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Right lanelets if they exists. Empty if they don't. * @see adjacentRight, right, adjacentRights */ - ConstLanelets rights(const ConstLanelet& lanelet) const; + ConstLanelets rights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Get all adjacent right (non-routable) lanelets of a given lanelet if they exist. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return Adjacent right lanelets if they exists. Empty if they don't. * @see adjacentRight, right, rights */ - ConstLanelets adjacentRights(const ConstLanelet& lanelet) const; + ConstLanelets adjacentRights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Retrieve all lanelets and relations right of a given lanelet. * @param lanelet Start lanelet + * @param routingCostId the routing cost module to be used. Can make a difference if one allows a lane change but the + * other one doesn't. * @return All lanelets and relations right of a given lanelet. * @see rights, adjacentRights */ - LaneletRelations rightRelations(const ConstLanelet& lanelet) const; + LaneletRelations rightRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const; /** @brief Retrieve all lanelets that are conflicting with the given lanelet. * @@ -238,54 +333,60 @@ class RoutingGraph { ConstLanelets reachableSetTowards(const ConstLanelet& lanelet, double maxRoutingCost, RoutingCostId routingCostId = {}, bool allowLaneChanges = true) const; + /** + * @brief Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePathsParams + * @param startPoint Start lanelet + * @param params Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details. + * @return all valid possible paths. If a lanelet can be reached + * using different paths, only the one is included that requires the least number of lane changes and has minimum + * routing costs. "startPoint" itself is always included if it is in the routing graph. + * @throws InvalidInputError if neither elementLimit nor costLimit is valid in params + */ + LaneletPaths possiblePaths(const ConstLanelet& startPoint, const PossiblePathsParams& params) const; + /** @brief Determines possible routes from a given start lanelet that are "minRoutingCost"-long. * - * @return possible paths that are at least as long as specified in 'minRoutingCost'. If a lanelet can be reached - * using different paths, only the one is included that requires the least number of lane changes and has minimum - * routing costs. "lanelet" itself is always included. - * @param startPoint Start lanelet - * @param minRoutingCost Costs that must be reached by a route. - * @param routingCostId ID of the routing cost module used - * @param allowLaneChanges Allow or forbid lane changes */ + * This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, + * params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default). + */ LaneletPaths possiblePaths(const ConstLanelet& startPoint, double minRoutingCost, RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const; - /** @brief Determines possible paths from a given start lanelet that are "minLanelets"-long. * - * @return possible paths that are at least as long as specified number of lanelets. If a lanelet can be reached - * using different paths, only the one is included that requires the least number of lane changes and has minimum - * routing costs. "lanelet" itself is always included. - * @param startPoint Start lanelet - * @param minLanelets Number of lanelets a route must be long - * @param allowLaneChanges Allow or forbid lane changes. Note that "lane changes" from a lanelet to an area do not - * count. - * @param routingCostId ID of the routing cost module used. This is important in cases where some of routing cost - * modules retuned an invalid edge weight and some not. + /** @brief Determines possible paths from a given start lanelet that are "minLanelets"-long. + * + * This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, + * params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default). */ LaneletPaths possiblePaths(const ConstLanelet& startPoint, uint32_t minLanelets, bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const; + /** + * @brief Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePathsParams + * @return possible paths that are at least as long as specified in 'minRoutingCost'. "targetLanelet" itself is + * always included if it is in the routing graph. + * @param targetLanelet Destination lanelet + * @param params Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details. + * @throws InvalidInputError if neither elementLimit nor costLimit is valid in params */ + LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, const PossiblePathsParams& params) const; + /** @brief Determines possible routes that reach the given lanelet and are "minRoutingCost" long. - * @return possible paths that are at least as long as specified in 'minRoutingCost'. "lanelet" itself is always - * included. - * @param targetLanelet Start lanelet - * @param minRoutingCost Costs that must be reached by a route. - * @param routingCostId ID of the routing cost module used - * @param allowLaneChanges Allow or forbid lane changes */ + * + * This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, + * params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default). */ LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, double minRoutingCost, RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const; /** @brief Determines possible paths towards a destination lanelet that are "minLanelets"-long. - * @return possible routes that are at least as long as specified number of lanelets. The last lanelet will aways be - * "targetLanelet" (or nothing if it is not part of the graph). - * @param targetLanelet target lanelet - * @param minLanelets Number of lanelets a route must be long - * @param allowLaneChanges Allow or forbid lane changes. Note that "lane changes" from a lanelet to an area do not - * count. - * @param routingCostId ID of the routing cost module used. This is important in cases where some of routing cost - * modules retuned an invalid edge weight and some not. */ + * + * This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, + * params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default). */ LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, uint32_t minLanelets, bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const; + //! Similar to RoutingGraph::possiblePaths, but also considers areas. + LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, + const PossiblePathsParams& params) const; + //! Similar to RoutingGraph::possiblePaths, but also considers areas. LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, double minRoutingCost, RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const; @@ -385,7 +486,7 @@ class RoutingGraph { Errors checkValidity(bool throwOnError = true) const; /** - * Constructs the routing graph. Don't call this directly, use RoutingGraph::make instead. + * Constructs the routing graph. Don't call this directly, use RoutingGraph::build instead. */ RoutingGraph(std::unique_ptr&& graph, lanelet::LaneletSubmapConstPtr&& passableMap); diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraphContainer.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraphContainer.h index b0890eb5ef8..666637cfacd 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraphContainer.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/RoutingGraphContainer.h @@ -3,10 +3,12 @@ #include #include #include + #include #include -#include "Route.h" -#include "RoutingGraph.h" + +#include "lanelet2_routing/Route.h" +#include "lanelet2_routing/RoutingGraph.h" namespace lanelet { namespace routing { diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/Types.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/Types.h index b6057d921dc..15cc66c8477 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/Types.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/Types.h @@ -1,8 +1,10 @@ #pragma once #include #include + #include -#include "Forward.h" + +#include "lanelet2_routing/Forward.h" namespace lanelet { namespace routing { diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/Graph.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/Graph.h index 7429bb5ba65..3bdc80a3b24 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/Graph.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/Graph.h @@ -1,12 +1,14 @@ #pragma once -#include #include + #include #include #include #include -#include "../Exceptions.h" + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/Forward.h" namespace lanelet { namespace routing { @@ -116,20 +118,20 @@ class Graph { inline size_t numRoutingCosts() const noexcept { return numRoutingCosts_; } inline const LaneletOrAreaToVertex& vertexLookup() const noexcept { return laneletOrAreaToVertex_; } - FilteredGraph withLaneChanges(RoutingCostId routingCostId = 0) { + FilteredGraph withLaneChanges(RoutingCostId routingCostId = 0) const { return getFilteredGraph(routingCostId, RelationType::Successor | RelationType::Left | RelationType::Right); } - FilteredGraph withoutLaneChanges(RoutingCostId routingCostId = 0) { + FilteredGraph withoutLaneChanges(RoutingCostId routingCostId = 0) const { return getFilteredGraph(routingCostId, RelationType::Successor); } - FilteredGraph withAreasAndLaneChanges(RoutingCostId routingCostId = 0) { + FilteredGraph withAreasAndLaneChanges(RoutingCostId routingCostId = 0) const { return getFilteredGraph(routingCostId, RelationType::Successor | RelationType::Left | RelationType::Right | RelationType::Area); } - FilteredGraph withAreasWithoutLaneChanges(RoutingCostId routingCostId = 0) { + FilteredGraph withAreasWithoutLaneChanges(RoutingCostId routingCostId = 0) const { return getFilteredGraph(routingCostId, RelationType::Successor | RelationType::Area); } @@ -167,7 +169,7 @@ class Graph { //! add new lanelet to graph inline Vertex addVertex(const typename BaseGraphT::vertex_property_type& property) { - GraphType::vertex_descriptor vd; + GraphType::vertex_descriptor vd = 0; vd = boost::add_vertex(graph_); graph_[vd] = property; laneletOrAreaToVertex_.emplace(property.get(), vd); diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/GraphUtils.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/GraphUtils.h index ee10b6ffecd..5faf5bdadcc 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/GraphUtils.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/GraphUtils.h @@ -1,8 +1,10 @@ #pragma once #include + #include #include -#include "Graph.h" + +#include "lanelet2_routing/internal/Graph.h" namespace lanelet { namespace routing { @@ -115,7 +117,7 @@ class OriginalGraphFilter { } } bool operator()(const GraphTraits::edge_descriptor& v) const { - auto& edge = (*g_)[v]; + const auto& edge = (*g_)[v]; return edge.costId == costId_ && (edge.relation & filterMask_) != RelationType::None; } @@ -138,32 +140,24 @@ class OnRouteFilter { const RouteLanelets* onRoute_{}; }; -//! Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) -class OnlyDrivableEdgesFilter { +template +class EdgeRelationFilter { public: - OnlyDrivableEdgesFilter() = default; - explicit OnlyDrivableEdgesFilter(const OriginalGraph& originalGraph) : originalGraph_{&originalGraph} {} + EdgeRelationFilter() = default; + explicit EdgeRelationFilter(const GraphType& graph) : graph_{&graph} {} bool operator()(FilteredRoutingGraph::edge_descriptor e) const { - auto type = (*originalGraph_)[e].relation; - return (type & (RelationType::Successor | RelationType::Left | RelationType::Right)) != RelationType::None; + auto type = (*graph_)[e].relation; + return (type & Relation) != RelationType::None; } private: - const OriginalGraph* originalGraph_{}; + const GraphType* graph_{}; }; -class OnlyConflictingFilter { - public: - OnlyConflictingFilter() = default; - explicit OnlyConflictingFilter(const OriginalGraph& originalGraph) : originalGraph_{&originalGraph} {} - bool operator()(FilteredRoutingGraph::edge_descriptor e) const { - auto type = (*originalGraph_)[e].relation; - return type == RelationType::Conflicting; - } - - private: - const OriginalGraph* originalGraph_{}; -}; +//! Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) +using OnlyDrivableEdgesFilter = + EdgeRelationFilter; +using OnlyConflictingFilter = EdgeRelationFilter; //! Removes conflicting edges from the graph class NoConflictingFilter { @@ -205,6 +199,24 @@ class NextToRouteFilter { const OriginalGraph* originalGraph_{}; }; +//! Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) OR leave the route at its end +class OnlyDrivableEdgesWithinFilter { + using SuccessorFilter = EdgeRelationFilter; + + public: + OnlyDrivableEdgesWithinFilter() = default; + explicit OnlyDrivableEdgesWithinFilter(RouteLanelets withinLanelets, const OriginalGraph& originalGraph) + : drivableEdge_{originalGraph}, successorEdge_{originalGraph}, withinLanelets_{std::move(withinLanelets)} {} + bool operator()(FilteredRoutingGraph::edge_descriptor e) const { + return drivableEdge_(e) && (!successorEdge_(e) || withinLanelets_.find(e.m_source) == withinLanelets_.end()); + } + + private: + OnlyDrivableEdgesFilter drivableEdge_; + SuccessorFilter successorEdge_; + RouteLanelets withinLanelets_; +}; + //! Finds vertices that are in conflict or adjacent to some vertices (not reachable though bidirectional lane changes) class ConflictingSectionFilter { public: @@ -378,7 +390,7 @@ using OnRouteGraph = boost::filtered_graph; using NoConflictingGraph = boost::filtered_graph; using OnlyConflictingGraph = boost::filtered_graph; -using NextToRouteGraph = boost::filtered_graph; +using NextToRouteGraph = boost::filtered_graph; using ConflictOrAdjacentToRouteGraph = boost::filtered_graph; using ConflictsWithPathGraph = boost::filtered_graph; diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RouteBuilder.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RouteBuilder.h index 63d89a09220..1f6bf856f50 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RouteBuilder.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RouteBuilder.h @@ -1,7 +1,7 @@ #pragma once -#include "Graph.h" -#include "LaneletPath.h" -#include "Route.h" +#include "lanelet2_routing/LaneletPath.h" +#include "lanelet2_routing/Route.h" +#include "lanelet2_routing/internal/Graph.h" namespace lanelet { namespace routing { diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphBuilder.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphBuilder.h index 4c958c74105..92a66d533ce 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphBuilder.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphBuilder.h @@ -1,7 +1,8 @@ #pragma once #include -#include "Graph.h" -#include "RoutingGraph.h" + +#include "lanelet2_routing/RoutingGraph.h" +#include "lanelet2_routing/internal/Graph.h" namespace lanelet { class LaneletLayer; @@ -23,8 +24,9 @@ class RoutingGraphBuilder { using PointsLaneletMapIt = PointsLaneletMap::iterator; using PointsLaneletMapResult = std::pair; - ConstLanelets getPassableLanelets(const LaneletLayer& lanelets, const traffic_rules::TrafficRules& trafficRules); - ConstAreas getPassableAreas(const AreaLayer& areas, const traffic_rules::TrafficRules& trafficRules); + static ConstLanelets getPassableLanelets(const LaneletLayer& lanelets, + const traffic_rules::TrafficRules& trafficRules); + static ConstAreas getPassableAreas(const AreaLayer& areas, const traffic_rules::TrafficRules& trafficRules); void appendBidirectionalLanelets(ConstLanelets& llts); void addLaneletsToGraph(ConstLanelets& llts); void addAreasToGraph(ConstAreas& areas); @@ -44,7 +46,7 @@ class RoutingGraphBuilder { //! Adds the first and last points of a lanelet to the search index void addPointsToSearchIndex(const ConstLanelet& ll); bool hasEdge(const ConstLanelet& from, const ConstLanelet& to); - void assignLaneChangeCosts(const ConstLanelets& froms, const ConstLanelets& tos, const RelationType& relation); + void assignLaneChangeCosts(ConstLanelets froms, ConstLanelets tos, const RelationType& relation); /** @brief Assigns routing costs of each routing cost module to a relation between two lanelets * @param from Start lanelet diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphVisualization.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphVisualization.h index f430544ad5e..9ddcf158f76 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphVisualization.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/RoutingGraphVisualization.h @@ -3,9 +3,10 @@ #include #include #include -#include "Exceptions.h" -#include "Forward.h" -#include "internal/Graph.h" + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/internal/Graph.h" namespace lanelet { diff --git a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/ShortestPath.h b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/ShortestPath.h index dedcab2a05a..9e673703c40 100644 --- a/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/ShortestPath.h +++ b/lanelet2/lanelet2_routing/include/lanelet2_routing/internal/ShortestPath.h @@ -2,9 +2,10 @@ #include #include #include -#include "Exceptions.h" -#include "Graph.h" -#include "GraphUtils.h" + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/internal/Graph.h" +#include "lanelet2_routing/internal/GraphUtils.h" namespace lanelet { namespace routing { diff --git a/lanelet2/lanelet2_routing/package.xml b/lanelet2/lanelet2_routing/package.xml index ba7005d6839..1190b8899a8 100644 --- a/lanelet2/lanelet2_routing/package.xml +++ b/lanelet2/lanelet2_routing/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_routing - 0.9.0 + 1.1.1 Routing module for lanelet2 BSD @@ -9,14 +10,18 @@ Matthias Mayr https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest boost lanelet2_core lanelet2_traffic_rules + catkin + ament_cmake diff --git a/lanelet2/lanelet2_routing/src/LaneletPath.cpp b/lanelet2/lanelet2_routing/src/LaneletPath.cpp index bd3513d5b2b..a1392938dea 100644 --- a/lanelet2/lanelet2_routing/src/LaneletPath.cpp +++ b/lanelet2/lanelet2_routing/src/LaneletPath.cpp @@ -1,9 +1,328 @@ -#include "LaneletPath.h" +#include "lanelet2_routing/LaneletPath.h" + +#include #include namespace lanelet { namespace routing { +namespace { + +ConstLineStrings3d extractBetween(const ConstLineStrings3d& wrappedLS, const size_t start, const size_t end) { + auto startIt = std::next(wrappedLS.begin(), start); + auto endIt = std::next(wrappedLS.begin(), end); + auto size = (start >= end) ? wrappedLS.size() - (start - end) - 1 : end - start - 1; + ConstLineStrings3d between; + between.reserve(size); + if (start >= end) { + between.insert(between.end(), std::next(startIt), wrappedLS.end()); + between.insert(between.end(), wrappedLS.begin(), endIt); + } else { + between.insert(between.end(), std::next(startIt), endIt); + } + return between; +} + +std::pair extractBounds(const ConstArea& area, + const ConstLineString3d& rearCommon, + const ConstLineString3d& frontCommon) { + const auto& bounds = area.outerBound(); + auto frontIt = std::find(bounds.begin(), bounds.end(), frontCommon); + if (frontIt == bounds.end()) { + throw InvalidInputError("line string front not found"); + } + auto endIt = std::find(bounds.begin(), bounds.end(), rearCommon); + if (endIt == bounds.end()) { + throw InvalidInputError("line string rear not found"); + } + auto start = std::distance(bounds.begin(), frontIt); + auto end = std::distance(bounds.begin(), endIt); + return std::make_pair(extractBetween(bounds, end, start), extractBetween(bounds, start, end)); +} + +ConstLineStrings3d extractExceptBorder(const ConstArea& area, const ConstLineString3d& border) { + const auto& bounds = area.outerBound(); + auto frontIt = std::find_if(bounds.begin(), bounds.end(), [&border](auto& ls) { return ls == border; }); + if (frontIt == bounds.end()) { + throw InvalidInputError("Given line string not in area"); + } + auto idx = std::distance(bounds.begin(), frontIt); + return extractBetween(bounds, idx, idx); +} + +void appendLineStrings(const ConstLineStrings3d& lss, BasicLineString3d& target, const bool reversed, + const bool omitLast, const bool omitFirst) { + auto compound = CompoundLineString3d(lss); + if (compound.size() < ((omitLast || omitFirst) ? (omitFirst && omitLast) ? 3 : 2 : 1)) { + return; + } + if (!reversed) { + target.insert(target.end(), std::next(compound.basicBegin(), omitFirst ? 1 : 0), + std::prev(compound.basicEnd(), omitLast ? 1 : 0)); + } else { + const auto& basicLS = compound.basicLineString(); + target.insert(target.end(), std::next(basicLS.rbegin(), omitFirst ? 1 : 0), + std::prev(basicLS.rend(), omitLast ? 1 : 0)); + } +} + +void appendLineStringsExceptFirst(const ConstLineStrings3d& lss, BasicLineString3d& target, const bool reversed) { + appendLineStrings(lss, target, reversed, false, true); +} + +void appendLineStrings(const ConstLineStrings3d& lss, BasicLineString3d& target) { + appendLineStrings(lss, target, false, false, false); +} + +void appendLineStringsExceptFirstAndLast(const ConstLineStrings3d& lss, BasicLineString3d& target) { + appendLineStrings(lss, target, false, true, true); +} + +struct Head { + ConstLaneletOrArea cur; + Optional next; +}; + +enum class LaneletAdjacency { Following, Preceding, Left, Right }; +struct LaneletPairAdjacency { + LaneletAdjacency ll; + LaneletAdjacency other; +}; +struct AdjacencyAndBorder { + LaneletAdjacency adjacency{LaneletAdjacency::Preceding}; + ConstLineString3d border; +}; +struct BoundsResult { + Optional prevBorder; + Optional llAdjacency; + BasicPolygon3d left; + BasicPolygon3d right; +}; + +Optional getLaneletAdjacency(const ConstLanelet& ll, const ConstArea& ar) { + auto res = geometry::determineCommonLineFollowing(ar, ll); + if (res) { + return AdjacencyAndBorder{LaneletAdjacency::Following, *res}; + } + res = geometry::determineCommonLinePreceding(ll, ar); + if (res) { + return AdjacencyAndBorder{LaneletAdjacency::Preceding, *res}; + } + if (geometry::leftOf(ll, ar)) { + return AdjacencyAndBorder{LaneletAdjacency::Right, ll.leftBound().invert()}; // must be inverted relative to area + } + if (geometry::rightOf(ll, ar)) { + return AdjacencyAndBorder{LaneletAdjacency::Left, ll.rightBound()}; // must be inverted relative to area + } + return {}; +} + +LaneletPairAdjacency getLaneletAdjacency(const ConstLanelet& ll, const ConstLanelet& other) { + if (geometry::follows(ll, other)) { + return LaneletPairAdjacency{LaneletAdjacency::Preceding, LaneletAdjacency::Following}; + } + if (geometry::follows(other, ll)) { + return LaneletPairAdjacency{LaneletAdjacency::Following, LaneletAdjacency::Preceding}; + } + if (geometry::leftOf(other, ll)) { + return LaneletPairAdjacency{LaneletAdjacency::Right, LaneletAdjacency::Left}; + } + if (geometry::rightOf(other, ll)) { + return LaneletPairAdjacency{LaneletAdjacency::Left, LaneletAdjacency::Right}; + } + return {}; +} + +void appendExtractedClockwise(BasicPolygon3d& target, const ConstLanelet& ll, const LaneletAdjacency& adj) { + if (adj == LaneletAdjacency::Right) { + target.insert(target.end(), ll.leftBound().basicBegin() + 1, ll.leftBound().basicEnd()); + } else if (adj == LaneletAdjacency::Preceding) { + target.emplace_back(utils::toBasicPoint(ll.rightBound().back())); + } else if (adj == LaneletAdjacency::Left) { + target.insert(target.end(), ll.rightBound().invert().basicBegin() + 1, ll.rightBound().invert().basicEnd()); + } else if (adj == LaneletAdjacency::Following) { + target.emplace_back(utils::toBasicPoint(ll.leftBound().front())); + } else { + throw InvalidInputError("Invalid adjacency"); + } +} + +void appendExtractedCounterClockwise(BasicPolygon3d& target, const ConstLanelet& ll, const LaneletAdjacency& adj) { + if (adj == LaneletAdjacency::Right) { + target.insert(target.end(), ll.leftBound().invert().basicBegin() + 1, ll.leftBound().invert().basicEnd()); + } else if (adj == LaneletAdjacency::Preceding) { + target.emplace_back(utils::toBasicPoint(ll.leftBound().back())); + } else if (adj == LaneletAdjacency::Left) { + target.insert(target.end(), ll.rightBound().basicBegin() + 1, ll.rightBound().basicEnd()); + } else if (adj == LaneletAdjacency::Following) { + target.emplace_back(utils::toBasicPoint(ll.rightBound().front())); + } else { + throw InvalidInputError("Invalid adjacency"); + } +} + +void appendFirst(BasicPolygon3d& poly, const ConstLanelet& ll, const LaneletAdjacency& in) { + if (in == LaneletAdjacency::Following) { + poly.emplace_back(utils::toBasicPoint(ll.leftBound().front())); + } else if (in == LaneletAdjacency::Right) { + poly.emplace_back(utils::toBasicPoint(ll.leftBound().back())); + } else if (in == LaneletAdjacency::Preceding) { + poly.emplace_back(utils::toBasicPoint(ll.rightBound().back())); + } else if (in == LaneletAdjacency::Left) { + poly.emplace_back(utils::toBasicPoint(ll.rightBound().front())); + } else { + throw InvalidInputError("Invalid adjacency"); + } +} + +using AdjMap = std::map; +void appendLaneletBoundsLeft(BasicPolygon3d& poly, const ConstLanelet& ll, const LaneletAdjacency& in, + const LaneletAdjacency& out) { + const AdjMap cw{{LaneletAdjacency::Left, LaneletAdjacency::Following}, + {LaneletAdjacency::Following, LaneletAdjacency::Right}, + {LaneletAdjacency::Right, LaneletAdjacency::Preceding}, + {LaneletAdjacency::Preceding, LaneletAdjacency::Left}}; + auto cwNext = cw.at(in); + while (cwNext != out) { + appendExtractedClockwise(poly, ll, cwNext); + cwNext = cw.at(cwNext); + } +} + +void appendLaneletBoundsRight(BasicPolygon3d& poly, const ConstLanelet& ll, const LaneletAdjacency& in, + const LaneletAdjacency& out) { + const AdjMap ccw{{LaneletAdjacency::Left, LaneletAdjacency::Preceding}, + {LaneletAdjacency::Preceding, LaneletAdjacency::Right}, + {LaneletAdjacency::Right, LaneletAdjacency::Following}, + {LaneletAdjacency::Following, LaneletAdjacency::Left}}; + auto ccwNext = ccw.at(in); + while (ccwNext != out) { + appendExtractedCounterClockwise(poly, ll, ccwNext); + ccwNext = ccw.at(ccwNext); + } +} + +void appendLaneletBounds(BoundsResult& br, const ConstLanelet& ll, const LaneletAdjacency& in, + const LaneletAdjacency& out) { + appendLaneletBoundsLeft(br.left, ll, in, out); + if (in != out) { + appendLaneletBoundsRight(br.right, ll, in, out); + } +} +/** + * @brief update border between cur area and next primitive + * @param br + * @param head + * @return border between cur area and next primitive in cur area + */ +ConstLineString3d getBorder(BoundsResult& br, const Head& head) { + if (head.next->isArea()) { + br.prevBorder = geometry::determineCommonLine(*(head.next->area()), *head.cur.area()); + if (!br.prevBorder) { + throw GeometryError("No shared line string found between adjacent primitives"); + } + return br.prevBorder->invert(); + } + auto adj = getLaneletAdjacency(*head.next->lanelet(), *head.cur.area()); + if (!adj) { + throw GeometryError("No shared line string found between adjacent primitives"); + } + br.llAdjacency = adj->adjacency; + return adj->border; +} + +void addLaneletPair(BoundsResult& res, const Head& head, const bool notTail = true) { + auto adj = getLaneletAdjacency(*head.cur.lanelet(), *head.next->lanelet()); + if (!notTail) { + appendFirst(res.left, *head.cur.lanelet(), adj.ll); + } + appendLaneletBounds(res, *head.cur.lanelet(), notTail ? *res.llAdjacency : adj.ll, adj.ll); + res.llAdjacency = adj.other; +} + +void addLaneletAreaHead(BoundsResult& res, const Head& head, const bool notTail = true) { + auto adj = getLaneletAdjacency(*head.cur.lanelet(), *head.next->area()); + if (!adj) { + throw std::runtime_error("Did not find adjacency"); + } + if (!notTail) { + appendFirst(res.left, *head.cur.lanelet(), adj->adjacency); + } + appendLaneletBounds(res, *head.cur.lanelet(), notTail ? *res.llAdjacency : adj->adjacency, adj->adjacency); + res.prevBorder = adj->border; +} + +void addLanelet(BoundsResult& res, const Head& head) { + if (!head.next) { + appendLaneletBounds(res, *head.cur.lanelet(), *res.llAdjacency, *res.llAdjacency); + res.left.pop_back(); // ugly AF + } else if (head.next->isLanelet()) { + addLaneletPair(res, head); + } else { + addLaneletAreaHead(res, head); + } +} + +void addFirstArea(BoundsResult& res, const Head& head) { + auto thisBorder = getBorder(res, head); + if (!head.cur.area()) { + throw GeometryError("Uninitialized area"); + } + appendLineStrings(extractExceptBorder(*head.cur.area(), thisBorder), res.left); +} + +void addFirstLanelet(BoundsResult& res, const Head& head) { + if (!head.next) { + throw std::runtime_error("Following primitive not intialized"); + } + if (head.next->isLanelet()) { + addLaneletPair(res, head, false); + } else { + addLaneletAreaHead(res, head, false); + } +} + +void addArea(BoundsResult& br, const Head& head) { + auto oldBorder = *br.prevBorder; + auto border = getBorder(br, head); + auto bounds = extractBounds(*head.cur.area(), oldBorder, border); + appendLineStringsExceptFirst(bounds.first, br.left, false); + appendLineStringsExceptFirst(bounds.second, br.right, true); +} + +BoundsResult appendTail(const Head& head) { + BoundsResult res; + if (!head.next) { + throw InvalidInputError("Tail must have successor, results must be empty"); + } + if (head.cur.isArea()) { + addFirstArea(res, head); + } else { + addFirstLanelet(res, head); + } + return res; +} + +void appendFinalArea(const Head& head, BoundsResult& br) { + if (!br.prevBorder) { + throw InvalidInputError("border not given for area"); + } + appendLineStringsExceptFirstAndLast(extractExceptBorder(*head.cur.area(), *br.prevBorder), br.left); +} + +void appendBounds(const Head& head, BoundsResult& br) { + if (head.cur.isLanelet()) { + addLanelet(br, head); + } else { + if (!head.next) { + appendFinalArea(head, br); + } else { + addArea(br, head); + } + } +} +} // namespace + LaneletSequence LaneletPath::getRemainingLane(LaneletPath::const_iterator laneletPosition) const { ConstLanelets lane; while (laneletPosition != lanelets_.end()) { @@ -15,5 +334,21 @@ LaneletSequence LaneletPath::getRemainingLane(LaneletPath::const_iterator lanele } return lane; } + +BasicPolygon3d getEnclosingPolygon3d(const LaneletOrAreaPath& path) { + if (path.empty()) { + return BasicPolygon3d(); + } + if (path.size() == 1ul) { + return path.front().boundingPolygon().basicPolygon(); + } + auto boundsResult = appendTail(Head{path[0], path[1]}); + for (size_t curIdx = 1; curIdx < path.size(); ++curIdx) { + appendBounds(Head{path[curIdx], (curIdx + 1 < path.size()) ? path[curIdx + 1] : Optional()}, + boundsResult); + } + boundsResult.left.insert(boundsResult.left.end(), boundsResult.right.rbegin(), boundsResult.right.rend()); + return std::move(boundsResult.left); +} } // namespace routing } // namespace lanelet diff --git a/lanelet2/lanelet2_routing/src/Route.cpp b/lanelet2/lanelet2_routing/src/Route.cpp index 8eac436e268..21a8069d77d 100644 --- a/lanelet2/lanelet2_routing/src/Route.cpp +++ b/lanelet2/lanelet2_routing/src/Route.cpp @@ -1,15 +1,17 @@ -#include "Route.h" +#include "lanelet2_routing/Route.h" + #include #include #include #include + #include #include -#include "Exceptions.h" -#include "internal/Graph.h" -#include "internal/GraphUtils.h" -#include "internal/ShortestPath.h" -#include + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/internal/Graph.h" +#include "lanelet2_routing/internal/GraphUtils.h" +#include "lanelet2_routing/internal/ShortestPath.h" namespace lanelet { namespace routing { @@ -378,7 +380,7 @@ Route::Errors Route::checkValidity(bool throwOnError) const { std::for_each(edges.first, edges.second, [&](internal::RouteGraph::Edge e) { // get reverse edge decltype(e) eRev; - bool exists; + bool exists = false; std::tie(eRev, exists) = boost::edge(boost::target(e, g), boost::source(e, g), g); auto sourceId = g[boost::source(e, g)].lanelet.id(); auto targetId = g[boost::target(e, g)].lanelet.id(); diff --git a/lanelet2/lanelet2_routing/src/RouteBuilder.cpp b/lanelet2/lanelet2_routing/src/RouteBuilder.cpp index fae747c25a2..9eee09439f2 100644 --- a/lanelet2/lanelet2_routing/src/RouteBuilder.cpp +++ b/lanelet2/lanelet2_routing/src/RouteBuilder.cpp @@ -1,15 +1,25 @@ -#include "internal/RouteBuilder.h" +#include "lanelet2_routing/internal/RouteBuilder.h" + +#include + #include #include #include -#include "internal/Graph.h" -#include "internal/GraphUtils.h" -#include "lanelet2_core/LaneletMap.h" + +#include "lanelet2_routing/internal/Graph.h" +#include "lanelet2_routing/internal/GraphUtils.h" namespace lanelet { namespace routing { namespace internal { namespace { +template +void breadthFirstSearch(const Graph& g, StartVertex v, Visitor vis) { + SparseColorMap cm; + boost::queue q; + boost::breadth_first_visit(g, v, q, vis, cm); +} + struct VisitationCount { bool isLeaf() const { return numFollowers + numLaneChangesOut == 0; } unsigned numFollowers{}; @@ -73,7 +83,7 @@ class VisitedLaneletGraph { //! Iterates the vertices of the graph template void forAllValidLanelets(Func&& f) const { - for (auto& vertex : visited_) { + for (const auto& vertex : visited_) { if (!!vertex.second && !vertex.second->isLeaf()) { f(vertex); } @@ -111,6 +121,58 @@ class VisitedLaneletGraph { const RouteLanelets* routeLanelets_{}; }; +//! Adaptor for boost graph. It is used to build the VisitedLaneletGraph. +class NeighbouringGraphVisitor : public boost::default_bfs_visitor { + public: + explicit NeighbouringGraphVisitor(VisitedLaneletGraph& counter) : counter_{&counter} {} + + // called by boost graph on a new vertex + template + void examine_vertex(LaneletVertexId v, const GraphType& /*g*/) { // NOLINT + counter_->init(v); + vCurr_ = v; + } + + // called directly after an all its edges + template + void examine_edge(NextToRouteGraph::edge_descriptor e, const GraphType& g) const { // NOLINT + assert(vCurr_ == boost::source(e, g) && "Breadth first search seems to iterate in a weird manner"); + counter_->add(vCurr_, e, g); + } + + private: + LaneletVertexId vCurr_{}; + VisitedLaneletGraph* counter_; +}; + +RouteLanelets getLeftAndRightLanelets(const LaneletVertexId& llt, const OriginalGraph& g) { + using LeftAndRightFilter = EdgeRelationFilter; + using LeftAndRightGraph = boost::filtered_graph; + class GraphVisitor : public boost::default_bfs_visitor { + public: + explicit GraphVisitor(RouteLanelets& lanelets) : lanelets_{&lanelets} {} + // called by boost graph on a new vertex + void examine_vertex(LaneletVertexId v, const LeftAndRightGraph& /*g*/) { // NOLINT + lanelets_->insert(v); + } + + private: + RouteLanelets* lanelets_; + }; + + LeftAndRightGraph graph{g, LeftAndRightFilter{g}}; + RouteLanelets leftAndRightLanelets; + breadthFirstSearch(graph, llt, GraphVisitor{leftAndRightLanelets}); + return leftAndRightLanelets; +} + +RouteLanelets lastLanelets(const std::vector& initialRoute, const OriginalGraph& originalGraph) { + if (initialRoute.empty() || initialRoute.front() == initialRoute.back()) { + return {}; + } + return getLeftAndRightLanelets(initialRoute.back(), originalGraph); +} + //! The visited lanelet graph initially also contains lanelets that are always conflicting with the route, but the route //! is not always conflicting with them. This class finds these cases. class PathsOutOfRouteFinder { @@ -210,27 +272,6 @@ class PathsOutOfRouteFinder { const RouteLanelets* llts_{}; }; -//! Adaptor for boost graph. It is used to build the VisitedLaneletGraph. -class NeighbouringGraphVisitor : public boost::default_bfs_visitor { - public: - explicit NeighbouringGraphVisitor(VisitedLaneletGraph& counter) : counter_{&counter} {} - // called by boost graph on a new vertex - void examine_vertex(LaneletVertexId v, const NextToRouteGraph& /*g*/) { // NOLINT - counter_->init(v); - vCurr_ = v; - } - - // called directly after an all its edges - void examine_edge(NextToRouteGraph::edge_descriptor e, const NextToRouteGraph& g) const { // NOLINT - assert(vCurr_ == boost::source(e, g) && "Breadth first search seems to iterate in a weird manner"); - counter_->add(vCurr_, e, g); - } - - private: - LaneletVertexId vCurr_{}; - VisitedLaneletGraph* counter_; -}; - //! A visitor that constructs the final route object by searching though the graph of lanelets on the route. class RouteConstructionVisitor : public boost::default_bfs_visitor { public: @@ -288,7 +329,7 @@ class RouteConstructionVisitor : public boost::default_bfs_visitor { } } - bool isDifferentLane(OnRouteGraph::edge_descriptor e, const OnRouteGraph& g) const { + static bool isDifferentLane(OnRouteGraph::edge_descriptor e, const OnRouteGraph& g) { // we increment the lane id whenever the vertex has more than one predecessor or the singele predecessor has // multiple follower. Non-Successor edges are always a different lane. if (g[e].relation != RelationType::Successor) { @@ -328,13 +369,6 @@ class RouteConstructionVisitor : public boost::default_bfs_visitor { LaneletVertexId sourceElem_{}; }; -template -void breadthFirstSearch(const Graph& g, StartVertex v, Visitor vis) { - SparseColorMap cm; - boost::queue q; - boost::breadth_first_visit(g, v, q, vis, cm); -} - //! This is the class that handles building the route. It iteratively adds lanelets initial route (i.e. the shortest //! path) that fulfill the definition of a lanelet on the route. This is done until convergence is reached. class RouteUnderConstruction { @@ -345,7 +379,8 @@ class RouteUnderConstruction { laneletsOnRoute_{initialRoute.begin(), initialRoute.end()}, originalGraph_{originalGraph}, routeGraph_{originalGraph_, {}, OnRouteFilter{laneletsOnRoute_}}, - nextToRouteGraph_{originalGraph_, OnlyDrivableEdgesFilter{originalGraph_}, + nextToRouteGraph_{originalGraph_, + OnlyDrivableEdgesWithinFilter{lastLanelets(initialRoute, originalGraph), originalGraph_}, NextToRouteFilter{laneletsOnRoute_, originalGraph_}}, laneletVisitor_{laneletsOnRoute_}, pathOutOfRouteFinder_{originalGraph_, laneletsOnRoute_} {} @@ -410,9 +445,6 @@ Optional RouteBuilder::getRouteFromShortestPath(const LaneletPath& path, // get the container for all the things RouteUnderConstruction routeUnderConstruction{vertexIds, originalGraph}; - //! @todo deleteme - auto ids = utils::transform(graph_.get().m_vertices, [&](auto& v) { return v.m_property.laneletOrArea.id(); }); - bool progress = true; while (progress) { progress = routeUnderConstruction.addAdjacentLaneletsToRoute(); diff --git a/lanelet2/lanelet2_routing/src/RoutingCost.cpp b/lanelet2/lanelet2_routing/src/RoutingCost.cpp index 4950364b0d2..047bab6da40 100644 --- a/lanelet2/lanelet2_routing/src/RoutingCost.cpp +++ b/lanelet2/lanelet2_routing/src/RoutingCost.cpp @@ -1,7 +1,9 @@ -#include "RoutingCost.h" +#include "lanelet2_routing/RoutingCost.h" + #include #include #include + #include namespace lanelet { @@ -19,21 +21,20 @@ Velocity speedLimit(const traffic_rules::TrafficRules& trafficRules, const Const } } // namespace -double RoutingCostTravelTime::travelTime(const traffic_rules::TrafficRules& trafficRules, - const ConstLanelet& ll) const { +double RoutingCostTravelTime::travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstLanelet& ll) { auto limit = speedLimit(trafficRules, ll); return units::SecondQuantity(geometry::approximatedLength2d(ll) * units::Meter() / limit).value(); } -double RoutingCostTravelTime::travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstArea& ar) const { +double RoutingCostTravelTime::travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstArea& ar) { auto limit = speedLimit(trafficRules, ar); auto diameter = boost::geometry::perimeter(utils::to2D(ar.outerBoundPolygon())); return units::SecondQuantity(diameter * units::Meter() / limit).value(); } -double RoutingCostDistance::length(const ConstLanelet& ll) const noexcept { return geometry::approximatedLength2d(ll); } +double RoutingCostDistance::length(const ConstLanelet& ll) noexcept { return geometry::approximatedLength2d(ll); } -double RoutingCostDistance::length(const ConstArea& ar) const noexcept { +double RoutingCostDistance::length(const ConstArea& ar) noexcept { return double(boost::geometry::perimeter(utils::to2D(ar.outerBoundPolygon()))); } } // namespace routing diff --git a/lanelet2/lanelet2_routing/src/RoutingGraph.cpp b/lanelet2/lanelet2_routing/src/RoutingGraph.cpp index 2010070d7d1..057db0bf906 100644 --- a/lanelet2/lanelet2_routing/src/RoutingGraph.cpp +++ b/lanelet2/lanelet2_routing/src/RoutingGraph.cpp @@ -1,4 +1,5 @@ -#include "RoutingGraph.h" +#include "lanelet2_routing/RoutingGraph.h" + #include #include #include @@ -6,23 +7,24 @@ #include #include #include + #include #include #include // Asserts #include -#include #include -#include "Exceptions.h" -#include "Forward.h" -#include "Route.h" -#include "internal/Graph.h" -#include "internal/GraphUtils.h" -#include "internal/RouteBuilder.h" -#include "internal/RoutingGraphBuilder.h" -#include "internal/ShortestPath.h" + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/Route.h" +#include "lanelet2_routing/internal/Graph.h" +#include "lanelet2_routing/internal/GraphUtils.h" +#include "lanelet2_routing/internal/RouteBuilder.h" +#include "lanelet2_routing/internal/RoutingGraphBuilder.h" +#include "lanelet2_routing/internal/ShortestPath.h" // needs to be included after shotestPath due to some overload resolution quirks -#include "internal/RoutingGraphVisualization.h" +#include "lanelet2_routing/internal/RoutingGraphVisualization.h" namespace lanelet { namespace routing { @@ -71,7 +73,8 @@ struct MoreLaneChanges { }; /** @brief Simple helper function to combine shortest paths */ -bool addToPath(ConstLanelets& path, const Optional& newElements) { +template +bool addToPath(T& path, const Optional& newElements) { if (newElements) { path.insert(path.end(), ++newElements->begin(), newElements->end()); return true; // NOLINT @@ -206,7 +209,7 @@ struct GetGraph { template std::vector buildPath(const DijkstraSearchMap& map, LaneletVertexId vertex, GraphT g) { - auto* currInfo = &map.at(vertex); + const auto* currInfo = &map.at(vertex); auto size = currInfo->length; std::vector path(size); while (true) { @@ -221,13 +224,49 @@ std::vector buildPath(const DijkstraSearchMap& map, return path; } -template +template +struct CombinedCost { + CombinedCost(const Cost1& c1, const Cost2& c2) : c1{c1}, c2{c2} {} + template + inline bool operator()(const T& v) const { + return c1(v) && c2(v); + } + Cost1 c1; + Cost2 c2; +}; + +template +struct StopIfLaneletsMoreThan { + explicit StopIfLaneletsMoreThan(size_t n) : n{n} {} + template + inline bool operator()(const T& v) const { + return Eq ? v.length <= n : v.length < n; + } + size_t n; +}; + +template +struct StopIfCostMoreThan { + explicit StopIfCostMoreThan(double c) : c{c} {} + template + inline bool operator()(const T& v) const { + return Eq ? v.cost <= c : v.cost < c; + } + + template + CombinedCost operator&&(const Other& o) { + return {*this, o}; + } + double c; +}; + +template std::vector possiblePathsImpl(const GraphType::vertex_descriptor& start, const FilteredRoutingGraph& graph, Func stopCriterion) { auto g = GetGraph{}(graph); DijkstraStyleSearch search(g); search.query(start, stopCriterion); - auto keepPath = [&](auto& vertex) { return vertex.second.isLeaf && !vertex.second.predicate; }; + auto keepPath = [&](auto& vertex) { return vertex.second.isLeaf && (KeepShorter || !vertex.second.predicate); }; auto numPaths = size_t(std::count_if(search.getMap().begin(), search.getMap().end(), keepPath)); std::vector result; result.reserve(numPaths); @@ -240,6 +279,36 @@ std::vector possiblePathsImpl(const GraphType::vertex_descriptor& return result; } +template +std::vector possiblePathsImpl(const GraphType::vertex_descriptor& start, + const FilteredRoutingGraph& graph, const PossiblePathsParams& params) { + if (params.routingCostLimit && !params.elementLimit && !params.includeShorterPaths) { + return possiblePathsImpl(start, graph, + StopIfCostMoreThan<>(*params.routingCostLimit)); + } + if (params.routingCostLimit && !params.elementLimit && params.includeShorterPaths) { + return possiblePathsImpl(start, graph, + StopIfCostMoreThan<>(*params.routingCostLimit)); + } + if (!params.routingCostLimit && params.elementLimit && !params.includeShorterPaths) { + return possiblePathsImpl(start, graph, + StopIfLaneletsMoreThan<>(*params.elementLimit)); + } + if (!params.routingCostLimit && params.elementLimit && params.includeShorterPaths) { + return possiblePathsImpl(start, graph, + StopIfLaneletsMoreThan<>(*params.elementLimit)); + } + if (params.routingCostLimit && params.elementLimit && !params.includeShorterPaths) { + return possiblePathsImpl( + start, graph, StopIfCostMoreThan<>(*params.routingCostLimit) && StopIfLaneletsMoreThan<>(*params.elementLimit)); + } + if (params.routingCostLimit && params.elementLimit && params.includeShorterPaths) { + return possiblePathsImpl( + start, graph, StopIfCostMoreThan<>(*params.routingCostLimit) && StopIfLaneletsMoreThan<>(*params.elementLimit)); + } + throw InvalidInputError("Possible paths called with invalid cost limit AND invalid element limit!"); +} + template std::vector reachableSetImpl(const GraphType::vertex_descriptor& start, const FilteredRoutingGraph& graph, Func stopCriterion) { @@ -256,24 +325,47 @@ std::vector reachableSetImpl(const GraphType::vertex_descriptor& sta return result; } -template -struct StopIfLaneletsMoreThan { - explicit StopIfLaneletsMoreThan(size_t n) : n{n} {} - template - inline bool operator()(const T& v) const { - return Eq ? v.length <= n : v.length < n; +template +Optional shortestPathImpl(const PrimT& from, const PrimT& to, RoutingCostId routingCostId, bool withLaneChanges, + bool withAreas, const internal::RoutingGraphGraph& graph) { + auto startVertex = graph.getVertex(from); + auto endVertex = graph.getVertex(to); + if (!startVertex || !endVertex) { + return {}; } - size_t n; -}; -template -struct StopIfCostMoreThan { - explicit StopIfCostMoreThan(double c) : c{c} {} - template - inline bool operator()(const T& v) const { - return Eq ? v.cost <= c : v.cost < c; + auto filteredGraph = + withLaneChanges + ? withAreas ? graph.withAreasAndLaneChanges(routingCostId) : graph.withLaneChanges(routingCostId) + : withAreas ? graph.withAreasWithoutLaneChanges(routingCostId) : graph.withoutLaneChanges(routingCostId); + DijkstraStyleSearch search(filteredGraph); + class DestinationReached {}; + try { + search.query(*startVertex, [endVertex](const internal::VertexVisitInformation& i) { + if (i.vertex == *endVertex) { + throw DestinationReached{}; + } + return true; + }); + } catch (DestinationReached) { // NOLINT + return PathT{buildPath(search.getMap(), *endVertex, filteredGraph)}; } - double c; -}; + return {}; +} + +template +Optional shortestPathViaImpl(Primitives routePoints, ShortestPathFunc&& shortestPath) { + Primitives path; + for (size_t it = 0; it < routePoints.size() - 1; it++) { + auto results = shortestPath(routePoints[it], routePoints[it + 1]); + if (!!results && !results->empty() && path.empty()) { + path.push_back(results->front()); + } + if (!addToPath(path, results)) { + return Optional(); + } + } + return RetT(path); +} } // namespace RoutingGraph::RoutingGraph(RoutingGraph&& /*other*/) noexcept = default; @@ -311,43 +403,34 @@ Optional RoutingGraph::getRouteVia(const ConstLanelet& from, const ConstL Optional RoutingGraph::shortestPath(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId, bool withLaneChanges) const { - auto startVertex = graph_->getVertex(from); - auto endVertex = graph_->getVertex(to); - if (!startVertex || !endVertex) { - return {}; - } - auto graph = withLaneChanges ? graph_->withLaneChanges(routingCostId) : graph_->withoutLaneChanges(routingCostId); - DijkstraStyleSearch search(graph); - class DestinationReached {}; - try { - search.query(*startVertex, [endVertex](const internal::VertexVisitInformation& i) { - if (i.vertex == *endVertex) { - throw DestinationReached{}; - } - return true; - }); - } catch (DestinationReached) { - return LaneletPath{buildPath(search.getMap(), *endVertex, graph)}; - } - return {}; + return shortestPathImpl(from, to, routingCostId, withLaneChanges, false, *graph_); +} + +Optional RoutingGraph::shortestPathIncludingAreas(const ConstLaneletOrArea& from, + const ConstLaneletOrArea& to, + RoutingCostId routingCostId, + bool withLaneChanges) const { + return shortestPathImpl(from, to, routingCostId, withLaneChanges, true, + *graph_); } Optional RoutingGraph::shortestPathVia(const ConstLanelet& start, const ConstLanelets& via, const ConstLanelet& end, RoutingCostId routingCostId, bool withLaneChanges) const { ConstLanelets routePoints = utils::concatenate({ConstLanelets{start}, via, ConstLanelets{end}}); - - ConstLanelets path; - for (size_t it = 0; it < routePoints.size() - 1; it++) { - auto results = shortestPath(routePoints[it], routePoints[it + 1], routingCostId, withLaneChanges); - if (!!results && !results->empty() && path.empty()) { - path.push_back(results->front()); - } - if (!addToPath(path, results)) { - return {}; - } - } - return LaneletPath(path); + return shortestPathViaImpl( + routePoints, [&](auto& from, auto& to) { return this->shortestPath(from, to, routingCostId, withLaneChanges); }); +} + +Optional RoutingGraph::shortestPathIncludingAreasVia(const ConstLaneletOrArea& start, + const ConstLaneletOrAreas& via, + const ConstLaneletOrArea& end, + RoutingCostId routingCostId, + bool withLaneChanges) const { + ConstLaneletOrAreas routePoints = utils::concatenate({ConstLaneletOrAreas{start}, via, ConstLaneletOrAreas{end}}); + return shortestPathViaImpl(routePoints, [&](auto& from, auto& to) { + return this->shortestPathIncludingAreas(from, to, routingCostId, withLaneChanges); + }); } Optional RoutingGraph::routingRelation(const ConstLanelet& from, const ConstLanelet& to, @@ -394,10 +477,10 @@ LaneletRelations RoutingGraph::previousRelations(const ConstLanelet& lanelet, bo return result; } -ConstLanelets RoutingGraph::besides(const ConstLanelet& lanelet) const { +ConstLanelets RoutingGraph::besides(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { auto move = [](auto it) { return std::make_move_iterator(it); }; - ConstLanelets left{lefts(lanelet)}; - ConstLanelets right{rights(lanelet)}; + ConstLanelets left{lefts(lanelet, routingCostId)}; + ConstLanelets right{rights(lanelet, routingCostId)}; ConstLanelets result; result.reserve(left.size() + right.size() + 1); result.insert(std::end(result), move(left.rbegin()), move(left.rend())); @@ -406,45 +489,47 @@ ConstLanelets RoutingGraph::besides(const ConstLanelet& lanelet) const { return result; } -Optional RoutingGraph::left(const ConstLanelet& lanelet) const { +Optional RoutingGraph::left(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { return ifLaneletInGraph(*graph_, lanelet, - [this](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->left()); }); + [&](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->left(routingCostId)); }); } -Optional RoutingGraph::adjacentLeft(const ConstLanelet& lanelet) const { - return ifLaneletInGraph(*graph_, lanelet, - [this](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->adjacentLeft()); }); +Optional RoutingGraph::adjacentLeft(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return ifLaneletInGraph(*graph_, lanelet, [&](auto& vertex) { + return neighboringLaneletImpl(vertex, graph_->adjacentLeft(routingCostId)); + }); } -Optional RoutingGraph::right(const ConstLanelet& lanelet) const { +Optional RoutingGraph::right(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { return ifLaneletInGraph(*graph_, lanelet, - [this](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->right()); }); + [&](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->right(routingCostId)); }); } -Optional RoutingGraph::adjacentRight(const ConstLanelet& lanelet) const { - return ifLaneletInGraph(*graph_, lanelet, - [this](auto& vertex) { return neighboringLaneletImpl(vertex, graph_->adjacentRight()); }); +Optional RoutingGraph::adjacentRight(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return ifLaneletInGraph(*graph_, lanelet, [&](auto& vertex) { + return neighboringLaneletImpl(vertex, graph_->adjacentRight(routingCostId)); + }); } -ConstLanelets RoutingGraph::lefts(const ConstLanelet& lanelet) const { - return getUntilEnd(lanelet, [this](const ConstLanelet& llt) { return left(llt); }); +ConstLanelets RoutingGraph::lefts(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return getUntilEnd(lanelet, [&](const ConstLanelet& llt) { return left(llt, routingCostId); }); } -ConstLanelets RoutingGraph::adjacentLefts(const ConstLanelet& lanelet) const { - return getUntilEnd(lanelet, [this](const ConstLanelet& llt) { return adjacentLeft(llt); }); +ConstLanelets RoutingGraph::adjacentLefts(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return getUntilEnd(lanelet, [&](const ConstLanelet& llt) { return adjacentLeft(llt, routingCostId); }); } -LaneletRelations RoutingGraph::leftRelations(const ConstLanelet& lanelet) const { +LaneletRelations RoutingGraph::leftRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { bool leftReached{false}; ConstLanelet current = lanelet; LaneletRelations result; while (!leftReached) { - const ConstLanelets leftOf{lefts(current)}; + const ConstLanelets leftOf{lefts(current, routingCostId)}; for (auto const& it : leftOf) { result.emplace_back(LaneletRelation{it, RelationType::Left}); current = it; } - const ConstLanelets adjacentLeftOf{adjacentLefts(current)}; + const ConstLanelets adjacentLeftOf{adjacentLefts(current, routingCostId)}; for (auto const& it : adjacentLeftOf) { result.emplace_back(LaneletRelation{it, RelationType::AdjacentLeft}); current = it; @@ -454,25 +539,25 @@ LaneletRelations RoutingGraph::leftRelations(const ConstLanelet& lanelet) const return result; } -ConstLanelets RoutingGraph::rights(const ConstLanelet& lanelet) const { - return getUntilEnd(lanelet, [this](const ConstLanelet& llt) { return right(llt); }); +ConstLanelets RoutingGraph::rights(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return getUntilEnd(lanelet, [&](const ConstLanelet& llt) { return right(llt, routingCostId); }); } -ConstLanelets RoutingGraph::adjacentRights(const ConstLanelet& lanelet) const { - return getUntilEnd(lanelet, [this](const ConstLanelet& llt) { return adjacentRight(llt); }); +ConstLanelets RoutingGraph::adjacentRights(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { + return getUntilEnd(lanelet, [&](const ConstLanelet& llt) { return adjacentRight(llt, routingCostId); }); } -LaneletRelations RoutingGraph::rightRelations(const ConstLanelet& lanelet) const { +LaneletRelations RoutingGraph::rightRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId) const { bool rightReached{false}; ConstLanelet current = lanelet; auto result = reservedVector(3); while (!rightReached) { - const ConstLanelets rightOf{rights(current)}; + const ConstLanelets rightOf{rights(current, routingCostId)}; for (auto const& it : rightOf) { result.emplace_back(LaneletRelation{it, RelationType::Right}); current = it; } - const ConstLanelets adjacentRightOf{adjacentRights(current)}; + const ConstLanelets adjacentRightOf{adjacentRights(current, routingCostId)}; for (auto const& it : adjacentRightOf) { result.emplace_back(LaneletRelation{it, RelationType::AdjacentRight}); current = it; @@ -516,69 +601,71 @@ ConstLanelets RoutingGraph::reachableSetTowards(const ConstLanelet& lanelet, dou return reachableSetImpl(*start, graph, StopIfCostMoreThan{maxRoutingCost}); } -LaneletPaths RoutingGraph::possiblePaths(const ConstLanelet& startPoint, double minRoutingCost, - RoutingCostId routingCostId, bool allowLaneChanges) const { +LaneletPaths RoutingGraph::possiblePaths(const ConstLanelet& startPoint, const PossiblePathsParams& params) const { auto start = graph_->getVertex(startPoint); if (!start) { return {}; } - auto graph = allowLaneChanges ? graph_->withLaneChanges(routingCostId) : graph_->withoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, StopIfCostMoreThan<>{minRoutingCost}); + auto graph = params.includeLaneChanges ? graph_->withLaneChanges(params.routingCostId) + : graph_->withoutLaneChanges(params.routingCostId); + return possiblePathsImpl(*start, graph, params); +} + +LaneletPaths RoutingGraph::possiblePaths(const ConstLanelet& startPoint, double minRoutingCost, + RoutingCostId routingCostId, bool allowLaneChanges) const { + return possiblePaths(startPoint, PossiblePathsParams{minRoutingCost, {}, routingCostId, allowLaneChanges, false}); } LaneletPaths RoutingGraph::possiblePaths(const ConstLanelet& startPoint, uint32_t minLanelets, bool allowLaneChanges, RoutingCostId routingCostId) const { - auto start = graph_->getVertex(startPoint); + return possiblePaths(startPoint, PossiblePathsParams{{}, minLanelets, routingCostId, allowLaneChanges, false}); +} + +LaneletPaths RoutingGraph::possiblePathsTowards(const ConstLanelet& targetLanelet, + const PossiblePathsParams& params) const { + auto start = graph_->getVertex(targetLanelet); if (!start) { return {}; } - auto graph = allowLaneChanges ? graph_->withLaneChanges(routingCostId) : graph_->withoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, StopIfLaneletsMoreThan<>{minLanelets}); + auto graph = params.includeLaneChanges ? graph_->withLaneChanges(params.routingCostId) + : graph_->withoutLaneChanges(params.routingCostId); + return possiblePathsImpl(*start, graph, params); } LaneletPaths RoutingGraph::possiblePathsTowards(const ConstLanelet& targetLanelet, double minRoutingCost, RoutingCostId routingCostId, bool allowLaneChanges) const { - auto start = graph_->getVertex(targetLanelet); - if (!start) { - return {}; - } - auto graph = allowLaneChanges ? graph_->withLaneChanges(routingCostId) : graph_->withoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, StopIfCostMoreThan<>{minRoutingCost}); + return possiblePathsTowards(targetLanelet, + PossiblePathsParams{minRoutingCost, {}, routingCostId, allowLaneChanges, false}); } LaneletPaths RoutingGraph::possiblePathsTowards(const ConstLanelet& targetLanelet, uint32_t minLanelets, bool allowLaneChanges, RoutingCostId routingCostId) const { - auto start = graph_->getVertex(targetLanelet); + return possiblePathsTowards(targetLanelet, + PossiblePathsParams{{}, minLanelets, routingCostId, allowLaneChanges, false}); +} + +LaneletOrAreaPaths RoutingGraph::possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, + const PossiblePathsParams& params) const { + auto start = graph_->getVertex(startPoint); if (!start) { return {}; } - auto graph = allowLaneChanges ? graph_->withLaneChanges(routingCostId) : graph_->withoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, StopIfLaneletsMoreThan<>{minLanelets}); + auto graph = params.includeLaneChanges ? graph_->withAreasAndLaneChanges(params.routingCostId) + : graph_->withAreasWithoutLaneChanges(params.routingCostId); + return possiblePathsImpl(*start, graph, params); } LaneletOrAreaPaths RoutingGraph::possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, double minRoutingCost, RoutingCostId routingCostId, bool allowLaneChanges) const { - auto start = graph_->getVertex(startPoint); - if (!start) { - return {}; - } - auto graph = allowLaneChanges ? graph_->withAreasAndLaneChanges(routingCostId) - : graph_->withAreasWithoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, - StopIfCostMoreThan<>{minRoutingCost}); + return possiblePathsIncludingAreas(startPoint, + PossiblePathsParams{minRoutingCost, {}, routingCostId, allowLaneChanges, false}); } LaneletOrAreaPaths RoutingGraph::possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, uint32_t minElements, bool allowLaneChanges, RoutingCostId routingCostId) const { - auto start = graph_->getVertex(startPoint); - if (!start) { - return {}; - } - auto graph = allowLaneChanges ? graph_->withAreasAndLaneChanges(routingCostId) - : graph_->withAreasWithoutLaneChanges(routingCostId); - return possiblePathsImpl(*start, graph, - StopIfLaneletsMoreThan<>{minElements}); + return possiblePathsIncludingAreas(startPoint, + PossiblePathsParams{{}, minElements, routingCostId, allowLaneChanges, false}); } void RoutingGraph::forEachSuccessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f, bool allowLaneChanges, @@ -672,7 +759,8 @@ void RoutingGraph::exportGraphViz(const std::string& filename, const RelationTyp //! Helper function to slim down getDebugLaneletMap RelationType allowedRelationsfromConfiguration(bool includeAdjacent, bool includeConflicting) { - RelationType allowedRelations{RelationType::Successor | RelationType::Left | RelationType::Right}; + RelationType allowedRelations{RelationType::Successor | RelationType::Left | RelationType::Right | + RelationType::Area}; if (includeAdjacent) { allowedRelations |= RelationType::AdjacentLeft; allowedRelations |= RelationType::AdjacentRight; @@ -699,7 +787,7 @@ class DebugMapBuilder { explicit DebugMapBuilder(const FilteredRoutingGraph& graph) : graph_{graph} {} LaneletMapPtr run(const internal::LaneletOrAreaToVertex& loa) { LaneletMapPtr output = std::make_shared(); - for (auto& vertex : loa) { + for (const auto& vertex : loa) { visitVertex(vertex); } auto lineStrings = utils::transform(lineStringMap_, [](auto& mapLs) { return mapLs.second; }); @@ -722,7 +810,7 @@ class DebugMapBuilder { } } - LaneletOrAreaPair getPair(const ConstLaneletOrArea& first, const ConstLaneletOrArea& second) { + static LaneletOrAreaPair getPair(const ConstLaneletOrArea& first, const ConstLaneletOrArea& second) { return first.id() < second.id() ? LaneletOrAreaPair(first, second) : LaneletOrAreaPair(second, first); } @@ -748,7 +836,6 @@ class DebugMapBuilder { } } - private: FilteredRoutingGraph graph_; std::unordered_map lineStringMap_; // Stores all relations std::unordered_map pointMap_; // Stores all 'edges' @@ -768,9 +855,9 @@ LaneletMapPtr RoutingGraph::getDebugLaneletMap(RoutingCostId routingCostId, bool RoutingGraph::Errors RoutingGraph::checkValidity(bool throwOnError) const { Errors errors; for (const auto& laWithVertex : graph_->vertexLookup()) { - auto& la = laWithVertex.first; + const auto& la = laWithVertex.first; auto ll = laWithVertex.first.lanelet(); - auto& vertex = laWithVertex.second; + const auto& vertex = laWithVertex.second; auto id = la.id(); // Check left relation Optional left; diff --git a/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp b/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp index f517c9ccbbb..8d2c606654e 100644 --- a/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp +++ b/lanelet2/lanelet2_routing/src/RoutingGraphBuilder.cpp @@ -1,11 +1,14 @@ -#include "internal/RoutingGraphBuilder.h" +#include "lanelet2_routing/internal/RoutingGraphBuilder.h" + #include #include #include + #include -#include "Exceptions.h" -#include "RoutingGraph.h" -#include "internal/Graph.h" + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/RoutingGraph.h" +#include "lanelet2_routing/internal/Graph.h" namespace lanelet { namespace routing { @@ -143,7 +146,8 @@ void RoutingGraphBuilder::addAreasToGraph(ConstAreas& areas) { } void RoutingGraphBuilder::addEdges(const ConstLanelets& lanelets, const LaneletLayer& passableLanelets) { - LaneChangeLaneletsCollector leftToRight, rightToLeft; + LaneChangeLaneletsCollector leftToRight; + LaneChangeLaneletsCollector rightToLeft; // Check relations between lanelets for (auto const& ll : lanelets) { addFollowingEdges(ll); @@ -237,27 +241,27 @@ void RoutingGraphBuilder::addConflictingEdge(const ConstLanelet& ll, const Lanel } void RoutingGraphBuilder::addLaneChangeEdges(LaneChangeLaneletsCollector& laneChanges, const RelationType& relation) { - auto getSuccessors = [this](auto beginEdgeIt, auto endEdgeIt) { + auto getSuccessors = [this](auto beginEdgeIt, auto endEdgeIt, auto getVertex) { ConstLanelets nexts; for (; beginEdgeIt != endEdgeIt; ++beginEdgeIt) { auto& edgeInfo = graph_->get()[*beginEdgeIt]; if (edgeInfo.relation == RelationType::Successor && edgeInfo.costId == 0) { - nexts.push_back(graph_->get()[boost::source(*beginEdgeIt, graph_->get())].lanelet()); + nexts.push_back(graph_->get()[getVertex(*beginEdgeIt, graph_->get())].lanelet()); } } return nexts; }; auto next = [this, &getSuccessors](const ConstLanelet& llt) { auto edges = boost::out_edges(*graph_->getVertex(llt), graph_->get()); - return getSuccessors(edges.first, edges.second); + return getSuccessors(edges.first, edges.second, [](auto edge, const auto& g) { return boost::target(edge, g); }); }; auto prev = [this, &getSuccessors](const ConstLanelet& llt) { auto edges = boost::in_edges(*graph_->getVertex(llt), graph_->get()); - return getSuccessors(edges.first, edges.second); + return getSuccessors(edges.first, edges.second, [](auto edge, const auto& g) { return boost::source(edge, g); }); }; Optional laneChangeLanelets; while (!!(laneChangeLanelets = laneChanges.getNextChangeLanelets(prev, next))) { - assignLaneChangeCosts(laneChangeLanelets->first, laneChangeLanelets->second, relation); + assignLaneChangeCosts(std::move(laneChangeLanelets->first), std::move(laneChangeLanelets->second), relation); } } @@ -334,41 +338,36 @@ bool RoutingGraphBuilder::hasEdge(const ConstLanelet& from, const ConstLanelet& return !!graph_->getEdgeInfo(from, to); } -void RoutingGraphBuilder::assignLaneChangeCosts(const ConstLanelets& froms, const ConstLanelets& tos, - const RelationType& relation) { +void RoutingGraphBuilder::assignLaneChangeCosts(ConstLanelets froms, ConstLanelets tos, const RelationType& relation) { assert(relation == RelationType::Left || relation == RelationType::Right); assert(froms.size() == tos.size()); - auto costs = utils::transform( - routingCosts_, [&](const RoutingCostPtr& cost) { return cost->getCostLaneChange(trafficRules_, froms, tos); }); - for (auto i = 0u; i < froms.size(); ++i) { - for (RoutingCostId costId = 0; costId < routingCosts_.size(); ++costId) { - if (!std::isfinite(costs[costId])) { + for (; !froms.empty(); froms.erase(froms.begin()), tos.erase(tos.begin())) { + for (RoutingCostId costId = 0; costId < RoutingCostId(routingCosts_.size()); ++costId) { + auto cost = routingCosts_[costId]->getCostLaneChange(trafficRules_, froms, tos); + if (!std::isfinite(cost)) { // if the costs are infinite, we add an adjacent edge instead auto adjacent = relation == RelationType::Left ? RelationType::AdjacentLeft : RelationType::AdjacentRight; - graph_->addEdge(froms[i], tos[i], EdgeInfo{1, costId, adjacent}); + graph_->addEdge(froms.front(), tos.front(), EdgeInfo{1, costId, adjacent}); continue; } - graph_->addEdge(froms[i], tos[i], EdgeInfo{costs[costId], costId, relation}); + graph_->addEdge(froms.front(), tos.front(), EdgeInfo{cost, costId, relation}); } } } void RoutingGraphBuilder::assignCosts(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to, const RelationType& relation) { - for (RoutingCostId rci = 0; rci < routingCosts_.size(); rci++) { + for (RoutingCostId rci = 0; rci < RoutingCostId(routingCosts_.size()); rci++) { EdgeInfo edgeInfo{}; edgeInfo.costId = rci; edgeInfo.relation = relation; auto& routingCost = *routingCosts_[rci]; if (relation == RelationType::Successor || relation == RelationType::Area) { edgeInfo.routingCost = routingCost.getCostSucceeding(trafficRules_, from, to); - } else if (relation == RelationType::Left) { + } else if (relation == RelationType::Left || relation == RelationType::Right) { edgeInfo.routingCost = routingCost.getCostLaneChange(trafficRules_, {*from.lanelet()}, {*to.lanelet()}); - } else if (relation == RelationType::Right) { - edgeInfo.routingCost = routingCost.getCostLaneChange(trafficRules_, {*from.lanelet()}, {*to.lanelet()}); - } else if (relation == RelationType::AdjacentLeft || relation == RelationType::AdjacentRight) { - edgeInfo.routingCost = 1; - } else if (relation == RelationType::Conflicting) { + } else if (relation == RelationType::AdjacentLeft || relation == RelationType::AdjacentRight || + relation == RelationType::Conflicting) { edgeInfo.routingCost = 1; } else { assert(false && "Trying to add edge with wrong relation type to graph."); // NOLINT diff --git a/lanelet2/lanelet2_routing/test/test_lanelet_or_area_path.cpp b/lanelet2/lanelet2_routing/test/test_lanelet_or_area_path.cpp new file mode 100644 index 00000000000..7144e13bcd8 --- /dev/null +++ b/lanelet2/lanelet2_routing/test/test_lanelet_or_area_path.cpp @@ -0,0 +1,211 @@ +#include +#include + +#include "lanelet2_routing/LaneletPath.h" + +using namespace lanelet; +using namespace lanelet::routing; + +/* + * 6 l8 7 l7 8 l6 9 l5 10 + * X<------X<------X<------X<------X + * ^ ^ ^ ^ + * |l9 |l10 |l11 |l12 + * | a1 | a2 | ll1 | ll2 + * | | ll3 | ll4 | + * X------>X------>X------>X------>X + * 1 l1 2 l2 3 l3 4 l4 5 + * | a51 | WE COME + * | V IN PEACE + * X<------X + * 12 11 + */ + +class LaneletOrAreaTest : public ::testing::Test { + private: + void SetUp() override { + Id id(1000); + p1 = Point3d(++id, 0, 0, 0); + p2 = Point3d(++id, 1, 0, 0); + p3 = Point3d(++id, 2, 0, 0); + p4 = Point3d(++id, 3, 0, 0); + p5 = Point3d(++id, 4, 0, 0); + p6 = Point3d(++id, 0, 1, 0); + p7 = Point3d(++id, 1, 1, 0); + p8 = Point3d(++id, 2, 1, 0); + p9 = Point3d(++id, 3, 1, 0); + p10 = Point3d(++id, 4, 1, 0); + p11 = Point3d(++id, 4, -1, 0); + p12 = Point3d(++id, 3, -1, 0); + + ls1 = LineString3d(++id, {p1, p2}); + ls2 = LineString3d(++id, {p2, p3}); + ls3 = LineString3d(++id, {p3, p4}); + ls4 = LineString3d(++id, {p4, p5}); + ls5 = LineString3d(++id, {p10, p9}); + ls6 = LineString3d(++id, {p9, p8}); + ls7 = LineString3d(++id, {p8, p7}); + ls8 = LineString3d(++id, {p7, p6}); + ls9 = LineString3d(++id, {p1, p6}); + ls10 = LineString3d(++id, {p2, p7}); + ls11 = LineString3d(++id, {p3, p8}); + ls12 = LineString3d(++id, {p4, p9}); + ls13 = LineString3d(++id, {p5, p11, p12, p4}); + + l1 = Lanelet(++id, ls6.invert(), ls3); + l2 = Lanelet(++id, ls5.invert(), ls4); + l3 = Lanelet(++id, ls10, ls11); + l4 = Lanelet(++id, ls11, ls12); + + a1 = Area(++id, {ls9, ls8.invert(), ls10.invert(), ls1.invert()}); + a2 = Area(++id, {ls10, ls7.invert(), ls11.invert(), ls2.invert()}); + a51 = Area(++id, {ls4, ls13}); + + areaPath = LaneletOrAreaPath({ConstLaneletOrArea(a1), ConstLaneletOrArea(a2)}); + laneletPath = LaneletOrAreaPath({ConstLaneletOrArea(l1), ConstLaneletOrArea(l2)}); + bothPath = LaneletOrAreaPath({ConstLaneletOrArea(a2), ConstLaneletOrArea(l1)}); + invAreaPath = LaneletOrAreaPath({ConstLaneletOrArea(l1.invert()), ConstLaneletOrArea(a2)}); + invLLPath = LaneletOrAreaPath({ConstLaneletOrArea(l2.invert()), ConstLaneletOrArea(l1.invert())}); + longPath = LaneletOrAreaPath( + {ConstLaneletOrArea(a1), ConstLaneletOrArea(a2), ConstLaneletOrArea(l1), ConstLaneletOrArea(l2)}); + longInvPath = LaneletOrAreaPath({ConstLaneletOrArea(l2.invert()), ConstLaneletOrArea(l1.invert()), + ConstLaneletOrArea(a2), ConstLaneletOrArea(a1)}); + sidePath = LaneletOrAreaPath({ConstLaneletOrArea(a1), ConstLaneletOrArea(l3), ConstLaneletOrArea(l4)}); + sideInvPath = LaneletOrAreaPath({ConstLaneletOrArea(l3), ConstLaneletOrArea(a1)}); + cornerPath = LaneletOrAreaPath({ConstLaneletOrArea(l1), ConstLaneletOrArea(l2), ConstLaneletOrArea(a51)}); + cornerPathInv = + LaneletOrAreaPath({ConstLaneletOrArea(a51), ConstLaneletOrArea(l2.invert()), ConstLaneletOrArea(l1.invert())}); + } + + public: + Point3d p1, p2, p3, p4, p5, p6, p7, p8, p9, p10, p11, p12; + LineString3d ls1, ls2, ls3, ls4, ls5, ls6, ls7, ls8, ls9, ls10, ls11, ls12, ls13; + Lanelet l1, l2, l3, l4; + Area a1, a2, a51; + LaneletOrAreaPath areaPath, laneletPath, bothPath, invAreaPath, invLLPath, longPath, longInvPath, sidePath, + sideInvPath, cornerPath, cornerPathInv; +}; +namespace { +void checkIdentical(const BasicPolygon3d& lhs, const BasicPolygon3d& rhs) { + auto to2D = [](const BasicPolygon3d& p3d) { + BasicPolygon2d p2d(p3d.size()); + for (size_t i = 0; i < p3d.size(); ++i) { + p2d[i] = p3d.at(i).head<2>(); + } + return p2d; + }; + BasicPolygon2d lhs2d = to2D(lhs); + BasicPolygon2d rhs2d = to2D(rhs); + // equals is buggy in older boost versions +#if BOOST_VERSION > 106500 + EXPECT_TRUE(boost::geometry::equals(lhs2d, rhs2d)); +#endif +} + +void checkEvenlySpaced(const BasicPolygon3d& poly, const double dist = 1.) { + for (size_t i = 0; i + 1 < poly.size(); ++i) { + EXPECT_DOUBLE_EQ(boost::geometry::distance(poly.at(i), poly.at(i + 1)), dist); + } + EXPECT_DOUBLE_EQ(boost::geometry::distance(poly.back(), poly.front()), dist); +} + +} // namespace + +TEST_F(LaneletOrAreaTest, enclosingPolygonAreas) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(areaPath); + BasicPolygon3d expected{p1, p6, p8, p3}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonLanelets) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(laneletPath); + BasicPolygon3d expected{p3, p8, p10, p5}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonLaneletsInverted) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(invLLPath); + BasicPolygon3d expected{p3, p8, p10, p5}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonMixed) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(bothPath); + BasicPolygon3d expected{p2, p7, p9, p4}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonAreaInverted) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(invAreaPath); + BasicPolygon3d expected{p2, p7, p9, p4}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonLong) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(longPath); + BasicPolygon3d expected{p1, p6, p10, p5}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 10ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonLongInverted) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(longInvPath); + BasicPolygon3d expected{p1, p6, p10, p5}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 10ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonSideways) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(sidePath); + BasicPolygon3d expected{p1, p6, p9, p4}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 8ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonSidewaysInvertrd) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(sideInvPath); + BasicPolygon3d expected{p1, p6, p8, p3}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 6ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonCorner) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(cornerPath); + BasicPolygon3d expected{p8, p10, p11, p12, p4, p3}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 8ul); +} + +TEST_F(LaneletOrAreaTest, enclosingPolygonCornerInv) { // NOLINT + BasicPolygons2d intersect; + BasicPolygon3d joined = getEnclosingPolygon3d(cornerPathInv); + BasicPolygon3d expected{p8, p10, p11, p12, p4, p3}; + checkIdentical(joined, expected); + checkEvenlySpaced(joined); + EXPECT_EQ(joined.size(), 8ul); +} diff --git a/lanelet2/lanelet2_routing/test/test_relations.cpp b/lanelet2/lanelet2_routing/test/test_relations.cpp index 25b5dcc22e6..801e3fe9447 100644 --- a/lanelet2/lanelet2_routing/test/test_relations.cpp +++ b/lanelet2/lanelet2_routing/test/test_relations.cpp @@ -1,5 +1,8 @@ #include -#include "RoutingGraph.h" + +#include + +#include "lanelet2_routing/RoutingGraph.h" #include "test_routing_map.h" using namespace lanelet; @@ -520,3 +523,14 @@ TEST_F(GermanVehicleGraph, conflictingDiverging) { // NOLINT ASSERT_EQ(result.size(), 1ul); EXPECT_EQ(result.front(), lanelets.at(2009)); } + +TEST_F(RoutingGraphTest, routingCostOnLaneChange) { // NOLINT + // tests that all lane changes are not possible when the space for a lane change is too small according to the routing + // cost object + auto graph = setUpGermanVehicleGraph(*testData.laneletMap, 2, 2, 3); + auto llt = [&](auto id) -> ConstLanelet { return lanelets.at(id); }; + EXPECT_EQ(graph->left(lanelets.at(2012)), llt(2011)); + EXPECT_EQ(graph->adjacentLeft(lanelets.at(2015)), llt(2014)); + EXPECT_EQ(graph->right(lanelets.at(2011)), llt(2012)); + EXPECT_EQ(graph->adjacentRight(lanelets.at(2014)), llt(2015)); +} diff --git a/lanelet2/lanelet2_routing/test/test_route.cpp b/lanelet2/lanelet2_routing/test/test_route.cpp index d4010817c67..b6d56465b70 100644 --- a/lanelet2/lanelet2_routing/test/test_route.cpp +++ b/lanelet2/lanelet2_routing/test/test_route.cpp @@ -1,6 +1,7 @@ #include -#include "Route.h" -#include "RoutingGraph.h" + +#include "lanelet2_routing/Route.h" +#include "lanelet2_routing/RoutingGraph.h" #include "test_routing_map.h" using namespace lanelet; @@ -37,6 +38,7 @@ class Route1NoLc : public TestRoute<2001, 2014> { class Route2 : public TestRoute<2001, 2004> {}; class Route3 : public TestRoute<2003, 2002> {}; class Route4 : public TestRoute<2003, 2013> {}; +class Route5 : public TestRoute<2066, 2064> {}; class RouteMaxHoseLeftRight : public TestRoute<2017, 2024> {}; class RouteMaxHoseRightLeft : public TestRoute<2023, 2016> {}; class RouteMaxHoseLeftRightDashedSolid : public TestRoute<2017, 2025> {}; @@ -58,7 +60,7 @@ template class AllRoutesTest : public T {}; using AllRoutes = - testing::Types; @@ -238,7 +240,11 @@ TEST_F(Route4, EndPoint) { // NOLINT EXPECT_EQ(route.getEndPoint().x(), new_end_point.x()); EXPECT_EQ(route.getEndPoint().y(), new_end_point.y()); EXPECT_EQ(route.getEndPoint().z(), new_end_point.z()); +} +TEST_F(Route5, NoCircle) { + EXPECT_EQ(route.size(), 9); + EXPECT_FALSE(hasLanelet(route.laneletSubmap()->laneletLayer, lanelets.at(2065))); } TEST_F(RouteMaxHoseLeftRight, CreateRouteMaxHose1) { // NOLINT diff --git a/lanelet2/lanelet2_routing/test/test_routing.cpp b/lanelet2/lanelet2_routing/test/test_routing.cpp index ddc4f71fbac..61469b40a8b 100644 --- a/lanelet2/lanelet2_routing/test/test_routing.cpp +++ b/lanelet2/lanelet2_routing/test/test_routing.cpp @@ -1,10 +1,11 @@ #include #include -#include + #include -#include "RoutingGraph.h" -#include "internal/Graph.h" -#include "internal/ShortestPath.h" + +#include "lanelet2_routing/RoutingGraph.h" +#include "lanelet2_routing/internal/Graph.h" +#include "lanelet2_routing/internal/ShortestPath.h" #include "test_routing_map.h" using namespace lanelet; @@ -57,7 +58,7 @@ TEST(DijkstraSearch, onSimpleGraph) { return v.vertex != 4; }); EXPECT_EQ(searcher.getMap().size(), boost::num_vertices(g)); - for (auto& v : searcher.getMap()) { + for (const auto& v : searcher.getMap()) { EXPECT_EQ(v.second.predicate, v.first != 4) << v.first; EXPECT_EQ(v.second.isLeaf, v.first == 5 || v.first == 4) << v.first; } @@ -67,9 +68,10 @@ TEST_F(GermanPedestrianGraph, NumberOfLanelets) { // NOLINT EXPECT_EQ(graph->passableSubmap()->laneletLayer.size(), 5ul); EXPECT_TRUE(graph->passableSubmap()->laneletLayer.exists(2031)); EXPECT_TRUE(graph->passableSubmap()->laneletLayer.exists(2050)); - EXPECT_EQ(graph->passableSubmap()->areaLayer.size(), 2ul); + EXPECT_EQ(graph->passableSubmap()->areaLayer.size(), 3ul); EXPECT_TRUE(graph->passableSubmap()->areaLayer.exists(3000)); EXPECT_TRUE(graph->passableSubmap()->areaLayer.exists(3001)); + EXPECT_TRUE(graph->passableSubmap()->areaLayer.exists(3002)); } TEST_F(GermanBicycleGraph, NumberOfLanelets) { // NOLINT @@ -237,21 +239,22 @@ TEST_F(GermanVehicleGraph, reachableSetInvalid) { TEST_F(GermanPedestrianGraph, reachableSetCrossingWithArea) { // NOLINT auto reachable = graph->reachableSetIncludingAreas(lanelets.at(2050), 100); - EXPECT_EQ(reachable.size(), 5ul); + EXPECT_EQ(reachable.size(), 6ul); EXPECT_TRUE(containsLanelet(reachable, 2050)); EXPECT_TRUE(containsLanelet(reachable, 2053)); EXPECT_TRUE(containsLanelet(reachable, 2052)); EXPECT_TRUE(containsLanelet(reachable, 3000)); EXPECT_TRUE(containsLanelet(reachable, 3001)); + EXPECT_TRUE(containsLanelet(reachable, 3002)); } TEST_F(GermanPedestrianGraph, reachableSetStartingFromArea) { // NOLINT auto reachable = graph->reachableSetIncludingAreas(areas.at(3000), 100); - EXPECT_EQ(reachable.size(), 4ul); + EXPECT_EQ(reachable.size(), 5ul); } TEST_F(GermanPedestrianGraph, reachableSetWithAreaFromTwoWayLanelet) { // NOLINT auto reachable = graph->reachableSetIncludingAreas(lanelets.at(2053).invert(), 100); EXPECT_TRUE(containsLanelet(reachable, 2053)); - EXPECT_EQ(reachable.size(), 5ul); + EXPECT_EQ(reachable.size(), 6ul); } TEST_F(GermanPedestrianGraph, reachableSetWithAreaFromUnconnectedLanelet) { // NOLINT auto reachable = graph->reachableSetIncludingAreas(lanelets.at(2051), 100); @@ -260,16 +263,18 @@ TEST_F(GermanPedestrianGraph, reachableSetWithAreaFromUnconnectedLanelet) { // TEST_F(GermanPedestrianGraph, possiblePathsWithAreaFromLanelet) { // NOLINT auto reachable = graph->possiblePathsIncludingAreas(lanelets.at(2050), 10, 0, false); - ASSERT_EQ(reachable.size(), 2ul); + ASSERT_EQ(reachable.size(), 3ul); EXPECT_EQ(reachable[0].size(), 3ul); EXPECT_EQ(reachable[1].size(), 3ul); + EXPECT_EQ(reachable[2].size(), 3ul); } TEST_F(GermanPedestrianGraph, possiblePathsWithAreaFromUnconnectedLanelet) { // NOLINT auto reachable = graph->possiblePathsIncludingAreas(lanelets.at(2050), 3, false); - ASSERT_EQ(reachable.size(), 2ul); + ASSERT_EQ(reachable.size(), 3ul); EXPECT_EQ(reachable[0].size(), 3ul); EXPECT_EQ(reachable[1].size(), 3ul); + EXPECT_EQ(reachable[2].size(), 3ul); } TEST_F(GermanVehicleGraph, possiblePathsMinRoutingCosts) { // NOLINT @@ -285,6 +290,50 @@ TEST_F(GermanVehicleGraph, possiblePathsMinRoutingCosts) { // NOLINT EXPECT_TRUE(containsLanelet(firstRoute, 2006)); } +TEST_F(GermanVehicleGraph, possiblePathsIncludeShorterLc) { // NOLINT + auto routes = graph->possiblePaths(lanelets.at(2041), PossiblePathsParams{1000, {}, 0, true, true}); + EXPECT_EQ(routes.size(), 3); + auto lastLLts = utils::transform(routes, [](auto& route) { return route.back(); }); + EXPECT_TRUE(has(lastLLts, lanelets.at(2062))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2049))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2048))); +} + +TEST_F(GermanVehicleGraph, possiblePathsIncludeShorterAllLimitsLc) { // NOLINT + auto routes = graph->possiblePaths(lanelets.at(2041), PossiblePathsParams{1000, 100, 0, true, true}); + EXPECT_EQ(routes.size(), 3); + auto lastLLts = utils::transform(routes, [](auto& route) { return route.back(); }); + EXPECT_TRUE(has(lastLLts, lanelets.at(2062))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2049))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2048))); +} + +TEST_F(GermanVehicleGraph, possiblePathsIncludeShorterNoLc) { // NOLINT + auto routes = graph->possiblePaths(lanelets.at(2041), PossiblePathsParams{1000, {}, 0, false, true}); + EXPECT_EQ(routes.size(), 3); + auto lastLLts = utils::transform(routes, [](auto& route) { return route.back(); }); + EXPECT_TRUE(has(lastLLts, lanelets.at(2063))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2049))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2047))); +} + +TEST_F(GermanVehicleGraph, possiblePathsIncludeShorterAllLimitsNoLc) { // NOLINT + auto routes = graph->possiblePaths(lanelets.at(2041), PossiblePathsParams{1000, 100, 0, false, true}); + EXPECT_EQ(routes.size(), 3); + auto lastLLts = utils::transform(routes, [](auto& route) { return route.back(); }); + EXPECT_TRUE(has(lastLLts, lanelets.at(2063))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2049))); + EXPECT_TRUE(has(lastLLts, lanelets.at(2047))); +} + +TEST_F(GermanVehicleGraph, possiblePathsLimitLengthNoLc) { // NOLINT + auto routes = graph->possiblePaths(lanelets.at(2041), PossiblePathsParams{2.5, 3, 0, false, false}); + EXPECT_TRUE(std::all_of(routes.begin(), routes.end(), [](auto& r) { return r.size() <= 3; })); + EXPECT_EQ(routes.size(), 3); + auto lastLLts = utils::transform(routes, [](auto& route) { return route.back(); }); + EXPECT_TRUE(has(lastLLts, lanelets.at(2042))); +} + TEST_F(GermanVehicleGraph, possiblePathsMaxHose) { // NOLINT // Max Hose Problem auto routes = graph->possiblePaths(lanelets.at(2017), 10.0, 0, true); @@ -412,6 +461,28 @@ TEST_F(GermanVehicleGraph, forEachPredecessorReachesLanelet) { // NOLINT EXPECT_THROW(graph->forEachPredecessor(lanelets.at(2007), throwIfTarget), TargetFound); // NOLINT } +TEST_F(GermanPedestrianGraph, shortestPathIncludingAreasFromArea) { // NOLINT + auto path = + graph->shortestPathIncludingAreas(ConstLaneletOrArea(areas.at(3001)), ConstLaneletOrArea(lanelets.at(2053))); + ASSERT_TRUE(!!path); + EXPECT_EQ(path->size(), 2ul); +} + +TEST_F(GermanPedestrianGraph, shortestPathIncludingAreasThroughAreas) { + auto path = + graph->shortestPathIncludingAreas(ConstLaneletOrArea(lanelets.at(2050)), ConstLaneletOrArea(lanelets.at(2053))); + ASSERT_TRUE(!!path); + EXPECT_EQ(path->size(), 4ul); +} + +TEST_F(GermanPedestrianGraph, shortestPathIncludingAreasViaThroughAreas) { + auto path = + graph->shortestPathIncludingAreasVia(ConstLaneletOrArea(lanelets.at(2050)), {ConstLaneletOrArea(areas.at(3002))}, + ConstLaneletOrArea(lanelets.at(2053))); + ASSERT_TRUE(!!path); + EXPECT_EQ(path->size(), 6ul); +} + TEST(RoutingCostInitialization, NegativeLaneChangeCost) { // NOLINT EXPECT_NO_THROW(RoutingCostDistance(1)); // NOLINT EXPECT_THROW(RoutingCostDistance(-1), InvalidInputError); // NOLINT diff --git a/lanelet2/lanelet2_routing/test/test_routing_graph_container.cpp b/lanelet2/lanelet2_routing/test/test_routing_graph_container.cpp index 0e73ab700b2..e1b45b8e998 100644 --- a/lanelet2/lanelet2_routing/test/test_routing_graph_container.cpp +++ b/lanelet2/lanelet2_routing/test/test_routing_graph_container.cpp @@ -1,8 +1,9 @@ -#include #include #include -#include "RoutingGraph.h" -#include "RoutingGraphContainer.h" + +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/RoutingGraph.h" +#include "lanelet2_routing/RoutingGraphContainer.h" #include "test_routing_map.h" using namespace lanelet; @@ -16,7 +17,6 @@ class RoutingGraphContainerTest : public RoutingGraphTest { container = std::make_unique(graphs); } - public: RoutingGraphContainerUPtr container; }; @@ -32,7 +32,6 @@ class RouteRoutingGraphContainerTest : public RoutingGraphContainerTest { route = std::make_unique(std::move(*tempRoute)); } - public: std::unique_ptr route; }; diff --git a/lanelet2/lanelet2_routing/test/test_routing_map.h b/lanelet2/lanelet2_routing/test/test_routing_map.h index 7bf9d7963e3..a2626d16099 100644 --- a/lanelet2/lanelet2_routing/test/test_routing_map.h +++ b/lanelet2/lanelet2_routing/test/test_routing_map.h @@ -3,10 +3,12 @@ #include #include #include + #include #include -#include "Forward.h" -#include "RoutingGraph.h" + +#include "lanelet2_routing/Forward.h" +#include "lanelet2_routing/RoutingGraph.h" /// The coordinates and relations for this test can be found in "LaneletTestMap.xml" which can be viewed in /// https://www.draw.io @@ -15,10 +17,10 @@ namespace routing { namespace tests { inline RoutingGraphPtr setUpGermanVehicleGraph(LaneletMap& map, double laneChangeCost = 2., - double participantHeight = 2.) { + double participantHeight = 2., double minLaneChangeLength = 0.) { traffic_rules::TrafficRulesPtr trafficRules{traffic_rules::TrafficRulesFactory::create( Locations::Germany, Participants::Vehicle, traffic_rules::TrafficRules::Configuration())}; - RoutingCostPtrs costPtrs{std::make_shared(laneChangeCost), + RoutingCostPtrs costPtrs{std::make_shared(laneChangeCost, minLaneChangeLength), std::make_shared(laneChangeCost)}; RoutingGraph::Configuration configuration; configuration.insert(std::make_pair(RoutingGraph::ParticipantHeight, participantHeight)); @@ -206,7 +208,8 @@ class RoutingGraphTestData { addPoint(31, 4, 0); // p103 addPoint(33, 4, 0); // p104 addPoint(31, 2, 0); // p105 - addPoint(33, 4, 0); // p106 + addPoint(33, 2, 0); // p106 + addPoint(31, 0, 0); // p107 // points on the conflicting and circular section pointId = 119; @@ -346,12 +349,15 @@ class RoutingGraphTestData { addLine({points.at(95), points.at(96)}); // ls1091 lines.at(1091).setAttribute(AttributeName::Type, AttributeValueString::Virtual); addLine({points.at(96), points.at(97)}); // ls1092 + lines.at(1092).setAttribute(AttributeName::Type, AttributeValueString::Curbstone); + lines.at(1092).setAttribute(AttributeName::Subtype, AttributeValueString::Low); addLine({points.at(97), points.at(98)}); // ls1093 lines.at(1093).setAttribute(AttributeName::Type, AttributeValueString::Curbstone); lines.at(1093).setAttribute(AttributeName::Subtype, AttributeValueString::Low); - addLine({points.at(98), points.at(92)}); // ls1094 - addLine({points.at(95), points.at(103)}); // ls1095 - addLine({points.at(96), points.at(105)}); // ls1096 + addLine({points.at(98), points.at(92)}); // ls1094 + addLine({points.at(95), points.at(103)}); // ls1095 + addLine({points.at(96), points.at(105)}); // ls1096 + lines.at(1096).setAttribute(AttributeName::Type, AttributeValueString::Wall); addLine({points.at(103), points.at(105)}); // ls1097 lines.at(1097).setAttribute(AttributeName::Type, AttributeValueString::Virtual); addLine({points.at(103), points.at(104)}); // ls1098 @@ -360,6 +366,8 @@ class RoutingGraphTestData { addLine({points.at(101), points.at(102)}); // ls1101 addLine({points.at(92), points.at(90)}); // ls1102 lines.at(1102).setAttribute(AttributeName::Type, AttributeValueString::Virtual); + addLine({points.at(97), points.at(107)}); // ls1103 + addLine({points.at(107), points.at(105)}); // ls1104 // lines on the conflicting and circular section lineId = 1199; @@ -381,7 +389,7 @@ class RoutingGraphTestData { addLine({points.at(129), points.at(131)}); // ls1215 addLine({points.at(130), points.at(42)}); // ls1216 lines.at(1205).setAttribute(AttributeName::Type, AttributeValueString::LineThin); - lines.at(1205).setAttribute(AttributeName::Type, AttributeValueString::Dashed); + lines.at(1205).setAttribute(AttributeName::Subtype, AttributeValueString::Dashed); } void initLanelets() { lanelets.clear(); @@ -462,10 +470,14 @@ class RoutingGraphTestData { addAreaPedestrian({lines.at(1102), lines.at(1088), lines.at(1089), lines.at(1090), lines.at(1091), lines.at(1092), lines.at(1093), lines.at(1094)}); // ar3000 addAreaPedestrian({lines.at(1095), lines.at(1097), lines.at(1096), lines.at(1091).invert()}); // ar3001 + // addAreaPedestrian({lines.at(1096).invert(), lines.at(1092), lines.at(1103), lines.at(1104)}); // ar3002 + addAreaPedestrian( + {lines.at(1096), lines.at(1104).invert(), lines.at(1103).invert(), lines.at(1092).invert()}); // ar3002 + areas.at(3002).setAttribute(AttributeName::Subtype, AttributeValueString::Walkway); } }; -namespace { +namespace { // NOLINT static RoutingGraphTestData testData; // NOLINT } // namespace diff --git a/lanelet2/lanelet2_routing/test/test_routing_visualization.cpp b/lanelet2/lanelet2_routing/test/test_routing_visualization.cpp index 7ca1aa48a95..91609ecdf39 100644 --- a/lanelet2/lanelet2_routing/test/test_routing_visualization.cpp +++ b/lanelet2/lanelet2_routing/test/test_routing_visualization.cpp @@ -1,7 +1,9 @@ #include -#include "Exceptions.h" -#include "RoutingGraph.h" -#include "boost/filesystem.hpp" + +#include + +#include "lanelet2_routing/Exceptions.h" +#include "lanelet2_routing/RoutingGraph.h" #include "test_routing_map.h" using namespace lanelet; @@ -13,12 +15,16 @@ class Tempfile { public: Tempfile() { char path[] = {"/tmp/lanelet2_unittest.XXXXXX"}; - auto res = mkdtemp(path); + auto* res = mkdtemp(path); if (res == nullptr) { throw lanelet::LaneletError("Failed to crate temporary directory"); } path_ = path; } + Tempfile(const Tempfile&) = delete; + Tempfile(Tempfile&&) = delete; + Tempfile& operator=(const Tempfile&) = delete; + Tempfile& operator=(Tempfile&&) = delete; ~Tempfile() { fs::remove_all(fs::path(path_)); } auto operator()(const std::string& str) const noexcept -> std::string { return (fs::path(path_) / str).string(); } @@ -40,7 +46,7 @@ TEST_F(GermanVehicleGraph, GraphVizExport) { // NOLIN TEST_F(GermanVehicleGraph, GraphVizExportError) { // NOLINT EXPECT_THROW(graph->exportGraphViz("", RelationType::None), lanelet::InvalidInputError); // NOLINT - EXPECT_THROW(graph->exportGraphViz("/bla"), lanelet::ExportError); // NOLINT + EXPECT_THROW(graph->exportGraphViz("/place/that/doesnt/exist"), lanelet::ExportError); // NOLINT } TEST_F(GermanVehicleGraph, GraphMLExport) { // NOLINT @@ -55,7 +61,7 @@ TEST_F(GermanVehicleGraph, GraphMLExport) { // NO TEST_F(GermanVehicleGraph, GraphMLExportError) { // NOLINT EXPECT_THROW(graph->exportGraphML("", RelationType::None), lanelet::InvalidInputError); // NOLINT - EXPECT_THROW(graph->exportGraphML("/place_that_doesnt_exist", RelationType::None), lanelet::ExportError); // NOLINT + EXPECT_THROW(graph->exportGraphML("/place/that/doesnt/exist", RelationType::None), lanelet::ExportError); // NOLINT } TEST_F(GermanVehicleGraph, DebugLaneletMap) { // NOLINT diff --git a/lanelet2/lanelet2_traffic_rules/CHANGELOG.rst b/lanelet2/lanelet2_traffic_rules/CHANGELOG.rst new file mode 100644 index 00000000000..1a67eb3c8bc --- /dev/null +++ b/lanelet2/lanelet2_traffic_rules/CHANGELOG.rst @@ -0,0 +1,28 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_traffic_rules +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Reorder includes with clang-format +* Making all includes in lanelet2_traffic_rules consistent. +* Updating package.xml files to format 3. +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add changelogs +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Started traffic rules refactoring, bugfixing in traffic rules and extend unittests +* Fix compiler errors with gcc 5 +* Initial commit +* Contributors: Fabian Poggenhans, Maximilian Naumann diff --git a/lanelet2/lanelet2_traffic_rules/CMakeLists.txt b/lanelet2/lanelet2_traffic_rules/CMakeLists.txt index b6c95dc7ddd..283286e6aee 100644 --- a/lanelet2/lanelet2_traffic_rules/CMakeLists.txt +++ b/lanelet2/lanelet2_traffic_rules/CMakeLists.txt @@ -1,33 +1,34 @@ -set(MRT_PKG_VERSION 2.2) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_traffic_rules) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) + +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -file(GLOB PROJECT_PYTHON_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "python_api/*.cpp") +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") if (PROJECT_PYTHON_SOURCE_FILES_SRC) # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project mrt_add_python_api( ${PROJECT_NAME} @@ -36,56 +37,27 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC) endif() ############################ -## read source code files ## +## Read source code files ## ############################ -file(GLOB_RECURSE PROJECT_HEADER_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "include/*.h" "include/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.h" "src/*.hpp") -file(GLOB PROJECT_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.cpp") - -if (PROJECT_SOURCE_FILES_SRC) - set(LIBRARY_NAME ${PROJECT_NAME}) -endif() - -################################### -## catkin specific configuration ## -################################### -# The catkin_package macro generates cmake config files for your package -# Declare things to be passed to dependent projects -# INCLUDE_DIRS: uncomment this if you package contains header files -# LIBRARIES: libraries you create in this project that dependent projects also need -# CATKIN_DEPENDS: catkin_packages dependent projects also need -# DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include ${mrt_EXPORT_INCLUDE_DIRS} - LIBRARIES ${LIBRARY_NAME} ${mrt_EXPORT_LIBRARIES} - CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} - ) +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") ########### ## Build ## ########### -# Add include and library directories -include_directories( - include/${PROJECT_NAME} - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - # Declare a cpp library mrt_add_library(${PROJECT_NAME} - INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GenericTrafficRules.h b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GenericTrafficRules.h index 834b2a0f6ae..2cb4659098d 100644 --- a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GenericTrafficRules.h +++ b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GenericTrafficRules.h @@ -1,7 +1,8 @@ #pragma once #include #include -#include "TrafficRules.h" + +#include "lanelet2_traffic_rules/TrafficRules.h" namespace lanelet { namespace traffic_rules { diff --git a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GermanTrafficRules.h b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GermanTrafficRules.h index 30a3dd427dc..39c526cfe21 100644 --- a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GermanTrafficRules.h +++ b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/GermanTrafficRules.h @@ -1,6 +1,7 @@ #pragma once #include -#include "GenericTrafficRules.h" + +#include "lanelet2_traffic_rules/GenericTrafficRules.h" namespace lanelet { namespace traffic_rules { diff --git a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/TrafficRulesFactory.h b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/TrafficRulesFactory.h index 9f707e7e2c7..d303b2c9fb1 100644 --- a/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/TrafficRulesFactory.h +++ b/lanelet2/lanelet2_traffic_rules/include/lanelet2_traffic_rules/TrafficRulesFactory.h @@ -1,5 +1,5 @@ #pragma once -#include "TrafficRules.h" +#include "lanelet2_traffic_rules/TrafficRules.h" namespace lanelet { struct Locations { diff --git a/lanelet2/lanelet2_traffic_rules/package.xml b/lanelet2/lanelet2_traffic_rules/package.xml index 47e47b5f767..685d1dce70e 100644 --- a/lanelet2/lanelet2_traffic_rules/package.xml +++ b/lanelet2/lanelet2_traffic_rules/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_traffic_rules - 0.9.0 + 1.1.1 Package for interpreting traffic rules in a lanelet map BSD @@ -9,11 +10,15 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest lanelet2_core + catkin + ament_cmake diff --git a/lanelet2/lanelet2_traffic_rules/src/GenericTrafficRules.cpp b/lanelet2/lanelet2_traffic_rules/src/GenericTrafficRules.cpp index b4164edbfe7..f32e856014a 100644 --- a/lanelet2/lanelet2_traffic_rules/src/GenericTrafficRules.cpp +++ b/lanelet2/lanelet2_traffic_rules/src/GenericTrafficRules.cpp @@ -1,9 +1,11 @@ -#include "GenericTrafficRules.h" +#include "lanelet2_traffic_rules/GenericTrafficRules.h" + #include #include #include #include -#include "Exceptions.h" + +#include "lanelet2_traffic_rules/Exceptions.h" namespace lanelet { namespace traffic_rules { diff --git a/lanelet2/lanelet2_traffic_rules/src/GermanTrafficRules.cpp b/lanelet2/lanelet2_traffic_rules/src/GermanTrafficRules.cpp index 823a74c5ea7..8b70fe6fa68 100644 --- a/lanelet2/lanelet2_traffic_rules/src/GermanTrafficRules.cpp +++ b/lanelet2/lanelet2_traffic_rules/src/GermanTrafficRules.cpp @@ -1,9 +1,11 @@ -#include "GermanTrafficRules.h" +#include "lanelet2_traffic_rules/GermanTrafficRules.h" + #include #include #include -#include "Exceptions.h" -#include "TrafficRulesFactory.h" + +#include "lanelet2_traffic_rules/Exceptions.h" +#include "lanelet2_traffic_rules/TrafficRulesFactory.h" using namespace std::string_literals; @@ -38,7 +40,7 @@ Velocity trafficSignToVelocity(const std::string& typeString) { } // namespace Optional GermanVehicle::speedLimit(const RegulatoryElementConstPtrs& regelems) const { - for (auto& regelem : regelems) { + for (const auto& regelem : regelems) { auto speedLimit = std::dynamic_pointer_cast(regelem); if (!!speedLimit) { return SpeedLimitInformation{trafficSignToVelocity(speedLimit->type()), true}; diff --git a/lanelet2/lanelet2_traffic_rules/src/TrafficRulesFactory.cpp b/lanelet2/lanelet2_traffic_rules/src/TrafficRulesFactory.cpp index 0ee4e701023..029dce08f52 100644 --- a/lanelet2/lanelet2_traffic_rules/src/TrafficRulesFactory.cpp +++ b/lanelet2/lanelet2_traffic_rules/src/TrafficRulesFactory.cpp @@ -1,4 +1,4 @@ -#include "TrafficRulesFactory.h" +#include "lanelet2_traffic_rules/TrafficRulesFactory.h" namespace lanelet { diff --git a/lanelet2/lanelet2_traffic_rules/test/lanelet2_traffic_rules.cpp b/lanelet2/lanelet2_traffic_rules/test/lanelet2_traffic_rules.cpp index 5562965d007..16033da2bdc 100644 --- a/lanelet2/lanelet2_traffic_rules/test/lanelet2_traffic_rules.cpp +++ b/lanelet2/lanelet2_traffic_rules/test/lanelet2_traffic_rules.cpp @@ -1,9 +1,10 @@ #include #include #include -#include "TrafficRules.h" -#include "TrafficRulesFactory.h" + #include "gtest/gtest.h" +#include "lanelet2_traffic_rules/TrafficRules.h" +#include "lanelet2_traffic_rules/TrafficRulesFactory.h" using Attr = lanelet::AttributeName; using AttrStr = lanelet::AttributeNamesString; @@ -12,7 +13,9 @@ using lanelet::Participants; lanelet::RegulatoryElementPtr getSpeedLimit(const std::string& type, const lanelet::AttributeMap& attributes = {}) { using namespace lanelet; - Point3d p1{10, 0, -1}, p2{11, 0, -2}; + Point3d p1{10, 0, -1}; + + Point3d p2{11, 0, -2}; LineString3d sign{7, {p1, p2}}; return SpeedLimit::make(5, attributes, {{sign}, type}); } @@ -20,7 +23,7 @@ lanelet::RegulatoryElementPtr getSpeedLimit(const std::string& type, const lanel lanelet::traffic_rules::TrafficRulesPtr germanVehicleRules() { using namespace lanelet; return traffic_rules::TrafficRulesFactory::create(Locations::Germany, Participants::Vehicle, {}); -}; +} lanelet::traffic_rules::TrafficRulesPtr germanBikeRules() { using namespace lanelet; diff --git a/lanelet2/lanelet2_validation/CHANGELOG.rst b/lanelet2/lanelet2_validation/CHANGELOG.rst new file mode 100644 index 00000000000..2db2470eca8 --- /dev/null +++ b/lanelet2/lanelet2_validation/CHANGELOG.rst @@ -0,0 +1,43 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package lanelet2_validation +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.1 (2020-09-14) +------------------ + +1.1.0 (2020-09-06) +------------------ +* Add experimental support for building with colcon on ros2 and ament_cmake +* Making all includes in lanelet2_validation consistent. +* Updating package.xml files to format 3. +* Contributors: Fabian Poggenhans, Joshua Whitley + +1.0.1 (2020-03-24) +------------------ +* Make sure lanelet2 buildtool_export_depends on mrt_cmake_modules +* Add geometry function to compute curvature from three points + Add tests, cleanup the validator that uses it +* Add changelogs +* Format files +* Contributors: Fabian Poggenhans + +1.0.0 (2020-03-03) +------------------ +* Bump version to 1.0 +* Update cmakelists files +* Fix headers missing their include guards +* Bump version to 0.9 +* Merge branch 'master' into reverse_routing +* Merge branch 'validate_repeated_points' into 'master' + Validate repeated points + See merge request MRT/released/lanelet2!142 +* Add a new IssueReport object returned by lanelet2_validation +* Implement new check in lanelet2_validation for repeated points +* code clean, fix one big curvature point in mapping_example.osm +* add curvature validator and unit test +* Improved readmes and corrected typos +* Documented ele tag for points, add it to validation +* Re-add support for hardcoding sign type or speed limit in regulatory elements +* Add new validators to sanitize tagging of a lanelet map, add unittests +* Add lanelet2 validation +* Contributors: Fabian Poggenhans, Lingguang Wang, Maximilian Naumann diff --git a/lanelet2/lanelet2_validation/CMakeLists.txt b/lanelet2/lanelet2_validation/CMakeLists.txt index 7c941f316fe..6eb87afe539 100644 --- a/lanelet2/lanelet2_validation/CMakeLists.txt +++ b/lanelet2/lanelet2_validation/CMakeLists.txt @@ -1,34 +1,34 @@ -set(MRT_PKG_VERSION 2.2.1) +set(MRT_PKG_VERSION 4.0.0) # Modify only if you know what you are doing! -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(lanelet2_validation) ################### -## find packages ## +## Find packages ## ################### find_package(mrt_cmake_modules REQUIRED) include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) - include(GatherDeps) -# Remove libs which cannot be found automatically -#list(REMOVE_ITEM DEPENDEND_PACKAGES ...) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -# Manually resolve removed dependend packages -#find_package(...) +# You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +# list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +# To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +# You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +endif() -# Mark files or folders for display in IDEs -mrt_add_to_ide(README.md .gitlab-ci.yml) +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) +mrt_parse_package_xml() ######################## -## add python modules ## +## Add python modules ## ######################## # This adds a python module if located under src/{PROJECT_NAME) mrt_python_module_setup() -file(GLOB PROJECT_PYTHON_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "python_api/*.cpp") +mrt_glob_files(PROJECT_PYTHON_SOURCE_FILES_SRC "python_api/*.cpp") if (PROJECT_PYTHON_SOURCE_FILES_SRC) # Add a cpp-python api library. Make sure there are no name collisions with python modules in this project mrt_add_python_api( ${PROJECT_NAME} @@ -37,48 +37,18 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC) endif() ############################ -## read source code files ## +## Read source code files ## ############################ -file(GLOB_RECURSE PROJECT_HEADER_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "include/*.h" "include/*.hpp") -file(GLOB_RECURSE PROJECT_SOURCE_FILES_INC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.h" "src/*.hpp") -file(GLOB_RECURSE PROJECT_SOURCE_FILES_SRC RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "src/*.cpp") - -if (PROJECT_SOURCE_FILES_SRC) - set(LIBRARY_NAME ${PROJECT_NAME}) -endif() - -################################### -## catkin specific configuration ## -################################### -# The catkin_package macro generates cmake config files for your package -# Declare things to be passed to dependent projects -# INCLUDE_DIRS: uncomment this if you package contains header files -# LIBRARIES: libraries you create in this project that dependent projects also need -# CATKIN_DEPENDS: catkin_packages dependent projects also need -# DEPENDS: system dependencies of this project that dependent projects also need -catkin_package( - INCLUDE_DIRS include ${mrt_EXPORT_INCLUDE_DIRS} - LIBRARIES ${LIBRARY_NAME} ${mrt_EXPORT_LIBRARIES} - CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} - ) +mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") +mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") +mrt_glob_files_recurse(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") ########### ## Build ## ########### -# Add include and library directories -include_directories( - include/${PROJECT_NAME} - ${mrt_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ) - -link_directories( - ${mrt_LIBRARY_DIRS} - ) - # Declare a cpp library mrt_add_library(${PROJECT_NAME} - INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} + INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} SOURCES ${PROJECT_SOURCE_FILES_SRC} ) @@ -94,12 +64,12 @@ else() mrt_add_executable(${PROJECT_NAME} FOLDER "tools") endif() - ############# ## Install ## ############# -# Install all targets, headers by default and scripts and other files if specified (folders or files) -mrt_install(PROGRAMS scripts FILES res data) +# Install all targets, headers by default and scripts and other files if specified (folders or files). +# This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) ############# ## Testing ## diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/BasicValidator.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/BasicValidator.h index 2eed878ba3f..a8d9b976512 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/BasicValidator.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/BasicValidator.h @@ -1,8 +1,10 @@ #pragma once #include #include + #include -#include "Issue.h" + +#include "lanelet2_validation/Issue.h" namespace lanelet { namespace routing { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/Cli.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/Cli.h index 351360a1df3..cddf3d89c04 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/Cli.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/Cli.h @@ -1,5 +1,5 @@ #pragma once -#include "Validation.h" +#include "lanelet2_validation/Validation.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/Issue.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/Issue.h index 8562f043587..bfca6bd43b1 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/Issue.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/Issue.h @@ -1,5 +1,6 @@ #pragma once #include + #include #include diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/Validation.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/Validation.h index 9781a8ecf3b..f45e97ac612 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/Validation.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/Validation.h @@ -1,7 +1,8 @@ #pragma once #include #include -#include "Issue.h" + +#include "lanelet2_validation/Issue.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/ValidatorFactory.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/ValidatorFactory.h index 8beaa76838a..2c8bffe039f 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/ValidatorFactory.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/ValidatorFactory.h @@ -1,8 +1,10 @@ #pragma once #include + #include #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/BoolTags.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/BoolTags.h index 6c052919638..9142c33d1d2 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/BoolTags.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/BoolTags.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/CurvatureTooBig.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/CurvatureTooBig.h index 94a9df5e58b..f04d1e496a5 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/CurvatureTooBig.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/CurvatureTooBig.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { @@ -9,9 +10,8 @@ class CurvatureTooBigChecker : public MapValidator { constexpr static const char* name() { return "mapping.curvature_too_big"; } Issues operator()(const LaneletMap& map) override; - double computeCurvature(const BasicPoint2d& p1, const BasicPoint2d& p2, const BasicPoint2d& p3); - void checkCurvature(Issues& issues, const ConstLineString2d& line, const Id& laneletId); + static void checkCurvature(Issues& issues, const ConstLineString2d& line, const Id& laneletId); }; } // namespace validation -} // namespace lanelet \ No newline at end of file +} // namespace lanelet diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/DuplicatedPoints.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/DuplicatedPoints.h index bef11ad6c8e..79afa99145b 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/DuplicatedPoints.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/DuplicatedPoints.h @@ -1,6 +1,7 @@ #pragma once #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/MandatoryTags.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/MandatoryTags.h index 676a59ef04b..3fdc6ed2f25 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/MandatoryTags.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/MandatoryTags.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/PointsTooClose.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/PointsTooClose.h index 2b8dd0238d5..0d4fb45de1a 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/PointsTooClose.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/PointsTooClose.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTagValue.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTagValue.h index dc6074a948f..2ac772d8c96 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTagValue.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTagValue.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTags.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTags.h index daeec32808f..69a0228b18a 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTags.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/mapping/UnknownTags.h @@ -1,5 +1,6 @@ #include -#include "BasicValidator.h" + +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/routing/RoutingGraphIsValid.h b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/routing/RoutingGraphIsValid.h index 53364b3914b..725fc9408e8 100644 --- a/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/routing/RoutingGraphIsValid.h +++ b/lanelet2/lanelet2_validation/include/lanelet2_validation/validators/routing/RoutingGraphIsValid.h @@ -1,4 +1,4 @@ -#include "BasicValidator.h" +#include "lanelet2_validation/BasicValidator.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/package.xml b/lanelet2/lanelet2_validation/package.xml index e5a0b231397..f72e4036cf5 100644 --- a/lanelet2/lanelet2_validation/package.xml +++ b/lanelet2/lanelet2_validation/package.xml @@ -1,7 +1,8 @@ - + + lanelet2_validation - 0.9.0 + 1.1.1 Package for sanitizing lanelet maps BSD @@ -9,8 +10,10 @@ Fabian Poggenhans https://github.com/fzi-forschungszentrum-informatik/lanelet2.git - catkin - mrt_cmake_modules + catkin + ament_cmake_core + mrt_cmake_modules + mrt_cmake_modules gtest lanelet2_core lanelet2_routing @@ -20,6 +23,8 @@ lanelet2_maps + catkin + ament_cmake diff --git a/lanelet2/lanelet2_validation/src/Cli.cpp b/lanelet2/lanelet2_validation/src/Cli.cpp index e150fe47fd9..9b623c7dc0a 100644 --- a/lanelet2/lanelet2_validation/src/Cli.cpp +++ b/lanelet2/lanelet2_validation/src/Cli.cpp @@ -1,4 +1,5 @@ -#include "Cli.h" +#include "lanelet2_validation/Cli.h" + #include #include diff --git a/lanelet2/lanelet2_validation/src/Validation.cpp b/lanelet2/lanelet2_validation/src/Validation.cpp index dbcc45121a1..10fc358536a 100644 --- a/lanelet2/lanelet2_validation/src/Validation.cpp +++ b/lanelet2/lanelet2_validation/src/Validation.cpp @@ -1,10 +1,12 @@ -#include "Validation.h" +#include "lanelet2_validation/Validation.h" + #include #include #include #include #include -#include "ValidatorFactory.h" + +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { @@ -59,7 +61,7 @@ void runRoutingGraphValidators(std::vector& issues, const Regexe if (routingGraphValidators.empty()) { return; } - for (auto& rule : rules) { + for (const auto& rule : rules) { routing::RoutingGraphPtr routingGraph; try { routingGraph = routing::RoutingGraph::build(map, *rule); @@ -77,7 +79,7 @@ void runRoutingGraphValidators(std::vector& issues, const Regexe Issues DetectedIssues::errors() const { Issues errors; - for (auto& issue : issues) { + for (const auto& issue : issues) { if (issue.severity == Severity::Error) { errors.push_back(issue); } @@ -87,7 +89,7 @@ Issues DetectedIssues::errors() const { Issues DetectedIssues::warnings() const { Issues warning; - for (auto& issue : issues) { + for (const auto& issue : issues) { if (issue.severity == Severity::Warning) { warning.push_back(issue); } @@ -102,7 +104,7 @@ Strings availabeChecks(const std::string& filterString) { IssueReport buildReport(std::vector issues) { IssueReport report; for (auto& issue : issues) { - auto buildReports = [& check = issue.checkName](auto& issue) { return issue.buildReport() + " [" + check + "]"; }; + auto buildReports = [&check = issue.checkName](auto& issue) { return issue.buildReport() + " [" + check + "]"; }; auto errorsFromCheck = utils::transform(issue.errors(), buildReports); if (!errorsFromCheck.empty()) { report.errors.insert(report.errors.end(), errorsFromCheck.begin(), errorsFromCheck.end()); diff --git a/lanelet2/lanelet2_validation/src/ValidatorFactory.cpp b/lanelet2/lanelet2_validation/src/ValidatorFactory.cpp index c8786af8aea..9651230f3b5 100644 --- a/lanelet2/lanelet2_validation/src/ValidatorFactory.cpp +++ b/lanelet2/lanelet2_validation/src/ValidatorFactory.cpp @@ -1,4 +1,4 @@ -#include "ValidatorFactory.h" +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { @@ -6,7 +6,7 @@ namespace { std::vector matchSingleRegex(const std::regex& regex, const std::vector& toMatch) { std::vector matches; - for (auto& str : toMatch) { + for (const auto& str : toMatch) { if (std::regex_match(str, regex)) { matches.push_back(str); } diff --git a/lanelet2/lanelet2_validation/src/validators/CheckTags.cpp b/lanelet2/lanelet2_validation/src/validators/CheckTags.cpp index 9d24f1c7e2e..c3ff40949ca 100644 --- a/lanelet2/lanelet2_validation/src/validators/CheckTags.cpp +++ b/lanelet2/lanelet2_validation/src/validators/CheckTags.cpp @@ -1,8 +1,8 @@ -#include "ValidatorFactory.h" -#include "validators/mapping/BoolTags.h" -#include "validators/mapping/MandatoryTags.h" -#include "validators/mapping/UnknownTagValue.h" -#include "validators/mapping/UnknownTags.h" +#include "lanelet2_validation/ValidatorFactory.h" +#include "lanelet2_validation/validators/mapping/BoolTags.h" +#include "lanelet2_validation/validators/mapping/MandatoryTags.h" +#include "lanelet2_validation/validators/mapping/UnknownTagValue.h" +#include "lanelet2_validation/validators/mapping/UnknownTags.h" namespace lanelet { namespace validation { @@ -148,7 +148,7 @@ const std::vector& mandatoryRegelemTags() { Issues checkKnownTags(const AttributeMap& attrs, const std::vector& knownTags, Id id, Primitive primitive) { Issues issues; - for (auto& attr : attrs) { + for (const auto& attr : attrs) { bool isKnown = utils::anyOf(knownTags, [&attr](auto& knownTag) { return startsWith(attr.first, knownTag); }); if (!isKnown) { issues.push_back( @@ -161,7 +161,7 @@ Issues checkKnownTags(const AttributeMap& attrs, const std::vector& Issues checkMandatoryTags(const AttributeMap& attrs, const std::vector& mandatoryTags, Id id, Primitive primitive) { Issues issues; - for (auto& tag : mandatoryTags) { + for (const auto& tag : mandatoryTags) { if (attrs.find(tag) == attrs.end()) { issues.push_back(Issue(Severity::Warning, primitive, id, "should have a " + tag + " attribute.")); } @@ -174,7 +174,7 @@ Issues checkKnownTagValues(const AttributeMap& attrs, const ValueMap& knownTagVa using Attr = AttributeNamesString; Issues issues; auto type = attrs.find(AttributeName::Type); - for (auto& attr : attrs) { + for (const auto& attr : attrs) { auto key = attr.first; bool isSubtype = combineSubtypes && key == Attr::Subtype && type != attrs.end(); if (isSubtype) { @@ -210,12 +210,13 @@ Issues checkAttribute(const AttributeMap& map, Id id, Primitive primitive) { static std::vector boolAttributes{Attr::OneWay, Attr::Dynamic, Attr::LaneChange, Attr::Participant, Attr::Fallback, Attr::Temporary}; Issues issues; - for (auto& attr : map) { + for (const auto& attr : map) { bool isBoolAttr = utils::anyOf(boolAttributes, [&attr](auto& boolAttr) { return startsWith(attr.first, boolAttr); }); if (isBoolAttr && !attr.second.asBool()) { - issues.push_back(Issue(Severity::Warning, primitive, id, "attribute " + attr.first + ": " + attr.second.value() + - " should be convertible to bool, but isn't.")); + issues.push_back( + Issue(Severity::Warning, primitive, id, + "attribute " + attr.first + ": " + attr.second.value() + " should be convertible to bool, but isn't.")); } } return issues; diff --git a/lanelet2/lanelet2_validation/src/validators/CurvatureTooBig.cpp b/lanelet2/lanelet2_validation/src/validators/CurvatureTooBig.cpp index 68f2ba4fc31..9a6b94979e7 100644 --- a/lanelet2/lanelet2_validation/src/validators/CurvatureTooBig.cpp +++ b/lanelet2/lanelet2_validation/src/validators/CurvatureTooBig.cpp @@ -1,7 +1,10 @@ -#include "validators/mapping/CurvatureTooBig.h" +#include "lanelet2_validation/validators/mapping/CurvatureTooBig.h" + +#include + #include -#include "ValidatorFactory.h" -#include "lanelet2_core/geometry/Point.h" + +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { @@ -11,31 +14,21 @@ RegisterMapValidator reg1; Issues CurvatureTooBigChecker::operator()(const LaneletMap& map) { Issues issues; - for (auto& lanelet : map.laneletLayer) { + for (const auto& lanelet : map.laneletLayer) { checkCurvature(issues, utils::to2D(lanelet.leftBound()), lanelet.id()); checkCurvature(issues, utils::to2D(lanelet.rightBound()), lanelet.id()); } return issues; } -double CurvatureTooBigChecker::computeCurvature(const BasicPoint2d& p1, const BasicPoint2d& p2, const BasicPoint2d& p3) { - auto dp = 0.5 * (p3 - p1); - auto ddp = p3 - 2.0 * p2 + p1; - auto denom = std::pow(dp.x() * dp.x() + dp.y() * dp.y(), 3.0 / 2.0); - if (std::fabs(denom) < 1e-20) { - denom = 1e-20; - } - return static_cast((ddp.y() * dp.x() - dp.y() * ddp.x()) / denom); -} - void CurvatureTooBigChecker::checkCurvature(Issues& issues, const ConstLineString2d& line, const Id& laneletId) { auto lineHyb = utils::toHybrid(line); if (lineHyb.size() >= 3) { for (size_t i = 1; i < lineHyb.size() - 1; ++i) { - if (std::fabs(computeCurvature(lineHyb[i - 1], lineHyb[i], lineHyb[i + 1])) > 0.5) { + if (std::fabs(geometry::curvature2d(lineHyb[i - 1], lineHyb[i], lineHyb[i + 1])) > 0.5) { issues.emplace_back(Severity::Warning, Primitive::Lanelet, laneletId, "Curvature at point " + std::to_string(line[i].id()) + - " is bigger than 0.5. This can confuse algorithms using this map."); + " is bigger than 0.5. This can confuse algorithms using this map."); } } } diff --git a/lanelet2/lanelet2_validation/src/validators/DuplicatedPoints.cpp b/lanelet2/lanelet2_validation/src/validators/DuplicatedPoints.cpp index 1479f080f50..a9490b03af9 100644 --- a/lanelet2/lanelet2_validation/src/validators/DuplicatedPoints.cpp +++ b/lanelet2/lanelet2_validation/src/validators/DuplicatedPoints.cpp @@ -1,6 +1,8 @@ -#include "validators/mapping/DuplicatedPoints.h" -#include "ValidatorFactory.h" -#include "lanelet2_core/primitives/Point.h" +#include "lanelet2_validation/validators/mapping/DuplicatedPoints.h" + +#include + +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { @@ -23,7 +25,7 @@ Optional hasDuplicates(const T& elem) { Issues DuplicatedPointsChecker::operator()(const lanelet::LaneletMap& map) { Issues issues; - for (auto& ls : map.lineStringLayer) { + for (const auto& ls : map.lineStringLayer) { auto duplicates = hasDuplicates(ls); if (!!duplicates) { issues.emplace_back(Severity::Error, Primitive::LineString, ls.id(), @@ -31,7 +33,7 @@ Issues DuplicatedPointsChecker::operator()(const lanelet::LaneletMap& map) { " multiple times in succession. This is not allowed!"); } } - for (auto& poly : map.polygonLayer) { + for (const auto& poly : map.polygonLayer) { auto duplicates = hasDuplicates(poly); if (!!duplicates) { issues.emplace_back(Severity::Error, Primitive::Polygon, poly.id(), diff --git a/lanelet2/lanelet2_validation/src/validators/PointsTooClose.cpp b/lanelet2/lanelet2_validation/src/validators/PointsTooClose.cpp index 2ec6846a1db..05d518662c7 100644 --- a/lanelet2/lanelet2_validation/src/validators/PointsTooClose.cpp +++ b/lanelet2/lanelet2_validation/src/validators/PointsTooClose.cpp @@ -1,6 +1,8 @@ -#include "validators/mapping/PointsTooClose.h" -#include "ValidatorFactory.h" -#include "lanelet2_core/geometry/Point.h" +#include "lanelet2_validation/validators/mapping/PointsTooClose.h" + +#include + +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { @@ -10,7 +12,7 @@ RegisterMapValidator reg; Issues PointsTooCloseChecker::operator()(const lanelet::LaneletMap& map) { Issues issues; - for (auto& p : map.pointLayer) { + for (const auto& p : map.pointLayer) { auto nearest = map.pointLayer.nearest(utils::to2D(p).basicPoint(), 2); if (nearest.size() == 2) { auto& next = nearest[0] == p ? nearest[1] : nearest[0]; diff --git a/lanelet2/lanelet2_validation/src/validators/RoutingGraphIsValid.cpp b/lanelet2/lanelet2_validation/src/validators/RoutingGraphIsValid.cpp index eb9abf78048..2f83aae90bd 100644 --- a/lanelet2/lanelet2_validation/src/validators/RoutingGraphIsValid.cpp +++ b/lanelet2/lanelet2_validation/src/validators/RoutingGraphIsValid.cpp @@ -1,6 +1,8 @@ -#include "validators/routing/RoutingGraphIsValid.h" -#include "ValidatorFactory.h" -#include "lanelet2_routing/RoutingGraph.h" +#include "lanelet2_validation/validators/routing/RoutingGraphIsValid.h" + +#include + +#include "lanelet2_validation/ValidatorFactory.h" namespace lanelet { namespace validation { diff --git a/lanelet2/lanelet2_validation/test/lanelet2_validation.cpp b/lanelet2/lanelet2_validation/test/lanelet2_validation.cpp index 84f1815f132..3e30df4c4b0 100644 --- a/lanelet2/lanelet2_validation/test/lanelet2_validation.cpp +++ b/lanelet2/lanelet2_validation/test/lanelet2_validation.cpp @@ -4,8 +4,9 @@ #include #include #include -#include "Cli.h" -#include "Validation.h" + +#include "lanelet2_validation/Cli.h" +#include "lanelet2_validation/Validation.h" TEST(TestAllValidators, onExampleMap) { // NOLINT const char* args[] = {"validator", "../../lanelet2_maps/res/mapping_example.osm", diff --git a/lanelet2/lanelet2_validation/tools/lanelet2_validate/main.cpp b/lanelet2/lanelet2_validation/tools/lanelet2_validate/main.cpp index 279e4a85d12..ae9623c62d6 100644 --- a/lanelet2/lanelet2_validation/tools/lanelet2_validate/main.cpp +++ b/lanelet2/lanelet2_validation/tools/lanelet2_validate/main.cpp @@ -1,4 +1,4 @@ -#include "Cli.h" +#include "lanelet2_validation/Cli.h" int main(int argc, char* argv[]) { auto config = lanelet::validation::parseCommandLine(argc, const_cast(argv)); // NOLINT diff --git a/messages/CONTRIBUTING.md b/messages/CONTRIBUTING.md index 3973501dc91..8b1dfbda427 100644 --- a/messages/CONTRIBUTING.md +++ b/messages/CONTRIBUTING.md @@ -7,7 +7,7 @@ we adhere to the [Contributor Covenant](https://www.contributor-covenant.org/), used [code of conduct](/CODE_OF_CONDUCT.md) adopted by many other communities such as Linux, Ruby on Rails and GitLab. -Everyone participating in the Autoware.Auto community is expected to follow the code of +Everyone participating in the Autoware.AI community is expected to follow the code of conduct. If someone in the community happens to be violating these terms, please let the project @@ -15,7 +15,7 @@ leads know, and we will address it as soon as possible. ## License -Autoware.Auto is licensed under Apache 2, and thus all contributions will be licensed as such +Autoware.AI is licensed under Apache 2, and thus all contributions will be licensed as such as per clause 5 of the Apache 2 License: ~~~ @@ -30,7 +30,7 @@ as per clause 5 of the Apache 2 License: ## Detailed contribution guidelines -For more detailed information on contributing to Autoware, including development processes, -please see the contributing guidelines on the Autoware Wiki: +For more detailed information on contributing to Autoware.AI, please see the contributing +guidelines on the Autoware Wiki: -https://github.com/autowarefoundation/autoware/wiki/Contributing-to-Autoware +https://github.com/Autoware-AI/autoware.ai/wiki/Contributing-to-Autoware diff --git a/messages/DISCLAIMER.md b/messages/DISCLAIMER.md new file mode 100644 index 00000000000..d0d6f97da09 --- /dev/null +++ b/messages/DISCLAIMER.md @@ -0,0 +1,50 @@ +DISCLAIMER + +The open-source software for self-driving vehicles, Autoware.AI, Autoware.IO, +Autoware.Auto. (collectively, referred to as “Autoware”) will be provided by +The Autoware Foundation under the Apache 2.0 License. This “DISCLAIMER” will be +applied to all users of Autoware (a “User” or “Users”) with the Apache 2.0 +License and Users shall hereby approve and acknowledge all the contents +specified in this disclaimer below and will be deemed to consent to this +disclaimer without any objection upon utilizing or downloading Autoware. + + +Disclaimer and Waiver of Warranties + +1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) +including but not limited to any representation or warranty (i) of fitness or +suitability for a particular purpose contemplated by the Users, (ii) of the +expected functions, commercial value, accuracy, or usefulness of the Service, +(iii) that the use by the Users of the Service complies with the laws and +regulations applicable to the Users or any internal rules established by +industrial organizations, (iv) that the Service will be free of interruption or +defects, (v) of the non-infringement of any third party's right and (vi) the +accuracy of the content of the Services and the software itself. + +2. The Autoware Foundation shall not be liable for any damage incurred by the +User that are attributable to the Autoware Foundation for any reasons +whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR +INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. + +3. A User shall be entirely responsible for the content posted by the User and +its use of any content of the Service or the Website. If the User is held +responsible in a civil action such as a claim for damages or even in a criminal +case, the Autoware Foundation and member companies, governments and academic & +non-profit organizations and their directors, officers, employees and agents +(collectively, the “Indemnified Parties”) shall be completely discharged from +any rights or assertions the User may have against the Indemnified Parties, or +from any legal action, litigation or similar procedures. + + +Indemnity + +A User shall indemnify and hold the Indemnified Parties harmless from any of +their damages, losses, liabilities, costs or expenses (including attorneys' +fees or criminal compensation), or any claims or demands made against the +Indemnified Parties by any third party, due to or arising out of, or in +connection with utilizing Autoware (including the representations and +warranties), the violation of applicable Product Liability Law of each country +(including criminal case) or violation of any applicable laws by the Users, or +the content posted by the User or its use of any content of the Service or the +Website. diff --git a/messages/README.md b/messages/README.md index 2b218041116..34057bd21e8 100644 --- a/messages/README.md +++ b/messages/README.md @@ -1,5 +1,7 @@ # messages +![Native CI workflow](https://github.com/Autoware-AI/messages/workflows/Native%20CI%20workflow/badge.svg) ![Cross CI workflow](https://github.com/Autoware-AI/messages/workflows/Cross%20CI%20workflow/badge.svg) + Autoware-specific message and interface definitions. www.autoware.org diff --git a/messages/SUPPORT.md b/messages/SUPPORT.md index 54c7aaa50d9..44606e1ff3c 100644 --- a/messages/SUPPORT.md +++ b/messages/SUPPORT.md @@ -1,5 +1,3 @@ # Support -To get support for Autoware, see the support guidelines on the Autoware wiki: - -https://github.com/autowarefoundation/Autoware/wiki/Support-guidelines +For detailed instructions on getting help, see the [support guidelines](https://github.com/Autoware-AI/autoware.ai/wiki/Support-guidelines). diff --git a/messages/autoware_can_msgs/CHANGELOG.rst b/messages/autoware_can_msgs/CHANGELOG.rst index 410960531a1..40731f02d4a 100644 --- a/messages/autoware_can_msgs/CHANGELOG.rst +++ b/messages/autoware_can_msgs/CHANGELOG.rst @@ -1,6 +1,14 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package autoware_can_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley 1.12.0 (2019-07-12) ------------------- diff --git a/messages/autoware_can_msgs/CMakeLists.txt b/messages/autoware_can_msgs/CMakeLists.txt index 025ace83e1a..54c97b3d823 100644 --- a/messages/autoware_can_msgs/CMakeLists.txt +++ b/messages/autoware_can_msgs/CMakeLists.txt @@ -6,24 +6,21 @@ find_package(catkin REQUIRED COMPONENTS std_msgs ) - -## Generate messages in the 'msg' folder add_message_files( DIRECTORY msg FILES - CANInfo.msg CANData.msg + CANInfo.msg CANPacket.msg ) -## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES - std_msgs + std_msgs ) catkin_package( CATKIN_DEPENDS - message_runtime - std_msgs + message_runtime + std_msgs ) diff --git a/messages/autoware_can_msgs/package.xml b/messages/autoware_can_msgs/package.xml index 655c1a58530..c86894b9e6d 100644 --- a/messages/autoware_can_msgs/package.xml +++ b/messages/autoware_can_msgs/package.xml @@ -1,7 +1,7 @@ autoware_can_msgs - 1.12.0 + 1.14.0 The autoware_can_msgs package Yusuke Fujii Apache 2 @@ -11,8 +11,6 @@ message_generation std_msgs - geometry_msgs - sensor_msgs message_runtime diff --git a/messages/autoware_config_msgs/CHANGELOG.rst b/messages/autoware_config_msgs/CHANGELOG.rst index 238424955b9..f7e254158c9 100644 --- a/messages/autoware_config_msgs/CHANGELOG.rst +++ b/messages/autoware_config_msgs/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package autoware_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Lateral limitation filter by twist_filter +* add param of decision_maker: disable insert stopline +* Add Message Properties for use_sim and use_decision_maker +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley, Yuma Nihei, s-azumi + 1.12.0 (2019-07-12) ------------------- diff --git a/messages/autoware_config_msgs/CMakeLists.txt b/messages/autoware_config_msgs/CMakeLists.txt index 1b967b36824..45956af6a50 100644 --- a/messages/autoware_config_msgs/CMakeLists.txt +++ b/messages/autoware_config_msgs/CMakeLists.txt @@ -6,49 +6,45 @@ find_package(catkin REQUIRED COMPONENTS std_msgs ) -## Generate messages in the 'msg' folder add_message_files( DIRECTORY msg FILES - - ## Runtime Manager ## - ConfigApproximateNDTMapping.msg - ConfigCarDPM.msg - ConfigCarFusion.msg - ConfigCarKF.msg - ConfigCompareMapFilter.msg - ConfigDecisionMaker.msg - ConfigDistanceFilter.msg - ConfigICP.msg - ConfigLaneRule.msg - ConfigLaneSelect.msg - ConfigLaneStop.msg - ConfigLatticeVelocitySet.msg - ConfigNDTMapping.msg - ConfigNDTMappingOutput.msg - ConfigNDT.msg - ConfigPedestrianDPM.msg - ConfigPedestrianFusion.msg - ConfigPedestrianKF.msg - ConfigPlannerSelector.msg - ConfigPoints2Polygon.msg - ConfigRandomFilter.msg - ConfigRayGroundFilter.msg - ConfigRcnn.msg - ConfigRingFilter.msg - ConfigRingGroundFilter.msg - ConfigSSD.msg - ConfigTwistFilter.msg - ConfigVelocitySet.msg - ConfigVoxelGridFilter.msg - ConfigWaypointFollower.msg - ConfigWaypointReplanner.msg + ConfigApproximateNDTMapping.msg + ConfigCarDPM.msg + ConfigCarFusion.msg + ConfigCarKF.msg + ConfigCompareMapFilter.msg + ConfigDecisionMaker.msg + ConfigDistanceFilter.msg + ConfigICP.msg + ConfigLaneRule.msg + ConfigLaneSelect.msg + ConfigLaneStop.msg + ConfigLatticeVelocitySet.msg + ConfigNDT.msg + ConfigNDTMapping.msg + ConfigNDTMappingOutput.msg + ConfigPedestrianDPM.msg + ConfigPedestrianFusion.msg + ConfigPedestrianKF.msg + ConfigPlannerSelector.msg + ConfigPoints2Polygon.msg + ConfigRandomFilter.msg + ConfigRayGroundFilter.msg + ConfigRcnn.msg + ConfigRingFilter.msg + ConfigRingGroundFilter.msg + ConfigSSD.msg + ConfigTwistFilter.msg + ConfigVelocitySet.msg + ConfigVoxelGridFilter.msg + ConfigWaypointFollower.msg + ConfigWaypointReplanner.msg ) -## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES - std_msgs + std_msgs ) catkin_package(CATKIN_DEPENDS diff --git a/messages/autoware_config_msgs/msg/ConfigWaypointReplanner.msg b/messages/autoware_config_msgs/msg/ConfigWaypointReplanner.msg index 9252894bc68..8c0ef59cf89 100644 --- a/messages/autoware_config_msgs/msg/ConfigWaypointReplanner.msg +++ b/messages/autoware_config_msgs/msg/ConfigWaypointReplanner.msg @@ -5,14 +5,10 @@ float32 velocity_max float32 velocity_min float32 accel_limit float32 decel_limit -float32 radius_thresh +float32 lateral_accel_limit float32 radius_min bool resample_mode float32 resample_interval -int32 velocity_offset -int32 end_point_offset -int32 braking_distance bool replan_curve_mode bool replan_endpoint_mode -bool overwrite_vmax_mode bool realtime_tuning_mode diff --git a/messages/autoware_config_msgs/package.xml b/messages/autoware_config_msgs/package.xml index e9023885b05..68f8bbec823 100644 --- a/messages/autoware_config_msgs/package.xml +++ b/messages/autoware_config_msgs/package.xml @@ -1,7 +1,7 @@ autoware_config_msgs - 1.12.0 + 1.14.0 The autoware_config_msgs package Yusuke Fujii Apache 2 diff --git a/messages/autoware_external_msgs/CHANGELOG.rst b/messages/autoware_external_msgs/CHANGELOG.rst index 5474de486f4..f8eb351012e 100644 --- a/messages/autoware_external_msgs/CHANGELOG.rst +++ b/messages/autoware_external_msgs/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_external_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley + 1.12.0 (2019-07-12) ------------------- * Adding CHANGELOG for autoware_external_msgs and autoware_map_msgs. diff --git a/messages/autoware_external_msgs/package.xml b/messages/autoware_external_msgs/package.xml index ce8c18e07ce..c43d67b5b05 100644 --- a/messages/autoware_external_msgs/package.xml +++ b/messages/autoware_external_msgs/package.xml @@ -1,7 +1,7 @@ autoware_external_msgs - 1.12.0 + 1.14.0 Package to contain an install external message dependencies Abraham Monrroy diff --git a/messages/autoware_map_msgs/CHANGELOG.rst b/messages/autoware_map_msgs/CHANGELOG.rst index 32b52cff043..3b1e5233d33 100644 --- a/messages/autoware_map_msgs/CHANGELOG.rst +++ b/messages/autoware_map_msgs/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_map_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley + 1.12.0 (2019-07-12) ------------------- * Adding CHANGELOG for autoware_external_msgs and autoware_map_msgs. diff --git a/messages/autoware_map_msgs/CMakeLists.txt b/messages/autoware_map_msgs/CMakeLists.txt index 1f57cc67697..3b50e74193f 100644 --- a/messages/autoware_map_msgs/CMakeLists.txt +++ b/messages/autoware_map_msgs/CMakeLists.txt @@ -8,44 +8,45 @@ find_package(catkin REQUIRED COMPONENTS add_message_files( FILES - Point.msg - Waypoint.msg - Lane.msg - SignalLight.msg - Signal.msg - LaneSignalLightRelation.msg - WaypointSignalRelation.msg - Area.msg - WaypointRelation.msg - LaneRelation.msg - WaypointLaneRelation.msg - LaneAttributeRelation.msg - LaneChangeRelation.msg - OppositeLaneRelation.msg - Wayarea.msg - - PointArray.msg - WaypointArray.msg - LaneArray.msg - SignalLightArray.msg - SignalArray.msg - LaneSignalLightRelationArray.msg - WaypointSignalRelationArray.msg - AreaArray.msg - WaypointRelationArray.msg - LaneRelationArray.msg - WaypointLaneRelationArray.msg - LaneAttributeRelationArray.msg - LaneChangeRelationArray.msg - OppositeLaneRelationArray.msg - WayareaArray.msg + Area.msg + AreaArray.msg + Lane.msg + LaneArray.msg + LaneAttributeRelation.msg + LaneAttributeRelationArray.msg + LaneChangeRelation.msg + LaneChangeRelationArray.msg + LaneRelation.msg + LaneRelationArray.msg + LaneSignalLightRelation.msg + LaneSignalLightRelationArray.msg + OppositeLaneRelation.msg + OppositeLaneRelationArray.msg + Point.msg + PointArray.msg + Signal.msg + SignalArray.msg + SignalLight.msg + SignalLightArray.msg + Wayarea.msg + WayareaArray.msg + Waypoint.msg + WaypointArray.msg + WaypointLaneRelation.msg + WaypointLaneRelationArray.msg + WaypointRelation.msg + WaypointRelationArray.msg + WaypointSignalRelation.msg + WaypointSignalRelationArray.msg ) generate_messages( DEPENDENCIES - std_msgs + std_msgs ) catkin_package( - CATKIN_DEPENDS message_runtime std_msgs + CATKIN_DEPENDS + message_runtime + std_msgs ) diff --git a/messages/autoware_map_msgs/package.xml b/messages/autoware_map_msgs/package.xml index b724da1ddba..6bc468d9ef2 100644 --- a/messages/autoware_map_msgs/package.xml +++ b/messages/autoware_map_msgs/package.xml @@ -1,7 +1,7 @@ autoware_map_msgs - 1.12.0 + 1.14.0 Includes messages to handle each class in Autoware Map Format mitsudome-r Apache 2 diff --git a/messages/autoware_msgs/CHANGELOG.rst b/messages/autoware_msgs/CHANGELOG.rst index c91db431f9b..5cd28368293 100644 --- a/messages/autoware_msgs/CHANGELOG.rst +++ b/messages/autoware_msgs/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Adding service message for TF-based TLR +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley + 1.12.0 (2019-07-12) ------------------- diff --git a/messages/autoware_msgs/CMakeLists.txt b/messages/autoware_msgs/CMakeLists.txt index 7aef3eb03c6..5fa18efd58a 100644 --- a/messages/autoware_msgs/CMakeLists.txt +++ b/messages/autoware_msgs/CMakeLists.txt @@ -2,93 +2,87 @@ cmake_minimum_required(VERSION 2.8.3) project(autoware_msgs) find_package(catkin REQUIRED COMPONENTS - message_generation - std_msgs - geometry_msgs - sensor_msgs - jsk_recognition_msgs - ) - + geometry_msgs + jsk_recognition_msgs + message_generation + sensor_msgs + std_msgs +) -## Generate messages in the 'msg' folder add_message_files( - DIRECTORY msg - FILES - ControlCommandStamped.msg - CloudCluster.msg - CloudClusterArray.msg - ColorSet.msg - ControlCommand.msg - DetectedObject.msg - DetectedObjectArray.msg - ExtractedPosition.msg - ImageLaneObjects.msg - ImageObjects.msg - LaneArray.msg - PointsImage.msg - ScanImage.msg - Signals.msg - TunedResult.msg - ValueSet.msg - Centroids.msg - DTLane.msg - GeometricRectangle.msg - ICPStat.msg - ImageObj.msg - ImageObjRanged.msg - ImageObjTracked.msg - ImageRect.msg - ImageRectRanged.msg - Lane.msg - NDTStat.msg - ObjLabel.msg - ObjPose.msg - ProjectionMatrix.msg - VscanTracked.msg - VscanTrackedArray.msg - Waypoint.msg - WaypointState.msg - VehicleCmd.msg - VehicleLocation.msg - VehicleStatus.msg - TrafficLightResult.msg - TrafficLightResultArray.msg - - AccelCmd.msg - AdjustXY.msg - BrakeCmd.msg - IndicatorCmd.msg - LampCmd.msg - SteerCmd.msg - TrafficLight.msg - StateCmd.msg - State.msg - ## Sync - SyncTimeMonitor.msg - SyncTimeDiff.msg - - ## Remote Control - RemoteCmd.msg + DIRECTORY msg + FILES + AccelCmd.msg + AdjustXY.msg + BrakeCmd.msg + Centroids.msg + CloudCluster.msg + CloudClusterArray.msg + ColorSet.msg + ControlCommand.msg + ControlCommandStamped.msg + DTLane.msg + DetectedObject.msg + DetectedObjectArray.msg + ExtractedPosition.msg + Gear.msg + GeometricRectangle.msg + ICPStat.msg + ImageLaneObjects.msg + ImageObj.msg + ImageObjRanged.msg + ImageObjTracked.msg + ImageObjects.msg + ImageRect.msg + ImageRectRanged.msg + IndicatorCmd.msg + LampCmd.msg + Lane.msg + LaneArray.msg + NDTStat.msg + ObjLabel.msg + ObjPose.msg + PointsImage.msg + ProjectionMatrix.msg + RemoteCmd.msg + ScanImage.msg + Signals.msg + State.msg + StateCmd.msg + SteerCmd.msg + SyncTimeDiff.msg + SyncTimeMonitor.msg + TrafficLight.msg + TrafficLightResult.msg + TrafficLightResultArray.msg + TunedResult.msg + ValueSet.msg + VehicleCmd.msg + VehicleLocation.msg + VehicleStatus.msg + VscanTracked.msg + VscanTrackedArray.msg + Waypoint.msg + WaypointState.msg ) add_service_files( FILES RecognizeLightState.srv ) -## Generate added messages and services with any dependencies listed here generate_messages( - DEPENDENCIES - std_msgs - geometry_msgs - sensor_msgs - jsk_recognition_msgs + DEPENDENCIES + geometry_msgs + jsk_recognition_msgs + sensor_msgs + std_msgs ) catkin_package( - CATKIN_DEPENDS - message_runtime - std_msgs - geometry_msgs - sensor_msgs - jsk_recognition_msgs + CATKIN_DEPENDS + geometry_msgs + jsk_recognition_msgs + message_runtime + sensor_msgs + std_msgs ) diff --git a/messages/autoware_msgs/msg/Gear.msg b/messages/autoware_msgs/msg/Gear.msg new file mode 100644 index 00000000000..b7e1b83d4f9 --- /dev/null +++ b/messages/autoware_msgs/msg/Gear.msg @@ -0,0 +1,7 @@ +uint8 NONE=0 +uint8 PARK=1 +uint8 REVERSE=2 +uint8 NEUTRAL=3 +uint8 DRIVE=4 +uint8 LOW=5 +uint8 gear \ No newline at end of file diff --git a/messages/autoware_msgs/msg/VehicleCmd.msg b/messages/autoware_msgs/msg/VehicleCmd.msg index a8e029c7454..37ba1f6ef46 100644 --- a/messages/autoware_msgs/msg/VehicleCmd.msg +++ b/messages/autoware_msgs/msg/VehicleCmd.msg @@ -3,7 +3,7 @@ autoware_msgs/SteerCmd steer_cmd autoware_msgs/AccelCmd accel_cmd autoware_msgs/BrakeCmd brake_cmd autoware_msgs/LampCmd lamp_cmd -int32 gear +autoware_msgs/Gear gear_cmd int32 mode geometry_msgs/TwistStamped twist_cmd autoware_msgs/ControlCommand ctrl_cmd diff --git a/messages/autoware_msgs/msg/VehicleStatus.msg b/messages/autoware_msgs/msg/VehicleStatus.msg index 9b1b56b90fb..88f1136c793 100644 --- a/messages/autoware_msgs/msg/VehicleStatus.msg +++ b/messages/autoware_msgs/msg/VehicleStatus.msg @@ -7,7 +7,7 @@ int32 steeringmode int32 MODE_MANUAL=0 int32 MODE_AUTO=1 -int32 gearshift +autoware_msgs/Gear current_gear float64 speed # vehicle velocity [km/s] int32 drivepedal diff --git a/messages/autoware_msgs/msg/Waypoint.msg b/messages/autoware_msgs/msg/Waypoint.msg index 064324c9d84..b25c64b2c3e 100644 --- a/messages/autoware_msgs/msg/Waypoint.msg +++ b/messages/autoware_msgs/msg/Waypoint.msg @@ -16,11 +16,11 @@ float32 cost float32 time_cost # Lane Direction -# FORWARD = 0 -# FORWARD_LEFT = 1 -# FORWARD_RIGHT = 2 -# BACKWARD = 3 -# BACKWARD_LEFT = 4 -# BACKWARD_RIGHT = 5 -# STANDSTILL = 6 +# FORWARD = 0 +# FORWARD_LEFT = 1 +# FORWARD_RIGHT = 2 +# BACKWARD = 3 +# BACKWARD_LEFT = 4 +# BACKWARD_RIGHT = 5 +# STANDSTILL = 6 uint32 direction \ No newline at end of file diff --git a/messages/autoware_msgs/package.xml b/messages/autoware_msgs/package.xml index 05d8fe80eeb..a4d203fe091 100644 --- a/messages/autoware_msgs/package.xml +++ b/messages/autoware_msgs/package.xml @@ -1,7 +1,7 @@ autoware_msgs - 1.12.0 + 1.14.0 The autoware_msgs package Yusuke Fujii Apache 2 diff --git a/messages/autoware_system_msgs/CHANGELOG.rst b/messages/autoware_system_msgs/CHANGELOG.rst index 609df0f7997..024b1c4c4f5 100644 --- a/messages/autoware_system_msgs/CHANGELOG.rst +++ b/messages/autoware_system_msgs/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package autoware_system_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update emergency category in DiagnosticStatus message +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley, Yuma Nihei + 1.12.0 (2019-07-12) ------------------- diff --git a/messages/autoware_system_msgs/CMakeLists.txt b/messages/autoware_system_msgs/CMakeLists.txt index f1948e8221d..1756b475c5b 100644 --- a/messages/autoware_system_msgs/CMakeLists.txt +++ b/messages/autoware_system_msgs/CMakeLists.txt @@ -1,36 +1,31 @@ cmake_minimum_required(VERSION 2.8.3) project(autoware_system_msgs) -add_compile_options(-std=c++14) +add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS message_generation - std_msgs rosgraph_msgs + std_msgs ) add_message_files( FILES - DiagnosticStatus.msg - DiagnosticStatusArray.msg - SystemStatus.msg - NodeStatus.msg - HardwareStatus.msg + DiagnosticStatus.msg + DiagnosticStatusArray.msg + HardwareStatus.msg + NodeStatus.msg + SystemStatus.msg ) generate_messages(DEPENDENCIES - std_msgs rosgraph_msgs + std_msgs ) catkin_package( CATKIN_DEPENDS - message_runtime - std_msgs - rosgraph_msgs + message_runtime + rosgraph_msgs + std_msgs ) - -foreach(dir msg) - install(DIRECTORY ${dir}/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) -endforeach(dir) diff --git a/messages/autoware_system_msgs/package.xml b/messages/autoware_system_msgs/package.xml index 77317a91238..353bdef6722 100644 --- a/messages/autoware_system_msgs/package.xml +++ b/messages/autoware_system_msgs/package.xml @@ -1,7 +1,7 @@ autoware_system_msgs - 1.12.0 + 1.14.0 The autoware_system_msgs package Masaya Kataoka BSD diff --git a/messages/tablet_socket_msgs/CHANGELOG.rst b/messages/tablet_socket_msgs/CHANGELOG.rst index 64ac7ef9313..49b20a6066c 100644 --- a/messages/tablet_socket_msgs/CHANGELOG.rst +++ b/messages/tablet_socket_msgs/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tablet_socket_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley + 1.12.0 (2019-07-12) ------------------- diff --git a/messages/tablet_socket_msgs/CMakeLists.txt b/messages/tablet_socket_msgs/CMakeLists.txt index 89f368a3afb..a0ea80700a8 100644 --- a/messages/tablet_socket_msgs/CMakeLists.txt +++ b/messages/tablet_socket_msgs/CMakeLists.txt @@ -1,184 +1,25 @@ cmake_minimum_required(VERSION 2.8.3) project(tablet_socket_msgs) -## Find catkin macros and libraries -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) -## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS std_msgs message_generation) - -## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) - - -## Uncomment this if the package has a setup.py. This macro ensures -## modules and global scripts declared therein get installed -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -# catkin_python_setup() - -################################################ -## Declare ROS messages, services and actions ## -################################################ - -## To declare and build messages, services or actions from within this -## package, follow these steps: -## * Let MSG_DEP_SET be the set of packages whose message types you use in -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). -## * In the file package.xml: -## * add a build_depend tag for "message_generation" -## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in -## but can be declared for certainty nonetheless: -## * add a run_depend tag for "message_runtime" -## * In this file (CMakeLists.txt): -## * add "message_generation" and every package in MSG_DEP_SET to -## find_package(catkin REQUIRED COMPONENTS ...) -## * add "message_runtime" and every package in MSG_DEP_SET to -## catkin_package(CATKIN_DEPENDS ...) -## * uncomment the add_*_files sections below as needed -## and list every .msg/.srv/.action file to be processed -## * uncomment the generate_messages entry below -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) +find_package(catkin REQUIRED COMPONENTS + message_generation + std_msgs +) -## Generate messages in the 'msg' folder add_message_files( FILES - Waypoint.msg - error_info.msg - gear_cmd.msg - mode_cmd.msg - mode_info.msg - route_cmd.msg + Waypoint.msg + error_info.msg + gear_cmd.msg + mode_cmd.msg + mode_info.msg + route_cmd.msg ) -## Generate services in the 'srv' folder -# add_service_files( -# FILES -# Service1.srv -# Service2.srv -# ) - -## Generate actions in the 'action' folder -# add_action_files( -# FILES -# Action1.action -# Action2.action -# ) - -## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs ) -################################################ -## Declare ROS dynamic reconfigure parameters ## -################################################ - -## To declare and build dynamic reconfigure parameters within this -## package, follow these steps: -## * In the file package.xml: -## * add a build_depend and a run_depend tag for "dynamic_reconfigure" -## * In this file (CMakeLists.txt): -## * add "dynamic_reconfigure" to -## find_package(catkin REQUIRED COMPONENTS ...) -## * uncomment the "generate_dynamic_reconfigure_options" section below -## and list every .cfg file to be processed - -## Generate dynamic reconfigure parameters in the 'cfg' folder -# generate_dynamic_reconfigure_options( -# cfg/DynReconf1.cfg -# cfg/DynReconf2.cfg -# ) - -################################### -## catkin specific configuration ## -################################### -## The catkin_package macro generates cmake config files for your package -## Declare things to be passed to dependent projects -## INCLUDE_DIRS: uncomment this if you package contains header files -## LIBRARIES: libraries you create in this project that dependent projects also need -## CATKIN_DEPENDS: catkin_packages dependent projects also need -## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( -# INCLUDE_DIRS include -# LIBRARIES tablet_socket_msgs CATKIN_DEPENDS message_runtime std_msgs -# DEPENDS system_lib ) - -########### -## Build ## -########### - -## Specify additional locations of header files -## Your package locations should be listed before other locations -# include_directories(include) - -## Declare a C++ library -# add_library(tablet_socket_msgs -# src/${PROJECT_NAME}/tablet_socket_msgs.cpp -# ) - -## Add cmake target dependencies of the library -## as an example, code may need to be generated before libraries -## either from message generation or dynamic reconfigure -# add_dependencies(tablet_socket_msgs ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Declare a C++ executable -# add_executable(tablet_socket_msgs_node src/tablet_socket_msgs_node.cpp) - -## Add cmake target dependencies of the executable -## same as for the library above -# add_dependencies(tablet_socket_msgs_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Specify libraries to link a library or executable target against -# target_link_libraries(tablet_socket_msgs_node -# ${catkin_LIBRARIES} -# ) - -############# -## Install ## -############# - -# all install targets should use catkin DESTINATION variables -# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html - -## Mark executable scripts (Python etc.) for installation -## in contrast to setup.py, you can choose the destination -# install(PROGRAMS -# scripts/my_python_script -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark executables and/or libraries for installation -# install(TARGETS tablet_socket_msgs tablet_socket_msgs_node -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -# ) - -## Mark cpp header files for installation -# install(DIRECTORY include/${PROJECT_NAME}/ -# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} -# FILES_MATCHING PATTERN "*.h" -# PATTERN ".svn" EXCLUDE -# ) - -## Mark other files for installation (e.g. launch and bag files, etc.) -# install(FILES -# # myfile1 -# # myfile2 -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -# ) - -############# -## Testing ## -############# - -## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_tablet_socket_msgs.cpp) -# if(TARGET ${PROJECT_NAME}-test) -# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) -# endif() - -## Add folders to be run by python nosetests -# catkin_add_nosetests(test) diff --git a/messages/tablet_socket_msgs/package.xml b/messages/tablet_socket_msgs/package.xml index 576639f44f1..1f021d03be1 100644 --- a/messages/tablet_socket_msgs/package.xml +++ b/messages/tablet_socket_msgs/package.xml @@ -1,7 +1,7 @@ tablet_socket_msgs - 1.12.0 + 1.14.0 The tablet_socket_msgs package Shohei Fujii Apache 2 diff --git a/messages/vector_map_msgs/CHANGELOG.rst b/messages/vector_map_msgs/CHANGELOG.rst index 6551a4292ac..6d41fb019e2 100644 --- a/messages/vector_map_msgs/CHANGELOG.rst +++ b/messages/vector_map_msgs/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package vector_map_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.14.0 (2020-09-03) +------------------- + +1.13.0 (2019-12-03) +------------------- +* Update package.xml files to Format 2. +* Contributors: Joshua Whitley + 1.12.0 (2019-07-12) ------------------- diff --git a/messages/vector_map_msgs/CMakeLists.txt b/messages/vector_map_msgs/CMakeLists.txt index 08675db336a..17b4a36c2ae 100644 --- a/messages/vector_map_msgs/CMakeLists.txt +++ b/messages/vector_map_msgs/CMakeLists.txt @@ -1,85 +1,86 @@ cmake_minimum_required(VERSION 2.8.3) project(vector_map_msgs) - find_package(catkin REQUIRED COMPONENTS - std_msgs message_generation + std_msgs ) add_message_files( FILES - Point.msg - PointArray.msg - Vector.msg - VectorArray.msg - Line.msg - LineArray.msg - Area.msg - AreaArray.msg - Pole.msg - PoleArray.msg - Box.msg - BoxArray.msg - DTLane.msg - DTLaneArray.msg - Node.msg - NodeArray.msg - Lane.msg - LaneArray.msg - WayArea.msg - WayAreaArray.msg - RoadEdge.msg - RoadEdgeArray.msg - Gutter.msg - GutterArray.msg - Curb.msg - CurbArray.msg - WhiteLine.msg - WhiteLineArray.msg - StopLine.msg - StopLineArray.msg - ZebraZone.msg - ZebraZoneArray.msg - CrossWalk.msg - CrossWalkArray.msg - RoadMark.msg - RoadMarkArray.msg - RoadPole.msg - RoadPoleArray.msg - RoadSign.msg - RoadSignArray.msg - Signal.msg - SignalArray.msg - StreetLight.msg - StreetLightArray.msg - UtilityPole.msg - UtilityPoleArray.msg - GuardRail.msg - GuardRailArray.msg - SideWalk.msg - SideWalkArray.msg - DriveOnPortion.msg - DriveOnPortionArray.msg - CrossRoad.msg - CrossRoadArray.msg - SideStrip.msg - SideStripArray.msg - CurveMirror.msg - CurveMirrorArray.msg - Wall.msg - WallArray.msg - Fence.msg - FenceArray.msg - RailCrossing.msg - RailCrossingArray.msg + Area.msg + AreaArray.msg + Box.msg + BoxArray.msg + CrossRoad.msg + CrossRoadArray.msg + CrossWalk.msg + CrossWalkArray.msg + Curb.msg + CurbArray.msg + CurveMirror.msg + CurveMirrorArray.msg + DTLane.msg + DTLaneArray.msg + DriveOnPortion.msg + DriveOnPortionArray.msg + Fence.msg + FenceArray.msg + GuardRail.msg + GuardRailArray.msg + Gutter.msg + GutterArray.msg + Lane.msg + LaneArray.msg + Line.msg + LineArray.msg + Node.msg + NodeArray.msg + Point.msg + PointArray.msg + Pole.msg + PoleArray.msg + RailCrossing.msg + RailCrossingArray.msg + RoadEdge.msg + RoadEdgeArray.msg + RoadMark.msg + RoadMarkArray.msg + RoadPole.msg + RoadPoleArray.msg + RoadSign.msg + RoadSignArray.msg + SideStrip.msg + SideStripArray.msg + SideWalk.msg + SideWalkArray.msg + Signal.msg + SignalArray.msg + StopLine.msg + StopLineArray.msg + StreetLight.msg + StreetLightArray.msg + UtilityPole.msg + UtilityPoleArray.msg + Vector.msg + VectorArray.msg + Wall.msg + WallArray.msg + WayArea.msg + WayAreaArray.msg + WhiteLine.msg + WhiteLineArray.msg + ZebraZone.msg + ZebraZoneArray.msg ) generate_messages( DEPENDENCIES - std_msgs + std_msgs ) catkin_package( - CATKIN_DEPENDS message_runtime std_msgs + CATKIN_DEPENDS + message_runtime + std_msgs ) diff --git a/messages/vector_map_msgs/package.xml b/messages/vector_map_msgs/package.xml index 60d40abc718..f1fa7375926 100644 --- a/messages/vector_map_msgs/package.xml +++ b/messages/vector_map_msgs/package.xml @@ -1,7 +1,7 @@ vector_map_msgs - 1.12.0 + 1.14.0 The vector_map_msgs package syouji Apache 2 diff --git a/mrt_cmake_modules/.cmake-format b/mrt_cmake_modules/.cmake-format new file mode 100644 index 00000000000..dd02f4084dd --- /dev/null +++ b/mrt_cmake_modules/.cmake-format @@ -0,0 +1,50 @@ +tab_size: 4 +line_width: 120 +enable_markup: False +additional_commands: + mrt_add_executable: + pargs: 1 + kwargs: + FOLDER: "*" + FILES: "*" + DEPENDS: "*" + LIBRARIES: "*" + mrt_add_links: + pargs: 1 + flags: [CUDA, NO_SANITIZER, TEST] + _mrt_export_package: + kwargs: + EXPORTS: "*" + TARGETS: "*" + LIBRARIES: "*" + mrt_add_nodelet: + pargs: 1 + kwargs: + FOLDER: "*" + TARGETNAME: "*" + DEPENDS: "*" + LIBRARIES: "*" + mrt_add_library: + pargs: 1 + kwargs: + INCLUDES: "*" + SOURCES: "*" + DEPENDS: "*" + LIBRARIES: "*" + _mrt_export_package: + kwargs: + EXPORTS: "*" + TARGETS: "*" + LIBRARIES: "*" + _mrt_run_test: + pargs: 3 + flags: [REDIRECT_STDERR] + kwargs: + COMMAND: "*" + COVERAGE_DIR: "*" + configure_package_config_file: + pargs: 2 + flags: [NO_SET_AND_CHECK_MACRO, NO_CHECK_REQUIRED_COMPONENTS_MACRO] + kwargs: + INSTALL_DESTINATION: "*" + diff --git a/mrt_cmake_modules/.gitlab-ci.yml b/mrt_cmake_modules/.gitlab-ci.yml index 670c794129b..581ece98482 100644 --- a/mrt_cmake_modules/.gitlab-ci.yml +++ b/mrt_cmake_modules/.gitlab-ci.yml @@ -7,6 +7,20 @@ code_quality: script: - ls +cmake_format: + # check for formatting issues in cmake files + stage: test + dependencies: [] + only: [master, merge_requests] + cache: {} + variables: + GIT_STRATEGY: fetch + before_script: [] + script: + - sudo apt update && sudo apt install -y python3-pip && pip3 install --user cmake_format pyyaml + - env PATH=~/.local/bin:$PATH find . -name "*.cmake" -exec cmake-format -i {} + + - git diff --exit-code || (echo "CMake formatting issues found. Please fix them first!"; $(exit 1)) + deps: script: # test only a few dependencies. There are too many diff --git a/mrt_cmake_modules/CHANGELOG.rst b/mrt_cmake_modules/CHANGELOG.rst new file mode 100644 index 00000000000..fccc57b14c3 --- /dev/null +++ b/mrt_cmake_modules/CHANGELOG.rst @@ -0,0 +1,86 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mrt_cmake_modules +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2020-09-30) +------------------ +* Fix finding boost python on versions with old cmake but new boost +* Contributors: Fabian Poggenhans + +1.0.7 (2020-09-30) +------------------ +* Fix versioning of sofiles +* Ensure unittests use the right gtest include dir +* Contributors: Fabian Poggenhans + +1.0.6 (2020-09-30) +------------------ +* Fix boost python building for python3 +* Contributors: Fabian Poggenhans + +1.0.5 (2020-09-29) +------------------ +* Fix build for ROS2, gtest should no longer be installed in ROS2 mode +* Improve python nosetest info +* Update boost-python depend message +* Fix python module setup +* Packages can now have both a python module and a python api +* Add qtbase5-dev key +* Contributors: Fabian Poggenhans, Kevin Rösch, Maximilian Naumann + +1.0.4 (2020-08-12) +------------------ +* Deleted deprecated configuration files +* Fix cuda host compiler used for cuda 11 +* Fix __init__.py template for python3 +* Fix target handling for ros2 +* Fix build failures on ROS1 +* Fix the conan support +* Add a dependency on ros_environment to ensure ROS_VERSION is set +* Default to building shared libraries +* Add QtScript to the list of qt components +* Change license to BSD +* Remove traces of GPL-licensed libgps +* Remove unnecessary includes of cuda files +* Update tensorflow c findscript to set new tensorflow include paths +* Add cuda support for node and nodelet. +* Remove usage of ast package for evaulating package.xml conditions +* Fix crash if eval_coverage.py runs with python3 +* Ensure that coverage is also generated for cpp code called from plain rostests +* Contributors: Fabian Poggenhans, Ilia Baltashov, Sven Richter + +1.0.3 (2020-05-25) +------------------ +* Replace deprecated platform.distro call with distro module +* Raise required CMake version to 3.0.2 to suppress warning with Noetic +* Remove boost signals component that is no longer part of boost +* Fixed c++14 test path include. +* Fix installation of python api files +* Update README.md +* Reformat with new version of cmake-format +* Add lcov as dependency again +* Fix FindBoostPython.cmake for cmake below 3.11 and python3 +* Fix multiple include of MrtPCL +* Contributors: Christian-Eike Framing, Fabian Poggenhans, Johannes Beck, Johannes Janosovits, Moritz Cremer + +1.0.2 (2020-03-24) +------------------ +* Fix PCL findscript, disable precompiling +* added jsoncpp +* Make sure packages search for mrt_cmake_modules in their package config +* Fix resolution of packages in underlaying workspaces +* Mention rosdoc.yaml in package.xml +* Contributors: Fabian Poggenhans, Johannes Beck, Johannes Janosovits + +1.0.1 (2020-03-11) +------------------ +* Update maintainer +* Update generate_dependency_file to search CMAKE_PREFIX_PATH for packages instead of ROS_PACKAGE_PATH +* Update package xml to contain ROS urls and use format 3 to specify python version specific deps +* Add a rosdoc file so that ros can build the cmake api +* Contributors: Fabian Poggenhans + +1.0.0 (2020-02-24) +------------------ +* Initial release for ROS +* Contributors: Andre-Marcel Hellmund, Claudio Bandera, Fabian Poggenhans, Johannes Beck, Johannes Graeter, Niels Ole Salscheider, Piotr Orzechowski diff --git a/mrt_cmake_modules/CMakeLists.txt b/mrt_cmake_modules/CMakeLists.txt index 98d988967d7..aa99d8d3d34 100644 --- a/mrt_cmake_modules/CMakeLists.txt +++ b/mrt_cmake_modules/CMakeLists.txt @@ -1,12 +1,37 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.0.2) project(mrt_cmake_modules) -find_package(catkin REQUIRED) +if($ENV{ROS_VERSION} EQUAL 1) + find_package(catkin REQUIRED) + catkin_package(CFG_EXTRAS mrt_cmake_modules-extras.cmake) +else() + cmake_policy(SET CMP0057 NEW) + set(CATKIN_PACKAGE_SHARE_DESTINATION share/${PROJECT_NAME}) + set(CATKIN_PACKAGE_BIN_DESTINATION bin) + find_package(ament_cmake_core REQUIRED) + ament_package(CONFIG_EXTRAS cmake/mrt_cmake_modules-extras.cmake.in) +endif() -catkin_python_setup() +# Install all cmake files +install(DIRECTORY cmake DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(PROGRAMS scripts/generate_cmake_dependency_file.py scripts/init_coverage.py scripts/eval_coverage.py + scripts/run_test.py DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts) +install(PROGRAMS scripts/generate_cmakelists.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +install(FILES yaml/cmake.yaml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/yaml) +install(FILES ci_templates/CMakeLists.txt DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) -catkin_package(CFG_EXTRAS mrt_cmake_modules-extras.cmake) - -## Install all cmake files -install(DIRECTORY cmake/Modules DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake) -install(PROGRAMS scripts/generate_cmake_dependency_file.py DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts) +# Make sure the same test targets exist as in other projects. This is so that "catkin run_tests" works, etc. +if(CATKIN_ENABLE_TESTING) + if(NOT TARGET tests) + add_custom_target(tests) + endif() + if(NOT TARGET run_tests) + # usually catkin does that for us + add_custom_target(run_tests) + enable_testing() + endif() + if(NOT TARGET run_tests_${PROJECT_NAME}) + add_custom_target(run_tests_${PROJECT_NAME}) + add_dependencies(run_tests run_tests_${PROJECT_NAME}) + endif() +endif() diff --git a/mrt_cmake_modules/CODEOWNERS b/mrt_cmake_modules/CODEOWNERS index 4a00795ed98..600531f6a52 100644 --- a/mrt_cmake_modules/CODEOWNERS +++ b/mrt_cmake_modules/CODEOWNERS @@ -1,5 +1 @@ -* @orzechowski @poggenhans @beck - -# Allow mrtbuild to update ROS yaml files. -/yaml/external-mrt-ros-*.yaml @mrtbuild -/yaml/mrt-ros.yaml @mrtbuild +* @roesch @poggenhans @beck diff --git a/mrt_cmake_modules/LICENSE b/mrt_cmake_modules/LICENSE index f58a34ad9b7..2ced447e2b0 100644 --- a/mrt_cmake_modules/LICENSE +++ b/mrt_cmake_modules/LICENSE @@ -1,674 +1,11 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 +Copyright 2020 Karlsruhe Institute of Technology, Institute for Measurement and Control Systems - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: - Preamble +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - The GNU General Public License is a free, copyleft license for -software and other kinds of works. +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - {one line to give the program's name and a brief idea of what it does.} - Copyright (C) 2019 Fabian Poggenhans - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - {project} Copyright (C) 2019 Fabian Poggenhans - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/mrt_cmake_modules/README.md b/mrt_cmake_modules/README.md index 41932c7888b..2d6242f09f3 100644 --- a/mrt_cmake_modules/README.md +++ b/mrt_cmake_modules/README.md @@ -1,66 +1,172 @@ -# mrt_cmake_modules -## Package Summary -This package provides the necessary cmake scripts to make use of several helper functions like e.g. the AutoDeps or the MRT ParamGenerator functionality and adds functions to simplify writing CMakeLists.txt files. - -The mrt_cmake_modules contains the following functionalities to provide simple and portable build and [dependency management](#dependency-management): -* [Simplified CMake functions](#cmake-api) -* [Resolve Debian packages](#base-yaml) -* [Finding thirdparty packages](#findscripts) - +# MRT CMake Modules (Massively Reduced Time writing CMake Modules(*)) Maintainer status: maintained -- Maintainer: Johannes Beck , Claudio Bandera , Fabian Poggenhans -- Author: Johannes Beck -- License: GPL-3.0+ +- Maintainer: Kevin Rösch, Fabian Poggenhans +- Author: Johannes Beck, Claudio Bandera, Fabian Poggenhans +- License: BSD, some files MIT - Bug / feature tracker: https://gitlab.mrt.uni-karlsruhe.de/MRT/mrt_cmake_modules/issues - Source: git https://gitlab.mrt.uni-karlsruhe.de/MRT/mrt_cmake_modules.git (branch: master) -## Dependency management -When using the *mrt_cmake_modules* it is enough to specify your dependencies in your manifest file (i.e. `package.xml`). In your `CMakeLists.txt`, add the following lines, to automatically resolve those dependencies: -```cmake -find_package(mrt_cmake_modules REQUIRED) -include(UseMrtStdCompilerFlags) -include(UseMrtAutoTarget) -include(GatherDeps) -find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) -``` -Your manifest file should contain at least the following to dependencies: -```xml -catkin -mrt_cmake_modules +Imagine you whould never have to write a **CMakeLists.txt** file again. Never forget to install everything, no need to update it whenever you add a file, not time lost for figuring out how to call and use `find_package` for your dependencies, etc. + +Well, this is exactly what `mrt_cmake_modules` do for you! The only thing you have to do is: +- Keep your files in a [fixed structure](#package-structure), +- keep library and executable code in separate packages and +- make sure the package.xml actually contains all the packages you depend on. + +If you don't want to agree to this, there are [ways to get this done as well](#cmake-api). This will require you to modify our template file a bit. + +On the other hand, you get a lot of things for free: +- Resolution of your [dependencies in CMake](#how-dependency-resolution-works-in-detail) +- Automatic generation of Nodes/Nodelets +- Supports C++ and Python(2/3) +- Python bindings for pybind11/boost-python +- Automated unittest detection and execution (including ROS tests) +- Automated [code coverage generation](#generating-code-coverage) +- Support for [sanitizers](#sanitizing-your-code) +- Support for [running clang-tidy](#using-clang-tidy) +- Automated install of your scripts/launchfiles/executables/libraries... to the correct location +- experimental support for **ROS2** and Conan builds + +*) Actually MRT stands for *Institut für Mess- und Regelungstechnik*, the institute that develops this package. + +## Building +`mrt_cmake_modules` is kept as leightweight as possible. It just contains a few CMake (and python) scripts. Its only dependency is `catkin` and `lcov` (for code coverage). + +## Getting started + +Interested? In order to get the CMake template file, you have to run a small script: `rosrun mrt_cmake_modules generate_cmakelists.py [--ros] [--exe]`. +This will create a CMakeLists.txt file ready to be used in your project. We distinguish four different types of packages (this the `--ros` and `--exe` flags): +- **Library package**: They have no dependency to ros (except catkin). Their goal is to either build a `lib.so`, contain only headers, contain a python module, contain python bindings. Or a mixture of these. And unittests, of course. +- **Ros library package (--ros)**: Similar to the above, but can also contain message, action or configuration files +- **Executable package (--exe)**: Provides either a number of executables, scripts or python modules for these scripts. And unittests of course. +- **Node/Nodelet package (--ros --exe)**: Provides a number of nodes or nodelets, python nodes and launchfiles. And rostests of course. + +## Package structure + +The best way to understand how packages have to be layed out is to have a look at the tree of an example package, and what it implies on the build. + +### Libraries + +Here is the structure of a package called `example_package`. It works out of the box with a *CMakeLists.txt* created with `generate_cmakelists.py example_package --ros`: +```bash +. +├── CMakeLists.txt # The generated CMakeLists +├── include # The headers of this package. Available in the whole package +│ └── example_package # It is a ROS convention to keep them within include/ +│ ├── a_header.hpp +│ └── internal # Headers here are only to be used within cpp files of this package +│ └── internal_header.hpp +├── msg +│ └── a_message.msg # Messages files that will be automatically generated (only available for --ros) +├── package.xml # You should know that. Should contain at least pybind11-dev for the bindings +├── python_api # Folder for python bindings. Every file here becoms a module +│ ├── python_bindings.cpp # Will be available as "import example_package.python_bindings" +│ └── more_python_bindings.cpp # Refer to the pybind11 doc for the content of this file +├── README.md # The readme +├── src # Every cpp file in this filder will become part of libexample_package.so +│ ├── examplefile.cpp +│ ├── onemorefile.cpp +│ └── example_package # Python modules have to go to src/ +│ ├── pythonmodule.py # Will be available as "import example_package.pythonmodule" +│ └── __init__.py +└── test # Contains the unittests. Will be executed when running the test or run_tests target + ├── test_example_package.cpp # Every file here will be a separate unittest executable + └── test_pyapi.py # Every py file that matches the testMatch regular expression will be executed + # using nosetest. Executables are ignored. See https://nose.readthedocs.io/ ``` -Other dependecies can be added with one of the following tags: -```xml - Build-time dependency required to build - this package, e.g. boost, opencv. - Exported build-time dependency required to - build packages that depend on this package, - e.g. boost, opencv. - Execution dependency required to run this - package, e.g. boost, opencv, but also all - python dependencies such as python-scipy. - Build-time, exported build-time and execution - dependency. This is a bundled synonym for - , and - . + +Note that everything in this structure is optional and can be left away if you don't need it (except for the CMakeLists.txt of course). + +### Executables, Nodes and Nodelets + +Here is the structure of a package called `example_package_ros_tool`. +It works out of the box with a *CMakeLists.txt* created with `generate_cmakelists.py example_package_ros_tool --exe --ros`: + +```bash +. +├── CMakeLists.txt +├── cfg +│ └── ConfigFile.cfg # Files to be passed to dynamic_reconfigure +├── launch # Contains launch files provided by this package +│ ├── some_node.launch +│ ├── some_nodelet.launch +│ ├── some_python_node.launch +│ └── params # Contains parameter files that will be installed +│ ├── some_parameters.yaml +│ └── some_python_parameters.yaml +├── nodelet_plugins.xml # Should reference the nodelet library at lib/lib--nodelet +├── package.xml # The manifest. It should reference the nodelet_plugins.xml +├── README.md +├── scripts # Executable scripts that will be installed. These can be python nodes as well +│ ├── bias_python_node.py +│ └── bias_script.sh +├── src # Every folder in here will be a node/nodelet or both +│ ├── nodename # nodename is the name of the node/nodelet +│ │ ├── somefile.cpp # Files compiled into the node and the nodelet +│ │ ├── somefile.hpp +│ │ ├── some_node.cpp # files ending with _node will end up being compiled into the node executable +│ │ └── a_nodelet.cpp # files ending whth _nodelet will end up as part of the nodelet library +│ └── example_package_ros_tool # python modules have to go to src/. +│ ├── node_module_python.py # These files can provide the node implementation for the scripts +│ └── __init__.py +└── test # The unittests + ├── test_node.cpp # Every pair of .cpp and .test files represents one rostest + ├── test_node.test + ├── test.cpp # A cpp file without a matching .test a normal unittest and launched without ROS + ├── node_python_test.py # Same for .py and .test files with the same name. The .py file must be executable! + └── node_python_test.test ``` -Additionally, the [MRT tools](https://gitlab.mrt.uni-karlsruhe.de/MRT/mrt_build) provide templates for both `CMakeLists.txt` and `package.xml`, that should be used for creating new packages. -## Unified Parameter Handling for ROS -**UPDATE**: the Documentation for the ParameterGenerator can be found [here](https://github.com/cbandera/rosparam_handler). -The MRT version extends the GitHub version, by allowing the _mrtcfg_ fileending and integrating it into the CMake-Templates. +For a normal, non-ros executable the structure is similar, but simpler. Every folder in the src file will become the name of an executable, and all cpp files within it will be part of the executable. -As always, the [MRT tools](https://gitlab.mrt.uni-karlsruhe.de/MRT/mrt_build) provide templates for the config file as well as for a sample node. +## Generating code coverage +By default, your project is compiled without code coverage information. This can be changed by setting the cmake parameter `MRT_ENABLE_COVERAGE` (e.g. by configuring cmake with `-DMRT_ENABLE_COVERAGE=true`). +Setting this requires a recompilation of the project. +If this is set, running the `run_tests` target will run the unittests and afterwards automatically generate an html coverage report. +The location is printed in the command line. If you set `MRT_ENABLE_COVERAGE=2`, it will also be opened in firefox afterwards. -## CMake API -This package contains a lot of useful cmake functions that are automatically available in all packages using the _mrt_cmake_modules_ as dependency, e.g. `mrt_install()`, `mrt_add_node_and_nodelet()`, etc. See [here](http://htmlpreview.github.io/?https://github.com/KIT-MRT/mrt_cmake_modules/blob/master/doc/generated_cmake_api.html) for a full documentation. +## Sanitizing your code +The Sanitizers [Asan](https://clang.llvm.org/docs/AddressSanitizer.html), [Tsan](https://clang.llvm.org/docs/ThreadSanitizer.html) and [UBsan](https://clang.llvm.org/docs/UndefinedBehaviorSanitizer.html) are great ways of detecting bugs at runtime. +Sadly, you cannot enable them all as once, because Tsan cannot be used together with Asan and UBsan. +You can enable them similarly to the code coverage by setting the `MRT_SANITIZER` cmake variable. It has two possible values: +- checks (enables Asan and UBsan) +- check_race (enables tsan) -## Base yaml -The [base.yml](yaml/base.yaml) controls how AutoDeps and Rosdep finds thirdparty dependencies. +If one of the sanitzers discovers an error at runtime, it will be printed to cerr. -__Rosdep__ is a tool that resolves and installs dependencies in package.xml files by searching the base.yaml (those added to the list of files in `/etc/ros/rosdep/sources.list.d/20-default.list`) for a matching entry and then installing the debian package stated in the _ubuntu_ section of each entry via `apt-get`. +## Using clang-tidy +Clang-tidy checks your code statically at compile time for patterns of unsave or wrong code. Using this feature requires clang-tidy to be installed. +You might also want to provide a .clang-tidy file within your project that enables the checks of your choice. Refere to clang-tidys documentation for details. +You can enable clang-tidy by setting the CMake variable `MRT_CLANG_TIDY`. -__AutoDeps__ (provided by this package) is used to resolve dependencies in the _package.xml_ at CMAKE configure time so that the paths to all thirdparty libraries are known. It searches the _base.yaml_ for matching entries and evaluates the _cmake_ section of matching entry to find out which include/library paths will be set when calling the CMake Command `find_package()`. Only for ``, CMAKE variables are not set. +If you set it to "check", clang-tidy will be run at compile time alongside the normal compiler and print all issues as compiler errors. +If you set it to "fix" the recommended fixes will be applied directly to your code. +**Careful**: Not all fixes ensure that the code compiles. +Also the "fix" mode of clang-tidy is not thread safe, meaning that if you compile with multiple threads, multiple clang-tidy instances might try to fix the same file at the same time. + +## How dependency resolution works in detail +The *mrt_cmake_modules* parse your manifest file (i.e. `package.xml`) in order to figure out your dependencies. The following lines in the `CMakeLists.txt` are responsible for this: +```cmake +find_package(mrt_cmake_modules REQUIRED) # finds this module +include(UseMrtStdCompilerFlags) # sets some generally useful compiler/warning flags +include(GatherDeps) # collects your dependencies and writes them into DEPENDEND_PACKAGES +find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) # resolves your dependencies by calling find_package appropriately. +``` +AutoDeps then figures out, which includes, libraries and targets are needed in order to build this package. +The result is written into `MRT_INCLUDE_DIRS`, `MRT_LIBRARIES` and `MRT_LIBRARY_DIRS`. These variables should be passed to the cmake targets. + +The magic that happens under the hood can be understood by looking at the [cmake.yaml](yaml/cmake.yaml) within this project. It defines, for which dependency in the package.xml which findscript has to be searched and what variables +it will set by the script if successful. These will then be appended to the `MRT_*` variables. + +## CMake API +This package contains a lot of useful cmake functions that are automatically available in all packages using the _mrt_cmake_modules_ as dependency, e.g. `mrt_install()`, `mrt_add_node_and_nodelet()`, `mrt_add_library()`, etc. +The automatically generated file already makes use of them, but you can also use them in your custom CMakeLists. +See [here](http://htmlpreview.github.io/?https://github.com/KIT-MRT/mrt_cmake_modules/blob/master/doc/generated_cmake_api.html) for a full documentation. ## Findscripts This package also contains a collection of [find-scripts](cmake/Modules) for thirdparty dependencies that are usually not shipped with a findscript. These are required by __AutoDeps__. + +## Going further +After you have saved time writing cmake boilerplate, it is now time to also save time writing ROS boilerplate. You might want to look into the [rosinterface_handler](https://github.com/KIT-MRT/rosinterface_handler) as well. It is already intergrated in the CMakeLists template. +All you have to do is write a `.rosif` file, and this project will automatically handle reading parameters from the parameter server, creating subscribers and publishers and handling reconfigure callbacks for you! diff --git a/mrt_cmake_modules/ci_templates/CMakeLists.txt b/mrt_cmake_modules/ci_templates/CMakeLists.txt index 5b0d3d026d1..d984c74b2d6 100644 --- a/mrt_cmake_modules/ci_templates/CMakeLists.txt +++ b/mrt_cmake_modules/ci_templates/CMakeLists.txt @@ -10,7 +10,7 @@ @ | @ # @ | @ # Put a "x" at the position to enable this line @ | @ # E.g a non-ros library has the following mask: @x |x @ -@xx|xx@ set(MRT_PKG_VERSION 3.0.1) +@xx|xx@ set(MRT_PKG_VERSION 4.0.0) @xx|xx@ # Modify only if you know what you are doing! @xx|xx@ cmake_minimum_required(VERSION 3.5.1) @xx|xx@ project(${CMAKE_PACKAGE_NAME}) @@ -20,14 +20,21 @@ @xx|xx@ ################### @xx|xx@ find_package(mrt_cmake_modules REQUIRED) @xx|xx@ include(UseMrtStdCompilerFlags) -@xx|xx@ @xx|xx@ include(GatherDeps) -@xx|xx@ # Remove libs which cannot be found automatically -@xx|xx@ #list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +@xx|xx@ +@xx|xx@ # You can add a custom.cmake in order to add special handling for this package. E.g. you can do: +@xx|xx@ # list(REMOVE_ITEM DEPENDEND_PACKAGES ...) +@xx|xx@ # To remove libs which cannot be found automatically. You can also "find_package" other, custom dependencies there. +@xx|xx@ # You can also set PROJECT_INSTALL_FILES to install files that are not installed by default. +@ x|xx@ # For packages that generate ROS messages, you can do e.g. the following to ensure messages are found: +@ x|xx@ # set(PROJECT_MESSAGE_DEPENDS std_msgs geometry_msgs) +@xx|xx@ if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +@xx|xx@ include("${CMAKE_CURRENT_SOURCE_DIR}/custom.cmake") +@xx|xx@ endif() +@xx|xx@ @xx|xx@ find_package(AutoDeps REQUIRED COMPONENTS ${DEPENDEND_PACKAGES}) @xx|xx@ -@xx|xx@ # Manually resolve removed dependend packages -@xx|xx@ #find_package(...) +@xx|xx@ mrt_parse_package_xml() @xx|xx@ @xx|xx@ ######################## @xx|xx@ ## Add python modules ## @@ -46,7 +53,7 @@ @ x|xx@ ################################################ @ x|xx@ ## Declare ROS messages, services and actions ## @ x|xx@ ################################################ -@ x|xx@ +@ x|xx@ @ x|xx@ # Add message, service and action files @ x|xx@ mrt_add_message_files(msg) @ x|xx@ mrt_add_service_files(srv) @@ -55,9 +62,7 @@ @ x|xx@ # Generate added messages and services with any dependencies listed here @ x|xx@ if (ROS_GENERATE_MESSAGES) @ x|xx@ generate_messages( -@ x|xx@ DEPENDENCIES -@ x|xx@ #add dependencies here -@ x|xx@ #std_msgs +@ x|xx@ DEPENDENCIES ${PROJECT_MESSAGE_DEPENDS} @ x|xx@ ) @ x|xx@ endif() @ x|xx@ @@ -74,31 +79,10 @@ @xx|x @ mrt_glob_files_recurse(PROJECT_HEADER_FILES_INC "include/*.h" "include/*.hpp" "include/*.cuh") @xx|x @ mrt_glob_files(PROJECT_SOURCE_FILES_INC "src/*.h" "src/*.hpp" "src/*.cuh") @xx|x @ mrt_glob_files(PROJECT_SOURCE_FILES_SRC "src/*.cpp" "src/*.cu") -@xx|x @ -@xx|x @ ################################################# -@xx|x @ ## Catkin specific configuration (preparation) ## -@xx|x @ ################################################# -@xx|x @ catkin_package_xml() -@xx|x @ -@xx| x@ ################################### -@xx| x@ ## Catkin specific configuration ## -@xx| x@ ################################### -@xx| x@ catkin_package() -@xx| x@ +@xx|xx@ @xx|xx@ ########### @xx|xx@ ## Build ## @xx|xx@ ########### -@xx|xx@ # Add include and library directories -@xx|xx@ include_directories( -@xx|x @ include/${PROJECT_NAME} -@xx|xx@ ${mrt_INCLUDE_DIRS} -@xx|xx@ ${catkin_INCLUDE_DIRS} -@xx|xx@ ) -@xx|xx@ -@xx|xx@ link_directories( -@xx|xx@ ${mrt_LIBRARY_DIRS} -@xx|xx@ ) -@xx|xx@ @xx|x @ # Declare a cpp library @xx|x @ mrt_add_library(${PROJECT_NAME} @xx|x @ INCLUDES ${PROJECT_HEADER_FILES_INC} ${PROJECT_SOURCE_FILES_INC} @@ -117,27 +101,13 @@ @ x| x@ mrt_add_node_and_nodelet(${PROJECT_NAME} FOLDER "src") @xx| x@ endif() @xx|xx@ -@xx|x @ ################################### -@xx|x @ ## Catkin specific configuration ## -@xx|x @ ################################### -@xx|x @ # The catkin_package macro generates cmake config files for your package -@xx|x @ # Declare things to be passed to dependent projects -@xx|x @ # INCLUDE_DIRS: uncomment this if you package contains header files -@xx|x @ # LIBRARIES: libraries you create in this project that dependent projects also need -@xx|x @ # CATKIN_DEPENDS: catkin_packages dependent projects also need -@xx|x @ # DEPENDS: system dependencies of this project that dependent projects also need -@xx|x @ catkin_package( -@xx|x @ INCLUDE_DIRS include ${mrt_EXPORT_INCLUDE_DIRS} -@xx|x @ LIBRARIES ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${mrt_EXPORT_LIBRARIES} -@xx|x @ CATKIN_DEPENDS ${catkin_EXPORT_DEPENDS} -@xx|x @ ) -@xx|x @ @xx|xx@ ############# @xx|xx@ ## Install ## @xx|xx@ ############# -@xx|xx@ # Install all targets, headers by default and scripts and other files if specified (folders or files) -@ x|xx@ mrt_install(PROGRAMS scripts FILES launch rviz maps res data nodelet_plugins.xml plugin_description.xml) -@x |xx@ mrt_install(PROGRAMS scripts FILES res data) +@xx|xx@ # Install all targets, headers by default and scripts and other files if specified (folders or files). +@xx|xx@ # This command also exports libraries and config files for dependent packages and this supersedes catkin_package. +@ x|xx@ mrt_install(PROGRAMS scripts FILES launch rviz maps res data nodelet_plugins.xml plugin_description.xml ${PROJECT_INSTALL_FILES}) +@x |xx@ mrt_install(PROGRAMS scripts FILES res data ${PROJECT_INSTALL_FILES}) @xx|xx@ @xx|xx@ ############# @xx|xx@ ## Testing ## @@ -145,7 +115,6 @@ @xx|xx@ # Add test targets for cpp and python tests @xx|xx@ if (CATKIN_ENABLE_TESTING) @ x| x@ # Include header in src folder via src//.h -@ x| x@ include_directories("src") @ x|xx@ mrt_add_ros_tests(test) @ x|x @ mrt_add_tests(test) @x |xx@ mrt_add_tests(test) diff --git a/mrt_cmake_modules/ci_templates/catkin_project_template.yml b/mrt_cmake_modules/ci_templates/catkin_project_template.yml index 22d84f6618e..2196dc53fbb 100644 --- a/mrt_cmake_modules/ci_templates/catkin_project_template.yml +++ b/mrt_cmake_modules/ci_templates/catkin_project_template.yml @@ -1,5 +1,5 @@ -#version=1.5 +#version=1.6 include: - - project: 'pub/mrt_cmake_modules' + - project: 'pub/mrt_build_config' ref: master file: '/ci_templates/default_catkin_project.yml' diff --git a/mrt_cmake_modules/ci_templates/default_catkin_project.yml b/mrt_cmake_modules/ci_templates/default_catkin_project.yml index 14d465edcb7..a36faee110c 100644 --- a/mrt_cmake_modules/ci_templates/default_catkin_project.yml +++ b/mrt_cmake_modules/ci_templates/default_catkin_project.yml @@ -1,170 +1,6 @@ -variables: - GIT_STRATEGY: none - GIT_CLONE_PATH: $CI_BUILDS_DIR/gitlab +#version=1.6 +include: + - project: 'pub/mrt_build_config' + ref: master + file: '/ci_templates/default_catkin_project.yml' -# Cache build results between building and testing -cache: - paths: - - catkin_ws/ -stages: - - build - - test - - verify - - deploy - -# Prepare workspace and checkout the code. This will be executed before every stage -before_script: - # Environment variablen setzen - - export SHELL="/bin/bash" - # Prepare workspace (in folder catkin_ws) - - sudo apt-get update && sudo apt-get upgrade -y - - mrt ci prepare $CI_PROJECT_NAME -c $CI_COMMIT_SHA - - cd catkin_ws - # add current branch name to branch management - - mrt ws branches set $CI_COMMIT_REF_NAME - -build: - stage: build - only: [branches, tags, merge_requests] # means "always" - script: - # Build project and resolve deps at the same time in debug mode - - mrt catkin build -s -rd -c --debug --default_yes --no-status $CI_PROJECT_NAME - # generate documentation - - mrt doc build --no-deps $CI_PROJECT_NAME - - cp -r build_debug/$CI_PROJECT_NAME/doxygen_doc/html ../doxygen - # make doxygen documentation available in gitlab - artifacts: - name: doxygen - paths: - - doxygen - expire_in: 6 mos - -general_code_quality: - stage: build - only: [master, release, merge_requests] - allow_failure: true - cache: {} - image: - name: ${CI_REGISTRY}/mrt/misc/mrt_build/gl_codequality - entrypoint: [""] - variables: - GIT_STRATEGY: fetch - SOURCE_CODE: $CI_PROJECT_DIR - CODECLIMATE_DEBUG: "True" - before_script: [] - script: - - /run.sh . - - chmod a+rw gl-code-quality-report.json - artifacts: - paths: [gl-code-quality-report.json] - expire_in: 6 mos - -code_quality: - dependencies: - - general_code_quality - cache: - policy: pull - needs: [general_code_quality] - stage: test - only: [master, release, merge_requests] - artifacts: - paths: [gl-code-quality-report.json] - reports: - codequality: gl-code-quality-report.json - script: - # Build code again, in case caching didn't work - - mrt catkin build -s -rd --debug --default_yes --no-status $CI_PROJECT_NAME - - source devel_debug/setup.bash - - cd src/$CI_PROJECT_NAME - - rm codeclimate.json || true - - cp ../../../gl-code-quality-report.json codeclimate.json || true - - mrt ci codequality $CI_PROJECT_NAME - - cp codeclimate.json ../../../gl-code-quality-report.json - -check_code_quality: - dependencies: - - code_quality - cache: - policy: pull - needs: [code_quality] - stage: verify - only: [master, release, merge_requests] - # default filename is codeclimate.json - script: - - mrt ci validate_codequality $MRT_QUALITY_LEVEL --filename gl-code-quality-report.json - artifacts: - paths: [gl-code-quality-report.json] - before_script: [] - cache: {} - -test: - stage: test - needs: [build] - only: [branches, tags, merge_requests] # means "always" - coverage: '/lines......: \d+.\d+\%/' - variables: - MRT_MIN_COVERAGE: $MRT_REQUIRED_COVERAGE - script: - # Build code again, in case caching didn't work - - mrt catkin build -s -rd --debug --default_yes --no-status $CI_PROJECT_NAME - # Run tests - - source devel_debug/setup.bash - - mrt catkin run_tests --no-status $CI_PROJECT_NAME --no-deps - # Summarize results - - catkin_test_results --verbose build_debug/$CI_PROJECT_NAME - - cp -r build_debug/$CI_PROJECT_NAME/coverage .. || true - # make coverage information available in gitlab - artifacts: - name: coverage - paths: - - coverage - expire_in: 6 mos - reports: - junit: catkin_ws/build_debug/$CI_PROJECT_NAME/test_results/$CI_PROJECT_NAME/*.xml - -report_licenses: - stage: verify - only: [master, release, merge_requests] - needs: [build] - cache: - policy: pull - script: - - mrt ws resolve_deps -y - - mrt ci report_licenses . - - cp licenses.json .. - artifacts: - reports: - license_management: licenses.json - -deps: - stage: verify - needs: [build] - only: [master, release, merge_requests] - variables: - MRT_CI_NO_TIDY: 1 - cache: - paths: - - catkin_ws/ - key: $CI_PROJECT_NAME-$CI_COMMIT_REF_NAME-deps - script: - # test all dependencies of this package. Exclude packages with -e, include with -i. - - mrt ci test_deps -f --no-status --release $CI_PROJECT_NAME $MRT_NAMESPACE -f --default-fail-on-warning - -# This job will create a homepage for your project, where you can browse coverage and doxygen. -# It is available under .pages.mrt.uni-karlsruhe.de///index.html -pages: - before_script: [] - needs: [build] - cache: {} - stage: deploy - script: - # everything in the public folder will be available as website - - mkdir public - - cp -r coverage public/ || true - - cp -r doxygen public/ || true - artifacts: - paths: - - public - only: - # only execute for master branch - - master diff --git a/mrt_cmake_modules/ci_templates/gbp_project.yml b/mrt_cmake_modules/ci_templates/gbp_project.yml index b03d13cdbc9..efc2389c637 100644 --- a/mrt_cmake_modules/ci_templates/gbp_project.yml +++ b/mrt_cmake_modules/ci_templates/gbp_project.yml @@ -1,82 +1,4 @@ -variables: - GIT_STRATEGY: none - CONTAINER_REGISTRY: ${CI_REGISTRY}/mrt/misc/mrt_build - -cache: - key: "empty" - paths: - - .doesnotexist/ - policy: pull - -stages: - - build_src - - build - - deploy - -build_src: - image: $CONTAINER_REGISTRY/mrt_packaging:18.04 - stage: build_src - tags: - - packaging - only: - - xenial - - debian - script: - - git clone --recurse-submodules $CI_REPOSITORY_URL $CI_PROJECT_NAME --branch $CI_COMMIT_REF_NAME - - cd $CI_PROJECT_NAME - - pwd && ls - - gbp buildpackage --git-submodules --git-builder=/bin/true --git-cleaner=/bin/true --git-export-dir= - artifacts: - paths: - - ./*.xz - - ./*.gz - name: "orig" - -build_bionic: - image: $CONTAINER_REGISTRY/mrt_packaging:18.04 - stage: build - tags: - - packaging - only: - - bionic - - debian - script: - - git clone --recurse-submodules $CI_REPOSITORY_URL $CI_PROJECT_NAME --branch $CI_COMMIT_REF_NAME - - cd $CI_PROJECT_NAME - - pwd && ls - - sudo apt update - - mrtdeb_install_build_dependencies - - mrtdeb_increment_version - - gbp buildpackage --git-submodules - artifacts: - paths: - - ./*.deb - - ./*.ddeb - - ./*.xz - - ./*.gz - - ./*.build - - ./*.buildinfo - - ./*.changes - - ./*.dsc - name: "debian_package" - -release_bionic: - image: $CONTAINER_REGISTRY/mrt_packaging:18.04 - stage: deploy - tags: - - packaging - when: manual - only: - - bionic - - debian - variables: - GIT_STRATEGY: none - dependencies: - - build_bionic - script: - # workaround rename ddeb files to deb files (not supported by reprepro) - - for file in *.ddeb; do mv "$file" "${file%.ddeb}.deb"; done || true - - sed -i 's/\.ddeb/.deb/' *.changes - - debsign -kAD63A68F --re-sign *.changes - - reprepro -b $REPOSITORY -v --waitforlock 1000 --ignore=wrongdistribution include $DISTRIBUTION *.changes - +include: + - project: 'pub/mrt_build_config' + ref: master + file: '/ci_templates/gbp_project.yml' diff --git a/mrt_cmake_modules/cmake/Modules/CatkinMockForConan.cmake b/mrt_cmake_modules/cmake/Modules/CatkinMockForConan.cmake index 3ffd4e32e55..24c3bd5b2fb 100644 --- a/mrt_cmake_modules/cmake/Modules/CatkinMockForConan.cmake +++ b/mrt_cmake_modules/cmake/Modules/CatkinMockForConan.cmake @@ -3,25 +3,16 @@ set(catkin_FOUND TRUE) message(STATUS "testing: ${CATKIN_ENABLE_TESTING}") -set(catkin_LIBRARIES ${CONAN_LIBS}) -set(MRT_ARCH ${CONAN_SETTINGS_ARCH}) -set(mrt_LIBRARIES ${${PROJECT_NAME}_LIBRARIES}) +conan_define_targets() +target_link_libraries(${PROJECT_NAME}::auto_deps_export INTERFACE ${CONAN_TARGETS}) +if(CONAN_USER_PYTHON_DEV_CONFIG_python_exec) + set(PYTHON_VERSION ${CONAN_USER_PYTHON_DEV_CONFIG_python_version}) + set(PYTHON_EXECUTABLE ${CONAN_USER_PYTHON_DEV_CONFIG_python_exec}) +endif() set(CATKIN_DEVEL_PREFIX ${CMAKE_CURRENT_BINARY_DIR}) -set(CATKIN_GLOBAL_PYTHON_DESTINATION ${CMAKE_INSTALL_LIBDIR}/python${PYTHON_VERSION}/dist-packages) -set(CATKIN_PACKAGE_LIB_DESTINATION ${CMAKE_INSTALL_LIBDIR}) -set(CATKIN_PACKAGE_BIN_DESTINATION ${CMAKE_INSTALL_BINDIR}) -set(CATKIN_PACKAGE_INCLUDE_DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}) -set(CATKIN_PACKAGE_SHARE_DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}) +set(${PROJECT_NAME}_CATKIN_PACKAGE True) # avoids that export cmake files are generated, conan does this + +function(catkin_package_xml) -function(catkin_package) endfunction() -function(catkin_install_python programs) - cmake_parse_arguments(ARG "OPTIONAL" "DESTINATION" "" ${ARGN}) - if(ARG_OPTIONAL) - set(optional_flag "OPTIONAL") - endif() - foreach(file ${ARG_UNPARSED_ARGUMENTS}) - install(PROGRAMS "${file}" DESTINATION "${ARG_DESTINATION}" ${optional_flag}) - endforeach() -endfunction() \ No newline at end of file diff --git a/mrt_cmake_modules/cmake/Modules/ExportPackage.cmake b/mrt_cmake_modules/cmake/Modules/ExportPackage.cmake new file mode 100644 index 00000000000..a64cb23ff0c --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/ExportPackage.cmake @@ -0,0 +1,118 @@ +function(_mrt_export_package) + cmake_parse_arguments(ARG "" "" "EXPORTS;LIBRARIES;TARGETS" ${ARGN}) + message(STATUS "Generating cmake exports for ${PROJECT_NAME} to ${CATKIN_DEVEL_PREFIX}/share") + + # deduplicate targets (e.g. contained by multiple variables) + if(ARG_TARGETS) + list(REMOVE_DUPLICATES ARG_TARGETS) + endif() + # handle extras file + set(extras_base_name ${CMAKE_CURRENT_SOURCE_DIR}/cmake/${PROJECT_NAME}-extras.cmake) + if(EXISTS ${extras_base_name}) + message(STATUS "Installing extras file '${PROJECT_NAME}-extras.cmake'") + configure_file(${extras_base_name} + ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}-extras.cmake COPYONLY) + install(FILES ${extras_base_name} DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake) + # _mrt_extras_file is expected by the config.cmake + set(_mrt_extras_file ${PROJECT_NAME}-extras.cmake) + elseif(EXISTS ${extras_base_name}.in) + message(STATUS "Installing and configuring extras file '${PROJECT_NAME}-extras.cmake.in'") + set(DEVELSPACE TRUE) + set(INSTALLSPACE FALSE) + set(PROJECT_SPACE_DIR ${CATKIN_DEVEL_PREFIX}) + set(PKG_CMAKE_DIR ${PROJECT_SPACE_DIR}/share/${PROJECT_NAME}/cmake) + set(PKG_INCLUDE_PREFIX ${CMAKE_CURRENT_SOURCE_DIR}) + configure_file(${extras_base_name}.in + ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}-extras.cmake @ONLY) + set(DEVELSPACE FALSE) + set(INSTALLSPACE TRUE) + set(PROJECT_SPACE_DIR ${CMAKE_INSTALL_PREFIX}) + set(PKG_CMAKE_DIR "\${${PROJECT_NAME}_DIR}") + set(PKG_INCLUDE_PREFIX "\\\${prefix}") + configure_file(${extras_base_name}.in + ${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}-extras.cmake @ONLY) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}-extras.cmake + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake) + set(_mrt_extras_file ${PROJECT_NAME}-extras.cmake) + elseif(EXISTS ${extras_base_name}.em) + message( + FATAL_ERROR + "The project contains a ${extras_base_name}.em file. These are not supported by mrt_cmake_modules. Please use ${extras_base_name}.in!" + ) + endif() + + # if we dont export something but still have messages or action files that generate a header, we build a dummy + # target and export that instead + if(NOT ARG_EXPORTS AND (ROS_GENERATE_ACTION OR ROS_GENERATE_MESSAGES)) + add_library(project_generated_headers INTERFACE) + mrt_add_links(project_generated_headers) + set(ARG_LIBRARIES project_generated_headers) + if(TARGET ${PROJECT_NAME}_compiler_flags) + list(APPEND ARG_LIBRARIES ${PROJECT_NAME}_compiler_flags) + endif() + install(TARGETS ${ARG_LIBRARIES} EXPORT generated_headers_exports) + set(ARG_EXPORTS generated_headers_exports) + endif() + + if(ARG_EXPORTS) + # these are expected by the config file + set(_mrt_libraries) + foreach(lib ${ARG_LIBRARIES}) + list(APPEND _mrt_libraries ${PROJECT_NAME}::${lib}) + endforeach() + set(_mrt_targets ${ARG_TARGETS}) + export( + EXPORT ${ARG_EXPORTS} + FILE ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}Targets.cmake + NAMESPACE ${PROJECT_NAME}::) + install( + EXPORT ${ARG_EXPORTS} + FILE ${PROJECT_NAME}Targets.cmake + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake + NAMESPACE ${PROJECT_NAME}::) + # create alias targets for multi-project builds + foreach(lib ${ARG_LIBRARIES}) + add_library(${PROJECT_NAME}::${lib} ALIAS ${lib}) + endforeach() + endif() + + include(CMakePackageConfigHelpers) + # generate the config file that includes the exports + configure_package_config_file( + ${MCM_TEMPLATE_DIR}/packageConfig.cmake.in + "${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}Config.cmake" + INSTALL_DESTINATION "${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake" + NO_SET_AND_CHECK_MACRO NO_CHECK_REQUIRED_COMPONENTS_MACRO) + # generate the version file for the config file + write_basic_package_version_file( + "${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}ConfigVersion.cmake" + VERSION "${${PROJECT_NAME}_VERSION}" + COMPATIBILITY AnyNewerVersion) + install(FILES "${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}ConfigVersion.cmake" + DESTINATION "${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake") + + # "install" the autodeps file to the devel folder + configure_file(${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake + ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/auto_dep_vars.cmake COPYONLY) + # "install" AutoDepsConfig file to the devel folder + configure_file(${MRT_CMAKE_MODULES_CMAKE_PATH}/Modules/FindAutoDeps.cmake + ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}AutoDepsConfig.cmake COPYONLY) + + # install the configuration and dependency file file + install( + FILES "${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}Config.cmake" + "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake" + "${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/cmake/${PROJECT_NAME}AutoDepsConfig.cmake" + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake) + + # install cmake files + if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/cmake) + install( + DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/cmake/ + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake + PATTERN "${PROJECT_NAME}-extras.cmake*" EXCLUDE) + endif() + + # install package.xml + install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/package.xml DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}) +endfunction() diff --git a/mrt_cmake_modules/cmake/Modules/FindANN.cmake b/mrt_cmake_modules/cmake/Modules/FindANN.cmake new file mode 100644 index 00000000000..86f51390288 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindANN.cmake @@ -0,0 +1,11 @@ +set(PACKAGE_HEADER_FILES "ANN/ANN.h") +set(PACKAGE_LIBRARIES ANN ann) + +find_path(ANN_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES}) +find_library(ANN_LIBRARIES NAMES ${PACKAGE_LIBRARIES}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args( + ANN + FOUND_VAR ANN_FOUND + REQUIRED_VARS ANN_INCLUDE_DIR ANN_LIBRARIES) diff --git a/mrt_cmake_modules/cmake/Modules/FindAravis.cmake b/mrt_cmake_modules/cmake/Modules/FindAravis.cmake index 7ad19ab2bc9..499e84bd7e5 100644 --- a/mrt_cmake_modules/cmake/Modules/FindAravis.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindAravis.cmake @@ -1,6 +1,6 @@ find_package(PkgConfig REQUIRED) include(FindPkgConfig) -pkg_check_modules(PC_ARAVIS REQUIRED aravis-0.6) +pkg_check_modules(PC_ARAVIS REQUIRED aravis-0.8) set(Aravis_INCLUDE_DIRS ${PC_ARAVIS_INCLUDE_DIRS}) @@ -11,7 +11,6 @@ foreach(LIB ${PC_ARAVIS_LIBRARIES}) endforeach() include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Aravis DEFAULT_MSG PC_ARAVIS_LIBRARIES PC_ARAVIS_LIBRARY_DIRS PC_ARAVIS_INCLUDE_DIRS) +find_package_handle_standard_args(Aravis DEFAULT_MSG PC_ARAVIS_LIBRARIES PC_ARAVIS_INCLUDE_DIRS) mark_as_advanced(Aravis_LIBRARIES Aravis_INCLUDE_DIRS) - diff --git a/mrt_cmake_modules/cmake/Modules/FindAutoDeps.cmake b/mrt_cmake_modules/cmake/Modules/FindAutoDeps.cmake index fe18882f230..782d381cf61 100644 --- a/mrt_cmake_modules/cmake/Modules/FindAutoDeps.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindAutoDeps.cmake @@ -1,198 +1,312 @@ -#author: Johannes Beck +#author: Johannes Beck, Fabian Poggenhans #email: Johannes.Beck@kit.edu -#license: GPLv3 -# +#license: BSD #This package automatically find_package catkin and non-catkin packages. #It has to be used together with GatherDeps.cmake. # # #Variables used from the generate_cmake_depencency_file.py: +#DEPENDEND_PACKAGES: all packages mentioned in package.xml #_CATKIN_PACKAGES_: contains all catkin packages -#_CATKIN_EXPORT_PACKAGES_: contains only the catkin packages, which shall be exported -# -#_OTHER_PACKAGES_: contains all other packages -#_OTHER_EXPORT_PACKAGES_: contains only the mrt packages, which shall be exported -#_CUDA_CATKIN_PACKAGES_: contains all packages which should be linked to cuda -#_CUDA_OTHER_PACKAGES_: contains all packages which should be linked to cuda +#_${${AutoDeps}_PREFIX}_PACKAGES_: contains all packages that are build_depends +#_${${AutoDeps}_PREFIX}_EXPORT_PACKAGES_: contains all packages that are build_export_depends +#_${${AutoDeps}_PREFIX}_CUDA_PACKAGES_: contains all packages which should be linked to cuda # #__CMAKE_INCLUDE_DIRS_: contains the find package variable include cmake name #__CMAKE_LIBRARY_DIRS_: contains the find package variable libraries cmake name #__CMAKE_LIBRARIES_: contains the find package variable libraries cmake name #__CMAKE_COMPONENTS_: components used in find_package(...) for the package # -#Variables set by this script: -#catkin_DEPENDS: Contains all catkin packages -#catkin_EXPORT_DEPENDS: Contains all catkin packages, which shall be exported. This shall be used in catkin_package +# Sets the following targets: +# ::auto_deps: A target that contains all targets that should be linked against internally +# ::auto_deps_cuda: A target that contains all targets which needs to be linked into cuda code. +# ::auto_deps_export: A target that contains all libraries which need to be linked publically +# ::auto_deps_test: A target that contains all libraries which need to be additionally linked by tests. Contains no libraries if enable_testing is off. # -#mrt_INCLUDE_DIRS: Contains all include directories used for building the package -#mrt_LIBRARY_DIRS: Contains all library directories used for building the package -#mrt_LIBRARIES: Contains all libraries used for building the package -#mrt_CUDA_LIBRARIES: Contains all libraries which needs to be linked into cuda code. -#mrt_TEST_LIBRARIES: Contains all libraries which needs to be linked to test executables. -#mrt_EXPORT_INCLUDE_DIRS: Contains all include directories which dependend packages also need for building -#mrt_EXPORT_LIBRARIES: Contains all libraries which dependend packages also need for building - -set(mrt_INCLUDE_DIRS "") -set(mrt_EXPORT_INCLUDE_DIRS "") -set(mrt_LIBRARIES "") -set(mrt_EXPORT_LIBRARIES "") -set(mrt_CUDA_LIBRARIES "") -set(mrt_TEST_LIBRARIES "") -set(mrt_LIBRARY_DIRS "") - -function(_cleanup_includes var_name_include_dir) - if(${var_name_include_dir}) - # remove /usr/include and /usr/local/include - # The compiler searches in those folders automatically and this can lead to - # problems if there are different versions of the same library installed - # at different places. - list(REMOVE_ITEM ${var_name_include_dir} "/usr/include" "/usr/local/include") - endif() - set (${var_name_include_dir} ${${var_name_include_dir}} PARENT_SCOPE) -endfunction() - -# Detect Conan builds. In this case we don't have to do anything, just load the conanfile and include the catkin mock. -if(CONAN_PACKAGE_NAME OR EXISTS ${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) - if(NOT CONAN_PACKAGE_NAME) - include(${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) - endif() - include(CatkinMockForConan) - return() +# The prefix will be chosen based on the value of the variable ${AutoDeps}_PREFIX if set. Otherwise it is set to "${PROJECT_NAME}" +# +# Also creates a target that has the name component::component for each component passed as an input unless the component itself already defines targets. +# +# For compability with catkin, this file also sets mrt_EXPORT_INCLUDE_DIRS and mrt_EXPORT_LIBRARIES to contain all headers +# and libraries that were found. These can be passed on to catkin_package. This behaviour can be disabled by setting AutoDeps_NO_CATKIN_EXPORT. +# +# A not for developers: This file is installed by several projects and might be executed recursively through find_packge. +# Therefore every variable that is not in a function must have a unique name. +if(NOT ${CMAKE_FIND_PACKAGE_NAME}_PREFIX) + set(${CMAKE_FIND_PACKAGE_NAME}_PREFIX ${PROJECT_NAME}) +endif() +if(TARGET ${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps) + message( + FATAL_ERROR + "AutoDeps targets are already defined! Please make sure that find_package(AutoDeps) is called only once per projct!" + ) endif() -if (AutoDeps_FIND_COMPONENTS) - #extract packages packages - set(_CATKIN_SELECTED_PACKAGES_ "") - set(_OTHER_SELECTED_PACKAGES_ "") - set(_CATKIN_TEST_SELECTED_PACKAGES_ "") - set(_OTHER_TEST_SELECTED_PACKAGES_ "") - - foreach(component ${AutoDeps_FIND_COMPONENTS}) - list(FIND _CATKIN_PACKAGES_ ${component} res) - if(NOT ${res} EQUAL -1) - list(APPEND _CATKIN_SELECTED_PACKAGES_ ${component}) - continue() - endif() +add_library(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps INTERFACE IMPORTED) +add_library(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_test INTERFACE IMPORTED) +add_library(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_cuda INTERFACE IMPORTED) +add_library(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_export INTERFACE IMPORTED) - list(FIND _OTHER_PACKAGES_ ${component} res) - if(NOT ${res} EQUAL -1) - list(APPEND _OTHER_SELECTED_PACKAGES_ ${component}) +function(_cleanup_libraries var_name_libs) + # replace "debug", "general" and "optimized" keywords in the libraries list with generator expressions + list(LENGTH ${var_name_libs} size) + foreach(idx RANGE ${size}) + if(${idx} EQUAL ${size}) continue() endif() - - list(FIND _CATKIN_TEST_PACKAGES_ ${component} res) - if(NOT ${res} EQUAL -1) - list(APPEND _CATKIN_TEST_SELECTED_PACKAGES_ ${component}) - continue() + list(GET ${var_name_libs} ${idx} statement) + if(${statement} STREQUAL "debug") + math(EXPR next ${idx}+1) + list(GET ${var_name_libs} ${next} lib) + list(REMOVE_AT ${var_name_libs} ${next}) + list(INSERT ${var_name_libs} ${next} "$<$:${lib}>") + elseif(${statement} STREQUAL "optimized") + math(EXPR next ${idx}+1) + list(GET ${var_name_libs} ${next} lib) + list(REMOVE_AT ${var_name_libs} ${next}) + list(INSERT ${var_name_libs} ${next} "$<$>:${lib}>") endif() + endforeach() + if(size) + list(REMOVE_ITEM ${var_name_libs} debug optimized general) + endif() + set(${var_name_libs} + ${${var_name_libs}} + PARENT_SCOPE) +endfunction() - list(FIND _OTHER_TEST_PACKAGES_ ${component} res) - if(NOT ${res} EQUAL -1) - list(APPEND _OTHER_TEST_SELECTED_PACKAGES_ ${component}) - continue() +function(_remove_generator_expressions libs_arg) + set(filtered_libs) + foreach(lib ${${libs_arg}}) + if(NOT lib MATCHES "^\\$<\\$:(.*)>") + string(REGEX REPLACE "^\\$<\\$>:(.*)>" "\\0" found ${lib}) + if(lib MATCHES "^\\$<\\$>:(.*)>") + list(APPEND filtered_libs ${CMAKE_MATCH_1}) + else() + if(NOT lib MATCHES "^\\$\\<") # we simply drop all other generator expressions. + list(APPEND filtered_libs ${lib}) + endif() + endif() endif() - - message(SEND_ERROR "Package ${component} specified but not found in package.xml. This package is ignored.") endforeach() - - if(CATKIN_ENABLE_TESTING) - list(APPEND _CATKIN_SELECTED_PACKAGES_ ${_CATKIN_TEST_SELECTED_PACKAGES_}) - list(APPEND _OTHER_SELECTED_PACKAGES_ ${_OTHER_TEST_SELECTED_PACKAGES_}) + set(${libs_arg} + ${filtered_libs} + PARENT_SCOPE) +endfunction() + +function(_get_libs_and_incs_recursive out_libs out_incs lib) + if(NOT TARGET ${lib}) + set(${out_libs} + ${${out_libs}} ${lib} + PARENT_SCOPE) + return() endif() - - #find catkin packages - find_package(catkin REQUIRED COMPONENTS ${_CATKIN_SELECTED_PACKAGES_}) - #append catkin packages libraries to CUDA libraries - foreach(cuda_package ${_CUDA_CATKIN_PACKAGES_}) - list(APPEND mrt_CUDA_LIBRARIES ${${cuda_package}_LIBRARIES}) - endforeach() - - #find other packages - foreach(other_package ${_OTHER_SELECTED_PACKAGES_}) - #check, if cmake variable mapping is available - if(NOT DEFINED _${other_package}_CMAKE_NAME_) - message(FATAL_ERROR "Package ${other_package} is specified for autodepend but cmake variables are not defined. Did you resolve dependencies?") + get_target_property(_target_include ${lib} INTERFACE_INCLUDE_DIRECTORIES) + get_target_property(_target_sys_include ${lib} INTERFACE_SYSTEM_INCLUDE_DIRECTORIES) + set(inc) + if(_target_include) + list(APPEND inc ${_target_include}) + endif() + if(_target_sys_include) + list(APPEND inc ${_target_sys_include}) + endif() + get_target_property(_target_type ${lib} TYPE) + if(${_target_type} STREQUAL "INTERFACE_LIBRARY") + get_target_property(_target_link ${lib} INTERFACE_LINK_LIBRARIES) + if(_target_link) + foreach(lib ${_target_link}) + _get_libs_and_incs_recursive(${out_libs} ${out_incs} ${lib}) + endforeach() endif() - - #find non catkin modules - if(DEFINED _${other_package}_CMAKE_COMPONENTS_) - find_package(${_${other_package}_CMAKE_NAME_} REQUIRED COMPONENTS ${_${other_package}_CMAKE_COMPONENTS_}) - else() - find_package(${_${other_package}_CMAKE_NAME_} REQUIRED) + else() + set(${out_libs} ${${out_libs}} ${lib}) + endif() + + set(${out_libs} + ${${out_libs}} + PARENT_SCOPE) + set(${out_incs} + ${${out_incs}} ${inc} + PARENT_SCOPE) +endfunction() + +macro(_find_dep output_target component) + set(${CMAKE_FIND_PACKAGE_NAME}_targetname ${component}::${component}) + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_CATKIN_PACKAGES_ ${component} + ${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package) + if(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package} EQUAL -1) + # is catkin package + + # only call find_package if it wasn't called already + if(NOT ${component}_LIBRARIES) + find_package(${component} REQUIRED) endif() - - #append found include directories - if(DEFINED _${other_package}_CMAKE_INCLUDE_DIRS_) - if(NOT DEFINED ${_${other_package}_CMAKE_INCLUDE_DIRS_}) - message(FATAL_ERROR "Package ${other_package}: Specified include dir variable ${_${other_package}_CMAKE_INCLUDE_DIRS_} not set.") + + if(${component}_EXPORTS_TARGETS) + # Simple case: Its another package that export targets + if(${component}_LIBRARIES) + set(${CMAKE_FIND_PACKAGE_NAME}_targetname ${${component}_LIBRARIES}) + else() + unset(${CMAKE_FIND_PACKAGE_NAME}_targetname) # the imported project seems to be empty endif() - - list(APPEND mrt_INCLUDE_DIRS ${${_${other_package}_CMAKE_INCLUDE_DIRS_}}) - - list(FIND _OTHER_EXPORT_PACKAGES_ ${other_package} res) - if(NOT ${res} EQUAL -1) - list(APPEND mrt_EXPORT_INCLUDE_DIRS ${${_${other_package}_CMAKE_INCLUDE_DIRS_}}) + elseif(NOT TARGET ${${CMAKE_FIND_PACKAGE_NAME}_targetname}) + # A normal catkin package that doesnt create targets. we have to create a new target. + add_library(${${CMAKE_FIND_PACKAGE_NAME}_targetname} INTERFACE IMPORTED) + set(${CMAKE_FIND_PACKAGE_NAME}_libs ${${component}_LIBRARIES}) + _cleanup_libraries(${CMAKE_FIND_PACKAGE_NAME}_libs) + # cmake-format: off + set_target_properties( + ${${CMAKE_FIND_PACKAGE_NAME}_targetname} + PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${${component}_INCLUDE_DIRS}" + INTERFACE_LINK_DIRECTORIES "${${component}_LIBRARY_DIRS}" + INTERFACE_LINK_LIBRARIES "${${CMAKE_FIND_PACKAGE_NAME}_libs}") + # cmake-format: on + if(${component}_EXPORTED_TARGETS) + add_dependencies(${${CMAKE_FIND_PACKAGE_NAME}_targetname} ${${component}_EXPORTED_TARGETS}) endif() + # TODO: All headers in imported targets are automatically "system" in cmake. In a future cmake version, this behaviour might be overridable. endif() - - #append library directories - if(DEFINED _${other_package}_CMAKE_LIBRARY_DIRS_) - if(NOT DEFINED ${_${other_package}_CMAKE_LIBRARY_DIRS_}) - message(FATAL_ERROR "Package ${other_package}: Specified library dirs variable ${${_${other_package}_CMAKE_LIBRARY_DIRS_}} not set.") + else() + # its an external package + if(_${component}_NO_CMAKE_) + # package is known to set no variables. do nothing. + unset(${CMAKE_FIND_PACKAGE_NAME}_targetname) + elseif(NOT DEFINED _${component}_CMAKE_NAME_) + message( + FATAL_ERROR + "Package ${component} was not found. If it is a catkin package: Make sure it is present. If it is an external package: Make sure it is listed in mrt_cmake_modules/yaml/cmake.yaml!" + ) + else() + #find non-catkin modules + + # test if was found already + set(${CMAKE_FIND_PACKAGE_NAME}_already_found TRUE) + if(NOT DEFINED _${component}_CMAKE_TARGETS_ AND NOT TARGET ${${CMAKE_FIND_PACKAGE_NAME}_targetname}) + set(${CMAKE_FIND_PACKAGE_NAME}_already_found FALSE) + else() + foreach(target ${_${component}_CMAKE_TARGETS_}) + if(NOT TARGET ${target}) + set(${CMAKE_FIND_PACKAGE_NAME}_already_found FALSE) + endif() + endforeach() endif() - - list(APPEND mrt_LIBRARY_DIRS ${${_${other_package}_CMAKE_LIBRARY_DIRS_}}) - endif() - - #append libraries - if(DEFINED _${other_package}_CMAKE_LIBRARIES_) - if(NOT DEFINED ${_${other_package}_CMAKE_LIBRARIES_}) - message(FATAL_ERROR "Package ${other_package}: Specified libraries variable ${${_${other_package}_CMAKE_LIBRARIES_}} not set.") + if(NOT ${CMAKE_FIND_PACKAGE_NAME}_already_found) + if(DEFINED _${component}_CMAKE_COMPONENTS_) + find_package(${_${component}_CMAKE_NAME_} REQUIRED COMPONENTS ${_${component}_CMAKE_COMPONENTS_}) + else() + find_package(${_${component}_CMAKE_NAME_} REQUIRED) + endif() endif() - # Append all libraries to link against a test executable (regular and test only). - list(APPEND mrt_TEST_LIBRARIES ${${_${other_package}_CMAKE_LIBRARIES_}}) - - list(FIND _OTHER_PACKAGES_ ${other_package} res) - if(NOT ${res} EQUAL -1) - list(APPEND mrt_LIBRARIES ${${_${other_package}_CMAKE_LIBRARIES_}}) - endif() + # add them to auto_deps target + if(DEFINED _${component}_CMAKE_TARGETS_) + # the library already defines a target for us. Everything is good. + set(${CMAKE_FIND_PACKAGE_NAME}_targetname ${_${component}_CMAKE_TARGETS_}) + elseif(NOT TARGET ${${CMAKE_FIND_PACKAGE_NAME}_targetname}) + # the library defines no target. Create it from the variables it sets. + add_library(${${CMAKE_FIND_PACKAGE_NAME}_targetname} INTERFACE IMPORTED) + set(${CMAKE_FIND_PACKAGE_NAME}_includes ${${_${component}_CMAKE_INCLUDE_DIRS_}}) + set(${CMAKE_FIND_PACKAGE_NAME}_libs ${${_${component}_CMAKE_LIBRARIES_}}) + _cleanup_libraries(${CMAKE_FIND_PACKAGE_NAME}_libs) + set_target_properties( + ${${CMAKE_FIND_PACKAGE_NAME}_targetname} + PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${${CMAKE_FIND_PACKAGE_NAME}_includes}" + INTERFACE_LINK_DIRECTORIES "${${_${component}_CMAKE_LIBRARY_DIRS_}}" + INTERFACE_LINK_LIBRARIES "${${CMAKE_FIND_PACKAGE_NAME}_libs}") + unset(${CMAKE_FIND_PACKAGE_NAME}_includes) + endif() # package defines targets + endif() # package definition is valid + endif() # catkin vs normal package + # add the target(s) to the output target and cleanup + if(${CMAKE_FIND_PACKAGE_NAME}_targetname) + set_property( + TARGET ${output_target} + APPEND + PROPERTY INTERFACE_LINK_LIBRARIES ${${CMAKE_FIND_PACKAGE_NAME}_targetname}) + unset(${CMAKE_FIND_PACKAGE_NAME}_targetname) + endif() + unset(${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package) +endmacro() - list(FIND _OTHER_EXPORT_PACKAGES_ ${other_package} res) - if(NOT ${res} EQUAL -1) - list(APPEND mrt_EXPORT_LIBRARIES ${${_${other_package}_CMAKE_LIBRARIES_}}) +# Detect Conan builds. In this case we don't have to do anything, just load the conanfile and include the catkin mock. +if(CONAN_PACKAGE_NAME OR EXISTS ${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) + if(NOT CONAN_PACKAGE_NAME) + include(${CMAKE_BINARY_DIR}/conanbuildinfo.cmake) + endif() + include(CatkinMockForConan) + return() +endif() +if(${CMAKE_FIND_PACKAGE_NAME}_FIND_COMPONENTS) + set(${CMAKE_FIND_PACKAGE_NAME}_CATKIN_SELECTED_PACKAGES_) + foreach(${CMAKE_FIND_PACKAGE_NAME}_component ${${CMAKE_FIND_PACKAGE_NAME}_FIND_COMPONENTS}) + # figure out where this variable goes + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_PACKAGES_ ${${CMAKE_FIND_PACKAGE_NAME}_component} + ${CMAKE_FIND_PACKAGE_NAME}_is_package) + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_EXPORT_PACKAGES_ ${${CMAKE_FIND_PACKAGE_NAME}_component} + ${CMAKE_FIND_PACKAGE_NAME}_is_export_package) + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_TEST_PACKAGES_ ${${CMAKE_FIND_PACKAGE_NAME}_component} + ${CMAKE_FIND_PACKAGE_NAME}_is_test_package) + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_CUDA_PACKAGES_ ${${CMAKE_FIND_PACKAGE_NAME}_component} + ${CMAKE_FIND_PACKAGE_NAME}_is_cuda_package) + if(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_export_package} EQUAL -1) + _find_dep(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_export ${${CMAKE_FIND_PACKAGE_NAME}_component}) + list(FIND _${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}_CATKIN_PACKAGES_ ${${CMAKE_FIND_PACKAGE_NAME}_component} + ${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package) + if(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package} EQUAL -1) + list(APPEND ${CMAKE_FIND_PACKAGE_NAME}_CATKIN_SELECTED_PACKAGES_ + ${${CMAKE_FIND_PACKAGE_NAME}_component}) endif() - - list(FIND _CUDA_OTHER_PACKAGES_ ${other_package} res) - if(NOT ${res} EQUAL -1) - list(APPEND mrt_CUDA_LIBRARIES ${${_${other_package}_CMAKE_LIBRARIES_}}) + unset(${CMAKE_FIND_PACKAGE_NAME}_is_catkin_package) + elseif(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_package} EQUAL -1) + _find_dep(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps ${${CMAKE_FIND_PACKAGE_NAME}_component}) + elseif(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_test_package} EQUAL -1) + if(CATKIN_ENABLE_TESTING) + _find_dep(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_test ${${CMAKE_FIND_PACKAGE_NAME}_component}) endif() + else() + message( + SEND_ERROR + "Package ${${CMAKE_FIND_PACKAGE_NAME}_component} specified but not found in package.xml. This package is ignored." + ) endif() + if(NOT ${${CMAKE_FIND_PACKAGE_NAME}_is_cuda_package} EQUAL -1) + _find_dep(${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_cuda ${${CMAKE_FIND_PACKAGE_NAME}_component}) + endif() + unset(${CMAKE_FIND_PACKAGE_NAME}_is_package) + unset(${CMAKE_FIND_PACKAGE_NAME}_is_export_package) + unset(${CMAKE_FIND_PACKAGE_NAME}_is_test_package) + unset(${CMAKE_FIND_PACKAGE_NAME}_is_cuda_package) endforeach() - - # Cleanup include directories. - _cleanup_includes(mrt_INCLUDE_DIRS) - _cleanup_includes(mrt_EXPORT_INCLUDE_DIRS) - _cleanup_includes(catkin_INCLUDE_DIRS) - - # Mark '/opt/mrtsoftware/...' include path as system headers, otherwise - # the order can get messed up between 'local' and 'release'. - set(_ALL_INCLUDE_DIRS ${mrt_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}) - if(_ALL_INCLUDE_DIRS) - list(FIND _ALL_INCLUDE_DIRS "/opt/mrtsoftware/local/include" _FOUND_LOCAL) - list(FIND _ALL_INCLUDE_DIRS "/opt/mrtsoftware/release/include" _FOUND_RELEASE) - if (NOT ${_FOUND_LOCAL} EQUAL -1 OR NOT ${_FOUND_RELEASE} EQUAL -1) - include_directories(SYSTEM "/opt/mrtsoftware/local/include" "/opt/mrtsoftware/release/include") - endif() + # set the variables as expected by catkin_package (for backwards compability) + if(${CMAKE_FIND_PACKAGE_NAME}_NO_CATKIN_EXPORT) + unset(${CMAKE_FIND_PACKAGE_NAME}_CATKIN_SELECTED_PACKAGES_) + return() + endif() + # this part is executed only once per package. We no longer have to use prefixes + set(mrt_EXPORT_INCLUDE_DIRS "") + set(mrt_EXPORT_LIBRARIES "") + set(catkin_EXPORT_DEPENDS ${${CMAKE_FIND_PACKAGE_NAME}_CATKIN_SELECTED_PACKAGES_}) + get_target_property(_export_targets ${${CMAKE_FIND_PACKAGE_NAME}_PREFIX}::auto_deps_export INTERFACE_LINK_LIBRARIES) + if(NOT _export_targets) + unset(_export_targets) # cmake sets it to "_export_targets-NOTFOUND". Sigh. endif() + foreach(_target ${_export_targets}) + _get_libs_and_incs_recursive(mrt_EXPORT_LIBRARIES mrt_EXPORT_INCLUDE_DIRS ${_target}) + endforeach() - #remove -lpthread from exports as this will not work with the catkin find package script. + # cleanup and report + unset(_target_include) + unset(_target_link) + unset(${CMAKE_FIND_PACKAGE_NAME}_CATKIN_SELECTED_PACKAGES_) + if(mrt_EXPORT_INCLUDE_DIRS) + list(REMOVE_DUPLICATES mrt_EXPORT_INCLUDE_DIRS) + endif() if(mrt_EXPORT_LIBRARIES) - list(REMOVE_ITEM mrt_EXPORT_LIBRARIES "-lpthread") + list(REMOVE_DUPLICATES mrt_EXPORT_LIBRARIES) endif() - + # catkin cannot handle generator expressions (of type $) + _remove_generator_expressions(mrt_EXPORT_LIBRARIES) + _remove_generator_expressions(mrt_EXPORT_INCLUDE_DIRS) endif() - -set(catkin_EXPORT_DEPENDS ${_CATKIN_EXPORT_PACKAGES_}) diff --git a/mrt_cmake_modules/cmake/Modules/FindBoostPython.cmake b/mrt_cmake_modules/cmake/Modules/FindBoostPython.cmake index d49b1f0270c..aa0fbbe3eef 100644 --- a/mrt_cmake_modules/cmake/Modules/FindBoostPython.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindBoostPython.cmake @@ -6,32 +6,52 @@ # BoostPython_LIBRARIES - the needed libs for boost+python if(PYTHON_VERSION) - set(_python_version ${PYTHON_VERSION}) + set(_python_version ${PYTHON_VERSION}) else() - set(_python_version 2.7) + set(_python_version 2.7) +endif() +if(_python_version VERSION_EQUAL 3 AND CMAKE_VERSION VERSION_GREATER 3.15) + # we also need the subversion + find_package(Python3 REQUIRED) + set(_python_version ${Python3_VERSION}) endif() - # this only works with a recent cmake/boost combination if(CMAKE_VERSION VERSION_GREATER 3.11) - find_package(Boost COMPONENTS python${_python_version} numpy${_python_version}) + find_package(Boost COMPONENTS python${_python_version} numpy${_python_version}) + # ...unless we are dealing with boost 1.70 and above where we can only hope this finds the right version + if(NOT Boost_PYTHON${_python_version}_FOUND) + set(Boost_PYTHON_VERSION ${_python_version}) + find_package(Boost COMPONENTS python numpy) + set(Boost_PYTHON${_python_version}_FOUND ${Boost_PYTHON_FOUND}) + set(Boost_PYTHON${_python_version}_LIBRARY ${Boost_PYTHON_LIBRARY}) + set(Boost_NUMPY${_python_version}_LIBRARY ${Boost_NUMPY_LIBRARY}) + endif() endif() -if(NOT Boost_FOUND) - find_package(Boost REQUIRED COMPONENTS python) - find_package(Boost QUIET COMPONENTS numpy) # numpy is not available on some boost versions - set(Python_ADDITIONAL_VERSIONS ${_python_version}) - find_package(PythonLibs REQUIRED) - set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${PYTHON_INCLUDE_DIR}) - set(BoostPython_LIBRARIES ${Boost_PYTHON_LIBRARIES} ${Boost_NUMPY_LIBRARIES} ${PYTHON_LIBRARIES}) +if(NOT (Boost_PYTHON${_python_version}_FOUND OR Boost_python_FOUND)) + # on older cmake versions, "python" finds python2, otherwise python3 + set(_search_version) + if(NOT _python_version VERSION_LESS 3) + set(_search_version ${_python_version}) + endif() + find_package(Boost REQUIRED COMPONENTS python${_search_version}) + find_package(Boost QUIET COMPONENTS numpy${_search_version}) # numpy is not available on some boost versions + set(Python_ADDITIONAL_VERSIONS ${_python_version}) + find_package(PythonLibs REQUIRED) + set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${PYTHON_INCLUDE_DIR}) + set(BoostPython_LIBRARIES ${Boost_PYTHON${_search_version}_LIBRARIES} ${Boost_NUMPY${_search_version}_LIBRARIES} + ${PYTHON_LIBRARIES}) elseif(_python_version VERSION_LESS 3) - find_package(Python2 REQUIRED COMPONENTS Development) - set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${Python2_INCLUDE_DIRS}) - set(BoostPython_LIBRARIES ${Boost_PYTHON2.7_LIBRARY} ${Boost_NUMPY2.7_LIBRARY} ${Python2_LIBRARIES}) + find_package(Python2 REQUIRED COMPONENTS Development) + set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${Python2_INCLUDE_DIRS}) + set(BoostPython_LIBRARIES ${Boost_PYTHON${_python_version}_LIBRARY} ${Boost_NUMPY${_python_version}_LIBRARY} + ${Python2_LIBRARIES}) else() - find_package(Python3 REQUIRED COMPONENTS Development) - set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${Python3_INCLUDE_DIRS}) - set(BoostPython_LIBRARIES ${Boost_PYTHON3.6_LIBRARY} ${Boost_NUMPY3.6_LIBRARY} ${Python3_LIBRARIES}) + find_package(Python3 REQUIRED COMPONENTS Development) + set(BoostPython_INCLUDE_DIRS ${Boost_INCLUDE_DIR} ${Python3_INCLUDE_DIRS}) + set(BoostPython_LIBRARIES ${Boost_PYTHON${_python_version}_LIBRARY} ${Boost_NUMPY${_python_version}_LIBRARY} + ${Python3_LIBRARIES}) endif() -find_package_handle_standard_args(BoostPython DEFAULT_MSG BoostPython_LIBRARIES BoostPython_INCLUDE_DIRS) +find_package_handle_standard_args(BoostPython DEFAULT_MSG BoostPython_LIBRARIES BoostPython_INCLUDE_DIRS) diff --git a/mrt_cmake_modules/cmake/Modules/FindCTensorflow.cmake b/mrt_cmake_modules/cmake/Modules/FindCTensorflow.cmake new file mode 100644 index 00000000000..6d28f49b392 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindCTensorflow.cmake @@ -0,0 +1,21 @@ +# try to find tensorflow +find_package(PkgConfig) +find_path(TENSORFLOW_C_INCLUDE_DIR tensorflow/tensorflow/c/c_api.h PATH_SUFFIXES tensorflow) + +set(TENSORFLOW_C_INCLUDE_DIR ${TENSORFLOW_C_INCLUDE_DIR} ${TENSORFLOW_C_INCLUDE_DIR}/tensorflow) + +find_library(TENSORFLOW_C_LIBRARY NAMES tensorflow) +find_library(TENSORFLOW_FRAMEWORK_LIBRARY NAMES tensorflow_framework) + +if(TENSORFLOW_FRAMEWORK_LIBRARY) + set(TENSORFLOW_LIBRARY ${TENSORFLOW_C_LIBRARY} ${TENSORFLOW_FRAMEWORK_LIBRARY}) +else() + set(TENSORFLOW_LIBRARY ${TENSORFLOW_C_LIBRARY}) +endif(TENSORFLOW_FRAMEWORK_LIBRARY) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(CTensorflow DEFAULT_MSG TENSORFLOW_LIBRARY TENSORFLOW_C_INCLUDE_DIR) + +mark_as_advanced(TENSORFLOW_LIBRARY TENSORFLOW_C_INCLUDE_DIR) +set(TENSORFLOW_LIBRARIES ${TENSORFLOW_LIBRARY}) +set(TENSORFLOW_C_INCLUDE_DIRS ${TENSORFLOW_C_INCLUDE_DIR}) diff --git a/mrt_cmake_modules/cmake/Modules/FindCairo.cmake b/mrt_cmake_modules/cmake/Modules/FindCairo.cmake index 202c256ac84..ba5fc5045e1 100644 --- a/mrt_cmake_modules/cmake/Modules/FindCairo.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindCairo.cmake @@ -8,40 +8,40 @@ # Define CAIRO_MIN_VERSION for which version desired. # -INCLUDE(FindPkgConfig) +include(FindPkgConfig) -IF(Cairo_FIND_REQUIRED) - SET(_pkgconfig_REQUIRED "REQUIRED") -ELSE(Cairo_FIND_REQUIRED) - SET(_pkgconfig_REQUIRED "") -ENDIF(Cairo_FIND_REQUIRED) +if(Cairo_FIND_REQUIRED) + set(_pkgconfig_REQUIRED "REQUIRED") +else(Cairo_FIND_REQUIRED) + set(_pkgconfig_REQUIRED "") +endif(Cairo_FIND_REQUIRED) -IF(CAIRO_MIN_VERSION) - PKG_SEARCH_MODULE(CAIRO ${_pkgconfig_REQUIRED} cairo>=${CAIRO_MIN_VERSION}) -ELSE(CAIRO_MIN_VERSION) - PKG_SEARCH_MODULE(CAIRO ${_pkgconfig_REQUIRED} cairo) -ENDIF(CAIRO_MIN_VERSION) +if(CAIRO_MIN_VERSION) + pkg_search_module(CAIRO ${_pkgconfig_REQUIRED} cairo>=${CAIRO_MIN_VERSION}) +else(CAIRO_MIN_VERSION) + pkg_search_module(CAIRO ${_pkgconfig_REQUIRED} cairo) +endif(CAIRO_MIN_VERSION) -IF(NOT CAIRO_FOUND AND NOT PKG_CONFIG_FOUND) - FIND_PATH(CAIRO_INCLUDE_DIRS cairo.h) - FIND_LIBRARY(CAIRO_LIBRARIES cairo) +if(NOT CAIRO_FOUND AND NOT PKG_CONFIG_FOUND) + find_path(CAIRO_INCLUDE_DIRS cairo.h) + find_library(CAIRO_LIBRARIES cairo) - # Report results - IF(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) - SET(CAIRO_FOUND 1) - IF(NOT Cairo_FIND_QUIETLY) - MESSAGE(STATUS "Found Cairo: ${CAIRO_LIBRARIES}") - ENDIF(NOT Cairo_FIND_QUIETLY) - ELSE(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) - IF(Cairo_FIND_REQUIRED) - MESSAGE(SEND_ERROR "Could not find Cairo") - ELSE(Cairo_FIND_REQUIRED) - IF(NOT Cairo_FIND_QUIETLY) - MESSAGE(STATUS "Could not find Cairo") - ENDIF(NOT Cairo_FIND_QUIETLY) - ENDIF(Cairo_FIND_REQUIRED) - ENDIF(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) -ENDIF(NOT CAIRO_FOUND AND NOT PKG_CONFIG_FOUND) + # Report results + if(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) + set(CAIRO_FOUND 1) + if(NOT Cairo_FIND_QUIETLY) + message(STATUS "Found Cairo: ${CAIRO_LIBRARIES}") + endif(NOT Cairo_FIND_QUIETLY) + else(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) + if(Cairo_FIND_REQUIRED) + message(SEND_ERROR "Could not find Cairo") + else(Cairo_FIND_REQUIRED) + if(NOT Cairo_FIND_QUIETLY) + message(STATUS "Could not find Cairo") + endif(NOT Cairo_FIND_QUIETLY) + endif(Cairo_FIND_REQUIRED) + endif(CAIRO_LIBRARIES AND CAIRO_INCLUDE_DIRS) +endif(NOT CAIRO_FOUND AND NOT PKG_CONFIG_FOUND) # Hide advanced variables from CMake GUIs -MARK_AS_ADVANCED(CAIRO_LIBRARIES CAIRO_INCLUDE_DIRS) +mark_as_advanced(CAIRO_LIBRARIES CAIRO_INCLUDE_DIRS) diff --git a/mrt_cmake_modules/cmake/Modules/FindCereal.cmake b/mrt_cmake_modules/cmake/Modules/FindCereal.cmake new file mode 100644 index 00000000000..1a18dddab20 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindCereal.cmake @@ -0,0 +1,11 @@ +set(PACKAGE_HEADER_FILES cereal/cereal.hpp) + +find_path(Cereal_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args( + Cereal + FOUND_VAR Cereal_FOUND + REQUIRED_VARS Cereal_INCLUDE_DIR) + +add_definitions(-DHAS_CEREAL) diff --git a/mrt_cmake_modules/cmake/Modules/FindClangTidy.cmake b/mrt_cmake_modules/cmake/Modules/FindClangTidy.cmake index 4c807ca0d1e..52e23825048 100644 --- a/mrt_cmake_modules/cmake/Modules/FindClangTidy.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindClangTidy.cmake @@ -1,13 +1,11 @@ find_program( - ClangTidy_EXE - NAMES "clang-tidy" - DOC "Path to clang-tidy executable" -) + ClangTidy_EXE + NAMES "clang-tidy" + DOC "Path to clang-tidy executable") include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(ClangTidy +find_package_handle_standard_args( + ClangTidy FOUND_VAR ClangTidy_FOUND - REQUIRED_VARS ClangTidy_EXE -) + REQUIRED_VARS ClangTidy_EXE) mark_as_advanced(CLANG_TIDY_EXE) - diff --git a/mrt_cmake_modules/cmake/Modules/FindEigen2.cmake b/mrt_cmake_modules/cmake/Modules/FindEigen2.cmake deleted file mode 100644 index 8c9814a6008..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindEigen2.cmake +++ /dev/null @@ -1,81 +0,0 @@ -# - Try to find Eigen2 lib -# -# This module supports requiring a minimum version, e.g. you can do -# find_package(Eigen2 2.0.3) -# to require version 2.0.3 to newer of Eigen2. -# -# Once done this will define -# -# EIGEN2_FOUND - system has eigen lib with correct version -# EIGEN2_INCLUDE_DIR - the eigen include directory -# EIGEN2_VERSION - eigen version - -# Copyright (c) 2006, 2007 Montel Laurent, -# Copyright (c) 2008, 2009 Gael Guennebaud, -# Redistribution and use is allowed according to the terms of the BSD license. - -if(NOT Eigen2_FIND_VERSION) - if(NOT Eigen2_FIND_VERSION_MAJOR) - set(Eigen2_FIND_VERSION_MAJOR 2) - endif(NOT Eigen2_FIND_VERSION_MAJOR) - if(NOT Eigen2_FIND_VERSION_MINOR) - set(Eigen2_FIND_VERSION_MINOR 0) - endif(NOT Eigen2_FIND_VERSION_MINOR) - if(NOT Eigen2_FIND_VERSION_PATCH) - set(Eigen2_FIND_VERSION_PATCH 0) - endif(NOT Eigen2_FIND_VERSION_PATCH) - - set(Eigen2_FIND_VERSION "${Eigen2_FIND_VERSION_MAJOR}.${Eigen2_FIND_VERSION_MINOR}.${Eigen2_FIND_VERSION_PATCH}") -endif(NOT Eigen2_FIND_VERSION) - -macro(_eigen2_check_version) - file(READ "${EIGEN2_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen2_version_header) - - string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen2_world_version_match "${_eigen2_version_header}") - set(EIGEN2_WORLD_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen2_major_version_match "${_eigen2_version_header}") - set(EIGEN2_MAJOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen2_minor_version_match "${_eigen2_version_header}") - set(EIGEN2_MINOR_VERSION "${CMAKE_MATCH_1}") - - set(EIGEN2_VERSION ${EIGEN2_WORLD_VERSION}.${EIGEN2_MAJOR_VERSION}.${EIGEN2_MINOR_VERSION}) - if((${EIGEN2_WORLD_VERSION} NOTEQUAL 2) OR (${EIGEN2_MAJOR_VERSION} GREATER 10) OR (${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION})) - set(EIGEN2_VERSION_OK FALSE) - else() - set(EIGEN2_VERSION_OK TRUE) - endif() - - if(NOT EIGEN2_VERSION_OK) - - message(STATUS "Eigen2 version ${EIGEN2_VERSION} found in ${EIGEN2_INCLUDE_DIR}, " - "but at least version ${Eigen2_FIND_VERSION} is required") - endif(NOT EIGEN2_VERSION_OK) -endmacro(_eigen2_check_version) - -if (EIGEN2_INCLUDE_DIR) - - # in cache already - _eigen2_check_version() - set(EIGEN2_FOUND ${EIGEN2_VERSION_OK}) - -else (EIGEN2_INCLUDE_DIR) - -find_path(EIGEN2_INCLUDE_DIR NAMES Eigen/Core - PATHS - ${INCLUDE_INSTALL_DIR} - ${KDE4_INCLUDE_DIR} - PATH_SUFFIXES eigen2 - ) - -if(EIGEN2_INCLUDE_DIR) - _eigen2_check_version() -endif(EIGEN2_INCLUDE_DIR) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Eigen2 DEFAULT_MSG EIGEN2_INCLUDE_DIR EIGEN2_VERSION_OK) - -mark_as_advanced(EIGEN2_INCLUDE_DIR) - -endif(EIGEN2_INCLUDE_DIR) - - diff --git a/mrt_cmake_modules/cmake/Modules/FindFlann.cmake b/mrt_cmake_modules/cmake/Modules/FindFlann.cmake index a6375c04484..967430201ea 100644 --- a/mrt_cmake_modules/cmake/Modules/FindFlann.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindFlann.cmake @@ -11,18 +11,14 @@ find_package(PkgConfig) pkg_check_modules(PC_FLANN flann) set(FLANN_DEFINITIONS ${PC_FLANN_CFLAGS_OTHER}) -find_path(FLANN_INCLUDE_DIR flann/flann.hpp - HINTS ${PC_FLANN_INCLUDEDIR} ${PC_FLANN_INCLUDE_DIRS}) +find_path(FLANN_INCLUDE_DIR flann/flann.hpp HINTS ${PC_FLANN_INCLUDEDIR} ${PC_FLANN_INCLUDE_DIRS}) -find_library(FLANN_LIBRARY flann - HINTS ${PC_FLANN_LIBDIR} ${PC_FLANN_LIBRARY_DIRS}) +find_library(FLANN_LIBRARY flann HINTS ${PC_FLANN_LIBDIR} ${PC_FLANN_LIBRARY_DIRS}) set(FLANN_INCLUDE_DIRS ${FLANN_INCLUDE_DIR}) set(FLANN_LIBRARIES ${FLANN_LIBRARY}) include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Flann DEFAULT_MSG - FLANN_LIBRARY FLANN_INCLUDE_DIR) +find_package_handle_standard_args(Flann DEFAULT_MSG FLANN_LIBRARY FLANN_INCLUDE_DIR) mark_as_advanced(FLANN_LIBRARY FLANN_INCLUDE_DIR) - diff --git a/mrt_cmake_modules/cmake/Modules/FindG2O.cmake b/mrt_cmake_modules/cmake/Modules/FindG2O.cmake deleted file mode 100644 index 655600fb8a9..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindG2O.cmake +++ /dev/null @@ -1,113 +0,0 @@ -# Find the header files - -FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h - ${G2O_ROOT}/include - $ENV{G2O_ROOT}/include - $ENV{G2O_ROOT} - /usr/local/include - /usr/include - /opt/local/include - /sw/local/include - /sw/include - NO_DEFAULT_PATH - ) - -# Macro to unify finding both the debug and release versions of the -# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY -# macro. - -MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) - - FIND_LIBRARY("${MYLIBRARY}_DEBUG" - NAMES "g2o_${MYLIBRARYNAME}_d" - PATHS - ${G2O_ROOT}/lib/Debug - ${G2O_ROOT}/lib - $ENV{G2O_ROOT}/lib/Debug - $ENV{G2O_ROOT}/lib - NO_DEFAULT_PATH - ) - - FIND_LIBRARY("${MYLIBRARY}_DEBUG" - NAMES "g2o_${MYLIBRARYNAME}_d" - PATHS - ~/Library/Frameworks - /Library/Frameworks - /usr/local/lib - /usr/local/lib64 - /usr/lib - /usr/lib64 - /opt/local/lib - /sw/local/lib - /sw/lib - ) - - FIND_LIBRARY(${MYLIBRARY} - NAMES "g2o_${MYLIBRARYNAME}" - PATHS - ${G2O_ROOT}/lib/Release - ${G2O_ROOT}/lib - $ENV{G2O_ROOT}/lib/Release - $ENV{G2O_ROOT}/lib - NO_DEFAULT_PATH - ) - - FIND_LIBRARY(${MYLIBRARY} - NAMES "g2o_${MYLIBRARYNAME}" - PATHS - ~/Library/Frameworks - /Library/Frameworks - /usr/local/lib - /usr/local/lib64 - /usr/lib - /usr/lib64 - /opt/local/lib - /sw/local/lib - /sw/lib - ) - - IF(NOT ${MYLIBRARY}_DEBUG) - IF(MYLIBRARY) - SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) - ENDIF(MYLIBRARY) - ENDIF( NOT ${MYLIBRARY}_DEBUG) - -ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) - -# Find the core elements -FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) -FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) - -# Find the CLI library -FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) - -# Find the pluggable solvers -FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) -FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) -FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) -FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) -FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) -FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) -FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) -FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) - -# Find the predefined types -FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) -FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) -FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) -FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) -FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) -FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) -FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) - -# G2O solvers declared found if we found at least one solver -SET(G2O_SOLVERS_FOUND "NO") -IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) - SET(G2O_SOLVERS_FOUND "YES") -ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) - -# G2O itself declared found if we found the core libraries and at least one solver -SET(G2O_FOUND "NO") -IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) - SET(G2O_FOUND "YES") -ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) diff --git a/mrt_cmake_modules/cmake/Modules/FindGTKMM.cmake b/mrt_cmake_modules/cmake/Modules/FindGTKMM.cmake deleted file mode 100644 index 4ff724ec33b..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindGTKMM.cmake +++ /dev/null @@ -1,6 +0,0 @@ -find_package(PkgConfig) - -pkg_check_modules(GTKMM gtkmm-3.0) # look into FindPkgConfig.cmake, - # it contains documentation -# Now the variables GTKMM_INCLUDE_DIRS, GTKMM_LIBRARY_DIRS and GTKMM_LIBRARIES -# contain what you expect \ No newline at end of file diff --git a/mrt_cmake_modules/cmake/Modules/FindGTest-headers.cmake b/mrt_cmake_modules/cmake/Modules/FindGTest-headers.cmake deleted file mode 100644 index e189f8acb8e..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindGTest-headers.cmake +++ /dev/null @@ -1,5 +0,0 @@ -find_path(GTest-headers_INCLUDE_DIRS NAMES gtest/gtest.h PATHS $ENV{GTEST_ROOT}/include ${GTEST_ROOT}/include /usr/local/include /usr/include) - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(GTest-headers FOUND_VAR GTest-headers_FOUND REQUIRED_VARS GTest-headers_INCLUDE_DIRS) - diff --git a/mrt_cmake_modules/cmake/Modules/FindGeographicLib.cmake b/mrt_cmake_modules/cmake/Modules/FindGeographicLib.cmake index 4f751deb8cf..63dfe309bcc 100644 --- a/mrt_cmake_modules/cmake/Modules/FindGeographicLib.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindGeographicLib.cmake @@ -7,15 +7,11 @@ # GeographicLib_LIBRARY_DIRS = /usr/local/lib find_package(PkgConfig) -find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h - PATH_SUFFIXES GeographicLib - ) +find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h PATH_SUFFIXES GeographicLib) set(GeographicLib_INCLUDE_DIRS ${GeographicLib_INCLUDE_DIR}) -find_library(GeographicLib_LIBRARIES - NAMES Geographic - ) +find_library(GeographicLib_LIBRARIES NAMES Geographic) -include (FindPackageHandleStandardArgs) -find_package_handle_standard_args (GeographicLib DEFAULT_MSG GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) -mark_as_advanced (GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(GeographicLib DEFAULT_MSG GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) +mark_as_advanced(GeographicLib_LIBRARIES GeographicLib_INCLUDE_DIRS) diff --git a/mrt_cmake_modules/cmake/Modules/FindGlog.cmake b/mrt_cmake_modules/cmake/Modules/FindGlog.cmake index 0dde218eebf..f84a89a34da 100644 --- a/mrt_cmake_modules/cmake/Modules/FindGlog.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindGlog.cmake @@ -1,6 +1,6 @@ # Ceres Solver - A fast non-linear least squares minimizer -# Copyright 2013 Google Inc. All rights reserved. -# http://code.google.com/p/ceres-solver/ +# Copyright 2015 Google Inc. All rights reserved. +# http://ceres-solver.org/ # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: @@ -36,9 +36,22 @@ # GLOG_FOUND: TRUE iff glog is found. # GLOG_INCLUDE_DIRS: Include directories for glog. # GLOG_LIBRARIES: Libraries required to link glog. +# FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION: True iff the version of glog found +# was built & installed / exported +# as a CMake package. # # The following variables control the behaviour of this module: # +# GLOG_PREFER_EXPORTED_GLOG_CMAKE_CONFIGURATION: TRUE/FALSE, iff TRUE then +# then prefer using an exported CMake configuration +# generated by glog > 0.3.4 over searching for the +# glog components manually. Otherwise (FALSE) +# ignore any exported glog CMake configurations and +# always perform a manual search for the components. +# Default: TRUE iff user does not define this variable +# before we are called, and does NOT specify either +# GLOG_INCLUDE_DIR_HINTS or GLOG_LIBRARY_DIR_HINTS +# otherwise FALSE. # GLOG_INCLUDE_DIR_HINTS: List of additional directories in which to # search for glog includes, e.g: /timbuktu/include. # GLOG_LIBRARY_DIR_HINTS: List of additional directories in which to @@ -60,113 +73,296 @@ # GLOG_LIBRARY: glog library, not including the libraries of any # dependencies. +# Reset CALLERS_CMAKE_FIND_LIBRARY_PREFIXES to its value when +# FindGlog was invoked. +macro(GLOG_RESET_FIND_LIBRARY_PREFIX) + if(MSVC AND CALLERS_CMAKE_FIND_LIBRARY_PREFIXES) + set(CMAKE_FIND_LIBRARY_PREFIXES "${CALLERS_CMAKE_FIND_LIBRARY_PREFIXES}") + endif() +endmacro(GLOG_RESET_FIND_LIBRARY_PREFIX) + # Called if we failed to find glog or any of it's required dependencies, # unsets all public (designed to be used externally) variables and reports # error message at priority depending upon [REQUIRED/QUIET/] argument. -MACRO(GLOG_REPORT_NOT_FOUND REASON_MSG) - UNSET(GLOG_FOUND) - UNSET(GLOG_INCLUDE_DIRS) - UNSET(GLOG_LIBRARIES) - # Make results of search visible in the CMake GUI if glog has not - # been found so that user does not have to toggle to advanced view. - MARK_AS_ADVANCED(CLEAR GLOG_INCLUDE_DIR - GLOG_LIBRARY) - # Note _FIND_[REQUIRED/QUIETLY] variables defined by FindPackage() - # use the camelcase library name, not uppercase. - IF (Glog_FIND_QUIETLY) - MESSAGE(STATUS "Failed to find glog - " ${REASON_MSG} ${ARGN}) - ELSEIF (Glog_FIND_REQUIRED) - MESSAGE(FATAL_ERROR "Failed to find glog - " ${REASON_MSG} ${ARGN}) - ELSE() - # Neither QUIETLY nor REQUIRED, use no priority which emits a message - # but continues configuration and allows generation. - MESSAGE("-- Failed to find glog - " ${REASON_MSG} ${ARGN}) - ENDIF () -ENDMACRO(GLOG_REPORT_NOT_FOUND) - -# Search user-installed locations first, so that we prefer user installs -# to system installs where both exist. -# -# TODO: Add standard Windows search locations for glog. -LIST(APPEND GLOG_CHECK_INCLUDE_DIRS - /usr/local/include - /usr/local/homebrew/include # Mac OS X - /opt/local/var/macports/software # Mac OS X. - /opt/local/include - /usr/include) -LIST(APPEND GLOG_CHECK_LIBRARY_DIRS - /usr/local/lib - /usr/local/homebrew/lib # Mac OS X. - /opt/local/lib - /usr/lib) - -# Search supplied hint directories first if supplied. -FIND_PATH(GLOG_INCLUDE_DIR - NAMES glog/logging.h - PATHS ${GLOG_INCLUDE_DIR_HINTS} - ${GLOG_CHECK_INCLUDE_DIRS}) -IF (NOT GLOG_INCLUDE_DIR OR - NOT EXISTS ${GLOG_INCLUDE_DIR}) - GLOG_REPORT_NOT_FOUND( - "Could not find glog include directory, set GLOG_INCLUDE_DIR " - "to directory containing glog/logging.h") -ENDIF (NOT GLOG_INCLUDE_DIR OR - NOT EXISTS ${GLOG_INCLUDE_DIR}) - -FIND_LIBRARY(GLOG_LIBRARY NAMES glog - PATHS ${GLOG_LIBRARY_DIR_HINTS} - ${GLOG_CHECK_LIBRARY_DIRS}) -IF (NOT GLOG_LIBRARY OR - NOT EXISTS ${GLOG_LIBRARY}) - GLOG_REPORT_NOT_FOUND( - "Could not find glog library, set GLOG_LIBRARY " - "to full path to libglog.") -ENDIF (NOT GLOG_LIBRARY OR - NOT EXISTS ${GLOG_LIBRARY}) - -# Mark internally as found, then verify. GLOG_REPORT_NOT_FOUND() unsets -# if called. -SET(GLOG_FOUND TRUE) - -# Glog does not seem to provide any record of the version in its -# source tree, thus cannot extract version. - -# Catch case when caller has set GLOG_INCLUDE_DIR in the cache / GUI and -# thus FIND_[PATH/LIBRARY] are not called, but specified locations are -# invalid, otherwise we would report the library as found. -IF (GLOG_INCLUDE_DIR AND - NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) - GLOG_REPORT_NOT_FOUND( - "Caller defined GLOG_INCLUDE_DIR:" - " ${GLOG_INCLUDE_DIR} does not contain glog/logging.h header.") -ENDIF (GLOG_INCLUDE_DIR AND - NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) -# TODO: This regex for glog library is pretty primitive, we use lowercase -# for comparison to handle Windows using CamelCase library names, could -# this check be better? -STRING(TOLOWER "${GLOG_LIBRARY}" LOWERCASE_GLOG_LIBRARY) -IF (GLOG_LIBRARY AND - NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") - GLOG_REPORT_NOT_FOUND( - "Caller defined GLOG_LIBRARY: " - "${GLOG_LIBRARY} does not match glog.") -ENDIF (GLOG_LIBRARY AND - NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") +macro(GLOG_REPORT_NOT_FOUND REASON_MSG) + unset(GLOG_FOUND) + unset(GLOG_INCLUDE_DIRS) + unset(GLOG_LIBRARIES) + # Make results of search visible in the CMake GUI if glog has not + # been found so that user does not have to toggle to advanced view. + mark_as_advanced(CLEAR GLOG_INCLUDE_DIR GLOG_LIBRARY) + + glog_reset_find_library_prefix() + + # Note _FIND_[REQUIRED/QUIETLY] variables defined by FindPackage() + # use the camelcase library name, not uppercase. + if(Glog_FIND_QUIETLY) + message(STATUS "Failed to find glog - " ${REASON_MSG} ${ARGN}) + elseif(Glog_FIND_REQUIRED) + message(FATAL_ERROR "Failed to find glog - " ${REASON_MSG} ${ARGN}) + else() + # Neither QUIETLY nor REQUIRED, use no priority which emits a message + # but continues configuration and allows generation. + message("-- Failed to find glog - " ${REASON_MSG} ${ARGN}) + endif() + return() +endmacro(GLOG_REPORT_NOT_FOUND) + +# Protect against any alternative find_package scripts for this library having +# been called previously (in a client project) which set GLOG_FOUND, but not +# the other variables we require / set here which could cause the search logic +# here to fail. +unset(GLOG_FOUND) + +# ----------------------------------------------------------------- +# By default, if the user has expressed no preference for using an exported +# glog CMake configuration over performing a search for the installed +# components, and has not specified any hints for the search locations, then +# prefer a glog exported configuration if available. +if(NOT DEFINED GLOG_PREFER_EXPORTED_GLOG_CMAKE_CONFIGURATION + AND NOT GLOG_INCLUDE_DIR_HINTS + AND NOT GLOG_LIBRARY_DIR_HINTS) + message(STATUS "No preference for use of exported glog CMake configuration " + "set, and no hints for include/library directories provided. " + "Defaulting to preferring an installed/exported glog CMake configuration " "if available.") + set(GLOG_PREFER_EXPORTED_GLOG_CMAKE_CONFIGURATION TRUE) +endif() + +# On macOS, add the Homebrew prefix (with appropriate suffixes) to the +# respective HINTS directories (after any user-specified locations). This +# handles Homebrew installations into non-standard locations (not /usr/local). +# We do not use CMAKE_PREFIX_PATH for this as given the search ordering of +# find_xxx(), doing so would override any user-specified HINTS locations with +# the Homebrew version if it exists. +if(CMAKE_SYSTEM_NAME MATCHES "Darwin") + find_program(HOMEBREW_EXECUTABLE brew) + mark_as_advanced(FORCE HOMEBREW_EXECUTABLE) + if(HOMEBREW_EXECUTABLE) + # Detected a Homebrew install, query for its install prefix. + execute_process( + COMMAND ${HOMEBREW_EXECUTABLE} --prefix + OUTPUT_VARIABLE HOMEBREW_INSTALL_PREFIX + OUTPUT_STRIP_TRAILING_WHITESPACE) + message(STATUS "Detected Homebrew with install prefix: " + "${HOMEBREW_INSTALL_PREFIX}, adding to CMake search paths.") + list(APPEND GLOG_INCLUDE_DIR_HINTS "${HOMEBREW_INSTALL_PREFIX}/include") + list(APPEND GLOG_LIBRARY_DIR_HINTS "${HOMEBREW_INSTALL_PREFIX}/lib") + endif() +endif() + +if(GLOG_PREFER_EXPORTED_GLOG_CMAKE_CONFIGURATION) + # Try to find an exported CMake configuration for glog, as generated by + # glog versions > 0.3.4 + # + # We search twice, s/t we can invert the ordering of precedence used by + # find_package() for exported package build directories, and installed + # packages (found via CMAKE_SYSTEM_PREFIX_PATH), listed as items 6) and 7) + # respectively in [1]. + # + # By default, exported build directories are (in theory) detected first, and + # this is usually the case on Windows. However, on OS X & Linux, the install + # path (/usr/local) is typically present in the PATH environment variable + # which is checked in item 4) in [1] (i.e. before both of the above, unless + # NO_SYSTEM_ENVIRONMENT_PATH is passed). As such on those OSs installed + # packages are usually detected in preference to exported package build + # directories. + # + # To ensure a more consistent response across all OSs, and as users usually + # want to prefer an installed version of a package over a locally built one + # where both exist (esp. as the exported build directory might be removed + # after installation), we first search with NO_CMAKE_PACKAGE_REGISTRY which + # means any build directories exported by the user are ignored, and thus + # installed directories are preferred. If this fails to find the package + # we then research again, but without NO_CMAKE_PACKAGE_REGISTRY, so any + # exported build directories will now be detected. + # + # To prevent confusion on Windows, we also pass NO_CMAKE_BUILDS_PATH (which + # is item 5) in [1]), to not preferentially use projects that were built + # recently with the CMake GUI to ensure that we always prefer an installed + # version if available. + # + # NOTE: We use the NAMES option as glog erroneously uses 'google-glog' as its + # project name when built with CMake, but exports itself as just 'glog'. + # On Linux/OS X this does not break detection as the project name is + # not used as part of the install path for the CMake package files, + # e.g. /usr/local/lib/cmake/glog, where the suffix is hardcoded + # in glog's CMakeLists. However, on Windows the project name *is* + # part of the install prefix: C:/Program Files/google-glog/[include,lib]. + # However, by default CMake checks: + # C:/Program Files/ which does not + # exist and thus detection fails. Thus we use the NAMES to force the + # search to use both google-glog & glog. + # + # [1] http://www.cmake.org/cmake/help/v2.8.11/cmake.html#command:find_package + find_package( + glog + QUIET + NAMES + google-glog + glog + HINTS + ${glog_DIR} + ${HOMEBREW_INSTALL_PREFIX} + NO_MODULE + NO_CMAKE_PACKAGE_REGISTRY + NO_CMAKE_BUILDS_PATH) + if(glog_FOUND) + message(STATUS "Found installed version of glog: ${glog_DIR}") + else() + # Failed to find an installed version of glog, repeat search allowing + # exported build directories. + message(STATUS "Failed to find installed glog CMake configuration, " + "searching for glog build directories exported with CMake.") + # Again pass NO_CMAKE_BUILDS_PATH, as we know that glog is exported and + # do not want to treat projects built with the CMake GUI preferentially. + find_package( + glog + QUIET + NAMES + google-glog + glog + NO_MODULE + NO_CMAKE_BUILDS_PATH) + if(glog_FOUND) + message(STATUS "Found exported glog build directory: ${glog_DIR}") + endif(glog_FOUND) + endif(glog_FOUND) + + set(FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION ${glog_FOUND}) + + if(FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION) + message(STATUS "Detected glog version: ${glog_VERSION}") + set(GLOG_FOUND ${glog_FOUND}) + # glog wraps the include directories into the exported glog::glog target. + set(GLOG_INCLUDE_DIR "") + set(GLOG_LIBRARY glog::glog) + else(FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION) + message(STATUS "Failed to find an installed/exported CMake configuration " + "for glog, will perform search for installed glog components.") + endif(FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION) +endif(GLOG_PREFER_EXPORTED_GLOG_CMAKE_CONFIGURATION) + +if(NOT GLOG_FOUND) + # Either failed to find an exported glog CMake configuration, or user + # told us not to use one. Perform a manual search for all glog components. + + # Handle possible presence of lib prefix for libraries on MSVC, see + # also GLOG_RESET_FIND_LIBRARY_PREFIX(). + if(MSVC) + # Preserve the caller's original values for CMAKE_FIND_LIBRARY_PREFIXES + # s/t we can set it back before returning. + set(CALLERS_CMAKE_FIND_LIBRARY_PREFIXES "${CMAKE_FIND_LIBRARY_PREFIXES}") + # The empty string in this list is important, it represents the case when + # the libraries have no prefix (shared libraries / DLLs). + set(CMAKE_FIND_LIBRARY_PREFIXES "lib" "" "${CMAKE_FIND_LIBRARY_PREFIXES}") + endif(MSVC) + + # Search user-installed locations first, so that we prefer user installs + # to system installs where both exist. + list( + APPEND + GLOG_CHECK_INCLUDE_DIRS + /usr/local/include + /usr/local/homebrew/include # Mac OS X + /opt/local/var/macports/software # Mac OS X. + /opt/local/include + /usr/include) + # Windows (for C:/Program Files prefix). + list( + APPEND + GLOG_CHECK_PATH_SUFFIXES + glog/include + glog/Include + Glog/include + Glog/Include + google-glog/include # CMake installs with project name prefix. + google-glog/Include) + + list(APPEND GLOG_CHECK_LIBRARY_DIRS /usr/local/lib /usr/local/homebrew/lib # Mac OS X. + /opt/local/lib /usr/lib) + # Windows (for C:/Program Files prefix). + list( + APPEND + GLOG_CHECK_LIBRARY_SUFFIXES + glog/lib + glog/Lib + Glog/lib + Glog/Lib + google-glog/lib # CMake installs with project name prefix. + google-glog/Lib) + + # Search supplied hint directories first if supplied. + find_path( + GLOG_INCLUDE_DIR + NAMES glog/logging.h + HINTS ${GLOG_INCLUDE_DIR_HINTS} + PATHS ${GLOG_CHECK_INCLUDE_DIRS} + PATH_SUFFIXES ${GLOG_CHECK_PATH_SUFFIXES}) + if(NOT GLOG_INCLUDE_DIR OR NOT EXISTS ${GLOG_INCLUDE_DIR}) + glog_report_not_found("Could not find glog include directory, set GLOG_INCLUDE_DIR " + "to directory containing glog/logging.h") + endif(NOT GLOG_INCLUDE_DIR OR NOT EXISTS ${GLOG_INCLUDE_DIR}) + + find_library( + GLOG_LIBRARY + NAMES glog + HINTS ${GLOG_LIBRARY_DIR_HINTS} + PATHS ${GLOG_CHECK_LIBRARY_DIRS} + PATH_SUFFIXES ${GLOG_CHECK_LIBRARY_SUFFIXES}) + if(NOT GLOG_LIBRARY OR NOT EXISTS ${GLOG_LIBRARY}) + glog_report_not_found("Could not find glog library, set GLOG_LIBRARY " "to full path to libglog.") + endif(NOT GLOG_LIBRARY OR NOT EXISTS ${GLOG_LIBRARY}) + + # Mark internally as found, then verify. GLOG_REPORT_NOT_FOUND() unsets + # if called. + set(GLOG_FOUND TRUE) + + # Glog does not seem to provide any record of the version in its + # source tree, thus cannot extract version. + + # Catch case when caller has set GLOG_INCLUDE_DIR in the cache / GUI and + # thus FIND_[PATH/LIBRARY] are not called, but specified locations are + # invalid, otherwise we would report the library as found. + if(GLOG_INCLUDE_DIR AND NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) + glog_report_not_found("Caller defined GLOG_INCLUDE_DIR:" + " ${GLOG_INCLUDE_DIR} does not contain glog/logging.h header.") + endif(GLOG_INCLUDE_DIR AND NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) + # TODO: This regex for glog library is pretty primitive, we use lowercase + # for comparison to handle Windows using CamelCase library names, could + # this check be better? + string(TOLOWER "${GLOG_LIBRARY}" LOWERCASE_GLOG_LIBRARY) + if(GLOG_LIBRARY AND NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") + glog_report_not_found("Caller defined GLOG_LIBRARY: " "${GLOG_LIBRARY} does not match glog.") + endif(GLOG_LIBRARY AND NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") + + glog_reset_find_library_prefix() + +endif(NOT GLOG_FOUND) # Set standard CMake FindPackage variables if found. -IF (GLOG_FOUND) - SET(GLOG_INCLUDE_DIRS ${GLOG_INCLUDE_DIR}) - SET(GLOG_LIBRARIES ${GLOG_LIBRARY}) -ENDIF (GLOG_FOUND) +if(GLOG_FOUND) + set(GLOG_INCLUDE_DIRS ${GLOG_INCLUDE_DIR}) + set(GLOG_LIBRARIES ${GLOG_LIBRARY}) +endif(GLOG_FOUND) + +# If we are using an exported CMake glog target, the include directories are +# wrapped into the target itself, and do not have to be (and are not) +# separately specified. In which case, we should not add GLOG_INCLUDE_DIRS +# to the list of required variables in order that glog be reported as found. +if(FOUND_INSTALLED_GLOG_CMAKE_CONFIGURATION) + set(GLOG_REQUIRED_VARIABLES GLOG_LIBRARIES) +else() + set(GLOG_REQUIRED_VARIABLES GLOG_INCLUDE_DIRS GLOG_LIBRARIES) +endif() # Handle REQUIRED / QUIET optional arguments. -INCLUDE(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Glog DEFAULT_MSG - GLOG_INCLUDE_DIRS GLOG_LIBRARIES) +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(Glog DEFAULT_MSG ${GLOG_REQUIRED_VARIABLES}) # Only mark internal variables as advanced if we found glog, otherwise # leave them visible in the standard GUI for the user to set manually. -IF (GLOG_FOUND) - MARK_AS_ADVANCED(FORCE GLOG_INCLUDE_DIR - GLOG_LIBRARY) -ENDIF (GLOG_FOUND) +if(GLOG_FOUND) + list(REMOVE_ITEM GLOG_INCLUDE_DIRS "/usr/include") + list(REMOVE_ITEM GLOG_INCLUDE_DIRS "/usr/local/include") + mark_as_advanced(FORCE GLOG_INCLUDE_DIR GLOG_LIBRARY glog_DIR) # Autogenerated by find_package(glog) +endif(GLOG_FOUND) diff --git a/mrt_cmake_modules/cmake/Modules/FindIGL.cmake b/mrt_cmake_modules/cmake/Modules/FindIGL.cmake index ecffc661bd8..4ece3540f43 100644 --- a/mrt_cmake_modules/cmake/Modules/FindIGL.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindIGL.cmake @@ -7,31 +7,31 @@ # cmake .. set(IGL_FOUND FALSE) -find_path(LIBIGL_INCLUDE_DIR igl/readOBJ.h +find_path( + LIBIGL_INCLUDE_DIR igl/readOBJ.h PATHS ${CMAKE_CURRENT_SOURCE_DIR}/../libigl - PATH_SUFFIXES include -) + PATH_SUFFIXES include) if(${LIBIGL_INCLUDE_DIR} STREQUAL "LIBIGL_INCLUDE_DIR-NOTFOUND") return() endif() -option(LIBIGL_USE_STATIC_LIBRARY "Use libigl as static library" OFF) -option(LIBIGL_WITH_CGAL "Use CGAL" OFF) -option(LIBIGL_WITH_COMISO "Use CoMiso" OFF) -option(LIBIGL_WITH_CORK "Use Cork" OFF) -option(LIBIGL_WITH_EMBREE "Use Embree" OFF) -option(LIBIGL_WITH_MATLAB "Use Matlab" OFF) -option(LIBIGL_WITH_MOSEK "Use MOSEK" OFF) -option(LIBIGL_WITH_OPENGL "Use OpenGL" ON) -option(LIBIGL_WITH_OPENGL_GLFW "Use GLFW" ON) -option(LIBIGL_WITH_OPENGL_GLFW_IMGUI "Use ImGui" OFF) -option(LIBIGL_WITH_PNG "Use PNG" ON) -option(LIBIGL_WITH_TETGEN "Use Tetgen" OFF) -option(LIBIGL_WITH_TRIANGLE "Use Triangle" OFF) -option(LIBIGL_WITH_XML "Use XML" OFF) -option(LIBIGL_WITH_PYTHON "Use Python" OFF) -option(LIBIGL_WITHOUT_COPYLEFT "Disable Copyleft libraries" OFF) +option(LIBIGL_USE_STATIC_LIBRARY "Use libigl as static library" OFF) +option(LIBIGL_WITH_CGAL "Use CGAL" OFF) +option(LIBIGL_WITH_COMISO "Use CoMiso" OFF) +option(LIBIGL_WITH_CORK "Use Cork" OFF) +option(LIBIGL_WITH_EMBREE "Use Embree" OFF) +option(LIBIGL_WITH_MATLAB "Use Matlab" OFF) +option(LIBIGL_WITH_MOSEK "Use MOSEK" OFF) +option(LIBIGL_WITH_OPENGL "Use OpenGL" ON) +option(LIBIGL_WITH_OPENGL_GLFW "Use GLFW" ON) +option(LIBIGL_WITH_OPENGL_GLFW_IMGUI "Use ImGui" OFF) +option(LIBIGL_WITH_PNG "Use PNG" ON) +option(LIBIGL_WITH_TETGEN "Use Tetgen" OFF) +option(LIBIGL_WITH_TRIANGLE "Use Triangle" OFF) +option(LIBIGL_WITH_XML "Use XML" OFF) +option(LIBIGL_WITH_PYTHON "Use Python" OFF) +option(LIBIGL_WITHOUT_COPYLEFT "Disable Copyleft libraries" OFF) list(APPEND CMAKE_MODULE_PATH "${LIBIGL_INCLUDE_DIR}/../cmake") include(libigl) diff --git a/mrt_cmake_modules/cmake/Modules/FindIpopt.cmake b/mrt_cmake_modules/cmake/Modules/FindIpopt.cmake index c33c96d263f..38f775809a5 100644 --- a/mrt_cmake_modules/cmake/Modules/FindIpopt.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindIpopt.cmake @@ -1,16 +1,10 @@ # try to find ipopt find_package(PkgConfig) -find_path(IPOPT_INCLUDE_DIRS IpIpoptApplication.hpp - PATH_SUFFIXES coin - ) +find_path(IPOPT_INCLUDE_DIRS IpIpoptApplication.hpp PATH_SUFFIXES coin) -find_library(IPOPT_LIBRARIES - NAMES ipopt - ) +find_library(IPOPT_LIBRARIES NAMES ipopt) add_definitions(-DHAVE_STDDEF_H) include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Ipopt DEFAULT_MSG - IPOPT_LIBRARIES IPOPT_INCLUDE_DIRS) +find_package_handle_standard_args(Ipopt DEFAULT_MSG IPOPT_LIBRARIES IPOPT_INCLUDE_DIRS) mark_as_advanced(IPOPT_LIBRARIES IPOPT_INCLUDE_DIRS) - diff --git a/mrt_cmake_modules/cmake/Modules/FindJsonCpp.cmake b/mrt_cmake_modules/cmake/Modules/FindJsonCpp.cmake new file mode 100644 index 00000000000..72c5ccd08ee --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindJsonCpp.cmake @@ -0,0 +1,443 @@ +# stolen fron https://github.com/rpavlik/cmake-modules/blob/master/FindJsonCpp.cmake + +# - Find jsoncpp - Overarching find module +# This is a over-arching find module to find older jsoncpp versions and those sadly built +# without JSONCPP_WITH_CMAKE_PACKAGE=ON, as well as those built with the cmake config file. +# It also wraps the different versions of the module. +# +# On CMake 3.0 and newer: +# JsonCpp::JsonCpp - Imported target (possibly an interface/alias) to use: +# if anything is populated, this is. If both shared and static are found, then +# this will be the static version on DLL platforms and shared on non-DLL platforms. +# JsonCpp::JsonCppShared - Imported target (possibly an interface/alias) for a +# shared library version. +# JsonCpp::JsonCppStatic - Imported target (possibly an interface/alias) for a +# static library version. +# +# On all CMake versions: (Note that on CMake 2.8.10 and earlier, you may need to use JSONCPP_INCLUDE_DIRS) +# JSONCPP_LIBRARY - wraps JsonCpp::JsonCpp or equiv. +# JSONCPP_LIBRARY_IS_SHARED - if we know for sure JSONCPP_LIBRARY is shared, this is true-ish. We try to "un-set" it if we don't know one way or another. +# JSONCPP_LIBRARY_SHARED - wraps JsonCpp::JsonCppShared or equiv. +# JSONCPP_LIBRARY_STATIC - wraps JsonCpp::JsonCppStatic or equiv. +# JSONCPP_INCLUDE_DIRS - Include directories - should (generally?) not needed if you require CMake 2.8.11+ since it handles target include directories. +# +# JSONCPP_FOUND - True if JsonCpp was found. +# +# Original Author: +# 2016 Ryan Pavlik +# Incorporates work from the module contributed to VRPN under the same license: +# 2011 Philippe Crassous (ENSAM ParisTech / Institut Image) p.crassous _at_ free.fr +# +# Copyright Philippe Crassous 2011. +# Copyright Sensics, Inc. 2016. +# Distributed under the Boost Software License, Version 1.0. +# (See accompanying file LICENSE_1_0.txt or copy at +# http://www.boost.org/LICENSE_1_0.txt) + +set(__jsoncpp_have_namespaced_targets OFF) +set(__jsoncpp_have_interface_support OFF) +if(NOT ("${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}" LESS 3.0)) + set(__jsoncpp_have_namespaced_targets ON) + set(__jsoncpp_have_interface_support ON) +elseif(("${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}" EQUAL 2.8) AND "${CMAKE_PATCH_VERSION}" GREATER 10) + set(__jsoncpp_have_interface_support ON) +endif() + +# sets __jsoncpp_have_jsoncpplib based on whether or not we have a real imported jsoncpp_lib target. +macro(_jsoncpp_check_for_real_jsoncpplib) + set(__jsoncpp_have_jsoncpplib FALSE) + if(TARGET jsoncpp_lib) + get_property( + __jsoncpp_lib_type + TARGET jsoncpp_lib + PROPERTY TYPE) + # We make interface libraries. If an actual config module made it, it would be an imported library. + if(NOT __jsoncpp_lib_type STREQUAL "INTERFACE_LIBRARY") + set(__jsoncpp_have_jsoncpplib TRUE) + endif() + endif() + #message(STATUS "__jsoncpp_have_jsoncpplib ${__jsoncpp_have_jsoncpplib}") +endmacro() + +include(FindPackageHandleStandardArgs) +# Ensure that if this is TRUE later, it's because we set it. +set(JSONCPP_FOUND FALSE) +set(__jsoncpp_have_jsoncpplib FALSE) + +# See if we find a CMake config file - there is no harm in calling this more than once, +# and we need to call it at least once every CMake invocation to create the original +# imported targets, since those don't stick around like cache variables. +find_package(jsoncpp QUIET NO_MODULE) + +if(jsoncpp_FOUND) + # Build a string to help us figure out when to invalidate our cache variables. + # start with where we found jsoncpp + set(__jsoncpp_info_string "[${jsoncpp_DIR}]") + + # part of the string to indicate if we found a real jsoncpp_lib (and what kind) + _jsoncpp_check_for_real_jsoncpplib() + + macro(_jsoncpp_apply_map_config target) + if(MSVC) + # Can't do this - different runtimes, incompatible ABI, etc. + set(_jsoncpp_debug_fallback) + else() + set(_jsoncpp_debug_fallback DEBUG) + #osvr_stash_map_config(DEBUG DEBUG RELWITHDEBINFO RELEASE MINSIZEREL NONE) + endif() + # Appending, just in case using project or upstream fixes this. + set_property( + TARGET ${target} + APPEND + PROPERTY MAP_IMPORTED_CONFIG_RELEASE RELEASE RELWITHDEBINFO MINSIZEREL NONE ${_jsoncpp_debug_fallback}) + set_property( + TARGET ${target} + APPEND + PROPERTY MAP_IMPORTED_CONFIG_RELWITHDEBINFO RELWITHDEBINFO RELEASE MINSIZEREL NONE + ${_jsoncpp_debug_fallback}) + set_property( + TARGET ${target} + APPEND + PROPERTY MAP_IMPORTED_CONFIG_MINSIZEREL MINSIZEREL RELEASE RELWITHDEBINFO NONE ${_jsoncpp_debug_fallback}) + set_property( + TARGET ${target} + APPEND + PROPERTY MAP_IMPORTED_CONFIG_NONE NONE RELEASE RELWITHDEBINFO MINSIZEREL ${_jsoncpp_debug_fallback}) + if(NOT MSVC) + set_property( + TARGET ${target} + APPEND + PROPERTY MAP_IMPORTED_CONFIG_DEBUG DEBUG RELWITHDEBINFO RELEASE MINSIZEREL NONE) + endif() + endmacro() + if(__jsoncpp_have_jsoncpplib) + list(APPEND __jsoncpp_info_string "[${__jsoncpp_lib_type}]") + _jsoncpp_apply_map_config(jsoncpp_lib) + else() + list(APPEND __jsoncpp_info_string "[]") + endif() + # part of the string to indicate if we found jsoncpp_lib_static + if(TARGET jsoncpp_lib_static) + list(APPEND __jsoncpp_info_string "[T]") + _jsoncpp_apply_map_config(jsoncpp_lib_static) + else() + list(APPEND __jsoncpp_info_string "[]") + endif() +endif() + +# If we found something, and it's not the exact same as what we've found before... +# NOTE: The contents of this "if" block update only (internal) cache variables! +# (since this will only get run the first CMake pass that finds jsoncpp or that finds a different/updated install) +if(jsoncpp_FOUND AND NOT __jsoncpp_info_string STREQUAL "${JSONCPP_CACHED_JSONCPP_DIR_DETAILS}") + #message("Updating jsoncpp cache variables! ${__jsoncpp_info_string}") + set(JSONCPP_CACHED_JSONCPP_DIR_DETAILS + "${__jsoncpp_info_string}" + CACHE INTERNAL "" FORCE) + unset(JSONCPP_IMPORTED_LIBRARY_SHARED) + unset(JSONCPP_IMPORTED_LIBRARY_STATIC) + unset(JSONCPP_IMPORTED_LIBRARY) + unset(JSONCPP_IMPORTED_INCLUDE_DIRS) + unset(JSONCPP_IMPORTED_LIBRARY_IS_SHARED) + + # if(__jsoncpp_have_jsoncpplib) is equivalent to if(TARGET jsoncpp_lib) except it excludes our + # "invented" jsoncpp_lib interface targets, made for convenience purposes after this block. + + if(__jsoncpp_have_jsoncpplib AND TARGET jsoncpp_lib_static) + + # A veritable cache of riches - we have both shared and static! + set(JSONCPP_IMPORTED_LIBRARY_SHARED + jsoncpp_lib + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_STATIC + jsoncpp_lib_static + CACHE INTERNAL "" FORCE) + if(WIN32 + OR CYGWIN + OR MINGW) + # DLL platforms: static library should be default + set(JSONCPP_IMPORTED_LIBRARY + ${JSONCPP_IMPORTED_LIBRARY_STATIC} + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_IS_SHARED + FALSE + CACHE INTERNAL "" FORCE) + else() + # Other platforms - might require PIC to be linked into shared libraries, so safest to prefer shared. + set(JSONCPP_IMPORTED_LIBRARY + ${JSONCPP_IMPORTED_LIBRARY_SHARED} + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_IS_SHARED + TRUE + CACHE INTERNAL "" FORCE) + endif() + + elseif(TARGET jsoncpp_lib_static) + # Well, only one variant, but we know for sure that it's static. + set(JSONCPP_IMPORTED_LIBRARY_STATIC + jsoncpp_lib_static + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY + jsoncpp_lib_static + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_IS_SHARED + FALSE + CACHE INTERNAL "" FORCE) + + elseif(__jsoncpp_have_jsoncpplib AND __jsoncpp_lib_type STREQUAL "STATIC_LIBRARY") + # We were able to figure out the mystery library is static! + set(JSONCPP_IMPORTED_LIBRARY_STATIC + jsoncpp_lib + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY + jsoncpp_lib + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_IS_SHARED + FALSE + CACHE INTERNAL "" FORCE) + + elseif(__jsoncpp_have_jsoncpplib AND __jsoncpp_lib_type STREQUAL "SHARED_LIBRARY") + # We were able to figure out the mystery library is shared! + set(JSONCPP_IMPORTED_LIBRARY_SHARED + jsoncpp_lib + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY + jsoncpp_lib + CACHE INTERNAL "" FORCE) + set(JSONCPP_IMPORTED_LIBRARY_IS_SHARED + TRUE + CACHE INTERNAL "" FORCE) + + elseif(__jsoncpp_have_jsoncpplib) + # One variant, and we have no idea if this is just an old version or if + # this is shared based on the target name alone. Hmm. + set(JSONCPP_IMPORTED_LIBRARY + jsoncpp_lib + CACHE INTERNAL "" FORCE) + endif() + + # Now, we need include directories. Can't just limit this to old CMakes, since + # new CMakes might be used to build projects designed to support older ones. + if(__jsoncpp_have_jsoncpplib) + get_property( + __jsoncpp_interface_include_dirs + TARGET jsoncpp_lib + PROPERTY INTERFACE_INCLUDE_DIRECTORIES) + if(__jsoncpp_interface_include_dirs) + set(JSONCPP_IMPORTED_INCLUDE_DIRS + "${__jsoncpp_interface_include_dirs}" + CACHE INTERNAL "" FORCE) + endif() + endif() + if(TARGET jsoncpp_lib_static AND NOT JSONCPP_IMPORTED_INCLUDE_DIRS) + get_property( + __jsoncpp_interface_include_dirs + TARGET jsoncpp_lib_static + PROPERTY INTERFACE_INCLUDE_DIRECTORIES) + if(__jsoncpp_interface_include_dirs) + set(JSONCPP_IMPORTED_INCLUDE_DIRS + "${__jsoncpp_interface_include_dirs}" + CACHE INTERNAL "" FORCE) + endif() + endif() +endif() + +# As a convenience... +if(TARGET jsoncpp_lib_static AND NOT TARGET jsoncpp_lib) + add_library(jsoncpp_lib INTERFACE) + target_link_libraries(jsoncpp_lib INTERFACE jsoncpp_lib_static) +endif() + +if(JSONCPP_IMPORTED_LIBRARY) + if(NOT JSONCPP_IMPORTED_INCLUDE_DIRS) + # OK, so we couldn't get it from the target... maybe we can figure it out from jsoncpp_DIR. + + # take off the jsoncpp component + get_filename_component(__jsoncpp_import_root "${jsoncpp_DIR}/.." ABSOLUTE) + set(__jsoncpp_hints "${__jsoncpp_import_root}") + # take off the cmake component + get_filename_component(__jsoncpp_import_root "${__jsoncpp_import_root}/.." ABSOLUTE) + list(APPEND __jsoncpp_hints "${__jsoncpp_import_root}") + # take off the lib component + get_filename_component(__jsoncpp_import_root "${__jsoncpp_import_root}/.." ABSOLUTE) + list(APPEND __jsoncpp_hints "${__jsoncpp_import_root}") + # take off one more component in case of multiarch lib + get_filename_component(__jsoncpp_import_root "${__jsoncpp_import_root}/.." ABSOLUTE) + list(APPEND __jsoncpp_hints "${__jsoncpp_import_root}") + + # Now, search. + find_path( + JsonCpp_INCLUDE_DIR + NAMES json/json.h + PATH_SUFFIXES include jsoncpp include/jsoncpp + HINTS ${__jsoncpp_hints}) + if(JsonCpp_INCLUDE_DIR) + mark_as_advanced(JsonCpp_INCLUDE_DIR) + # Note - this does not set it in the cache, in case we find it better at some point in the future! + set(JSONCPP_IMPORTED_INCLUDE_DIRS ${JsonCpp_INCLUDE_DIR}) + endif() + endif() + + find_package_handle_standard_args(JsonCpp DEFAULT_MSG jsoncpp_DIR JSONCPP_IMPORTED_LIBRARY + JSONCPP_IMPORTED_INCLUDE_DIRS) +endif() + +if(JSONCPP_FOUND) + # Create any missing namespaced targets from the config module. + if(__jsoncpp_have_namespaced_targets) + if(JSONCPP_IMPORTED_LIBRARY AND NOT TARGET JsonCpp::JsonCpp) + add_library(JsonCpp::JsonCpp INTERFACE IMPORTED) + set_target_properties( + JsonCpp::JsonCpp PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${JSONCPP_IMPORTED_INCLUDE_DIRS}" + INTERFACE_LINK_LIBRARIES "${JSONCPP_IMPORTED_LIBRARY}") + endif() + + if(JSONCPP_IMPORTED_LIBRARY_SHARED AND NOT TARGET JsonCpp::JsonCppShared) + add_library(JsonCpp::JsonCppShared INTERFACE IMPORTED) + set_target_properties( + JsonCpp::JsonCppShared PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${JSONCPP_IMPORTED_INCLUDE_DIRS}" + INTERFACE_LINK_LIBRARIES "${JSONCPP_IMPORTED_LIBRARY_SHARED}") + endif() + + if(JSONCPP_IMPORTED_LIBRARY_STATIC AND NOT TARGET JsonCpp::JsonCppStatic) + add_library(JsonCpp::JsonCppStatic INTERFACE IMPORTED) + set_target_properties( + JsonCpp::JsonCppStatic PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${JSONCPP_IMPORTED_INCLUDE_DIRS}" + INTERFACE_LINK_LIBRARIES "${JSONCPP_IMPORTED_LIBRARY_STATIC}") + endif() + + # Hide the stuff we didn't, and no longer, need. + if(NOT JsonCpp_LIBRARY) + unset(JsonCpp_LIBRARY CACHE) + endif() + if(NOT JsonCpp_INCLUDE_DIR) + unset(JsonCpp_INCLUDE_DIR CACHE) + endif() + endif() + + set(JSONCPP_LIBRARY ${JSONCPP_IMPORTED_LIBRARY}) + set(JSONCPP_INCLUDE_DIRS ${JSONCPP_IMPORTED_INCLUDE_DIRS}) + if(DEFINED JSONCPP_IMPORTED_LIBRARY_IS_SHARED) + set(JSONCPP_LIBRARY_IS_SHARED ${JSONCPP_IMPORTED_LIBRARY_IS_SHARED}) + else() + unset(JSONCPP_LIBRARY_IS_SHARED) + endif() + + if(JSONCPP_IMPORTED_LIBRARY_SHARED) + set(JSONCPP_LIBRARY_SHARED ${JSONCPP_IMPORTED_LIBRARY_SHARED}) + endif() + + if(JSONCPP_IMPORTED_LIBRARY_STATIC) + set(JSONCPP_LIBRARY_STATIC ${JSONCPP_IMPORTED_LIBRARY_STATIC}) + endif() +endif() + +# Still nothing after looking for the config file: must go "old-school" +if(NOT JSONCPP_FOUND) + # Invoke pkgconfig for hints + find_package(PkgConfig QUIET) + set(_JSONCPP_INCLUDE_HINTS) + set(_JSONCPP_LIB_HINTS) + if(PKG_CONFIG_FOUND) + pkg_search_module(_JSONCPP_PC QUIET jsoncpp) + if(_JSONCPP_PC_INCLUDE_DIRS) + set(_JSONCPP_INCLUDE_HINTS ${_JSONCPP_PC_INCLUDE_DIRS}) + endif() + if(_JSONCPP_PC_LIBRARY_DIRS) + set(_JSONCPP_LIB_HINTS ${_JSONCPP_PC_LIBRARY_DIRS}) + endif() + if(_JSONCPP_PC_LIBRARIES) + set(_JSONCPP_LIB_NAMES ${_JSONCPP_PC_LIBRARIES}) + endif() + endif() + + if(NOT _JSONCPP_LIB_NAMES) + # OK, if pkg-config wasn't able to give us a library name suggestion, then we may + # have to resort to some intense old logic. + set(_JSONCPP_LIB_NAMES jsoncpp) + set(_JSONCPP_PATHSUFFIXES) + + if(CMAKE_SYSTEM_NAME STREQUAL "Linux") + list(APPEND _JSONCPP_PATHSUFFIXES linux-gcc) # bit of a generalization but close... + endif() + if(CMAKE_COMPILER_IS_GNUCXX AND CMAKE_SYSTEM_NAME STREQUAL "Linux") + list(APPEND _JSONCPP_LIB_NAMES json_linux-gcc-${CMAKE_CXX_COMPILER_VERSION}_libmt json_linux-gcc_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES linux-gcc-${CMAKE_CXX_COMPILER_VERSION}) + + elseif(MSVC) + if(MSVC_VERSION EQUAL 1200) + list(APPEND _JSONCPP_LIB_NAMES json_vc6_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc6) + elseif(MSVC_VERSION EQUAL 1300) + list(APPEND _JSONCPP_LIB_NAMES json_vc7_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc7) + elseif(MSVC_VERSION EQUAL 1310) + list(APPEND _JSONCPP_LIB_NAMES json_vc71_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc71) + elseif(MSVC_VERSION EQUAL 1400) + list(APPEND _JSONCPP_LIB_NAMES json_vc8_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc80) + elseif(MSVC_VERSION EQUAL 1500) + list(APPEND _JSONCPP_LIB_NAMES json_vc9_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc90) + elseif(MSVC_VERSION EQUAL 1600) + list(APPEND _JSONCPP_LIB_NAMES json_vc10_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES msvc10 msvc100) + endif() + + elseif(MINGW) + list(APPEND _JSONCPP_LIB_NAMES json_mingw_libmt) + list(APPEND _JSONCPP_PATHSUFFIXES mingw) + + else() + list(APPEND _JSONCPP_LIB_NAMES json_suncc_libmt json_vacpp_libmt) + endif() + endif() # end of old logic + + # Actually go looking. + find_path( + JsonCpp_INCLUDE_DIR + NAMES json/json.h + PATH_SUFFIXES jsoncpp + HINTS ${_JSONCPP_INCLUDE_HINTS}) + find_library( + JsonCpp_LIBRARY + NAMES ${_JSONCPP_LIB_NAMES} + PATHS libs + PATH_SUFFIXES ${_JSONCPP_PATHSUFFIXES} + HINTS ${_JSONCPP_LIB_HINTS}) + + find_package_handle_standard_args(JsonCpp DEFAULT_MSG JsonCpp_INCLUDE_DIR JsonCpp_LIBRARY) + + if(JSONCPP_FOUND) + # We already know that the target doesn't exist, let's make it. + # TODO don't know why we get errors like: + # error: 'JsonCpp::JsonCpp-NOTFOUND', needed by 'bin/osvr_json_to_c', missing and no known rule to make it + # when we do the imported target commented out below. So, instead, we make an interface + # target with an alias. Hmm. + + #add_library(JsonCpp::JsonCpp UNKNOWN IMPORTED) + #set_target_properties(JsonCpp::JsonCpp PROPERTIES + # IMPORTED_LOCATION "${JsonCpp_LIBRARY}" + # INTERFACE_INCLUDE_DIRECTORIES "${JsonCpp_INCLUDE_DIR}" + # IMPORTED_LINK_INTERFACE_LANGUAGES "CXX") + + set(JSONCPP_LIBRARY "${JsonCpp_LIBRARY}") + set(JSONCPP_INCLUDE_DIRS "${JsonCpp_INCLUDE_DIR}") + unset(JSONCPP_LIBRARY_IS_SHARED) + + if(__jsoncpp_have_interface_support AND NOT TARGET jsoncpp_interface) + add_library(jsoncpp_interface INTERFACE) + set_target_properties(jsoncpp_interface PROPERTIES INTERFACE_LINK_LIBRARIES "${JsonCpp_LIBRARY}" + INTERFACE_INCLUDE_DIRECTORIES "${JsonCpp_INCLUDE_DIR}") + endif() + if(__jsoncpp_have_namespaced_targets) + if(NOT TARGET JsonCpp::JsonCpp) + add_library(JsonCpp::JsonCpp ALIAS jsoncpp_interface) + endif() + endif() + endif() +endif() + +if(JSONCPP_FOUND) + mark_as_advanced(jsoncpp_DIR JsonCpp_INCLUDE_DIR JsonCpp_LIBRARY) +endif() diff --git a/mrt_cmake_modules/cmake/Modules/FindLeptonica.cmake b/mrt_cmake_modules/cmake/Modules/FindLeptonica.cmake new file mode 100644 index 00000000000..5267bbd26db --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindLeptonica.cmake @@ -0,0 +1,11 @@ +set(PACKAGE_HEADER_FILES leptonica/allheaders.h) +set(PACKAGE_LIBRARIES lept) + +find_path(Leptonica_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES}) +find_library(Leptonica_LIBRARIES NAMES ${PACKAGE_LIBRARIES}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args( + Leptonica + FOUND_VAR Leptonica_FOUND + REQUIRED_VARS Leptonica_INCLUDE_DIR Leptonica_LIBRARIES) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtMetis.cmake b/mrt_cmake_modules/cmake/Modules/FindMetis.cmake similarity index 63% rename from mrt_cmake_modules/cmake/Modules/FindMrtMetis.cmake rename to mrt_cmake_modules/cmake/Modules/FindMetis.cmake index 2b876094b60..ff2c5418a1c 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtMetis.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMetis.cmake @@ -5,5 +5,7 @@ find_path(Metis_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES}) find_library(Metis_LIBRARIES NAMES ${PACKAGE_LIBRARIES}) include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Metis FOUND_VAR Metis_FOUND REQUIRED_VARS Metis_INCLUDE_DIR Metis_LIBRARIES) - +find_package_handle_standard_args( + Metis + FOUND_VAR Metis_FOUND + REQUIRED_VARS Metis_INCLUDE_DIR Metis_LIBRARIES) diff --git a/mrt_cmake_modules/cmake/Modules/FindMinpack.cmake b/mrt_cmake_modules/cmake/Modules/FindMinpack.cmake deleted file mode 100644 index b6295e393c8..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMinpack.cmake +++ /dev/null @@ -1,34 +0,0 @@ -# - Find minpack -# Find the Minpack Library (minpack-dev in Xenial) -# -# Using libyaml-cpp: -# find_package(Minpack REQUIRED) -# include_directories(${MINPACK_INCLUDE_DIRS}) -# add_executable(foo foo.cc) -# target_link_libraries(foo ${MINPACK_LIBRARIES}) -# This module sets the following variables: -# MINPACK_FOUND - set to true if the library is found -# MINPACK_INCLUDE_DIRS - list of required include directories -# MINPACK_LIBRARIES - list of libraries to be linked - -find_package(PkgConfig) -#pkg_check_modules(MINPACK REQUIRED minpack) -find_path(MINPACK_INCLUDE_DIRECTORY - NAMES minpack.h - PATHS ${MINPACK_INCLUDE_DIRS} /usr/include -) -find_library(MINPACK_LIBRARY - NAMES minpack - PATHS /usr/lib) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(minpack - FOUND_VAR MINPACK_FOUND - REQUIRED_VARS MINPACK_LIBRARY MINPACK_INCLUDE_DIRECTORY -) - -if (MINPACK_FOUND) - set(MINPACK_INCLUDE_DIRS ${MINPACK_INCLUDE_DIRECTORY}) - set(MINPACK_LIBRARIES ${MINPACK_LIBRARY}) -endif () -mark_as_advanced(MINPACK_INCLUDE_DIRECTORY MINPACK_LIBRARY) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtANN.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtANN.cmake deleted file mode 100644 index 2a2bd0c8780..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtANN.cmake +++ /dev/null @@ -1,11 +0,0 @@ -set(PACKAGE_HEADER_FILES "ANN/ANN.h") -set(PACKAGE_LIBRARIES ANN ann) -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/ann-1.1.2") -set(PACKAGE_PATH "/mrtsoftware/pkg/ann-1.1.2") - -find_path(ANN_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES} PATHS "${PACKAGE_LOCAL_PATH}/include" "${PACKAGE_PATH}/include") -find_library(ANN_LIBRARIES NAMES ${PACKAGE_LIBRARIES} PATHS "${PACKAGE_LOCAL_PATH}/lib" "${PACKAGE_PATH}/lib") - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(ANN FOUND_VAR ANN_FOUND REQUIRED_VARS ANN_INCLUDE_DIR ANN_LIBRARIES) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtCTensorflow.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtCTensorflow.cmake deleted file mode 100644 index 058d2df8d6b..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtCTensorflow.cmake +++ /dev/null @@ -1,28 +0,0 @@ -# try to find tensorflow -find_package(PkgConfig) -find_path(TENSORFLOW_C_INCLUDE_DIR tensorflow/tensorflow/c/c_api.h - PATH_SUFFIXES tensorflow - ) - -set(TENSORFLOW_C_INCLUDE_DIR ${TENSORFLOW_C_INCLUDE_DIR}) - -find_library(TENSORFLOW_C_LIBRARY - NAMES tensorflow - ) -find_library(TENSORFLOW_FRAMEWORK_LIBRARY - NAMES tensorflow_framework - ) - -if(TENSORFLOW_FRAMEWORK_LIBRARY) - set(TENSORFLOW_LIBRARY ${TENSORFLOW_C_LIBRARY} ${TENSORFLOW_FRAMEWORK_LIBRARY}) -else() - set(TENSORFLOW_LIBRARY ${TENSORFLOW_C_LIBRARY}) -endif(TENSORFLOW_FRAMEWORK_LIBRARY) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(MrtCTensorflow DEFAULT_MSG - TENSORFLOW_LIBRARY TENSORFLOW_C_INCLUDE_DIR) - -mark_as_advanced(TENSORFLOW_LIBRARY TENSORFLOW_C_INCLUDE_DIR) -set(TENSORFLOW_LIBRARIES ${TENSORFLOW_LIBRARY} ) -set(TENSORFLOW_C_INCLUDE_DIRS ${TENSORFLOW_C_INCLUDE_DIR} ) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtCUDA.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtCUDA.cmake index 9e5956274e4..32275433de5 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtCUDA.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMrtCUDA.cmake @@ -1,35 +1,39 @@ find_package(CUDA REQUIRED) -if (${CUDA_VERSION_STRING} VERSION_LESS 10.0) +if(${CUDA_VERSION_STRING} VERSION_LESS 10.0) set(_CUDA_HOST_COMPILER "g++-6") elseif(${CUDA_VERSION_STRING} VERSION_LESS 10.2) set(_CUDA_HOST_COMPILER "g++-7") -else() +elseif(${CUDA_VERSION_STRING} VERSION_LESS 11.0) set(_CUDA_HOST_COMPILER "g++-8") +else() + set(_CUDA_HOST_COMPILER "g++-9") endif() -if(${CMAKE_VERSION} VERSION_LESS "3.9.0") - set(CUDA_HOST_COMPILER "${_CUDA_HOST_COMPILER}") - - set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -Wno-deprecated-gpu-targets -std=c++14") - if(${CMAKE_BUILD_TYPE} STREQUAL "Debug") - set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -lineinfo -g --compiler-options -fPIC") - else() - set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -DNDEBUG -O3 --compiler-options -fPIC") - endif() +if(POLICY CMP0104) + cmake_policy(SET CMP0104 NEW) +endif() - set(CUDA_PROPAGATE_HOST_FLAGS OFF) -else() - set(CMAKE_CUDA_COMPILER "${CUDA_TOOLKIT_ROOT_DIR}/bin/nvcc") - set(CMAKE_CUDA_HOST_COMPILER "${_CUDA_HOST_COMPILER}") - set(CMAKE_CUDA_FLAGS "-lineinfo --expt-relaxed-constexpr") +if(NOT TARGET cuda_compiler_flags) + add_library(cuda_compiler_flags INTERFACE IMPORTED) + if(${CMAKE_VERSION} VERSION_LESS "3.9.0") + set(CUDA_HOST_COMPILER "${_CUDA_HOST_COMPILER}") - enable_language(CUDA) + target_compile_options( + cuda_compiler_flags + INTERFACE -Wno-deprecated-gpu-targets;-std=c++14 $<$:-lineinfo;-g;--compiler-options;-fPIC> + $<$>-O3;--compiler-options;-fPIC>) + target_compile_definitions(cuda_compiler_flags $<$>NDEBUG>) + set(CUDA_PROPAGATE_HOST_FLAGS OFF) + else() + set(CMAKE_CUDA_COMPILER "${CUDA_TOOLKIT_ROOT_DIR}/bin/nvcc") + set(CMAKE_CUDA_HOST_COMPILER "${_CUDA_HOST_COMPILER}") + enable_language(CUDA) - if(NOT DEFINED CMAKE_CUDA_STANDARD) - set(CMAKE_CUDA_STANDARD 14) - set(CMAKE_CUDA_STANDARD_REQUIRED ON) + target_compile_options(cuda_compiler_flags + INTERFACE $<$:-lineinfo;--expt-relaxed-constexpr>) + # in cmake 3.17 apparently there should by cuda_std_14 as compile feature + target_compile_features(cuda_compiler_flags INTERFACE cxx_std_14) + target_include_directories(cuda_compiler_flags INTERFACE "${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}") endif() - - set(CUDA_INCLUDE_DIRS "${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}") endif() diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtCaffe.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtCaffe.cmake deleted file mode 100644 index bf845dd2f61..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtCaffe.cmake +++ /dev/null @@ -1,21 +0,0 @@ -#Use the following block, if a package config file is already created by cmake. -#Adjust the following paths if needed. -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/caffe-0.9/share/Caffe") -set(PACKAGE_PATH "/mrtsoftware/pkg/caffe-0.9/share/Caffe") - -#old mrtsoftware-style -if (EXISTS ${PACKAGE_LOCAL_PATH}) - set(Caffe_DIR ${PACKAGE_LOCAL_PATH}) -elseif(EXISTS ${PACKAGE_PATH}) - set(Caffe_DIR ${PACKAGE_PATH}) -endif() - -# find package component -if(MrtCaffe_FIND_REQUIRED) - find_package(Caffe REQUIRED) -elseif(MrtCaffe_FIND_QUIETLY) - find_package(Caffe QUIET) -else() - find_package(Caffe) -endif() - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtCereal.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtCereal.cmake deleted file mode 100644 index 084274cd332..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtCereal.cmake +++ /dev/null @@ -1,11 +0,0 @@ -set(PACKAGE_HEADER_FILES cereal/cereal.hpp) -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/cereal-1.1.2") -set(PACKAGE_PATH "/mrtsoftware/pkg/cereal-1.1.2") - -find_path(Cereal_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES} PATHS "${PACKAGE_LOCAL_PATH}/include" "${PACKAGE_PATH}/include") - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Cereal FOUND_VAR Cereal_FOUND REQUIRED_VARS Cereal_INCLUDE_DIR) - -add_definitions(-DHAS_CEREAL) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtCeres.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtCeres.cmake deleted file mode 100644 index 91cbeb2f1c2..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtCeres.cmake +++ /dev/null @@ -1,25 +0,0 @@ -#Use the following block, if a package config file is already created by cmake. -#Adjust the following paths if needed. -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/ceres-1.10.0/share/Ceres") -set(PACKAGE_PATH "/mrtsoftware/pkg/ceres-1.10.0/share/Ceres") - -if (EXISTS ${PACKAGE_LOCAL_PATH}) - set(Ceres_DIR ${PACKAGE_LOCAL_PATH}) -elseif(EXISTS ${PACKAGE_PATH}) - set(Ceres_DIR ${PACKAGE_PATH}) -endif() - -# find package component -if(MrtCeres_FIND_REQUIRED) - find_package(Ceres REQUIRED) -elseif(MrtCeres_FIND_QUIETLY) - find_package(Ceres QUIET) -else() - find_package(Ceres) -endif() - -if(NOT CERES_INCLUDE_DIRS AND CERES_LIBRARIES) - # Newer ceres versions no longer set CERS_INCLUDE_DIRS - get_target_property(CERES_INCLUDE_DIRS ceres INTERFACE_INCLUDE_DIRECTORIES) -endif() - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtLAPACK.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtLAPACK.cmake deleted file mode 100644 index d6dbaa3161c..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtLAPACK.cmake +++ /dev/null @@ -1,15 +0,0 @@ -if(MrtLAPACK_FIND_REQUIRED) - find_package(LAPACK QUIET REQUIRED) -elseif(MrtLAPACK_FIND_QUIETLY) - find_package(LAPACK QUIET) -else() - find_package(LAPACK QUIET) -endif() - -set(MrtLAPACK_FOUND LAPACK_FOUND) - -# LAPACK_LIBRARIES are empty with cmake 3.16 but it is needed on ubuntu 18.04. -# Maybe this is a bug in the LAPACK cmake find script. -if (NOT LAPACK_LIBRARIES) - set(LAPACK_LIBRARIES "lapack") -endif() diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtLeptonica.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtLeptonica.cmake deleted file mode 100644 index c0c4811b956..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtLeptonica.cmake +++ /dev/null @@ -1,11 +0,0 @@ -set(PACKAGE_HEADER_FILES leptonica/allheaders.h) -set(PACKAGE_LIBRARIES lept) -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/leptonica-1.72") -set(PACKAGE_PATH "/mrtsoftware/pkg/leptonica-1.72") - -find_path(Leptonica_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES} PATHS "${PACKAGE_LOCAL_PATH}/include" "${PACKAGE_PATH}/include" /usr/local/include /usr/include) -find_library(Leptonica_LIBRARIES NAMES ${PACKAGE_LIBRARIES} PATHS "${PACKAGE_LOCAL_PATH}/lib" "${PACKAGE_PATH}/lib" /usr/local/lib /usr/lib) - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Leptonica FOUND_VAR Leptonica_FOUND REQUIRED_VARS Leptonica_INCLUDE_DIR Leptonica_LIBRARIES) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtOpenCV.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtOpenCV.cmake deleted file mode 100644 index 8df35dc733b..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtOpenCV.cmake +++ /dev/null @@ -1,20 +0,0 @@ -#Use the following block, if a package config file is already created by cmake. -#Adjust the following paths if needed. -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/opencv-2.4.11/share/OpenCV") -set(PACKAGE_PATH "/mrtsoftware/pkg/opencv-2.4.11/share/OpenCV") - -#old mrtsoftware-style -if (EXISTS ${PACKAGE_LOCAL_PATH}) - set(OpenCV_DIR ${PACKAGE_LOCAL_PATH}) -elseif(EXISTS ${PACKAGE_PATH}) - set(OpenCV_DIR ${PACKAGE_PATH}) -endif() - -# find package component -if(MrtOpenCV_FIND_REQUIRED) - find_package(OpenCV REQUIRED) -elseif(MrtOpenCV_FIND_QUIETLY) - find_package(OpenCV QUIET) -else() - find_package(OpenCV) -endif() diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtOpenGL.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtOpenGL.cmake new file mode 100644 index 00000000000..95daf0de7e3 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindMrtOpenGL.cmake @@ -0,0 +1,10 @@ +# only required to silence cmake warnings +set(OpenGL_GL_PREFERENCE GLVND) +if(MrtOpenGL_FIND_REQUIRED) + find_package(OpenGL QUIET REQUIRED) +elseif(MrtOpenGL_FIND_QUIETLY) + find_package(OpenGL QUIET) +else() + find_package(OpenGL QUIET) +endif() +set(MrtOpenGL_FOUND ${OpenGL_FOUND}) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtPCL.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtPCL.cmake index a00451c3298..652ebc90f58 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtPCL.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMrtPCL.cmake @@ -1,27 +1,61 @@ -#Use the following block, if a package config file is already created by cmake. -#Adjust the following paths if needed. -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/pcl-1.8/share/pcl-1.8") -set(PACKAGE_PATH "/mrtsoftware/pkg/pcl-1.8/share/pcl-1.8") +# protect agains multiple inclusion +if(TARGET mrt_pcl::pcl) + return() +endif() cmake_policy(PUSH) if(POLICY CMP0074) - cmake_policy(SET CMP0074 NEW) -endif() - -#old mrtsoftware-style -if (EXISTS ${PACKAGE_LOCAL_PATH}) - set(PCL_DIR ${PACKAGE_LOCAL_PATH}) -elseif(EXISTS ${PACKAGE_PATH}) - set(PCL_DIR ${PACKAGE_PATH}) + cmake_policy(SET CMP0074 NEW) endif() # find package component if(Mrtpcl_FIND_REQUIRED) - find_package(PCL QUIET REQUIRED) + find_package(PCL QUIET REQUIRED) elseif(Mrtpcl_FIND_QUIETLY) - find_package(PCL QUIET) + find_package(PCL QUIET) else() - find_package(PCL QUIET) + find_package(PCL QUIET) endif() +add_library(mrt_pcl::pcl INTERFACE IMPORTED) + +# Copied from FindAutoDeps.cmake +function(_cleanup_libraries var_name_libs) + # replace "debug", "general" and "optimized" keywords in the libraries list with generator expressions + list(LENGTH ${var_name_libs} size) + foreach(idx RANGE ${size}) + if(${idx} EQUAL ${size}) + continue() + endif() + list(GET ${var_name_libs} ${idx} statement) + if(${statement} STREQUAL "debug") + math(EXPR next ${idx}+1) + list(GET ${var_name_libs} ${next} lib) + list(REMOVE_AT ${var_name_libs} ${next}) + list(INSERT ${var_name_libs} ${next} "$<$:${lib}>") + elseif(${statement} STREQUAL "optimized") + math(EXPR next ${idx}+1) + list(GET ${var_name_libs} ${next} lib) + list(REMOVE_AT ${var_name_libs} ${next}) + list(INSERT ${var_name_libs} ${next} "$<$>:${lib}>") + endif() + endforeach() + if(size) + list(REMOVE_ITEM ${var_name_libs} debug optimized general) + endif() + set(${var_name_libs} + ${${var_name_libs}} + PARENT_SCOPE) +endfunction() + +_cleanup_libraries(PCL_LIBRARIES) + +# Add PCL_NO_PRECOMPILE as this resolves Eigen issues. +set_target_properties( + mrt_pcl::pcl + PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${PCL_INCLUDE_DIRS}" + INTERFACE_LINK_DIRECTORIES "${PCL_LIBRARY_DIRS}" + INTERFACE_LINK_LIBRARIES "${PCL_LIBRARIES}" + INTERFACE_COMPILE_DEFINITIONS "PCL_NO_PRECOMPILE") + cmake_policy(POP) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtQt4.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtQt4.cmake index 4cc18e0e400..1e9c1eef884 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtQt4.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMrtQt4.cmake @@ -1,4 +1,3 @@ find_package(Qt4 REQUIRED ${MrtQt4_FIND_COMPONENTS}) -message( STATUS "Qt Components: " ${MrtQt4_FIND_COMPONENTS}) +message(STATUS "Qt Components: " ${MrtQt4_FIND_COMPONENTS}) include(${QT_USE_FILE}) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtQt5.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtQt5.cmake index af5aad9361c..4c0887c4af8 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtQt5.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMrtQt5.cmake @@ -1,5 +1,12 @@ if(NOT MrtQt5_FIND_COMPONENTS) - set(_components QtCore QtDBus QtGui QtNetwork QtTest QtWidgets QtXml) + set(_components + QtCore + QtDBus + QtGui + QtNetwork + QtTest + QtWidgets + QtXml) else() set(_components ${MrtQt5_FIND_COMPONENTS}) endif() @@ -8,8 +15,6 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON) set(CMAKE_AUTOMOC ON) set(CMAKE_AUTOUIC ON) -message(STATUS "Search for Qt5:") - foreach(_component ${_components}) set(_libname Qt5${_component}) if(MrtQt5_FIND_REQUIRED) @@ -19,8 +24,8 @@ foreach(_component ${_components}) endif() if(${_libname}_FOUND) - message(STATUS " Found ${_libname}") - list(APPEND QT_INCLUDES ${${_libname}_INCLUDE_DIRS}) - list(APPEND QT_LIBRARIES "Qt5::${_component}") + message(STATUS " Found ${_libname}") + list(APPEND QT_INCLUDES ${${_libname}_INCLUDE_DIRS}) + list(APPEND QT_LIBRARIES "Qt5::${_component}") endif() endforeach() diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtSuiteSparse.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtSuiteSparse.cmake deleted file mode 100644 index a44fe8fd972..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtSuiteSparse.cmake +++ /dev/null @@ -1,620 +0,0 @@ -# Ceres Solver - A fast non-linear least squares minimizer -# Copyright 2013 Google Inc. All rights reserved. -# http://code.google.com/p/ceres-solver/ -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# * Neither the name of Google Inc. nor the names of its contributors may be -# used to endorse or promote products derived from this software without -# specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -# Author: alexs.mac@gmail.com (Alex Stewart) -# - -# FindSuiteSparse.cmake - Find SuiteSparse libraries & dependencies. -# -# This module defines the following variables: -# -# SUITESPARSE_FOUND: TRUE iff SuiteSparse and all dependencies have been found. -# SUITESPARSE_INCLUDE_DIRS: Include directories for all SuiteSparse components. -# SUITESPARSE_LIBRARIES: Libraries for all SuiteSparse component libraries and -# dependencies. -# SUITESPARSE_VERSION: Extracted from UFconfig.h (<= v3) or -# SuiteSparse_config.h (>= v4). -# SUITESPARSE_MAIN_VERSION: Equal to 4 if SUITESPARSE_VERSION = 4.2.1 -# SUITESPARSE_SUB_VERSION: Equal to 2 if SUITESPARSE_VERSION = 4.2.1 -# SUITESPARSE_SUBSUB_VERSION: Equal to 1 if SUITESPARSE_VERSION = 4.2.1 -# -# SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION: TRUE iff running -# on Ubuntu, SUITESPARSE_VERSION is 3.4.0 and found SuiteSparse is a system -# install, in which case found version of SuiteSparse cannot be used to link -# a shared library due to a bug (static linking is unaffected). -# -# The following variables control the behaviour of this module: -# -# SUITESPARSE_INCLUDE_DIR_HINTS: List of additional directories in which to -# search for SuiteSparse includes, -# e.g: /timbuktu/include. -# SUITESPARSE_LIBRARY_DIR_HINTS: List of additional directories in which to -# search for SuiteSparse libraries, -# e.g: /timbuktu/lib. -# -# The following variables define the presence / includes & libraries for the -# SuiteSparse components searched for, the SUITESPARSE_XX variables are the -# union of the variables for all components. -# -# == Symmetric Approximate Minimum Degree (AMD) -# AMD_FOUND -# AMD_INCLUDE_DIR -# AMD_LIBRARY -# -# == Constrained Approximate Minimum Degree (CAMD) -# CAMD_FOUND -# CAMD_INCLUDE_DIR -# CAMD_LIBRARY -# -# == Column Approximate Minimum Degree (COLAMD) -# COLAMD_FOUND -# COLAMD_INCLUDE_DIR -# COLAMD_LIBRARY -# -# Constrained Column Approximate Minimum Degree (CCOLAMD) -# CCOLAMD_FOUND -# CCOLAMD_INCLUDE_DIR -# CCOLAMD_LIBRARY -# -# == Sparse Supernodal Cholesky Factorization and Update/Downdate (CHOLMOD) -# CHOLMOD_FOUND -# CHOLMOD_INCLUDE_DIR -# CHOLMOD_LIBRARY -# -# == Multifrontal Sparse QR (SuiteSparseQR) -# SUITESPARSEQR_FOUND -# SUITESPARSEQR_INCLUDE_DIR -# SUITESPARSEQR_LIBRARY -# -# == Common configuration for all but CSparse (SuiteSparse version >= 4). -# SUITESPARSE_CONFIG_FOUND -# SUITESPARSE_CONFIG_INCLUDE_DIR -# SUITESPARSE_CONFIG_LIBRARY -# -# == Common configuration for all but CSparse (SuiteSparse version < 4). -# UFCONFIG_FOUND -# UFCONFIG_INCLUDE_DIR -# -# Optional SuiteSparse Dependencies: -# -# == Serial Graph Partitioning and Fill-reducing Matrix Ordering (METIS) -# METIS_FOUND -# METIS_LIBRARY -# -# == Intel Thread Building Blocks (TBB) -# TBB_FOUND -# TBB_LIBRARIES - -# Called if we failed to find SuiteSparse or any of it's required dependencies, -# unsets all public (designed to be used externally) variables and reports -# error message at priority depending upon [REQUIRED/QUIET/] argument. -MACRO(SUITESPARSE_REPORT_NOT_FOUND REASON_MSG) - UNSET(SUITESPARSE_FOUND) - UNSET(SUITESPARSE_INCLUDE_DIRS) - UNSET(SUITESPARSE_LIBRARIES) - UNSET(SUITESPARSE_VERSION) - UNSET(SUITESPARSE_MAIN_VERSION) - UNSET(SUITESPARSE_SUB_VERSION) - UNSET(SUITESPARSE_SUBSUB_VERSION) - # Do NOT unset SUITESPARSE_FOUND_REQUIRED_VARS here, as it is used by - # FindPackageHandleStandardArgs() to generate the automatic error message on - # failure which highlights which components are missing. - - # Note _FIND_[REQUIRED/QUIETLY] variables defined by FindPackage() - # use the camelcase library name, not uppercase. - IF (SuiteSparse_FIND_QUIETLY) - MESSAGE(STATUS "Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) - ELSEIF (SuiteSparse_FIND_REQUIRED) - MESSAGE(FATAL_ERROR "Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) - ELSE() - # Neither QUIETLY nor REQUIRED, use no priority which emits a message - # but continues configuration and allows generation. - MESSAGE("-- Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) - ENDIF (SuiteSparse_FIND_QUIETLY) - - # Do not call RETURN(), s/t we keep processing if not called with REQUIRED. -ENDMACRO(SUITESPARSE_REPORT_NOT_FOUND) - -# Specify search directories for include files and libraries (this is the union -# of the search directories for all OSs). Search user-specified hint -# directories first if supplied, and search user-installed locations first -# so that we prefer user installs to system installs where both exist. -LIST(APPEND SUITESPARSE_CHECK_INCLUDE_DIRS - /mrtsoftware/pkg/local/suitesparse-4.4.4/include - /mrtsoftware/pkg/suitesparse-4.4.4/include - /usr/local/include - /usr/local/include/suitesparse - /usr/include/suitesparse # Ubuntu - /usr/include) -LIST(APPEND SUITESPARSE_CHECK_LIBRARY_DIRS - /mrtsoftware/pkg/local/suitesparse-4.4.4/lib - /mrtsoftware/pkg/suitesparse-4.4.4/lib - /usr/local/lib - /usr/local/lib/suitesparse - /usr/lib/suitesparse # Ubuntu - /usr/lib) - -# Given the number of components of SuiteSparse, and to ensure that the -# automatic failure message generated by FindPackageHandleStandardArgs() -# when not all required components are found is helpful, we maintain a list -# of all variables that must be defined for SuiteSparse to be considered found. -UNSET(SUITESPARSE_FOUND_REQUIRED_VARS) - -# BLAS. -FIND_PACKAGE(BLAS QUIET) -IF (NOT BLAS_FOUND) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find BLAS library (required for SuiteSparse).") -ENDIF (NOT BLAS_FOUND) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS BLAS_FOUND) - -# LAPACK. -FIND_PACKAGE(LAPACK QUIET) -IF (NOT LAPACK_FOUND) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find LAPACK library (required for SuiteSparse).") -ENDIF (NOT LAPACK_FOUND) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS LAPACK_FOUND) - -# AMD. -SET(AMD_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS AMD_FOUND) -FIND_LIBRARY(AMD_LIBRARY NAMES amd - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${AMD_LIBRARY}) - MESSAGE(STATUS "Found AMD library: ${AMD_LIBRARY}") -ELSE (EXISTS ${AMD_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find AMD library (required SuiteSparse component).") - SET(AMD_FOUND FALSE) -ENDIF (EXISTS ${AMD_LIBRARY}) -MARK_AS_ADVANCED(AMD_LIBRARY) - -FIND_PATH(AMD_INCLUDE_DIR NAMES amd.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${AMD_INCLUDE_DIR}) - MESSAGE(STATUS "Found AMD header in: ${AMD_INCLUDE_DIR}") -ELSE (EXISTS ${AMD_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find AMD header (required SuiteSparse component).") - SET(AMD_FOUND FALSE) -ENDIF (EXISTS ${AMD_INCLUDE_DIR}) -MARK_AS_ADVANCED(AMD_INCLUDE_DIR) - -# CAMD. -SET(CAMD_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS CAMD_FOUND) -FIND_LIBRARY(CAMD_LIBRARY NAMES camd - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${CAMD_LIBRARY}) - MESSAGE(STATUS "Found CAMD library: ${CAMD_LIBRARY}") -ELSE (EXISTS ${CAMD_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CAMD library (required SuiteSparse component).") - SET(CAMD_FOUND FALSE) -ENDIF (EXISTS ${CAMD_LIBRARY}) -MARK_AS_ADVANCED(CAMD_LIBRARY) - -FIND_PATH(CAMD_INCLUDE_DIR NAMES camd.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${CAMD_INCLUDE_DIR}) - MESSAGE(STATUS "Found CAMD header in: ${CAMD_INCLUDE_DIR}") -ELSE (EXISTS ${CAMD_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CAMD header (required SuiteSparse component).") - SET(CAMD_FOUND FALSE) -ENDIF (EXISTS ${CAMD_INCLUDE_DIR}) -MARK_AS_ADVANCED(CAMD_INCLUDE_DIR) - -# COLAMD. -SET(COLAMD_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS COLAMD_FOUND) -FIND_LIBRARY(COLAMD_LIBRARY NAMES colamd - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${COLAMD_LIBRARY}) - MESSAGE(STATUS "Found COLAMD library: ${COLAMD_LIBRARY}") -ELSE (EXISTS ${COLAMD_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find COLAMD library (required SuiteSparse component).") - SET(COLAMD_FOUND FALSE) -ENDIF (EXISTS ${COLAMD_LIBRARY}) -MARK_AS_ADVANCED(COLAMD_LIBRARY) - -FIND_PATH(COLAMD_INCLUDE_DIR NAMES colamd.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${COLAMD_INCLUDE_DIR}) - MESSAGE(STATUS "Found COLAMD header in: ${COLAMD_INCLUDE_DIR}") -ELSE (EXISTS ${COLAMD_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find COLAMD header (required SuiteSparse component).") - SET(COLAMD_FOUND FALSE) -ENDIF (EXISTS ${COLAMD_INCLUDE_DIR}) -MARK_AS_ADVANCED(COLAMD_INCLUDE_DIR) - -# CCOLAMD. -SET(CCOLAMD_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS CCOLAMD_FOUND) -FIND_LIBRARY(CCOLAMD_LIBRARY NAMES ccolamd - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${CCOLAMD_LIBRARY}) - MESSAGE(STATUS "Found CCOLAMD library: ${CCOLAMD_LIBRARY}") -ELSE (EXISTS ${CCOLAMD_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CCOLAMD library (required SuiteSparse component).") - SET(CCOLAMD_FOUND FALSE) -ENDIF (EXISTS ${CCOLAMD_LIBRARY}) -MARK_AS_ADVANCED(CCOLAMD_LIBRARY) - -FIND_PATH(CCOLAMD_INCLUDE_DIR NAMES ccolamd.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${CCOLAMD_INCLUDE_DIR}) - MESSAGE(STATUS "Found CCOLAMD header in: ${CCOLAMD_INCLUDE_DIR}") -ELSE (EXISTS ${CCOLAMD_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CCOLAMD header (required SuiteSparse component).") - SET(CCOLAMD_FOUND FALSE) -ENDIF (EXISTS ${CCOLAMD_INCLUDE_DIR}) -MARK_AS_ADVANCED(CCOLAMD_INCLUDE_DIR) - -# CHOLMOD. -SET(CHOLMOD_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS CHOLMOD_FOUND) -FIND_LIBRARY(CHOLMOD_LIBRARY NAMES cholmod - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${CHOLMOD_LIBRARY}) - MESSAGE(STATUS "Found CHOLMOD library: ${CHOLMOD_LIBRARY}") -ELSE (EXISTS ${CHOLMOD_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CHOLMOD library (required SuiteSparse component).") - SET(CHOLMOD_FOUND FALSE) -ENDIF (EXISTS ${CHOLMOD_LIBRARY}) -MARK_AS_ADVANCED(CHOLMOD_LIBRARY) - -FIND_PATH(CHOLMOD_INCLUDE_DIR NAMES cholmod.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${CHOLMOD_INCLUDE_DIR}) - MESSAGE(STATUS "Found CHOLMOD header in: ${CHOLMOD_INCLUDE_DIR}") -ELSE (EXISTS ${CHOLMOD_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find CHOLMOD header (required SuiteSparse component).") - SET(CHOLMOD_FOUND FALSE) -ENDIF (EXISTS ${CHOLMOD_INCLUDE_DIR}) -MARK_AS_ADVANCED(CHOLMOD_INCLUDE_DIR) - -# SuiteSparseQR. -SET(SUITESPARSEQR_FOUND TRUE) -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS SUITESPARSEQR_FOUND) -FIND_LIBRARY(SUITESPARSEQR_LIBRARY NAMES spqr - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${SUITESPARSEQR_LIBRARY}) - MESSAGE(STATUS "Found SuiteSparseQR library: ${SUITESPARSEQR_LIBRARY}") -ELSE (EXISTS ${SUITESPARSEQR_LIBRARY}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find SuiteSparseQR library (required SuiteSparse component).") - SET(SUITESPARSEQR_FOUND FALSE) -ENDIF (EXISTS ${SUITESPARSEQR_LIBRARY}) -MARK_AS_ADVANCED(SUITESPARSEQR_LIBRARY) - -FIND_PATH(SUITESPARSEQR_INCLUDE_DIR NAMES SuiteSparseQR.hpp - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${SUITESPARSEQR_INCLUDE_DIR}) - MESSAGE(STATUS "Found SuiteSparseQR header in: ${SUITESPARSEQR_INCLUDE_DIR}") -ELSE (EXISTS ${SUITESPARSEQR_INCLUDE_DIR}) - SUITESPARSE_REPORT_NOT_FOUND( - "Did not find SUITESPARSEQR header (required SuiteSparse component).") - SET(SUITESPARSEQR_FOUND FALSE) -ENDIF (EXISTS ${SUITESPARSEQR_INCLUDE_DIR}) -MARK_AS_ADVANCED(SUITESPARSEQR_INCLUDE_DIR) - -IF (SUITESPARSEQR_FOUND) - # SuiteSparseQR may be compiled with Intel Threading Building Blocks, - # we assume that if TBB is installed, SuiteSparseQR was compiled with - # support for it, this will do no harm if it wasn't. - SET(TBB_FOUND TRUE) - FIND_LIBRARY(TBB_LIBRARIES NAMES tbb - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) - IF (EXISTS ${TBB_LIBRARIES}) - MESSAGE(STATUS "Found Intel Thread Building Blocks (TBB) library: " - "${TBB_LIBRARIES}, assuming SuiteSparseQR was compiled with TBB.") - ELSE (EXISTS ${TBB_LIBRARIES}) - MESSAGE(STATUS "Did not find Intel TBB library, assuming SuiteSparseQR was " - "not compiled with TBB.") - SET(TBB_FOUND FALSE) - ENDIF (EXISTS ${TBB_LIBRARIES}) - MARK_AS_ADVANCED(TBB_LIBRARIES) - - IF (TBB_FOUND) - FIND_LIBRARY(TBB_MALLOC_LIB NAMES tbbmalloc - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) - IF (EXISTS ${TBB_MALLOC_LIB}) - MESSAGE(STATUS "Found Intel Thread Building Blocks (TBB) Malloc library: " - "${TBB_MALLOC_LIB}") - # Append TBB malloc library to TBB libraries list whilst retaining - # any CMake generated help string (cache variable). - LIST(APPEND TBB_LIBRARIES ${TBB_MALLOC_LIB}) - GET_PROPERTY(HELP_STRING CACHE TBB_LIBRARIES PROPERTY HELPSTRING) - SET(TBB_LIBRARIES "${TBB_LIBRARIES}" CACHE STRING "${HELP_STRING}") - - # Add the TBB libraries to the SuiteSparseQR libraries (the only - # libraries to optionally depend on TBB). - LIST(APPEND SUITESPARSEQR_LIBRARY ${TBB_LIBRARIES}) - - ELSE (EXISTS ${TBB_MALLOC_LIB}) - # If we cannot find all required TBB components do not include it as - # a dependency. - MESSAGE(STATUS "Did not find Intel Thread Building Blocks (TBB) Malloc " - "Library, discarding TBB as a dependency.") - SET(TBB_FOUND FALSE) - ENDIF (EXISTS ${TBB_MALLOC_LIB}) - MARK_AS_ADVANCED(TBB_MALLOC_LIB) - ENDIF (TBB_FOUND) -ENDIF(SUITESPARSEQR_FOUND) - -# UFconfig / SuiteSparse_config. -# -# If SuiteSparse version is >= 4 then SuiteSparse_config is required. -# For SuiteSparse 3, UFconfig.h is required. -FIND_LIBRARY(SUITESPARSE_CONFIG_LIBRARY NAMES suitesparseconfig - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) -IF (EXISTS ${SUITESPARSE_CONFIG_LIBRARY}) - MESSAGE(STATUS "Found SuiteSparse_config library: " - "${SUITESPARSE_CONFIG_LIBRARY}") -ENDIF (EXISTS ${SUITESPARSE_CONFIG_LIBRARY}) -MARK_AS_ADVANCED(SUITESPARSE_CONFIG_LIBRARY) - -FIND_PATH(SUITESPARSE_CONFIG_INCLUDE_DIR NAMES SuiteSparse_config.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) -IF (EXISTS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) - MESSAGE(STATUS "Found SuiteSparse_config header in: " - "${SUITESPARSE_CONFIG_INCLUDE_DIR}") -ENDIF (EXISTS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) -MARK_AS_ADVANCED(SUITESPARSE_CONFIG_INCLUDE_DIR) - -SET(SUITESPARSE_CONFIG_FOUND FALSE) -SET(UFCONFIG_FOUND FALSE) - -IF (EXISTS ${SUITESPARSE_CONFIG_LIBRARY} AND - EXISTS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) - SET(SUITESPARSE_CONFIG_FOUND TRUE) - # SuiteSparse_config (SuiteSparse version >= 4) requires librt library for - # timing by default when compiled on Linux or Unix, but not on OSX (which - # does not have librt). - IF (CMAKE_SYSTEM_NAME MATCHES "Linux" OR UNIX AND NOT APPLE) - FIND_LIBRARY(LIBRT_LIBRARY NAMES rt - PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS}) - IF (LIBRT_LIBRARY) - MESSAGE(STATUS "Adding librt: ${LIBRT_LIBRARY} to " - "SuiteSparse_config libraries (required on Linux & Unix [not OSX] if " - "SuiteSparse is compiled with timing).") - ELSE (LIBRT_LIBRARY) - MESSAGE(STATUS "Could not find librt, but found SuiteSparse_config, " - "assuming that SuiteSparse was compiled without timing.") - ENDIF (LIBRT_LIBRARY) - MARK_AS_ADVANCED(LIBRT_LIBRARY) - LIST(APPEND SUITESPARSE_CONFIG_LIBRARY ${LIBRT_LIBRARY}) - ENDIF (CMAKE_SYSTEM_NAME MATCHES "Linux" OR UNIX AND NOT APPLE) - -ELSE (EXISTS ${SUITESPARSE_CONFIG_LIBRARY} AND - EXISTS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) - # Failed to find SuiteSparse_config (>= v4 installs), instead look for - # UFconfig header which should be present in < v4 installs. - SET(SUITESPARSE_CONFIG_FOUND FALSE) - FIND_PATH(UFCONFIG_INCLUDE_DIR NAMES UFconfig.h - PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS}) - IF (EXISTS ${UFCONFIG_INCLUDE_DIR}) - MESSAGE(STATUS "Found UFconfig header in: ${UFCONFIG_INCLUDE_DIR}") - SET(UFCONFIG_FOUND TRUE) - ENDIF (EXISTS ${UFCONFIG_INCLUDE_DIR}) - MARK_AS_ADVANCED(UFCONFIG_INCLUDE_DIR) -ENDIF (EXISTS ${SUITESPARSE_CONFIG_LIBRARY} AND - EXISTS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) - -IF (NOT SUITESPARSE_CONFIG_FOUND AND - NOT UFCONFIG_FOUND) - SUITESPARSE_REPORT_NOT_FOUND( - "Failed to find either: SuiteSparse_config header & library (should be " - "present in all SuiteSparse >= v4 installs), or UFconfig header (should " - "be present in all SuiteSparse < v4 installs).") -ENDIF (NOT SUITESPARSE_CONFIG_FOUND AND - NOT UFCONFIG_FOUND) - -# Extract the SuiteSparse version from the appropriate header (UFconfig.h for -# <= v3, SuiteSparse_config.h for >= v4). -LIST(APPEND SUITESPARSE_FOUND_REQUIRED_VARS SUITESPARSE_VERSION) - -IF (UFCONFIG_FOUND) - # SuiteSparse version <= 3. - SET(SUITESPARSE_VERSION_FILE ${UFCONFIG_INCLUDE_DIR}/UFconfig.h) - IF (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) - SUITESPARSE_REPORT_NOT_FOUND( - "Could not find file: ${SUITESPARSE_VERSION_FILE} containing version " - "information for <= v3 SuiteSparse installs, but UFconfig was found " - "(only present in <= v3 installs).") - ELSE (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) - FILE(READ ${SUITESPARSE_VERSION_FILE} UFCONFIG_CONTENTS) - - STRING(REGEX MATCH "#define SUITESPARSE_MAIN_VERSION [0-9]+" - SUITESPARSE_MAIN_VERSION "${UFCONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_MAIN_VERSION ([0-9]+)" "\\1" - SUITESPARSE_MAIN_VERSION "${SUITESPARSE_MAIN_VERSION}") - - STRING(REGEX MATCH "#define SUITESPARSE_SUB_VERSION [0-9]+" - SUITESPARSE_SUB_VERSION "${UFCONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_SUB_VERSION ([0-9]+)" "\\1" - SUITESPARSE_SUB_VERSION "${SUITESPARSE_SUB_VERSION}") - - STRING(REGEX MATCH "#define SUITESPARSE_SUBSUB_VERSION [0-9]+" - SUITESPARSE_SUBSUB_VERSION "${UFCONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_SUBSUB_VERSION ([0-9]+)" "\\1" - SUITESPARSE_SUBSUB_VERSION "${SUITESPARSE_SUBSUB_VERSION}") - - # This is on a single line s/t CMake does not interpret it as a list of - # elements and insert ';' separators which would result in 4.;2.;1 nonsense. - SET(SUITESPARSE_VERSION - "${SUITESPARSE_MAIN_VERSION}.${SUITESPARSE_SUB_VERSION}.${SUITESPARSE_SUBSUB_VERSION}") - ENDIF (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) -ENDIF (UFCONFIG_FOUND) - -IF (SUITESPARSE_CONFIG_FOUND) - # SuiteSparse version >= 4. - SET(SUITESPARSE_VERSION_FILE - ${SUITESPARSE_CONFIG_INCLUDE_DIR}/SuiteSparse_config.h) - IF (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) - SUITESPARSE_REPORT_NOT_FOUND( - "Could not find file: ${SUITESPARSE_VERSION_FILE} containing version " - "information for >= v4 SuiteSparse installs, but SuiteSparse_config was " - "found (only present in >= v4 installs).") - ELSE (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) - FILE(READ ${SUITESPARSE_VERSION_FILE} SUITESPARSE_CONFIG_CONTENTS) - - STRING(REGEX MATCH "#define SUITESPARSE_MAIN_VERSION [0-9]+" - SUITESPARSE_MAIN_VERSION "${SUITESPARSE_CONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_MAIN_VERSION ([0-9]+)" "\\1" - SUITESPARSE_MAIN_VERSION "${SUITESPARSE_MAIN_VERSION}") - - STRING(REGEX MATCH "#define SUITESPARSE_SUB_VERSION [0-9]+" - SUITESPARSE_SUB_VERSION "${SUITESPARSE_CONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_SUB_VERSION ([0-9]+)" "\\1" - SUITESPARSE_SUB_VERSION "${SUITESPARSE_SUB_VERSION}") - - STRING(REGEX MATCH "#define SUITESPARSE_SUBSUB_VERSION [0-9]+" - SUITESPARSE_SUBSUB_VERSION "${SUITESPARSE_CONFIG_CONTENTS}") - STRING(REGEX REPLACE "#define SUITESPARSE_SUBSUB_VERSION ([0-9]+)" "\\1" - SUITESPARSE_SUBSUB_VERSION "${SUITESPARSE_SUBSUB_VERSION}") - - # This is on a single line s/t CMake does not interpret it as a list of - # elements and insert ';' separators which would result in 4.;2.;1 nonsense. - SET(SUITESPARSE_VERSION - "${SUITESPARSE_MAIN_VERSION}.${SUITESPARSE_SUB_VERSION}.${SUITESPARSE_SUBSUB_VERSION}") - ENDIF (NOT EXISTS ${SUITESPARSE_VERSION_FILE}) -ENDIF (SUITESPARSE_CONFIG_FOUND) - -# METIS (Optional dependency). -find_package(MrtMetis QUIET) - -# Only mark SuiteSparse as found if all required components and dependencies -# have been found. -SET(SUITESPARSE_FOUND TRUE) -FOREACH(REQUIRED_VAR ${SUITESPARSE_FOUND_REQUIRED_VARS}) - IF (NOT ${REQUIRED_VAR}) - SET(SUITESPARSE_FOUND FALSE) - ENDIF (NOT ${REQUIRED_VAR}) -ENDFOREACH(REQUIRED_VAR ${SUITESPARSE_FOUND_REQUIRED_VARS}) - -IF (SUITESPARSE_FOUND) - LIST(APPEND SUITESPARSE_INCLUDE_DIRS - ${AMD_INCLUDE_DIR} - ${CAMD_INCLUDE_DIR} - ${COLAMD_INCLUDE_DIR} - ${CCOLAMD_INCLUDE_DIR} - ${CHOLMOD_INCLUDE_DIR} - ${SUITESPARSEQR_INCLUDE_DIR}) - # Handle config separately, as otherwise at least one of them will be set - # to NOTFOUND which would cause any check on SUITESPARSE_INCLUDE_DIRS to fail. - IF (SUITESPARSE_CONFIG_FOUND) - LIST(APPEND SUITESPARSE_INCLUDE_DIRS - ${SUITESPARSE_CONFIG_INCLUDE_DIR}) - ENDIF (SUITESPARSE_CONFIG_FOUND) - IF (UFCONFIG_FOUND) - LIST(APPEND SUITESPARSE_INCLUDE_DIRS - ${UFCONFIG_INCLUDE_DIR}) - ENDIF (UFCONFIG_FOUND) - # As SuiteSparse includes are often all in the same directory, remove any - # repetitions. - LIST(REMOVE_DUPLICATES SUITESPARSE_INCLUDE_DIRS) - - # Important: The ordering of these libraries is *NOT* arbitrary, as these - # could potentially be static libraries their link ordering is important. - LIST(APPEND SUITESPARSE_LIBRARIES - ${SUITESPARSEQR_LIBRARY} - ${CHOLMOD_LIBRARY} - ${CCOLAMD_LIBRARY} - ${CAMD_LIBRARY} - ${COLAMD_LIBRARY} - ${AMD_LIBRARY} - ${LAPACK_LIBRARIES} - ${BLAS_LIBRARIES}) - IF (SUITESPARSE_CONFIG_FOUND) - LIST(APPEND SUITESPARSE_LIBRARIES - ${SUITESPARSE_CONFIG_LIBRARY}) - ENDIF (SUITESPARSE_CONFIG_FOUND) - IF (METIS_FOUND) - LIST(APPEND SUITESPARSE_LIBRARIES - ${METIS_LIBRARY}) - ENDIF (METIS_FOUND) -ENDIF() - -# Determine if we are running on Ubuntu with the package install of SuiteSparse -# which is broken and does not support linking a shared library. -SET(SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION FALSE) -IF (CMAKE_SYSTEM_NAME MATCHES "Linux" AND - SUITESPARSE_VERSION VERSION_EQUAL 3.4.0) - FIND_PROGRAM(LSB_RELEASE_EXECUTABLE lsb_release) - IF (LSB_RELEASE_EXECUTABLE) - # Any even moderately recent Ubuntu release (likely to be affected by - # this bug) should have lsb_release, if it isn't present we are likely - # on a different Linux distribution (should be fine). - - EXECUTE_PROCESS(COMMAND ${LSB_RELEASE_EXECUTABLE} -si - OUTPUT_VARIABLE LSB_DISTRIBUTOR_ID - OUTPUT_STRIP_TRAILING_WHITESPACE) - - IF (LSB_DISTRIBUTOR_ID MATCHES "Ubuntu" AND - SUITESPARSE_LIBRARIES MATCHES "/usr/lib/libamd") - # We are on Ubuntu, and the SuiteSparse version matches the broken - # system install version and is a system install. - SET(SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION TRUE) - MESSAGE(STATUS "Found system install of SuiteSparse " - "${SUITESPARSE_VERSION} running on Ubuntu, which has a known bug " - "preventing linking of shared libraries (static linking unaffected).") - ENDIF (LSB_DISTRIBUTOR_ID MATCHES "Ubuntu" AND - SUITESPARSE_LIBRARIES MATCHES "/usr/lib/libamd") - ENDIF (LSB_RELEASE_EXECUTABLE) -ENDIF (CMAKE_SYSTEM_NAME MATCHES "Linux" AND - SUITESPARSE_VERSION VERSION_EQUAL 3.4.0) - -# Handle REQUIRED and QUIET arguments to FIND_PACKAGE -INCLUDE(FindPackageHandleStandardArgs) -IF (SUITESPARSE_FOUND) - FIND_PACKAGE_HANDLE_STANDARD_ARGS(SuiteSparse - REQUIRED_VARS ${SUITESPARSE_FOUND_REQUIRED_VARS} - VERSION_VAR SUITESPARSE_VERSION - FAIL_MESSAGE "Failed to find some/all required components of SuiteSparse.") - - IF (SUITESPARSE_FOUND) - list(APPEND MRT_INCLUDE_DIRS ${SUITESPARSE_INCLUDE_DIRS}) - list(APPEND MRT_LIBRARIES ${SUITESPARSE_LIBRARIES}) - ENDIF() -ELSE (SUITESPARSE_FOUND) - # Do not pass VERSION_VAR to FindPackageHandleStandardArgs() if we failed to - # find SuiteSparse to avoid a confusing autogenerated failure message - # that states 'not found (missing: FOO) (found version: x.y.z)'. - FIND_PACKAGE_HANDLE_STANDARD_ARGS(SuiteSparse - REQUIRED_VARS ${SUITESPARSE_FOUND_REQUIRED_VARS} - FAIL_MESSAGE "Failed to find some/all required components of SuiteSparse.") -ENDIF (SUITESPARSE_FOUND) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtTensorflow.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtTensorflow.cmake deleted file mode 100644 index 3600442d570..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtTensorflow.cmake +++ /dev/null @@ -1,30 +0,0 @@ -# try to find tensorflow -find_package(PkgConfig) -find_path(TENSORFLOW_INCLUDE_DIR tensorflow/core/public/session.h - PATH_SUFFIXES tensorflow - ) - -set(TENSORFLOW_INCLUDE_DIR - ${TENSORFLOW_INCLUDE_DIR} - ${TENSORFLOW_INCLUDE_DIR}/src - ) - -find_library(TENSORFLOW_CC_LIBRARY - NAMES tensorflow_cc - ) -find_library(TENSORFLOW_FRAMEWORK_LIBRARY - NAMES tensorflow_framework - ) - -set(TENSORFLOW_LIBRARY ${TENSORFLOW_CC_LIBRARY}) -if(TENSORFLOW_FRAMEWORK_LIBRARY) - set(TENSORFLOW_LIBRARY ${TENSORFLOW_LIBRARY} ${TENSORFLOW_FRAMEWORK_LIBRARY}) -endif(TENSORFLOW_FRAMEWORK_LIBRARY) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(MrtTensorflow DEFAULT_MSG - TENSORFLOW_LIBRARY TENSORFLOW_INCLUDE_DIR) - -mark_as_advanced(TENSORFLOW_LIBRARY TENSORFLOW_INCLUDE_DIR) -set(TENSORFLOW_LIBRARIES ${TENSORFLOW_LIBRARY} ) -set(TENSORFLOW_INCLUDE_DIRS ${TENSORFLOW_INCLUDE_DIR} ) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtTesseract.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtTesseract.cmake deleted file mode 100644 index d03cd6489a5..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtTesseract.cmake +++ /dev/null @@ -1,11 +0,0 @@ -set(PACKAGE_HEADER_FILES tesseract/apitypes.h) -set(PACKAGE_LIBRARIES tesseract) -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/tesseract-3.04.00") -set(PACKAGE_PATH "/mrtsoftware/pkg/tesseract-3.04.00") - -find_path(Tesseract_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES} PATHS "${PACKAGE_LOCAL_PATH}/include" "${PACKAGE_PATH}/include" /usr/local/include /usr/include) -find_library(Tesseract_LIBRARIES NAMES ${PACKAGE_LIBRARIES} PATHS "${PACKAGE_LOCAL_PATH}/lib" "${PACKAGE_PATH}/lib" /usr/local/lib /usr/lib) - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Tesseract FOUND_VAR Tesseract_FOUND REQUIRED_VARS Tesseract_INCLUDE_DIR Tesseract_LIBRARIES) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtVTK.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtVTK.cmake index 0da6b17057d..76ae41b1ad4 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtVTK.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindMrtVTK.cmake @@ -1,20 +1,19 @@ -set(PACKAGE_LOCAL_PATH "/opt/mrtsoftware/local/lib/cmake/vtk-6.3") -set(PACKAGE_PATH "/opt/mrtsoftware/release/lib/cmake/vtk-6.3") - -# old /mrtsoftware style -if (EXISTS ${PACKAGE_LOCAL_PATH}) - set(VTK_DIR ${PACKAGE_LOCAL_PATH}) -elseif(EXISTS ${PACKAGE_PATH}) - set(VTK_DIR ${PACKAGE_PATH}) -endif() - # find package component if(MrtVTK_FIND_REQUIRED) - find_package(VTK REQUIRED) + find_package(VTK REQUIRED) elseif(MrtVTK_FIND_QUIETLY) - find_package(VTK QUIET) + find_package(VTK QUIET) else() - find_package(VTK) + find_package(VTK) endif() +# Wrap all VTK_DEFINITIONS so that they are not used in CUDA code. This will prevent +# warnings generated by nvcc. +set(NEW_VTK_DEFINITION) +foreach(VTK_DEFINITION ${VTK_DEFINITIONS}) + list(APPEND NEW_VTK_DEFINITION "$<$>:${VTK_DEFINITION}>") +endforeach() +set(VTK_DEFINITIONS ${NEW_VTK_DEFINITION}) +unset(NEW_VTK_DEFINITION) + include(${VTK_USE_FILE}) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtbenchmark.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtbenchmark.cmake deleted file mode 100644 index 7423eda0548..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtbenchmark.cmake +++ /dev/null @@ -1,11 +0,0 @@ -# we need this only because mrt_cmake_modules corrently does not support importing targets -# find package component -if(MrtOpenCV_FIND_REQUIRED) - find_package(benchmark REQUIRED) -elseif(MrtOpenCV_FIND_QUIETLY) - find_package(benchmark QUIET) -else() - find_package(benchmark) -endif() - -set(benchmark_LIBRARIES benchmark::benchmark) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtf2c.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtf2c.cmake deleted file mode 100644 index a2c60ddf310..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtf2c.cmake +++ /dev/null @@ -1,15 +0,0 @@ -################################################################################################################ -#Use this block, if you have to write your own cmake find script. -#Add the header files and libraries files which are search for and adjust the -#paths as needed. -set(PACKAGE_HEADER_FILES "f2c.h") -set(PACKAGE_LIBRARIES "libf2c.a") -set(PACKAGE_LOCAL_PATH "/mrtsoftware/pkg/local/ftwoc-2.0") -set(PACKAGE_PATH "/mrtsoftware/pkg/ftwoc-2.0") - -find_path(f2c_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES} PATHS "${PACKAGE_LOCAL_PATH}/include" "${PACKAGE_PATH}/include") -find_library(f2c_LIBRARIES NAMES ${PACKAGE_LIBRARIES} PATHS "${PACKAGE_LOCAL_PATH}/lib" "${PACKAGE_PATH}/lib") - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(f2c FOUND_VAR f2c_FOUND REQUIRED_VARS f2c_INCLUDE_DIR f2c_LIBRARIES) - diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtnlopt.cmake b/mrt_cmake_modules/cmake/Modules/FindMrtnlopt.cmake deleted file mode 100644 index 79500102867..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindMrtnlopt.cmake +++ /dev/null @@ -1,33 +0,0 @@ - -# - Find NLopt -# Find the native NLopt includes and library -# -# nlopt_INCLUDE_DIR - where to find nlopt.h, etc. -# nlopt_LIBRARIES - List of libraries when using nlopt. -# nlopt_FOUND - True if nlopt found. - - -IF (nlopt_INCLUDE_DIR) - # Already in cache, be silent - SET (nlopt_FIND_QUIETLY TRUE) -ENDIF (nlopt_INCLUDE_DIR) - -FIND_PATH(nlopt_INCLUDE_DIR nlopt.h) - -SET (nlopt_NAMES nlopt nlopt_cxx) -FIND_LIBRARY (nlopt_LIBRARY NAMES ${nlopt_NAMES}) - -# handle the QUIETLY and REQUIRED arguments and set nlopt_FOUND to TRUE if -# all listed variables are TRUE -INCLUDE (FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS (nlopt DEFAULT_MSG - nlopt_LIBRARY - nlopt_INCLUDE_DIR) - -IF(nlopt_FOUND) - SET (nlopt_LIBRARIES ${nlopt_LIBRARY}) -ELSE (nlopt_FOUND) - SET (nlopt_LIBRARIES) -ENDIF (nlopt_FOUND) - -MARK_AS_ADVANCED (nlopt_LIBRARY nlopt_INCLUDE_DIR) diff --git a/mrt_cmake_modules/cmake/Modules/FindOSG.cmake b/mrt_cmake_modules/cmake/Modules/FindOSG.cmake deleted file mode 100644 index c1a1b6bbeb0..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindOSG.cmake +++ /dev/null @@ -1,274 +0,0 @@ -# - Find OpenSceneGraph -# This module searches for the OpenSceneGraph core "osg" library as well as -# OpenThreads, and whatever additional COMPONENTS (nodekits) that you specify. -# See http://www.openscenegraph.org -# -# NOTE: To use this module effectively you must either require CMake >= 2.6.3 -# with cmake_minimum_required(VERSION 2.6.3) or download and place -# FindOpenThreads.cmake, Findosg_functions.cmake, Findosg.cmake, -# and Find.cmake files into your CMAKE_MODULE_PATH. -# -#================================== -# -# This module accepts the following variables (note mixed case) -# -# OpenSceneGraph_DEBUG - Enable debugging output -# -# OpenSceneGraph_MARK_AS_ADVANCED - Mark cache variables as advanced -# automatically -# -# The following environment variables are also respected for finding the OSG -# and it's various components. CMAKE_PREFIX_PATH can also be used for this -# (see find_library() CMake documentation). -# -# _DIR (where MODULE is of the form "OSGVOLUME" and there is a FindosgVolume.cmake file) -# OSG_DIR -# OSGDIR -# OSG_ROOT -# -# This module defines the following output variables: -# -# OPENSCENEGRAPH_FOUND - Was the OSG and all of the specified components found? -# -# OPENSCENEGRAPH_VERSION - The version of the OSG which was found -# -# OPENSCENEGRAPH_INCLUDE_DIRS - Where to find the headers -# -# OPENSCENEGRAPH_LIBRARIES - The OSG libraries -# -#================================== -# Example Usage: -# -# find_package(OpenSceneGraph 2.0.0 REQUIRED osgDB osgUtil) -# # libOpenThreads & libosg automatically searched -# include_directories(${OPENSCENEGRAPH_INCLUDE_DIRS}) -# -# add_executable(foo foo.cc) -# target_link_libraries(foo ${OPENSCENEGRAPH_LIBRARIES}) -# - -#============================================================================= -# Copyright 2009 Kitware, Inc. -# Copyright 2009 Philip Lowman -# -# Distributed under the OSI-approved BSD License (the "License"); -# see below. -# -# This software is distributed WITHOUT ANY WARRANTY; without even the -# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. -# See the License for more information. -#============================================================================= -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# * Neither the names of Kitware, Inc., the Insight Software Consortium, -# nor the names of their contributors may be used to endorse or promote -# products derived from this software without specific prior written -# permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR -# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT -# HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT -# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, -# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY -# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -#============================================================================= - -# -# Naming convention: -# Local variables of the form _osg_foo -# Input variables of the form OpenSceneGraph_FOO -# Output variables of the form OPENSCENEGRAPH_FOO -# - -include(Findosg_functions) - -set(_osg_modules_to_process) -foreach(_osg_component ${OpenSceneGraph_FIND_COMPONENTS}) - list(APPEND _osg_modules_to_process ${_osg_component}) -endforeach() -list(APPEND _osg_modules_to_process "osg" "OpenThreads") -list(REMOVE_DUPLICATES _osg_modules_to_process) - -if(OpenSceneGraph_DEBUG) - message("[ FindOpenSceneGraph.cmake:${CMAKE_CURRENT_LIST_LINE} ] " - "Components = ${_osg_modules_to_process}") -endif() - -# -# First we need to find and parse osg/Version -# -OSG_FIND_PATH(OSG osg/Version) -if(OpenSceneGraph_MARK_AS_ADVANCED) - OSG_MARK_AS_ADVANCED(OSG) -endif() - -# Try to ascertain the version... -if(OSG_INCLUDE_DIR) - if(OpenSceneGraph_DEBUG) - message("[ FindOpenSceneGraph.cmake:${CMAKE_CURRENT_LIST_LINE} ] " - "Detected OSG_INCLUDE_DIR = ${OSG_INCLUDE_DIR}") - endif() - - set(_osg_Version_file "${OSG_INCLUDE_DIR}/osg/Version") - if("${OSG_INCLUDE_DIR}" MATCHES "\\.framework$" AND NOT EXISTS "${_osg_Version_file}") - set(_osg_Version_file "${OSG_INCLUDE_DIR}/Headers/Version") - endif() - - if(EXISTS "${_osg_Version_file}") - file(READ "${_osg_Version_file}" _osg_Version_contents) - else() - set(_osg_Version_contents "unknown") - endif() - - string(REGEX MATCH ".*#define OSG_VERSION_MAJOR[ \t]+[0-9]+.*" - _osg_old_defines "${_osg_Version_contents}") - string(REGEX MATCH ".*#define OPENSCENEGRAPH_MAJOR_VERSION[ \t]+[0-9]+.*" - _osg_new_defines "${_osg_Version_contents}") - if(_osg_old_defines) - string(REGEX REPLACE ".*#define OSG_VERSION_MAJOR[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_MAJOR ${_osg_Version_contents}) - string(REGEX REPLACE ".*#define OSG_VERSION_MINOR[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_MINOR ${_osg_Version_contents}) - string(REGEX REPLACE ".*#define OSG_VERSION_PATCH[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_PATCH ${_osg_Version_contents}) - elseif(_osg_new_defines) - string(REGEX REPLACE ".*#define OPENSCENEGRAPH_MAJOR_VERSION[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_MAJOR ${_osg_Version_contents}) - string(REGEX REPLACE ".*#define OPENSCENEGRAPH_MINOR_VERSION[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_MINOR ${_osg_Version_contents}) - string(REGEX REPLACE ".*#define OPENSCENEGRAPH_PATCH_VERSION[ \t]+([0-9]+).*" - "\\1" _osg_VERSION_PATCH ${_osg_Version_contents}) - else() - message("[ FindOpenSceneGraph.cmake:${CMAKE_CURRENT_LIST_LINE} ] " - "Failed to parse version number, please report this as a bug") - endif() - - set(OPENSCENEGRAPH_VERSION "${_osg_VERSION_MAJOR}.${_osg_VERSION_MINOR}.${_osg_VERSION_PATCH}" - CACHE INTERNAL "The version of OSG which was detected") - if(OpenSceneGraph_DEBUG) - message("[ FindOpenSceneGraph.cmake:${CMAKE_CURRENT_LIST_LINE} ] " - "Detected version ${OPENSCENEGRAPH_VERSION}") - endif() -endif() - -# -# Version checking -# -if(OpenSceneGraph_FIND_VERSION AND OPENSCENEGRAPH_VERSION) - if(OpenSceneGraph_FIND_VERSION_EXACT) - if(NOT OPENSCENEGRAPH_VERSION VERSION_EQUAL ${OpenSceneGraph_FIND_VERSION}) - set(_osg_version_not_exact TRUE) - endif() - else() - # version is too low - if(NOT OPENSCENEGRAPH_VERSION VERSION_EQUAL ${OpenSceneGraph_FIND_VERSION} AND - NOT OPENSCENEGRAPH_VERSION VERSION_GREATER ${OpenSceneGraph_FIND_VERSION}) - set(_osg_version_not_high_enough TRUE) - endif() - endif() -endif() - -set(_osg_quiet) -if(OpenSceneGraph_FIND_QUIETLY) - set(_osg_quiet "QUIET") -endif() -# -# Here we call FIND_PACKAGE() on all of the components -# -foreach(_osg_module ${_osg_modules_to_process}) - if(OpenSceneGraph_DEBUG) - message("[ FindOpenSceneGraph.cmake:${CMAKE_CURRENT_LIST_LINE} ] " - "Calling find_package(${_osg_module} ${_osg_required} ${_osg_quiet})") - endif() - find_package(${_osg_module} ${_osg_quiet}) - - string(TOUPPER ${_osg_module} _osg_module_UC) - list(APPEND OPENSCENEGRAPH_INCLUDE_DIR ${${_osg_module_UC}_INCLUDE_DIR}) - list(APPEND OPENSCENEGRAPH_LIBRARIES ${${_osg_module_UC}_LIBRARIES}) - - if(OpenSceneGraph_MARK_AS_ADVANCED) - OSG_MARK_AS_ADVANCED(${_osg_module}) - endif() -endforeach() - -if(OPENSCENEGRAPH_INCLUDE_DIR) - list(REMOVE_DUPLICATES OPENSCENEGRAPH_INCLUDE_DIR) -endif() - -# -# Inform the users with an error message based on -# what version they have vs. what version was -# required. -# -if(OpenSceneGraph_FIND_REQUIRED) - set(_osg_version_output_type FATAL_ERROR) -else() - set(_osg_version_output_type STATUS) -endif() -if(_osg_version_not_high_enough) - set(_osg_EPIC_FAIL TRUE) - if(NOT OpenSceneGraph_FIND_QUIETLY) - message(${_osg_version_output_type} - "ERROR: Version ${OpenSceneGraph_FIND_VERSION} or higher of the OSG " - "is required. Version ${OPENSCENEGRAPH_VERSION} was found.") - endif() -elseif(_osg_version_not_exact) - set(_osg_EPIC_FAIL TRUE) - if(NOT OpenSceneGraph_FIND_QUIETLY) - message(${_osg_version_output_type} - "ERROR: Version ${OpenSceneGraph_FIND_VERSION} of the OSG is required " - "(exactly), version ${OPENSCENEGRAPH_VERSION} was found.") - endif() -else() - - # - # Check each module to see if it's found - # - if(OpenSceneGraph_FIND_REQUIRED) - set(_osg_missing_message) - foreach(_osg_module ${_osg_modules_to_process}) - string(TOUPPER ${_osg_module} _osg_module_UC) - if(NOT ${_osg_module_UC}_FOUND) - set(_osg_missing_nodekit_fail true) - set(_osg_missing_message "${_osg_missing_message} ${_osg_module}") - endif() - endforeach() - - if(_osg_missing_nodekit_fail) - message(FATAL_ERROR "ERROR: Missing the following osg " - "libraries: ${_osg_missing_message}.\n" - "Consider using CMAKE_PREFIX_PATH or the OSG_DIR " - "environment variable. See the " - "${CMAKE_CURRENT_LIST_FILE} for more details.") - endif() - endif() - - include(FindPackageHandleStandardArgs) - FIND_PACKAGE_HANDLE_STANDARD_ARGS(OpenSceneGraph DEFAULT_MSG OPENSCENEGRAPH_LIBRARIES OPENSCENEGRAPH_INCLUDE_DIR) -endif() - -if(_osg_EPIC_FAIL) - # Zero out everything, we didn't meet version requirements - set(OPENSCENEGRAPH_FOUND FALSE) - set(OPENSCENEGRAPH_LIBRARIES) - set(OPENSCENEGRAPH_INCLUDE_DIR) -endif() - -set(OPENSCENEGRAPH_INCLUDE_DIRS ${OPENSCENEGRAPH_INCLUDE_DIR}) - - diff --git a/mrt_cmake_modules/cmake/Modules/FindPCAP.cmake b/mrt_cmake_modules/cmake/Modules/FindPCAP.cmake deleted file mode 100644 index e5049bfb36f..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindPCAP.cmake +++ /dev/null @@ -1,74 +0,0 @@ -# - Try to find libpcap include dirs and libraries -# -# Usage of this module as follows: -# -# find_package(PCAP) -# -# Variables used by this module, they can change the default behaviour and need -# to be set before calling find_package: -# -# PCAP_ROOT_DIR Set this variable to the root installation of -# libpcap if the module has problems finding the -# proper installation path. -# -# Variables defined by this module: -# -# PCAP_FOUND System has libpcap, include and library dirs found -# PCAP_INCLUDE_DIR The libpcap include directories. -# PCAP_LIBRARY The libpcap library (possibly includes a thread -# library e.g. required by pf_ring's libpcap) -# HAVE_PF_RING If a found version of libpcap supports PF_RING - -find_path(PCAP_ROOT_DIR - NAMES include/pcap.h -) - -find_path(PCAP_INCLUDE_DIR - NAMES pcap.h - HINTS ${PCAP_ROOT_DIR}/include -) - -find_library(PCAP_LIBRARY - NAMES pcap - HINTS ${PCAP_ROOT_DIR}/lib -) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(PCAP DEFAULT_MSG - PCAP_LIBRARY - PCAP_INCLUDE_DIR -) - -include(CheckCSourceCompiles) -set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY}) -check_c_source_compiles("int main() { return 0; }" PCAP_LINKS_SOLO) -set(CMAKE_REQUIRED_LIBRARIES) - -# check if linking against libpcap also needs to link against a thread library -if (NOT PCAP_LINKS_SOLO) - find_package(Threads) - if (THREADS_FOUND) - set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY} ${CMAKE_THREAD_LIBS_INIT}) - check_c_source_compiles("int main() { return 0; }" PCAP_NEEDS_THREADS) - set(CMAKE_REQUIRED_LIBRARIES) - endif () - if (THREADS_FOUND AND PCAP_NEEDS_THREADS) - set(_tmp ${PCAP_LIBRARY} ${CMAKE_THREAD_LIBS_INIT}) - list(REMOVE_DUPLICATES _tmp) - set(PCAP_LIBRARY ${_tmp} - CACHE STRING "Libraries needed to link against libpcap" FORCE) - else () - message(FATAL_ERROR "Couldn't determine how to link against libpcap") - endif () -endif () - -include(CheckFunctionExists) -set(CMAKE_REQUIRED_LIBRARIES ${PCAP_LIBRARY}) -check_function_exists(pcap_get_pfring_id HAVE_PF_RING) -set(CMAKE_REQUIRED_LIBRARIES) - -mark_as_advanced( - PCAP_ROOT_DIR - PCAP_INCLUDE_DIR - PCAP_LIBRARY -) diff --git a/mrt_cmake_modules/cmake/Modules/FindPNG++.cmake b/mrt_cmake_modules/cmake/Modules/FindPNG++.cmake index 67e83466cc2..dd09d832d1b 100644 --- a/mrt_cmake_modules/cmake/Modules/FindPNG++.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindPNG++.cmake @@ -1,4 +1,4 @@ -# - Find the PNG++ includes +# - Find the PNG++ includes # # This module searches libpng++, the library for working with PNG images. # @@ -24,26 +24,23 @@ # License text for the above reference.) if(PNG_FIND_QUIETLY) - set(_FIND_ZLIB_ARG QUIET) + set(_FIND_ZLIB_ARG QUIET) endif() find_package(ZLIB ${_FIND_ZLIB_ARG}) +find_package(PNG REQUIRED) if(ZLIB_FOUND) - find_path( - PNG++_INCLUDE_DIR - png.hpp - /usr/local/include/png++ - /usr/include/png++ - ) - if (PNG++_INCLUDE_DIR) - set(PNG++_INCLUDE_DIRS ${PNG++_INCLUDE_DIR} ${ZLIB_INCLUDE_DIR} ) - unset(PNG++_INCLUDE_DIR) - endif () + find_path(PNG++_INCLUDE_DIR png.hpp /usr/local/include/png++ /usr/include/png++) + + set(PNG++_LIBRARIES ${PNG_LIBRARIES}) + + if(PNG++_INCLUDE_DIR) + set(PNG++_INCLUDE_DIRS ${PNG++_INCLUDE_DIR} ${ZLIB_INCLUDE_DIR}) + unset(PNG++_INCLUDE_DIR) + endif() endif() # handle the QUIETLY and REQUIRED arguments and set PNG_FOUND to TRUE if include(FindPackageHandleStandardArgs) find_package_handle_standard_args(PNG++ REQUIRED_VARS PNG++_INCLUDE_DIRS) mark_as_advanced(PNG++_INCLUDE_DIRS) - - diff --git a/mrt_cmake_modules/cmake/Modules/FindPoco.cmake b/mrt_cmake_modules/cmake/Modules/FindPoco.cmake deleted file mode 100644 index f39f704acdc..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindPoco.cmake +++ /dev/null @@ -1,63 +0,0 @@ -# CMake find script for Poco C++ library -# Adapted from: https://github.com/astahl/poco-cmake/blob/master/cmake/FindPoco.cmake -# -# The following components are available: -# --------------------------------------- -# Util (loaded by default) -# Foundation (loaded by default) -# XML -# Zip -# Crypto -# Data -# Net -# NetSSL_OpenSSL -# OSP -# -# Usage: -# find_package(Poco REQUIRED OSP Data Crypto) -# -# On completion, the script defines the following variables: -# -# - Compound variables: -# Poco_FOUND -# - true if all requested components were found. -# Poco_LIBRARIES -# - contains release (and debug if available) libraries for all requested components. -# It has the form "optimized LIB1 debug LIBd1 optimized LIB2 ...", ready for use with the target_link_libraries command. -# Poco_INCLUDE_DIRS -# - Contains include directories for all requested components. - -find_path(Poco_INCLUDE_DIRS NAMES Poco/Poco.h PATHS /usr/include) - -# append the default minimum components to the list to find -list(APPEND components - ${Poco_FIND_COMPONENTS} - Util - Foundation -) -list(REMOVE_DUPLICATES components) - -set(search_for_debug false) -if (${CMAKE_BUILD_TYPE} MATCHES [d|D][e|E][b|B][u|U][g|G]) - set(search_for_debug true) -endif () - -set(Poco_LIBRARIES "") -set(Poco_LIBRARY_VAR_NAMES "") -# iterate the components -foreach(component ${components}) - # release library - if (${search_for_debug}) - find_library(Poco_${component}_library NAMES Poco${component}d PATHS /usr/lib) - else() - find_library(Poco_${component}_library NAMES Poco${component} PATHS /usr/lib) - endif() - list(APPEND Poco_LIBRARIES ${Poco_${component}_library}) - list(APPEND Poco_LIBRARY_VAR_NAMES Poco_${component}_library) -endforeach() - -include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(Poco FOUND_VAR Poco_FOUND REQUIRED_VARS Poco_INCLUDE_DIRS ${POCO_LIBRARY_VAR_NAMES}) -mark_as_advanced(${Poco_LIBRARY_VAR_NAMES}) - - diff --git a/mrt_cmake_modules/cmake/Modules/FindQwt.cmake b/mrt_cmake_modules/cmake/Modules/FindQwt.cmake deleted file mode 100644 index 0f9bbc33898..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindQwt.cmake +++ /dev/null @@ -1,118 +0,0 @@ -# Qt Widgets for Technical Applications -# available at http://www.http://qwt.sourceforge.net/ -# -# The module defines the following variables: -# QWT_FOUND - the system has Qwt -# QWT_INCLUDE_DIR - where to find qwt_plot.h -# QWT_INCLUDE_DIRS - qwt includes -# QWT_LIBRARY - where to find the Qwt library -# QWT_LIBRARIES - aditional libraries -# QWT_MAJOR_VERSION - major version -# QWT_MINOR_VERSION - minor version -# QWT_PATCH_VERSION - patch version -# QWT_VERSION_STRING - version (ex. 5.2.1) -# QWT_ROOT_DIR - root dir (ex. /usr/local) - -#============================================================================= -# Copyright 2010-2013, Julien Schueller -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, this -# list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR -# ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -# (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND -# ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -# The views and conclusions contained in the software and documentation are those -# of the authors and should not be interpreted as representing official policies, -# either expressed or implied, of the FreeBSD Project. -#============================================================================= - - -find_path ( QWT_INCLUDE_DIR - NAMES qwt_plot.h - HINTS ${QT_INCLUDE_DIR} - PATH_SUFFIXES qwt qwt-qt3 qwt-qt4 qwt-qt5 -) - -set ( QWT_INCLUDE_DIRS ${QWT_INCLUDE_DIR} ) - -# version -set ( _VERSION_FILE ${QWT_INCLUDE_DIR}/qwt_global.h ) -if ( EXISTS ${_VERSION_FILE} ) - file ( STRINGS ${_VERSION_FILE} _VERSION_LINE REGEX "define[ ]+QWT_VERSION_STR" ) - if ( _VERSION_LINE ) - string ( REGEX REPLACE ".*define[ ]+QWT_VERSION_STR[ ]+\"(.*)\".*" "\\1" QWT_VERSION_STRING "${_VERSION_LINE}" ) - string ( REGEX REPLACE "([0-9]+)\\.([0-9]+)\\.([0-9]+)" "\\1" QWT_MAJOR_VERSION "${QWT_VERSION_STRING}" ) - string ( REGEX REPLACE "([0-9]+)\\.([0-9]+)\\.([0-9]+)" "\\2" QWT_MINOR_VERSION "${QWT_VERSION_STRING}" ) - string ( REGEX REPLACE "([0-9]+)\\.([0-9]+)\\.([0-9]+)" "\\3" QWT_PATCH_VERSION "${QWT_VERSION_STRING}" ) - endif () -endif () - - -# check version -set ( _QWT_VERSION_MATCH TRUE ) -if ( Qwt_FIND_VERSION AND QWT_VERSION_STRING ) - if ( Qwt_FIND_VERSION_EXACT ) - if ( NOT Qwt_FIND_VERSION VERSION_EQUAL QWT_VERSION_STRING ) - set ( _QWT_VERSION_MATCH FALSE ) - endif () - else () - if ( QWT_VERSION_STRING VERSION_LESS Qwt_FIND_VERSION ) - set ( _QWT_VERSION_MATCH FALSE ) - endif () - endif () -endif () - - -find_library ( QWT_LIBRARY - NAMES qwt qwt-qt3 qwt-qt4 qwt-qt5 - HINTS ${QT_LIBRARY_DIR} -) - -set ( QWT_LIBRARIES ${QWT_LIBRARY} ) - - -# try to guess root dir from include dir -if ( QWT_INCLUDE_DIR ) - string ( REGEX REPLACE "(.*)/include.*" "\\1" QWT_ROOT_DIR ${QWT_INCLUDE_DIR} ) -# try to guess root dir from library dir -elseif ( QWT_LIBRARY ) - string ( REGEX REPLACE "(.*)/lib[/|32|64].*" "\\1" QWT_ROOT_DIR ${QWT_LIBRARY} ) -endif () - - -# handle the QUIETLY and REQUIRED arguments -include ( FindPackageHandleStandardArgs ) -if ( CMAKE_VERSION LESS 2.8.3 ) - find_package_handle_standard_args( Qwt DEFAULT_MSG QWT_LIBRARY QWT_INCLUDE_DIR _QWT_VERSION_MATCH ) -else () - find_package_handle_standard_args( Qwt REQUIRED_VARS QWT_LIBRARY QWT_INCLUDE_DIR _QWT_VERSION_MATCH VERSION_VAR QWT_VERSION_STRING ) -endif () - - -mark_as_advanced ( - QWT_LIBRARY - QWT_LIBRARIES - QWT_INCLUDE_DIR - QWT_INCLUDE_DIRS - QWT_MAJOR_VERSION - QWT_MINOR_VERSION - QWT_PATCH_VERSION - QWT_VERSION_STRING - QWT_ROOT_DIR -) diff --git a/mrt_cmake_modules/cmake/Modules/FindRapidXML.cmake b/mrt_cmake_modules/cmake/Modules/FindRapidXML.cmake deleted file mode 100644 index 2bafa74c991..00000000000 --- a/mrt_cmake_modules/cmake/Modules/FindRapidXML.cmake +++ /dev/null @@ -1,36 +0,0 @@ -# This script locates the RapidXML library -# ------------------------------------ -# -# usage: -# find_package(RAPIDXML ...) -# -# searches in RAPIDXML_ROOT and usual locations -# -# Sets RAPIDXML_DIR - -# find the tinyxml directory find the SFML include directory -find_path(RAPIDXML_DIR rapidxml.hpp - PATH_SUFFIXES include - PATHS - ${RapidXML_ROOT} - $ENV{RapidXML_ROOT} - ~/Library/Frameworks - /Library/Frameworks - /usr/local/ - /usr/ - /sw # Fink - /opt/local/ # DarwinPorts - /opt/csw/ # Blastwave - /opt/) - -if (NOT RAPIDXML_DIR) - if(RapidXML_FIND_REQUIRED) #prefix is filename, case matters - message(FATAL_ERROR "Could not find RapidXML!") - elseif(NOT RapidXML_FIND_QUIETLY) - message("Could not find RapidXML!") - endif(RapidXML_FIND_REQUIRED) -endif(NOT RAPIDXML_DIR) - -if (NOT RapidXML_FIND_QUIETLY) - message("Found RapidXML: ${RAPIDXML_DIR}") -endif (NOT RapidXML_FIND_QUIETLY) diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtSDL2.cmake b/mrt_cmake_modules/cmake/Modules/FindSDL2.cmake similarity index 52% rename from mrt_cmake_modules/cmake/Modules/FindMrtSDL2.cmake rename to mrt_cmake_modules/cmake/Modules/FindSDL2.cmake index 2ec81e6f08d..45e64f47075 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtSDL2.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindSDL2.cmake @@ -78,33 +78,32 @@ # because not all systems place things in SDL/ (see FreeBSD). if(NOT SDL2_DIR) - set(SDL2_DIR "" CACHE PATH "SDL2 directory") + set(SDL2_DIR + "" + CACHE PATH "SDL2 directory") endif() -find_path(SDL2_INCLUDE_DIR SDL.h - HINTS - ENV SDLDIR - ${SDL2_DIR} - PATH_SUFFIXES SDL2 - # path suffixes to search inside ENV{SDLDIR} - include/SDL2 include -) +find_path( + SDL2_INCLUDE_DIR SDL.h + HINTS ENV SDLDIR ${SDL2_DIR} + PATH_SUFFIXES + SDL2 + # path suffixes to search inside ENV{SDLDIR} + include/SDL2 include) if(CMAKE_SIZEOF_VOID_P EQUAL 8) - set(VC_LIB_PATH_SUFFIX lib/x64) + set(VC_LIB_PATH_SUFFIX lib/x64) else() - set(VC_LIB_PATH_SUFFIX lib/x86) + set(VC_LIB_PATH_SUFFIX lib/x86) endif() # SDL-1.1 is the name used by FreeBSD ports... # don't confuse it for the version number. -find_library(SDL2_LIBRARY_TEMP - NAMES SDL2 - HINTS - ENV SDLDIR - ${SDL2_DIR} - PATH_SUFFIXES lib ${VC_LIB_PATH_SUFFIX} -) +find_library( + SDL2_LIBRARY_TEMP + NAMES SDL2 + HINTS ENV SDLDIR ${SDL2_DIR} + PATH_SUFFIXES lib ${VC_LIB_PATH_SUFFIX}) # Hide this cache variable from the user, it's an internal implementation # detail. The documented library variable for the user is SDL2_LIBRARY @@ -112,24 +111,18 @@ find_library(SDL2_LIBRARY_TEMP set_property(CACHE SDL2_LIBRARY_TEMP PROPERTY TYPE INTERNAL) if(NOT SDL2_BUILDING_LIBRARY) - if(NOT SDL2_INCLUDE_DIR MATCHES ".framework") - # Non-OS X framework versions expect you to also dynamically link to - # SDLmain. This is mainly for Windows and OS X. Other (Unix) platforms - # seem to provide SDLmain for compatibility even though they don't - # necessarily need it. - find_library(SDL2MAIN_LIBRARY - NAMES SDL2main - HINTS - ENV SDLDIR - ${SDL2_DIR} - PATH_SUFFIXES lib ${VC_LIB_PATH_SUFFIX} - PATHS - /sw - /opt/local - /opt/csw - /opt - ) - endif() + if(NOT SDL2_INCLUDE_DIR MATCHES ".framework") + # Non-OS X framework versions expect you to also dynamically link to + # SDLmain. This is mainly for Windows and OS X. Other (Unix) platforms + # seem to provide SDLmain for compatibility even though they don't + # necessarily need it. + find_library( + SDL2MAIN_LIBRARY + NAMES SDL2main + HINTS ENV SDLDIR ${SDL2_DIR} + PATH_SUFFIXES lib ${VC_LIB_PATH_SUFFIX} + PATHS /sw /opt/local /opt/csw /opt) + endif() endif() # SDL may require threads on your system. @@ -137,74 +130,83 @@ endif() # frameworks may already provide it. # But for non-OSX systems, I will use the CMake Threads package. if(NOT APPLE) - find_package(Threads) + find_package(Threads) endif() # MinGW needs an additional link flag, -mwindows # It's total link flags should look like -lmingw32 -lSDLmain -lSDL -mwindows if(MINGW) - set(MINGW32_LIBRARY mingw32 "-mwindows" CACHE STRING "link flags for MinGW") + set(MINGW32_LIBRARY + mingw32 "-mwindows" + CACHE STRING "link flags for MinGW") endif() if(SDL2_LIBRARY_TEMP) - # For SDLmain - if(SDL2MAIN_LIBRARY AND NOT SDL2_BUILDING_LIBRARY) - list(FIND SDL2_LIBRARY_TEMP "${SDL2MAIN_LIBRARY}" _SDL2_MAIN_INDEX) - if(_SDL2_MAIN_INDEX EQUAL -1) - set(SDL2_LIBRARY_TEMP "${SDL2MAIN_LIBRARY}" ${SDL2_LIBRARY_TEMP}) + # For SDLmain + if(SDL2MAIN_LIBRARY AND NOT SDL2_BUILDING_LIBRARY) + list(FIND SDL2_LIBRARY_TEMP "${SDL2MAIN_LIBRARY}" _SDL2_MAIN_INDEX) + if(_SDL2_MAIN_INDEX EQUAL -1) + set(SDL2_LIBRARY_TEMP "${SDL2MAIN_LIBRARY}" ${SDL2_LIBRARY_TEMP}) + endif() + unset(_SDL2_MAIN_INDEX) + endif() + + # For OS X, SDL uses Cocoa as a backend so it must link to Cocoa. + # CMake doesn't display the -framework Cocoa string in the UI even + # though it actually is there if I modify a pre-used variable. + # I think it has something to do with the CACHE STRING. + # So I use a temporary variable until the end so I can set the + # "real" variable in one-shot. + if(APPLE) + set(SDL2_LIBRARY_TEMP ${SDL2_LIBRARY_TEMP} "-framework Cocoa") + endif() + + # For threads, as mentioned Apple doesn't need this. + # In fact, there seems to be a problem if I used the Threads package + # and try using this line, so I'm just skipping it entirely for OS X. + if(NOT APPLE) + set(SDL2_LIBRARY_TEMP ${SDL2_LIBRARY_TEMP} ${CMAKE_THREAD_LIBS_INIT}) endif() - unset(_SDL2_MAIN_INDEX) - endif() - - # For OS X, SDL uses Cocoa as a backend so it must link to Cocoa. - # CMake doesn't display the -framework Cocoa string in the UI even - # though it actually is there if I modify a pre-used variable. - # I think it has something to do with the CACHE STRING. - # So I use a temporary variable until the end so I can set the - # "real" variable in one-shot. - if(APPLE) - set(SDL2_LIBRARY_TEMP ${SDL2_LIBRARY_TEMP} "-framework Cocoa") - endif() - - # For threads, as mentioned Apple doesn't need this. - # In fact, there seems to be a problem if I used the Threads package - # and try using this line, so I'm just skipping it entirely for OS X. - if(NOT APPLE) - set(SDL2_LIBRARY_TEMP ${SDL2_LIBRARY_TEMP} ${CMAKE_THREAD_LIBS_INIT}) - endif() - - # For MinGW library - if(MINGW) - set(SDL2_LIBRARY_TEMP ${MINGW32_LIBRARY} ${SDL2_LIBRARY_TEMP}) - endif() - - # Set the final string here so the GUI reflects the final state. - set(SDL2_LIBRARY ${SDL2_LIBRARY_TEMP} CACHE STRING "Where the SDL Library can be found") + + # For MinGW library + if(MINGW) + set(SDL2_LIBRARY_TEMP ${MINGW32_LIBRARY} ${SDL2_LIBRARY_TEMP}) + endif() + + # Set the final string here so the GUI reflects the final state. + set(SDL2_LIBRARY + ${SDL2_LIBRARY_TEMP} + CACHE STRING "Where the SDL Library can be found") endif() if(SDL2_INCLUDE_DIR AND EXISTS "${SDL2_INCLUDE_DIR}/SDL2_version.h") - file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_MAJOR_LINE REGEX "^#define[ \t]+SDL2_MAJOR_VERSION[ \t]+[0-9]+$") - file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_MINOR_LINE REGEX "^#define[ \t]+SDL2_MINOR_VERSION[ \t]+[0-9]+$") - file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_PATCH_LINE REGEX "^#define[ \t]+SDL2_PATCHLEVEL[ \t]+[0-9]+$") - string(REGEX REPLACE "^#define[ \t]+SDL2_MAJOR_VERSION[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_MAJOR "${SDL2_VERSION_MAJOR_LINE}") - string(REGEX REPLACE "^#define[ \t]+SDL2_MINOR_VERSION[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_MINOR "${SDL2_VERSION_MINOR_LINE}") - string(REGEX REPLACE "^#define[ \t]+SDL2_PATCHLEVEL[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_PATCH "${SDL2_VERSION_PATCH_LINE}") - set(SDL2_VERSION_STRING ${SDL2_VERSION_MAJOR}.${SDL2_VERSION_MINOR}.${SDL2_VERSION_PATCH}) - unset(SDL2_VERSION_MAJOR_LINE) - unset(SDL2_VERSION_MINOR_LINE) - unset(SDL2_VERSION_PATCH_LINE) - unset(SDL2_VERSION_MAJOR) - unset(SDL2_VERSION_MINOR) - unset(SDL2_VERSION_PATCH) + file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_MAJOR_LINE + REGEX "^#define[ \t]+SDL2_MAJOR_VERSION[ \t]+[0-9]+$") + file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_MINOR_LINE + REGEX "^#define[ \t]+SDL2_MINOR_VERSION[ \t]+[0-9]+$") + file(STRINGS "${SDL2_INCLUDE_DIR}/SDL2_version.h" SDL2_VERSION_PATCH_LINE + REGEX "^#define[ \t]+SDL2_PATCHLEVEL[ \t]+[0-9]+$") + string(REGEX REPLACE "^#define[ \t]+SDL2_MAJOR_VERSION[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_MAJOR + "${SDL2_VERSION_MAJOR_LINE}") + string(REGEX REPLACE "^#define[ \t]+SDL2_MINOR_VERSION[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_MINOR + "${SDL2_VERSION_MINOR_LINE}") + string(REGEX REPLACE "^#define[ \t]+SDL2_PATCHLEVEL[ \t]+([0-9]+)$" "\\1" SDL2_VERSION_PATCH + "${SDL2_VERSION_PATCH_LINE}") + set(SDL2_VERSION_STRING ${SDL2_VERSION_MAJOR}.${SDL2_VERSION_MINOR}.${SDL2_VERSION_PATCH}) + unset(SDL2_VERSION_MAJOR_LINE) + unset(SDL2_VERSION_MINOR_LINE) + unset(SDL2_VERSION_PATCH_LINE) + unset(SDL2_VERSION_MAJOR) + unset(SDL2_VERSION_MINOR) + unset(SDL2_VERSION_PATCH) endif() set(SDL2_LIBRARIES ${SDL2_LIBRARY}) set(SDL2_INCLUDE_DIRS ${SDL2_INCLUDE_DIR}) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(SDL - REQUIRED_VARS SDL2_LIBRARIES SDL2_INCLUDE_DIRS - VERSION_VAR SDL2_VERSION_STRING) +find_package_handle_standard_args( + SDL + REQUIRED_VARS SDL2_LIBRARIES SDL2_INCLUDE_DIRS + VERSION_VAR SDL2_VERSION_STRING) mark_as_advanced(SDL2_LIBRARY SDL2_INCLUDE_DIR) - - diff --git a/mrt_cmake_modules/cmake/Modules/FindSqlite3.cmake b/mrt_cmake_modules/cmake/Modules/FindSqlite3.cmake index aa650e38afe..38a643cab6f 100644 --- a/mrt_cmake_modules/cmake/Modules/FindSqlite3.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindSqlite3.cmake @@ -13,75 +13,56 @@ # For details see the accompanying COPYING-CMAKE-SCRIPTS file. # - -if (SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) - # in cache already - set(SQLITE3_FOUND TRUE) -else (SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) - # use pkg-config to get the directories and then use these values - # in the FIND_PATH() and FIND_LIBRARY() calls - if (${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) - include(UsePkgConfig) - pkgconfig(sqlite3 _SQLITE3_INCLUDEDIR _SQLITE3_LIBDIR _SQLITE3_LDFLAGS _SQLITE3_CFLAGS) - else (${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) - find_package(PkgConfig) - if (PKG_CONFIG_FOUND) - pkg_check_modules(_SQLITE3 sqlite3) - endif (PKG_CONFIG_FOUND) - endif (${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) - find_path(SQLITE3_INCLUDE_DIR - NAMES - sqlite3.h - PATHS - ${_SQLITE3_INCLUDEDIR} - /usr/include - /usr/local/include - /opt/local/include - /sw/include - ) - - find_library(SQLITE3_LIBRARY - NAMES - sqlite3 - PATHS - ${_SQLITE3_LIBDIR} - /usr/lib - /usr/local/lib - /opt/local/lib - /sw/lib - ) - - if (SQLITE3_LIBRARY) +if(SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) + # in cache already set(SQLITE3_FOUND TRUE) - endif (SQLITE3_LIBRARY) +else(SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) + # use pkg-config to get the directories and then use these values + # in the FIND_PATH() and FIND_LIBRARY() calls + if(${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) + include(UsePkgConfig) + pkgconfig(sqlite3 _SQLITE3_INCLUDEDIR _SQLITE3_LIBDIR _SQLITE3_LDFLAGS _SQLITE3_CFLAGS) + else(${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) + find_package(PkgConfig) + if(PKG_CONFIG_FOUND) + pkg_check_modules(_SQLITE3 sqlite3) + endif(PKG_CONFIG_FOUND) + endif(${CMAKE_MAJOR_VERSION} EQUAL 2 AND ${CMAKE_MINOR_VERSION} EQUAL 4) + find_path( + SQLITE3_INCLUDE_DIR + NAMES sqlite3.h + PATHS ${_SQLITE3_INCLUDEDIR} /usr/include /usr/local/include /opt/local/include /sw/include) + + find_library( + SQLITE3_LIBRARY + NAMES sqlite3 + PATHS ${_SQLITE3_LIBDIR} /usr/lib /usr/local/lib /opt/local/lib /sw/lib) - set(SQLITE3_INCLUDE_DIRS - ${SQLITE3_INCLUDE_DIR} - ) + if(SQLITE3_LIBRARY) + set(SQLITE3_FOUND TRUE) + endif(SQLITE3_LIBRARY) - if (SQLITE3_FOUND) - set(SQLITE3_LIBRARIES - ${SQLITE3_LIBRARIES} - ${SQLITE3_LIBRARY} - ) - endif (SQLITE3_FOUND) + set(SQLITE3_INCLUDE_DIRS ${SQLITE3_INCLUDE_DIR}) - if (SQLITE3_INCLUDE_DIRS AND SQLITE3_LIBRARIES) - set(SQLITE3_FOUND TRUE) - endif (SQLITE3_INCLUDE_DIRS AND SQLITE3_LIBRARIES) + if(SQLITE3_FOUND) + set(SQLITE3_LIBRARIES ${SQLITE3_LIBRARIES} ${SQLITE3_LIBRARY}) + endif(SQLITE3_FOUND) - if (SQLITE3_FOUND) - if (NOT Sqlite3_FIND_QUIETLY) - message(STATUS "Found Sqlite3: ${SQLITE3_LIBRARIES}") - endif (NOT Sqlite3_FIND_QUIETLY) - else (SQLITE3_FOUND) - if (Sqlite3_FIND_REQUIRED) - message(FATAL_ERROR "Could not find Sqlite3") - endif (Sqlite3_FIND_REQUIRED) - endif (SQLITE3_FOUND) + if(SQLITE3_INCLUDE_DIRS AND SQLITE3_LIBRARIES) + set(SQLITE3_FOUND TRUE) + endif(SQLITE3_INCLUDE_DIRS AND SQLITE3_LIBRARIES) - # show the SQLITE3_INCLUDE_DIRS and SQLITE3_LIBRARIES variables only in the advanced view - mark_as_advanced(SQLITE3_INCLUDE_DIRS SQLITE3_LIBRARIES) + if(SQLITE3_FOUND) + if(NOT Sqlite3_FIND_QUIETLY) + message(STATUS "Found Sqlite3: ${SQLITE3_LIBRARIES}") + endif(NOT Sqlite3_FIND_QUIETLY) + else(SQLITE3_FOUND) + if(Sqlite3_FIND_REQUIRED) + message(FATAL_ERROR "Could not find Sqlite3") + endif(Sqlite3_FIND_REQUIRED) + endif(SQLITE3_FOUND) -endif (SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) + # show the SQLITE3_INCLUDE_DIRS and SQLITE3_LIBRARIES variables only in the advanced view + mark_as_advanced(SQLITE3_INCLUDE_DIRS SQLITE3_LIBRARIES) +endif(SQLITE3_LIBRARIES AND SQLITE3_INCLUDE_DIRS) diff --git a/mrt_cmake_modules/cmake/Modules/FindSuiteSparse.cmake b/mrt_cmake_modules/cmake/Modules/FindSuiteSparse.cmake new file mode 100644 index 00000000000..840e26bc5cd --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindSuiteSparse.cmake @@ -0,0 +1,521 @@ +# Ceres Solver - A fast non-linear least squares minimizer +# Copyright 2015 Google Inc. All rights reserved. +# http://ceres-solver.org/ +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# * Neither the name of Google Inc. nor the names of its contributors may be +# used to endorse or promote products derived from this software without +# specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: alexs.mac@gmail.com (Alex Stewart) +# + +# FindSuiteSparse.cmake - Find SuiteSparse libraries & dependencies. +# +# This module defines the following variables: +# +# SUITESPARSE_FOUND: TRUE iff SuiteSparse and all dependencies have been found. +# SUITESPARSE_INCLUDE_DIRS: Include directories for all SuiteSparse components. +# SUITESPARSE_LIBRARIES: Libraries for all SuiteSparse component libraries and +# dependencies. +# SUITESPARSE_VERSION: Extracted from UFconfig.h (<= v3) or +# SuiteSparse_config.h (>= v4). +# SUITESPARSE_MAIN_VERSION: Equal to 4 if SUITESPARSE_VERSION = 4.2.1 +# SUITESPARSE_SUB_VERSION: Equal to 2 if SUITESPARSE_VERSION = 4.2.1 +# SUITESPARSE_SUBSUB_VERSION: Equal to 1 if SUITESPARSE_VERSION = 4.2.1 +# +# SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION: TRUE iff running +# on Ubuntu, SUITESPARSE_VERSION is 3.4.0 and found SuiteSparse is a system +# install, in which case found version of SuiteSparse cannot be used to link +# a shared library due to a bug (static linking is unaffected). +# +# The following variables control the behaviour of this module: +# +# SUITESPARSE_INCLUDE_DIR_HINTS: List of additional directories in which to +# search for SuiteSparse includes, +# e.g: /timbuktu/include. +# SUITESPARSE_LIBRARY_DIR_HINTS: List of additional directories in which to +# search for SuiteSparse libraries, +# e.g: /timbuktu/lib. +# +# The following variables define the presence / includes & libraries for the +# SuiteSparse components searched for, the SUITESPARSE_XX variables are the +# union of the variables for all components. +# +# == Symmetric Approximate Minimum Degree (AMD) +# AMD_FOUND +# AMD_INCLUDE_DIR +# AMD_LIBRARY +# +# == Constrained Approximate Minimum Degree (CAMD) +# CAMD_FOUND +# CAMD_INCLUDE_DIR +# CAMD_LIBRARY +# +# == Column Approximate Minimum Degree (COLAMD) +# COLAMD_FOUND +# COLAMD_INCLUDE_DIR +# COLAMD_LIBRARY +# +# Constrained Column Approximate Minimum Degree (CCOLAMD) +# CCOLAMD_FOUND +# CCOLAMD_INCLUDE_DIR +# CCOLAMD_LIBRARY +# +# == Sparse Supernodal Cholesky Factorization and Update/Downdate (CHOLMOD) +# CHOLMOD_FOUND +# CHOLMOD_INCLUDE_DIR +# CHOLMOD_LIBRARY +# +# == Multifrontal Sparse QR (SuiteSparseQR) +# SUITESPARSEQR_FOUND +# SUITESPARSEQR_INCLUDE_DIR +# SUITESPARSEQR_LIBRARY +# +# == Common configuration for all but CSparse (SuiteSparse version >= 4). +# SUITESPARSE_CONFIG_FOUND +# SUITESPARSE_CONFIG_INCLUDE_DIR +# SUITESPARSE_CONFIG_LIBRARY +# +# == Common configuration for all but CSparse (SuiteSparse version < 4). +# UFCONFIG_FOUND +# UFCONFIG_INCLUDE_DIR +# +# Optional SuiteSparse Dependencies: +# +# == Serial Graph Partitioning and Fill-reducing Matrix Ordering (METIS) +# METIS_FOUND +# METIS_LIBRARY + +# Reset CALLERS_CMAKE_FIND_LIBRARY_PREFIXES to its value when +# FindSuiteSparse was invoked. +macro(SUITESPARSE_RESET_FIND_LIBRARY_PREFIX) + if(MSVC) + set(CMAKE_FIND_LIBRARY_PREFIXES "${CALLERS_CMAKE_FIND_LIBRARY_PREFIXES}") + endif(MSVC) +endmacro(SUITESPARSE_RESET_FIND_LIBRARY_PREFIX) + +# Called if we failed to find SuiteSparse or any of it's required dependencies, +# unsets all public (designed to be used externally) variables and reports +# error message at priority depending upon [REQUIRED/QUIET/] argument. +macro(SUITESPARSE_REPORT_NOT_FOUND REASON_MSG) + unset(SUITESPARSE_FOUND) + unset(SUITESPARSE_INCLUDE_DIRS) + unset(SUITESPARSE_LIBRARIES) + unset(SUITESPARSE_VERSION) + unset(SUITESPARSE_MAIN_VERSION) + unset(SUITESPARSE_SUB_VERSION) + unset(SUITESPARSE_SUBSUB_VERSION) + # Do NOT unset SUITESPARSE_FOUND_REQUIRED_VARS here, as it is used by + # FindPackageHandleStandardArgs() to generate the automatic error message on + # failure which highlights which components are missing. + + suitesparse_reset_find_library_prefix() + + # Note _FIND_[REQUIRED/QUIETLY] variables defined by FindPackage() + # use the camelcase library name, not uppercase. + if(SuiteSparse_FIND_QUIETLY) + message(STATUS "Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) + elseif(SuiteSparse_FIND_REQUIRED) + message(FATAL_ERROR "Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) + else() + # Neither QUIETLY nor REQUIRED, use no priority which emits a message + # but continues configuration and allows generation. + message("-- Failed to find SuiteSparse - " ${REASON_MSG} ${ARGN}) + endif(SuiteSparse_FIND_QUIETLY) + + # Do not call return(), s/t we keep processing if not called with REQUIRED + # and report all missing components, rather than bailing after failing to find + # the first. +endmacro(SUITESPARSE_REPORT_NOT_FOUND) + +# Protect against any alternative find_package scripts for this library having +# been called previously (in a client project) which set SUITESPARSE_FOUND, but +# not the other variables we require / set here which could cause the search +# logic here to fail. +unset(SUITESPARSE_FOUND) + +# Handle possible presence of lib prefix for libraries on MSVC, see +# also SUITESPARSE_RESET_FIND_LIBRARY_PREFIX(). +if(MSVC) + # Preserve the caller's original values for CMAKE_FIND_LIBRARY_PREFIXES + # s/t we can set it back before returning. + set(CALLERS_CMAKE_FIND_LIBRARY_PREFIXES "${CMAKE_FIND_LIBRARY_PREFIXES}") + # The empty string in this list is important, it represents the case when + # the libraries have no prefix (shared libraries / DLLs). + set(CMAKE_FIND_LIBRARY_PREFIXES "lib" "" "${CMAKE_FIND_LIBRARY_PREFIXES}") +endif(MSVC) + +# On macOS, add the Homebrew prefix (with appropriate suffixes) to the +# respective HINTS directories (after any user-specified locations). This +# handles Homebrew installations into non-standard locations (not /usr/local). +# We do not use CMAKE_PREFIX_PATH for this as given the search ordering of +# find_xxx(), doing so would override any user-specified HINTS locations with +# the Homebrew version if it exists. +if(CMAKE_SYSTEM_NAME MATCHES "Darwin") + find_program(HOMEBREW_EXECUTABLE brew) + mark_as_advanced(FORCE HOMEBREW_EXECUTABLE) + if(HOMEBREW_EXECUTABLE) + # Detected a Homebrew install, query for its install prefix. + execute_process( + COMMAND ${HOMEBREW_EXECUTABLE} --prefix + OUTPUT_VARIABLE HOMEBREW_INSTALL_PREFIX + OUTPUT_STRIP_TRAILING_WHITESPACE) + message(STATUS "Detected Homebrew with install prefix: " + "${HOMEBREW_INSTALL_PREFIX}, adding to CMake search paths.") + list(APPEND SUITESPARSE_INCLUDE_DIR_HINTS "${HOMEBREW_INSTALL_PREFIX}/include") + list(APPEND SUITESPARSE_LIBRARY_DIR_HINTS "${HOMEBREW_INSTALL_PREFIX}/lib") + endif() +endif() + +# Specify search directories for include files and libraries (this is the union +# of the search directories for all OSs). Search user-specified hint +# directories first if supplied, and search user-installed locations first +# so that we prefer user installs to system installs where both exist. +list( + APPEND + SUITESPARSE_CHECK_INCLUDE_DIRS + /opt/local/include + /opt/local/include/ufsparse # Mac OS X + /usr/local/homebrew/include # Mac OS X + /usr/local/include + /usr/include) +list( + APPEND + SUITESPARSE_CHECK_LIBRARY_DIRS + /opt/local/lib + /opt/local/lib/ufsparse # Mac OS X + /usr/local/homebrew/lib # Mac OS X + /usr/local/lib + /usr/lib) +# Additional suffixes to try appending to each search path. +list(APPEND SUITESPARSE_CHECK_PATH_SUFFIXES suitesparse) # Windows/Ubuntu + +# Wrappers to find_path/library that pass the SuiteSparse search hints/paths. +# +# suitesparse_find_component( [FILES name1 [name2 ...]] +# [LIBRARIES name1 [name2 ...]] +# [REQUIRED]) +macro(suitesparse_find_component COMPONENT) + include(CMakeParseArguments) + set(OPTIONS REQUIRED) + set(MULTI_VALUE_ARGS FILES LIBRARIES) + cmake_parse_arguments(SUITESPARSE_FIND_${COMPONENT} "${OPTIONS}" "" "${MULTI_VALUE_ARGS}" ${ARGN}) + + if(SUITESPARSE_FIND_${COMPONENT}_REQUIRED) + list(APPEND SUITESPARSE_FOUND_REQUIRED_VARS ${COMPONENT}_FOUND) + endif() + + set(${COMPONENT}_FOUND TRUE) + if(SUITESPARSE_FIND_${COMPONENT}_FILES) + find_path( + ${COMPONENT}_INCLUDE_DIR + NAMES ${SUITESPARSE_FIND_${COMPONENT}_FILES} + HINTS ${SUITESPARSE_INCLUDE_DIR_HINTS} + PATHS ${SUITESPARSE_CHECK_INCLUDE_DIRS} + PATH_SUFFIXES ${SUITESPARSE_CHECK_PATH_SUFFIXES}) + if(${COMPONENT}_INCLUDE_DIR) + message(STATUS "Found ${COMPONENT} headers in: " "${${COMPONENT}_INCLUDE_DIR}") + mark_as_advanced(${COMPONENT}_INCLUDE_DIR) + else() + # Specified headers not found. + set(${COMPONENT}_FOUND FALSE) + if(SUITESPARSE_FIND_${COMPONENT}_REQUIRED) + suitesparse_report_not_found("Did not find ${COMPONENT} header (required SuiteSparse component).") + else() + message(STATUS "Did not find ${COMPONENT} header (optional " "SuiteSparse component).") + # Hide optional vars from CMake GUI even if not found. + mark_as_advanced(${COMPONENT}_INCLUDE_DIR) + endif() + endif() + endif() + + if(SUITESPARSE_FIND_${COMPONENT}_LIBRARIES) + find_library( + ${COMPONENT}_LIBRARY + NAMES ${SUITESPARSE_FIND_${COMPONENT}_LIBRARIES} + HINTS ${SUITESPARSE_LIBRARY_DIR_HINTS} + PATHS ${SUITESPARSE_CHECK_LIBRARY_DIRS} + PATH_SUFFIXES ${SUITESPARSE_CHECK_PATH_SUFFIXES}) + if(${COMPONENT}_LIBRARY) + message(STATUS "Found ${COMPONENT} library: ${${COMPONENT}_LIBRARY}") + mark_as_advanced(${COMPONENT}_LIBRARY) + else() + # Specified libraries not found. + set(${COMPONENT}_FOUND FALSE) + if(SUITESPARSE_FIND_${COMPONENT}_REQUIRED) + suitesparse_report_not_found("Did not find ${COMPONENT} library (required SuiteSparse component).") + else() + message(STATUS "Did not find ${COMPONENT} library (optional SuiteSparse " "dependency)") + # Hide optional vars from CMake GUI even if not found. + mark_as_advanced(${COMPONENT}_LIBRARY) + endif() + endif() + endif() +endmacro() + +# Given the number of components of SuiteSparse, and to ensure that the +# automatic failure message generated by FindPackageHandleStandardArgs() +# when not all required components are found is helpful, we maintain a list +# of all variables that must be defined for SuiteSparse to be considered found. +unset(SUITESPARSE_FOUND_REQUIRED_VARS) + +# BLAS. +find_package(BLAS QUIET) +if(NOT BLAS_FOUND) + suitesparse_report_not_found("Did not find BLAS library (required for SuiteSparse).") +endif(NOT BLAS_FOUND) +list(APPEND SUITESPARSE_FOUND_REQUIRED_VARS BLAS_FOUND) + +# LAPACK. +find_package(LAPACK QUIET) +if(NOT LAPACK_FOUND) + suitesparse_report_not_found("Did not find LAPACK library (required for SuiteSparse).") +endif(NOT LAPACK_FOUND) +list(APPEND SUITESPARSE_FOUND_REQUIRED_VARS LAPACK_FOUND) + +suitesparse_find_component(AMD REQUIRED FILES amd.h LIBRARIES amd) +suitesparse_find_component(CAMD REQUIRED FILES camd.h LIBRARIES camd) +suitesparse_find_component(COLAMD REQUIRED FILES colamd.h LIBRARIES colamd) +suitesparse_find_component(CCOLAMD REQUIRED FILES ccolamd.h LIBRARIES ccolamd) +suitesparse_find_component(CHOLMOD REQUIRED FILES cholmod.h LIBRARIES cholmod) +suitesparse_find_component(SUITESPARSEQR REQUIRED FILES SuiteSparseQR.hpp LIBRARIES spqr) +if(SUITESPARSEQR_FOUND) + # SuiteSparseQR may be compiled with Intel Threading Building Blocks, + # we assume that if TBB is installed, SuiteSparseQR was compiled with + # support for it, this will do no harm if it wasn't. + find_package(TBB QUIET) + if(TBB_FOUND) + message(STATUS "Found Intel Thread Building Blocks (TBB) library " + "(${TBB_VERSION}) assuming SuiteSparseQR was compiled " "with TBB.") + # Add the TBB target to the SuiteSparseQR libraries (the only + # libraries to optionally depend on TBB). + list(APPEND SUITESPARSEQR_LIBRARY tbb) + else() + message(STATUS "Did not find Intel TBB library, assuming SuiteSparseQR was " "not compiled with TBB.") + endif() +endif(SUITESPARSEQR_FOUND) + +# UFconfig / SuiteSparse_config. +# +# If SuiteSparse version is >= 4 then SuiteSparse_config is required. +# For SuiteSparse 3, UFconfig.h is required. +suitesparse_find_component(SUITESPARSE_CONFIG FILES SuiteSparse_config.h LIBRARIES suitesparseconfig) + +if(SUITESPARSE_CONFIG_FOUND) + # SuiteSparse_config (SuiteSparse version >= 4) requires librt library for + # timing by default when compiled on Linux or Unix, but not on OSX (which + # does not have librt). + if(CMAKE_SYSTEM_NAME MATCHES "Linux" + OR UNIX + AND NOT APPLE) + suitesparse_find_component(LIBRT LIBRARIES rt) + if(LIBRT_FOUND) + message(STATUS "Adding librt: ${LIBRT_LIBRARY} to " + "SuiteSparse_config libraries (required on Linux & Unix [not OSX] if " + "SuiteSparse is compiled with timing).") + list(APPEND SUITESPARSE_CONFIG_LIBRARY ${LIBRT_LIBRARY}) + else() + message(STATUS "Could not find librt, but found SuiteSparse_config, " + "assuming that SuiteSparse was compiled without timing.") + endif() + endif( + CMAKE_SYSTEM_NAME MATCHES "Linux" + OR UNIX + AND NOT APPLE) +else() + # Failed to find SuiteSparse_config (>= v4 installs), instead look for + # UFconfig header which should be present in < v4 installs. + suitesparse_find_component(UFCONFIG FILES UFconfig.h) +endif() + +if(NOT SUITESPARSE_CONFIG_FOUND AND NOT UFCONFIG_FOUND) + suitesparse_report_not_found( + "Failed to find either: SuiteSparse_config header & library (should be " + "present in all SuiteSparse >= v4 installs), or UFconfig header (should " + "be present in all SuiteSparse < v4 installs).") +endif() + +# Extract the SuiteSparse version from the appropriate header (UFconfig.h for +# <= v3, SuiteSparse_config.h for >= v4). +list(APPEND SUITESPARSE_FOUND_REQUIRED_VARS SUITESPARSE_VERSION) + +if(UFCONFIG_FOUND) + # SuiteSparse version <= 3. + set(SUITESPARSE_VERSION_FILE ${UFCONFIG_INCLUDE_DIR}/UFconfig.h) + if(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) + suitesparse_report_not_found( + "Could not find file: ${SUITESPARSE_VERSION_FILE} containing version " + "information for <= v3 SuiteSparse installs, but UFconfig was found " "(only present in <= v3 installs).") + else(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) + file(READ ${SUITESPARSE_VERSION_FILE} UFCONFIG_CONTENTS) + + string(REGEX MATCH "#define SUITESPARSE_MAIN_VERSION [0-9]+" SUITESPARSE_MAIN_VERSION "${UFCONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_MAIN_VERSION ([0-9]+)" "\\1" SUITESPARSE_MAIN_VERSION + "${SUITESPARSE_MAIN_VERSION}") + + string(REGEX MATCH "#define SUITESPARSE_SUB_VERSION [0-9]+" SUITESPARSE_SUB_VERSION "${UFCONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_SUB_VERSION ([0-9]+)" "\\1" SUITESPARSE_SUB_VERSION + "${SUITESPARSE_SUB_VERSION}") + + string(REGEX MATCH "#define SUITESPARSE_SUBSUB_VERSION [0-9]+" SUITESPARSE_SUBSUB_VERSION + "${UFCONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_SUBSUB_VERSION ([0-9]+)" "\\1" SUITESPARSE_SUBSUB_VERSION + "${SUITESPARSE_SUBSUB_VERSION}") + + # This is on a single line s/t CMake does not interpret it as a list of + # elements and insert ';' separators which would result in 4.;2.;1 nonsense. + set(SUITESPARSE_VERSION "${SUITESPARSE_MAIN_VERSION}.${SUITESPARSE_SUB_VERSION}.${SUITESPARSE_SUBSUB_VERSION}") + endif(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) +endif(UFCONFIG_FOUND) + +if(SUITESPARSE_CONFIG_FOUND) + # SuiteSparse version >= 4. + set(SUITESPARSE_VERSION_FILE ${SUITESPARSE_CONFIG_INCLUDE_DIR}/SuiteSparse_config.h) + if(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) + suitesparse_report_not_found( + "Could not find file: ${SUITESPARSE_VERSION_FILE} containing version " + "information for >= v4 SuiteSparse installs, but SuiteSparse_config was " + "found (only present in >= v4 installs).") + else(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) + file(READ ${SUITESPARSE_VERSION_FILE} SUITESPARSE_CONFIG_CONTENTS) + + string(REGEX MATCH "#define SUITESPARSE_MAIN_VERSION [0-9]+" SUITESPARSE_MAIN_VERSION + "${SUITESPARSE_CONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_MAIN_VERSION ([0-9]+)" "\\1" SUITESPARSE_MAIN_VERSION + "${SUITESPARSE_MAIN_VERSION}") + + string(REGEX MATCH "#define SUITESPARSE_SUB_VERSION [0-9]+" SUITESPARSE_SUB_VERSION + "${SUITESPARSE_CONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_SUB_VERSION ([0-9]+)" "\\1" SUITESPARSE_SUB_VERSION + "${SUITESPARSE_SUB_VERSION}") + + string(REGEX MATCH "#define SUITESPARSE_SUBSUB_VERSION [0-9]+" SUITESPARSE_SUBSUB_VERSION + "${SUITESPARSE_CONFIG_CONTENTS}") + string(REGEX REPLACE "#define SUITESPARSE_SUBSUB_VERSION ([0-9]+)" "\\1" SUITESPARSE_SUBSUB_VERSION + "${SUITESPARSE_SUBSUB_VERSION}") + + # This is on a single line s/t CMake does not interpret it as a list of + # elements and insert ';' separators which would result in 4.;2.;1 nonsense. + set(SUITESPARSE_VERSION "${SUITESPARSE_MAIN_VERSION}.${SUITESPARSE_SUB_VERSION}.${SUITESPARSE_SUBSUB_VERSION}") + endif(NOT EXISTS ${SUITESPARSE_VERSION_FILE}) +endif(SUITESPARSE_CONFIG_FOUND) + +# METIS (Optional dependency). +suitesparse_find_component(METIS LIBRARIES metis) + +# Only mark SuiteSparse as found if all required components and dependencies +# have been found. +set(SUITESPARSE_FOUND TRUE) +foreach(REQUIRED_VAR ${SUITESPARSE_FOUND_REQUIRED_VARS}) + if(NOT ${REQUIRED_VAR}) + set(SUITESPARSE_FOUND FALSE) + endif(NOT ${REQUIRED_VAR}) +endforeach(REQUIRED_VAR ${SUITESPARSE_FOUND_REQUIRED_VARS}) + +if(SUITESPARSE_FOUND) + list( + APPEND + SUITESPARSE_INCLUDE_DIRS + ${AMD_INCLUDE_DIR} + ${CAMD_INCLUDE_DIR} + ${COLAMD_INCLUDE_DIR} + ${CCOLAMD_INCLUDE_DIR} + ${CHOLMOD_INCLUDE_DIR} + ${SUITESPARSEQR_INCLUDE_DIR}) + # Handle config separately, as otherwise at least one of them will be set + # to NOTFOUND which would cause any check on SUITESPARSE_INCLUDE_DIRS to fail. + if(SUITESPARSE_CONFIG_FOUND) + list(APPEND SUITESPARSE_INCLUDE_DIRS ${SUITESPARSE_CONFIG_INCLUDE_DIR}) + endif(SUITESPARSE_CONFIG_FOUND) + if(UFCONFIG_FOUND) + list(APPEND SUITESPARSE_INCLUDE_DIRS ${UFCONFIG_INCLUDE_DIR}) + endif(UFCONFIG_FOUND) + # As SuiteSparse includes are often all in the same directory, remove any + # repetitions. + list(REMOVE_DUPLICATES SUITESPARSE_INCLUDE_DIRS) + + # Important: The ordering of these libraries is *NOT* arbitrary, as these + # could potentially be static libraries their link ordering is important. + list( + APPEND + SUITESPARSE_LIBRARIES + ${SUITESPARSEQR_LIBRARY} + ${CHOLMOD_LIBRARY} + ${CCOLAMD_LIBRARY} + ${CAMD_LIBRARY} + ${COLAMD_LIBRARY} + ${AMD_LIBRARY} + ${LAPACK_LIBRARIES} + ${BLAS_LIBRARIES}) + if(SUITESPARSE_CONFIG_FOUND) + list(APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_CONFIG_LIBRARY}) + endif(SUITESPARSE_CONFIG_FOUND) + if(METIS_FOUND) + list(APPEND SUITESPARSE_LIBRARIES ${METIS_LIBRARY}) + endif(METIS_FOUND) +endif() + +# Determine if we are running on Ubuntu with the package install of SuiteSparse +# which is broken and does not support linking a shared library. +set(SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION FALSE) +if(CMAKE_SYSTEM_NAME MATCHES "Linux" AND SUITESPARSE_VERSION VERSION_EQUAL 3.4.0) + find_program(LSB_RELEASE_EXECUTABLE lsb_release) + if(LSB_RELEASE_EXECUTABLE) + # Any even moderately recent Ubuntu release (likely to be affected by + # this bug) should have lsb_release, if it isn't present we are likely + # on a different Linux distribution (should be fine). + execute_process( + COMMAND ${LSB_RELEASE_EXECUTABLE} -si + OUTPUT_VARIABLE LSB_DISTRIBUTOR_ID + OUTPUT_STRIP_TRAILING_WHITESPACE) + + if(LSB_DISTRIBUTOR_ID MATCHES "Ubuntu" AND SUITESPARSE_LIBRARIES MATCHES "/usr/lib/libamd") + # We are on Ubuntu, and the SuiteSparse version matches the broken + # system install version and is a system install. + set(SUITESPARSE_IS_BROKEN_SHARED_LINKING_UBUNTU_SYSTEM_VERSION TRUE) + message(STATUS "Found system install of SuiteSparse " + "${SUITESPARSE_VERSION} running on Ubuntu, which has a known bug " + "preventing linking of shared libraries (static linking unaffected).") + endif(LSB_DISTRIBUTOR_ID MATCHES "Ubuntu" AND SUITESPARSE_LIBRARIES MATCHES "/usr/lib/libamd") + endif(LSB_RELEASE_EXECUTABLE) +endif(CMAKE_SYSTEM_NAME MATCHES "Linux" AND SUITESPARSE_VERSION VERSION_EQUAL 3.4.0) + +suitesparse_reset_find_library_prefix() + +# Handle REQUIRED and QUIET arguments to FIND_PACKAGE +include(FindPackageHandleStandardArgs) +if(SUITESPARSE_FOUND) + find_package_handle_standard_args( + SuiteSparse + REQUIRED_VARS ${SUITESPARSE_FOUND_REQUIRED_VARS} + VERSION_VAR SUITESPARSE_VERSION + FAIL_MESSAGE "Failed to find some/all required components of SuiteSparse.") +else(SUITESPARSE_FOUND) + # Do not pass VERSION_VAR to FindPackageHandleStandardArgs() if we failed to + # find SuiteSparse to avoid a confusing autogenerated failure message + # that states 'not found (missing: FOO) (found version: x.y.z)'. + find_package_handle_standard_args( + SuiteSparse + REQUIRED_VARS ${SUITESPARSE_FOUND_REQUIRED_VARS} + FAIL_MESSAGE "Failed to find some/all required components of SuiteSparse.") +endif(SUITESPARSE_FOUND) diff --git a/mrt_cmake_modules/cmake/Modules/FindTBB.cmake b/mrt_cmake_modules/cmake/Modules/FindTBB.cmake index e8ed5197d4a..00225be56b4 100644 --- a/mrt_cmake_modules/cmake/Modules/FindTBB.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindTBB.cmake @@ -1,346 +1,302 @@ -# - Find ThreadingBuildingBlocks include dirs and libraries -# Use this module by invoking find_package with the form: -# find_package(TBB -# [REQUIRED] # Fail with error if TBB is not found -# ) # -# Once done, this will define +# The MIT License (MIT) # -# TBB_FOUND - system has TBB -# TBB_INCLUDE_DIRS - the TBB include directories -# TBB_LIBRARIES - TBB libraries to be lined, doesn't include malloc or -# malloc proxy +# Copyright (c) 2015 Justus Calvin # -# TBB_VERSION_MAJOR - Major Product Version Number -# TBB_VERSION_MINOR - Minor Product Version Number -# TBB_INTERFACE_VERSION - Engineering Focused Version Number -# TBB_COMPATIBLE_INTERFACE_VERSION - The oldest major interface version -# still supported. This uses the engineering -# focused interface version numbers. +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: # -# TBB_MALLOC_FOUND - system has TBB malloc library -# TBB_MALLOC_INCLUDE_DIRS - the TBB malloc include directories -# TBB_MALLOC_LIBRARIES - The TBB malloc libraries to be lined +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. # -# TBB_MALLOC_PROXY_FOUND - system has TBB malloc proxy library -# TBB_MALLOC_PROXY_INCLUDE_DIRS = the TBB malloc proxy include directories -# TBB_MALLOC_PROXY_LIBRARIES - The TBB malloc proxy libraries to be lined +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. + # +# FindTBB +# ------- # -# This module reads hints about search locations from variables: -# ENV TBB_ARCH_PLATFORM - for eg. set it to "mic" for Xeon Phi builds -# ENV TBB_ROOT or just TBB_ROOT - root directory of tbb installation -# ENV TBB_BUILD_PREFIX - specifies the build prefix for user built tbb -# libraries. Should be specified with ENV TBB_ROOT -# and optionally... -# ENV TBB_BUILD_DIR - if build directory is different than ${TBB_ROOT}/build +# Find TBB include directories and libraries. # +# Usage: # -# Modified by Robert Maynard from the original OGRE source +# find_package(TBB [major[.minor]] [EXACT] +# [QUIET] [REQUIRED] +# [[COMPONENTS] [components...]] +# [OPTIONAL_COMPONENTS components...]) # -#------------------------------------------------------------------- -# This file is part of the CMake build system for OGRE -# (Object-oriented Graphics Rendering Engine) -# For the latest info, see http://www.ogre3d.org/ +# where the allowed components are tbbmalloc and tbb_preview. Users may modify +# the behavior of this module with the following variables: # -# The contents of this file are placed in the public domain. Feel -# free to make use of it in any way you like. -#------------------------------------------------------------------- +# * TBB_ROOT_DIR - The base directory the of TBB installation. +# * TBB_INCLUDE_DIR - The directory that contains the TBB headers files. +# * TBB_LIBRARY - The directory that contains the TBB library files. +# * TBB__LIBRARY - The path of the TBB the corresponding TBB library. +# These libraries, if specified, override the +# corresponding library search results, where +# may be tbb, tbb_debug, tbbmalloc, tbbmalloc_debug, +# tbb_preview, or tbb_preview_debug. +# * TBB_USE_DEBUG_BUILD - The debug version of tbb libraries, if present, will +# be used instead of the release version. # -#============================================================================= -# Copyright 2010-2012 Kitware, Inc. -# Copyright 2012 Rolf Eike Beer +# Users may modify the behavior of this module with the following environment +# variables: # -# Distributed under the OSI-approved BSD License (the "License"); -# see accompanying file Copyright.txt for details. +# * TBB_INSTALL_DIR +# * TBBROOT +# * LIBRARY_PATH # -# This software is distributed WITHOUT ANY WARRANTY; without even the -# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. -# See the License for more information. -#============================================================================= -# (To distribute this file outside of CMake, substitute the full -# License text for the above reference.) - - -#============================================================================= -# FindTBB helper functions and macros +# This module will set the following variables: # - -#=============================================== -# Do the final processing for the package find. -#=============================================== -macro(findpkg_finish PREFIX) - # skip if already processed during this run - if (NOT ${PREFIX}_FOUND) - if (${PREFIX}_INCLUDE_DIR AND ${PREFIX}_LIBRARY) - set(${PREFIX}_FOUND TRUE) - set (${PREFIX}_INCLUDE_DIRS ${${PREFIX}_INCLUDE_DIR}) - set (${PREFIX}_LIBRARIES ${${PREFIX}_LIBRARY}) - else () - if (${PREFIX}_FIND_REQUIRED AND NOT ${PREFIX}_FIND_QUIETLY) - message(FATAL_ERROR "Required library ${PREFIX} not found.") - endif () - endif () - - #mark the following variables as internal variables - mark_as_advanced(${PREFIX}_INCLUDE_DIR - ${PREFIX}_LIBRARY - ${PREFIX}_LIBRARY_DEBUG - ${PREFIX}_LIBRARY_RELEASE) - endif () -endmacro(findpkg_finish) - -#=============================================== -# Generate debug names from given RELEASEease names -#=============================================== -macro(get_debug_names PREFIX) - foreach(i ${${PREFIX}}) - set(${PREFIX}_DEBUG ${${PREFIX}_DEBUG} ${i}d ${i}D ${i}_d ${i}_D ${i}_debug ${i}) - endforeach(i) -endmacro(get_debug_names) - -#=============================================== -# See if we have env vars to help us find tbb -#=============================================== -macro(getenv_path VAR) - set(ENV_${VAR} $ENV{${VAR}}) - # replace won't work if var is blank - if (ENV_${VAR}) - string( REGEX REPLACE "\\\\" "/" ENV_${VAR} ${ENV_${VAR}} ) - endif () -endmacro(getenv_path) - -#=============================================== -# Couple a set of RELEASEease AND debug libraries -#=============================================== -macro(make_library_set PREFIX) - if (${PREFIX}_RELEASE AND ${PREFIX}_DEBUG) - set(${PREFIX} optimized ${${PREFIX}_RELEASE} debug ${${PREFIX}_DEBUG}) - elseif (${PREFIX}_RELEASE) - set(${PREFIX} ${${PREFIX}_RELEASE}) - elseif (${PREFIX}_DEBUG) - set(${PREFIX} ${${PREFIX}_DEBUG}) - endif () -endmacro(make_library_set) - - -#============================================================================= -# Now to actually find TBB +# * TBB_FOUND - Set to false, or undefined, if we haven’t found, or +# don’t want to use TBB. +# * TBB__FOUND - If False, optional part of TBB sytem is +# not available. +# * TBB_VERSION - The full version string +# * TBB_VERSION_MAJOR - The major version +# * TBB_VERSION_MINOR - The minor version +# * TBB_INTERFACE_VERSION - The interface version number defined in +# tbb/tbb_stddef.h. +# * TBB__LIBRARY_RELEASE - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. +# * TBB__LIBRARY_DEGUG - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. # - -# Get path, convert backslashes as ${ENV_${var}} -getenv_path(TBB_ROOT) - -# initialize search paths -set(TBB_PREFIX_PATH ${TBB_ROOT} ${ENV_TBB_ROOT}) -set(TBB_INC_SEARCH_PATH "") -set(TBB_LIB_SEARCH_PATH "") - - -# If user built from sources -set(TBB_BUILD_PREFIX $ENV{TBB_BUILD_PREFIX}) -if (TBB_BUILD_PREFIX AND ENV_TBB_ROOT) - getenv_path(TBB_BUILD_DIR) - if (NOT ENV_TBB_BUILD_DIR) - set(ENV_TBB_BUILD_DIR ${ENV_TBB_ROOT}/build) - endif () - - # include directory under ${ENV_TBB_ROOT}/include - list(APPEND TBB_LIB_SEARCH_PATH - ${ENV_TBB_BUILD_DIR}/${TBB_BUILD_PREFIX}_release - ${ENV_TBB_BUILD_DIR}/${TBB_BUILD_PREFIX}_debug) -endif () - - -# For Windows, let's assume that the user might be using the precompiled -# TBB packages from the main website. These use a rather awkward directory -# structure (at least for automatically finding the right files) depending -# on platform and compiler, but we'll do our best to accommodate it. -# Not adding the same effort for the precompiled linux builds, though. Those -# have different versions for CC compiler versions and linux kernels which -# will never adequately match the user's setup, so there is no feasible way -# to detect the "best" version to use. The user will have to manually -# select the right files. (Chances are the distributions are shipping their -# custom version of tbb, anyway, so the problem is probably nonexistant.) -if (WIN32 AND MSVC) - set(COMPILER_PREFIX "vc7.1") - if (MSVC_VERSION EQUAL 1400) - set(COMPILER_PREFIX "vc8") - elseif(MSVC_VERSION EQUAL 1500) - set(COMPILER_PREFIX "vc9") - elseif(MSVC_VERSION EQUAL 1600) - set(COMPILER_PREFIX "vc10") - elseif(MSVC_VERSION EQUAL 1700) - set(COMPILER_PREFIX "vc11") - elseif(MSVC_VERSION EQUAL 1800) - set(COMPILER_PREFIX "vc12") - elseif(MSVC_VERSION EQUAL 1900) - set(COMPILER_PREFIX "vc14") - endif () - - # for each prefix path, add ia32/64\${COMPILER_PREFIX}\lib to the lib search path - foreach (dir ${TBB_PREFIX_PATH}) - if (CMAKE_CL_64) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/ia64/${COMPILER_PREFIX}/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/ia64/${COMPILER_PREFIX}) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/intel64/${COMPILER_PREFIX}/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/intel64/${COMPILER_PREFIX}) - else () - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/ia32/${COMPILER_PREFIX}/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/ia32/${COMPILER_PREFIX}) - endif () - endforeach () -endif () - -# For OS X binary distribution, choose libc++ based libraries for Maverics and -# above and AppleClang -if (${CMAKE_SYSTEM_NAME} STREQUAL "Darwin" AND - NOT ${CMAKE_SYSTEM_VERSION} LESS 13.0) - set (USE_LIBCXX OFF) - cmake_policy(GET CMP0025 POLICY_VAR) - - if ("${POLICY_VAR}" STREQUAL "NEW") - if (${CMAKE_CXX_COMPILER_ID} STREQUAL "AppleClang") - set (USE_LIBCXX ON) - endif () - else () - if (${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang") - set (USE_LIBCXX ON) - endif () - endif () - - if (${USE_LIBCXX}) - foreach (dir ${TBB_PREFIX_PATH}) - list (APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/libc++ ${dir}/libc++/lib) - endforeach () - endif () -endif () - -# check compiler ABI -if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND - CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.4) - set(COMPILER_PREFIX "gcc4.1") -else () # Assume compatibility with 4.4 for other compilers - set(COMPILER_PREFIX "gcc4.4") -endif () - -# if platform architecture is explicitly specified -set(TBB_ARCH_PLATFORM $ENV{TBB_ARCH_PLATFORM}) -if (TBB_ARCH_PLATFORM) - foreach (dir ${TBB_PREFIX_PATH}) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/${TBB_ARCH_PLATFORM}/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/${TBB_ARCH_PLATFORM}) - endforeach () -endif () - -foreach (dir ${TBB_PREFIX_PATH}) - if (CMAKE_SIZEOF_VOID_P EQUAL 8) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/intel64) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/intel64/${COMPILER_PREFIX}) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/intel64/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/intel64/${COMPILER_PREFIX}/lib) - else () - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/ia32) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib/ia32/${COMPILER_PREFIX}) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/ia32/lib) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/ia32/${COMPILER_PREFIX}/lib) - endif () -endforeach () - -# add general search paths -foreach (dir ${TBB_PREFIX_PATH}) - list(APPEND TBB_LIB_SEARCH_PATH ${dir}/lib ${dir}/Lib ${dir}/lib/tbb - ${dir}/Libs) - list(APPEND TBB_INC_SEARCH_PATH ${dir}/include ${dir}/Include - ${dir}/include/tbb) -endforeach () - -set(TBB_LIBRARY_NAMES tbb) -get_debug_names(TBB_LIBRARY_NAMES) - - -find_path(TBB_INCLUDE_DIR - NAMES tbb/tbb.h - PATHS ${TBB_INC_SEARCH_PATH}) - -find_library(TBB_LIBRARY_RELEASE - NAMES ${TBB_LIBRARY_NAMES} - PATHS ${TBB_LIB_SEARCH_PATH}) -find_library(TBB_LIBRARY_DEBUG - NAMES ${TBB_LIBRARY_NAMES_DEBUG} - PATHS ${TBB_LIB_SEARCH_PATH}) -make_library_set(TBB_LIBRARY) - -findpkg_finish(TBB) - -#if we haven't found TBB no point on going any further -if (NOT TBB_FOUND) - return() -endif () - -#============================================================================= -# Look for TBB's malloc package -set(TBB_MALLOC_LIBRARY_NAMES tbbmalloc) -get_debug_names(TBB_MALLOC_LIBRARY_NAMES) - -find_path(TBB_MALLOC_INCLUDE_DIR - NAMES tbb/tbb.h - PATHS ${TBB_INC_SEARCH_PATH}) - -find_library(TBB_MALLOC_LIBRARY_RELEASE - NAMES ${TBB_MALLOC_LIBRARY_NAMES} - PATHS ${TBB_LIB_SEARCH_PATH}) -find_library(TBB_MALLOC_LIBRARY_DEBUG - NAMES ${TBB_MALLOC_LIBRARY_NAMES_DEBUG} - PATHS ${TBB_LIB_SEARCH_PATH}) -make_library_set(TBB_MALLOC_LIBRARY) - -findpkg_finish(TBB_MALLOC) - -#============================================================================= -# Look for TBB's malloc proxy package -set(TBB_MALLOC_PROXY_LIBRARY_NAMES tbbmalloc_proxy) -get_debug_names(TBB_MALLOC_PROXY_LIBRARY_NAMES) - -find_path(TBB_MALLOC_PROXY_INCLUDE_DIR - NAMES tbb/tbbmalloc_proxy.h - PATHS ${TBB_INC_SEARCH_PATH}) - -find_library(TBB_MALLOC_PROXY_LIBRARY_RELEASE - NAMES ${TBB_MALLOC_PROXY_LIBRARY_NAMES} - PATHS ${TBB_LIB_SEARCH_PATH}) -find_library(TBB_MALLOC_PROXY_LIBRARY_DEBUG - NAMES ${TBB_MALLOC_PROXY_LIBRARY_NAMES_DEBUG} - PATHS ${TBB_LIB_SEARCH_PATH}) -make_library_set(TBB_MALLOC_PROXY_LIBRARY) - -findpkg_finish(TBB_MALLOC_PROXY) - - -#============================================================================= -#parse all the version numbers from tbb -if(NOT TBB_VERSION) - - #only read the start of the file - file(READ - "${TBB_INCLUDE_DIR}/tbb/tbb_stddef.h" - TBB_VERSION_CONTENTS - LIMIT 2048) - - string(REGEX REPLACE - ".*#define TBB_VERSION_MAJOR ([0-9]+).*" "\\1" - TBB_VERSION_MAJOR "${TBB_VERSION_CONTENTS}") - - string(REGEX REPLACE - ".*#define TBB_VERSION_MINOR ([0-9]+).*" "\\1" - TBB_VERSION_MINOR "${TBB_VERSION_CONTENTS}") - - string(REGEX REPLACE - ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" - TBB_INTERFACE_VERSION "${TBB_VERSION_CONTENTS}") - - string(REGEX REPLACE - ".*#define TBB_COMPATIBLE_INTERFACE_VERSION ([0-9]+).*" "\\1" - TBB_COMPATIBLE_INTERFACE_VERSION "${TBB_VERSION_CONTENTS}") +# The following varibles should be used to build and link with TBB: +# +# * TBB_INCLUDE_DIRS - The include directory for TBB. +# * TBB_LIBRARIES - The libraries to link against to use TBB. +# * TBB_LIBRARIES_RELEASE - The release libraries to link against to use TBB. +# * TBB_LIBRARIES_DEBUG - The debug libraries to link against to use TBB. +# * TBB_DEFINITIONS - Definitions to use when compiling code that uses +# TBB. +# * TBB_DEFINITIONS_RELEASE - Definitions to use when compiling release code that +# uses TBB. +# * TBB_DEFINITIONS_DEBUG - Definitions to use when compiling debug code that +# uses TBB. +# +# This module will also create the "tbb" target that may be used when building +# executables and libraries. + +include(FindPackageHandleStandardArgs) + +if(NOT TBB_FOUND) + + ################################## + # Check the build type + ################################## + + if(NOT DEFINED TBB_USE_DEBUG_BUILD) + if(CMAKE_BUILD_TYPE MATCHES "(Debug|DEBUG|debug|RelWithDebInfo|RELWITHDEBINFO|relwithdebinfo)") + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() + elseif(TBB_USE_DEBUG_BUILD) + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() + + ################################## + # Set the TBB search directories + ################################## + + # Define search paths based on user input and environment variables + set(TBB_SEARCH_DIR ${TBB_ROOT_DIR} $ENV{TBB_INSTALL_DIR} $ENV{TBBROOT}) + + # Define the search directories based on the current platform + if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(TBB_DEFAULT_SEARCH_DIR "C:/Program Files/Intel/TBB" "C:/Program Files (x86)/Intel/TBB") + + # Set the target architecture + if(CMAKE_SIZEOF_VOID_P EQUAL 8) + set(TBB_ARCHITECTURE "intel64") + else() + set(TBB_ARCHITECTURE "ia32") + endif() + + # Set the TBB search library path search suffix based on the version of VC + if(WINDOWS_STORE) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11_ui") + elseif(MSVC14) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc14") + elseif(MSVC12) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc12") + elseif(MSVC11) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11") + elseif(MSVC10) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc10") + endif() + + # Add the library path search suffix for the VC independent version of TBB + list(APPEND TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc_mt") + + elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin") + # OS X + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") + + # TODO: Check to see which C++ library is being used by the compiler. + if(NOT ${CMAKE_SYSTEM_VERSION} VERSION_LESS 13.0) + # The default C++ library on OS X 10.9 and later is libc++ + set(TBB_LIB_PATH_SUFFIX "lib/libc++" "lib") + else() + set(TBB_LIB_PATH_SUFFIX "lib") + endif() + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux") + # Linux + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") + + # TODO: Check compiler version to see the suffix should be /gcc4.1 or + # /gcc4.1. For now, assume that the compiler is more recent than + # gcc 4.4.x or later. + if(CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(TBB_LIB_PATH_SUFFIX "lib/intel64/gcc4.4") + elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "^i.86$") + set(TBB_LIB_PATH_SUFFIX "lib/ia32/gcc4.4") + endif() + endif() + + ################################## + # Find the TBB include dir + ################################## + + find_path( + TBB_INCLUDE_DIRS tbb/tbb.h + HINTS ${TBB_INCLUDE_DIR} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} + PATH_SUFFIXES include) + + ################################## + # Set version strings + ################################## + + if(TBB_INCLUDE_DIRS) + file(READ "${TBB_INCLUDE_DIRS}/tbb/tbb_stddef.h" _tbb_version_file) + string(REGEX REPLACE ".*#define TBB_VERSION_MAJOR ([0-9]+).*" "\\1" TBB_VERSION_MAJOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_VERSION_MINOR ([0-9]+).*" "\\1" TBB_VERSION_MINOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" TBB_INTERFACE_VERSION + "${_tbb_version_file}") + set(TBB_VERSION "${TBB_VERSION_MAJOR}.${TBB_VERSION_MINOR}") + endif() + + ################################## + # Find TBB components + ################################## + + if(TBB_VERSION VERSION_LESS 4.3) + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc tbb) + else() + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc_proxy tbbmalloc tbb) + endif() + + # Find each component + foreach(_comp ${TBB_SEARCH_COMPOMPONENTS}) + if(";${TBB_FIND_COMPONENTS};tbb;" MATCHES ";${_comp};") + + # Search for the libraries + find_library( + TBB_${_comp}_LIBRARY_RELEASE ${_comp} + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) + + find_library( + TBB_${_comp}_LIBRARY_DEBUG ${_comp}_debug + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) + + if(TBB_${_comp}_LIBRARY_DEBUG) + list(APPEND TBB_LIBRARIES_DEBUG "${TBB_${_comp}_LIBRARY_DEBUG}") + endif() + if(TBB_${_comp}_LIBRARY_RELEASE) + list(APPEND TBB_LIBRARIES_RELEASE "${TBB_${_comp}_LIBRARY_RELEASE}") + endif() + if(TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE} AND NOT TBB_${_comp}_LIBRARY) + set(TBB_${_comp}_LIBRARY "${TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE}}") + endif() + + if(TBB_${_comp}_LIBRARY AND EXISTS "${TBB_${_comp}_LIBRARY}") + set(TBB_${_comp}_FOUND TRUE) + else() + set(TBB_${_comp}_FOUND FALSE) + endif() + + # Mark internal variables as advanced + mark_as_advanced(TBB_${_comp}_LIBRARY_RELEASE) + mark_as_advanced(TBB_${_comp}_LIBRARY_DEBUG) + mark_as_advanced(TBB_${_comp}_LIBRARY) + + endif() + endforeach() + + ################################## + # Set compile flags and libraries + ################################## + + set(TBB_DEFINITIONS_RELEASE "") + set(TBB_DEFINITIONS_DEBUG "-DTBB_USE_DEBUG=1") + + if(TBB_LIBRARIES_${TBB_BUILD_TYPE}) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_${TBB_BUILD_TYPE}}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_${TBB_BUILD_TYPE}}") + elseif(TBB_LIBRARIES_RELEASE) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_RELEASE}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_RELEASE}") + elseif(TBB_LIBRARIES_DEBUG) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_DEBUG}") + endif() + + find_package_handle_standard_args( + TBB + REQUIRED_VARS TBB_INCLUDE_DIRS TBB_LIBRARIES + HANDLE_COMPONENTS + VERSION_VAR TBB_VERSION) + + ################################## + # Create targets + ################################## + + if(NOT CMAKE_VERSION VERSION_LESS 3.0 AND TBB_FOUND) + add_library(tbb SHARED IMPORTED) + set_target_properties(tbb PROPERTIES INTERFACE_INCLUDE_DIRECTORIES ${TBB_INCLUDE_DIRS} IMPORTED_LOCATION + ${TBB_LIBRARIES}) + if(TBB_LIBRARIES_RELEASE AND TBB_LIBRARIES_DEBUG) + set_target_properties( + tbb + PROPERTIES INTERFACE_COMPILE_DEFINITIONS + "$<$,$>:TBB_USE_DEBUG=1>" + IMPORTED_LOCATION_DEBUG ${TBB_LIBRARIES_DEBUG} + IMPORTED_LOCATION_RELWITHDEBINFO ${TBB_LIBRARIES_DEBUG} + IMPORTED_LOCATION_RELEASE ${TBB_LIBRARIES_RELEASE} + IMPORTED_LOCATION_MINSIZEREL ${TBB_LIBRARIES_RELEASE}) + elseif(TBB_LIBRARIES_RELEASE) + set_target_properties(tbb PROPERTIES IMPORTED_LOCATION ${TBB_LIBRARIES_RELEASE}) + else() + set_target_properties(tbb PROPERTIES INTERFACE_COMPILE_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}" + IMPORTED_LOCATION ${TBB_LIBRARIES_DEBUG}) + endif() + endif() + + mark_as_advanced(TBB_INCLUDE_DIRS TBB_LIBRARIES) + + unset(TBB_ARCHITECTURE) + unset(TBB_BUILD_TYPE) + unset(TBB_LIB_PATH_SUFFIX) + unset(TBB_DEFAULT_SEARCH_DIR) endif() - diff --git a/mrt_cmake_modules/cmake/Modules/FindTensorflow.cmake b/mrt_cmake_modules/cmake/Modules/FindTensorflow.cmake new file mode 100644 index 00000000000..740715929f9 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindTensorflow.cmake @@ -0,0 +1,20 @@ +# try to find tensorflow +find_package(PkgConfig) +find_path(TENSORFLOW_INCLUDE_DIR tensorflow/core/public/session.h PATH_SUFFIXES tensorflow) + +set(TENSORFLOW_INCLUDE_DIR ${TENSORFLOW_INCLUDE_DIR} ${TENSORFLOW_INCLUDE_DIR}/src) + +find_library(TENSORFLOW_CC_LIBRARY NAMES tensorflow_cc) +find_library(TENSORFLOW_FRAMEWORK_LIBRARY NAMES tensorflow_framework) + +set(TENSORFLOW_LIBRARY ${TENSORFLOW_CC_LIBRARY}) +if(TENSORFLOW_FRAMEWORK_LIBRARY) + set(TENSORFLOW_LIBRARY ${TENSORFLOW_LIBRARY} ${TENSORFLOW_FRAMEWORK_LIBRARY}) +endif(TENSORFLOW_FRAMEWORK_LIBRARY) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(MrtTensorflow DEFAULT_MSG TENSORFLOW_LIBRARY TENSORFLOW_INCLUDE_DIR) + +mark_as_advanced(TENSORFLOW_LIBRARY TENSORFLOW_INCLUDE_DIR) +set(TENSORFLOW_LIBRARIES ${TENSORFLOW_LIBRARY}) +set(TENSORFLOW_INCLUDE_DIRS ${TENSORFLOW_INCLUDE_DIR}) diff --git a/mrt_cmake_modules/cmake/Modules/FindTesseract.cmake b/mrt_cmake_modules/cmake/Modules/FindTesseract.cmake new file mode 100644 index 00000000000..7c6a2a7d5da --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindTesseract.cmake @@ -0,0 +1,11 @@ +set(PACKAGE_HEADER_FILES tesseract/apitypes.h) +set(PACKAGE_LIBRARIES tesseract) + +find_path(Tesseract_INCLUDE_DIR NAMES ${PACKAGE_HEADER_FILES}) +find_library(Tesseract_LIBRARIES NAMES ${PACKAGE_LIBRARIES}) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args( + Tesseract + FOUND_VAR Tesseract_FOUND + REQUIRED_VARS Tesseract_INCLUDE_DIR Tesseract_LIBRARIES) diff --git a/mrt_cmake_modules/cmake/Modules/FindTinyXML.cmake b/mrt_cmake_modules/cmake/Modules/FindTinyXML.cmake index 1abecb06242..f27d901d569 100644 --- a/mrt_cmake_modules/cmake/Modules/FindTinyXML.cmake +++ b/mrt_cmake_modules/cmake/Modules/FindTinyXML.cmake @@ -6,21 +6,21 @@ # TINYXML_LIBRARIES - List of libraries when using TinyXML. # -IF( TINYXML_INCLUDE_DIR ) +if(TINYXML_INCLUDE_DIR) # Already in cache, be silent - SET( TinyXML_FIND_QUIETLY TRUE ) -ENDIF( TINYXML_INCLUDE_DIR ) + set(TinyXML_FIND_QUIETLY TRUE) +endif(TINYXML_INCLUDE_DIR) -FIND_PATH( TINYXML_INCLUDE_DIR "tinyxml.h" - PATH_SUFFIXES "tinyxml" ) +find_path(TINYXML_INCLUDE_DIR "tinyxml.h" PATH_SUFFIXES "tinyxml") -FIND_LIBRARY( TINYXML_LIBRARIES - NAMES "tinyxml" - PATH_SUFFIXES "tinyxml" ) +find_library( + TINYXML_LIBRARIES + NAMES "tinyxml" + PATH_SUFFIXES "tinyxml") # handle the QUIETLY and REQUIRED arguments and set TINYXML_FOUND to TRUE if # all listed variables are TRUE -INCLUDE(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS( "TinyXML" DEFAULT_MSG TINYXML_INCLUDE_DIR TINYXML_LIBRARIES ) +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args("TinyXML" DEFAULT_MSG TINYXML_INCLUDE_DIR TINYXML_LIBRARIES) -MARK_AS_ADVANCED( TINYXML_INCLUDE_DIR TINYXML_LIBRARIES ) +mark_as_advanced(TINYXML_INCLUDE_DIR TINYXML_LIBRARIES) diff --git a/mrt_cmake_modules/cmake/Modules/FindTinyXML2.cmake b/mrt_cmake_modules/cmake/Modules/FindTinyXML2.cmake new file mode 100644 index 00000000000..47dcb2c7f90 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/FindTinyXML2.cmake @@ -0,0 +1,23 @@ +# Find headers and libraries +find_path( + TinyXML2_INCLUDE_DIR + NAMES tinyxml2.h + PATH_SUFFIXES "tinyxml2" ${TinyXML2_INCLUDE_PATH}) +find_library( + TinyXML2_LIBRARY + NAMES tinyxml2 + PATH_SUFFIXES "tinyxml2" ${TinyXML2_LIBRARY_PATH}) + +mark_as_advanced(TinyXML2_INCLUDE_DIR TinyXML2_LIBRARY) + +# Output variables generation +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(TinyXML2 DEFAULT_MSG TinyXML2_LIBRARY TinyXML2_INCLUDE_DIR) + +set(TinyXML2_FOUND ${TINYXML2_FOUND}) # Enforce case-correctness: Set appropriately cased variable... +unset(TINYXML2_FOUND) # ...and unset uppercase variable generated by find_package_handle_standard_args + +if(TinyXML2_FOUND) + set(TinyXML2_INCLUDE_DIRS ${TinyXML2_INCLUDE_DIR}) + set(TinyXML2_LIBRARIES ${TinyXML2_LIBRARY}) +endif() diff --git a/mrt_cmake_modules/cmake/Modules/FindMrtebus-sdk.cmake b/mrt_cmake_modules/cmake/Modules/Findebus-sdk.cmake similarity index 71% rename from mrt_cmake_modules/cmake/Modules/FindMrtebus-sdk.cmake rename to mrt_cmake_modules/cmake/Modules/Findebus-sdk.cmake index fe5f5c89a1f..698a862219b 100644 --- a/mrt_cmake_modules/cmake/Modules/FindMrtebus-sdk.cmake +++ b/mrt_cmake_modules/cmake/Modules/Findebus-sdk.cmake @@ -28,12 +28,15 @@ set(PACKAGE_LIBRARIES SimpleImagingLib) set(PACKAGE_PATH /opt/pleora/ebus_sdk/Ubuntu-x86_64) -set(PACKAGE_PATH_GENI /opt/pleora/ebus_sdk/Ubuntu-x86_64/lib/genicam/bin/Linux64_x64) +set(PACKAGE_PATH_GENI /opt/pleora/ebus_sdk/Ubuntu-x86_64/lib/genicam/bin/Linux64_x64) set(ebus-sdk_INCLUDE_DIR "") set(ebus-sdk_INCLUDE_DIR_VAR_NAMES "") foreach(header_file ${PACKAGE_HEADER_FILES}) - find_path(${header_file}_INCLUDE_DIR NAMES ${header_file} PATHS "${PACKAGE_PATH}/include") + find_path( + ${header_file}_INCLUDE_DIR + NAMES ${header_file} + PATHS "${PACKAGE_PATH}/include") list(APPEND ebus-sdk_INCLUDE_DIR ${${header_file}_INCLUDE_DIR}) list(APPEND ebus-sdk_INCLUDE_DIR_VAR_NAMES ${header_file}_INCLUDE_DIR) endforeach() @@ -41,11 +44,17 @@ endforeach() set(ebus-sdk_LIBRARIES "") set(ebus-sdk_LIBRARY_VAR_NAMES "") foreach(library ${PACKAGE_LIBRARIES}) - find_library(${library}_LIBRARY NAMES ${library} PATHS "${PACKAGE_PATH}/lib" "${PACKAGE_PATH_GENI}") + find_library( + ${library}_LIBRARY + NAMES ${library} + PATHS "${PACKAGE_PATH}/lib" "${PACKAGE_PATH_GENI}") list(APPEND ebus-sdk_LIBRARIES ${${library}_LIBRARY}) list(APPEND ebus-sdk_LIBRARY_VAR_NAMES ${library}_LIBRARY) endforeach() include(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(ebus-sdk FOUND_VAR ebus-sdk_FOUND REQUIRED_VARS ${ebus-sdk_INCLUDE_DIR_VAR_NAMES} ${ebus-sdk_LIBRARY_VAR_NAMES}) +find_package_handle_standard_args( + ebus-sdk + FOUND_VAR ebus-sdk_FOUND + REQUIRED_VARS ${ebus-sdk_INCLUDE_DIR_VAR_NAMES} ${ebus-sdk_LIBRARY_VAR_NAMES}) mark_as_advanced(${ebus-sdk_INCLUDE_DIR_VAR_NAMES} ${ebus-sdk_LIBRARY_VAR_NAMES}) diff --git a/mrt_cmake_modules/cmake/Modules/Findgtest.cmake b/mrt_cmake_modules/cmake/Modules/Findgtest.cmake index 3ec7e2a36cf..c4d854c503a 100644 --- a/mrt_cmake_modules/cmake/Modules/Findgtest.cmake +++ b/mrt_cmake_modules/cmake/Modules/Findgtest.cmake @@ -1,8 +1,8 @@ -if (CATKIN_ENABLE_TESTING) - #just add gtest and gtest_main to link to - #those files are generated during catkin test ny building gtest - set(gtest_INCLUDE_DIRS "") - set(gtest_LIBRARIES gtest) +if(CATKIN_ENABLE_TESTING) + #just add gtest and gtest_main to link to + #those files are generated during catkin test ny building gtest + set(gtest_INCLUDE_DIRS "") + set(gtest_LIBRARIES gtest) else() - message(FATAL_ERROR "CMake script only implemented for gtest as test_depend") + message(FATAL_ERROR "CMake script only implemented for gtest as test_depend") endif() diff --git a/mrt_cmake_modules/cmake/Modules/Findlibgps.cmake b/mrt_cmake_modules/cmake/Modules/Findlibgps.cmake deleted file mode 100644 index ffc2bd275a8..00000000000 --- a/mrt_cmake_modules/cmake/Modules/Findlibgps.cmake +++ /dev/null @@ -1,57 +0,0 @@ -# -# Copyright 2015 Ettus Research LLC -# -# This program is free software: you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation, either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of -# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -# GNU General Public License for more details. -# -# You should have received a copy of the GNU General Public License -# along with this program. If not, see . -# -# - Find libgps -# Find the Gpsd includes and client library -# This module defines -# LIBGPS_INCLUDE_DIR, where to find gps.h -# LIBGPS_LIBRARIES, the libraries needed by a GPSD client. -# LIBGPS_FOUND, If false, do not try to use GPSD. -# also defined, but not for general use are -# LIBGPS_LIBRARY, where to find the GPSD library. - -INCLUDE(FindPkgConfig) -PKG_CHECK_MODULES(PC_GPSD "libgps") - -IF(PC_GPSD_FOUND) - FIND_PATH( - LIBGPS_INCLUDE_DIR - NAMES gps.h - HINTS ${PC_GPSD_INCLUDE_DIR} - ) - - SET( - LIBGPS_NAMES - ${LIBGPS_NAMES} gps - ) - - FIND_LIBRARY( - LIBGPS_LIBRARY - NAMES ${LIBGPS_NAMES} - HINTS ${PC_GPSD_LIBDIR} - ) -ENDIF(PC_GPSD_FOUND) - -# handle the QUIETLY and REQUIRED arguments and set LIBGPS_FOUND to TRUE if -# all listed variables are TRUE -INCLUDE(FindPackageHandleStandardArgs) -FIND_PACKAGE_HANDLE_STANDARD_ARGS(LIBGPS DEFAULT_MSG LIBGPS_LIBRARY LIBGPS_INCLUDE_DIR) - -IF(LIBGPS_FOUND) - SET(LIBGPS_LIBRARIES ${LIBGPS_LIBRARY}) -ENDIF(LIBGPS_FOUND) - -MARK_AS_ADVANCED(LIBGPS_LIBRARY LIBGPS_INCLUDE_DIR) diff --git a/mrt_cmake_modules/cmake/Modules/Findnlopt.cmake b/mrt_cmake_modules/cmake/Modules/Findnlopt.cmake new file mode 100644 index 00000000000..f350786c33a --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/Findnlopt.cmake @@ -0,0 +1,29 @@ +# - Find NLopt +# Find the native NLopt includes and library +# +# nlopt_INCLUDE_DIR - where to find nlopt.h, etc. +# nlopt_LIBRARIES - List of libraries when using nlopt. +# nlopt_FOUND - True if nlopt found. + +if(nlopt_INCLUDE_DIR) + # Already in cache, be silent + set(nlopt_FIND_QUIETLY TRUE) +endif(nlopt_INCLUDE_DIR) + +find_path(nlopt_INCLUDE_DIR nlopt.h) + +set(nlopt_NAMES nlopt nlopt_cxx) +find_library(nlopt_LIBRARY NAMES ${nlopt_NAMES}) + +# handle the QUIETLY and REQUIRED arguments and set nlopt_FOUND to TRUE if +# all listed variables are TRUE +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(nlopt DEFAULT_MSG nlopt_LIBRARY nlopt_INCLUDE_DIR) + +if(nlopt_FOUND) + set(nlopt_LIBRARIES ${nlopt_LIBRARY}) +else(nlopt_FOUND) + set(nlopt_LIBRARIES) +endif(nlopt_FOUND) + +mark_as_advanced(nlopt_LIBRARY nlopt_INCLUDE_DIR) diff --git a/mrt_cmake_modules/cmake/Modules/Findpugixml.cmake b/mrt_cmake_modules/cmake/Modules/Findpugixml.cmake index 08478e75130..0968f527316 100644 --- a/mrt_cmake_modules/cmake/Modules/Findpugixml.cmake +++ b/mrt_cmake_modules/cmake/Modules/Findpugixml.cmake @@ -1,13 +1,8 @@ -find_library(PUGIXML_LIBRARIES - NAMES pugixml -) -find_path(PUGIXML_INCLUDE_DIRS +find_library(PUGIXML_LIBRARIES NAMES pugixml) +find_path( + PUGIXML_INCLUDE_DIRS NAMES pugixml.hpp - PATH_SUFFIXES pugixml -) + PATH_SUFFIXES pugixml) include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(pugixml DEFAULT_MSG - PUGIXML_LIBRARIES - PUGIXML_INCLUDE_DIRS -) +find_package_handle_standard_args(pugixml DEFAULT_MSG PUGIXML_LIBRARIES PUGIXML_INCLUDE_DIRS) diff --git a/mrt_cmake_modules/cmake/Modules/Findrange-v3.cmake b/mrt_cmake_modules/cmake/Modules/Findrange-v3.cmake deleted file mode 100644 index 4c9f9a0b84e..00000000000 --- a/mrt_cmake_modules/cmake/Modules/Findrange-v3.cmake +++ /dev/null @@ -1,9 +0,0 @@ -# Looks for library range-v3. - -find_path(range-v3_INCLUDE_DIR range/v3/all.hpp) - -mark_as_advanced(range-v3_INCLUDE_DIR) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(range-v3 REQUIRED_VARS range-v3_INCLUDE_DIR) - diff --git a/mrt_cmake_modules/cmake/Modules/Findyaml-cpp.cmake b/mrt_cmake_modules/cmake/Modules/Findyaml-cpp.cmake deleted file mode 100644 index 99a2ed1540b..00000000000 --- a/mrt_cmake_modules/cmake/Modules/Findyaml-cpp.cmake +++ /dev/null @@ -1,34 +0,0 @@ -# - Find libyaml-cpp -# Find the YAML C++ Library -# -# Using libyaml-cpp: -# find_package(yaml-cpp REQUIRED) -# include_directories(${yaml-cpp_INCLUDE_DIRS}) -# add_executable(foo foo.cc) -# target_link_libraries(foo ${yaml-cpp_LIBRARIES}) -# This module sets the following variables: -# yaml-cpp_FOUND - set to true if the library is found -# yaml-cpp_INCLUDE_DIRS - list of required include directories -# yaml-cpp_LIBRARIES - list of libraries to be linked - -find_package(PkgConfig REQUIRED) -pkg_check_modules(YAML-CPP REQUIRED yaml-cpp) -find_path(YAML-CPP_INCLUDE_DIRECTORY - NAMES yaml.h - PATHS ${YAML-CPP_INCLUDE_DIRS} /usr/include/yaml-cpp -) -find_library(YAML-CPP_LIBRARY - NAMES yaml-cpp - PATHS ${YAML-CPP_LIBRARY_DIRS}) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(yaml-cpp - FOUND_VAR yaml-cpp_FOUND - REQUIRED_VARS YAML-CPP_LIBRARY YAML-CPP_INCLUDE_DIRECTORY -) - -if (yaml-cpp_FOUND) - set(yaml-cpp_INCLUDE_DIRS ${YAML-CPP_INCLUDE_DIRECTORY}) - set(yaml-cpp_LIBRARIES ${YAML-CPP_LIBRARY}) -endif () -mark_as_advanced(YAML-CPP_INCLUDE_DIRECTORY YAML-CPP_LIBRARY) diff --git a/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake b/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake index fefae9fecc7..7dae89f4d5f 100644 --- a/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake +++ b/mrt_cmake_modules/cmake/Modules/GatherDeps.cmake @@ -5,23 +5,26 @@ endif() #Add "watch" to package.xml. This is achieved by using configure_file. This is not necessary for catkin_make but #if eclipse is used and the make target is used directly -configure_file("${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/package.xml" COPYONLY) +configure_file("${CMAKE_CURRENT_SOURCE_DIR}/package.xml" + "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/package.xml" COPYONLY) -#use find package catkin here so that the cmake variable CATKIN_ENV is set. This variable is used -#so that rospack can find the packages in this workspace -find_package(catkin REQUIRED) - -#gather dependencies from package.xml. The command runs in python3 with the ros environemnt +#gather dependencies from package.xml. The command runs in python with the ros environemnt #variable set. This is used, because the python script is calling some ros tools to distinguish #between catkin and non catkin packages. +set(_gather_cmd + ${MRT_CMAKE_ENV} ${PYTHON_EXECUTABLE} ${MRT_CMAKE_MODULES_ROOT_PATH}/scripts/generate_cmake_dependency_file.py + "${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${MRT_CMAKE_MODULES_ROOT_PATH}/yaml/cmake.yaml" + "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake") execute_process( - COMMAND sh ${CATKIN_ENV} /usr/bin/python3 ${MCM_ROOT}/scripts/generate_cmake_dependency_file.py "${CMAKE_CURRENT_SOURCE_DIR}/package.xml" "${MCM_ROOT}/yaml/base.yaml" "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake" - RESULT_VARIABLE _GEN_DEPS_RES_ ERROR_VARIABLE _GEN_DEPS_ERROR_) + COMMAND ${_gather_cmd} + RESULT_VARIABLE _GEN_DEPS_RES_ + ERROR_VARIABLE _GEN_DEPS_ERROR_) -if (NOT _GEN_DEPS_RES_ EQUAL 0) - message(FATAL_ERROR "Gather depenencies faild: ${_GEN_DEPS_ERROR_}") +if(NOT _GEN_DEPS_RES_ EQUAL 0) + message(FATAL_ERROR "Gather depenencies failed: ${_GEN_DEPS_ERROR_}") +elseif(_GEN_DEPS_ERROR_) + message(WARNING ${_GEN_DEPS_ERROR_}) endif() #include the generated variable cmake file include("${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/auto_dep_vars.cmake") - diff --git a/mrt_cmake_modules/cmake/Modules/MRTCoverage.cmake b/mrt_cmake_modules/cmake/Modules/MRTCoverage.cmake deleted file mode 100644 index 3d891f30ed1..00000000000 --- a/mrt_cmake_modules/cmake/Modules/MRTCoverage.cmake +++ /dev/null @@ -1,168 +0,0 @@ -# Copyright (c) 2012 - 2015, Lars Bilke -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without modification, -# are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, this -# list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# 3. Neither the name of the copyright holder nor the names of its contributors -# may be used to endorse or promote products derived from this software without -# specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR -# ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -# (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON -# ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -# -# -# -# 2012-01-31, Lars Bilke -# - Enable Code Coverage -# -# 2013-09-17, Joakim Söderberg -# - Added support for Clang. -# - Some additional usage instructions. -# -# USAGE: - -# 0. (Mac only) If you use Xcode 5.1 make sure to patch geninfo as described here: -# http://stackoverflow.com/a/22404544/80480 -# -# 1. Copy this file into your cmake modules path. -# -# 2. Add the following line to your CMakeLists.txt: -# INCLUDE(CodeCoverage) -# -# 3. Set compiler flags to turn off optimization and enable coverage: -# SET(CMAKE_CXX_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") -# SET(CMAKE_C_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") -# -# 3. Use the function SETUP_TARGET_FOR_COVERAGE to create a custom make target -# which runs your test executable and produces a lcov code coverage report: -# Example: -# SETUP_TARGET_FOR_COVERAGE( -# my_coverage_target # Name for custom target. -# test_driver # Name of the test driver executable that runs the tests. -# # NOTE! This should always have a ZERO as exit code -# # otherwise the coverage generation will not complete. -# coverage # Name of output directory. -# ) -# -# 4. Build a Debug build: -# cmake -DCMAKE_BUILD_TYPE=Debug .. -# make -# make my_coverage_target -# -# - -# Check prereqs -FIND_PROGRAM( GCOV_PATH gcov ) -FIND_PROGRAM( LCOV_PATH lcov ) -FIND_PROGRAM( GENHTML_PATH genhtml ) -if("${CMAKE_CXX_COMPILER_VERSION}" VERSION_GREATER 8) - # lcov is unreliable above gcc 8 - FIND_PROGRAM( GCOVR_PATH gcovr PATHS ${CMAKE_SOURCE_DIR}/tests) -endif() - -IF(NOT GCOV_PATH) - MESSAGE(FATAL_ERROR "gcov not found! Aborting...") -ENDIF() # NOT GCOV_PATH - -IF("${CMAKE_CXX_COMPILER_ID}" MATCHES "(Apple)?[Cc]lang") - IF("${CMAKE_CXX_COMPILER_VERSION}" VERSION_LESS 3) - MESSAGE(FATAL_ERROR "Clang version must be 3.0.0 or greater! Aborting...") - ENDIF() -ELSEIF(NOT CMAKE_COMPILER_IS_GNUCXX) - MESSAGE(FATAL_ERROR "Compiler is not GNU gcc! Aborting...") -ENDIF() # CHECK VALID COMPILER - -IF ( NOT CMAKE_BUILD_TYPE STREQUAL "Debug") - MESSAGE( WARNING "Code coverage results with an optimized (non-Debug) build may be misleading" ) -ENDIF() # NOT CMAKE_BUILD_TYPE STREQUAL "Debug" - -function(_setup_lcov_target _targetname _outputname _init_targetname) - SET(coverage_baseline "${CMAKE_CURRENT_BINARY_DIR}/${_outputname}.baseline") - SET(coverage_info "${CMAKE_CURRENT_BINARY_DIR}/${_outputname}.info") - SET(coverage_combined "${coverage_info}.combined") - SET(coverage_cleaned "${coverage_info}.cleaned") - - message(STATUS "Adding initial coverage target ${_init_targetname}") - ADD_CUSTOM_TARGET(${_init_targetname} - COMMAND ${LCOV_PATH} --directory ${CMAKE_CURRENT_BINARY_DIR} --capture --initial --output-file ${coverage_baseline} -q - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} - COMMENT "Initializing code coverage counters" - ) - - if(NOT GENHTML_PATH) - MESSAGE(FATAL_ERROR "genhtml not found! Aborting...") - ENDIF() # NOT GENHTML_PATH - - # Setup target - message(STATUS "Adding postprocess coverage target ${_targetname}") - - ADD_CUSTOM_TARGET(${_targetname} - # Capturing lcov counters and generating report - COMMAND ${LCOV_PATH} --directory ${CMAKE_CURRENT_BINARY_DIR} --capture --output-file ${coverage_info} -q - COMMAND ${LCOV_PATH} -a ${coverage_info} -a ${coverage_baseline} --output-file ${coverage_combined} -q || true - COMMAND ${LCOV_PATH} --extract ${coverage_combined} '${CMAKE_CURRENT_LIST_DIR}/*' --output-file ${coverage_cleaned} -q || true - COMMAND ${GENHTML_PATH} -o ${_outputname} ${coverage_cleaned} || true - COMMAND ${CMAKE_COMMAND} -E remove ${coverage_info} ${coverage_combined} - - # Cleanup lcov - COMMAND ${LCOV_PATH} --directory ${CMAKE_CURRENT_BINARY_DIR} --zerocounters -q - - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} - COMMENT "Processing code coverage counters and generating report." - ) -endfunction() - - -function(_setup_gcovr_target _targetname _outputname _init_targetname) - message(STATUS "Adding coverage target ${_targetname} using gcovr") - if(ENV{MRT_MIN_COVERAGE}) - set(MIN_COVERAGE "--fail-under-line $ENV{MRT_MIN_COVERAGE} ") - endif() - ADD_CUSTOM_TARGET(${_targetname} - COMMAND mkdir -p ${_outputname} - COMMAND if [ ! -z "$$MRT_MIN_COVERAGE" ]; then export MIN_COVERAGE=\"--fail-under-line $$MRT_MIN_COVERAGE\"$ fi$ ${GCOVR_PATH} -j 4 -s -r ${CMAKE_CURRENT_LIST_DIR} $$MIN_COVERAGE --object-directory ${CMAKE_CURRENT_BINARY_DIR} --html-details --html-title "${PROJECT_NAME} coverage" -o ${_outputname}/index.html || (>&2 echo "Coverage $$MRT_MIN_COVERAGE% not reached!" && false) - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} - COMMENT "Processing code coverage counters and generating report." - ) -endfunction() - -# Param _targetname The name of new the custom make target to run _after_ the executables -# Param _outputname lcov output is generated as _outputname.info -# HTML report is generated in _outputname/index.html -# Param _init_targetname The name of the target to run _before_ the executables -FUNCTION(SETUP_TARGET_FOR_COVERAGE _targetname _outputname _init_targetname) - - IF(NOT LCOV_PATH AND NOT GCOVR_PATH) - MESSAGE(FATAL_ERROR "lcov not found! Aborting...") - ENDIF() # NOT LCOV_PATH - - if(LCOV_PATH) - _setup_lcov_target(${_targetname} ${_outputname} ${_init_targetname}) - else() - _setup_gcovr_target(${_targetname} ${_outputname} ${_init_targetname}) - endif() - - # Show info where to find the report - ADD_CUSTOM_COMMAND(TARGET ${_targetname} POST_BUILD - COMMAND ; - COMMENT "Open ${CMAKE_CURRENT_BINARY_DIR}/${_outputname}/index.html in your browser to view the coverage report." - ) - -ENDFUNCTION() # SETUP_TARGET_FOR_COVERAGE - diff --git a/mrt_cmake_modules/cmake/Modules/MrtParamGenerator.cmake b/mrt_cmake_modules/cmake/Modules/MrtParamGenerator.cmake deleted file mode 100644 index f9a59188d22..00000000000 --- a/mrt_cmake_modules/cmake/Modules/MrtParamGenerator.cmake +++ /dev/null @@ -1,23 +0,0 @@ -macro(generate_parameter_files) - if (${PROJECT_NAME}_CATKIN_PACKAGE) - message(FATAL_ERROR "generate_mrt_ros_parameters() must be called before catkin_package() in project '${PROJECT_NAME}'") - endif () - - # ensure that package destination variables are defined - catkin_destinations() - find_package(rosparam_handler) - - - - # Gather all files - file(GLOB MRT_CFG_FILES RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "cfg/*.mrtcfg") - file(GLOB DYN_RECONF_CFG_FILES RELATIVE "${CMAKE_CURRENT_LIST_DIR}" "cfg/*.cfg") - set(PARAM_FILES ${MRT_CFG_FILES} ${DYN_RECONF_CFG_FILES}) - # generate dynamic reconfigure files - if(rosparam_handler_FOUND_CATKIN_PROJECT) - generate_ros_parameter_files(${PARAM_FILES}) - else() - message(FATAL_ERROR "Dependency to rosparam_handler is missing. Can not build config files for project ${PROJECT_NAME}") - endif() - -endmacro() diff --git a/mrt_cmake_modules/cmake/Modules/MrtTesting.cmake b/mrt_cmake_modules/cmake/Modules/MrtTesting.cmake new file mode 100644 index 00000000000..2284ab870f2 --- /dev/null +++ b/mrt_cmake_modules/cmake/Modules/MrtTesting.cmake @@ -0,0 +1,304 @@ +function(mrt_init_testing) + # initialize target structure + if(TARGET tests_${PROJECT_NAME}) + return() # mrt_init_testing was already called + endif() + if(NOT TARGET tests) + if(NOT ROS_VERSION EQUAL 1) + # out of ros1 tests are always built by default, so we add it to the all target + set(all ALL) + endif() + add_custom_target(tests ${all}) + endif() + if(NOT TARGET run_tests) + # usually catkin does that for us + add_custom_target(run_tests) + enable_testing() + endif() + if(NOT TARGET run_tests_${PROJECT_NAME}) + add_custom_target(run_tests_${PROJECT_NAME}) + add_dependencies(run_tests run_tests_${PROJECT_NAME}) + endif() + add_custom_target(tests_${PROJECT_NAME}) + + # make sure all targets within this project are built first (also messages and python binaries) + set(_combined_deps ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_MRT_TARGETS}) + if(_combined_deps) + add_dependencies(tests ${_combined_deps}) + endif() + set(_test_results ${CMAKE_BINARY_DIR}/test_results) + if(DEFINED CATKIN_TEST_RESULTS_DIR) + # support overriding to be compatible with catkin + set(_test_results ${CATKIN_TEST_RESULTS_DIR}) + endif() + set(MRT_TEST_RESULTS_DIR + ${_test_results} + CACHE INTERNAL "basedir where test xmls will be written (in subfolder )") + if(MRT_ENABLE_COVERAGE) + # these variables are global (for compability with toplevel cmakelists) + # this also means they might still be in the cache, even if mrt_enable_coverage is now different + set(MRT_COVERAGE_DIR + ${CMAKE_BINARY_DIR}/mrt_coverage + CACHE INTERNAL "") + set(coverage_dir ${MRT_COVERAGE_DIR}) + message(STATUS "Outputting coverage to ${coverage_dir}") + endif() + if(NOT TARGET init_tests) + set(pre_test_cmd + ${PYTHON_EXECUTABLE} + ${MRT_CMAKE_MODULES_ROOT_PATH}/scripts/init_coverage.py + ${PROJECT_NAME} + ${CMAKE_BINARY_DIR} + ${CMAKE_CURRENT_LIST_DIR} + ${MRT_TEST_RESULTS_DIR}/${PROJECT_NAME} + ${coverage_dir}) + add_custom_target( + init_tests + COMMAND ${pre_test_cmd} + COMMENT "Initializing unittests" + VERBATIM) + if(MRT_ENABLE_COVERAGE AND MRT_ENABLE_COVERAGE GREATER 1) + set(show_result "--show") + endif() + set(post_test_cmd + ${PYTHON_EXECUTABLE} + ${MRT_CMAKE_MODULES_ROOT_PATH}/scripts/eval_coverage.py + ${CMAKE_SOURCE_DIR} + ${CMAKE_BINARY_DIR} + ${MRT_TEST_RESULTS_DIR} + ${coverage_dir} + ${show_result}) + if(NOT MRT_NO_FAIL_ON_TESTS) + set(fail_on_test --fail_on_test) + endif() + add_custom_target( + eval_tests + COMMAND ${post_test_cmd} --coverage_stderr ${fail_on_test} + COMMENT "Evaluating unittest results" + VERBATIM) + add_dependencies(init_tests tests) + add_dependencies(eval_tests init_tests) + add_dependencies(run_tests eval_tests) + + if(CMAKE_VERSION VERSION_GREATER "3.12") + include(ProcessorCount) + ProcessorCount(cores) + set(make_jobs "--parallel ${cores}") + endif() + + # configure ctest + string(REPLACE ";" " " pre_test_cmd "${pre_test_cmd}") + string(REPLACE ";" " " post_test_cmd "${post_test_cmd}") + add_test(build_tests ${CATKIN_ENV} bash -c + "\"${CMAKE_COMMAND}\" --build ${CMAKE_BINARY_DIR} ${make_jobs} --target tests && ${pre_test_cmd}") + configure_file(${MCM_TEMPLATE_DIR}/CTestCustom.cmake.in "${CMAKE_CURRENT_BINARY_DIR}/CTestCustom.cmake" @ONLY) + configure_file(${MCM_TEMPLATE_DIR}/CTestCustom.cmake.in "${CMAKE_BINARY_DIR}/CTestCustom.cmake" @ONLY) + configure_file(${CMAKE_ROOT}/Modules/DartConfiguration.tcl.in + ${CMAKE_CURRENT_BINARY_DIR}/CTestConfiguration.ini) + configure_file(${CMAKE_ROOT}/Modules/DartConfiguration.tcl.in ${PROJECT_BINARY_DIR}/CTestConfiguration.ini) + endif() + # add the dependencies between targets + add_dependencies(tests tests_${PROJECT_NAME}) +endfunction() + +# All paths have to be absolute +function(_mrt_run_test target_name working_dir result_xml_path) + cmake_parse_arguments(ARG "REDIRECT_STDERR" "COVERAGE_DIR" "COMMAND" ${ARGN}) + set(cmd ${ARG_COMMAND}) + set(working_dir_arg "--working-dir" ${working_dir}) + if(ARG_COVERAGE_DIR) + set(coverage_dir_arg "--coverage-dir" ${ARG_COVERAGE_DIR}) + endif() + if(ARG_REDIRECT_STDERR) + set(redirect_arg "--redirect-stderr") + endif() + + set(run_test_cmd + ${CATKIN_ENV} + ${PYTHON_EXECUTABLE} + ${MRT_CMAKE_MODULES_ROOT_PATH}/scripts/run_test.py + ${result_xml_path} + ${working_dir_arg} + ${coverage_dir_arg} + ${redirect_arg}) + + # for ctest the command needs to return non-zero if any test failed + set(run_test_cmd_fail ${run_test_cmd} "--return-code" ${cmd}) + add_test(NAME ${target_name} COMMAND ${run_test_cmd_fail}) + + # dependency for ctest to build the tests first + set_tests_properties(${target_name} PROPERTIES DEPENDS build_tests) + + # for the run_tests target the command needs to return zero so that testing is not aborted + add_custom_target( + run_test_${target_name} + COMMAND ${run_test_cmd} ${cmd} + VERBATIM) + add_dependencies(eval_tests run_test_${target_name}) + add_dependencies(run_test_${target_name} init_tests) +endfunction() + +function(_mrt_create_executable_gtest target file) + if(NOT TARGET gtest_main) + # gtest_vendor is used on ros2 and should be preferred if available + find_package(gtest_vendor QUIET) + # add googletest as subdir to this project + find_file( + gtest_sources "gtest.cc" + PATH_SUFFIXES "../src/googletest/googletest/src" "googletest/googletest/src" "src" + HINTS ${CMAKE_CURRENT_LIST_DIR} ${MRT_GTEST_DIR} ${gtest_vendor_BASE_DIR}) + if(NOT gtest_sources) + message(FATAL_ERROR "Failed to find the source files of googletest!") + endif() + get_filename_component(gtest_src ${gtest_sources} PATH) + get_filename_component(gtest_base ${gtest_src} PATH) + if(NOT gtest_vendor_BASE_DIR) + get_filename_component(gtest_base ${gtest_base} PATH) + endif() + if(NOT EXISTS ${gtest_base}/CMakeLists.txt) + message(FATAL_ERROR "Failed to find googletest base directory at: ${gtest_base}!") + endif() + if(NOT ROS_VERSION EQUAL 2) + set(exclude EXCLUDE_FROM_ALL) # ament has trouble if library targets are not built in the all target + endif() + # by default, googletest installs itself too. We have to disable this behaviour. + set(INSTALL_GTEST + OFF + CACHE BOOL "Enable installation of googletest") + add_subdirectory(${gtest_base} ${CMAKE_CURRENT_BINARY_DIR}/gtest ${exclude}) + if(NOT TARGET gtest_main) + message(FATAL_ERROR "Gtest seems not to build gtest_main!") + endif() + if(gtest_vendor_BASE_DIR) + # no, gtest_vendor doesn't set its own include dir *sigh* + target_include_directories(gtest_main BEFORE PUBLIC "${gtest_vendor_BASE_DIR}/include") + endif() + endif() + message(STATUS "Creating gtest '${target}' from ${file}") + add_executable(${target} ${file}) + set_target_properties(${target} PROPERTIES EXCLUDE_FROM_ALL TRUE) + target_link_libraries(${target} PRIVATE gtest_main) +endfunction() + +function(mrt_add_gtest target file) + mrt_init_testing() + cmake_parse_arguments(ARG "" "WORKING_DIRECTORY" "" ${ARGN}) + _mrt_create_executable_gtest(${target} ${file}) + add_dependencies(tests_${PROJECT_NAME} ${target}) + set(result_xml_path ${MRT_TEST_RESULTS_DIR}/${PROJECT_NAME}/gtest-${target}.xml) + set(cmd "$ --gtest_color=yes --gtest_output=xml:${result_xml_path}") + if(MRT_ENABLE_COVERAGE) + set(coverage_arg COVERAGE_DIR ${MRT_COVERAGE_DIR}/${target}) + endif() + _mrt_run_test( + ${target} ${ARG_WORKING_DIRECTORY} ${result_xml_path} + ${coverage_arg} + COMMAND ${cmd}) +endfunction() + +function(mrt_add_rostest target launch_file) + mrt_init_testing() + get_filename_component(test_name ${launch_file} NAME_WE) + set(result_xml_path "${MRT_TEST_RESULTS_DIR}/${PROJECT_NAME}/rostest_${test_name}.xml") + find_program(ROSTEST_EXE rostest) + if(NOT ROSTEST_EXE) + message(FATAL_ERROR "rostest not found! Aborting...") + endif() + set(cmd + "${PYTHON_EXECUTABLE} ${ROSTEST_EXE} --pkgdir=${PROJECT_SOURCE_DIR} --package=${PROJECT_NAME} --results-filename ${test_name}.xml --results-base-dir \"${MRT_TEST_RESULTS_DIR}\" ${CMAKE_CURRENT_LIST_DIR}/${launch_file}" + ) + if(MRT_ENABLE_COVERAGE) + set(coverage_arg COVERAGE_DIR ${MRT_COVERAGE_DIR}/${target}) + endif() + + get_filename_component(test_name ${launch_file} NAME_WE) + # rostest appends "rostest-" to the file name. This behaviour is apparently undocumented... + set(result_xml_path "${MRT_TEST_RESULTS_DIR}/${PROJECT_NAME}/rostest-${test_name}.xml") + _mrt_run_test( + ${target} ${CMAKE_CURRENT_BINARY_DIR} ${result_xml_path} + ${coverage_arg} + COMMAND ${cmd}) +endfunction() + +function(mrt_add_rostest_gtest target launch_file cpp_file) + mrt_init_testing() + _mrt_create_executable_gtest(${target} ${cpp_file}) + add_dependencies(tests_${PROJECT_NAME} ${target}) + mrt_add_rostest(${target} ${launch_file}) +endfunction() + +function(_mrt_add_nosetests_impl folder) + find_program( + NOSETESTS + NAMES "nosetests${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" + "nosetests-${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" "nosetests${PYTHON_VERSION_MAJOR}" + "nosetests-${PYTHON_VERSION_MAJOR}" "nosetests") + if(NOSETESTS) + message(STATUS "Using Python nosetests: ${NOSETESTS}") + else() + if("${PYTHON_VERSION_MAJOR}" STREQUAL "3") + message(STATUS "nosetests not found, Python tests can not be run (try installing package 'python3-nose')") + else() + message(STATUS "nosetests not found, Python tests can not be run (try installing package 'python-nose')") + endif() + return() + endif() + + cmake_parse_arguments(_nose "" "TIMEOUT" "DEPENDS" ${ARGN}) + if(NOT _nose_TIMEOUT) + set(_nose_TIMEOUT 60) + endif() + if(NOT _nose_TIMEOUT GREATER 0) + message(FATAL_ERROR "nosetests() TIMEOUT argument must be a valid number of seconds greater than zero") + endif() + + set(path ${CMAKE_CURRENT_LIST_DIR}/${folder}) + + # strip PROJECT_SOURCE_DIR and PROJECT_BINARY_DIR prefix from output_file_name + set(output_file_name ${folder}) + string(REPLACE "/" "." output_file_name ${output_file_name}) + string(REPLACE ":" "." output_file_name ${output_file_name}) + + set(test_name nosetests-${PROJECT_NAME}-${output_file_name}) + message(STATUS "Adding nosetest ${test_name}") + # check if coverage reports are being requested + if(MRT_ENABLE_COVERAGE) + # we dont want to enable coverage when there are only python rostests around (ie executable python files) + # because these are not executed by nosetests. + mrt_glob_files(has_init_py src/${PROJECT_NAME}/__init__.py) + mrt_glob_files(has_test_py ${folder}/*.py) + execute_process(COMMAND find ${path} -name *.py -type f -not -executable OUTPUT_VARIABLE test_py_files) + execute_process(COMMAND find ${path} -name *.py -type f -executable OUTPUT_VARIABLE exec_py_files) + if(has_init_py AND (test_py_files OR NOT exec_py_files)) + find_program(PY_COVERAGE NAMES "python-coverage${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" + "python-coverage${PYTHON_VERSION_MAJOR}" "python-coverage") + if(PY_COVERAGE) + message(STATUS "Enabling coverage for python tests") + set(covarg + " --with-coverage --cover-erase --cover-inclusive --cover-package=src/${PROJECT_NAME} --cover-xml --cover-xml-file=\"${MRT_COVERAGE_DIR}/${test_name}_coverage.xml\"" + ) + endif() + endif() + set(cover_dir_arg COVERAGE_DIR ${MRT_COVERAGE_DIR}/${test_name}) + endif() + + set(output_path ${MRT_TEST_RESULTS_DIR}/${PROJECT_NAME}) + set(tests "--where=${path}") + set(result_xml_path ${output_path}/${test_name}.xml) + set(cmd + "${NOSETESTS} -P --process-timeout=${_nose_TIMEOUT} ${tests} --with-xunit --xunit-file=\"${result_xml_path}\" ${covarg}" + ) + _mrt_run_test( + ${test_name} ${CMAKE_CURRENT_LIST_DIR} ${result_xml_path} + ${coverage_arg} + COMMAND ${cmd} ${cover_dir_arg} + REDIRECT_STDERR) + if(ARG_DEPENDS) + add_dependencies(tests_{PROJECT_NAME} ${ARG_DEPENDS}) + endif() + # make sure python api is compiled first + if(${PROJECT_NAME}_PYTHON_API_TARGET) + add_dependencies(tests_${PROJECT_NAME} ${${PROJECT_NAME}_PYTHON_API_TARGET}) + set_tests_properties(${test_name} PROPERTIES DEPENDS build_tests) + endif() +endfunction() diff --git a/mrt_cmake_modules/cmake/Modules/UseMrtStdCompilerFlags.cmake b/mrt_cmake_modules/cmake/Modules/UseMrtStdCompilerFlags.cmake index ae676e097d6..595e3072ae5 100644 --- a/mrt_cmake_modules/cmake/Modules/UseMrtStdCompilerFlags.cmake +++ b/mrt_cmake_modules/cmake/Modules/UseMrtStdCompilerFlags.cmake @@ -1,156 +1,78 @@ -include(CheckCXXCompilerFlag) - -#Require C++14 -if (CMAKE_VERSION VERSION_LESS "3.1") - CHECK_CXX_COMPILER_FLAG("-std=c++14" Cpp14CompilerFlag) - if (${Cpp14CompilerFlag}) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") - set(CMAKE_CXX_STANDARD 14) - elseif(CMAKE_CXX_COMPILER_ID STREQUAL "MSVC" AND NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS "17") - set(CMAKE_CXX_STANDARD_REQUIRED ON) - #no additional flag is required - else() - message(FATAL_ERROR "Compiler does not have c++14 support. Use at least g++4.9 or Visual Studio 2013 and newer.") - endif() -elseif (CMAKE_VERSION VERSION_LESS "3.8") - # c++17 is not supported in cmake 3.7 and earlier - set(CMAKE_CXX_STANDARD 14) - set(CMAKE_CXX_STANDARD_REQUIRED ON) -else() - # we dont require it since compilers might still support only 14 - set(CMAKE_CXX_STANDARD 17) -endif () - -# use gold linker -set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fuse-ld=gold") -set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -fuse-ld=gold") - -# Add _DEBUG and _GLIBCXX_ASSERTIONS for debug configuration. This enables e.g. assertions in OpenCV and the STL. -if (CMAKE_VERSION VERSION_GREATER "3.12") - add_compile_definitions($<$:_DEBUG> $<$:_GLIBCXX_ASSERTIONS>) -endif() - -# Add support for std::filesystem. For GCC version <= 8 one needs to link against -lstdc++fs. -link_libraries($<$,$,9.0>>:stdc++fs>) +# this file creates the target ${PROJECT_NAME}_${PROJECT_NAME}_compiler_flags and ${PROJECT_NAME}_${PROJECT_NAME}_private_compiler_flags that will be used by all targets created by mrt_cmake_modules. It also sets some basic configurations that generally make sens with cmake and ROS. # export compile commands -if(${CMAKE_VERSION} VERSION_GREATER "3.5.0") - set(CMAKE_EXPORT_COMPILE_COMMANDS YES) -endif() - -# Select arch flag -if(MRT_ARCH) - if(NOT MRT_ARCH STREQUAL "None" AND NOT MRT_ARCH STREQUAL "none") - set(_arch "${MRT_ARCH}") - endif() -else() - # On X86, sandybridge is the lowest common cpu arch for us - set(_x86_arch_list "i386" "amd64" "AMD64" "x86_64" "i686" "x86" "x64" "EM64T") +set(CMAKE_EXPORT_COMPILE_COMMANDS YES) - list(FIND _x86_arch_list ${CMAKE_SYSTEM_PROCESSOR} _index) +# default to building shared libraries. This can be changed by passing "-DBUILD_SHARED_LIBS=Off" to cmake. +option(BUILD_SHARED_LIBS "Build libraries as shared libraries by default." ON) - if(${_index} GREATER -1) - message(STATUS "MRT_ARCH not set and X86 target detected (${CMAKE_SYSTEM_PROCESSOR})") - set(_arch "sandybridge") - endif() +add_library(${PROJECT_NAME}_compiler_flags INTERFACE) +add_library(${PROJECT_NAME}_private_compiler_flags INTERFACE) - unset(_x86_arch_list) - unset(_index) +# At least c++14 is required. This can be increased in a file referenced by MRT_CMAKE_CONFIG_FILE. +if(CMAKE_VERSION VERSION_LESS "3.8") + target_compile_options(${PROJECT_NAME}_compiler_flags INTERFACE -std=c++14) +else() + target_compile_features(${PROJECT_NAME}_compiler_flags INTERFACE cxx_std_14) endif() -if(_arch) - message(STATUS "Setting -march to " ${_arch}) - set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -march=${_arch}") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -march=${_arch}") - unset(_arch) +# Add _DEBUG and _GLIBCXX_ASSERTIONS for debug configuration. This enables e.g. assertions in OpenCV and the STL. +if(CMAKE_VERSION VERSION_GREATER "3.12") + target_compile_definitions(${PROJECT_NAME}_private_compiler_flags INTERFACE $<$:_DEBUG> + $<$:_GLIBCXX_ASSERTIONS>) endif() +# Add support for std::filesystem. For GCC version <= 8 one needs to link against -lstdc++fs. +target_link_libraries(${PROJECT_NAME}_compiler_flags + INTERFACE $<$,$,9.0>>:stdc++fs>) + # add OpenMP if present # it would be great to have this in package.xmls instead, but catkin cannot handle setting the required cmake flags for dependencies find_package(OpenMP) -if (OpenMP_FOUND) - set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") +if(OpenMP_FOUND) + if(TARGET OpenMP::OpenMP_CXX) + target_link_libraries(${PROJECT_NAME}_compiler_flags INTERFACE OpenMP::OpenMP_CXX) + else() + target_compile_options(${PROJECT_NAME}_compiler_flags INTERFACE $<$:${OpenMP_CXX_FLAGS}> + $<$:${OpenMP_C_FLAGS}>) + if(CMAKE_VERSION VERSION_LESS "3.10") + target_link_libraries(${PROJECT_NAME}_compiler_flags INTERFACE ${OpenMP_CXX_FLAGS}) + else() + target_link_libraries( + ${PROJECT_NAME}_compiler_flags INTERFACE $<$:${OpenMP_CXX_FLAGS}> + $<$:${OpenMP_C_FLAGS}>) + endif() + endif() endif() # add gcov flags +set(gcc_like_cxx "$,$>") +set(gcc_cxx "$,$>") +set(gcc_like_c "$,$>") if(MRT_ENABLE_COVERAGE) - include(MRTCoverage) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g --coverage") - set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -g --coverage") -endif() - -# add warning/error flags -# see here for documentation: https://gcc.gnu.org/onlinedocs/gcc/Warning-Options.html -# unused-parameter: ignored because ros_tools usually have unused parameters - -if(MRT_COMPILE_ERROR) - if(MRT_COMPILE_ERROR STREQUAL "all") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=all") - set(MRT_USE_DEFAULT_WERROR_FLAGS FALSE) - elseif(MRT_COMPILE_ERROR STREQUAL "off") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error=all") - set(MRT_USE_DEFAULT_WERROR_FLAGS FALSE) - elseif(MRT_COMPILE_ERROR STREQUAL "auto") - set(MRT_USE_DEFAULT_WERROR_FLAGS TRUE) - else() - message(FATAL_ERROR "Don't know how to handle value '${MRT_COMPILE_ERROR}' in variable MRT_COMPILE_ERROR, must be one of all auto off. Exiting.") - endif() -else() - set(MRT_USE_DEFAULT_WERROR_FLAGS TRUE) -endif() - -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wno-unused-parameter") -if(MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=address -Werror=enum-compare -Werror=format -Werror=nonnull -Werror=return-type -Werror=sequence-point -Werror=strict-aliasing -Werror=switch -Werror=trigraphs -Werror=volatile-register-var") -endif() - -if(CMAKE_COMPILER_IS_GNUCC) - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 5 AND MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=array-bounds=1 -Werror=openmp-simd ") - endif() - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.3) - if(MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=bool-compare -Werror=init-self -Werror=logical-not-parentheses -Werror=memset-transposed-args -Werror=nonnull-compare -Werror=sizeof-pointer-memaccess -Werror=tautological-compare -Werror=uninitialized") - endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-ignored-attributes") # ignored-attributes: ignored because of thousands of eigen 3.3 warnings - endif() - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 7) - if(MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=bool-operation -Werror=memset-elt-size") - endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -faligned-new") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-int-in-bool-context") # no-int-in-bool-context: ignored because of thousands of eigen 3.3 warnings - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-maybe-uninitialized") # This causes some false positives with eigen. - endif() - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 8) - if(MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=catch-value -Werror=missing-attributes -Werror=multistatement-macros -Werror=restrict -Werror=sizeof-pointer-div -Werror=misleading-indentation") - endif() - endif() - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 9) - if(MRT_USE_DEFAULT_WERROR_FLAGS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=pessimizing-move") + target_compile_options(${PROJECT_NAME}_private_compiler_flags INTERFACE $<${gcc_like_cxx}:-g;--coverage> + $<${gcc_like_c}:-g;--coverage>) + if(CMAKE_VERSION VERSION_LESS "3.13") + target_link_libraries(${PROJECT_NAME}_private_compiler_flags INTERFACE --coverage) + else() + target_link_options(${PROJECT_NAME}_private_compiler_flags INTERFACE $<${gcc_like_cxx}:--coverage> + $<${gcc_like_c}:--coverage>) endif() - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-copy") # Too many warnings in Eigen - endif() endif() +# Set ccache basedir if ccache is available to enable cache hits across multiple workspaces. +# But still leave it to the user to activate ccache (e.g. with `export PATH=/usr/lib/ccache:$PATH` in `~/.bashrc`) +find_program(CCACHE_FOUND ccache) +if(CCACHE_FOUND AND CCACHE_BASEDIR) + set(CMAKE_CXX_COMPILER_LAUNCHER CCACHE_BASEDIR=${CCACHE_BASEDIR}) +endif() - -# the following -wall flags are not an error (please update this list): -# - char-subscripts: Might cause false positives in openCV -# - int-in-bool-context: Too many false positives in Eigen 3.3 -# - reorder: Too many errors reported -# - restict: Not part of 7.2 -# - sign-compare: Too many false positives in for-loops -# - strict-overflow: False positives, optimization level dependent -# - unknown-pragmas: Pragmas might be for a different compiler -# - unused-*: Sometimes unused declarations are desired -# - comment: Report errors in vtkMath.h for VTK6. - -#add compiler flags -CHECK_CXX_COMPILER_FLAG("-fdiagnostics-color=auto" FLAG_AVAILABLE) -if (${FLAG_AVAILABLE}) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fdiagnostics-color=auto") +# Include config file if set. This is done last so that the target ${PROJECT_NAME}_compiler_flags can be further modified +# The config file is supposed to contain system-specific configurations (basically like a cmake toolchain file) and personal preferences (e.g. warning options) +if(MRT_CMAKE_CONFIG_FILE) + message(STATUS "MRT CMake configuration file found: ${MRT_CMAKE_CONFIG_FILE}") + include(${MRT_CMAKE_CONFIG_FILE}) +elseif(DEFINED ENV{MRT_CMAKE_CONFIG_FILE}) + message(STATUS "MRT CMake configuration file found: $ENV{MRT_CMAKE_CONFIG_FILE}") + include($ENV{MRT_CMAKE_CONFIG_FILE}) endif() diff --git a/mrt_cmake_modules/cmake/README.md b/mrt_cmake_modules/cmake/README.md new file mode 100644 index 00000000000..eb0db3e508e --- /dev/null +++ b/mrt_cmake_modules/cmake/README.md @@ -0,0 +1,3 @@ +# Contributing cmake find scripts + +Please make sure to format your `FindMyNewLibrary.cmake` files with `cmake-format` from the [cmakelang python package](https://pypi.org/project/cmakelang/), before creating merge requests. diff --git a/mrt_cmake_modules/cmake/Templates/CTestCustom.cmake.in b/mrt_cmake_modules/cmake/Templates/CTestCustom.cmake.in new file mode 100644 index 00000000000..3b22f6e89df --- /dev/null +++ b/mrt_cmake_modules/cmake/Templates/CTestCustom.cmake.in @@ -0,0 +1,6 @@ +# This file configures ctest and has been generated by mrt_cmake_modules. +# Don't change this file, it will be overwritten by the next cmake run. +set(CTEST_CUSTOM_MAXIMUM_PASSED_TEST_OUTPUT_SIZE 0) +set(CTEST_CUSTOM_MAXIMUM_FAILED_TEST_OUTPUT_SIZE 0) +#set(CTEST_CUSTOM_PRE_TEST "@pre_test_cmd@") +set(CTEST_CUSTOM_POST_TEST "@post_test_cmd@") diff --git a/mrt_cmake_modules/cmake/Templates/__init__.py.in b/mrt_cmake_modules/cmake/Templates/__init__.py.in index 88c33c084d0..5a6dd6ab92b 100755 --- a/mrt_cmake_modules/cmake/Templates/__init__.py.in +++ b/mrt_cmake_modules/cmake/Templates/__init__.py.in @@ -1,11 +1,10 @@ # Autogenerated by mrt_cmake_modules for python api -from os.path import dirname, basename, isfile -from glob import glob +from os.path import dirname +from pkgutil import iter_modules # automatically import all files in this module -modules = glob(dirname(__file__)+"/*.so") -__all__ = [ basename(f)[:-3] for f in modules ] +__all__ = [name for _, name, _ in iter_modules([dirname(__file__)])] for module_name in __all__: from importlib import import_module @@ -13,5 +12,3 @@ for module_name in __all__: if len(__all__) == 1: globals().update(module.__dict__) del module -del modules - diff --git a/mrt_cmake_modules/cmake/Templates/mrt_cached_variables.cmake.in b/mrt_cmake_modules/cmake/Templates/mrt_cached_variables.cmake.in deleted file mode 100644 index 898a07a7fb9..00000000000 --- a/mrt_cmake_modules/cmake/Templates/mrt_cached_variables.cmake.in +++ /dev/null @@ -1,7 +0,0 @@ -# this file has been automatically generated from mrt_cmake_modules/cmake/Templates/mrt_cached_variables.cmake.in -# it serves to cache the flags from catkin runs for qtcreator generator runs -set(CMAKE_BUILD_TYPE @CMAKE_BUILD_TYPE@) -set(CMAKE_CXX_FLAGS @CMAKE_CXX_FLAGS@) -set(ENV{CMAKE_PREFIX_PATH} @_ENV_CMAKE_PREFIX_PATH@) -set(MRT_SANITIZER @MRT_SANITIZER@) -set(MRT_SANITIZER_RECOVER @MRT_SANITIZER_RECOVER@) diff --git a/mrt_cmake_modules/cmake/Templates/packageConfig.cmake.in b/mrt_cmake_modules/cmake/Templates/packageConfig.cmake.in new file mode 100644 index 00000000000..ecce0d449a3 --- /dev/null +++ b/mrt_cmake_modules/cmake/Templates/packageConfig.cmake.in @@ -0,0 +1,80 @@ +# File was automatically generated by mrt_cmake_modules +# +# This file exports the following variables: +# @PROJECT_NAME@_LIBRARIES: Library targets that should be linked against +# @PROJECT_NAME@_EXPORTED_TARGETS: As required by catkin +# @PROJECT_NAME@_EXPORTS_TARGETS: To indicate this package exports targets instead of plain libraries + +@PACKAGE_INIT@ + +set(@PROJECT_NAME@_LIBRARIES @_mrt_libraries@) # things that dependend packages should link against + +# catkin wants this. Don't bother with it. +set(@PROJECT_NAME@_EXPORTED_TARGETS) + +# mark this as a catkin project +set(@PROJECT_NAME@_FOUND_CATKIN_PROJECT TRUE) +set(@PROJECT_NAME@_EXPORTS_TARGETS TRUE) + +macro(_init_package_dependencies) + # gets all targets that this package export_depends on and sets var to the name of these targets. + # because this config file might be used recursively we have to be extra careful that variables set here do not affect each other + if(TARGET @PROJECT_NAME@::auto_deps_export) + return() + endif() + if(NOT EXISTS "${CMAKE_CURRENT_LIST_DIR}/auto_dep_vars.cmake") + message(FATAL_ERROR "Project @PROJECT_NAME@ did not export its dependencies properly! No auto_dep file was found.") + endif() + # Resolve deps in the same style they were resolved when this project was built + include("${CMAKE_CURRENT_LIST_DIR}/auto_dep_vars.cmake") # sets _@PROJECT_NAME@_EXPORT_PACKAGES_ + + set(@PROJECT_NAME@AutoDeps_PREFIX "@PROJECT_NAME@") + set(@PROJECT_NAME@AutoDeps_NO_CATKIN_EXPORT TRUE) # disable variable export because catkin is not listening here + if(NOT mrt_cmake_modules_FOUND) + # We need the mrt_cmake_modules because they provide extra CMake Modules for finding thirdparty stuff + find_package(mrt_cmake_modules REQUIRED) + endif() + find_package(@PROJECT_NAME@AutoDeps REQUIRED + COMPONENTS ${_@PROJECT_NAME@_EXPORT_PACKAGES_} + PATHS ${CMAKE_CURRENT_LIST_DIR} NO_DEFAULT_PATH + ) + if(NOT OpenMP_FOUND) + find_package(OpenMP) # openmp is by default always a dependency + endif() + unset(@PROJECT_NAME@AutoDeps_PREFIX) + unset(@PROJECT_NAME@AutoDeps_NO_CATKIN_EXPORT) +endmacro() + +if(@PROJECT_NAME@_LIBRARIES) + _init_package_dependencies() +endif() + +# add the targets +if(EXISTS "${CMAKE_CURRENT_LIST_DIR}/@PROJECT_NAME@Targets.cmake") + include("${CMAKE_CURRENT_LIST_DIR}/@PROJECT_NAME@Targets.cmake") +endif() + +# add dependencies to other things generated by this package +set(@PROJECT_NAME@_targets @_mrt_targets@) +if(@PROJECT_NAME@_targets AND NOT TARGET @PROJECT_NAME@::mrt_exported_targets) + set(namespaced_exported_targets) + foreach(t ${@PROJECT_NAME@_targets}) + if(NOT TARGET ${target}) + add_library(@PROJECT_NAME@::${t} INTERFACE IMPORTED) + list(APPEND namespaced_exported_targets @PROJECT_NAME@::${t}) + else() + list(APPEND namespaced_exported_targets ${t}) + endif() + endforeach() + add_library(@PROJECT_NAME@::mrt_exported_targets INTERFACE IMPORTED) + add_dependencies(@PROJECT_NAME@::mrt_exported_targets ${namespaced_exported_targets}) + list(APPEND @PROJECT_NAME@_LIBRARIES @PROJECT_NAME@::mrt_exported_targets) + unset(namespaced_exported_targets) +endif() + +set(@PROJECT_NAME@_EXTRAS_FILE @_mrt_extras_file@) +if(@PROJECT_NAME@_EXTRAS_FILE) + include(${CMAKE_CURRENT_LIST_DIR}/${@PROJECT_NAME@_EXTRAS_FILE}) +endif() +unset(@PROJECT_NAME@_EXTRAS_FILE) +unset(@PROJECT_NAME@_targets) diff --git a/mrt_cmake_modules/cmake/Templates/python_api_install.py.in b/mrt_cmake_modules/cmake/Templates/python_api_install.py.in index 2166758626a..e4e5060ecec 100755 --- a/mrt_cmake_modules/cmake/Templates/python_api_install.py.in +++ b/mrt_cmake_modules/cmake/Templates/python_api_install.py.in @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python # this file is taken and converted from a bash script from catkin to correctly install python modules import os import sys diff --git a/mrt_cmake_modules/cmake/Templates/setup.py.in b/mrt_cmake_modules/cmake/Templates/setup.py.in index 70b30d5d6a5..b244c55fc19 100644 --- a/mrt_cmake_modules/cmake/Templates/setup.py.in +++ b/mrt_cmake_modules/cmake/Templates/setup.py.in @@ -1,7 +1,7 @@ ## THIS FILE HAS BEEN AUTOGENERATED FOR USE WITH CATKIN AND IS NOT SUPPOSED TO BE TRACKED BY GIT! ## DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD -from distutils.core import setup +from setuptools import setup from catkin_pkg.python_setup import generate_distutils_setup # fetch values from package.xml diff --git a/mrt_cmake_modules/cmake/Templates/test_utility.hpp.in b/mrt_cmake_modules/cmake/Templates/test_utility.hpp.in index 3e9ee561724..e5882077dd4 100644 --- a/mrt_cmake_modules/cmake/Templates/test_utility.hpp.in +++ b/mrt_cmake_modules/cmake/Templates/test_utility.hpp.in @@ -19,7 +19,7 @@ namespace @PROJECT_NAME@ { namespace test{ -#ifdef TEST_PATH_USE_STD_FILESYSTEM +#if TEST_PATH_USE_STD_FILESYSTEM static const std::filesystem::path projectRootDir{"@PROJECT_SOURCE_DIR@"}; #else static const boost::filesystem::path projectRootDir{"@PROJECT_SOURCE_DIR@"}; diff --git a/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.em b/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.em deleted file mode 100644 index 53fbadb344f..00000000000 --- a/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.em +++ /dev/null @@ -1,1120 +0,0 @@ -# Generated from: mrt_cmake_modules/cmake/mrt_cmake_modules-extra.cmake.em -if(_MRT_CMAKE_MODULES_EXTRAS_INCLUDED_) - return() -endif() -set(_MRT_CMAKE_MODULES_EXTRAS_INCLUDED_ TRUE) - -# Check cmakelists version -set(_MRT_RECOMMENDED_VERSION 2.1) -if(MRT_PKG_VERSION VERSION_LESS _MRT_RECOMMENDED_VERSION ) - message(WARNING "Current CMakeLists.txt version is less than the recommended version ${_MRT_RECOMMENDED_VERSION}. If you are the maintainer, please update it with\n'mrt maintenance update_cmakelists ${PROJECT_NAME}'.") -endif() - -# Set the cmake install path -@[if DEVELSPACE]@ -# cmake dir in develspace -list(APPEND CMAKE_MODULE_PATH "@(PROJECT_SOURCE_DIR)/cmake/Modules") -@[else]@ -# cmake dir in installspace -list(APPEND CMAKE_MODULE_PATH "@(PKG_CMAKE_DIR)/Modules") -@[end if]@ -set(MCM_ROOT "@(CMAKE_CURRENT_SOURCE_DIR)") - -# care for clang-tidy flags -if(MRT_CLANG_TIDY STREQUAL "check") - set(MRT_CLANG_TIDY_FLAGS "-extra-arg=-Wno-unknown-warning-option" "-header-filter=${PROJECT_SOURCE_DIR}/.*") -elseif(MRT_CLANG_TIDY STREQUAL "fix") - set(MRT_CLANG_TIDY_FLAGS "-extra-arg=-Wno-unknown-warning-option" "-fix-errors" "-header-filter=${PROJECT_SOURCE_DIR}/.*" "-format-style=file") -endif() -if(DEFINED MRT_CLANG_TIDY_FLAGS) - if(${CMAKE_VERSION} VERSION_LESS "3.6.0") - message(WARNING "Using clang-tidy requires at least CMAKE 3.6.0. Please upgrade CMake.") - endif() - find_package(ClangTidy) - if(ClangTidy_FOUND) - message(STATUS "Add clang tidy flags") - set(CMAKE_CXX_CLANG_TIDY "${ClangTidy_EXE}" "${MRT_CLANG_TIDY_FLAGS}") - else() - message(WARNING "Failed to find clang-tidy. Is it installed?") - endif() -endif() - -# cache or load environment for non-catkin build -if( NOT DEFINED CATKIN_DEVEL_PREFIX AND EXISTS "${CMAKE_CURRENT_BINARY_DIR}/mrt_cached_variables.cmake") - message(STATUS "Non-catkin build detected. Loading cached variables from last catkin run.") - include("${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/mrt_cached_variables.cmake") -else() - set(_ENV_CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH}) - configure_file(${MCM_ROOT}/cmake/Templates/mrt_cached_variables.cmake.in "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/mrt_cached_variables.cmake" @@ONLY) -endif() - - -# Set build flags to MRT_SANITIZER_CXX_FLAGS based on the current sanitizer configuration -# based on the configruation in the MRT_SANITIZER variable -if(MRT_SANITIZER STREQUAL "checks") - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.3) - set(MRT_SANITIZER_CXX_FLAGS "-fsanitize=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow" "-fsanitize-recover=alignment") - set(MRT_SANITIZER_EXE_CXX_FLAGS "-fsanitize=address,leak,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow" "-fsanitize-recover=alignment") - set(MRT_SANITIZER_LINK_FLAGS "-static-libasan" "-lubsan") - elseif(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 4.9) - set(MRT_SANITIZER_CXX_FLAGS "-fsanitize=undefined,float-divide-by-zero,float-cast-overflow" "-fsanitize-recover=alignment") - set(MRT_SANITIZER_EXE_CXX_FLAGS "-fsanitize=address,leak,undefined,float-divide-by-zero,float-cast-overflow" "-fsanitize-recover=alignment") - set(MRT_SANITIZER_LINK_FLAGS "-static-libasan" "-lubsan") - endif() - set(MRT_SANITIZER_ENABLED 1) -elseif(MRT_SANITIZER STREQUAL "check_race") - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.3) - set(MRT_SANITIZER_CXX_FLAGS "-fsanitize=thread,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow") - elseif(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 4.9) - set(MRT_SANITIZER_CXX_FLAGS "-fsanitize=thread,undefined,float-divide-by-zero,float-cast-overflow") - endif() - set(MRT_SANITIZER_LINK_FLAGS "-static-libtsan") - set(MRT_SANITIZER_ENABLED 1) -endif() -if(MRT_SANITIZER_ENABLED AND MRT_SANITIZER_RECOVER STREQUAL "no_recover") - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.3) - set(MRT_SANITIZER_CXX_FLAGS "-fno-sanitize-recover=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow" ${MRT_SANITIZER_CXX_FLAGS}) - elseif(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 4.9) - set(MRT_SANITIZER_CXX_FLAGS "-fno-sanitize-recover=undefined,float-divide-by-zero,float-cast-overflow" ${MRT_SANITIZER_CXX_FLAGS}) - endif() -endif() - -# define rosparam/rosinterface_handler macro for compability. Macros will be overriden by the actual macros defined by the packages, if existing. -macro(generate_ros_parameter_files) - # handle pure dynamic reconfigure files - foreach (_cfg ${ARGN}) - get_filename_component(_cfgext ${_cfg} EXT) - if( _cfgext STREQUAL ".cfg" ) - list(APPEND _${PROJECT_NAME}_pure_cfg_files "${_cfg}") - else() - list(APPEND _${PROJECT_NAME}_rosparam_other_param_files "${_cfg}") - endif() - endforeach() - # generate dynamic reconfigure files - if(_${PROJECT_NAME}_pure_cfg_files AND NOT TARGET ${PROJECT_NAME}_gencfg AND NOT rosinterface_handler_FOUND_CATKIN_PROJECT) - if(dynamic_reconfigure_FOUND_CATKIN_PROJECT) - generate_dynamic_reconfigure_options(${_${PROJECT_NAME}_pure_cfg_files}) - else() - message(WARNING "Dependency to dynamic_reconfigure is missing, or find_package(dynamic_reconfigure) was not called yet. Not building dynamic config files") - endif() - endif() - # if there are other config files, someone will have forgotten to include the rosparam/rosinterface handler - if(_${PROJECT_NAME}_rosparam_other_param_files AND NOT rosinterface_handler_FOUND_CATKIN_PROJECT) - message(FATAL_ERROR "Dependency rosinterface_handler or rosparam_handler could not be found. Did you add it to your package.xml?") - endif() -endmacro() -macro(generate_ros_interface_files) - # handle pure dynamic reconfigure files - foreach (_cfg ${ARGN}) - get_filename_component(_cfgext ${_cfg} EXT) - if(NOT _cfgext STREQUAL ".cfg" ) - list(APPEND _${PROJECT_NAME}_rosif_other_param_files "${_cfg}") - endif() - endforeach() - if(_${PROJECT_NAME}_rosif_other_param_files AND NOT rosparam_handler_FOUND_CATKIN_PROJECT) - message(FATAL_ERROR "Dependency rosinterface_handler or rosparam_handler could not be found. Did you add it to your package.xml?") - endif() -endmacro() - -macro(_setup_coverage_info) - setup_target_for_coverage(${PROJECT_NAME}-coverage coverage ${PROJECT_NAME}-pre-coverage) - # make sure the target is built after running tests - add_dependencies(run_tests ${PROJECT_NAME}-coverage) - add_dependencies(${PROJECT_NAME}-coverage _run_tests_${PROJECT_NAME}) - if(TARGET ${PROJECT_NAME}-pre-coverage) - add_dependencies(clean_test_results_${PROJECT_NAME} ${PROJECT_NAME}-pre-coverage) - add_dependencies(${PROJECT_NAME}-pre-coverage tests) - endif() - if(MRT_ENABLE_COVERAGE GREATER 1) - add_custom_command(TARGET ${PROJECT_NAME}-coverage - POST_BUILD - COMMAND firefox ${CMAKE_CURRENT_BINARY_DIR}/coverage/index.html > /dev/null 2>&1 & - COMMENT "Showing coverage results" - ) - endif() -endmacro() - - -# -# Registers the custom check_tests command and adds a dependency for a certain unittest -# -# Example: -# :: -# -# _mrt_register_test( -# ) -# -macro(_mrt_register_test) - # we need this only once per project - if(MRT_NO_FAIL_ON_TESTS OR _mrt_checks_${PROJECT_NAME} OR NOT TARGET _run_tests_${PROJECT_NAME}) - return() - endif() - # pygment formats xml more nicely - find_program(CCAT pygmentize) - if(CCAT) - set(RUN_CCAT | ${CCAT}) - endif() - - add_custom_command(TARGET _run_tests_${PROJECT_NAME} - POST_BUILD - COMMAND /bin/bash -c \"set -o pipefail$ catkin_test_results --verbose . ${RUN_CCAT} 1>&2\" # redirect to stderr for better output in catkin - WORKING_DIRECTORY ${CMAKE_CURRENT_BUILD_DIR} - COMMENT "Showing test results" - ) - set(_mrt_checks_${PROJECT_NAME} TRUE PARENT_SCOPE) -endmacro() - -# Glob for folders in the search directory. -function(mrt_glob_folders DIRECTORY_LIST SEARCH_DIRECTORY) - if(${CMAKE_VERSION} VERSION_LESS "3.12.0") - file(GLOB DIRECTORIES "${SEARCH_DIRECTORY}/[^.]*") - else() - file(GLOB DIRECTORIES CONFIGURE_DEPENDS "${SEARCH_DIRECTORY}/[^.]*") - endif() - - set(_DIRECTORY_LIST_ "") - foreach(SRC_DIR ${DIRECTORIES}) - if(IS_DIRECTORY "${SRC_DIR}") - get_filename_component(DIRECTORY_NAME "${SRC_DIR}" NAME) - list(APPEND _DIRECTORY_LIST_ ${DIRECTORY_NAME}) - endif() - endforeach() - set(${DIRECTORY_LIST} ${_DIRECTORY_LIST_} PARENT_SCOPE) -endfunction() - -# Deprecated function. Use 'mrt_glob_folders' instead. -macro(glob_folders) - mrt_glob_folders(${ARGV}) -endmacro() - -# Globs for message files and calls add_message_files -macro(mrt_add_message_files folder_name) - mrt_glob_files(_ROS_MESSAGE_FILES REL_FOLDER ${folder_name} ${folder_name}/*.msg) - if (_ROS_MESSAGE_FILES) - add_message_files(FILES ${_ROS_MESSAGE_FILES} DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${folder_name}") - set(ROS_GENERATE_MESSAGES True) - endif() -endmacro() - -# Globs for service files and calls add_service_files -macro(mrt_add_service_files folder_name) - mrt_glob_files(_ROS_SERVICE_FILES REL_FOLDER ${folder_name} ${folder_name}/*.srv) - if (_ROS_SERVICE_FILES) - add_service_files(FILES ${_ROS_SERVICE_FILES} DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${folder_name}") - set(ROS_GENERATE_MESSAGES True) - endif() -endmacro() - -# Globs for action files and calls add_action_files -macro(mrt_add_action_files folder_name) - mrt_glob_files(_ROS_ACTION_FILES REL_FOLDER ${folder_name} ${folder_name}/*.action) - if (_ROS_ACTION_FILES) - add_action_files(FILES ${_ROS_ACTION_FILES} DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${folder_name}") - endif() -endmacro() - -# Deprecated function. Use one of 'mrt_add_message_files', 'mrt_add_service_files' or 'mrt_add_action_files'. -macro(glob_ros_files excecutable_name extension_name) - mrt_glob_files(ROS_${excecutable_name}_FILES REL_FOLDER ${extension_name} "${extension_name}/*.${extension_name}") - - if (ROS_${excecutable_name}_FILES) - #work around to execute a command wich name is given in a variable - #write a file with the command, include it and delete the file again - file(WRITE "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake" "${excecutable_name}( - DIRECTORY \"${PROJECT_SOURCE_DIR}/${extension_name}\" - FILES - ${ROS_${excecutable_name}_FILES} - )") - include("${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake") - file(REMOVE "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake") - - set(ROS_GENERATE_MESSAGES True) - endif() -endmacro() - -# Globs files in the currect project dir. -function(mrt_glob_files varname) - cmake_parse_arguments(PARAMS "" "REL_FOLDER" "" ${ARGN}) - - if (PARAMS_REL_FOLDER) - set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}/${PARAMS_REL_FOLDER}") - else() - set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}") - endif() - - if(${CMAKE_VERSION} VERSION_LESS "3.12.0") - file(GLOB files RELATIVE "${RELATIVE_PATH}" ${PARAMS_UNPARSED_ARGUMENTS}) - else() - file(GLOB files RELATIVE "${RELATIVE_PATH}" CONFIGURE_DEPENDS ${PARAMS_UNPARSED_ARGUMENTS}) - endif() - set(${varname} ${files} PARENT_SCOPE) -endfunction() - -# Globs files recursivly in the currect project dir. -function(mrt_glob_files_recurse varname) - cmake_parse_arguments(PARAMS "" "REL_FOLDER" "" ${ARGN}) - - if (PARAMS_REL_FOLDER) - set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}/${PARAMS_REL_FOLDER}") - else() - set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}") - endif() - - if(${CMAKE_VERSION} VERSION_LESS "3.12.0") - file(GLOB_RECURSE files RELATIVE "${RELATIVE_PATH}" ${PARAMS_UNPARSED_ARGUMENTS}) - else() - file(GLOB_RECURSE files RELATIVE "${RELATIVE_PATH}" CONFIGURE_DEPENDS ${PARAMS_UNPARSED_ARGUMENTS}) - endif() - set(${varname} ${files} PARENT_SCOPE) -endfunction() - -# -# Once upon a time this used to make non-code files known to IDEs that parse Cmake output. But as this -# messes up with the target determination mechanism used by most ides and garbages up the target view. -# -# Therefore this function is no longer used and only here for backwards compability. -# -# @@public -# -function(mrt_add_to_ide files) -endfunction() - -# -# Automatically sets up and installs python modules located under ``src/${PROJECT_NAME}``. -# Modules can afterwards simply be included using "import " in python. -# -# The python folder (under src/${PROJECT_NAME}) is required to have an __init__.py file. -# -# The command will automatically generate a setup.py in your project folder. -# This file should not be commited, as it will be regenerated at every new CMAKE run. -# Due to restrictions imposed by catkin (searches hardcoded for this setup.py), the file cannot -# be placed elsewhere. -# -# Example: -# :: -# -# mrt_python_module_setup() -# -# @@public -# -function(mrt_python_module_setup) - if(NOT catkin_FOUND) - find_package(catkin REQUIRED) - endif() - if(ARGN) - message(FATAL_ERROR "mrt_python_module_setup() called with unused arguments: ${ARGN}") - endif() - if(NOT EXISTS "${PROJECT_SOURCE_DIR}/src/${PROJECT_NAME}/__init__.py") - return() - endif() - set(PKG_PYTHON_MODULE ${PROJECT_NAME}) - set(${PROJECT_NAME}_PYTHON_MODULE ${PROJECT_NAME} PARENT_SCOPE) - set(PACKAGE_DIR "src") - configure_file(${MCM_ROOT}/cmake/Templates/setup.py.in "${PROJECT_SOURCE_DIR}/setup.py" @@ONLY) - catkin_python_setup() -endfunction() - - -# -# Generates a python module from boost-python cpp files. -# -# Each .cpp will become a seperate .py submodule within . After building and sourcing you can use the modules simply with "import .". -# -# The files are automatically linked with boost-python libraries and a python module is generated -# and installed from the resulting library. If this project declares any libraries with ``mrt_add_library()``, they will automatically be linked with this library. -# -# This function will define the compiler variable ``PYTHON_API_MODULE_NAME`` with the name of the generated library. This can be used in the ``BOOST_PYTHON_MODULE`` C++ Macro. -# -# .. note:: This function can only be called once per package. -# -# :param modulename: Name of the module needs to be passed as first parameter. -# :type modulename: string -# :param FILES: list of C++ files defining the BOOST-Python API. -# :type FILES: list of strings -# -# Example: -# :: -# -# mrt_add_python_api( example_package -# FILES python_api/python.cpp -# ) -# -# @@public -# -function(mrt_add_python_api modulename) - cmake_parse_arguments(MRT_ADD_PYTHON_API "" "" "FILES" ${ARGN}) - if(NOT MRT_ADD_PYTHON_API_FILES) - return() - endif() - - #set and check target name - set( PYTHON_API_MODULE_NAME ${modulename}) - if("${${PROJECT_NAME}_PYTHON_MODULE}" STREQUAL "${PYTHON_API_MODULE_NAME}") - message(FATAL_ERROR "The name of the python_api module conflicts with the name of the python module. Please choose a different name") - endif() - - if("${PYTHON_API_MODULE_NAME}" STREQUAL "${PROJECT_NAME}") - # mark that catkin_python_setup() was called and the setup.py file contains a package with the same name as the current project - # in order to disable installation of generated __init__.py files in generate_messages() and generate_dynamic_reconfigure_options() - set(${PROJECT_NAME}_CATKIN_PYTHON_SETUP_HAS_PACKAGE_INIT TRUE PARENT_SCOPE) - endif() - if(${PROJECT_NAME}_PYTHON_API_TARGET) - message(FATAL_ERROR "mrt_add_python_api() was already called for this project. You can add only one python_api per project!") - endif() - - if (NOT pybind11_FOUND AND NOT BoostPython_FOUND) - message(FATAL_ERROR "Missing dependency to pybind11 or boost python. Add either 'pybind11-dev' or 'libboost-python' to 'package.xml'") - endif() - - if (pybind11_FOUND AND BoostPython_FOUND) - message(FATAL_ERROR "Found pybind11 and boost python. Only one is allowed.") - endif() - - # put in devel folder - set(DEVEL_PREFIX ${CATKIN_DEVEL_PREFIX}) - set(PYTHON_MODULE_DIR ${DEVEL_PREFIX}/${CATKIN_GLOBAL_PYTHON_DESTINATION}/${PYTHON_API_MODULE_NAME}) - - # add library for each file - foreach(API_FILE ${MRT_ADD_PYTHON_API_FILES}) - get_filename_component(SUBMODULE_NAME ${API_FILE} NAME_WE) - set( TARGET_NAME "${PROJECT_NAME}-${PYTHON_API_MODULE_NAME}-${SUBMODULE_NAME}-pyapi") - set( LIBRARY_NAME ${SUBMODULE_NAME}) - message(STATUS "Adding python api library \"${LIBRARY_NAME}\" to python module \"${PYTHON_API_MODULE_NAME}\"") - - if (pybind11_FOUND) - pybind11_add_module(${TARGET_NAME} MODULE ${API_FILE}) - target_link_libraries(${TARGET_NAME} PRIVATE pybind11::module) - elseif(BoostPython_FOUND) - add_library(${TARGET_NAME} SHARED ${API_FILE}) - target_link_libraries(${TARGET_NAME} PRIVATE ${BoostPython_LIBRARIES} ${PYTHON_LIBRARY}) - endif() - - set_target_properties(${TARGET_NAME} - PROPERTIES OUTPUT_NAME ${LIBRARY_NAME} - PREFIX "" - ) - - set_target_properties(${TARGET_NAME} PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${PYTHON_MODULE_DIR}") - - target_compile_definitions(${TARGET_NAME} PRIVATE -DPYTHON_API_MODULE_NAME=${LIBRARY_NAME}) - - target_link_libraries( ${TARGET_NAME} PRIVATE - ${catkin_LIBRARIES} - ${mrt_LIBRARIES} - ${MRT_SANITIZER_LINK_FLAGS} - ) - - set(_deps ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS}) - if(_deps) - add_dependencies(${TARGET_NAME} ${_deps}) - endif() - list(APPEND GENERATED_TARGETS ${TARGET_NAME} ) - endforeach() - configure_file(${MCM_ROOT}/cmake/Templates/__init__.py.in ${PYTHON_MODULE_DIR}/__init__.py) - - # append to list of all targets in this project - set(${PROJECT_NAME}_PYTHON_API_TARGET ${GENERATED_TARGETS} PARENT_SCOPE) - - # configure setup.py for install - set(PKG_PYTHON_MODULE ${PYTHON_API_MODULE_NAME}) - set(PACKAGE_DIR ${DEVEL_PREFIX}/${CATKIN_GLOBAL_PYTHON_DESTINATION}) - set(PACKAGE_DATA "*.so*") - configure_file(${MCM_ROOT}/cmake/Templates/setup.py.in "${CMAKE_CURRENT_BINARY_DIR}/setup.py" @@ONLY) - configure_file(${MCM_ROOT}/cmake/Templates/python_api_install.py.in "${CMAKE_CURRENT_BINARY_DIR}/python_api_install.py" @@ONLY) - install(CODE "execute_process(COMMAND ${CMAKE_CURRENT_BINARY_DIR}/python_api_install.py)") -endfunction() - - -# -# Adds a library. -# -# This command ensures the library is compiled with all necessary dependencies. If no files are passed, the command will return silently. -# -# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. -# -# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. -# -# :param libname: Name of the library to generate as first argument (without lib or .so) -# :type libname: string -# :param INCLUDES: Include files needed for the library, absolute or relative to ${PROJECT_SOURCE_DIR} -# :type INCLUDES: list of strings -# :param SOURCES: Source files to be added. If empty, a header-only library is assumed -# :type SOURCES: list of strings -# :param DEPENDS: List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects. -# :type DEPENDS: list of strings -# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects -# :type LIBRARIES: list of strings -# -# Example: -# :: -# -# mrt_add_library( example_package -# INCLUDES include/example_package/myclass.h include/example_package/myclass2.h -# SOURCES src/myclass.cpp src/myclass.cpp -# ) -# -# @@public -# -function(mrt_add_library libname) - set(LIBRARY_NAME ${libname}) - if(NOT LIBRARY_NAME) - message(FATAL_ERROR "No executable name specified for call to mrt_add_library!") - endif() - cmake_parse_arguments(MRT_ADD_LIBRARY "" "" "INCLUDES;SOURCES;DEPENDS;LIBRARIES" ${ARGN}) - set(LIBRARY_TARGET_NAME ${LIBRARY_NAME}) - - if(NOT MRT_ADD_LIBRARY_INCLUDES AND NOT MRT_ADD_LIBRARY_SOURCES) - return() - endif() - - # catch header-only libraries - if(NOT MRT_ADD_LIBRARY_SOURCES) - # we only set a fake target to make the files show up in IDEs - message(STATUS "Adding header-only library with files ${MRT_ADD_LIBRARY_INCLUDES}") - add_custom_target(${LIBRARY_TARGET_NAME} SOURCES ${MRT_ADD_LIBRARY_INCLUDES}) - return() - endif() - - foreach(SOURCE_FILE ${MRT_ADD_LIBRARY_SOURCES}) - get_filename_component(FILE_EXT ${SOURCE_FILE} EXT) - if ("${FILE_EXT}" STREQUAL ".cu") - list(APPEND _MRT_CUDA_SOURCES_FILES "${SOURCE_FILE}") - set(_MRT_HAS_CUDA_SOURCE_FILES TRUE) - else() - list(APPEND _MRT_CPP_SOURCE_FILES "${SOURCE_FILE}") - set(_MRT_HAS_CPP_SOURCE_FILES TRUE) - endif() - endforeach() - - # This is the easiest for a CUDA only library: Create an empty file. - if(NOT _MRT_HAS_CPP_SOURCE_FILES) - message(STATUS "CMAKE_CURRENT_BINARY_DIR: ${CMAKE_CURRENT_BINARY_DIR}") - file(WRITE "${CMAKE_CURRENT_BINARY_DIR}/empty.cpp" "") - list(APPEND _MRT_CPP_SOURCE_FILES "${CMAKE_CURRENT_BINARY_DIR}/empty.cpp") - endif() - - # generate the target - message(STATUS "Adding library \"${LIBRARY_NAME}\" with source ${_MRT_CPP_SOURCE_FILES}") - add_library(${LIBRARY_TARGET_NAME} - ${MRT_ADD_LIBRARY_INCLUDES} ${_MRT_CPP_SOURCE_FILES} - ) - set_target_properties(${LIBRARY_TARGET_NAME} - PROPERTIES OUTPUT_NAME ${LIBRARY_NAME} - ) - target_compile_options(${LIBRARY_TARGET_NAME} - PRIVATE ${MRT_SANITIZER_CXX_FLAGS} - ) - set(_combined_deps ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${MRT_ADD_LIBRARY_DEPENDS}) - if(_combined_deps) - add_dependencies(${LIBRARY_TARGET_NAME} ${_combined_deps}) - endif() - target_link_libraries(${LIBRARY_TARGET_NAME} - ${catkin_LIBRARIES} - ${mrt_LIBRARIES} - ${MRT_ADD_LIBRARY_LIBRARIES} - ${MRT_SANITIZER_CXX_FLAGS} - ${MRT_SANITIZER_LINK_FLAGS} - ) - # add dependency to python_api if existing (needs to be declared before this library) - foreach(_py_api_target ${${PROJECT_NAME}_PYTHON_API_TARGET}) - target_link_libraries(${_py_api_target} PRIVATE ${LIBRARY_TARGET_NAME}) - endforeach() - - # Add cuda target - if (_MRT_HAS_CUDA_SOURCE_FILES) - if (NOT DEFINED CUDA_FOUND) - message(FATAL_ERROR "Found CUDA source file but no dependency to CUDA. Please add cuda to your package.xml.") - endif() - - # generate cuda target - set(CUDA_TARGET_NAME _${LIBRARY_TARGET_NAME}_cuda) - # NVCC does not like '-' in file names. - string(REPLACE "-" "_" CUDA_TARGET_NAME ${CUDA_TARGET_NAME}) - - message(STATUS "Adding library \"${CUDA_TARGET_NAME}\" with source ${_MRT_CUDA_SOURCES_FILES}") - - if(${CMAKE_VERSION} VERSION_LESS "3.9.0") - cuda_add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCES_FILES}) - else() - add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCES_FILES}) - # We cannot link to all libraries as nvcc does not unterstand all the flags - # etc. which could be passed to target_link_libraries as a target. So the - # dependencies were added to the mrt_CUDA_LIBRARIES variable. - target_link_libraries(${CUDA_TARGET_NAME} PRIVATE ${mrt_CUDA_LIBRARIES}) - set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY POSITION_INDEPENDENT_CODE ON) - set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY CUDA_SEPARABLE_COMPILATION ON) - endif() - - # link cuda library to executable - target_link_libraries(${LIBRARY_TARGET_NAME} ${CUDA_TARGET_NAME}) - endif() - - # append to list of all targets in this project - set(${PROJECT_NAME}_GENERATED_LIBRARIES ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${LIBRARY_TARGET_NAME} ${CUDA_TARGET_NAME} PARENT_SCOPE) - set(${PROJECT_NAME}_MRT_TARGETS ${${PROJECT_NAME}_MRT_TARGETS} ${LIBRARY_TARGET_NAME} ${CUDA_TARGET_NAME} PARENT_SCOPE) -endfunction() - - -# -# Adds an executable. -# -# This command ensures the executable is compiled with all necessary dependencies. -# -# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. -# -# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. -# -# :param execname: name of the executable -# :type execname: string -# :param FOLDER: Folder containing the .cpp/.cc-files and .h/.hh/.hpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}``. -# :type FOLDER: string -# :param FILES: List of extra source files to add. This or the FOLDER parameter is mandatory. -# :type FILES: list of strings -# :param DEPENDS: List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects. -# :type DEPENDS: list of strings -# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects -# :type LIBRARIES: list of strings -# -# Example: -# :: -# -# mrt_add_executable( example_package -# FOLDER src/example_package -# ) -# -# @@public -# -function(mrt_add_executable execname) - set(EXEC_NAME ${execname}) - if(NOT EXEC_NAME) - message(FATAL_ERROR "No executable name specified for call to mrt_add_executable()!") - endif() - cmake_parse_arguments(MRT_ADD_EXECUTABLE "" "FOLDER" "FILES;DEPENDS;LIBRARIES" ${ARGN}) - if(NOT MRT_ADD_EXECUTABLE_FOLDER AND NOT MRT_ADD_EXECUTABLE_FILES) - message(FATAL_ERROR "No FOLDER or FILES argument passed to mrt_add_executable()!") - endif() - set(EXEC_TARGET_NAME ${PROJECT_NAME}-${EXEC_NAME}-exec) - - # get the files - if(MRT_ADD_EXECUTABLE_FOLDER) - mrt_glob_files_recurse(EXEC_SOURCE_FILES_INC "${MRT_ADD_EXECUTABLE_FOLDER}/*.h" "${MRT_ADD_EXECUTABLE_FOLDER}/*.hpp" "${MRT_ADD_EXECUTABLE_FOLDER}/*.hh" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cuh") - mrt_glob_files_recurse(EXEC_SOURCE_FILES_SRC "${MRT_ADD_EXECUTABLE_FOLDER}/*.cpp" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cc" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cu") - endif() - if(MRT_ADD_EXECUTABLE_FILES) - list(APPEND EXEC_SOURCE_FILES_SRC ${MRT_ADD_EXECUTABLE_FILES}) - list(REMOVE_DUPLICATES EXEC_SOURCE_FILES_SRC) - endif() - if(NOT EXEC_SOURCE_FILES_SRC) - return() - endif() - - # separate cuda files - set(_MRT_CPP_SOURCE_FILES ) - set(_MRT_CUDA_SOURCES_FILES ) - foreach(SOURCE_FILE ${EXEC_SOURCE_FILES_SRC}) - get_filename_component(FILE_EXT ${SOURCE_FILE} EXT) - if ("${FILE_EXT}" STREQUAL ".cu") - list(APPEND _MRT_CUDA_SOURCES_FILES "${SOURCE_FILE}") - set(_MRT_HAS_CUDA_SOURCE_FILES TRUE) - else() - list(APPEND _MRT_CPP_SOURCE_FILES "${SOURCE_FILE}") - endif() - endforeach() - - # generate the target - message(STATUS "Adding executable \"${EXEC_NAME}\"") - add_executable(${EXEC_TARGET_NAME} - ${EXEC_SOURCE_FILES_INC} - ${_MRT_CPP_SOURCE_FILES} - ) - set_target_properties(${EXEC_TARGET_NAME} - PROPERTIES OUTPUT_NAME ${EXEC_NAME} - ) - target_compile_options(${EXEC_TARGET_NAME} - PRIVATE ${MRT_SANITIZER_CXX_FLAGS} - ) - target_include_directories(${EXEC_TARGET_NAME} - PRIVATE "${MRT_ADD_EXECUTABLE_FOLDER}" - ) - set(_combined_deps ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${MRT_ADD_EXECUTABLE_DEPENDS}) - if(_combined_deps) - add_dependencies(${EXEC_TARGET_NAME} ${_combined_deps}) - endif() - target_link_libraries(${EXEC_TARGET_NAME} PRIVATE - ${catkin_LIBRARIES} - ${mrt_LIBRARIES} - ${MRT_ADD_EXECUTABLE_LIBRARIES} - ${MRT_SANITIZER_EXE_CXX_FLAGS} - ${MRT_SANITIZER_LINK_FLAGS} - ${${PROJECT_NAME}_GENERATED_LIBRARIES} - ) - - # Add cuda target - if (_MRT_HAS_CUDA_SOURCE_FILES) - if (NOT DEFINED CUDA_FOUND) - message(FATAL_ERROR "Found CUDA source file but no dependency to CUDA. Please add CUDA to your package.xml.") - endif() - - # generate cuda target - set(CUDA_TARGET_NAME _${EXEC_TARGET_NAME}_cuda) - - # NVCC does not like '-' in file names and because 'cuda_add_library' creates - # a helper file which contains the target name, one has to replace '-'. - string(REPLACE "-" "_" CUDA_TARGET_NAME ${CUDA_TARGET_NAME}) - - if(${CMAKE_VERSION} VERSION_LESS "3.9.0") - cuda_add_library(${CUDA_TARGET_NAME} STATIC ${_MRT_CUDA_SOURCES_FILES}) - else() - message(STATUS "Adding ${_MRT_CUDA_SOURCES_FILES} files.") - add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCES_FILES}) - # We cannot link to all libraries as nvcc does not unterstand all the flags - # etc. which could be passed to target_link_libraries as a target. So the - # dependencies were added to the mrt_CUDA_LIBRARIES variable. - target_link_libraries(${CUDA_TARGET_NAME} PRIVATE ${mrt_CUDA_LIBRARIES}) - set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY POSITION_INDEPENDENT_CODE ON) - set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY CUDA_SEPARABLE_COMPILATION ON) - endif() - - # link cuda library to executable - target_link_libraries(${EXEC_TARGET_NAME} PRIVATE ${CUDA_TARGET_NAME}) - endif() - - # append to list of all targets in this project - set(${PROJECT_NAME}_MRT_TARGETS ${${PROJECT_NAME}_MRT_TARGETS} ${EXEC_TARGET_NAME} ${CUDA_TARGET_NAME} PARENT_SCOPE) -endfunction() - - -# -# Adds a nodelet. -# -# This command ensures the nodelet is compiled with all necessary dependencies. Make sure to add lib{NAME}_nodelet to the ``nodelet_plugins.xml`` file. -# -# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. -# -# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. -# -# It requires a ``*_nodelet.cpp``-File to be present in this folder. -# The command will look for a ``*_node.cpp``-file and remove it from the list of files to avoid ``main()``-functions to be compiled into the library. -# -# :param nodeletname: base name of the nodelet (_nodelet will be appended to the base name to avoid conflicts with library packages) -# :type nodeletname: string -# :param FOLDER: Folder with cpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}`` -# :type FOLDER: string -# :param DEPENDS: List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects. -# :type DEPENDS: list of strings -# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects -# :type LIBRARIES: list of strings -# :param TARGETNAME: Choose the name of the internal CMAKE target. Will be autogenerated if not specified. -# :type TARGETNAME: string -# -# Example: -# :: -# -# mrt_add_nodelet( example_package -# FOLDER src/example_package -# ) -# -# The resulting entry in the ``nodelet_plugins.xml`` is thus: -# -# @@public -# -function(mrt_add_nodelet nodeletname) - - set(NODELET_NAME ${nodeletname}) - if(NOT NODELET_NAME) - message(FATAL_ERROR "No nodelet name specified for call to mrt_add_nodelet()!") - endif() - cmake_parse_arguments(MRT_ADD_NODELET "" "FOLDER;TARGETNAME" "DEPENDS;LIBRARIES" ${ARGN}) - if(NOT MRT_ADD_NODELET_TARGETNAME) - set(NODELET_TARGET_NAME ${PROJECT_NAME}-${NODELET_NAME}-nodelet) - else() - set(NODELET_TARGET_NAME ${MRT_ADD_NODELET_TARGETNAME}) - endif() - - # get the files - mrt_glob_files(NODELET_SOURCE_FILES_INC "${MRT_ADD_NODELET_FOLDER}/*.h" "${MRT_ADD_NODELET_FOLDER}/*.hpp" "${MRT_ADD_EXECUTABLE_FOLDER}/*.hh") - mrt_glob_files(NODELET_SOURCE_FILES_SRC "${MRT_ADD_NODELET_FOLDER}/*.cpp" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cc") - - # Find nodelet - mrt_glob_files(NODELET_CPP "${MRT_ADD_NODELET_FOLDER}/*_nodelet.cpp" "${MRT_ADD_NODELET_FOLDER}/*_nodelet.cc") - if(NOT NODELET_CPP) - return() - endif() - - # Remove nodes (with their main) from src-files - mrt_glob_files(NODE_CPP "${MRT_ADD_NODELET_FOLDER}/*_node.cpp" "${MRT_ADD_NODELET_FOLDER}/*_node.cc") - if (NODE_CPP) - list(REMOVE_ITEM NODELET_SOURCE_FILES_SRC ${NODE_CPP}) - endif () - - # determine library name - STRING(REGEX REPLACE "_node" "" NODELET_NAME ${NODELET_NAME}) - STRING(REGEX REPLACE "_nodelet" "" NODELET_NAME ${NODELET_NAME}) - set(NODELET_NAME ${NODELET_NAME}_nodelet) - - # generate the target - message(STATUS "Adding nodelet \"${NODELET_NAME}\"") - add_library(${NODELET_TARGET_NAME} - ${NODELET_SOURCE_FILES_INC} - ${NODELET_SOURCE_FILES_SRC} - ) - set_target_properties(${NODELET_TARGET_NAME} - PROPERTIES OUTPUT_NAME ${NODELET_NAME} - ) - target_compile_options(${NODELET_TARGET_NAME} - PRIVATE ${MRT_SANITIZER_CXX_FLAGS} - ) - add_dependencies(${NODELET_TARGET_NAME} ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${MRT_ADD_NODELET_DEPENDS}) - target_link_libraries(${NODELET_TARGET_NAME} - ${catkin_LIBRARIES} - ${mrt_LIBRARIES} - ${MRT_ADD_NODELET_LIBRARIES} - ${MRT_SANITIZER_CXX_FLAGS} - ${MRT_SANITIZER_LINK_FLAGS} - ) - # append to list of all targets in this project - set(${PROJECT_NAME}_GENERATED_LIBRARIES ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${NODELET_TARGET_NAME} PARENT_SCOPE) - set(${PROJECT_NAME}_MRT_TARGETS ${${PROJECT_NAME}_MRT_TARGETS} ${NODELET_TARGET_NAME} PARENT_SCOPE) -endfunction() - - -# -# Adds a node and a corresponding nodelet. -# -# This command ensures the node/nodelet are compiled with all necessary dependencies. Make sure to add lib{NAME}_nodelet to the ``nodelet_plugins.xml`` file. -# -# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. -# -# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. -# -# It requires a ``*_nodelet.cpp`` file and a ``*_node.cpp`` file to be present in this folder. It will then compile a nodelet-library, create an executable from the ``*_node.cpp`` file and link the executable with the nodelet library. -# -# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. -# -# :param basename: base name of the node/nodelet (_nodelet will be appended for the nodelet name to avoid conflicts with library packages) -# :type basename: string -# :param FOLDER: Folder with cpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}`` -# :type FOLDER: string -# :param DEPENDS: List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects. -# :type DEPENDS: list of strings -# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects -# :type LIBRARIES: list of strings -# -# Example: -# :: -# -# mrt_add_node_and_nodelet( example_package -# FOLDER src/example_package -# ) -# -# The resulting entry in the ``nodelet_plugins.xml`` is thus: -# -# @@public -# -function(mrt_add_node_and_nodelet basename) - cmake_parse_arguments(MRT_ADD_NN "" "FOLDER" "DEPENDS;LIBRARIES" ${ARGN}) - set(BASE_NAME ${basename}) - if(NOT BASE_NAME) - message(FATAL_ERROR "No base name specified for call to mrt_add_node_and_nodelet()!") - endif() - set(NODELET_TARGET_NAME ${PROJECT_NAME}-${BASE_NAME}-nodelet) - - # add nodelet - mrt_add_nodelet(${BASE_NAME} - FOLDER ${MRT_ADD_NN_FOLDER} - TARGETNAME ${NODELET_TARGET_NAME} - DEPENDS ${MRT_ADD_NN_DEPENDS} - LIBRARIES ${MRT_ADD_NN_LIBRARIES} - ) - # pass lists on to parent scope - set(${PROJECT_NAME}_GENERATED_LIBRARIES ${${PROJECT_NAME}_GENERATED_LIBRARIES} PARENT_SCOPE) - set(${PROJECT_NAME}_MRT_TARGETS ${${PROJECT_NAME}_MRT_TARGETS} PARENT_SCOPE) - - # search the files we have to build with - if(NOT TARGET ${NODELET_TARGET_NAME} OR DEFINED MRT_SANITIZER_ENABLED) - unset(NODELET_TARGET_NAME) - mrt_glob_files(NODE_CPP "${MRT_ADD_NN_FOLDER}/*.cpp" "${MRT_ADD_NN_FOLDER}/*.cc") - else() - mrt_glob_files(NODE_CPP "${MRT_ADD_NN_FOLDER}/*_node.cpp" "${MRT_ADD_NN_FOLDER}/*_node.cc") - endif() - - # find *_node file containing the main() and add the executable - mrt_glob_files(NODE_H "${MRT_ADD_NN_FOLDER}/*.h" "${MRT_ADD_NN_FOLDER}/*.hpp" "${MRT_ADD_NN_FOLDER}/*.hh") - mrt_glob_files(NODE_MAIN "${MRT_ADD_NN_FOLDER}/*_node.cpp" "${MRT_ADD_NN_FOLDER}/*_node.cc") - if(NODE_MAIN) - mrt_add_executable(${BASE_NAME} - FILES ${NODE_CPP} ${NODE_H} - DEPENDS ${MRT_ADD_NN_DEPENDS} ${NODELET_TARGET_NAME} - LIBRARIES ${MRT_ADD_NN_LIBRARIES} ${NODELET_TARGET_NAME} - ) - # pass lists on to parent scope - set(${PROJECT_NAME}_GENERATED_LIBRARIES ${${PROJECT_NAME}_GENERATED_LIBRARIES} PARENT_SCOPE) - set(${PROJECT_NAME}_MRT_TARGETS ${${PROJECT_NAME}_MRT_TARGETS} PARENT_SCOPE) - endif() -endfunction() - - -# -# Adds all rostests (identified by a .test file) contained in a folder as unittests. -# -# If a .cpp file exists with the same name, it will be added and comiled as a gtest test. -# Unittests can be run with "catkin run_tests" or similar. "-test" will be appended to the name of the test node to avoid conflicts (i.e. the type argument should then be in a mytest.test file). -# -# Unittests will always be executed with the folder as cwd. E.g. if the test folder contains a sub-folder "test_data", it can simply be accessed as "test_data". -# -# If coverage information is enabled (by setting ``MRT_ENABLE_COVARAGE`` to true), coverage analysis will be performed after unittests have run. The results can be found in the package's build folder in the folder "coverage". -# -# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. -# -# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument -# :type folder: string -# :param LIBRARIES: Additional (non-catkin, non-mrt) libraries to link to -# :type LIBRARIES: list of strings -# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) -# :type DEPENDS: list of strings -# -# Example: -# :: -# -# mrt_add_ros_tests( test -# ) -# -# @@public -# -function(mrt_add_ros_tests folder) - set(TEST_FOLDER ${folder}) - cmake_parse_arguments(MRT_ADD_ROS_TESTS "" "" "LIBRARIES;DEPENDS" ${ARGN}) - mrt_glob_files(_ros_tests "${TEST_FOLDER}/*.test") - add_custom_target(${PROJECT_NAME}-rostest_test_files SOURCES ${_ros_tests}) - configure_file(${MCM_ROOT}/cmake/Templates/test_utility.hpp.in ${PROJECT_BINARY_DIR}/tests/test/test_utility.hpp @@ONLY) - - foreach(_ros_test ${_ros_tests}) - get_filename_component(_test_name ${_ros_test} NAME_WE) - # make sure we add only one -test to the target - STRING(REGEX REPLACE "-test" "" TEST_NAME ${_test_name}) - set(TEST_NAME ${TEST_NAME}-test) - set(TEST_TARGET_NAME ${PROJECT_NAME}-${TEST_NAME}) - # look for a matching .cpp - if(EXISTS "${PROJECT_SOURCE_DIR}/${TEST_FOLDER}/${_test_name}.cpp") - message(STATUS "Adding gtest-rostest \"${TEST_TARGET_NAME}\" with test file ${_ros_test}") - add_rostest_gtest(${TEST_TARGET_NAME} ${_ros_test} "${TEST_FOLDER}/${_test_name}.cpp") - target_compile_options(${TEST_TARGET_NAME} - PRIVATE ${MRT_SANITIZER_EXE_CXX_FLAGS} - ) - target_link_libraries(${TEST_TARGET_NAME} - ${${PROJECT_NAME}_GENERATED_LIBRARIES} - ${catkin_LIBRARIES} - ${mrt_TEST_LIBRARIES} - ${MRT_ADD_ROS_TESTS_LIBRARIES} - ${MRT_SANITIZER_EXE_CXX_FLAGS} - ${MRT_SANITIZER_LINK_FLAGS} - gtest_main - ) - target_include_directories(${TEST_TARGET_NAME} - PRIVATE ${PROJECT_BINARY_DIR}/tests) - add_dependencies(${TEST_TARGET_NAME} - ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_MRT_TARGETS} ${MRT_ADD_ROS_TESTS_DEPENDS} - ) - set_target_properties(${TEST_TARGET_NAME} PROPERTIES OUTPUT_NAME ${TEST_NAME}) - set(TARGET_ADDED True) - else() - message(STATUS "Adding plain rostest \"${_ros_test}\"") - add_rostest(${_ros_test} - DEPENDENCIES ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_MRT_TARGETS} ${MRT_ADD_ROS_TESTS_DEPENDS} - ) - endif() - endforeach() - if(MRT_ENABLE_COVERAGE AND TARGET_ADDED AND NOT TARGET ${PROJECT_NAME}-coverage AND TARGET run_tests) - _setup_coverage_info() - endif() - _mrt_register_test() -endfunction() - -# -# Adds all gtests (without a corresponding .test file) contained in a folder as unittests. -# -# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument -# :type folder: string -# :param LIBRARIES: Additional (non-catkin, non-mrt) libraries to link to -# :type LIBRARIES: list of strings -# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) -# :type DEPENDS: list of strings -# -# -# Unittests will be executed with the folder as cwd if ctest or the run_test target is used. E.g. if the test folder contains a sub-folder "test_data", it can simply be accessed as "test_data". -# Another way of getting the location of the project root folder path is to ``#include "test/test_utility.hpp"`` and use the variable ``::test::projectRootDir``. -# -# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. -# -# If coverage information is enabled (by setting ``MRT_ENABLE_COVARAGE`` to true), coverage analysis will be performed after unittests have run. The results can be found in the package's build folder in the folder "coverage". -# -# Example: -# :: -# -# mrt_add_tests( test -# ) -# -# @@public -# -function(mrt_add_tests folder) - set(TEST_FOLDER ${folder}) - cmake_parse_arguments(MRT_ADD_TESTS "" "" "LIBRARIES;DEPENDS" ${ARGN}) - mrt_glob_files(_tests "${TEST_FOLDER}/*.cpp" "${TEST_FOLDER}/*.cc") - configure_file(${MCM_ROOT}/cmake/Templates/test_utility.hpp.in ${PROJECT_BINARY_DIR}/tests/test/test_utility.hpp @@ONLY) - - foreach(_test ${_tests}) - get_filename_component(_test_name ${_test} NAME_WE) - # make sure we add only one -test to the target - STRING(REGEX REPLACE "-test" "" TEST_TARGET_NAME ${_test_name}) - set(TEST_TARGET_NAME ${PROJECT_NAME}-${TEST_TARGET_NAME}-test) - # exclude cpp files with a test file (those are ros tests) - if(NOT EXISTS "${PROJECT_SOURCE_DIR}/${TEST_FOLDER}/${_test_name}.test") - message(STATUS "Adding gtest unittest \"${TEST_TARGET_NAME}\" with working dir ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}") - catkin_add_gtest(${TEST_TARGET_NAME} ${_test} WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}) - target_link_libraries(${TEST_TARGET_NAME} - ${${PROJECT_NAME}_GENERATED_LIBRARIES} - ${catkin_LIBRARIES} - ${mrt_TEST_LIBRARIES} - ${MRT_ADD_TESTS_LIBRARIES} - ${MRT_SANITIZER_EXE_CXX_FLAGS} - ${MRT_SANITIZER_LINK_FLAGS} - gtest_main) - target_compile_options(${TEST_TARGET_NAME} - PRIVATE ${MRT_SANITIZER_EXE_CXX_FLAGS} - ) - target_include_directories(${TEST_TARGET_NAME} - PRIVATE ${PROJECT_BINARY_DIR}/tests) - - add_dependencies(${TEST_TARGET_NAME} - ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_MRT_TARGETS} ${MRT_ADD_TESTS_DEPENDS} - ) - set(TARGET_ADDED True) - endif() - endforeach() - if(MRT_ENABLE_COVERAGE AND TARGET_ADDED AND NOT TARGET ${PROJECT_NAME}-coverage AND TARGET run_tests) - _setup_coverage_info() - endif() - _mrt_register_test() -endfunction() - - -# Adds python nosetest contained in a folder. Wraps the function catkin_add_nosetests. -# -# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument -# :type folder: string -# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) -# :type DEPENDS: list of strings -# :param DEPENDENCIES: Alias for DEPENDS -# :type DEPENDENCIES: list of strings -# -# Example: -# :: -# -# mrt_add_nosetests(test) -# -# @@public -# -function(mrt_add_nosetests folder) - set(TEST_FOLDER ${folder}) - cmake_parse_arguments(MRT_ADD_NOSETESTS "" "" "DEPENDS;DEPENDENCIES" ${ARGN}) - if(NOT IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}) - return() - endif() - - message(STATUS "Adding nosetests in folder ${TEST_FOLDER}") - catkin_add_nosetests(${TEST_FOLDER} - DEPENDENCIES ${MRT_ADD_NOSETESTS_DEPENDENCIES} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_PYTHON_API_TARGET} - ) - if(MRT_ENABLE_COVERAGE AND MRT_FORCE_PYTHON_COVERAGE AND NOT TARGET ${PROJECT_NAME}-coverage AND TARGET run_tests) - _setup_coverage_info() - endif() - _mrt_register_test() -endfunction() - - -# Installs all relevant project files. -# -# All targets added by the mrt_add_ commands will be installed automatically when using this command. Other files/folders (launchfiles, scripts) need to be specified explicitly. -# Non existing files and folders will be silently ignored. All files will be marked as project files for IDEs. -# -# :param PROGRAMS: List of all folders and files that are programs (python scripts will be indentified and treated separately). Files will be made executable. -# :type PROGRAMS: list of strings -# :param FILES: List of non-executable files and folders. Subfolders will be installed recursively. -# :type FILES: list of strings -# -# Example: -# :: -# -# mrt_install( -# PROGRAMS scripts -# FILES launch nodelet_plugins.xml -# ) -# -# @@public -# -function(mrt_install) - cmake_parse_arguments(MRT_INSTALL "" "" "PROGRAMS;FILES" ${ARGN}) - - # install targets - if(${PROJECT_NAME}_MRT_TARGETS) - message(STATUS "Marking targets \"${${PROJECT_NAME}_MRT_TARGETS}\" of package \"${PROJECT_NAME}\" for installation") - install(TARGETS ${${PROJECT_NAME}_MRT_TARGETS} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - endif() - - # install header - if(EXISTS ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}/) - message(STATUS "Marking HEADER FILES in \"include\" folder of package \"${PROJECT_NAME}\" for installation") - install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - PATTERN ".gitignore" EXCLUDE - ) - endif() - - # helper function for installing programs - function(mrt_install_program program_path) - get_filename_component(extension ${program_path} EXT) - get_filename_component(program ${program_path} NAME) - if("${extension}" STREQUAL ".py") - message(STATUS "Marking PYTHON PROGRAM \"${program}\" of package \"${PROJECT_NAME}\" for installation") - catkin_install_python(PROGRAMS ${program_path} - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - else() - message(STATUS "Marking PROGRAM \"${program}\" of package \"${PROJECT_NAME}\" for installation") - install(PROGRAMS ${program_path} - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - endif() - endfunction() - - # install programs - foreach(ELEMENT ${MRT_INSTALL_PROGRAMS}) - if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${ELEMENT}) - mrt_glob_files(FILES "${PROJECT_SOURCE_DIR}/${ELEMENT}/[^.]*[^~]") - foreach(FILE ${FILES}) - if(NOT IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${FILE}) - mrt_install_program(${FILE}) - endif() - endforeach() - elseif(EXISTS ${PROJECT_SOURCE_DIR}/${ELEMENT}) - mrt_install_program(${ELEMENT}) - endif() - endforeach() - - # install files - foreach(ELEMENT ${MRT_INSTALL_FILES}) - if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${ELEMENT}) - message(STATUS "Marking SHARED CONTENT FOLDER \"${ELEMENT}\" of package \"${PROJECT_NAME}\" for installation") - install(DIRECTORY ${ELEMENT} - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - elseif(EXISTS ${PROJECT_SOURCE_DIR}/${ELEMENT}) - message(STATUS "Marking FILE \"${ELEMENT}\" of package \"${PROJECT_NAME}\" for installation") - install(FILES ${ELEMENT} DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) - endif() - endforeach() -endfunction() diff --git a/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.in b/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.in new file mode 100644 index 00000000000..0a4965f2912 --- /dev/null +++ b/mrt_cmake_modules/cmake/mrt_cmake_modules-extras.cmake.in @@ -0,0 +1,26 @@ +# Generated from: mrt_cmake_modules/cmake/mrt_cmake_modules-extra.cmake.in +if(_MRT_CMAKE_MODULES_EXTRAS_INCLUDED_) + return() +endif() +set(_MRT_CMAKE_MODULES_EXTRAS_INCLUDED_ TRUE) + +# Check cmakelists version +set(_MRT_RECOMMENDED_VERSION 4.0) +if(MRT_PKG_VERSION AND MRT_PKG_VERSION VERSION_LESS _MRT_RECOMMENDED_VERSION ) + message(WARNING "Current CMakeLists.txt version is less than the recommended version ${_MRT_RECOMMENDED_VERSION}. If you are the maintainer, please update it with\n'mrt maintenance update_cmakelists ${PROJECT_NAME}'.") +endif() + +# Set the cmake install path +if(@DEVELSPACE@) + # cmake dir in develspace + set(MRT_CMAKE_MODULES_ROOT_PATH "@PROJECT_SOURCE_DIR@") + set(MRT_CMAKE_MODULES_CMAKE_PATH "@PROJECT_SOURCE_DIR@/cmake") +else() + # cmake dir in installspace + set(MRT_CMAKE_MODULES_ROOT_PATH "${mrt_cmake_modules_DIR}/..") + set(MRT_CMAKE_MODULES_CMAKE_PATH "${mrt_cmake_modules_DIR}") +endif() + +list(APPEND CMAKE_MODULE_PATH "${MRT_CMAKE_MODULES_CMAKE_PATH}/Modules") +set(MCM_TEMPLATE_DIR "${MRT_CMAKE_MODULES_CMAKE_PATH}/Templates") +include(${MRT_CMAKE_MODULES_CMAKE_PATH}/mrt_cmake_modules-macros.cmake) diff --git a/mrt_cmake_modules/cmake/mrt_cmake_modules-macros.cmake b/mrt_cmake_modules/cmake/mrt_cmake_modules-macros.cmake new file mode 100644 index 00000000000..9c00a3ab5a0 --- /dev/null +++ b/mrt_cmake_modules/cmake/mrt_cmake_modules-macros.cmake @@ -0,0 +1,1524 @@ +include(${MRT_CMAKE_MODULES_CMAKE_PATH}/Modules/MrtTesting.cmake) + +# care for clang-tidy flags +if(MRT_CLANG_TIDY STREQUAL "check") + set(MRT_CLANG_TIDY_FLAGS "-extra-arg=-Wno-unknown-warning-option" "-header-filter=${PROJECT_SOURCE_DIR}/.*") +elseif(MRT_CLANG_TIDY STREQUAL "fix") + set(MRT_CLANG_TIDY_FLAGS "-extra-arg=-Wno-unknown-warning-option" "-fix-errors" + "-header-filter=${PROJECT_SOURCE_DIR}/.*" "-format-style=file") +endif() +if(DEFINED MRT_CLANG_TIDY_FLAGS) + if(${CMAKE_VERSION} VERSION_LESS "3.6.0") + message(WARNING "Using clang-tidy requires at least CMAKE 3.6.0. Please upgrade CMake.") + endif() + find_package(ClangTidy) + if(ClangTidy_FOUND) + message(STATUS "Add clang tidy flags") + set(CMAKE_CXX_CLANG_TIDY "${ClangTidy_EXE}" "${MRT_CLANG_TIDY_FLAGS}") + else() + message(WARNING "Failed to find clang-tidy. Is it installed?") + endif() +endif() +unset(MRT_CLANG_TIDY_FLAGS) + +# Disable that all dependant packages are treated as "system" packages (suppressing all warnings from there). +# We later add the "system" explicitly to all include dirs of parent workspaces. +set(CMAKE_NO_SYSTEM_FROM_IMPORTED YES) + +# construct the mrt_sanitizer_lib_flags and mrt_sanitizer_exe_flags target based on the configuation in the MRT_SANITIZER variable +if(NOT TARGET ${PROJECT_NAME}_sanitizer_lib_flags AND NOT TARGET ${PROJECT_NAME}_sanitizer_exe_flags) + add_library(${PROJECT_NAME}_sanitizer_lib_flags INTERFACE) + add_library(${PROJECT_NAME}_sanitizer_exe_flags INTERFACE) + set(gcc_cxx "$,$,$,6.3>>") + if(MRT_SANITIZER STREQUAL "checks" OR MRT_SANITIZER STREQUAL "check_race") + # note: in no-recover mode, we still recover from nullptr issues. This mitigates problems with serialization libs + # (like boost::serialzation and cereal) that use this hack to force template instanciation. + target_compile_options( + ${PROJECT_NAME}_sanitizer_lib_flags + INTERFACE + $<$>:-fsanitize=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + $<$>:-fsanitize=thread,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + $<$>:-fno-sanitize-recover=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + $<$>:$,-fsanitize-recover=alignment$null,-fsanitize-recover=alignment>> + ) + target_compile_options( + ${PROJECT_NAME}_sanitizer_exe_flags + INTERFACE + $<$>:-fsanitize=address,leak,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + $<$>:-fsanitize=thread,undefined,float-divide-by-zero,float-cast-overflow> + $<$>:-fno-sanitize-recover=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + $<$>:$,-fsanitize-recover=alignment$null,-fsanitize-recover=alignment>> + ) + target_link_options( + ${PROJECT_NAME}_sanitizer_lib_flags + INTERFACE + $<$>:-fsanitize=undefined,bounds-strict,float-divide-by-zero,float-cast-overflow;-fsanitize-recover=alignment> + $<$>:-fsanitize=thread,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow> + ) + target_link_options( + ${PROJECT_NAME}_sanitizer_exe_flags + INTERFACE + $<$>:-fsanitize=address,leak,undefined,bounds-strict,float-divide-by-zero,float-cast-overflow;-fsanitize-recover=alignment> + $<$>:-fsanitize=thread,undefined,float-divide-by-zero,float-cast-overflow> + ) + # your brain just exploded due to all this? mine did too... + endif() +endif() # create sanitizer target + +# set install dirs (CMAKE_INSTALL_). We use them over catkins dirs, but use the same layout as catkin does by default. +include(GNUInstallDirs) +if(NOT CATKIN_DEVEL_PREFIX) + set(CATKIN_DEVEL_PREFIX ${CMAKE_CURRENT_BINARY_DIR}/devel) +endif() +if(NOT EXISTS ${CATKIN_DEVEL_PREFIX}/include) + # ensure that the devel include folder exists + file(MAKE_DIRECTORY ${CATKIN_DEVEL_PREFIX}/include) +endif() + +# set the ros version +if(DEFINED ENV{ROS_VERSION}) + set(ROS_VERSION $ENV{ROS_VERSION}) +endif() + +# make sure catkin/ament are found so that PYTHON_EXECUTABLE (and CATKIN_ENV) is set. +if(NOT PYTHON_VERSION AND DEFINED $ENV{ROS_PYTHON_VERSION}) + set(PYTHON_VERSION + $ENV{ROS_PYTHON_VERSION} + CACHE STRING "Python version to use ('major.minor' or 'major')") +endif() + +if(ROS_VERSION EQUAL 1) + find_package(catkin REQUIRED) + set(MRT_CMAKE_ENV sh ${CATKIN_ENV}) +elseif(ROS_VERSION EQUAL 2) + find_package(ament_cmake_core REQUIRED) + if(NOT DEFINED BUILD_TESTING OR BUILD_TESTING) + # our cmake template still relies on CATKIN_ENABLE_TESTING + set(CATKIN_ENABLE_TESTING TRUE) + endif() +else() + set(CATKIN_ENABLE_TESTING TRUE) +endif() +# would be nicer to put this in a function, but cmake requires this at global scope +if(CATKIN_ENABLE_TESTING) + enable_testing() +endif() + +# set some global variables needed/modified by the functions below +# list of folders containing a folder "" with headers required by this project. These will be installed by mrt_install. +set(${PROJECT_NAME}_LOCAL_INCLUDE_DIRS "${CMAKE_CURRENT_SOURCE_DIR}/include;${CATKIN_DEVEL_PREFIX}/include") +set(${PROJECT_NAME}_PYTHON_API_TARGET "") # contains the list of python api targets +set(${PROJECT_NAME}_GENERATED_LIBRARIES "") # the list of library targets built and installed by the tools +set(${PROJECT_NAME}_MRT_TARGETS "") # list of all public installable targets created by the functions here + +# this function determines all includes directories that belong to parent workspaces (including the ros installation). +# we later mark all of these directories as system directories so that warnings from these headers are hidden. +# It is important to maintain the order of CMAKE_INSTALL_PREFIX so that the include order matches the order in which workspaces are overlayed. +function(_get_parent_workspace_include_dirs outdir) + # Assuming the parent directory of the install dir is the workspace. + # Not the best assumption but it works (in the worst case we mark too much headers as "system") + get_filename_component(current_workspace ${CMAKE_INSTALL_PREFIX} DIRECTORY) + + set(workspace_include_dirs) + foreach(workspace ${CMAKE_PREFIX_PATH}) + string(FIND ${workspace} ${current_workspace} _is_current_workspace) + if(NOT ${_is_current_workspace} EQUAL -1) + continue() + endif() + foreach(_include_dir ${mrt_EXPORT_INCLUDE_DIRS}) + string(FIND ${_include_dir} ${workspace} _pos) + if(NOT ${_pos} EQUAL -1) + list(APPEND workspace_include_dirs ${_include_dir}) + endif() + endforeach() + endforeach() + set(${outdir} + ${workspace_include_dirs} + PARENT_SCOPE) +endfunction() + +# define rosparam/rosinterface_handler macro for compability. Macros will be overriden by the actual macros defined by the packages, if existing. +macro(generate_ros_parameter_files) + # handle pure dynamic reconfigure files + foreach(_cfg ${ARGN}) + get_filename_component(_cfgext ${_cfg} EXT) + if(_cfgext STREQUAL ".cfg") + list(APPEND _${PROJECT_NAME}_pure_cfg_files "${_cfg}") + else() + list(APPEND _${PROJECT_NAME}_rosparam_other_param_files "${_cfg}") + endif() + endforeach() + # generate dynamic reconfigure files + if(_${PROJECT_NAME}_pure_cfg_files + AND NOT TARGET ${PROJECT_NAME}_gencfg + AND NOT (rosinterface_handler_FOUND_CATKIN_PROJECT OR rosinterface_handler_FOUND)) + if(dynamic_reconfigure_FOUND_CATKIN_PROJECT) + generate_dynamic_reconfigure_options(${_${PROJECT_NAME}_pure_cfg_files}) + else() + message( + WARNING + "Dependency to dynamic_reconfigure is missing, or find_package(dynamic_reconfigure) was not called yet. Not building dynamic config files" + ) + endif() + endif() + # if there are other config files, someone will have forgotten to include the rosparam/rosinterface handler + if(_${PROJECT_NAME}_rosparam_other_param_files AND NOT (rosinterface_handler_FOUND_CATKIN_PROJECT + OR rosinterface_handler_FOUND)) + message( + FATAL_ERROR + "Dependency rosinterface_handler or rosparam_handler could not be found. Did you add it to your package.xml?" + ) + endif() +endmacro() +macro(generate_ros_interface_files) + # handle pure dynamic reconfigure files + foreach(_cfg ${ARGN}) + get_filename_component(_cfgext ${_cfg} EXT) + if(NOT _cfgext STREQUAL ".cfg") + list(APPEND _${PROJECT_NAME}_rosif_other_param_files "${_cfg}") + endif() + endforeach() + if(_${PROJECT_NAME}_rosif_other_param_files AND NOT (rosparam_handler_FOUND_CATKIN_PROJECT + OR rosinterface_handler_FOUND)) + message( + FATAL_ERROR + "Dependency rosinterface_handler or rosparam_handler could not be found. Did you add it to your package.xml?" + ) + endif() +endmacro() + +macro(_setup_coverage_info) + setup_target_for_coverage(${PROJECT_NAME}-coverage coverage ${PROJECT_NAME}-pre-coverage) + # make sure the target is built after running tests + add_dependencies(run_tests ${PROJECT_NAME}-coverage) + add_dependencies(${PROJECT_NAME}-coverage _run_tests_${PROJECT_NAME}) + if(TARGET ${PROJECT_NAME}-pre-coverage) + add_dependencies(clean_test_results_${PROJECT_NAME} ${PROJECT_NAME}-pre-coverage) + add_dependencies(${PROJECT_NAME}-pre-coverage tests) + endif() + if(MRT_ENABLE_COVERAGE GREATER 1) + add_custom_command( + TARGET ${PROJECT_NAME}-coverage + POST_BUILD + COMMAND firefox ${CMAKE_CURRENT_BINARY_DIR}/coverage/index.html > /dev/null 2>&1 & + COMMENT "Showing coverage results") + endif() +endmacro() + +macro(_mrt_register_ament_python_hook) + # ament is different in catkin that you have to register environment hooks for everything + # code was taken from ament_cmake_python + if(NOT _MRT_AMENT_PYTHON_HOOK_REGISTERED) + find_package(ament_cmake_core QUIET REQUIRED) + # use native separators in environment hook to match what pure Python packages do + file(TO_NATIVE_PATH "${destination}" destination) + + # register information for .dsv generation + _mrt_get_python_destination(PYTHON_INSTALL_DIR) + set(AMENT_CMAKE_ENVIRONMENT_HOOKS_DESC_pythonpath "prepend-non-duplicate;PYTHONPATH;${destination}") + ament_environment_hooks("${ament_cmake_package_templates_ENVIRONMENT_HOOK_PYTHONPATH}") + set(_MRT_AMENT_PYTHON_HOOK_REGISTERED + TRUE + PARENT_SCOPE) + endif() +endmacro() + +# +# Parses the package.xml and sets its information in form of cmake variables as ${PACKAGE_NAME}_, where info is +# one of version, VERSION, MAINTAINER, PACKAGE_FORMAT, _DEPENDS, URL_ +# +# This function must be called before any other of the mrt_* functions can be called. +# +# @public +# +macro(mrt_parse_package_xml) + # TODO: replace this by our own stuff. + if(NOT COMMAND catkin_package_xml AND ROS_VERSION EQUAL 1) + find_package(catkin REQUIRED) + elseif(NOT COMMAND ament_package_xml AND ROS_VERSION EQUAL 2) + find_package(ament_cmake_core REQUIRED) + endif() + if(ROS_VERSION EQUAL 1) + catkin_package_xml() + elseif(ROS_VERSION EQUAL 2) + ament_package_xml() + endif() +endmacro() + +# +# Adds all the librares and targets that this target should be linked against. This includes dependencies found by AutoDeps, compiler flags and sanitizers. +# Also sets all local include directories usually required by the target +# +# This function is automatically called for all targets created with mrt_add_(executable/library/test/...). +# +# :param CUDA: indicates this is cuda and not C++ code +# +# Example: +# :: +# +# mrt_add_links(my_target [CUDA] +# ) +# +# @public +# +function(mrt_add_links target) + cmake_parse_arguments(ARG "CUDA;NO_SANITIZER;TEST" "" "" ${ARGN}) + get_target_property(target_type ${target} TYPE) + + # add dependencies + if(ARG_CUDA) + # this is a cuda target + if(TARGET ${PROJECT_NAME}::auto_deps_cuda) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}::auto_deps_cuda) + endif() + else() + if(NOT target_type STREQUAL "INTERFACE_LIBRARY") + if(TARGET ${PROJECT_NAME}::auto_deps) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}::auto_deps) + endif() + if(TARGET ${PROJECT_NAME}::auto_deps_export) + # we use the namespaced alias here, because this is how other subdirectories see it + target_link_libraries(${target} PUBLIC ${PROJECT_NAME}::auto_deps_export) + endif() + else() + if(NOT (MRT_PKG_VERSION AND MRT_PKG_VERSION VERSION_LESS "3.0.2") AND TARGET + ${PROJECT_NAME}::auto_deps_export) + # On old cmakelists still using catkin_package, we cannot use the export target on interface libraries, + # because catkin tries to interpret generator expressions as libraries. We instead export them though mrt_EXPORTED_LIBRARIES. + target_link_libraries(${target} INTERFACE ${PROJECT_NAME}::auto_deps_export) + endif() + endif() + + endif() + # add test depends + if(ARG_TEST AND TARGET ${PROJECT_NAME}::auto_deps_test) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}::auto_deps_test) + endif() + + # add include dirs + if(NOT target_type STREQUAL "INTERFACE_LIBRARY") + # For convenience, targets within the project can omit the project name for including local headers + if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/include/${PROJECT_NAME} AND NOT MRT_NO_LOCAL_INCLUDE) + target_include_directories(${target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include/${PROJECT_NAME}) + endif() + # set the include dir for installation and dependent targets. + foreach(include ${${PROJECT_NAME}_LOCAL_INCLUDE_DIRS}) + if(EXISTS ${include}) + target_include_directories(${target} PUBLIC $) + endif() + endforeach() + # mark all include include dirs from parent workspaces as "system" (silence warnings from these) + _get_parent_workspace_include_dirs(workspace_include_dirs) + if(workspace_include_dirs) + target_include_directories(${target} SYSTEM PRIVATE ${workspace_include_dirs}) + endif() + else() + # set the include dir for installation and dependent targets. + foreach(include ${${PROJECT_NAME}_LOCAL_INCLUDE_DIRS}) + if(EXISTS ${include}) + target_include_directories(${target} INTERFACE $) + endif() + endforeach() + endif() + if(NOT target_type STREQUAL "EXECUTABLE") + target_include_directories(${target} INTERFACE $) + endif() + + # add sanitizer flags if set + if(NOT ARG_NO_SANITIZER) + if(target_type STREQUAL "EXECUTABLE") + if(TARGET ${PROJECT_NAME}_sanitizer_exe_flags) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}_sanitizer_exe_flags) + endif() + elseif(NOT target_type STREQUAL "INTERFACE_LIBRARY") + if(TARGET ${PROJECT_NAME}_sanitizer_lib_flags) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}_sanitizer_lib_flags) + endif() + endif() + endif() + + # add compile flags + if(ARG_CUDA) + # below cmake 3.17, setting cpp standard also affects the cuda standard. So we cannot use the normal compiler_flags. + if(TARGET cuda_compiler_flags) + target_link_libraries(${target} PRIVATE cuda_compiler_flags) + endif() + elseif(NOT target_type STREQUAL "INTERFACE_LIBRARY") + if(TARGET ${PROJECT_NAME}_compiler_flags) + target_link_libraries(${target} PUBLIC ${PROJECT_NAME}_compiler_flags) + endif() + if(TARGET ${PROJECT_NAME}_private_compiler_flags) + target_link_libraries(${target} PRIVATE ${PROJECT_NAME}_private_compiler_flags) + endif() + else() + if(NOT (MRT_PKG_VERSION AND MRT_PKG_VERSION VERSION_LESS "3.0.2") AND TARGET ${PROJECT_NAME}_compiler_flags) + # We can not add flags with generator expression to interface libraries because catkin interprets them as libraries. + # Its not a problem though, because catkin wouldn't export these flags anyways. + target_link_libraries(${target} INTERFACE ${PROJECT_NAME}_compiler_flags) + endif() + endif() # interface library or not + + # set dependencies to exported targets like messages and such + set(_deps ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS}) + if(_deps) + add_dependencies(${target} ${_deps}) + endif() +endfunction() + +function(_mrt_get_python_destination output_var) + if(DEFINED MRT_PYTHON_INSTALL_DESTINATION) + set(${output_var} + ${MRT_PYTHON_INSTALL_DESTINATION} + PARENT_SCOPE) + return() + endif() + if(PYTHON_VERSION) + set(_python_version ${PYTHON_VERSION}) + elseif(DEFINED ENV{ROS_PYTHON_VERSION}) + set(_python_version $ENV{ROS_PYTHON_VERSION}) + endif() + # finding python sets PYTHON_VERSION_ + if(CMAKE_VERSION VERSION_LESS 3.12) + set(Python_ADDITIONAL_VERSIONS ${_python_version}) + find_package(PythonInterp REQUIRED) + elseif(_python_version VERSION_LESS 3) + find_package(Python2 REQUIRED) + else() + find_package(Python3 REQUIRED) + endif() + # seems ros2 found an even more complex way to determine the install location... + if(NOT ROS_VERSION EQUAL 1) + set(_python_code + "from distutils.sysconfig import get_python_lib" + "import os" + "print(os.path.relpath(get_python_lib(prefix='${CMAKE_INSTALL_PREFIX}'), start='${CMAKE_INSTALL_PREFIX}').replace(os.sep, '/'))" + ) + execute_process( + COMMAND "${PYTHON_EXECUTABLE}" "-c" "${_python_code}" + OUTPUT_VARIABLE _output + RESULT_VARIABLE _result + OUTPUT_STRIP_TRAILING_WHITESPACE) + set(${output_var} ${_output}) + elseif(WIN32) + set(${output_var} lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages) + elseif(EXISTS "/etc/debian_version") + if("${PYTHON_VERSION_MAJOR}" STREQUAL "3") + set(${output_var} lib/python${PYTHON_VERSION_MAJOR}/dist-packages) + else() + set(${output_var} lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/dist-packages) + endif() + else() + set(${output_var} lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages) + endif() + set(${output_var} + ${${output_var}} + PARENT_SCOPE) + set(MRT_PYTHON_INSTALL_DESTINATION + ${${output_var}} + CACHE INTERNAL "Installation dir for python files") +endfunction() + +# Glob for folders in the search directory. +function(mrt_glob_folders DIRECTORY_LIST SEARCH_DIRECTORY) + if(${CMAKE_VERSION} VERSION_LESS "3.12.0") + file(GLOB DIRECTORIES "${SEARCH_DIRECTORY}/[^.]*") + else() + file(GLOB DIRECTORIES CONFIGURE_DEPENDS "${SEARCH_DIRECTORY}/[^.]*") + endif() + + set(_DIRECTORY_LIST_ "") + foreach(SRC_DIR ${DIRECTORIES}) + if(IS_DIRECTORY "${SRC_DIR}") + get_filename_component(DIRECTORY_NAME "${SRC_DIR}" NAME) + list(APPEND _DIRECTORY_LIST_ ${DIRECTORY_NAME}) + endif() + endforeach() + set(${DIRECTORY_LIST} + ${_DIRECTORY_LIST_} + PARENT_SCOPE) +endfunction() + +# Deprecated function. Use 'mrt_glob_folders' instead. +macro(glob_folders) + mrt_glob_folders(${ARGV}) +endmacro() + +# Globs for message files and calls add_message_files +macro(mrt_add_message_files folder_name) + mrt_glob_files(_ROS_MESSAGE_FILES REL_FOLDER ${folder_name} ${folder_name}/*.msg) + if(_ROS_MESSAGE_FILES) + add_message_files(FILES ${_ROS_MESSAGE_FILES} DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${folder_name}") + set(ROS_GENERATE_MESSAGES True) + endif() +endmacro() + +# Globs for service files and calls add_service_files +macro(mrt_add_service_files folder_name) + mrt_glob_files(_ROS_SERVICE_FILES REL_FOLDER ${folder_name} ${folder_name}/*.srv) + if(_ROS_SERVICE_FILES) + add_service_files(FILES ${_ROS_SERVICE_FILES} DIRECTORY "${CMAKE_CURRENT_LIST_DIR}/${folder_name}") + set(ROS_GENERATE_MESSAGES True) + endif() +endmacro() + +# Globs for action files and calls add_action_files +macro(mrt_add_action_files folder_name) + mrt_glob_files(_ROS_ACTION_FILES REL_FOLDER ${folder_name} ${folder_name}/*.action) + if(_ROS_ACTION_FILES) + add_action_files(FILES ${_ROS_ACTION_FILES} DIRECTORY "${folder_name}") + set(ROS_GENERATE_ACTION True) + endif() +endmacro() + +# Deprecated function. Use one of 'mrt_add_message_files', 'mrt_add_service_files' or 'mrt_add_action_files'. +macro(glob_ros_files excecutable_name extension_name) + mrt_glob_files(ROS_${excecutable_name}_FILES REL_FOLDER ${extension_name} "${extension_name}/*.${extension_name}") + + if(ROS_${excecutable_name}_FILES) + #work around to execute a command wich name is given in a variable + #write a file with the command, include it and delete the file again + file( + WRITE "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake" + "${excecutable_name}( + DIRECTORY \"${PROJECT_SOURCE_DIR}/${extension_name}\" + FILES + ${ROS_${excecutable_name}_FILES} + )") + include("${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake") + file(REMOVE "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/_GLOB_ROS_TEMP_FILE.cmake") + + set(ROS_GENERATE_MESSAGES True) + endif() +endmacro() + +# Globs files in the currect project dir. +function(mrt_glob_files varname) + cmake_parse_arguments(PARAMS "" "REL_FOLDER" "" ${ARGN}) + + if(PARAMS_REL_FOLDER) + set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}/${PARAMS_REL_FOLDER}") + else() + set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}") + endif() + + if(${CMAKE_VERSION} VERSION_LESS "3.12.0") + file( + GLOB files + RELATIVE "${RELATIVE_PATH}" + ${PARAMS_UNPARSED_ARGUMENTS}) + else() + file( + GLOB files + RELATIVE "${RELATIVE_PATH}" + CONFIGURE_DEPENDS ${PARAMS_UNPARSED_ARGUMENTS}) + endif() + set(${varname} + ${files} + PARENT_SCOPE) +endfunction() + +# Globs files recursivly in the currect project dir. +function(mrt_glob_files_recurse varname) + cmake_parse_arguments(PARAMS "" "REL_FOLDER" "" ${ARGN}) + + if(PARAMS_REL_FOLDER) + set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}/${PARAMS_REL_FOLDER}") + else() + set(RELATIVE_PATH "${PROJECT_SOURCE_DIR}") + endif() + + if(${CMAKE_VERSION} VERSION_LESS "3.12.0") + file( + GLOB_RECURSE files + RELATIVE "${RELATIVE_PATH}" + ${PARAMS_UNPARSED_ARGUMENTS}) + else() + file( + GLOB_RECURSE files + RELATIVE "${RELATIVE_PATH}" + CONFIGURE_DEPENDS ${PARAMS_UNPARSED_ARGUMENTS}) + endif() + set(${varname} + ${files} + PARENT_SCOPE) +endfunction() + +# +# Once upon a time this used to make non-code files known to IDEs that parse Cmake output. But as this +# messes up with the target determination mechanism used by most ides and garbages up the target view. +# +# Therefore this function is no longer used and only here for backwards compability. +# +# @public +# +function(mrt_add_to_ide files) + +endfunction() + +# +# Automatically sets up and installs python modules located under ``src/${PROJECT_NAME}``. +# Modules can afterwards simply be included using "import " in python. +# +# The python folder (under src/${PROJECT_NAME}) is required to have an __init__.py file. +# +# On Ros1, the command will automatically generate a setup.py in your project folder. +# This file should not be commited, as it will be regenerated at every new CMAKE run. +# Due to restrictions imposed by catkin (searches hardcoded for this setup.py), the file cannot +# be placed elsewhere. +# +# Example: +# :: +# +# mrt_python_module_setup() +# +# @public +# +function(mrt_python_module_setup) + if(ARGN) + message(FATAL_ERROR "mrt_python_module_setup() called with unused arguments: ${ARGN}") + endif() + set(module_folder ${PROJECT_SOURCE_DIR}/src/${PROJECT_NAME}) + if(NOT EXISTS "${module_folder}/__init__.py") + return() + endif() + set(${PROJECT_NAME}_PYTHON_MODULE + ${PROJECT_NAME} + PARENT_SCOPE) + if(ROS_VERSION EQUAL 1) + if(NOT catkin_FOUND) + find_package(catkin REQUIRED) + endif() + set(PKG_PYTHON_MODULE ${PROJECT_NAME}) + set(PACKAGE_DIR "src") + configure_file(${MCM_TEMPLATE_DIR}/setup.py.in "${PROJECT_SOURCE_DIR}/setup.py" @ONLY) + catkin_python_setup() + else() + _mrt_get_python_destination(python_destination) + set(destination "${python_destination}/${PROJECT_NAME}") + install( + DIRECTORY "${module_folder}/" + DESTINATION "${python_destination}/${PROJECT_NAME}" + PATTERN "*.pyc" EXCLUDE + PATTERN "__pycache__" EXCLUDE) + # compile Python files + install( + CODE "execute_process( + COMMAND + \"${PYTHON_EXECUTABLE}\" \"-m\" \"compileall\" + \"${CMAKE_INSTALL_PREFIX}/${python_destination}/${PROJECT_NAME}\" + )") + if(ROS_VERSION EQUAL 2) + _mrt_register_ament_python_hook() + endif() + endif() +endfunction() + +# +# Generates a python module from boost-python cpp files. +# +# Each .cpp will become a seperate .py submodule within . After building and sourcing you can use the modules simply with "import .". +# +# The files are automatically linked with boost-python libraries and a python module is generated +# and installed from the resulting library. If this project declares any libraries with ``mrt_add_library()``, they will automatically be linked with this library. +# +# This function will define the compiler variable ``PYTHON_API_MODULE_NAME`` with the name of the generated library. This can be used in the ``BOOST_PYTHON_MODULE`` C++ Macro. +# +# .. note:: This function can only be called once per package. +# +# :param modulename: Name of the module needs to be passed as first parameter. +# :type modulename: string +# :param FILES: list of C++ files defining the BOOST-Python API. +# :type FILES: list of strings +# +# Example: +# :: +# +# mrt_add_python_api( example_package +# FILES python_api/python.cpp +# ) +# +# @public +# +function(mrt_add_python_api modulename) + cmake_parse_arguments(MRT_ADD_PYTHON_API "" "" "FILES" ${ARGN}) + if(NOT MRT_ADD_PYTHON_API_FILES) + return() + endif() + + #set and check target name + set(PYTHON_API_MODULE_NAME ${modulename}) + + if("${PYTHON_API_MODULE_NAME}" STREQUAL "${PROJECT_NAME}") + # mark that catkin_python_setup() was called and the setup.py file contains a package with the same name as the current project + # in order to disable installation of generated __init__.py files in generate_messages() and generate_dynamic_reconfigure_options() + set(${PROJECT_NAME}_CATKIN_PYTHON_SETUP_HAS_PACKAGE_INIT + TRUE + PARENT_SCOPE) + endif() + if(${PROJECT_NAME}_PYTHON_API_TARGET) + message( + FATAL_ERROR + "mrt_add_python_api() was already called for this project. You can add only one python_api per project!" + ) + endif() + + if(NOT pybind11_FOUND AND NOT BoostPython_FOUND) + message( + FATAL_ERROR + "Missing dependency to pybind11 or boost python. Add either 'pybind11-dev' or 'libboost-python-dev' to 'package.xml'" + ) + endif() + + if(pybind11_FOUND AND BoostPython_FOUND) + message(FATAL_ERROR "Found pybind11 and boost python. Only one is allowed.") + endif() + + # put in devel folder + set(DEVEL_PREFIX ${CATKIN_DEVEL_PREFIX}) + _mrt_get_python_destination(python_destination) + set(PYTHON_MODULE_DIR "${DEVEL_PREFIX}/${python_destination}/${PYTHON_API_MODULE_NAME}") + + # add library for each file + foreach(API_FILE ${MRT_ADD_PYTHON_API_FILES}) + get_filename_component(SUBMODULE_NAME ${API_FILE} NAME_WE) + set(TARGET_NAME "${PROJECT_NAME}-${PYTHON_API_MODULE_NAME}-${SUBMODULE_NAME}-pyapi") + set(LIBRARY_NAME ${SUBMODULE_NAME}) + message(STATUS "Adding python api library \"${LIBRARY_NAME}\" to python module \"${PYTHON_API_MODULE_NAME}\"") + + if(pybind11_FOUND) + pybind11_add_module(${TARGET_NAME} MODULE ${API_FILE}) + target_link_libraries(${TARGET_NAME} PRIVATE pybind11::module) + elseif(BoostPython_FOUND) + add_library(${TARGET_NAME} SHARED ${API_FILE}) + target_link_libraries(${TARGET_NAME} PRIVATE ${BoostPython_LIBRARIES} ${PYTHON_LIBRARY}) + endif() + + set_target_properties(${TARGET_NAME} PROPERTIES OUTPUT_NAME ${LIBRARY_NAME} PREFIX "") + # Yes for all build types. Someone setting CMAKE_LIBRARY_OUTPUT_DIRS_DEBUG would screw everything... + set_target_properties( + ${TARGET_NAME} + PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${PYTHON_MODULE_DIR}" + LIBRARY_OUTPUT_DIRECTORY_RELEASE "${PYTHON_MODULE_DIR}" + LIBRARY_OUTPUT_DIRECTORY_RELWITHDEBINFO "${PYTHON_MODULE_DIR}" + LIBRARY_OUTPUT_DIRECTORY_MINSIZEREL "${PYTHON_MODULE_DIR}" + LIBRARY_OUTPUT_DIRECTORY_DEBUG "${PYTHON_MODULE_DIR}") + + target_compile_definitions(${TARGET_NAME} PRIVATE PYTHON_API_MODULE_NAME=${LIBRARY_NAME}) + mrt_add_links(${TARGET_NAME} NO_SANITIZER) # you really don't want to debug python... + list(APPEND GENERATED_TARGETS ${TARGET_NAME}) + endforeach() + if(NOT "${${PROJECT_NAME}_PYTHON_MODULE}" STREQUAL "${PYTHON_API_MODULE_NAME}") + configure_file(${MCM_TEMPLATE_DIR}/__init__.py.in ${PYTHON_MODULE_DIR}/__init__.py) + if(GENERATE_ENVIRONMENT_CACHE_COMMAND) + # regenerate the environment cache. This makes sure PYTHONPATH is set correctly for nosetests + safe_execute_process(COMMAND ${GENERATE_ENVIRONMENT_CACHE_COMMAND}) + endif() + endif() + + # append to list of all targets in this project + set(${PROJECT_NAME}_PYTHON_API_TARGET + ${GENERATED_TARGETS} + PARENT_SCOPE) + if(ROS_VERSION EQUAL 1) + # configure setup.py for install + set(PKG_PYTHON_MODULE ${PYTHON_API_MODULE_NAME}) + set(PACKAGE_DIR ${DEVEL_PREFIX}/${python_destination}) + set(PACKAGE_DATA "*.so*") + configure_file(${MCM_TEMPLATE_DIR}/setup.py.in "${CMAKE_CURRENT_BINARY_DIR}/setup.py" @ONLY) + configure_file(${MCM_TEMPLATE_DIR}/python_api_install.py.in "${CMAKE_CURRENT_BINARY_DIR}/python_api_install.py" + @ONLY) + install(CODE "execute_process(COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/python_api_install.py)") + else() + if(ROS_VERSION EQUAL 2) + _mrt_register_ament_python_hook() + endif() + set(install_destination ${python_destination}/${PYTHON_API_MODULE_NAME}) + install(FILES ${PYTHON_MODULE_DIR}/__init__.py DESTINATION ${install_destination}) + install(TARGETS ${GENERATED_TARGETS} DESTINATION ${install_destination}) + endif() +endfunction() + +# +# Adds a library. +# +# This command ensures the library is compiled with all necessary dependencies. If no files are passed, the command will return silently. +# +# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. +# +# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. +# +# :param libname: Name of the library to generate as first argument (without lib or .so) +# :type libname: string +# :param INCLUDES: Public include files needed to use the library, absolute or relative to ${PROJECT_SOURCE_DIR} +# :type INCLUDES: list of strings +# :param SOURCES: Source files and private headers to be added. If no source files are passed, a header-only library is assumed +# :type SOURCES: list of strings +# :param DEPENDS: List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects. +# :type DEPENDS: list of strings +# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects +# :type LIBRARIES: list of strings +# +# Example: +# :: +# +# mrt_add_library( example_package +# INCLUDES include/example_package/myclass.h include/example_package/myclass2.h +# SOURCES src/myclass.cpp src/myclass.cpp +# ) +# +# @public +# +function(mrt_add_library libname) + set(LIBRARY_NAME ${libname}) + if(NOT LIBRARY_NAME) + message(FATAL_ERROR "No library name specified for call to mrt_add_library!") + endif() + cmake_parse_arguments(MRT_ADD_LIBRARY "" "" "INCLUDES;SOURCES;DEPENDS;LIBRARIES" ${ARGN}) + set(LIBRARY_TARGET_NAME ${LIBRARY_NAME}) + + # generate the library target + if(NOT MRT_ADD_LIBRARY_SOURCES) + # build a "header-only" library. This is done even when there are no files at all, so that pure message packages + # have something other packages can depend on. + message(STATUS "Adding header-only library with files ${MRT_ADD_LIBRARY_INCLUDES}") + add_library(${LIBRARY_TARGET_NAME} INTERFACE) + else() + # normal library (potentially with cuda sources) + foreach(SOURCE_FILE ${MRT_ADD_LIBRARY_SOURCES}) + get_filename_component(FILE_EXT ${SOURCE_FILE} EXT) + if("${FILE_EXT}" STREQUAL ".cu") + list(APPEND _MRT_CUDA_SOURCE_FILES "${SOURCE_FILE}") + else() + list(APPEND _MRT_CPP_SOURCE_FILES "${SOURCE_FILE}") + endif() + endforeach() + + # This is the easiest for a CUDA only library: Create an empty file. + if(NOT _MRT_CPP_SOURCE_FILES) + message(STATUS "CMAKE_CURRENT_BINARY_DIR: ${CMAKE_CURRENT_BINARY_DIR}") + file(WRITE "${CMAKE_CURRENT_BINARY_DIR}/empty.cpp" "") + list(APPEND _MRT_CPP_SOURCE_FILES "${CMAKE_CURRENT_BINARY_DIR}/empty.cpp") + endif() + + # generate the target + message( + STATUS + "Adding library \"${LIBRARY_NAME}\" with source ${_MRT_CPP_SOURCE_FILES}, includes ${MRT_ADD_LIBRARY_INCLUDES}" + ) + add_library(${LIBRARY_TARGET_NAME} ${MRT_ADD_LIBRARY_INCLUDES} ${_MRT_CPP_SOURCE_FILES}) + + # we always build with fPIC to avoid problems when mixing static and shared libs + set_property(TARGET ${LIBRARY_TARGET_NAME} PROPERTY POSITION_INDEPENDENT_CODE ON) + + # extract the major version + if(${PROJECT_NAME}_VERSION) + string(REPLACE "." ";" versions ${${PROJECT_NAME}_VERSION}) + list(GET versions 0 version_major) + set_target_properties( + ${LIBRARY_TARGET_NAME} + PROPERTIES OUTPUT_NAME ${LIBRARY_NAME} + SOVERSION ${version_major} + VERSION ${${PROJECT_NAME}_VERSION}) + endif() + target_compile_options(${LIBRARY_TARGET_NAME} PRIVATE ${MRT_SANITIZER_CXX_FLAGS}) + if(MRT_ADD_LIBRARY_LIBRARIES) + target_link_libraries(${LIBRARY_TARGET_NAME} PRIVATE ${MRT_ADD_LIBRARY_LIBRARIES}) + endif() + endif() + # link to python_api if existing (needs to be declared before this library) + foreach(_py_api_target ${${PROJECT_NAME}_PYTHON_API_TARGET}) + target_link_libraries(${_py_api_target} PRIVATE ${LIBRARY_TARGET_NAME}) + endforeach() + set(${PROJECT_NAME}_EXPORTED_TARGETS + ${${PROJECT_NAME}_EXPORTED_TARGETS} ${${PROJECT_NAME}_PYTHON_API_TARGET} + PARENT_SCOPE) + + mrt_add_links(${LIBRARY_TARGET_NAME}) + + # Add cuda target + if(_MRT_CUDA_SOURCE_FILES) + if(NOT DEFINED CUDA_FOUND) + message( + FATAL_ERROR + "Found CUDA source file but no dependency to CUDA. Please add cuda to your package.xml." + ) + endif() + + # generate cuda target + set(CUDA_TARGET_NAME _${LIBRARY_TARGET_NAME}_cuda) + # NVCC does not like '-' in file names. + string(REPLACE "-" "_" CUDA_TARGET_NAME ${CUDA_TARGET_NAME}) + + message(STATUS "Adding library \"${CUDA_TARGET_NAME}\" with source ${_MRT_CUDA_SOURCE_FILES}") + + if(${CMAKE_VERSION} VERSION_LESS "3.9.0") + cuda_add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCE_FILES}) + else() + add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCE_FILES}) + # We cannot link to all libraries as nvcc does not unterstand all the flags + # etc. which could be passed to target_link_libraries as a target. So the + # dependencies were added to the mrt_CUDA_LIBRARIES variable. + target_compile_options(${CUDA_TARGET_NAME} PRIVATE --compiler-options -fPIC) + set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY POSITION_INDEPENDENT_CODE ON) + set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY CUDA_SEPARABLE_COMPILATION ON) + mrt_add_links(${CUDA_TARGET_NAME} CUDA) + endif() + + # link cuda library to normal library + target_link_libraries(${LIBRARY_TARGET_NAME} PRIVATE ${CUDA_TARGET_NAME}) + endif() + + # append to list of all targets in this project + set(${PROJECT_NAME}_GENERATED_LIBRARIES + ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${LIBRARY_TARGET_NAME} ${CUDA_TARGET_NAME} + PARENT_SCOPE) + set(${PROJECT_NAME}_MRT_TARGETS + ${${PROJECT_NAME}_MRT_TARGETS} ${LIBRARY_TARGET_NAME} ${CUDA_TARGET_NAME} + PARENT_SCOPE) +endfunction() + +# +# Adds an executable. +# +# This command ensures the executable is compiled with all necessary dependencies. +# +# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. +# +# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. +# +# :param execname: name of the executable +# :type execname: string +# :param FOLDER: Folder containing the .cpp/.cc-files and .h/.hh/.hpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}``. +# :type FOLDER: string +# :param FILES: List of extra source files to add. This or the FOLDER parameter is mandatory. +# :type FILES: list of strings +# :param DEPENDS: List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects. +# :type DEPENDS: list of strings +# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects +# :type LIBRARIES: list of strings +# +# Example: +# :: +# +# mrt_add_executable( example_package +# FOLDER src/example_package +# ) +# +# @public +# +function(mrt_add_executable execname) + set(EXEC_NAME ${execname}) + if(NOT EXEC_NAME) + message(FATAL_ERROR "No executable name specified for call to mrt_add_executable()!") + endif() + cmake_parse_arguments(MRT_ADD_EXECUTABLE "" "FOLDER" "FILES;DEPENDS;LIBRARIES" ${ARGN}) + if(NOT MRT_ADD_EXECUTABLE_FOLDER AND NOT MRT_ADD_EXECUTABLE_FILES) + message(FATAL_ERROR "No FOLDER or FILES argument passed to mrt_add_executable()!") + endif() + set(EXEC_TARGET_NAME ${PROJECT_NAME}-${EXEC_NAME}-exec) + + # get the files + if(MRT_ADD_EXECUTABLE_FOLDER) + mrt_glob_files_recurse( + EXEC_SOURCE_FILES_INC "${MRT_ADD_EXECUTABLE_FOLDER}/*.h" "${MRT_ADD_EXECUTABLE_FOLDER}/*.hpp" + "${MRT_ADD_EXECUTABLE_FOLDER}/*.hh" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cuh") + mrt_glob_files_recurse(EXEC_SOURCE_FILES_SRC "${MRT_ADD_EXECUTABLE_FOLDER}/*.cpp" + "${MRT_ADD_EXECUTABLE_FOLDER}/*.cc" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cu") + endif() + if(MRT_ADD_EXECUTABLE_FILES) + list(APPEND EXEC_SOURCE_FILES_SRC ${MRT_ADD_EXECUTABLE_FILES}) + list(REMOVE_DUPLICATES EXEC_SOURCE_FILES_SRC) + endif() + if(NOT EXEC_SOURCE_FILES_SRC) + return() + endif() + + # separate cuda files + set(_MRT_CPP_SOURCE_FILES) + set(_MRT_CUDA_SOURCE_FILES) + foreach(SOURCE_FILE ${EXEC_SOURCE_FILES_SRC}) + get_filename_component(FILE_EXT ${SOURCE_FILE} EXT) + if("${FILE_EXT}" STREQUAL ".cu") + list(APPEND _MRT_CUDA_SOURCE_FILES "${SOURCE_FILE}") + else() + list(APPEND _MRT_CPP_SOURCE_FILES "${SOURCE_FILE}") + endif() + endforeach() + + # generate the target + message(STATUS "Adding executable \"${EXEC_NAME}\" with source: ${_MRT_CPP_SOURCE_FILES}") + add_executable(${EXEC_TARGET_NAME} ${EXEC_SOURCE_FILES_INC} ${_MRT_CPP_SOURCE_FILES}) + set_target_properties(${EXEC_TARGET_NAME} PROPERTIES OUTPUT_NAME ${EXEC_NAME}) + # seems superfluous but is necessary to avoid quirks with autmoc'ed files + if(MRT_ADD_EXECUTABLE_FOLDER) + target_include_directories(${EXEC_TARGET_NAME} + PRIVATE "${CMAKE_CURRENT_SOURCE_DIR}/${MRT_ADD_EXECUTABLE_FOLDER}") + endif() + mrt_add_links(${EXEC_TARGET_NAME}) + if(MRT_ADD_EXECUTABLE_DEPENDS) + add_dependencies(${EXEC_TARGET_NAME} ${MRT_ADD_EXECUTABLE_DEPENDS}) + endif() + if(MRT_ADD_EXECUTABLE_LIBRARIES) + target_link_libraries(${EXEC_TARGET_NAME} PRIVATE ${MRT_ADD_EXECUTABLE_LIBRARIES}) + endif() + if(${PROJECT_NAME}_GENERATED_LIBRARIES) + target_link_libraries(${EXEC_TARGET_NAME} PRIVATE ${${PROJECT_NAME}_GENERATED_LIBRARIES}) + endif() + + # Add cuda target + if(_MRT_CUDA_SOURCE_FILES) + if(NOT DEFINED CUDA_FOUND) + message( + FATAL_ERROR + "Found CUDA source file but no dependency to CUDA. Please add CUDA to your package.xml." + ) + endif() + + # generate cuda target + set(CUDA_TARGET_NAME _${EXEC_TARGET_NAME}_cuda) + + # NVCC does not like '-' in file names and because 'cuda_add_library' creates + # a helper file which contains the target name, one has to replace '-'. + string(REPLACE "-" "_" CUDA_TARGET_NAME ${CUDA_TARGET_NAME}) + + if(${CMAKE_VERSION} VERSION_LESS "3.9.0") + cuda_add_library(${CUDA_TARGET_NAME} STATIC ${_MRT_CUDA_SOURCE_FILES}) + else() + message(STATUS "Adding ${_MRT_CUDA_SOURCE_FILES} files.") + add_library(${CUDA_TARGET_NAME} SHARED ${_MRT_CUDA_SOURCE_FILES}) + # We cannot link to all libraries as nvcc does not unterstand all the flags + # etc. which could be passed to target_link_libraries as a target. So the + # dependencies were added to the mrt_CUDA_LIBRARIES variable. + set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY POSITION_INDEPENDENT_CODE ON) + set_property(TARGET ${CUDA_TARGET_NAME} PROPERTY CUDA_SEPARABLE_COMPILATION ON) + endif() + mrt_add_links(${CUDA_TARGET_NAME} CUDA) + target_link_libraries(${CUDA_TARGET_NAME} PRIVATE ${MRT_ADD_EXECUTABLE_LIBRARIES}) + + # link cuda library to executable + target_link_libraries(${EXEC_TARGET_NAME} PRIVATE ${CUDA_TARGET_NAME}) + set(${PROJECT_NAME}_GENERATED_LIBRARIES + ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${CUDA_TARGET_NAME} + PARENT_SCOPE) + endif() + + # append to list of all targets in this project + set(${PROJECT_NAME}_MRT_TARGETS + ${${PROJECT_NAME}_MRT_TARGETS} ${EXEC_TARGET_NAME} ${CUDA_TARGET_NAME} + PARENT_SCOPE) +endfunction() + +# +# Adds a nodelet. +# +# This command ensures the nodelet is compiled with all necessary dependencies. Make sure to add lib{PROJECT_NAME}-{NAME}-nodelet to the ``nodelet_plugins.xml`` file. +# +# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. +# +# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. +# +# It requires a ``*_nodelet.cpp``-File to be present in this folder. +# The command will look for a ``*_node.cpp``-file and remove it from the list of files to avoid ``main()``-functions to be compiled into the library. +# +# :param nodeletname: base name of the nodelet (_nodelet will be appended to the base name to avoid conflicts with library packages) +# :type nodeletname: string +# :param FOLDER: Folder with cpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}`` +# :type FOLDER: string +# :param DEPENDS: List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects. +# :type DEPENDS: list of strings +# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects +# :type LIBRARIES: list of strings +# :param TARGETNAME: Choose the name of the internal CMAKE target. Will be autogenerated if not specified. +# :type TARGETNAME: string +# +# Example: +# :: +# +# mrt_add_nodelet( example_package +# FOLDER src/example_package +# ) +# +# The resulting entry in the ``nodelet_plugins.xml`` is thus: +# +# @public +# +function(mrt_add_nodelet nodeletname) + + set(NODELET_NAME ${nodeletname}) + if(NOT NODELET_NAME) + message(FATAL_ERROR "No nodelet name specified for call to mrt_add_nodelet()!") + endif() + cmake_parse_arguments(MRT_ADD_NODELET "" "FOLDER;TARGETNAME" "DEPENDS;LIBRARIES" ${ARGN}) + if(NOT MRT_ADD_NODELET_TARGETNAME) + set(NODELET_TARGET_NAME ${PROJECT_NAME}-${NODELET_NAME}-nodelet) + else() + set(NODELET_TARGET_NAME ${MRT_ADD_NODELET_TARGETNAME}) + endif() + + # get the files + mrt_glob_files(NODELET_SOURCE_FILES_INC "${MRT_ADD_NODELET_FOLDER}/*.h" "${MRT_ADD_NODELET_FOLDER}/*.hpp" + "${MRT_ADD_EXECUTABLE_FOLDER}/*.hh" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cuh") + mrt_glob_files(NODELET_SOURCE_FILES_SRC "${MRT_ADD_NODELET_FOLDER}/*.cpp" "${MRT_ADD_EXECUTABLE_FOLDER}/*.cc" + "${MRT_ADD_EXECUTABLE_FOLDER}/*.cu") + + # Find nodelet + mrt_glob_files(NODELET_CPP "${MRT_ADD_NODELET_FOLDER}/*_nodelet.cpp" "${MRT_ADD_NODELET_FOLDER}/*_nodelet.cc") + if(NOT NODELET_CPP) + return() + endif() + + # Remove nodes (with their main) from src-files + mrt_glob_files(NODE_CPP "${MRT_ADD_NODELET_FOLDER}/*_node.cpp" "${MRT_ADD_NODELET_FOLDER}/*_node.cc") + if(NODE_CPP) + list(REMOVE_ITEM NODELET_SOURCE_FILES_SRC ${NODE_CPP}) + endif() + + # determine library name + + # generate the target + message(STATUS "Adding nodelet \"${NODELET_NAME}\"") + mrt_add_library( + ${NODELET_TARGET_NAME} + INCLUDES ${NODELET_SOURCE_FILES_INC} + SOURCES ${NODELET_SOURCE_FILES_SRC} + DEPENDS ${MRT_ADD_NODELET_DEPENDS} + LIBRARIES ${MRT_ADD_NODELET_LIBRARIES}) + + # the nodelet library used to be referenced as lib"nodeletname" in ros. For backward compability we still provide a symlink to older versions + if(MRT_PKG_VERSION VERSION_LESS 3.1) + string(REGEX REPLACE "_node" "" OLD_NODELET_NAME ${nodeletname}) + string(REGEX REPLACE "_nodelet" "" OLD_NODELET_NAME ${OLD_NODELET_NAME}) + set(OLD_NODELET_NAME ${OLD_NODELET_NAME}_nodelet) + add_custom_command( + TARGET ${NODELET_TARGET_NAME} + POST_BUILD + COMMAND cd $ && ln -sf $ + lib${OLD_NODELET_NAME}.so) + install(FILES $/lib${OLD_NODELET_NAME}.so + DESTINATION ${CMAKE_INSTALL_LIBDIR}) + endif() + # make nodelet headers available in unittests + get_filename_component(nodelet_dir ${CMAKE_CURRENT_SOURCE_DIR}/${MRT_ADD_NODELET_FOLDER} DIRECTORY) + target_include_directories(${NODELET_TARGET_NAME} INTERFACE $) + # pass lists on to parent scope. We are not exporting the library, because they are not supposed to be used by external projects + set(${PROJECT_NAME}_GENERATED_LIBRARIES + ${${PROJECT_NAME}_GENERATED_LIBRARIES} + PARENT_SCOPE) +endfunction() + +# +# Adds a node and a corresponding nodelet. +# +# This command ensures the node/nodelet are compiled with all necessary dependencies. Make sure to add lib--nodelet to the ``nodelet_plugins.xml`` file. +# +# .. note:: Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible. +# +# The files are automatically added to the list of installable targets so that ``mrt_install`` can mark them for installation. +# +# It requires a ``*_nodelet.cpp`` file and a ``*_node.cpp`` file to be present in this folder. It will then compile a nodelet-library, create an executable from the ``*_node.cpp`` file and link the executable with the nodelet library. +# +# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. +# +# :param basename: base name of the node/nodelet (_nodelet will be appended for the nodelet name to avoid conflicts with library packages) +# :type basename: string +# :param FOLDER: Folder with cpp files for the executable, relative to ``${PROJECT_SOURCE_DIR}`` +# :type FOLDER: string +# :param DEPENDS: List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects. +# :type DEPENDS: list of strings +# :param LIBRARIES: Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects +# :type LIBRARIES: list of strings +# +# Example: +# :: +# +# mrt_add_node_and_nodelet( example_package +# FOLDER src/example_package +# ) +# +# The resulting entry in the ``nodelet_plugins.xml`` is thus (for a package named example_package): +# +# @public +# +function(mrt_add_node_and_nodelet basename) + cmake_parse_arguments(MRT_ADD_NN "" "FOLDER" "DEPENDS;LIBRARIES" ${ARGN}) + set(BASE_NAME ${basename}) + if(NOT BASE_NAME) + message(FATAL_ERROR "No base name specified for call to mrt_add_node_and_nodelet()!") + endif() + set(NODELET_TARGET_NAME ${PROJECT_NAME}-${BASE_NAME}-nodelet) + # add nodelet + mrt_add_nodelet( + ${BASE_NAME} + FOLDER ${MRT_ADD_NN_FOLDER} + TARGETNAME ${NODELET_TARGET_NAME} + DEPENDS ${MRT_ADD_NN_DEPENDS} + LIBRARIES ${MRT_ADD_NN_LIBRARIES}) + # pass lists on to parent scope + set(${PROJECT_NAME}_GENERATED_LIBRARIES + ${${PROJECT_NAME}_GENERATED_LIBRARIES} + PARENT_SCOPE) + set(${PROJECT_NAME}_MRT_TARGETS + ${${PROJECT_NAME}_MRT_TARGETS} + PARENT_SCOPE) + + # search the files we have to build with + if(NOT TARGET ${NODELET_TARGET_NAME}) + unset(NODELET_TARGET_NAME) + mrt_glob_files(NODE_CPP "${MRT_ADD_NN_FOLDER}/*.cpp" "${MRT_ADD_NN_FOLDER}/*.cc" "${MRT_ADD_NN_FOLDER}/*.cu") + else() + mrt_glob_files(NODE_CPP "${MRT_ADD_NN_FOLDER}/*_node.cpp" "${MRT_ADD_NN_FOLDER}/*_node.cc") + endif() + + # find *_node file containing the main() and add the executable + mrt_glob_files(NODE_H "${MRT_ADD_NN_FOLDER}/*.h" "${MRT_ADD_NN_FOLDER}/*.hpp" "${MRT_ADD_NN_FOLDER}/*.hh" + "${MRT_ADD_NN_FOLDER}/*.cuh") + mrt_glob_files(NODE_MAIN "${MRT_ADD_NN_FOLDER}/*_node.cpp" "${MRT_ADD_NN_FOLDER}/*_node.cc") + if(NODE_MAIN) + mrt_add_executable( + ${BASE_NAME} + FILES ${NODE_CPP} ${NODE_H} + DEPENDS ${MRT_ADD_NN_DEPENDS} ${NODELET_TARGET_NAME} + LIBRARIES ${MRT_ADD_NN_LIBRARIES} ${NODELET_TARGET_NAME}) + # pass lists on to parent scope + set(${PROJECT_NAME}_GENERATED_LIBRARIES + ${${PROJECT_NAME}_GENERATED_LIBRARIES} + PARENT_SCOPE) + set(${PROJECT_NAME}_MRT_TARGETS + ${${PROJECT_NAME}_MRT_TARGETS} + PARENT_SCOPE) + endif() +endfunction() + +# +# Adds all rostests (identified by a .test file) contained in a folder as unittests. +# +# If a .cpp file exists with the same name, it will be added and comiled as a gtest test. +# Unittests can be run with "catkin run_tests" or similar. "-test" will be appended to the name of the test node to avoid conflicts (i.e. the type argument should then be in a mytest.test file). +# +# Unittests will always be executed with the folder as cwd. E.g. if the test folder contains a sub-folder "test_data", it can simply be accessed as "test_data". +# +# If coverage information is enabled (by setting ``MRT_ENABLE_COVARAGE`` to true), coverage analysis will be performed after unittests have run. The results can be found in the package's build folder in the folder "coverage". +# +# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. +# +# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument +# :type folder: string +# :param LIBRARIES: Additional (non-catkin, non-mrt) libraries to link to +# :type LIBRARIES: list of strings +# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) +# :type DEPENDS: list of strings +# +# Example: +# :: +# +# mrt_add_ros_tests( test +# ) +# +# @public +# +function(mrt_add_ros_tests folder) + set(TEST_FOLDER ${folder}) + cmake_parse_arguments(MRT_ADD_ROS_TESTS "" "" "LIBRARIES;DEPENDS" ${ARGN}) + mrt_glob_files(_ros_tests "${TEST_FOLDER}/*.test") + add_custom_target(${PROJECT_NAME}-rostest_test_files SOURCES ${_ros_tests}) + configure_file(${MCM_TEMPLATE_DIR}/test_utility.hpp.in ${PROJECT_BINARY_DIR}/tests/test/test_utility.hpp @ONLY) + mrt_init_testing() + + foreach(_ros_test ${_ros_tests}) + get_filename_component(_test_name ${_ros_test} NAME_WE) + # make sure we add only one -test to the target + string(REGEX REPLACE "-test" "" TEST_NAME ${_test_name}) + set(TEST_NAME ${TEST_NAME}-test) + set(TEST_TARGET_NAME ${PROJECT_NAME}-rostest-${TEST_NAME}) + # look for a matching .cpp + if(EXISTS "${PROJECT_SOURCE_DIR}/${TEST_FOLDER}/${_test_name}.cpp") + message(STATUS "Adding gtest-rostest \"${TEST_TARGET_NAME}\" with test file ${_ros_test}") + mrt_add_rostest_gtest(${TEST_TARGET_NAME} ${_ros_test} "${TEST_FOLDER}/${_test_name}.cpp") + mrt_add_links(${TEST_TARGET_NAME} TEST) + target_include_directories(${TEST_TARGET_NAME} PRIVATE ${PROJECT_BINARY_DIR}/tests) + if(${PROJECT_NAME}_GENERATED_LIBRARIES) + target_link_libraries(${TEST_TARGET_NAME} PRIVATE ${${PROJECT_NAME}_GENERATED_LIBRARIES}) + endif() + if(MRT_ADD_ROS_TESTS_DEPENDS) + add_dependencies(${TEST_TARGET_NAME} ${MRT_ADD_ROS_TESTS_DEPENDS}) + endif() + set_target_properties(${TEST_TARGET_NAME} PROPERTIES OUTPUT_NAME ${TEST_NAME}) + set(TARGET_ADDED True) + else() + message(STATUS "Adding plain rostest \"${_ros_test}\"") + mrt_add_rostest(${TEST_TARGET_NAME} ${_ros_test}) + endif() + endforeach() +endfunction() + +# +# Adds all gtests (without a corresponding .test file) contained in a folder as unittests. +# +# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument +# :type folder: string +# :param LIBRARIES: Additional (non-catkin, non-mrt) libraries to link to +# :type LIBRARIES: list of strings +# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) +# :type DEPENDS: list of strings +# +# +# Unittests will be executed with the folder as cwd if ctest or the run_test target is used. E.g. if the test folder contains a sub-folder "test_data", it can simply be accessed as "test_data". +# Another way of getting the location of the project root folder path is to ``#include "test/test_utility.hpp"`` and use the variable ``::test::projectRootDir``. +# +# Unless the variable ``${MRT_NO_FAIL_ON_TESTS}`` is set, failing unittests will result in a failed build. +# +# If coverage information is enabled (by setting ``MRT_ENABLE_COVARAGE`` to true), coverage analysis will be performed after unittests have run. The results can be found in the package's build folder in the folder "coverage". +# +# Example: +# :: +# +# mrt_add_tests( test +# ) +# +# @public +# +function(mrt_add_tests folder) + set(TEST_FOLDER ${folder}) + cmake_parse_arguments(MRT_ADD_TESTS "" "" "LIBRARIES;DEPENDS" ${ARGN}) + mrt_glob_files(_tests "${TEST_FOLDER}/*.cpp" "${TEST_FOLDER}/*.cc") + configure_file(${MCM_TEMPLATE_DIR}/test_utility.hpp.in ${PROJECT_BINARY_DIR}/tests/test/test_utility.hpp @ONLY) + mrt_init_testing() + + foreach(_test ${_tests}) + get_filename_component(_test_name ${_test} NAME_WE) + # make sure we add only one -test to the target + string(REGEX REPLACE "-test" "" TEST_TARGET_NAME ${_test_name}) + set(TEST_TARGET_NAME ${PROJECT_NAME}-gtest-${TEST_TARGET_NAME}) + # exclude cpp files with a test file (those are ros tests) + if(NOT EXISTS "${PROJECT_SOURCE_DIR}/${TEST_FOLDER}/${_test_name}.test") + message( + STATUS + "Adding gtest unittest \"${TEST_TARGET_NAME}\" with working dir ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}" + ) + mrt_add_gtest(${TEST_TARGET_NAME} ${_test} WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}) + mrt_add_links(${TEST_TARGET_NAME} TEST) + target_include_directories(${TEST_TARGET_NAME} PRIVATE ${PROJECT_BINARY_DIR}/tests) + if(${PROJECT_NAME}_GENERATED_LIBRARIES) + target_link_libraries(${TEST_TARGET_NAME} PRIVATE ${${PROJECT_NAME}_GENERATED_LIBRARIES}) + endif() + if(MRT_ADD_TESTS_DEPENDS) + add_dependencies(${TEST_TARGET_NAME} ${MRT_ADD_TESTS_DEPENDS}) + endif() + set(TARGET_ADDED True) + endif() + endforeach() +endfunction() + +# Adds python nosetest contained in a folder. Wraps the function catkin_add_nosetests. +# +# :param folder: folder containing the tests (relative to ``${PROJECT_SOURCE_DIR}``) as first argument +# :type folder: string +# :param DEPENDS: Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data) +# :type DEPENDS: list of strings +# :param DEPENDENCIES: Alias for DEPENDS +# :type DEPENDENCIES: list of strings +# +# Example: +# :: +# +# mrt_add_nosetests(test) +# +# @public +# +function(mrt_add_nosetests folder) + mrt_init_testing() + set(TEST_FOLDER ${folder}) + cmake_parse_arguments(ARG "" "" "DEPENDS;DEPENDENCIES" ${ARGN}) + if(NOT IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}) + return() + endif() + + message(STATUS "Adding nosetests in folder ${PROJECT_SOURCE_DIR}/${TEST_FOLDER}") + _mrt_add_nosetests_impl(${TEST_FOLDER} DEPENDS ${ARG_DEPENDS} ${ARG_DEPENDENCIES}) +endfunction() + +function(_mrt_install_python source_file destination) + if(ROS_VERSION EQUAL 1) + # we can just use catkin + catkin_install_python(PROGRAMS ${source_file} DESTINATION ${destination}) + return() + endif() + # for ament, we have to fix the shebang before we can install (ament does not provide this feature) + + # read file and check shebang line + file(READ ${source_file} data) + set(regex "^#![ \t]*/([^\r\n]+)/env[ \t]+python([\r\n])") + string(REGEX MATCH "${regex}" shebang_line "${data}") + string(LENGTH "${shebang_line}" length) + string(SUBSTRING "${data}" 0 ${length} prefix) + if("${shebang_line}" STREQUAL "${prefix}") + # write modified file with modified shebang line + get_filename_component(python_name ${PYTHON_EXECUTABLE} NAME) + string(REGEX REPLACE "${regex}" "#!/\\1/env ${python_name}\\2" data "${data}") + get_filename_component(filename ${source_file} NAME) + set(rewritten_file "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/python_files") + file(MAKE_DIRECTORY ${rewritten_file}) + set(rewritten_file "${rewritten_file}/${filename}") + file(WRITE ${rewritten_file} "${data}") + else() + # Shebang did not match, install file unmodified + set(rewritten_file "${source_file}") + endif() + # install (modified) file to destination + # Install copy of file with re-written shebang to install space + install(PROGRAMS "${rewritten_file}" DESTINATION "${destination}") +endfunction() + +# Installs all relevant project files. +# +# All targets added by the mrt_add_ commands will be installed automatically when using this command. Other files/folders (launchfiles, scripts) need to be specified explicitly. +# Non existing files and folders will be silently ignored. +# +# If the project contains a file cmake/-extras.cmake[.in], it will be automatically included by all depending projects. This allows to export cmake functions, etc. If the file ends with [.in], it will be configured by cmake +# and the variables "@DEVELSPACE@" "@INSTALLSPACE@" will be replaced by true or files depending on the build type, @PROJECT_SPACE_DIR@ to the devel/install folder and @PKT_CMAKE_DIR@ to the cmake folder +# +# :param PROGRAMS: List of all folders and files that are programs (python scripts will be indentified and treated separately). Files will be made executable. +# :type PROGRAMS: list of strings +# :param FILES: List of non-executable files and folders. Subfolders will be installed recursively. +# :type FILES: list of strings +# :param EXPORT_LIBS: List of non-mrt-created libraries that should be installed and exported +# :type EXPORT_LIBS: list of (interface) library targets +# +# Example: +# :: +# +# mrt_install( +# PROGRAMS scripts +# FILES launch nodelet_plugins.xml +# ) +# +# @public +# +function(mrt_install) + cmake_parse_arguments(MRT_INSTALL "" "" "PROGRAMS;FILES;EXPORT_LIBS" ${ARGN}) + # install targets + set(export_targets ${${PROJECT_NAME}_GENERATED_LIBRARIES} ${EXPORT_EXPORT_LIBS}) + if(export_targets AND TARGET ${PROJECT_NAME}_compiler_flags) + # export the public compiler flags of this project + list(APPEND export_targets ${PROJECT_NAME}_compiler_flags) + endif() + + # static libs require our private flags to be in the export set + foreach(target ${export_targets}) + get_target_property(target_type ${target} TYPE) + if(target_type STREQUAL "STATIC_LIBRARY") + set(has_static True) + break() + endif() + endforeach() + if(has_static AND TARGET ${PROJECT_NAME}_private_compiler_flags) + list(APPEND export_targets ${PROJECT_NAME}_private_compiler_flags) + endif() + if(has_static AND TARGET ${PROJECT_NAME}_sanitizer_lib_flags) + list(APPEND export_targets ${PROJECT_NAME}_sanitizer_lib_flags) + endif() + + set(install_bin ${CMAKE_INSTALL_LIBDIR}/${PROJECT_NAME}) + + # this is how catkin does it (instead of "bin"). We might think about adding a way to override this... + if(export_targets) + message( + STATUS + "Marking libraries \"${${PROJECT_NAME}_MRT_TARGETS}\" of package \"${PROJECT_NAME}\" for installation") + install( + TARGETS ${export_targets} + EXPORT ${PROJECT_NAME}_EXPORTS + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${install_bin}) + set(package_exports ${PROJECT_NAME}_EXPORTS) + endif() + set(remaining_targets ${${PROJECT_NAME}_MRT_TARGETS}) + if(${PROJECT_NAME}_GENERATED_LIBRARIES) + list(REMOVE_ITEM remaining_targets ${${PROJECT_NAME}_GENERATED_LIBRARIES}) + endif() + if(remaining_targets) + if(${PROJECT_NAME}_MRT_TARGETS) + message(STATUS "Marking targets \"${remaining_targets}\" of package \"${PROJECT_NAME}\" for installation") + install( + TARGETS ${remaining_targets} + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${install_bin}) + endif() + endif() + + # install header + if(EXISTS ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}) + message( + STATUS + "Marking HEADER FILES in \"include/${PROJECT_NAME}\" folder of package \"${PROJECT_NAME}\" for installation" + ) + # the "/" at the end of the path matters! + # TODO: Cmake 3.10(?) supports installing with "TYPE HEADER". That removes the need of "FILES_MATCHING PATTERN". + install( + DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/${PROJECT_NAME} + FILES_MATCHING + PATTERN "*.h" + PATTERN "*.hpp" + PATTERN "*.hh" + PATTERN "*.cuh") + endif() + + # helper function for installing programs + function(mrt_install_program program_path) + get_filename_component(extension ${program_path} EXT) + get_filename_component(program ${program_path} NAME) + if("${extension}" STREQUAL ".py") + message(STATUS "Marking PYTHON PROGRAM \"${program}\" of package \"${PROJECT_NAME}\" for installation") + _mrt_install_python(${program_path} ${install_bin}) + else() + message(STATUS "Marking PROGRAM \"${program}\" of package \"${PROJECT_NAME}\" for installation") + install(PROGRAMS ${program_path} DESTINATION ${install_bin}) + endif() + endfunction() + + # install programs + foreach(ELEMENT ${MRT_INSTALL_PROGRAMS}) + if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${ELEMENT}) + mrt_glob_files(FILES "${PROJECT_SOURCE_DIR}/${ELEMENT}/[^.]*[^~]") + foreach(FILE ${FILES}) + if(NOT IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${FILE}) + mrt_install_program(${FILE}) + endif() + endforeach() + elseif(EXISTS ${PROJECT_SOURCE_DIR}/${ELEMENT}) + mrt_install_program(${ELEMENT}) + endif() + endforeach() + + # install files + foreach(ELEMENT ${MRT_INSTALL_FILES}) + if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/${ELEMENT}) + message( + STATUS "Marking SHARED CONTENT FOLDER \"${ELEMENT}\" of package \"${PROJECT_NAME}\" for installation") + install(DIRECTORY ${ELEMENT} DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}) + elseif(EXISTS ${PROJECT_SOURCE_DIR}/${ELEMENT}) + message(STATUS "Marking FILE \"${ELEMENT}\" of package \"${PROJECT_NAME}\" for installation") + install(FILES ${ELEMENT} DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}) + endif() + endforeach() + + # export the config + # ensure catkin_package wasnt already called before. It should already have generated a configuration. + if(NOT ${PROJECT_NAME}_CATKIN_PACKAGE) + set(${PROJECT_NAME}_CATKIN_PACKAGE TRUE) + include(${MRT_CMAKE_MODULES_CMAKE_PATH}/Modules/ExportPackage.cmake) + _mrt_export_package( + EXPORTS ${package_exports} + LIBRARIES ${export_targets} + TARGETS ${remaining_targets} ${${PROJECT_NAME}_EXPORTED_TARGETS}) + endif() + + # generate environment files for ros2 + if(ROS_VERSION EQUAL 2) + find_package(ament_cmake_core REQUIRED) + ament_execute_extensions(ament_package) + endif() +endfunction() diff --git a/mrt_cmake_modules/doc/.buildinfo b/mrt_cmake_modules/doc/.buildinfo index 6bacafaf497..e4bffaf2e59 100644 --- a/mrt_cmake_modules/doc/.buildinfo +++ b/mrt_cmake_modules/doc/.buildinfo @@ -1,4 +1,4 @@ # Sphinx build info version 1 # This file hashes the configuration used when building these files. When it is not found, a full rebuild will be done. -config: 7af4352f635e70a62d09eefd35e3d081 +config: c3bf84308d83e2422afc0c82cb6cb23c tags: 645f666f9bcd5a90fca523b33c5a78b7 diff --git a/mrt_cmake_modules/doc/_static/basic.css b/mrt_cmake_modules/doc/_static/basic.css index c89fc7e920b..607b5f5582e 100644 --- a/mrt_cmake_modules/doc/_static/basic.css +++ b/mrt_cmake_modules/doc/_static/basic.css @@ -4,7 +4,7 @@ * * Sphinx stylesheet -- basic theme. * - * :copyright: Copyright 2007-2016 by the Sphinx team, see AUTHORS. + * :copyright: Copyright 2007-2018 by the Sphinx team, see AUTHORS. * :license: BSD, see LICENSE for details. * */ @@ -52,6 +52,8 @@ div.sphinxsidebar { width: 230px; margin-left: -100%; font-size: 90%; + word-wrap: break-word; + overflow-wrap : break-word; } div.sphinxsidebar ul { @@ -83,10 +85,6 @@ div.sphinxsidebar #searchbox input[type="text"] { width: 170px; } -div.sphinxsidebar #searchbox input[type="submit"] { - width: 30px; -} - img { border: 0; max-width: 100%; @@ -124,6 +122,8 @@ ul.keywordmatches li.goodmatch a { table.contentstable { width: 90%; + margin-left: auto; + margin-right: auto; } table.contentstable p.biglink { @@ -151,9 +151,14 @@ table.indextable td { vertical-align: top; } -table.indextable dl, table.indextable dd { +table.indextable ul { margin-top: 0; margin-bottom: 0; + list-style-type: none; +} + +table.indextable > tbody > tr > td > ul { + padding-left: 0em; } table.indextable tr.pcap { @@ -185,8 +190,22 @@ div.genindex-jumpbox { padding: 0.4em; } +/* -- domain module index --------------------------------------------------- */ + +table.modindextable td { + padding: 2px; + border-collapse: collapse; +} + /* -- general body styles --------------------------------------------------- */ +div.body p, div.body dd, div.body li, div.body blockquote { + -moz-hyphens: auto; + -ms-hyphens: auto; + -webkit-hyphens: auto; + hyphens: auto; +} + a.headerlink { visibility: hidden; } @@ -212,10 +231,6 @@ div.body td { text-align: left; } -.field-list ul { - padding-left: 1em; -} - .first { margin-top: 0 !important; } @@ -317,6 +332,11 @@ table.docutils { border-collapse: collapse; } +table.align-center { + margin-left: auto; + margin-right: auto; +} + table caption span.caption-number { font-style: italic; } @@ -332,10 +352,6 @@ table.docutils td, table.docutils th { border-bottom: 1px solid #aaa; } -table.field-list td, table.field-list th { - border: 0 !important; -} - table.footnote td, table.footnote th { border: 0 !important; } @@ -372,6 +388,27 @@ div.figure p.caption span.caption-number { div.figure p.caption span.caption-text { } +/* -- field list styles ----------------------------------------------------- */ + +table.field-list td, table.field-list th { + border: 0 !important; +} + +.field-list ul { + margin: 0; + padding-left: 1em; +} + +.field-list p { + margin: 0; +} + +.field-name { + -moz-hyphens: manual; + -ms-hyphens: manual; + -webkit-hyphens: manual; + hyphens: manual; +} /* -- other body styles ----------------------------------------------------- */ @@ -413,24 +450,19 @@ dd { margin-left: 30px; } -dt:target, .highlighted { +dt:target, span.highlighted { background-color: #fbe54e; } +rect.highlighted { + fill: #fbe54e; +} + dl.glossary dt { font-weight: bold; font-size: 1.1em; } -.field-list ul { - margin: 0; - padding-left: 1em; -} - -.field-list p { - margin: 0; -} - .optional { font-size: 1.3em; } @@ -489,6 +521,13 @@ pre { overflow-y: hidden; /* fixes display issues on Chrome browsers */ } +span.pre { + -moz-hyphens: none; + -ms-hyphens: none; + -webkit-hyphens: none; + hyphens: none; +} + td.linenos pre { padding: 5px 0px; border: 0; @@ -580,6 +619,16 @@ span.eqno { float: right; } +span.eqno a.headerlink { + position: relative; + left: 0px; + z-index: 1; +} + +div.math:hover a.headerlink { + visibility: visible; +} + /* -- printout stylesheet --------------------------------------------------- */ @media print { diff --git a/mrt_cmake_modules/doc/_static/comment-bright.png b/mrt_cmake_modules/doc/_static/comment-bright.png index 551517b8c83b76f734ff791f847829a760ad1903..15e27edb12ac25701ac0ac21b97b52bb4e45415e 100644 GIT binary patch delta 733 zcmV<30wVpa8}tQ`BYy(BNklgfIX78$8Pzv({A~p%??+>KY!ZpSaofV`2`U3L6yZw z^GUTOa6DFW!{Y^e?#!+?F0dsB?zaW{?y>)M+b6$v+$+Cy-XlM?+a=$%-(~-gFMO)v zrd&7#!SPz>TdNd!XHmrDZwUxQaS;Qn7?KiL0gM$14akH>&hv=|&)%PBRplFME5zil z-gM9<7x^~^k$*cXBAQ8QhGK$_TZX%oi3tD`Wm}P3ukdc&a>X~T^_$f;Uw6(q>ej6R z5E+0qQ<4GFgfs@QEQl%AFI~89#k%Yb%2yy( zq?8ih{p8%ZoDU?=xA4x7FZ9T*3p0!Ih?cF-oHVo4joWx%&$qHRZ3zl3T)Gz~5->ob z72=F@&ws~3E07bJ0R;!GSQTs5Am`#;*WHjvHRvY?&$Lm-vq z1a_BzocI^ULXV!lbMd%|^B#fY;XX)n<&R^L=84u1e_3ziq;Hz-*k5~zwY3*oDKt0; zbM@M@@89;@m*4RFgvvM_4;5LB!@OB@^WbVTjaJ0LG~~7%b6&V3$CCT-bjyozm}^?# zwA`F`?cKk$-?cuD!Xdb;;rTd@-*8rL{CoPf59&ghTmgWD z0l;*TI7e|ZE3OddDgXd@nX){&BsoQaTL>+22Uk}v9w^R9 z7b_GtVFF>AKrX_0nHe&HG!NkO%m4tOkrff(gY*4(&VLTB&dxTDwhmt{>c0m6B4T3W z{^ifBa6kY6;dFk{{wy!E8h|?nfNlPwCGG@hUJIag_lst-4?wj5py}FI^KkfnJUm6A zkh$5}<>chpO2k52Vaiv1{%68pz*qfj`F=e7_x0eu;v|7GU4cgg_~63K^h~83&yop* zV%+ABM}Pdc3;+Bb(;~!4V!2o<6ys46agIcqjPo+3B8fthDa9qy|77CdEc*jK-!%ZR zYCZvbku9iQV*~a}ClFY4z~c7+0P?$U!PF=S1Au6Q;m>#f??3%Vpd|o+W=WE9003S@ zBra6Svp>fO002awfhw>;8}z{#EWidF!3EsG3xE7zHiSYX#KJ-lLJDMn9CBbOtb#%) zhRv`YDqt_vKpix|QD}yfa1JiQRk#j4a1Z)n2%fLC6RbVIkUx0b+_+BaR3c znT7Zv!AJxWizFb)h!jyGOOZ85F;a?DAXP{m@;!0_Ifqlp|(=5QHQ7#Gr)$3XMd?XsE4X&sBct1q<&fbi3VB2Ov6t@q*0);U*o*S zAPZv|vv@2aYYnT0b%8a+Cb7-ge0D0knEf5Qi#@8Tp*ce{N;6lpQuCB%KL_KOarm5c zP6_8IrP_yNQcbz0DW*G2J50yT%*~?B)|oY%Ju%lZ z=bPu7*PGwBU|M)uEVih&xMfMQuC{HqePL%}7iYJ{uEXw=y_0>qeSeMpJqHbk*$%56 zS{;6Kv~mM9! zg3B(KJ}#RZ#@)!hR=4N)wtYw9={>5&Kw=W)*2gz%*kgNq+ zEef_mrsz~!DAy_nvS(#iX1~pe$~l&+o-57m%(KedkbgIv@1Ote62cPUlD4IWOIIx& zSmwQ~YB{nzae3Pc;}r!fhE@iwJh+OsDs9zItL;~pu715HdQEGAUct(O!LkCy1 z<%NCg+}G`0PgpNm-?d@-hMgNe6^V+j6x$b<6@S<$+<4_1hi}TincS4LsjI}fWY1>O zX6feMEq|U{4wkBy=9dm`4cXeX4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC- zq*U}&`cyXV(%rRT*Z6MH?i+i&_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-N zmiuj8txj!m?Z*Ss1N{dh4z}01)YTo*JycSU)_*JOM-ImyzW$x>cP$Mz4ONYt#^NJz zM0w=t_X*$k9t}F$c8q(h;Rn+nb{%IOFKR-X@|s4QQ=0o*Vq3aT%s$c9>fU<%N829{ zoHRUHc}nwC$!Xf@g42^{^3RN&m7RTlF8SPG+oHC6=VQ*_Y7cMkx)5~X(nbG^=R3SR z&VO9;xODQe+vO8ixL2C5I$v$-bm~0*lhaSfyPUh4uDM)mx$b(swR>jw=^LIm&fWCA zdGQwi*43UlJ>9+YdT;l|_x0Zv-F|W>{m#p~*>@-It-MdXU-UrjLD@syht)q@{@mE_ z+<$7occAmp+(-8Yg@e!jk@b%cLj{kSkAKUC4TkHUI6gT!;y-fz>HMcd&t%Ugo)`Y2 z{>!cx7B7DI)$7;J(U{Spm-3gBzioV_{p!H$8L!*M!p0uH$#^p{Ui4P`?ZJ24cOCDe z-w#jZd?0@)|7iKK^;6KN`;!@ylm7$*nDhK&GcDTy000JJOGiWi{{a60|De66lYamJ z010qNS#tmY3ljhU3ljkVnw%H_000McNliru+6W03HVQ(iTs!~(0^UhPK~y-)g_28X zU1b!7zrFu+?!AdIZ9&__+F%oEg3oAMEr>-ZMn#Gg!C^t16d|BuNvojX$dD?QLY-KV zBG`csGzck9iuF}ef?9~Vts#=vO@A6_YLlCDbI$qy?ckQE;Nu%@*o(zpi!EGdXW!2Z z_um8TkX>(l(b3YZTQjk?G^fF*HoKJjsq*Ofuh%|$WRbrh0A0N!j2*il?l{^0{Ncw> z-MX=Kdo{OpNzGVJAxS+zRuX2u9IhOnJ$Bc?-u^KL`?`>Q17$ut*va2COT z%gx1jVaZ5x&&sMwk{PB($O5@w8=T1SMDoJ9S6Yv*UBI4G?fnOz_$5;*%vS{wLCh1J zV!06vd@xHr;!|%o6hwx8Tz+xl%`NW;z{{Up`C;=-#RnD>lUf!mQzt5a=Jc772grRO z^G5E2xnP%u&Q5NRdIsh;H-9v^_RCesJZPj+QjqAngNL9-76eTdm0)Hf-qX^#t+gfc zDw~#4X?AfC7ds+_xacq^Xn+ub1&{bp&zq_g3|6vGQel0Rq`s777Og8PQ4EEm;v$G0 zbpwMeQ#1ky7!XWxYTk0mqQ&3+LheIVB)Tz<4W}Y;y`*IOnVoL!l80O;BnI#7&Mk7DSz?s<~L?(sc6u$m?wjy7cK| zwaR?8Z}j3dd}b(!MUKcpV-rM?qJkj`uKs-E6V=K$hi-WqKwtgJC?Dw<92;MLsxn!% zxrG{$VtERA4G0iL2!8=q^DD zAKbm65sy?RldP8Ht64RhA3Rh3cLN8hTPrt^5y-?z{4zqB1V-z2j2z_~7pM+yLJI`NWanA~u9RIXo;n7c96&U)YLgs-FGlx~*_c{Jg zvesu1E5(8YEf&5wF=YFPcRe@1=MJmiag(L*xc2vB^chh_*IV}zvm8t$ixa-3b2=<8Bm(pRUqXm4)!D3cJ5RAyTg7SCt-9NHDl}N z;eNk39wGuWTYrM2B_IXCGFJftkuV1UK@_c-6MStac>Z$(1PL71mOw@(#%Yx6uwKE`1|iHCFt9aE`>>3le8r)0oeW$ED2V$i-1qB z!CK*C@aG^u8*l~rG2r*&ao~{IZ7Nuit_q0suodnvV1L%~YPy180Gb6do!x?Tw+_{{-o95ay-GVoR;X<=q#&{_8M})l$G76!8|Oe;qrmI| zc-bcj-Uob!vAre8sKtKrKcjF$i z^lp!zkL?C|y^vlHr1HXeVJd;1I~g&Ob-q)&(fn7s-KI}G{wnKzg_U5G(V%bX6ukIe%Jx=Ic-6u4_H+isr7{9Cy@+J&qF; z?qz`E`)F!!3V~1B?)TtRWX!W|BhM(VGW6Q6jfsl(h$ibH15qZ&^gRClt!W71Uw-TG zAX)wlp}QVEkGj05OX6kUs87QIgqa-EAk!(+T+=Tm5B}|!W~aXUz1i_(@E_&Jz>@e? l?;x3~`?kzL#`t%Ue*n~ZaeyQJIlTY?002ovPDHLkV1j1ulU)D+ delta 3577 zcmVYP2KpP2BYz4{X+uL$P-t&-Z*ypGa3D!TLm+T+Z)Rz1WdHzp+MQEpR8#2| zJ@?-9LQ9B%luK_?6$l_wLW_VDktQl32@pz%A)(n7QNa;KMFbnjpojyGj)066Q7jCK z3fKqaA)=0hqlk*i`{8?|Yu3E?=FR@K*FNX0^PRKL2fzpnmVZbyQ8j=JsX`tR;Dg7+ z#^K~HK!FM*Z~zbpvt%K2{UZSY_f59&ghTmgWD z0l;*TI7e|ZE3OddDgXd@nX){&BsoQaTL>+22Uk}v9w^R9 z7b_GtVFF>AKrX_0nHe&HG!NkO%m4tOkrff(gY*4(&VLTB&dxTDwhmt{>c0m6B4T3W z{^ifBa6kY6;dFk{{wy!E8h|?nfNlPwCGG@hUJIag_lst-4?wj5py}FI^KkfnJUm6A zkh$5}<>chpO2k52Vaiv1{%68pz*qfj`F=e7_x0eu;v|7GU4cgg_~63K^h~83&yop* zV%+ABM}Pdc3;+Bb(;~!4V!2o<6ys46agIcqjPo+3B8fthDa9qy|77CdEc*jK-!%ZR zYCZvbku9iQV*~a}ClFY4z~c7+0P?$U!PF=S1Au6Q;m>#f??3%Vpd|o+W=WE9003S@ zBra6Svp>fO002awfhw>;8}z{#EWidF!3EsG3xE7zHiSYX#KJ-lLJDMn9CBbOtb#%) zhRv`YDqt_vKpix|QD}yfa1JiQRk#j4a1Z)n2%fLC6RbVIkUx0b+_+BaR3c znT7Zv!AJxWizFb)h!jyGOOZ85F;a?DAXP{m@;!0_Ifqlp|(=5QHQ7#Gr)$3XMd?XsE4X&sBct1q<&fbi3VB2Ov6t@q*0);U*o*S zAPZv|vv@2aYYnT0b%8a+Cb7-ge0D0knEf5Qi#@8Tp*ce{N;6lpQuCB%KL_KOarm5c zP6_8IrP_yNQcbz0DW*G2J50yT%*~?B)|oY%Ju%lZ z=bPu7*PGwBU|M)uEVih&xMfMQuC{HqePL%}7iYJ{uEXw=y_0>qeSeMpJqHbk*$%56 zS{;6Kv~mM9! zg3B(KJ}#RZ#@)!hR=4N)wtYw9={>5&Kw=W)*2gz%*kgNq+ zEef_mrsz~!DAy_nvS(#iX1~pe$~l&+o-57m%(KedkbgIv@1Ote62cPUlD4IWOIIx& zSmwQ~YB{nzae3Pc;}r!fhE@iwJh+OsDs9zItL;~pu715HdQEGAUct(O!LkCy1 z<%NCg+}G`0PgpNm-?d@-hMgNe6^V+j6x$b<6@S<$+<4_1hi}TincS4LsjI}fWY1>O zX6feMEq|U{4wkBy=9dm`4cXeX4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC- zq*U}&`cyXV(%rRT*Z6MH?i+i&_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-N zmiuj8txj!m?Z*Ss1N{dh4z}01)YTo*JycSU)_*JOM-ImyzW$x>cP$Mz4ONYt#^NJz zM0w=t_X*$k9t}F$c8q(h;Rn+nb{%IOFKR-X@|s4QQ=0o*Vq3aT%s$c9>fU<%N829{ zoHRUHc}nwC$!Xf@g42^{^3RN&m7RTlF8SPG+oHC6=VQ*_Y7cMkx)5~X(nbG^=R3SR z&VO9;xODQe+vO8ixL2C5I$v$-bm~0*lhaSfyPUh4uDM)mx$b(swR>jw=^LIm&fWCA zdGQwi*43UlJ>9+YdT;l|_x0Zv-F|W>{m#p~*>@-It-MdXU-UrjLD@syht)q@{@mE_ z+<$7occAmp+(-8Yg@e!jk@b%cLj{kSkAKUC4TkHUI6gT!;y-fz>HMcd&t%Ugo)`Y2 z{>!cx7B7DI)$7;J(U{Spm-3gBzioV_{p!H$8L!*M!p0uH$#^p{Ui4P`?ZJ24cOCDe z-w#jZd?0@)|7iKK^;6KN`;!@ylm7$*nDhK&GcDTy000JJOGiWi{{a60|De66lYamJ z010qNS#tmY3ljhU3ljkVnw%H_000McNliru+6WR87a`)C$lU+{11w2IK~y-)Ws+Y= zopl(;KhN)d-*b+hGtGJO56hLdri)cFO?FWc$<~TS)J3c=iqXv$6d4=C#exQ{#EN3k zMI=N-t&14TT1GWue?U>pBAPm#GJmI=njWSekG}8wd!KF&F6wjj<$>q>JYV<u91WRaq|uqBBKP6V0?p-NL59wrK0w( z$_m#SDPQ!Z$nhd^JO|f+7k5xca94d2OLJ&sSxlB7F%NtrF@@O7WWlkHSDtorzD?u; zb&KN$*MnHx;JDy9P~G<{4}9__s&MATBV4R+MuA8TjlZ3ye&qZMCVz9o&W1M1iimoi zs$&Gtb?_1%n|pqse0YG$p?)6eI7)hUg5>HVP3OMWht7P47y7QVTDEIBQIvk}_Nv0P z>l*P~SL1OcmNfY3QpyKL`T^^ZGQqG#zQ7s{0ot3~|B$$A$niz~j#AKPe~ouODX1{{HoGv&UDY zv^1uwh!I##-NMw??UeOipk(qgMk5q_fjv@x>a2NdhfwzXSq9r{IzRpByKPfr3*Fu4 z=a;RjW*3yp7ng&-`^J__Fa2rdX8(PlP6wV$t(E1z*6}sH^K$*`UG4o=pLu)m=gv)! z9$po9LSaQAt1z9{8HHo~mpfj&Qn&Yu%+($5UHfs`N$pjb$uG<)v?x5NFrwfqWdCQd zabI6W^}e1u;_t>3zRX`8S9n$-1)$K7pXL4m2x@*eEbnAf00000NkvXXu0mjfJi5i~ diff --git a/mrt_cmake_modules/doc/_static/comment.png b/mrt_cmake_modules/doc/_static/comment.png index 92feb52b8824c6b0f59b658b1196c61de9162a95..dfbc0cbd512bdeefcb1984c99d8e577efb77f006 100644 GIT binary patch delta 617 zcmV-v0+#*t8i56nBYy%&NklWd+(1-70zU(rtxtqR%j-lsH|CKQJXqD{+F7Jup|pRuhQFVdUw@0>ky z*1TY!!dA#IA*r}ObSESk-6OCkg5*#h0AQq*X$E0;P~qAd6`Z=k_k*lIM8l(T*@4V1 z6=21^AfaqpB{>8^307MuAi4LvISfny#Dc7H; z+j6gYtxsBW-+zM8hyV(EnlU`4l!hvR5JGs7we;ZyuMOZ}%HtBU`yGuatU@${nlgNv z)@wkpl^@`pz&)=}ra^zdnc2viWjmk>NX@OXRRewEW;1j{m zniEpp4XNQqxFVSO^pqvDtz7R)=J&;kS|OK?bN zFaUsNI{<(mvC0%^<5{^ZU3?Vp!AxUrWg*=czh>)+OBG{E;zntC()^4N5cd32keyG0 zXzSOWC1Q7T4aMl~c47azN_(im0N)7OqdPBCGw;353_o$DqGRDhuhU$Eaj!@m000000NkvXXu0mjf DXSNf59&ghTmgWD z0l;*TI7e|ZE3OddDgXd@nX){&BsoQaTL>+22Uk}v9w^R9 z7b_GtVFF>AKrX_0nHe&HG!NkO%m4tOkrff(gY*4(&VLTB&dxTDwhmt{>c0m6B4T3W z{^ifBa6kY6;dFk{{wy!E8h|?nfNlPwCGG@hUJIag_lst-4?wj5py}FI^KkfnJUm6A zkh$5}<>chpO2k52Vaiv1{%68pz*qfj`F=e7_x0eu;v|7GU4cgg_~63K^h~83&yop* zV%+ABM}Pdc3;+Bb(;~!4V!2o<6ys46agIcqjPo+3B8fthDa9qy|77CdEc*jK-!%ZR zYCZvbku9iQV*~a}ClFY4z~c7+0P?$U!PF=S1Au6Q;m>#f??3%Vpd|o+W=WE9003S@ zBra6Svp>fO002awfhw>;8}z{#EWidF!3EsG3xE7zHiSYX#KJ-lLJDMn9CBbOtb#%) zhRv`YDqt_vKpix|QD}yfa1JiQRk#j4a1Z)n2%fLC6RbVIkUx0b+_+BaR3c znT7Zv!AJxWizFb)h!jyGOOZ85F;a?DAXP{m@;!0_Ifqlp|(=5QHQ7#Gr)$3XMd?XsE4X&sBct1q<&fbi3VB2Ov6t@q*0);U*o*S zAPZv|vv@2aYYnT0b%8a+Cb7-ge0D0knEf5Qi#@8Tp*ce{N;6lpQuCB%KL_KOarm5c zP6_8IrP_yNQcbz0DW*G2J50yT%*~?B)|oY%Ju%lZ z=bPu7*PGwBU|M)uEVih&xMfMQuC{HqePL%}7iYJ{uEXw=y_0>qeSeMpJqHbk*$%56 zS{;6Kv~mM9! zg3B(KJ}#RZ#@)!hR=4N)wtYw9={>5&Kw=W)*2gz%*kgNq+ zEef_mrsz~!DAy_nvS(#iX1~pe$~l&+o-57m%(KedkbgIv@1Ote62cPUlD4IWOIIx& zSmwQ~YB{nzae3Pc;}r!fhE@iwJh+OsDs9zItL;~pu715HdQEGAUct(O!LkCy1 z<%NCg+}G`0PgpNm-?d@-hMgNe6^V+j6x$b<6@S<$+<4_1hi}TincS4LsjI}fWY1>O zX6feMEq|U{4wkBy=9dm`4cXeX4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC- zq*U}&`cyXV(%rRT*Z6MH?i+i&_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-N zmiuj8txj!m?Z*Ss1N{dh4z}01)YTo*JycSU)_*JOM-ImyzW$x>cP$Mz4ONYt#^NJz zM0w=t_X*$k9t}F$c8q(h;Rn+nb{%IOFKR-X@|s4QQ=0o*Vq3aT%s$c9>fU<%N829{ zoHRUHc}nwC$!Xf@g42^{^3RN&m7RTlF8SPG+oHC6=VQ*_Y7cMkx)5~X(nbG^=R3SR z&VO9;xODQe+vO8ixL2C5I$v$-bm~0*lhaSfyPUh4uDM)mx$b(swR>jw=^LIm&fWCA zdGQwi*43UlJ>9+YdT;l|_x0Zv-F|W>{m#p~*>@-It-MdXU-UrjLD@syht)q@{@mE_ z+<$7occAmp+(-8Yg@e!jk@b%cLj{kSkAKUC4TkHUI6gT!;y-fz>HMcd&t%Ugo)`Y2 z{>!cx7B7DI)$7;J(U{Spm-3gBzioV_{p!H$8L!*M!p0uH$#^p{Ui4P`?ZJ24cOCDe z-w#jZd?0@)|7iKK^;6KN`;!@ylm7$*nDhK&GcDTy000JJOGiWi{{a60|De66lYamJ z010qNS#tmY3ljhU3ljkVnw%H_000McNliru+6W5(F+1;8x4!@Y0;fqtK~y-)b&<ifarvbDmIM2^4!4}c(0gom<6 zl#?|7=gJF@kK8&YfUoC%nd{EHj8}LeqUUvoxf0=kqji62>ne+U`d#%J)abyK&Y`=eD%oA!G8q-d~|env}a@G z(3O{0R9Yvb^)mu;j>zt6Wg^_Qc)mG*|Mr`&1F%;<2_74{ZDOg>d}4W}h?QnWQh0lJ z?Ij2iL=yV-kL9^qy|EpD;Y02J-u(0=^>-d*{J`|^)`6?uNTzL9_ipG0bYZn9iX2Tm zemgn8^x>XeLoe}PxNPI)pF8)-WqDxA|Wj zJ~}&i?7NevKcA@{dGp<=jsJXo=8}H3xLVZ#-61t4YQ>Eakt!8oav;T69OUlAu`Ki;O^-g5Z=fq4pe0B z>Eal|aeZm8B_D$V!=b2u|Ko(!W3N>7=ozUvFi(k!W@r+UVo_vTY~d<%VxI2m{BMWn e=8M0HdHG-&tM`PJ{DMF;7(8A5T-G@yGywn?m^Ur} diff --git a/mrt_cmake_modules/doc/_static/doctools.js b/mrt_cmake_modules/doc/_static/doctools.js index e2e70cc287e..0c15c0099b5 100644 --- a/mrt_cmake_modules/doc/_static/doctools.js +++ b/mrt_cmake_modules/doc/_static/doctools.js @@ -4,7 +4,7 @@ * * Sphinx JavaScript utilities for all documentation. * - * :copyright: Copyright 2007-2016 by the Sphinx team, see AUTHORS. + * :copyright: Copyright 2007-2018 by the Sphinx team, see AUTHORS. * :license: BSD, see LICENSE for details. * */ @@ -45,7 +45,7 @@ jQuery.urlencode = encodeURIComponent; * it will always return arrays of strings for the value parts. */ jQuery.getQueryParameters = function(s) { - if (typeof s == 'undefined') + if (typeof s === 'undefined') s = document.location.search; var parts = s.substr(s.indexOf('?') + 1).split('&'); var result = {}; @@ -66,29 +66,53 @@ jQuery.getQueryParameters = function(s) { * span elements with the given class name. */ jQuery.fn.highlightText = function(text, className) { - function highlight(node) { - if (node.nodeType == 3) { + function highlight(node, addItems) { + if (node.nodeType === 3) { var val = node.nodeValue; var pos = val.toLowerCase().indexOf(text); if (pos >= 0 && !jQuery(node.parentNode).hasClass(className)) { - var span = document.createElement("span"); - span.className = className; + var span; + var isInSVG = jQuery(node).closest("body, svg, foreignObject").is("svg"); + if (isInSVG) { + span = document.createElementNS("http://www.w3.org/2000/svg", "tspan"); + } else { + span = document.createElement("span"); + span.className = className; + } span.appendChild(document.createTextNode(val.substr(pos, text.length))); node.parentNode.insertBefore(span, node.parentNode.insertBefore( document.createTextNode(val.substr(pos + text.length)), node.nextSibling)); node.nodeValue = val.substr(0, pos); + if (isInSVG) { + var bbox = span.getBBox(); + var rect = document.createElementNS("http://www.w3.org/2000/svg", "rect"); + rect.x.baseVal.value = bbox.x; + rect.y.baseVal.value = bbox.y; + rect.width.baseVal.value = bbox.width; + rect.height.baseVal.value = bbox.height; + rect.setAttribute('class', className); + var parentOfText = node.parentNode.parentNode; + addItems.push({ + "parent": node.parentNode, + "target": rect}); + } } } else if (!jQuery(node).is("button, select, textarea")) { jQuery.each(node.childNodes, function() { - highlight(this); + highlight(this, addItems); }); } } - return this.each(function() { - highlight(this); + var addItems = []; + var result = this.each(function() { + highlight(this, addItems); }); + for (var i = 0; i < addItems.length; ++i) { + jQuery(addItems[i].parent).before(addItems[i].target); + } + return result; }; /* @@ -124,27 +148,28 @@ var Documentation = { this.fixFirefoxAnchorBug(); this.highlightSearchWords(); this.initIndexTable(); + }, /** * i18n support */ TRANSLATIONS : {}, - PLURAL_EXPR : function(n) { return n == 1 ? 0 : 1; }, + PLURAL_EXPR : function(n) { return n === 1 ? 0 : 1; }, LOCALE : 'unknown', // gettext and ngettext don't access this so that the functions // can safely bound to a different name (_ = Documentation.gettext) gettext : function(string) { var translated = Documentation.TRANSLATIONS[string]; - if (typeof translated == 'undefined') + if (typeof translated === 'undefined') return string; - return (typeof translated == 'string') ? translated : translated[0]; + return (typeof translated === 'string') ? translated : translated[0]; }, ngettext : function(singular, plural, n) { var translated = Documentation.TRANSLATIONS[singular]; - if (typeof translated == 'undefined') + if (typeof translated === 'undefined') return (n == 1) ? singular : plural; return translated[Documentation.PLURALEXPR(n)]; }, @@ -179,7 +204,7 @@ var Documentation = { * see: https://bugzilla.mozilla.org/show_bug.cgi?id=645075 */ fixFirefoxAnchorBug : function() { - if (document.location.hash) + if (document.location.hash && $.browser.mozilla) window.setTimeout(function() { document.location.href += ''; }, 10); @@ -215,7 +240,7 @@ var Documentation = { var src = $(this).attr('src'); var idnum = $(this).attr('id').substr(7); $('tr.cg-' + idnum).toggle(); - if (src.substr(-9) == 'minus.png') + if (src.substr(-9) === 'minus.png') $(this).attr('src', src.substr(0, src.length-9) + 'plus.png'); else $(this).attr('src', src.substr(0, src.length-8) + 'minus.png'); @@ -247,11 +272,34 @@ var Documentation = { var path = document.location.pathname; var parts = path.split(/\//); $.each(DOCUMENTATION_OPTIONS.URL_ROOT.split(/\//), function() { - if (this == '..') + if (this === '..') parts.pop(); }); var url = parts.join('/'); return path.substring(url.lastIndexOf('/') + 1, path.length - 1); + }, + + initOnKeyListeners: function() { + $(document).keyup(function(event) { + var activeElementType = document.activeElement.tagName; + // don't navigate when in search box or textarea + if (activeElementType !== 'TEXTAREA' && activeElementType !== 'INPUT' && activeElementType !== 'SELECT') { + switch (event.keyCode) { + case 37: // left + var prevHref = $('link[rel="prev"]').prop('href'); + if (prevHref) { + window.location.href = prevHref; + return false; + } + case 39: // right + var nextHref = $('link[rel="next"]').prop('href'); + if (nextHref) { + window.location.href = nextHref; + return false; + } + } + } + }); } }; @@ -260,4 +308,4 @@ _ = Documentation.gettext; $(document).ready(function() { Documentation.init(); -}); +}); \ No newline at end of file diff --git a/mrt_cmake_modules/doc/_static/documentation_options.js b/mrt_cmake_modules/doc/_static/documentation_options.js new file mode 100644 index 00000000000..63285938676 --- /dev/null +++ b/mrt_cmake_modules/doc/_static/documentation_options.js @@ -0,0 +1,10 @@ +var DOCUMENTATION_OPTIONS = { + URL_ROOT: document.getElementById("documentation_options").getAttribute('data-url_root'), + VERSION: '1.0.0', + LANGUAGE: 'None', + COLLAPSE_INDEX: false, + FILE_SUFFIX: '.html', + HAS_SOURCE: true, + SOURCELINK_SUFFIX: '.txt', + NAVIGATION_WITH_KEYS: false, +}; \ No newline at end of file diff --git a/mrt_cmake_modules/doc/_static/down-pressed.png b/mrt_cmake_modules/doc/_static/down-pressed.png index 7c30d004b71b32bb2fc06b3bd4dc8278baab0946..5756c8cad8854722893dc70b9eb4bb0400343a39 100644 GIT binary patch delta 205 zcmV;;05bpE0^R|T8Gi-<001BJ|6u?C0HsMpK~#7FW7r%Y&&)s`0P6)2N6UquC+gFgAR6l|+0|jZ_6oe@;fCU_FgBkz;&H}&BVO8(200000NkvXX Hu0mjfcLq?d literal 347 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!63?wyl`GbKJV{wqX6T`Z5GB1G~&H|6fVxZ#d zAk65bF}ngN$X?><>&kwMor^(NtW3yF87Slz;1l8sq&LUMQwyA_72h&sm+fe#sqFPEG6cGWQ5ul00000NkvXXu0mjfPn}Jr literal 347 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!63?wyl`GbKJV{wqX6T`Z5GB1G~&H|6fVxZ#d zAk65bF}ngN$X?><>&kwMol#tg zK_ydLmzem(vK1>2TzUEGl*lj!N<7$PCrdoWV0 z$w0*Ap!bZ4if7h;-yfL#MC0e;t{xY+$l~DX2EWYIPet1cohf^BdG+jXhtuq&W-0|c zKPmlKv-7OTjb}T)7@fTGd9y~u4{g8An;)c2U=w=nwQ7}zVDc>n+a diff --git a/mrt_cmake_modules/doc/_static/file.png b/mrt_cmake_modules/doc/_static/file.png index 254c60bfbe2715ae2edca48ebccfd074deb8031d..a858a410e4faa62ce324d814e4b816fff83a6fb3 100644 GIT binary patch delta 270 zcmV+p0rCFk0-gep8Gi-<001BJ|6u?C0Od(UK~#7Ft&@XN1_2a>_bGdYY}X*$wg%Z8 zX4^eLuH_4yI={KTGvE4t=dOhQ{{Ff0@^V-tLGTw3SS|KM34VWn@%{Y`^7Hc(fX9g_ zicl0KzJQGf2M0JjJOnv9Itt_X_}EYomFiC>k|gO1*chE`et&{k_w3`1`{pLd8NJp; zSHKirG_`jDQGLSB!vO}iUi_FB)c4J!zJCD?1B<9>>H?|nnlLX&FX=!=Dd|LdaVwJZ zYLJv$1)ft?HNJok%;*_tnx-%Czi(NV2}dSOW^;Ujqko~hyL-**-}v7%CAd|8D^sxP UU_nOG00000Ne4wvM6N<$f*gB&bN~PV delta 342 zcmbQo^o(hOWIZzj1A~Sxe=v~ZEbxddW?= 0 && j < len ? [ this[ j ] ] : [] ); + }, + + end: function() { + return this.prevObject || this.constructor(); + }, + + // For internal use only. + // Behaves like an Array's method, not like a jQuery method. + push: push, + sort: arr.sort, + splice: arr.splice +}; + +jQuery.extend = jQuery.fn.extend = function() { + var options, name, src, copy, copyIsArray, clone, + target = arguments[ 0 ] || {}, + i = 1, + length = arguments.length, + deep = false; + + // Handle a deep copy situation + if ( typeof target === "boolean" ) { + deep = target; + + // Skip the boolean and the target + target = arguments[ i ] || {}; + i++; + } + + // Handle case when target is a string or something (possible in deep copy) + if ( typeof target !== "object" && !jQuery.isFunction( target ) ) { + target = {}; + } + + // Extend jQuery itself if only one argument is passed + if ( i === length ) { + target = this; + i--; + } + + for ( ; i < length; i++ ) { + + // Only deal with non-null/undefined values + if ( ( options = arguments[ i ] ) != null ) { + + // Extend the base object + for ( name in options ) { + src = target[ name ]; + copy = options[ name ]; + + // Prevent never-ending loop + if ( target === copy ) { + continue; + } + + // Recurse if we're merging plain objects or arrays + if ( deep && copy && ( jQuery.isPlainObject( copy ) || + ( copyIsArray = Array.isArray( copy ) ) ) ) { + + if ( copyIsArray ) { + copyIsArray = false; + clone = src && Array.isArray( src ) ? src : []; + + } else { + clone = src && jQuery.isPlainObject( src ) ? src : {}; + } + + // Never move original objects, clone them + target[ name ] = jQuery.extend( deep, clone, copy ); + + // Don't bring in undefined values + } else if ( copy !== undefined ) { + target[ name ] = copy; + } + } + } + } + + // Return the modified object + return target; +}; + +jQuery.extend( { + + // Unique for each copy of jQuery on the page + expando: "jQuery" + ( version + Math.random() ).replace( /\D/g, "" ), + + // Assume jQuery is ready without the ready module + isReady: true, + + error: function( msg ) { + throw new Error( msg ); + }, + + noop: function() {}, + + isFunction: function( obj ) { + return jQuery.type( obj ) === "function"; + }, + + isWindow: function( obj ) { + return obj != null && obj === obj.window; + }, + + isNumeric: function( obj ) { + + // As of jQuery 3.0, isNumeric is limited to + // strings and numbers (primitives or objects) + // that can be coerced to finite numbers (gh-2662) + var type = jQuery.type( obj ); + return ( type === "number" || type === "string" ) && + + // parseFloat NaNs numeric-cast false positives ("") + // ...but misinterprets leading-number strings, particularly hex literals ("0x...") + // subtraction forces infinities to NaN + !isNaN( obj - parseFloat( obj ) ); + }, + + isPlainObject: function( obj ) { + var proto, Ctor; + + // Detect obvious negatives + // Use toString instead of jQuery.type to catch host objects + if ( !obj || toString.call( obj ) !== "[object Object]" ) { + return false; + } + + proto = getProto( obj ); + + // Objects with no prototype (e.g., `Object.create( null )`) are plain + if ( !proto ) { + return true; + } + + // Objects with prototype are plain iff they were constructed by a global Object function + Ctor = hasOwn.call( proto, "constructor" ) && proto.constructor; + return typeof Ctor === "function" && fnToString.call( Ctor ) === ObjectFunctionString; + }, + + isEmptyObject: function( obj ) { + + /* eslint-disable no-unused-vars */ + // See https://github.com/eslint/eslint/issues/6125 + var name; + + for ( name in obj ) { + return false; + } + return true; + }, + + type: function( obj ) { + if ( obj == null ) { + return obj + ""; + } + + // Support: Android <=2.3 only (functionish RegExp) + return typeof obj === "object" || typeof obj === "function" ? + class2type[ toString.call( obj ) ] || "object" : + typeof obj; + }, + + // Evaluates a script in a global context + globalEval: function( code ) { + DOMEval( code ); + }, + + // Convert dashed to camelCase; used by the css and data modules + // Support: IE <=9 - 11, Edge 12 - 13 + // Microsoft forgot to hump their vendor prefix (#9572) + camelCase: function( string ) { + return string.replace( rmsPrefix, "ms-" ).replace( rdashAlpha, fcamelCase ); + }, + + each: function( obj, callback ) { + var length, i = 0; + + if ( isArrayLike( obj ) ) { + length = obj.length; + for ( ; i < length; i++ ) { + if ( callback.call( obj[ i ], i, obj[ i ] ) === false ) { + break; + } + } + } else { + for ( i in obj ) { + if ( callback.call( obj[ i ], i, obj[ i ] ) === false ) { + break; + } + } + } + + return obj; + }, + + // Support: Android <=4.0 only + trim: function( text ) { + return text == null ? + "" : + ( text + "" ).replace( rtrim, "" ); + }, + + // results is for internal usage only + makeArray: function( arr, results ) { + var ret = results || []; + + if ( arr != null ) { + if ( isArrayLike( Object( arr ) ) ) { + jQuery.merge( ret, + typeof arr === "string" ? + [ arr ] : arr + ); + } else { + push.call( ret, arr ); + } + } + + return ret; + }, + + inArray: function( elem, arr, i ) { + return arr == null ? -1 : indexOf.call( arr, elem, i ); + }, + + // Support: Android <=4.0 only, PhantomJS 1 only + // push.apply(_, arraylike) throws on ancient WebKit + merge: function( first, second ) { + var len = +second.length, + j = 0, + i = first.length; + + for ( ; j < len; j++ ) { + first[ i++ ] = second[ j ]; + } + + first.length = i; + + return first; + }, + + grep: function( elems, callback, invert ) { + var callbackInverse, + matches = [], + i = 0, + length = elems.length, + callbackExpect = !invert; + + // Go through the array, only saving the items + // that pass the validator function + for ( ; i < length; i++ ) { + callbackInverse = !callback( elems[ i ], i ); + if ( callbackInverse !== callbackExpect ) { + matches.push( elems[ i ] ); + } + } + + return matches; + }, + + // arg is for internal usage only + map: function( elems, callback, arg ) { + var length, value, + i = 0, + ret = []; + + // Go through the array, translating each of the items to their new values + if ( isArrayLike( elems ) ) { + length = elems.length; + for ( ; i < length; i++ ) { + value = callback( elems[ i ], i, arg ); + + if ( value != null ) { + ret.push( value ); + } + } + + // Go through every key on the object, + } else { + for ( i in elems ) { + value = callback( elems[ i ], i, arg ); + + if ( value != null ) { + ret.push( value ); + } + } + } + + // Flatten any nested arrays + return concat.apply( [], ret ); + }, + + // A global GUID counter for objects + guid: 1, + + // Bind a function to a context, optionally partially applying any + // arguments. + proxy: function( fn, context ) { + var tmp, args, proxy; + + if ( typeof context === "string" ) { + tmp = fn[ context ]; + context = fn; + fn = tmp; + } + + // Quick check to determine if target is callable, in the spec + // this throws a TypeError, but we will just return undefined. + if ( !jQuery.isFunction( fn ) ) { + return undefined; + } + + // Simulated bind + args = slice.call( arguments, 2 ); + proxy = function() { + return fn.apply( context || this, args.concat( slice.call( arguments ) ) ); + }; + + // Set the guid of unique handler to the same of original handler, so it can be removed + proxy.guid = fn.guid = fn.guid || jQuery.guid++; + + return proxy; + }, + + now: Date.now, + + // jQuery.support is not used in Core but other projects attach their + // properties to it so it needs to exist. + support: support +} ); + +if ( typeof Symbol === "function" ) { + jQuery.fn[ Symbol.iterator ] = arr[ Symbol.iterator ]; +} + +// Populate the class2type map +jQuery.each( "Boolean Number String Function Array Date RegExp Object Error Symbol".split( " " ), +function( i, name ) { + class2type[ "[object " + name + "]" ] = name.toLowerCase(); +} ); + +function isArrayLike( obj ) { + + // Support: real iOS 8.2 only (not reproducible in simulator) + // `in` check used to prevent JIT error (gh-2145) + // hasOwn isn't used here due to false negatives + // regarding Nodelist length in IE + var length = !!obj && "length" in obj && obj.length, + type = jQuery.type( obj ); + + if ( type === "function" || jQuery.isWindow( obj ) ) { + return false; + } + + return type === "array" || length === 0 || + typeof length === "number" && length > 0 && ( length - 1 ) in obj; +} +var Sizzle = +/*! + * Sizzle CSS Selector Engine v2.3.3 + * https://sizzlejs.com/ + * + * Copyright jQuery Foundation and other contributors + * Released under the MIT license + * http://jquery.org/license + * + * Date: 2016-08-08 + */ +(function( window ) { + +var i, + support, + Expr, + getText, + isXML, + tokenize, + compile, + select, + outermostContext, + sortInput, + hasDuplicate, + + // Local document vars + setDocument, + document, + docElem, + documentIsHTML, + rbuggyQSA, + rbuggyMatches, + matches, + contains, + + // Instance-specific data + expando = "sizzle" + 1 * new Date(), + preferredDoc = window.document, + dirruns = 0, + done = 0, + classCache = createCache(), + tokenCache = createCache(), + compilerCache = createCache(), + sortOrder = function( a, b ) { + if ( a === b ) { + hasDuplicate = true; + } + return 0; + }, + + // Instance methods + hasOwn = ({}).hasOwnProperty, + arr = [], + pop = arr.pop, + push_native = arr.push, + push = arr.push, + slice = arr.slice, + // Use a stripped-down indexOf as it's faster than native + // https://jsperf.com/thor-indexof-vs-for/5 + indexOf = function( list, elem ) { + var i = 0, + len = list.length; + for ( ; i < len; i++ ) { + if ( list[i] === elem ) { + return i; + } + } + return -1; + }, + + booleans = "checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped", + + // Regular expressions + + // http://www.w3.org/TR/css3-selectors/#whitespace + whitespace = "[\\x20\\t\\r\\n\\f]", + + // http://www.w3.org/TR/CSS21/syndata.html#value-def-identifier + identifier = "(?:\\\\.|[\\w-]|[^\0-\\xa0])+", + + // Attribute selectors: http://www.w3.org/TR/selectors/#attribute-selectors + attributes = "\\[" + whitespace + "*(" + identifier + ")(?:" + whitespace + + // Operator (capture 2) + "*([*^$|!~]?=)" + whitespace + + // "Attribute values must be CSS identifiers [capture 5] or strings [capture 3 or capture 4]" + "*(?:'((?:\\\\.|[^\\\\'])*)'|\"((?:\\\\.|[^\\\\\"])*)\"|(" + identifier + "))|)" + whitespace + + "*\\]", + + pseudos = ":(" + identifier + ")(?:\\((" + + // To reduce the number of selectors needing tokenize in the preFilter, prefer arguments: + // 1. quoted (capture 3; capture 4 or capture 5) + "('((?:\\\\.|[^\\\\'])*)'|\"((?:\\\\.|[^\\\\\"])*)\")|" + + // 2. simple (capture 6) + "((?:\\\\.|[^\\\\()[\\]]|" + attributes + ")*)|" + + // 3. anything else (capture 2) + ".*" + + ")\\)|)", + + // Leading and non-escaped trailing whitespace, capturing some non-whitespace characters preceding the latter + rwhitespace = new RegExp( whitespace + "+", "g" ), + rtrim = new RegExp( "^" + whitespace + "+|((?:^|[^\\\\])(?:\\\\.)*)" + whitespace + "+$", "g" ), + + rcomma = new RegExp( "^" + whitespace + "*," + whitespace + "*" ), + rcombinators = new RegExp( "^" + whitespace + "*([>+~]|" + whitespace + ")" + whitespace + "*" ), + + rattributeQuotes = new RegExp( "=" + whitespace + "*([^\\]'\"]*?)" + whitespace + "*\\]", "g" ), + + rpseudo = new RegExp( pseudos ), + ridentifier = new RegExp( "^" + identifier + "$" ), + + matchExpr = { + "ID": new RegExp( "^#(" + identifier + ")" ), + "CLASS": new RegExp( "^\\.(" + identifier + ")" ), + "TAG": new RegExp( "^(" + identifier + "|[*])" ), + "ATTR": new RegExp( "^" + attributes ), + "PSEUDO": new RegExp( "^" + pseudos ), + "CHILD": new RegExp( "^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\(" + whitespace + + "*(even|odd|(([+-]|)(\\d*)n|)" + whitespace + "*(?:([+-]|)" + whitespace + + "*(\\d+)|))" + whitespace + "*\\)|)", "i" ), + "bool": new RegExp( "^(?:" + booleans + ")$", "i" ), + // For use in libraries implementing .is() + // We use this for POS matching in `select` + "needsContext": new RegExp( "^" + whitespace + "*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\(" + + whitespace + "*((?:-\\d)?\\d*)" + whitespace + "*\\)|)(?=[^-]|$)", "i" ) + }, + + rinputs = /^(?:input|select|textarea|button)$/i, + rheader = /^h\d$/i, + + rnative = /^[^{]+\{\s*\[native \w/, + + // Easily-parseable/retrievable ID or TAG or CLASS selectors + rquickExpr = /^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/, + + rsibling = /[+~]/, + + // CSS escapes + // http://www.w3.org/TR/CSS21/syndata.html#escaped-characters + runescape = new RegExp( "\\\\([\\da-f]{1,6}" + whitespace + "?|(" + whitespace + ")|.)", "ig" ), + funescape = function( _, escaped, escapedWhitespace ) { + var high = "0x" + escaped - 0x10000; + // NaN means non-codepoint + // Support: Firefox<24 + // Workaround erroneous numeric interpretation of +"0x" + return high !== high || escapedWhitespace ? + escaped : + high < 0 ? + // BMP codepoint + String.fromCharCode( high + 0x10000 ) : + // Supplemental Plane codepoint (surrogate pair) + String.fromCharCode( high >> 10 | 0xD800, high & 0x3FF | 0xDC00 ); + }, + + // CSS string/identifier serialization + // https://drafts.csswg.org/cssom/#common-serializing-idioms + rcssescape = /([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g, + fcssescape = function( ch, asCodePoint ) { + if ( asCodePoint ) { + + // U+0000 NULL becomes U+FFFD REPLACEMENT CHARACTER + if ( ch === "\0" ) { + return "\uFFFD"; + } + + // Control characters and (dependent upon position) numbers get escaped as code points + return ch.slice( 0, -1 ) + "\\" + ch.charCodeAt( ch.length - 1 ).toString( 16 ) + " "; + } + + // Other potentially-special ASCII characters get backslash-escaped + return "\\" + ch; + }, + + // Used for iframes + // See setDocument() + // Removing the function wrapper causes a "Permission Denied" + // error in IE + unloadHandler = function() { + setDocument(); + }, + + disabledAncestor = addCombinator( + function( elem ) { + return elem.disabled === true && ("form" in elem || "label" in elem); + }, + { dir: "parentNode", next: "legend" } + ); + +// Optimize for push.apply( _, NodeList ) +try { + push.apply( + (arr = slice.call( preferredDoc.childNodes )), + preferredDoc.childNodes + ); + // Support: Android<4.0 + // Detect silently failing push.apply + arr[ preferredDoc.childNodes.length ].nodeType; +} catch ( e ) { + push = { apply: arr.length ? + + // Leverage slice if possible + function( target, els ) { + push_native.apply( target, slice.call(els) ); + } : + + // Support: IE<9 + // Otherwise append directly + function( target, els ) { + var j = target.length, + i = 0; + // Can't trust NodeList.length + while ( (target[j++] = els[i++]) ) {} + target.length = j - 1; + } + }; +} + +function Sizzle( selector, context, results, seed ) { + var m, i, elem, nid, match, groups, newSelector, + newContext = context && context.ownerDocument, + + // nodeType defaults to 9, since context defaults to document + nodeType = context ? context.nodeType : 9; + + results = results || []; + + // Return early from calls with invalid selector or context + if ( typeof selector !== "string" || !selector || + nodeType !== 1 && nodeType !== 9 && nodeType !== 11 ) { + + return results; + } + + // Try to shortcut find operations (as opposed to filters) in HTML documents + if ( !seed ) { + + if ( ( context ? context.ownerDocument || context : preferredDoc ) !== document ) { + setDocument( context ); + } + context = context || document; + + if ( documentIsHTML ) { + + // If the selector is sufficiently simple, try using a "get*By*" DOM method + // (excepting DocumentFragment context, where the methods don't exist) + if ( nodeType !== 11 && (match = rquickExpr.exec( selector )) ) { + + // ID selector + if ( (m = match[1]) ) { + + // Document context + if ( nodeType === 9 ) { + if ( (elem = context.getElementById( m )) ) { + + // Support: IE, Opera, Webkit + // TODO: identify versions + // getElementById can match elements by name instead of ID + if ( elem.id === m ) { + results.push( elem ); + return results; + } + } else { + return results; + } + + // Element context + } else { + + // Support: IE, Opera, Webkit + // TODO: identify versions + // getElementById can match elements by name instead of ID + if ( newContext && (elem = newContext.getElementById( m )) && + contains( context, elem ) && + elem.id === m ) { + + results.push( elem ); + return results; + } + } + + // Type selector + } else if ( match[2] ) { + push.apply( results, context.getElementsByTagName( selector ) ); + return results; + + // Class selector + } else if ( (m = match[3]) && support.getElementsByClassName && + context.getElementsByClassName ) { + + push.apply( results, context.getElementsByClassName( m ) ); + return results; + } + } + + // Take advantage of querySelectorAll + if ( support.qsa && + !compilerCache[ selector + " " ] && + (!rbuggyQSA || !rbuggyQSA.test( selector )) ) { + + if ( nodeType !== 1 ) { + newContext = context; + newSelector = selector; + + // qSA looks outside Element context, which is not what we want + // Thanks to Andrew Dupont for this workaround technique + // Support: IE <=8 + // Exclude object elements + } else if ( context.nodeName.toLowerCase() !== "object" ) { + + // Capture the context ID, setting it first if necessary + if ( (nid = context.getAttribute( "id" )) ) { + nid = nid.replace( rcssescape, fcssescape ); + } else { + context.setAttribute( "id", (nid = expando) ); + } + + // Prefix every selector in the list + groups = tokenize( selector ); + i = groups.length; + while ( i-- ) { + groups[i] = "#" + nid + " " + toSelector( groups[i] ); + } + newSelector = groups.join( "," ); + + // Expand context for sibling selectors + newContext = rsibling.test( selector ) && testContext( context.parentNode ) || + context; + } + + if ( newSelector ) { + try { + push.apply( results, + newContext.querySelectorAll( newSelector ) + ); + return results; + } catch ( qsaError ) { + } finally { + if ( nid === expando ) { + context.removeAttribute( "id" ); + } + } + } + } + } + } + + // All others + return select( selector.replace( rtrim, "$1" ), context, results, seed ); +} + +/** + * Create key-value caches of limited size + * @returns {function(string, object)} Returns the Object data after storing it on itself with + * property name the (space-suffixed) string and (if the cache is larger than Expr.cacheLength) + * deleting the oldest entry + */ +function createCache() { + var keys = []; + + function cache( key, value ) { + // Use (key + " ") to avoid collision with native prototype properties (see Issue #157) + if ( keys.push( key + " " ) > Expr.cacheLength ) { + // Only keep the most recent entries + delete cache[ keys.shift() ]; + } + return (cache[ key + " " ] = value); + } + return cache; +} + +/** + * Mark a function for special use by Sizzle + * @param {Function} fn The function to mark + */ +function markFunction( fn ) { + fn[ expando ] = true; + return fn; +} + +/** + * Support testing using an element + * @param {Function} fn Passed the created element and returns a boolean result + */ +function assert( fn ) { + var el = document.createElement("fieldset"); + + try { + return !!fn( el ); + } catch (e) { + return false; + } finally { + // Remove from its parent by default + if ( el.parentNode ) { + el.parentNode.removeChild( el ); + } + // release memory in IE + el = null; + } +} + +/** + * Adds the same handler for all of the specified attrs + * @param {String} attrs Pipe-separated list of attributes + * @param {Function} handler The method that will be applied + */ +function addHandle( attrs, handler ) { + var arr = attrs.split("|"), + i = arr.length; + + while ( i-- ) { + Expr.attrHandle[ arr[i] ] = handler; + } +} + +/** + * Checks document order of two siblings + * @param {Element} a + * @param {Element} b + * @returns {Number} Returns less than 0 if a precedes b, greater than 0 if a follows b + */ +function siblingCheck( a, b ) { + var cur = b && a, + diff = cur && a.nodeType === 1 && b.nodeType === 1 && + a.sourceIndex - b.sourceIndex; + + // Use IE sourceIndex if available on both nodes + if ( diff ) { + return diff; + } + + // Check if b follows a + if ( cur ) { + while ( (cur = cur.nextSibling) ) { + if ( cur === b ) { + return -1; + } + } + } + + return a ? 1 : -1; +} + +/** + * Returns a function to use in pseudos for input types + * @param {String} type + */ +function createInputPseudo( type ) { + return function( elem ) { + var name = elem.nodeName.toLowerCase(); + return name === "input" && elem.type === type; + }; +} + +/** + * Returns a function to use in pseudos for buttons + * @param {String} type + */ +function createButtonPseudo( type ) { + return function( elem ) { + var name = elem.nodeName.toLowerCase(); + return (name === "input" || name === "button") && elem.type === type; + }; +} + +/** + * Returns a function to use in pseudos for :enabled/:disabled + * @param {Boolean} disabled true for :disabled; false for :enabled + */ +function createDisabledPseudo( disabled ) { + + // Known :disabled false positives: fieldset[disabled] > legend:nth-of-type(n+2) :can-disable + return function( elem ) { + + // Only certain elements can match :enabled or :disabled + // https://html.spec.whatwg.org/multipage/scripting.html#selector-enabled + // https://html.spec.whatwg.org/multipage/scripting.html#selector-disabled + if ( "form" in elem ) { + + // Check for inherited disabledness on relevant non-disabled elements: + // * listed form-associated elements in a disabled fieldset + // https://html.spec.whatwg.org/multipage/forms.html#category-listed + // https://html.spec.whatwg.org/multipage/forms.html#concept-fe-disabled + // * option elements in a disabled optgroup + // https://html.spec.whatwg.org/multipage/forms.html#concept-option-disabled + // All such elements have a "form" property. + if ( elem.parentNode && elem.disabled === false ) { + + // Option elements defer to a parent optgroup if present + if ( "label" in elem ) { + if ( "label" in elem.parentNode ) { + return elem.parentNode.disabled === disabled; + } else { + return elem.disabled === disabled; + } + } + + // Support: IE 6 - 11 + // Use the isDisabled shortcut property to check for disabled fieldset ancestors + return elem.isDisabled === disabled || + + // Where there is no isDisabled, check manually + /* jshint -W018 */ + elem.isDisabled !== !disabled && + disabledAncestor( elem ) === disabled; + } + + return elem.disabled === disabled; + + // Try to winnow out elements that can't be disabled before trusting the disabled property. + // Some victims get caught in our net (label, legend, menu, track), but it shouldn't + // even exist on them, let alone have a boolean value. + } else if ( "label" in elem ) { + return elem.disabled === disabled; + } + + // Remaining elements are neither :enabled nor :disabled + return false; + }; +} + +/** + * Returns a function to use in pseudos for positionals + * @param {Function} fn + */ +function createPositionalPseudo( fn ) { + return markFunction(function( argument ) { + argument = +argument; + return markFunction(function( seed, matches ) { + var j, + matchIndexes = fn( [], seed.length, argument ), + i = matchIndexes.length; + + // Match elements found at the specified indexes + while ( i-- ) { + if ( seed[ (j = matchIndexes[i]) ] ) { + seed[j] = !(matches[j] = seed[j]); + } + } + }); + }); +} + +/** + * Checks a node for validity as a Sizzle context + * @param {Element|Object=} context + * @returns {Element|Object|Boolean} The input node if acceptable, otherwise a falsy value + */ +function testContext( context ) { + return context && typeof context.getElementsByTagName !== "undefined" && context; +} + +// Expose support vars for convenience +support = Sizzle.support = {}; + +/** + * Detects XML nodes + * @param {Element|Object} elem An element or a document + * @returns {Boolean} True iff elem is a non-HTML XML node + */ +isXML = Sizzle.isXML = function( elem ) { + // documentElement is verified for cases where it doesn't yet exist + // (such as loading iframes in IE - #4833) + var documentElement = elem && (elem.ownerDocument || elem).documentElement; + return documentElement ? documentElement.nodeName !== "HTML" : false; +}; + +/** + * Sets document-related variables once based on the current document + * @param {Element|Object} [doc] An element or document object to use to set the document + * @returns {Object} Returns the current document + */ +setDocument = Sizzle.setDocument = function( node ) { + var hasCompare, subWindow, + doc = node ? node.ownerDocument || node : preferredDoc; + + // Return early if doc is invalid or already selected + if ( doc === document || doc.nodeType !== 9 || !doc.documentElement ) { + return document; + } + + // Update global variables + document = doc; + docElem = document.documentElement; + documentIsHTML = !isXML( document ); + + // Support: IE 9-11, Edge + // Accessing iframe documents after unload throws "permission denied" errors (jQuery #13936) + if ( preferredDoc !== document && + (subWindow = document.defaultView) && subWindow.top !== subWindow ) { + + // Support: IE 11, Edge + if ( subWindow.addEventListener ) { + subWindow.addEventListener( "unload", unloadHandler, false ); + + // Support: IE 9 - 10 only + } else if ( subWindow.attachEvent ) { + subWindow.attachEvent( "onunload", unloadHandler ); + } + } + + /* Attributes + ---------------------------------------------------------------------- */ + + // Support: IE<8 + // Verify that getAttribute really returns attributes and not properties + // (excepting IE8 booleans) + support.attributes = assert(function( el ) { + el.className = "i"; + return !el.getAttribute("className"); + }); + + /* getElement(s)By* + ---------------------------------------------------------------------- */ + + // Check if getElementsByTagName("*") returns only elements + support.getElementsByTagName = assert(function( el ) { + el.appendChild( document.createComment("") ); + return !el.getElementsByTagName("*").length; + }); + + // Support: IE<9 + support.getElementsByClassName = rnative.test( document.getElementsByClassName ); + + // Support: IE<10 + // Check if getElementById returns elements by name + // The broken getElementById methods don't pick up programmatically-set names, + // so use a roundabout getElementsByName test + support.getById = assert(function( el ) { + docElem.appendChild( el ).id = expando; + return !document.getElementsByName || !document.getElementsByName( expando ).length; + }); + + // ID filter and find + if ( support.getById ) { + Expr.filter["ID"] = function( id ) { + var attrId = id.replace( runescape, funescape ); + return function( elem ) { + return elem.getAttribute("id") === attrId; + }; + }; + Expr.find["ID"] = function( id, context ) { + if ( typeof context.getElementById !== "undefined" && documentIsHTML ) { + var elem = context.getElementById( id ); + return elem ? [ elem ] : []; + } + }; + } else { + Expr.filter["ID"] = function( id ) { + var attrId = id.replace( runescape, funescape ); + return function( elem ) { + var node = typeof elem.getAttributeNode !== "undefined" && + elem.getAttributeNode("id"); + return node && node.value === attrId; + }; + }; + + // Support: IE 6 - 7 only + // getElementById is not reliable as a find shortcut + Expr.find["ID"] = function( id, context ) { + if ( typeof context.getElementById !== "undefined" && documentIsHTML ) { + var node, i, elems, + elem = context.getElementById( id ); + + if ( elem ) { + + // Verify the id attribute + node = elem.getAttributeNode("id"); + if ( node && node.value === id ) { + return [ elem ]; + } + + // Fall back on getElementsByName + elems = context.getElementsByName( id ); + i = 0; + while ( (elem = elems[i++]) ) { + node = elem.getAttributeNode("id"); + if ( node && node.value === id ) { + return [ elem ]; + } + } + } + + return []; + } + }; + } + + // Tag + Expr.find["TAG"] = support.getElementsByTagName ? + function( tag, context ) { + if ( typeof context.getElementsByTagName !== "undefined" ) { + return context.getElementsByTagName( tag ); + + // DocumentFragment nodes don't have gEBTN + } else if ( support.qsa ) { + return context.querySelectorAll( tag ); + } + } : + + function( tag, context ) { + var elem, + tmp = [], + i = 0, + // By happy coincidence, a (broken) gEBTN appears on DocumentFragment nodes too + results = context.getElementsByTagName( tag ); + + // Filter out possible comments + if ( tag === "*" ) { + while ( (elem = results[i++]) ) { + if ( elem.nodeType === 1 ) { + tmp.push( elem ); + } + } + + return tmp; + } + return results; + }; + + // Class + Expr.find["CLASS"] = support.getElementsByClassName && function( className, context ) { + if ( typeof context.getElementsByClassName !== "undefined" && documentIsHTML ) { + return context.getElementsByClassName( className ); + } + }; + + /* QSA/matchesSelector + ---------------------------------------------------------------------- */ + + // QSA and matchesSelector support + + // matchesSelector(:active) reports false when true (IE9/Opera 11.5) + rbuggyMatches = []; + + // qSa(:focus) reports false when true (Chrome 21) + // We allow this because of a bug in IE8/9 that throws an error + // whenever `document.activeElement` is accessed on an iframe + // So, we allow :focus to pass through QSA all the time to avoid the IE error + // See https://bugs.jquery.com/ticket/13378 + rbuggyQSA = []; + + if ( (support.qsa = rnative.test( document.querySelectorAll )) ) { + // Build QSA regex + // Regex strategy adopted from Diego Perini + assert(function( el ) { + // Select is set to empty string on purpose + // This is to test IE's treatment of not explicitly + // setting a boolean content attribute, + // since its presence should be enough + // https://bugs.jquery.com/ticket/12359 + docElem.appendChild( el ).innerHTML = "" + + ""; + + // Support: IE8, Opera 11-12.16 + // Nothing should be selected when empty strings follow ^= or $= or *= + // The test attribute must be unknown in Opera but "safe" for WinRT + // https://msdn.microsoft.com/en-us/library/ie/hh465388.aspx#attribute_section + if ( el.querySelectorAll("[msallowcapture^='']").length ) { + rbuggyQSA.push( "[*^$]=" + whitespace + "*(?:''|\"\")" ); + } + + // Support: IE8 + // Boolean attributes and "value" are not treated correctly + if ( !el.querySelectorAll("[selected]").length ) { + rbuggyQSA.push( "\\[" + whitespace + "*(?:value|" + booleans + ")" ); + } + + // Support: Chrome<29, Android<4.4, Safari<7.0+, iOS<7.0+, PhantomJS<1.9.8+ + if ( !el.querySelectorAll( "[id~=" + expando + "-]" ).length ) { + rbuggyQSA.push("~="); + } + + // Webkit/Opera - :checked should return selected option elements + // http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked + // IE8 throws error here and will not see later tests + if ( !el.querySelectorAll(":checked").length ) { + rbuggyQSA.push(":checked"); + } + + // Support: Safari 8+, iOS 8+ + // https://bugs.webkit.org/show_bug.cgi?id=136851 + // In-page `selector#id sibling-combinator selector` fails + if ( !el.querySelectorAll( "a#" + expando + "+*" ).length ) { + rbuggyQSA.push(".#.+[+~]"); + } + }); + + assert(function( el ) { + el.innerHTML = "" + + ""; + + // Support: Windows 8 Native Apps + // The type and name attributes are restricted during .innerHTML assignment + var input = document.createElement("input"); + input.setAttribute( "type", "hidden" ); + el.appendChild( input ).setAttribute( "name", "D" ); + + // Support: IE8 + // Enforce case-sensitivity of name attribute + if ( el.querySelectorAll("[name=d]").length ) { + rbuggyQSA.push( "name" + whitespace + "*[*^$|!~]?=" ); + } + + // FF 3.5 - :enabled/:disabled and hidden elements (hidden elements are still enabled) + // IE8 throws error here and will not see later tests + if ( el.querySelectorAll(":enabled").length !== 2 ) { + rbuggyQSA.push( ":enabled", ":disabled" ); + } + + // Support: IE9-11+ + // IE's :disabled selector does not pick up the children of disabled fieldsets + docElem.appendChild( el ).disabled = true; + if ( el.querySelectorAll(":disabled").length !== 2 ) { + rbuggyQSA.push( ":enabled", ":disabled" ); + } + + // Opera 10-11 does not throw on post-comma invalid pseudos + el.querySelectorAll("*,:x"); + rbuggyQSA.push(",.*:"); + }); + } + + if ( (support.matchesSelector = rnative.test( (matches = docElem.matches || + docElem.webkitMatchesSelector || + docElem.mozMatchesSelector || + docElem.oMatchesSelector || + docElem.msMatchesSelector) )) ) { + + assert(function( el ) { + // Check to see if it's possible to do matchesSelector + // on a disconnected node (IE 9) + support.disconnectedMatch = matches.call( el, "*" ); + + // This should fail with an exception + // Gecko does not error, returns false instead + matches.call( el, "[s!='']:x" ); + rbuggyMatches.push( "!=", pseudos ); + }); + } + + rbuggyQSA = rbuggyQSA.length && new RegExp( rbuggyQSA.join("|") ); + rbuggyMatches = rbuggyMatches.length && new RegExp( rbuggyMatches.join("|") ); + + /* Contains + ---------------------------------------------------------------------- */ + hasCompare = rnative.test( docElem.compareDocumentPosition ); + + // Element contains another + // Purposefully self-exclusive + // As in, an element does not contain itself + contains = hasCompare || rnative.test( docElem.contains ) ? + function( a, b ) { + var adown = a.nodeType === 9 ? a.documentElement : a, + bup = b && b.parentNode; + return a === bup || !!( bup && bup.nodeType === 1 && ( + adown.contains ? + adown.contains( bup ) : + a.compareDocumentPosition && a.compareDocumentPosition( bup ) & 16 + )); + } : + function( a, b ) { + if ( b ) { + while ( (b = b.parentNode) ) { + if ( b === a ) { + return true; + } + } + } + return false; + }; + + /* Sorting + ---------------------------------------------------------------------- */ + + // Document order sorting + sortOrder = hasCompare ? + function( a, b ) { + + // Flag for duplicate removal + if ( a === b ) { + hasDuplicate = true; + return 0; + } + + // Sort on method existence if only one input has compareDocumentPosition + var compare = !a.compareDocumentPosition - !b.compareDocumentPosition; + if ( compare ) { + return compare; + } + + // Calculate position if both inputs belong to the same document + compare = ( a.ownerDocument || a ) === ( b.ownerDocument || b ) ? + a.compareDocumentPosition( b ) : + + // Otherwise we know they are disconnected + 1; + + // Disconnected nodes + if ( compare & 1 || + (!support.sortDetached && b.compareDocumentPosition( a ) === compare) ) { + + // Choose the first element that is related to our preferred document + if ( a === document || a.ownerDocument === preferredDoc && contains(preferredDoc, a) ) { + return -1; + } + if ( b === document || b.ownerDocument === preferredDoc && contains(preferredDoc, b) ) { + return 1; + } + + // Maintain original order + return sortInput ? + ( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) : + 0; + } + + return compare & 4 ? -1 : 1; + } : + function( a, b ) { + // Exit early if the nodes are identical + if ( a === b ) { + hasDuplicate = true; + return 0; + } + + var cur, + i = 0, + aup = a.parentNode, + bup = b.parentNode, + ap = [ a ], + bp = [ b ]; + + // Parentless nodes are either documents or disconnected + if ( !aup || !bup ) { + return a === document ? -1 : + b === document ? 1 : + aup ? -1 : + bup ? 1 : + sortInput ? + ( indexOf( sortInput, a ) - indexOf( sortInput, b ) ) : + 0; + + // If the nodes are siblings, we can do a quick check + } else if ( aup === bup ) { + return siblingCheck( a, b ); + } + + // Otherwise we need full lists of their ancestors for comparison + cur = a; + while ( (cur = cur.parentNode) ) { + ap.unshift( cur ); + } + cur = b; + while ( (cur = cur.parentNode) ) { + bp.unshift( cur ); + } + + // Walk down the tree looking for a discrepancy + while ( ap[i] === bp[i] ) { + i++; + } + + return i ? + // Do a sibling check if the nodes have a common ancestor + siblingCheck( ap[i], bp[i] ) : + + // Otherwise nodes in our document sort first + ap[i] === preferredDoc ? -1 : + bp[i] === preferredDoc ? 1 : + 0; + }; + + return document; +}; + +Sizzle.matches = function( expr, elements ) { + return Sizzle( expr, null, null, elements ); +}; + +Sizzle.matchesSelector = function( elem, expr ) { + // Set document vars if needed + if ( ( elem.ownerDocument || elem ) !== document ) { + setDocument( elem ); + } + + // Make sure that attribute selectors are quoted + expr = expr.replace( rattributeQuotes, "='$1']" ); + + if ( support.matchesSelector && documentIsHTML && + !compilerCache[ expr + " " ] && + ( !rbuggyMatches || !rbuggyMatches.test( expr ) ) && + ( !rbuggyQSA || !rbuggyQSA.test( expr ) ) ) { + + try { + var ret = matches.call( elem, expr ); + + // IE 9's matchesSelector returns false on disconnected nodes + if ( ret || support.disconnectedMatch || + // As well, disconnected nodes are said to be in a document + // fragment in IE 9 + elem.document && elem.document.nodeType !== 11 ) { + return ret; + } + } catch (e) {} + } + + return Sizzle( expr, document, null, [ elem ] ).length > 0; +}; + +Sizzle.contains = function( context, elem ) { + // Set document vars if needed + if ( ( context.ownerDocument || context ) !== document ) { + setDocument( context ); + } + return contains( context, elem ); +}; + +Sizzle.attr = function( elem, name ) { + // Set document vars if needed + if ( ( elem.ownerDocument || elem ) !== document ) { + setDocument( elem ); + } + + var fn = Expr.attrHandle[ name.toLowerCase() ], + // Don't get fooled by Object.prototype properties (jQuery #13807) + val = fn && hasOwn.call( Expr.attrHandle, name.toLowerCase() ) ? + fn( elem, name, !documentIsHTML ) : + undefined; + + return val !== undefined ? + val : + support.attributes || !documentIsHTML ? + elem.getAttribute( name ) : + (val = elem.getAttributeNode(name)) && val.specified ? + val.value : + null; +}; + +Sizzle.escape = function( sel ) { + return (sel + "").replace( rcssescape, fcssescape ); +}; + +Sizzle.error = function( msg ) { + throw new Error( "Syntax error, unrecognized expression: " + msg ); +}; + +/** + * Document sorting and removing duplicates + * @param {ArrayLike} results + */ +Sizzle.uniqueSort = function( results ) { + var elem, + duplicates = [], + j = 0, + i = 0; + + // Unless we *know* we can detect duplicates, assume their presence + hasDuplicate = !support.detectDuplicates; + sortInput = !support.sortStable && results.slice( 0 ); + results.sort( sortOrder ); + + if ( hasDuplicate ) { + while ( (elem = results[i++]) ) { + if ( elem === results[ i ] ) { + j = duplicates.push( i ); + } + } + while ( j-- ) { + results.splice( duplicates[ j ], 1 ); + } + } + + // Clear input after sorting to release objects + // See https://github.com/jquery/sizzle/pull/225 + sortInput = null; + + return results; +}; + +/** + * Utility function for retrieving the text value of an array of DOM nodes + * @param {Array|Element} elem + */ +getText = Sizzle.getText = function( elem ) { + var node, + ret = "", + i = 0, + nodeType = elem.nodeType; + + if ( !nodeType ) { + // If no nodeType, this is expected to be an array + while ( (node = elem[i++]) ) { + // Do not traverse comment nodes + ret += getText( node ); + } + } else if ( nodeType === 1 || nodeType === 9 || nodeType === 11 ) { + // Use textContent for elements + // innerText usage removed for consistency of new lines (jQuery #11153) + if ( typeof elem.textContent === "string" ) { + return elem.textContent; + } else { + // Traverse its children + for ( elem = elem.firstChild; elem; elem = elem.nextSibling ) { + ret += getText( elem ); + } + } + } else if ( nodeType === 3 || nodeType === 4 ) { + return elem.nodeValue; + } + // Do not include comment or processing instruction nodes + + return ret; +}; + +Expr = Sizzle.selectors = { + + // Can be adjusted by the user + cacheLength: 50, + + createPseudo: markFunction, + + match: matchExpr, + + attrHandle: {}, + + find: {}, + + relative: { + ">": { dir: "parentNode", first: true }, + " ": { dir: "parentNode" }, + "+": { dir: "previousSibling", first: true }, + "~": { dir: "previousSibling" } + }, + + preFilter: { + "ATTR": function( match ) { + match[1] = match[1].replace( runescape, funescape ); + + // Move the given value to match[3] whether quoted or unquoted + match[3] = ( match[3] || match[4] || match[5] || "" ).replace( runescape, funescape ); + + if ( match[2] === "~=" ) { + match[3] = " " + match[3] + " "; + } + + return match.slice( 0, 4 ); + }, + + "CHILD": function( match ) { + /* matches from matchExpr["CHILD"] + 1 type (only|nth|...) + 2 what (child|of-type) + 3 argument (even|odd|\d*|\d*n([+-]\d+)?|...) + 4 xn-component of xn+y argument ([+-]?\d*n|) + 5 sign of xn-component + 6 x of xn-component + 7 sign of y-component + 8 y of y-component + */ + match[1] = match[1].toLowerCase(); + + if ( match[1].slice( 0, 3 ) === "nth" ) { + // nth-* requires argument + if ( !match[3] ) { + Sizzle.error( match[0] ); + } + + // numeric x and y parameters for Expr.filter.CHILD + // remember that false/true cast respectively to 0/1 + match[4] = +( match[4] ? match[5] + (match[6] || 1) : 2 * ( match[3] === "even" || match[3] === "odd" ) ); + match[5] = +( ( match[7] + match[8] ) || match[3] === "odd" ); + + // other types prohibit arguments + } else if ( match[3] ) { + Sizzle.error( match[0] ); + } + + return match; + }, + + "PSEUDO": function( match ) { + var excess, + unquoted = !match[6] && match[2]; + + if ( matchExpr["CHILD"].test( match[0] ) ) { + return null; + } + + // Accept quoted arguments as-is + if ( match[3] ) { + match[2] = match[4] || match[5] || ""; + + // Strip excess characters from unquoted arguments + } else if ( unquoted && rpseudo.test( unquoted ) && + // Get excess from tokenize (recursively) + (excess = tokenize( unquoted, true )) && + // advance to the next closing parenthesis + (excess = unquoted.indexOf( ")", unquoted.length - excess ) - unquoted.length) ) { + + // excess is a negative index + match[0] = match[0].slice( 0, excess ); + match[2] = unquoted.slice( 0, excess ); + } + + // Return only captures needed by the pseudo filter method (type and argument) + return match.slice( 0, 3 ); + } + }, + + filter: { + + "TAG": function( nodeNameSelector ) { + var nodeName = nodeNameSelector.replace( runescape, funescape ).toLowerCase(); + return nodeNameSelector === "*" ? + function() { return true; } : + function( elem ) { + return elem.nodeName && elem.nodeName.toLowerCase() === nodeName; + }; + }, + + "CLASS": function( className ) { + var pattern = classCache[ className + " " ]; + + return pattern || + (pattern = new RegExp( "(^|" + whitespace + ")" + className + "(" + whitespace + "|$)" )) && + classCache( className, function( elem ) { + return pattern.test( typeof elem.className === "string" && elem.className || typeof elem.getAttribute !== "undefined" && elem.getAttribute("class") || "" ); + }); + }, + + "ATTR": function( name, operator, check ) { + return function( elem ) { + var result = Sizzle.attr( elem, name ); + + if ( result == null ) { + return operator === "!="; + } + if ( !operator ) { + return true; + } + + result += ""; + + return operator === "=" ? result === check : + operator === "!=" ? result !== check : + operator === "^=" ? check && result.indexOf( check ) === 0 : + operator === "*=" ? check && result.indexOf( check ) > -1 : + operator === "$=" ? check && result.slice( -check.length ) === check : + operator === "~=" ? ( " " + result.replace( rwhitespace, " " ) + " " ).indexOf( check ) > -1 : + operator === "|=" ? result === check || result.slice( 0, check.length + 1 ) === check + "-" : + false; + }; + }, + + "CHILD": function( type, what, argument, first, last ) { + var simple = type.slice( 0, 3 ) !== "nth", + forward = type.slice( -4 ) !== "last", + ofType = what === "of-type"; + + return first === 1 && last === 0 ? + + // Shortcut for :nth-*(n) + function( elem ) { + return !!elem.parentNode; + } : + + function( elem, context, xml ) { + var cache, uniqueCache, outerCache, node, nodeIndex, start, + dir = simple !== forward ? "nextSibling" : "previousSibling", + parent = elem.parentNode, + name = ofType && elem.nodeName.toLowerCase(), + useCache = !xml && !ofType, + diff = false; + + if ( parent ) { + + // :(first|last|only)-(child|of-type) + if ( simple ) { + while ( dir ) { + node = elem; + while ( (node = node[ dir ]) ) { + if ( ofType ? + node.nodeName.toLowerCase() === name : + node.nodeType === 1 ) { + + return false; + } + } + // Reverse direction for :only-* (if we haven't yet done so) + start = dir = type === "only" && !start && "nextSibling"; + } + return true; + } + + start = [ forward ? parent.firstChild : parent.lastChild ]; + + // non-xml :nth-child(...) stores cache data on `parent` + if ( forward && useCache ) { + + // Seek `elem` from a previously-cached index + + // ...in a gzip-friendly way + node = parent; + outerCache = node[ expando ] || (node[ expando ] = {}); + + // Support: IE <9 only + // Defend against cloned attroperties (jQuery gh-1709) + uniqueCache = outerCache[ node.uniqueID ] || + (outerCache[ node.uniqueID ] = {}); + + cache = uniqueCache[ type ] || []; + nodeIndex = cache[ 0 ] === dirruns && cache[ 1 ]; + diff = nodeIndex && cache[ 2 ]; + node = nodeIndex && parent.childNodes[ nodeIndex ]; + + while ( (node = ++nodeIndex && node && node[ dir ] || + + // Fallback to seeking `elem` from the start + (diff = nodeIndex = 0) || start.pop()) ) { + + // When found, cache indexes on `parent` and break + if ( node.nodeType === 1 && ++diff && node === elem ) { + uniqueCache[ type ] = [ dirruns, nodeIndex, diff ]; + break; + } + } + + } else { + // Use previously-cached element index if available + if ( useCache ) { + // ...in a gzip-friendly way + node = elem; + outerCache = node[ expando ] || (node[ expando ] = {}); + + // Support: IE <9 only + // Defend against cloned attroperties (jQuery gh-1709) + uniqueCache = outerCache[ node.uniqueID ] || + (outerCache[ node.uniqueID ] = {}); + + cache = uniqueCache[ type ] || []; + nodeIndex = cache[ 0 ] === dirruns && cache[ 1 ]; + diff = nodeIndex; + } + + // xml :nth-child(...) + // or :nth-last-child(...) or :nth(-last)?-of-type(...) + if ( diff === false ) { + // Use the same loop as above to seek `elem` from the start + while ( (node = ++nodeIndex && node && node[ dir ] || + (diff = nodeIndex = 0) || start.pop()) ) { + + if ( ( ofType ? + node.nodeName.toLowerCase() === name : + node.nodeType === 1 ) && + ++diff ) { + + // Cache the index of each encountered element + if ( useCache ) { + outerCache = node[ expando ] || (node[ expando ] = {}); + + // Support: IE <9 only + // Defend against cloned attroperties (jQuery gh-1709) + uniqueCache = outerCache[ node.uniqueID ] || + (outerCache[ node.uniqueID ] = {}); + + uniqueCache[ type ] = [ dirruns, diff ]; + } + + if ( node === elem ) { + break; + } + } + } + } + } + + // Incorporate the offset, then check against cycle size + diff -= last; + return diff === first || ( diff % first === 0 && diff / first >= 0 ); + } + }; + }, + + "PSEUDO": function( pseudo, argument ) { + // pseudo-class names are case-insensitive + // http://www.w3.org/TR/selectors/#pseudo-classes + // Prioritize by case sensitivity in case custom pseudos are added with uppercase letters + // Remember that setFilters inherits from pseudos + var args, + fn = Expr.pseudos[ pseudo ] || Expr.setFilters[ pseudo.toLowerCase() ] || + Sizzle.error( "unsupported pseudo: " + pseudo ); + + // The user may use createPseudo to indicate that + // arguments are needed to create the filter function + // just as Sizzle does + if ( fn[ expando ] ) { + return fn( argument ); + } + + // But maintain support for old signatures + if ( fn.length > 1 ) { + args = [ pseudo, pseudo, "", argument ]; + return Expr.setFilters.hasOwnProperty( pseudo.toLowerCase() ) ? + markFunction(function( seed, matches ) { + var idx, + matched = fn( seed, argument ), + i = matched.length; + while ( i-- ) { + idx = indexOf( seed, matched[i] ); + seed[ idx ] = !( matches[ idx ] = matched[i] ); + } + }) : + function( elem ) { + return fn( elem, 0, args ); + }; + } + + return fn; + } + }, + + pseudos: { + // Potentially complex pseudos + "not": markFunction(function( selector ) { + // Trim the selector passed to compile + // to avoid treating leading and trailing + // spaces as combinators + var input = [], + results = [], + matcher = compile( selector.replace( rtrim, "$1" ) ); + + return matcher[ expando ] ? + markFunction(function( seed, matches, context, xml ) { + var elem, + unmatched = matcher( seed, null, xml, [] ), + i = seed.length; + + // Match elements unmatched by `matcher` + while ( i-- ) { + if ( (elem = unmatched[i]) ) { + seed[i] = !(matches[i] = elem); + } + } + }) : + function( elem, context, xml ) { + input[0] = elem; + matcher( input, null, xml, results ); + // Don't keep the element (issue #299) + input[0] = null; + return !results.pop(); + }; + }), + + "has": markFunction(function( selector ) { + return function( elem ) { + return Sizzle( selector, elem ).length > 0; + }; + }), + + "contains": markFunction(function( text ) { + text = text.replace( runescape, funescape ); + return function( elem ) { + return ( elem.textContent || elem.innerText || getText( elem ) ).indexOf( text ) > -1; + }; + }), + + // "Whether an element is represented by a :lang() selector + // is based solely on the element's language value + // being equal to the identifier C, + // or beginning with the identifier C immediately followed by "-". + // The matching of C against the element's language value is performed case-insensitively. + // The identifier C does not have to be a valid language name." + // http://www.w3.org/TR/selectors/#lang-pseudo + "lang": markFunction( function( lang ) { + // lang value must be a valid identifier + if ( !ridentifier.test(lang || "") ) { + Sizzle.error( "unsupported lang: " + lang ); + } + lang = lang.replace( runescape, funescape ).toLowerCase(); + return function( elem ) { + var elemLang; + do { + if ( (elemLang = documentIsHTML ? + elem.lang : + elem.getAttribute("xml:lang") || elem.getAttribute("lang")) ) { + + elemLang = elemLang.toLowerCase(); + return elemLang === lang || elemLang.indexOf( lang + "-" ) === 0; + } + } while ( (elem = elem.parentNode) && elem.nodeType === 1 ); + return false; + }; + }), + + // Miscellaneous + "target": function( elem ) { + var hash = window.location && window.location.hash; + return hash && hash.slice( 1 ) === elem.id; + }, + + "root": function( elem ) { + return elem === docElem; + }, + + "focus": function( elem ) { + return elem === document.activeElement && (!document.hasFocus || document.hasFocus()) && !!(elem.type || elem.href || ~elem.tabIndex); + }, + + // Boolean properties + "enabled": createDisabledPseudo( false ), + "disabled": createDisabledPseudo( true ), + + "checked": function( elem ) { + // In CSS3, :checked should return both checked and selected elements + // http://www.w3.org/TR/2011/REC-css3-selectors-20110929/#checked + var nodeName = elem.nodeName.toLowerCase(); + return (nodeName === "input" && !!elem.checked) || (nodeName === "option" && !!elem.selected); + }, + + "selected": function( elem ) { + // Accessing this property makes selected-by-default + // options in Safari work properly + if ( elem.parentNode ) { + elem.parentNode.selectedIndex; + } + + return elem.selected === true; + }, + + // Contents + "empty": function( elem ) { + // http://www.w3.org/TR/selectors/#empty-pseudo + // :empty is negated by element (1) or content nodes (text: 3; cdata: 4; entity ref: 5), + // but not by others (comment: 8; processing instruction: 7; etc.) + // nodeType < 6 works because attributes (2) do not appear as children + for ( elem = elem.firstChild; elem; elem = elem.nextSibling ) { + if ( elem.nodeType < 6 ) { + return false; + } + } + return true; + }, + + "parent": function( elem ) { + return !Expr.pseudos["empty"]( elem ); + }, + + // Element/input types + "header": function( elem ) { + return rheader.test( elem.nodeName ); + }, + + "input": function( elem ) { + return rinputs.test( elem.nodeName ); + }, + + "button": function( elem ) { + var name = elem.nodeName.toLowerCase(); + return name === "input" && elem.type === "button" || name === "button"; + }, + + "text": function( elem ) { + var attr; + return elem.nodeName.toLowerCase() === "input" && + elem.type === "text" && + + // Support: IE<8 + // New HTML5 attribute values (e.g., "search") appear with elem.type === "text" + ( (attr = elem.getAttribute("type")) == null || attr.toLowerCase() === "text" ); + }, + + // Position-in-collection + "first": createPositionalPseudo(function() { + return [ 0 ]; + }), + + "last": createPositionalPseudo(function( matchIndexes, length ) { + return [ length - 1 ]; + }), + + "eq": createPositionalPseudo(function( matchIndexes, length, argument ) { + return [ argument < 0 ? argument + length : argument ]; + }), + + "even": createPositionalPseudo(function( matchIndexes, length ) { + var i = 0; + for ( ; i < length; i += 2 ) { + matchIndexes.push( i ); + } + return matchIndexes; + }), + + "odd": createPositionalPseudo(function( matchIndexes, length ) { + var i = 1; + for ( ; i < length; i += 2 ) { + matchIndexes.push( i ); + } + return matchIndexes; + }), + + "lt": createPositionalPseudo(function( matchIndexes, length, argument ) { + var i = argument < 0 ? argument + length : argument; + for ( ; --i >= 0; ) { + matchIndexes.push( i ); + } + return matchIndexes; + }), + + "gt": createPositionalPseudo(function( matchIndexes, length, argument ) { + var i = argument < 0 ? argument + length : argument; + for ( ; ++i < length; ) { + matchIndexes.push( i ); + } + return matchIndexes; + }) + } +}; + +Expr.pseudos["nth"] = Expr.pseudos["eq"]; + +// Add button/input type pseudos +for ( i in { radio: true, checkbox: true, file: true, password: true, image: true } ) { + Expr.pseudos[ i ] = createInputPseudo( i ); +} +for ( i in { submit: true, reset: true } ) { + Expr.pseudos[ i ] = createButtonPseudo( i ); +} + +// Easy API for creating new setFilters +function setFilters() {} +setFilters.prototype = Expr.filters = Expr.pseudos; +Expr.setFilters = new setFilters(); + +tokenize = Sizzle.tokenize = function( selector, parseOnly ) { + var matched, match, tokens, type, + soFar, groups, preFilters, + cached = tokenCache[ selector + " " ]; + + if ( cached ) { + return parseOnly ? 0 : cached.slice( 0 ); + } + + soFar = selector; + groups = []; + preFilters = Expr.preFilter; + + while ( soFar ) { + + // Comma and first run + if ( !matched || (match = rcomma.exec( soFar )) ) { + if ( match ) { + // Don't consume trailing commas as valid + soFar = soFar.slice( match[0].length ) || soFar; + } + groups.push( (tokens = []) ); + } + + matched = false; + + // Combinators + if ( (match = rcombinators.exec( soFar )) ) { + matched = match.shift(); + tokens.push({ + value: matched, + // Cast descendant combinators to space + type: match[0].replace( rtrim, " " ) + }); + soFar = soFar.slice( matched.length ); + } + + // Filters + for ( type in Expr.filter ) { + if ( (match = matchExpr[ type ].exec( soFar )) && (!preFilters[ type ] || + (match = preFilters[ type ]( match ))) ) { + matched = match.shift(); + tokens.push({ + value: matched, + type: type, + matches: match + }); + soFar = soFar.slice( matched.length ); + } + } + + if ( !matched ) { + break; + } + } + + // Return the length of the invalid excess + // if we're just parsing + // Otherwise, throw an error or return tokens + return parseOnly ? + soFar.length : + soFar ? + Sizzle.error( selector ) : + // Cache the tokens + tokenCache( selector, groups ).slice( 0 ); +}; + +function toSelector( tokens ) { + var i = 0, + len = tokens.length, + selector = ""; + for ( ; i < len; i++ ) { + selector += tokens[i].value; + } + return selector; +} + +function addCombinator( matcher, combinator, base ) { + var dir = combinator.dir, + skip = combinator.next, + key = skip || dir, + checkNonElements = base && key === "parentNode", + doneName = done++; + + return combinator.first ? + // Check against closest ancestor/preceding element + function( elem, context, xml ) { + while ( (elem = elem[ dir ]) ) { + if ( elem.nodeType === 1 || checkNonElements ) { + return matcher( elem, context, xml ); + } + } + return false; + } : + + // Check against all ancestor/preceding elements + function( elem, context, xml ) { + var oldCache, uniqueCache, outerCache, + newCache = [ dirruns, doneName ]; + + // We can't set arbitrary data on XML nodes, so they don't benefit from combinator caching + if ( xml ) { + while ( (elem = elem[ dir ]) ) { + if ( elem.nodeType === 1 || checkNonElements ) { + if ( matcher( elem, context, xml ) ) { + return true; + } + } + } + } else { + while ( (elem = elem[ dir ]) ) { + if ( elem.nodeType === 1 || checkNonElements ) { + outerCache = elem[ expando ] || (elem[ expando ] = {}); + + // Support: IE <9 only + // Defend against cloned attroperties (jQuery gh-1709) + uniqueCache = outerCache[ elem.uniqueID ] || (outerCache[ elem.uniqueID ] = {}); + + if ( skip && skip === elem.nodeName.toLowerCase() ) { + elem = elem[ dir ] || elem; + } else if ( (oldCache = uniqueCache[ key ]) && + oldCache[ 0 ] === dirruns && oldCache[ 1 ] === doneName ) { + + // Assign to newCache so results back-propagate to previous elements + return (newCache[ 2 ] = oldCache[ 2 ]); + } else { + // Reuse newcache so results back-propagate to previous elements + uniqueCache[ key ] = newCache; + + // A match means we're done; a fail means we have to keep checking + if ( (newCache[ 2 ] = matcher( elem, context, xml )) ) { + return true; + } + } + } + } + } + return false; + }; +} + +function elementMatcher( matchers ) { + return matchers.length > 1 ? + function( elem, context, xml ) { + var i = matchers.length; + while ( i-- ) { + if ( !matchers[i]( elem, context, xml ) ) { + return false; + } + } + return true; + } : + matchers[0]; +} + +function multipleContexts( selector, contexts, results ) { + var i = 0, + len = contexts.length; + for ( ; i < len; i++ ) { + Sizzle( selector, contexts[i], results ); + } + return results; +} + +function condense( unmatched, map, filter, context, xml ) { + var elem, + newUnmatched = [], + i = 0, + len = unmatched.length, + mapped = map != null; + + for ( ; i < len; i++ ) { + if ( (elem = unmatched[i]) ) { + if ( !filter || filter( elem, context, xml ) ) { + newUnmatched.push( elem ); + if ( mapped ) { + map.push( i ); + } + } + } + } + + return newUnmatched; +} + +function setMatcher( preFilter, selector, matcher, postFilter, postFinder, postSelector ) { + if ( postFilter && !postFilter[ expando ] ) { + postFilter = setMatcher( postFilter ); + } + if ( postFinder && !postFinder[ expando ] ) { + postFinder = setMatcher( postFinder, postSelector ); + } + return markFunction(function( seed, results, context, xml ) { + var temp, i, elem, + preMap = [], + postMap = [], + preexisting = results.length, + + // Get initial elements from seed or context + elems = seed || multipleContexts( selector || "*", context.nodeType ? [ context ] : context, [] ), + + // Prefilter to get matcher input, preserving a map for seed-results synchronization + matcherIn = preFilter && ( seed || !selector ) ? + condense( elems, preMap, preFilter, context, xml ) : + elems, + + matcherOut = matcher ? + // If we have a postFinder, or filtered seed, or non-seed postFilter or preexisting results, + postFinder || ( seed ? preFilter : preexisting || postFilter ) ? + + // ...intermediate processing is necessary + [] : + + // ...otherwise use results directly + results : + matcherIn; + + // Find primary matches + if ( matcher ) { + matcher( matcherIn, matcherOut, context, xml ); + } + + // Apply postFilter + if ( postFilter ) { + temp = condense( matcherOut, postMap ); + postFilter( temp, [], context, xml ); + + // Un-match failing elements by moving them back to matcherIn + i = temp.length; + while ( i-- ) { + if ( (elem = temp[i]) ) { + matcherOut[ postMap[i] ] = !(matcherIn[ postMap[i] ] = elem); + } + } + } + + if ( seed ) { + if ( postFinder || preFilter ) { + if ( postFinder ) { + // Get the final matcherOut by condensing this intermediate into postFinder contexts + temp = []; + i = matcherOut.length; + while ( i-- ) { + if ( (elem = matcherOut[i]) ) { + // Restore matcherIn since elem is not yet a final match + temp.push( (matcherIn[i] = elem) ); + } + } + postFinder( null, (matcherOut = []), temp, xml ); + } + + // Move matched elements from seed to results to keep them synchronized + i = matcherOut.length; + while ( i-- ) { + if ( (elem = matcherOut[i]) && + (temp = postFinder ? indexOf( seed, elem ) : preMap[i]) > -1 ) { + + seed[temp] = !(results[temp] = elem); + } + } + } + + // Add elements to results, through postFinder if defined + } else { + matcherOut = condense( + matcherOut === results ? + matcherOut.splice( preexisting, matcherOut.length ) : + matcherOut + ); + if ( postFinder ) { + postFinder( null, results, matcherOut, xml ); + } else { + push.apply( results, matcherOut ); + } + } + }); +} + +function matcherFromTokens( tokens ) { + var checkContext, matcher, j, + len = tokens.length, + leadingRelative = Expr.relative[ tokens[0].type ], + implicitRelative = leadingRelative || Expr.relative[" "], + i = leadingRelative ? 1 : 0, + + // The foundational matcher ensures that elements are reachable from top-level context(s) + matchContext = addCombinator( function( elem ) { + return elem === checkContext; + }, implicitRelative, true ), + matchAnyContext = addCombinator( function( elem ) { + return indexOf( checkContext, elem ) > -1; + }, implicitRelative, true ), + matchers = [ function( elem, context, xml ) { + var ret = ( !leadingRelative && ( xml || context !== outermostContext ) ) || ( + (checkContext = context).nodeType ? + matchContext( elem, context, xml ) : + matchAnyContext( elem, context, xml ) ); + // Avoid hanging onto element (issue #299) + checkContext = null; + return ret; + } ]; + + for ( ; i < len; i++ ) { + if ( (matcher = Expr.relative[ tokens[i].type ]) ) { + matchers = [ addCombinator(elementMatcher( matchers ), matcher) ]; + } else { + matcher = Expr.filter[ tokens[i].type ].apply( null, tokens[i].matches ); + + // Return special upon seeing a positional matcher + if ( matcher[ expando ] ) { + // Find the next relative operator (if any) for proper handling + j = ++i; + for ( ; j < len; j++ ) { + if ( Expr.relative[ tokens[j].type ] ) { + break; + } + } + return setMatcher( + i > 1 && elementMatcher( matchers ), + i > 1 && toSelector( + // If the preceding token was a descendant combinator, insert an implicit any-element `*` + tokens.slice( 0, i - 1 ).concat({ value: tokens[ i - 2 ].type === " " ? "*" : "" }) + ).replace( rtrim, "$1" ), + matcher, + i < j && matcherFromTokens( tokens.slice( i, j ) ), + j < len && matcherFromTokens( (tokens = tokens.slice( j )) ), + j < len && toSelector( tokens ) + ); + } + matchers.push( matcher ); + } + } + + return elementMatcher( matchers ); +} + +function matcherFromGroupMatchers( elementMatchers, setMatchers ) { + var bySet = setMatchers.length > 0, + byElement = elementMatchers.length > 0, + superMatcher = function( seed, context, xml, results, outermost ) { + var elem, j, matcher, + matchedCount = 0, + i = "0", + unmatched = seed && [], + setMatched = [], + contextBackup = outermostContext, + // We must always have either seed elements or outermost context + elems = seed || byElement && Expr.find["TAG"]( "*", outermost ), + // Use integer dirruns iff this is the outermost matcher + dirrunsUnique = (dirruns += contextBackup == null ? 1 : Math.random() || 0.1), + len = elems.length; + + if ( outermost ) { + outermostContext = context === document || context || outermost; + } + + // Add elements passing elementMatchers directly to results + // Support: IE<9, Safari + // Tolerate NodeList properties (IE: "length"; Safari: ) matching elements by id + for ( ; i !== len && (elem = elems[i]) != null; i++ ) { + if ( byElement && elem ) { + j = 0; + if ( !context && elem.ownerDocument !== document ) { + setDocument( elem ); + xml = !documentIsHTML; + } + while ( (matcher = elementMatchers[j++]) ) { + if ( matcher( elem, context || document, xml) ) { + results.push( elem ); + break; + } + } + if ( outermost ) { + dirruns = dirrunsUnique; + } + } + + // Track unmatched elements for set filters + if ( bySet ) { + // They will have gone through all possible matchers + if ( (elem = !matcher && elem) ) { + matchedCount--; + } + + // Lengthen the array for every element, matched or not + if ( seed ) { + unmatched.push( elem ); + } + } + } + + // `i` is now the count of elements visited above, and adding it to `matchedCount` + // makes the latter nonnegative. + matchedCount += i; + + // Apply set filters to unmatched elements + // NOTE: This can be skipped if there are no unmatched elements (i.e., `matchedCount` + // equals `i`), unless we didn't visit _any_ elements in the above loop because we have + // no element matchers and no seed. + // Incrementing an initially-string "0" `i` allows `i` to remain a string only in that + // case, which will result in a "00" `matchedCount` that differs from `i` but is also + // numerically zero. + if ( bySet && i !== matchedCount ) { + j = 0; + while ( (matcher = setMatchers[j++]) ) { + matcher( unmatched, setMatched, context, xml ); + } + + if ( seed ) { + // Reintegrate element matches to eliminate the need for sorting + if ( matchedCount > 0 ) { + while ( i-- ) { + if ( !(unmatched[i] || setMatched[i]) ) { + setMatched[i] = pop.call( results ); + } + } + } + + // Discard index placeholder values to get only actual matches + setMatched = condense( setMatched ); + } + + // Add matches to results + push.apply( results, setMatched ); + + // Seedless set matches succeeding multiple successful matchers stipulate sorting + if ( outermost && !seed && setMatched.length > 0 && + ( matchedCount + setMatchers.length ) > 1 ) { + + Sizzle.uniqueSort( results ); + } + } + + // Override manipulation of globals by nested matchers + if ( outermost ) { + dirruns = dirrunsUnique; + outermostContext = contextBackup; + } + + return unmatched; + }; + + return bySet ? + markFunction( superMatcher ) : + superMatcher; +} + +compile = Sizzle.compile = function( selector, match /* Internal Use Only */ ) { + var i, + setMatchers = [], + elementMatchers = [], + cached = compilerCache[ selector + " " ]; + + if ( !cached ) { + // Generate a function of recursive functions that can be used to check each element + if ( !match ) { + match = tokenize( selector ); + } + i = match.length; + while ( i-- ) { + cached = matcherFromTokens( match[i] ); + if ( cached[ expando ] ) { + setMatchers.push( cached ); + } else { + elementMatchers.push( cached ); + } + } + + // Cache the compiled function + cached = compilerCache( selector, matcherFromGroupMatchers( elementMatchers, setMatchers ) ); + + // Save selector and tokenization + cached.selector = selector; + } + return cached; +}; + +/** + * A low-level selection function that works with Sizzle's compiled + * selector functions + * @param {String|Function} selector A selector or a pre-compiled + * selector function built with Sizzle.compile + * @param {Element} context + * @param {Array} [results] + * @param {Array} [seed] A set of elements to match against + */ +select = Sizzle.select = function( selector, context, results, seed ) { + var i, tokens, token, type, find, + compiled = typeof selector === "function" && selector, + match = !seed && tokenize( (selector = compiled.selector || selector) ); + + results = results || []; + + // Try to minimize operations if there is only one selector in the list and no seed + // (the latter of which guarantees us context) + if ( match.length === 1 ) { + + // Reduce context if the leading compound selector is an ID + tokens = match[0] = match[0].slice( 0 ); + if ( tokens.length > 2 && (token = tokens[0]).type === "ID" && + context.nodeType === 9 && documentIsHTML && Expr.relative[ tokens[1].type ] ) { + + context = ( Expr.find["ID"]( token.matches[0].replace(runescape, funescape), context ) || [] )[0]; + if ( !context ) { + return results; + + // Precompiled matchers will still verify ancestry, so step up a level + } else if ( compiled ) { + context = context.parentNode; + } + + selector = selector.slice( tokens.shift().value.length ); + } + + // Fetch a seed set for right-to-left matching + i = matchExpr["needsContext"].test( selector ) ? 0 : tokens.length; + while ( i-- ) { + token = tokens[i]; + + // Abort if we hit a combinator + if ( Expr.relative[ (type = token.type) ] ) { + break; + } + if ( (find = Expr.find[ type ]) ) { + // Search, expanding context for leading sibling combinators + if ( (seed = find( + token.matches[0].replace( runescape, funescape ), + rsibling.test( tokens[0].type ) && testContext( context.parentNode ) || context + )) ) { + + // If seed is empty or no tokens remain, we can return early + tokens.splice( i, 1 ); + selector = seed.length && toSelector( tokens ); + if ( !selector ) { + push.apply( results, seed ); + return results; + } + + break; + } + } + } + } + + // Compile and execute a filtering function if one is not provided + // Provide `match` to avoid retokenization if we modified the selector above + ( compiled || compile( selector, match ) )( + seed, + context, + !documentIsHTML, + results, + !context || rsibling.test( selector ) && testContext( context.parentNode ) || context + ); + return results; +}; + +// One-time assignments + +// Sort stability +support.sortStable = expando.split("").sort( sortOrder ).join("") === expando; + +// Support: Chrome 14-35+ +// Always assume duplicates if they aren't passed to the comparison function +support.detectDuplicates = !!hasDuplicate; + +// Initialize against the default document +setDocument(); + +// Support: Webkit<537.32 - Safari 6.0.3/Chrome 25 (fixed in Chrome 27) +// Detached nodes confoundingly follow *each other* +support.sortDetached = assert(function( el ) { + // Should return 1, but returns 4 (following) + return el.compareDocumentPosition( document.createElement("fieldset") ) & 1; +}); + +// Support: IE<8 +// Prevent attribute/property "interpolation" +// https://msdn.microsoft.com/en-us/library/ms536429%28VS.85%29.aspx +if ( !assert(function( el ) { + el.innerHTML = ""; + return el.firstChild.getAttribute("href") === "#" ; +}) ) { + addHandle( "type|href|height|width", function( elem, name, isXML ) { + if ( !isXML ) { + return elem.getAttribute( name, name.toLowerCase() === "type" ? 1 : 2 ); + } + }); +} + +// Support: IE<9 +// Use defaultValue in place of getAttribute("value") +if ( !support.attributes || !assert(function( el ) { + el.innerHTML = ""; + el.firstChild.setAttribute( "value", "" ); + return el.firstChild.getAttribute( "value" ) === ""; +}) ) { + addHandle( "value", function( elem, name, isXML ) { + if ( !isXML && elem.nodeName.toLowerCase() === "input" ) { + return elem.defaultValue; + } + }); +} + +// Support: IE<9 +// Use getAttributeNode to fetch booleans when getAttribute lies +if ( !assert(function( el ) { + return el.getAttribute("disabled") == null; +}) ) { + addHandle( booleans, function( elem, name, isXML ) { + var val; + if ( !isXML ) { + return elem[ name ] === true ? name.toLowerCase() : + (val = elem.getAttributeNode( name )) && val.specified ? + val.value : + null; + } + }); +} + +return Sizzle; + +})( window ); + + + +jQuery.find = Sizzle; +jQuery.expr = Sizzle.selectors; + +// Deprecated +jQuery.expr[ ":" ] = jQuery.expr.pseudos; +jQuery.uniqueSort = jQuery.unique = Sizzle.uniqueSort; +jQuery.text = Sizzle.getText; +jQuery.isXMLDoc = Sizzle.isXML; +jQuery.contains = Sizzle.contains; +jQuery.escapeSelector = Sizzle.escape; + + + + +var dir = function( elem, dir, until ) { + var matched = [], + truncate = until !== undefined; + + while ( ( elem = elem[ dir ] ) && elem.nodeType !== 9 ) { + if ( elem.nodeType === 1 ) { + if ( truncate && jQuery( elem ).is( until ) ) { + break; + } + matched.push( elem ); + } + } + return matched; +}; + + +var siblings = function( n, elem ) { + var matched = []; + + for ( ; n; n = n.nextSibling ) { + if ( n.nodeType === 1 && n !== elem ) { + matched.push( n ); + } + } + + return matched; +}; + + +var rneedsContext = jQuery.expr.match.needsContext; + + + +function nodeName( elem, name ) { + + return elem.nodeName && elem.nodeName.toLowerCase() === name.toLowerCase(); + +}; +var rsingleTag = ( /^<([a-z][^\/\0>:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i ); + + + +var risSimple = /^.[^:#\[\.,]*$/; + +// Implement the identical functionality for filter and not +function winnow( elements, qualifier, not ) { + if ( jQuery.isFunction( qualifier ) ) { + return jQuery.grep( elements, function( elem, i ) { + return !!qualifier.call( elem, i, elem ) !== not; + } ); + } + + // Single element + if ( qualifier.nodeType ) { + return jQuery.grep( elements, function( elem ) { + return ( elem === qualifier ) !== not; + } ); + } + + // Arraylike of elements (jQuery, arguments, Array) + if ( typeof qualifier !== "string" ) { + return jQuery.grep( elements, function( elem ) { + return ( indexOf.call( qualifier, elem ) > -1 ) !== not; + } ); + } + + // Simple selector that can be filtered directly, removing non-Elements + if ( risSimple.test( qualifier ) ) { + return jQuery.filter( qualifier, elements, not ); + } + + // Complex selector, compare the two sets, removing non-Elements + qualifier = jQuery.filter( qualifier, elements ); + return jQuery.grep( elements, function( elem ) { + return ( indexOf.call( qualifier, elem ) > -1 ) !== not && elem.nodeType === 1; + } ); +} + +jQuery.filter = function( expr, elems, not ) { + var elem = elems[ 0 ]; + + if ( not ) { + expr = ":not(" + expr + ")"; + } + + if ( elems.length === 1 && elem.nodeType === 1 ) { + return jQuery.find.matchesSelector( elem, expr ) ? [ elem ] : []; + } + + return jQuery.find.matches( expr, jQuery.grep( elems, function( elem ) { + return elem.nodeType === 1; + } ) ); +}; + +jQuery.fn.extend( { + find: function( selector ) { + var i, ret, + len = this.length, + self = this; + + if ( typeof selector !== "string" ) { + return this.pushStack( jQuery( selector ).filter( function() { + for ( i = 0; i < len; i++ ) { + if ( jQuery.contains( self[ i ], this ) ) { + return true; + } + } + } ) ); + } + + ret = this.pushStack( [] ); + + for ( i = 0; i < len; i++ ) { + jQuery.find( selector, self[ i ], ret ); + } + + return len > 1 ? jQuery.uniqueSort( ret ) : ret; + }, + filter: function( selector ) { + return this.pushStack( winnow( this, selector || [], false ) ); + }, + not: function( selector ) { + return this.pushStack( winnow( this, selector || [], true ) ); + }, + is: function( selector ) { + return !!winnow( + this, + + // If this is a positional/relative selector, check membership in the returned set + // so $("p:first").is("p:last") won't return true for a doc with two "p". + typeof selector === "string" && rneedsContext.test( selector ) ? + jQuery( selector ) : + selector || [], + false + ).length; + } +} ); + + +// Initialize a jQuery object + + +// A central reference to the root jQuery(document) +var rootjQuery, + + // A simple way to check for HTML strings + // Prioritize #id over to avoid XSS via location.hash (#9521) + // Strict HTML recognition (#11290: must start with <) + // Shortcut simple #id case for speed + rquickExpr = /^(?:\s*(<[\w\W]+>)[^>]*|#([\w-]+))$/, + + init = jQuery.fn.init = function( selector, context, root ) { + var match, elem; + + // HANDLE: $(""), $(null), $(undefined), $(false) + if ( !selector ) { + return this; + } + + // Method init() accepts an alternate rootjQuery + // so migrate can support jQuery.sub (gh-2101) + root = root || rootjQuery; + + // Handle HTML strings + if ( typeof selector === "string" ) { + if ( selector[ 0 ] === "<" && + selector[ selector.length - 1 ] === ">" && + selector.length >= 3 ) { + + // Assume that strings that start and end with <> are HTML and skip the regex check + match = [ null, selector, null ]; + + } else { + match = rquickExpr.exec( selector ); + } + + // Match html or make sure no context is specified for #id + if ( match && ( match[ 1 ] || !context ) ) { + + // HANDLE: $(html) -> $(array) + if ( match[ 1 ] ) { + context = context instanceof jQuery ? context[ 0 ] : context; + + // Option to run scripts is true for back-compat + // Intentionally let the error be thrown if parseHTML is not present + jQuery.merge( this, jQuery.parseHTML( + match[ 1 ], + context && context.nodeType ? context.ownerDocument || context : document, + true + ) ); + + // HANDLE: $(html, props) + if ( rsingleTag.test( match[ 1 ] ) && jQuery.isPlainObject( context ) ) { + for ( match in context ) { + + // Properties of context are called as methods if possible + if ( jQuery.isFunction( this[ match ] ) ) { + this[ match ]( context[ match ] ); + + // ...and otherwise set as attributes + } else { + this.attr( match, context[ match ] ); + } + } + } + + return this; + + // HANDLE: $(#id) + } else { + elem = document.getElementById( match[ 2 ] ); + + if ( elem ) { + + // Inject the element directly into the jQuery object + this[ 0 ] = elem; + this.length = 1; + } + return this; + } + + // HANDLE: $(expr, $(...)) + } else if ( !context || context.jquery ) { + return ( context || root ).find( selector ); + + // HANDLE: $(expr, context) + // (which is just equivalent to: $(context).find(expr) + } else { + return this.constructor( context ).find( selector ); + } + + // HANDLE: $(DOMElement) + } else if ( selector.nodeType ) { + this[ 0 ] = selector; + this.length = 1; + return this; + + // HANDLE: $(function) + // Shortcut for document ready + } else if ( jQuery.isFunction( selector ) ) { + return root.ready !== undefined ? + root.ready( selector ) : + + // Execute immediately if ready is not present + selector( jQuery ); + } + + return jQuery.makeArray( selector, this ); + }; + +// Give the init function the jQuery prototype for later instantiation +init.prototype = jQuery.fn; + +// Initialize central reference +rootjQuery = jQuery( document ); + + +var rparentsprev = /^(?:parents|prev(?:Until|All))/, + + // Methods guaranteed to produce a unique set when starting from a unique set + guaranteedUnique = { + children: true, + contents: true, + next: true, + prev: true + }; + +jQuery.fn.extend( { + has: function( target ) { + var targets = jQuery( target, this ), + l = targets.length; + + return this.filter( function() { + var i = 0; + for ( ; i < l; i++ ) { + if ( jQuery.contains( this, targets[ i ] ) ) { + return true; + } + } + } ); + }, + + closest: function( selectors, context ) { + var cur, + i = 0, + l = this.length, + matched = [], + targets = typeof selectors !== "string" && jQuery( selectors ); + + // Positional selectors never match, since there's no _selection_ context + if ( !rneedsContext.test( selectors ) ) { + for ( ; i < l; i++ ) { + for ( cur = this[ i ]; cur && cur !== context; cur = cur.parentNode ) { + + // Always skip document fragments + if ( cur.nodeType < 11 && ( targets ? + targets.index( cur ) > -1 : + + // Don't pass non-elements to Sizzle + cur.nodeType === 1 && + jQuery.find.matchesSelector( cur, selectors ) ) ) { + + matched.push( cur ); + break; + } + } + } + } + + return this.pushStack( matched.length > 1 ? jQuery.uniqueSort( matched ) : matched ); + }, + + // Determine the position of an element within the set + index: function( elem ) { + + // No argument, return index in parent + if ( !elem ) { + return ( this[ 0 ] && this[ 0 ].parentNode ) ? this.first().prevAll().length : -1; + } + + // Index in selector + if ( typeof elem === "string" ) { + return indexOf.call( jQuery( elem ), this[ 0 ] ); + } + + // Locate the position of the desired element + return indexOf.call( this, + + // If it receives a jQuery object, the first element is used + elem.jquery ? elem[ 0 ] : elem + ); + }, + + add: function( selector, context ) { + return this.pushStack( + jQuery.uniqueSort( + jQuery.merge( this.get(), jQuery( selector, context ) ) + ) + ); + }, + + addBack: function( selector ) { + return this.add( selector == null ? + this.prevObject : this.prevObject.filter( selector ) + ); + } +} ); + +function sibling( cur, dir ) { + while ( ( cur = cur[ dir ] ) && cur.nodeType !== 1 ) {} + return cur; +} + +jQuery.each( { + parent: function( elem ) { + var parent = elem.parentNode; + return parent && parent.nodeType !== 11 ? parent : null; + }, + parents: function( elem ) { + return dir( elem, "parentNode" ); + }, + parentsUntil: function( elem, i, until ) { + return dir( elem, "parentNode", until ); + }, + next: function( elem ) { + return sibling( elem, "nextSibling" ); + }, + prev: function( elem ) { + return sibling( elem, "previousSibling" ); + }, + nextAll: function( elem ) { + return dir( elem, "nextSibling" ); + }, + prevAll: function( elem ) { + return dir( elem, "previousSibling" ); + }, + nextUntil: function( elem, i, until ) { + return dir( elem, "nextSibling", until ); + }, + prevUntil: function( elem, i, until ) { + return dir( elem, "previousSibling", until ); + }, + siblings: function( elem ) { + return siblings( ( elem.parentNode || {} ).firstChild, elem ); + }, + children: function( elem ) { + return siblings( elem.firstChild ); + }, + contents: function( elem ) { + if ( nodeName( elem, "iframe" ) ) { + return elem.contentDocument; + } + + // Support: IE 9 - 11 only, iOS 7 only, Android Browser <=4.3 only + // Treat the template element as a regular one in browsers that + // don't support it. + if ( nodeName( elem, "template" ) ) { + elem = elem.content || elem; + } + + return jQuery.merge( [], elem.childNodes ); + } +}, function( name, fn ) { + jQuery.fn[ name ] = function( until, selector ) { + var matched = jQuery.map( this, fn, until ); + + if ( name.slice( -5 ) !== "Until" ) { + selector = until; + } + + if ( selector && typeof selector === "string" ) { + matched = jQuery.filter( selector, matched ); + } + + if ( this.length > 1 ) { + + // Remove duplicates + if ( !guaranteedUnique[ name ] ) { + jQuery.uniqueSort( matched ); + } + + // Reverse order for parents* and prev-derivatives + if ( rparentsprev.test( name ) ) { + matched.reverse(); + } + } + + return this.pushStack( matched ); + }; +} ); +var rnothtmlwhite = ( /[^\x20\t\r\n\f]+/g ); + + + +// Convert String-formatted options into Object-formatted ones +function createOptions( options ) { + var object = {}; + jQuery.each( options.match( rnothtmlwhite ) || [], function( _, flag ) { + object[ flag ] = true; + } ); + return object; +} + +/* + * Create a callback list using the following parameters: + * + * options: an optional list of space-separated options that will change how + * the callback list behaves or a more traditional option object + * + * By default a callback list will act like an event callback list and can be + * "fired" multiple times. + * + * Possible options: + * + * once: will ensure the callback list can only be fired once (like a Deferred) + * + * memory: will keep track of previous values and will call any callback added + * after the list has been fired right away with the latest "memorized" + * values (like a Deferred) + * + * unique: will ensure a callback can only be added once (no duplicate in the list) + * + * stopOnFalse: interrupt callings when a callback returns false + * + */ +jQuery.Callbacks = function( options ) { + + // Convert options from String-formatted to Object-formatted if needed + // (we check in cache first) + options = typeof options === "string" ? + createOptions( options ) : + jQuery.extend( {}, options ); + + var // Flag to know if list is currently firing + firing, + + // Last fire value for non-forgettable lists + memory, + + // Flag to know if list was already fired + fired, + + // Flag to prevent firing + locked, + + // Actual callback list + list = [], + + // Queue of execution data for repeatable lists + queue = [], + + // Index of currently firing callback (modified by add/remove as needed) + firingIndex = -1, + + // Fire callbacks + fire = function() { + + // Enforce single-firing + locked = locked || options.once; + + // Execute callbacks for all pending executions, + // respecting firingIndex overrides and runtime changes + fired = firing = true; + for ( ; queue.length; firingIndex = -1 ) { + memory = queue.shift(); + while ( ++firingIndex < list.length ) { + + // Run callback and check for early termination + if ( list[ firingIndex ].apply( memory[ 0 ], memory[ 1 ] ) === false && + options.stopOnFalse ) { + + // Jump to end and forget the data so .add doesn't re-fire + firingIndex = list.length; + memory = false; + } + } + } + + // Forget the data if we're done with it + if ( !options.memory ) { + memory = false; + } + + firing = false; + + // Clean up if we're done firing for good + if ( locked ) { + + // Keep an empty list if we have data for future add calls + if ( memory ) { + list = []; + + // Otherwise, this object is spent + } else { + list = ""; + } + } + }, + + // Actual Callbacks object + self = { + + // Add a callback or a collection of callbacks to the list + add: function() { + if ( list ) { + + // If we have memory from a past run, we should fire after adding + if ( memory && !firing ) { + firingIndex = list.length - 1; + queue.push( memory ); + } + + ( function add( args ) { + jQuery.each( args, function( _, arg ) { + if ( jQuery.isFunction( arg ) ) { + if ( !options.unique || !self.has( arg ) ) { + list.push( arg ); + } + } else if ( arg && arg.length && jQuery.type( arg ) !== "string" ) { + + // Inspect recursively + add( arg ); + } + } ); + } )( arguments ); + + if ( memory && !firing ) { + fire(); + } + } + return this; + }, + + // Remove a callback from the list + remove: function() { + jQuery.each( arguments, function( _, arg ) { + var index; + while ( ( index = jQuery.inArray( arg, list, index ) ) > -1 ) { + list.splice( index, 1 ); + + // Handle firing indexes + if ( index <= firingIndex ) { + firingIndex--; + } + } + } ); + return this; + }, + + // Check if a given callback is in the list. + // If no argument is given, return whether or not list has callbacks attached. + has: function( fn ) { + return fn ? + jQuery.inArray( fn, list ) > -1 : + list.length > 0; + }, + + // Remove all callbacks from the list + empty: function() { + if ( list ) { + list = []; + } + return this; + }, + + // Disable .fire and .add + // Abort any current/pending executions + // Clear all callbacks and values + disable: function() { + locked = queue = []; + list = memory = ""; + return this; + }, + disabled: function() { + return !list; + }, + + // Disable .fire + // Also disable .add unless we have memory (since it would have no effect) + // Abort any pending executions + lock: function() { + locked = queue = []; + if ( !memory && !firing ) { + list = memory = ""; + } + return this; + }, + locked: function() { + return !!locked; + }, + + // Call all callbacks with the given context and arguments + fireWith: function( context, args ) { + if ( !locked ) { + args = args || []; + args = [ context, args.slice ? args.slice() : args ]; + queue.push( args ); + if ( !firing ) { + fire(); + } + } + return this; + }, + + // Call all the callbacks with the given arguments + fire: function() { + self.fireWith( this, arguments ); + return this; + }, + + // To know if the callbacks have already been called at least once + fired: function() { + return !!fired; + } + }; + + return self; +}; + + +function Identity( v ) { + return v; +} +function Thrower( ex ) { + throw ex; +} + +function adoptValue( value, resolve, reject, noValue ) { + var method; + + try { + + // Check for promise aspect first to privilege synchronous behavior + if ( value && jQuery.isFunction( ( method = value.promise ) ) ) { + method.call( value ).done( resolve ).fail( reject ); + + // Other thenables + } else if ( value && jQuery.isFunction( ( method = value.then ) ) ) { + method.call( value, resolve, reject ); + + // Other non-thenables + } else { + + // Control `resolve` arguments by letting Array#slice cast boolean `noValue` to integer: + // * false: [ value ].slice( 0 ) => resolve( value ) + // * true: [ value ].slice( 1 ) => resolve() + resolve.apply( undefined, [ value ].slice( noValue ) ); + } + + // For Promises/A+, convert exceptions into rejections + // Since jQuery.when doesn't unwrap thenables, we can skip the extra checks appearing in + // Deferred#then to conditionally suppress rejection. + } catch ( value ) { + + // Support: Android 4.0 only + // Strict mode functions invoked without .call/.apply get global-object context + reject.apply( undefined, [ value ] ); + } +} + +jQuery.extend( { + + Deferred: function( func ) { + var tuples = [ + + // action, add listener, callbacks, + // ... .then handlers, argument index, [final state] + [ "notify", "progress", jQuery.Callbacks( "memory" ), + jQuery.Callbacks( "memory" ), 2 ], + [ "resolve", "done", jQuery.Callbacks( "once memory" ), + jQuery.Callbacks( "once memory" ), 0, "resolved" ], + [ "reject", "fail", jQuery.Callbacks( "once memory" ), + jQuery.Callbacks( "once memory" ), 1, "rejected" ] + ], + state = "pending", + promise = { + state: function() { + return state; + }, + always: function() { + deferred.done( arguments ).fail( arguments ); + return this; + }, + "catch": function( fn ) { + return promise.then( null, fn ); + }, + + // Keep pipe for back-compat + pipe: function( /* fnDone, fnFail, fnProgress */ ) { + var fns = arguments; + + return jQuery.Deferred( function( newDefer ) { + jQuery.each( tuples, function( i, tuple ) { + + // Map tuples (progress, done, fail) to arguments (done, fail, progress) + var fn = jQuery.isFunction( fns[ tuple[ 4 ] ] ) && fns[ tuple[ 4 ] ]; + + // deferred.progress(function() { bind to newDefer or newDefer.notify }) + // deferred.done(function() { bind to newDefer or newDefer.resolve }) + // deferred.fail(function() { bind to newDefer or newDefer.reject }) + deferred[ tuple[ 1 ] ]( function() { + var returned = fn && fn.apply( this, arguments ); + if ( returned && jQuery.isFunction( returned.promise ) ) { + returned.promise() + .progress( newDefer.notify ) + .done( newDefer.resolve ) + .fail( newDefer.reject ); + } else { + newDefer[ tuple[ 0 ] + "With" ]( + this, + fn ? [ returned ] : arguments + ); + } + } ); + } ); + fns = null; + } ).promise(); + }, + then: function( onFulfilled, onRejected, onProgress ) { + var maxDepth = 0; + function resolve( depth, deferred, handler, special ) { + return function() { + var that = this, + args = arguments, + mightThrow = function() { + var returned, then; + + // Support: Promises/A+ section 2.3.3.3.3 + // https://promisesaplus.com/#point-59 + // Ignore double-resolution attempts + if ( depth < maxDepth ) { + return; + } + + returned = handler.apply( that, args ); + + // Support: Promises/A+ section 2.3.1 + // https://promisesaplus.com/#point-48 + if ( returned === deferred.promise() ) { + throw new TypeError( "Thenable self-resolution" ); + } + + // Support: Promises/A+ sections 2.3.3.1, 3.5 + // https://promisesaplus.com/#point-54 + // https://promisesaplus.com/#point-75 + // Retrieve `then` only once + then = returned && + + // Support: Promises/A+ section 2.3.4 + // https://promisesaplus.com/#point-64 + // Only check objects and functions for thenability + ( typeof returned === "object" || + typeof returned === "function" ) && + returned.then; + + // Handle a returned thenable + if ( jQuery.isFunction( then ) ) { + + // Special processors (notify) just wait for resolution + if ( special ) { + then.call( + returned, + resolve( maxDepth, deferred, Identity, special ), + resolve( maxDepth, deferred, Thrower, special ) + ); + + // Normal processors (resolve) also hook into progress + } else { + + // ...and disregard older resolution values + maxDepth++; + + then.call( + returned, + resolve( maxDepth, deferred, Identity, special ), + resolve( maxDepth, deferred, Thrower, special ), + resolve( maxDepth, deferred, Identity, + deferred.notifyWith ) + ); + } + + // Handle all other returned values + } else { + + // Only substitute handlers pass on context + // and multiple values (non-spec behavior) + if ( handler !== Identity ) { + that = undefined; + args = [ returned ]; + } + + // Process the value(s) + // Default process is resolve + ( special || deferred.resolveWith )( that, args ); + } + }, + + // Only normal processors (resolve) catch and reject exceptions + process = special ? + mightThrow : + function() { + try { + mightThrow(); + } catch ( e ) { + + if ( jQuery.Deferred.exceptionHook ) { + jQuery.Deferred.exceptionHook( e, + process.stackTrace ); + } + + // Support: Promises/A+ section 2.3.3.3.4.1 + // https://promisesaplus.com/#point-61 + // Ignore post-resolution exceptions + if ( depth + 1 >= maxDepth ) { + + // Only substitute handlers pass on context + // and multiple values (non-spec behavior) + if ( handler !== Thrower ) { + that = undefined; + args = [ e ]; + } + + deferred.rejectWith( that, args ); + } + } + }; + + // Support: Promises/A+ section 2.3.3.3.1 + // https://promisesaplus.com/#point-57 + // Re-resolve promises immediately to dodge false rejection from + // subsequent errors + if ( depth ) { + process(); + } else { + + // Call an optional hook to record the stack, in case of exception + // since it's otherwise lost when execution goes async + if ( jQuery.Deferred.getStackHook ) { + process.stackTrace = jQuery.Deferred.getStackHook(); + } + window.setTimeout( process ); + } + }; + } + + return jQuery.Deferred( function( newDefer ) { + + // progress_handlers.add( ... ) + tuples[ 0 ][ 3 ].add( + resolve( + 0, + newDefer, + jQuery.isFunction( onProgress ) ? + onProgress : + Identity, + newDefer.notifyWith + ) + ); + + // fulfilled_handlers.add( ... ) + tuples[ 1 ][ 3 ].add( + resolve( + 0, + newDefer, + jQuery.isFunction( onFulfilled ) ? + onFulfilled : + Identity + ) + ); + + // rejected_handlers.add( ... ) + tuples[ 2 ][ 3 ].add( + resolve( + 0, + newDefer, + jQuery.isFunction( onRejected ) ? + onRejected : + Thrower + ) + ); + } ).promise(); + }, + + // Get a promise for this deferred + // If obj is provided, the promise aspect is added to the object + promise: function( obj ) { + return obj != null ? jQuery.extend( obj, promise ) : promise; + } + }, + deferred = {}; + + // Add list-specific methods + jQuery.each( tuples, function( i, tuple ) { + var list = tuple[ 2 ], + stateString = tuple[ 5 ]; + + // promise.progress = list.add + // promise.done = list.add + // promise.fail = list.add + promise[ tuple[ 1 ] ] = list.add; + + // Handle state + if ( stateString ) { + list.add( + function() { + + // state = "resolved" (i.e., fulfilled) + // state = "rejected" + state = stateString; + }, + + // rejected_callbacks.disable + // fulfilled_callbacks.disable + tuples[ 3 - i ][ 2 ].disable, + + // progress_callbacks.lock + tuples[ 0 ][ 2 ].lock + ); + } + + // progress_handlers.fire + // fulfilled_handlers.fire + // rejected_handlers.fire + list.add( tuple[ 3 ].fire ); + + // deferred.notify = function() { deferred.notifyWith(...) } + // deferred.resolve = function() { deferred.resolveWith(...) } + // deferred.reject = function() { deferred.rejectWith(...) } + deferred[ tuple[ 0 ] ] = function() { + deferred[ tuple[ 0 ] + "With" ]( this === deferred ? undefined : this, arguments ); + return this; + }; + + // deferred.notifyWith = list.fireWith + // deferred.resolveWith = list.fireWith + // deferred.rejectWith = list.fireWith + deferred[ tuple[ 0 ] + "With" ] = list.fireWith; + } ); + + // Make the deferred a promise + promise.promise( deferred ); + + // Call given func if any + if ( func ) { + func.call( deferred, deferred ); + } + + // All done! + return deferred; + }, + + // Deferred helper + when: function( singleValue ) { + var + + // count of uncompleted subordinates + remaining = arguments.length, + + // count of unprocessed arguments + i = remaining, + + // subordinate fulfillment data + resolveContexts = Array( i ), + resolveValues = slice.call( arguments ), + + // the master Deferred + master = jQuery.Deferred(), + + // subordinate callback factory + updateFunc = function( i ) { + return function( value ) { + resolveContexts[ i ] = this; + resolveValues[ i ] = arguments.length > 1 ? slice.call( arguments ) : value; + if ( !( --remaining ) ) { + master.resolveWith( resolveContexts, resolveValues ); + } + }; + }; + + // Single- and empty arguments are adopted like Promise.resolve + if ( remaining <= 1 ) { + adoptValue( singleValue, master.done( updateFunc( i ) ).resolve, master.reject, + !remaining ); + + // Use .then() to unwrap secondary thenables (cf. gh-3000) + if ( master.state() === "pending" || + jQuery.isFunction( resolveValues[ i ] && resolveValues[ i ].then ) ) { + + return master.then(); + } + } + + // Multiple arguments are aggregated like Promise.all array elements + while ( i-- ) { + adoptValue( resolveValues[ i ], updateFunc( i ), master.reject ); + } + + return master.promise(); + } +} ); + + +// These usually indicate a programmer mistake during development, +// warn about them ASAP rather than swallowing them by default. +var rerrorNames = /^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/; + +jQuery.Deferred.exceptionHook = function( error, stack ) { + + // Support: IE 8 - 9 only + // Console exists when dev tools are open, which can happen at any time + if ( window.console && window.console.warn && error && rerrorNames.test( error.name ) ) { + window.console.warn( "jQuery.Deferred exception: " + error.message, error.stack, stack ); + } +}; + + + + +jQuery.readyException = function( error ) { + window.setTimeout( function() { + throw error; + } ); +}; + + + + +// The deferred used on DOM ready +var readyList = jQuery.Deferred(); + +jQuery.fn.ready = function( fn ) { + + readyList + .then( fn ) + + // Wrap jQuery.readyException in a function so that the lookup + // happens at the time of error handling instead of callback + // registration. + .catch( function( error ) { + jQuery.readyException( error ); + } ); + + return this; +}; + +jQuery.extend( { + + // Is the DOM ready to be used? Set to true once it occurs. + isReady: false, + + // A counter to track how many items to wait for before + // the ready event fires. See #6781 + readyWait: 1, + + // Handle when the DOM is ready + ready: function( wait ) { + + // Abort if there are pending holds or we're already ready + if ( wait === true ? --jQuery.readyWait : jQuery.isReady ) { + return; + } + + // Remember that the DOM is ready + jQuery.isReady = true; + + // If a normal DOM Ready event fired, decrement, and wait if need be + if ( wait !== true && --jQuery.readyWait > 0 ) { + return; + } + + // If there are functions bound, to execute + readyList.resolveWith( document, [ jQuery ] ); + } +} ); + +jQuery.ready.then = readyList.then; + +// The ready event handler and self cleanup method +function completed() { + document.removeEventListener( "DOMContentLoaded", completed ); + window.removeEventListener( "load", completed ); + jQuery.ready(); +} + +// Catch cases where $(document).ready() is called +// after the browser event has already occurred. +// Support: IE <=9 - 10 only +// Older IE sometimes signals "interactive" too soon +if ( document.readyState === "complete" || + ( document.readyState !== "loading" && !document.documentElement.doScroll ) ) { + + // Handle it asynchronously to allow scripts the opportunity to delay ready + window.setTimeout( jQuery.ready ); + +} else { + + // Use the handy event callback + document.addEventListener( "DOMContentLoaded", completed ); + + // A fallback to window.onload, that will always work + window.addEventListener( "load", completed ); +} + + + + +// Multifunctional method to get and set values of a collection +// The value/s can optionally be executed if it's a function +var access = function( elems, fn, key, value, chainable, emptyGet, raw ) { + var i = 0, + len = elems.length, + bulk = key == null; + + // Sets many values + if ( jQuery.type( key ) === "object" ) { + chainable = true; + for ( i in key ) { + access( elems, fn, i, key[ i ], true, emptyGet, raw ); + } + + // Sets one value + } else if ( value !== undefined ) { + chainable = true; + + if ( !jQuery.isFunction( value ) ) { + raw = true; + } + + if ( bulk ) { + + // Bulk operations run against the entire set + if ( raw ) { + fn.call( elems, value ); + fn = null; + + // ...except when executing function values + } else { + bulk = fn; + fn = function( elem, key, value ) { + return bulk.call( jQuery( elem ), value ); + }; + } + } + + if ( fn ) { + for ( ; i < len; i++ ) { + fn( + elems[ i ], key, raw ? + value : + value.call( elems[ i ], i, fn( elems[ i ], key ) ) + ); + } + } + } + + if ( chainable ) { + return elems; + } + + // Gets + if ( bulk ) { + return fn.call( elems ); + } + + return len ? fn( elems[ 0 ], key ) : emptyGet; +}; +var acceptData = function( owner ) { + + // Accepts only: + // - Node + // - Node.ELEMENT_NODE + // - Node.DOCUMENT_NODE + // - Object + // - Any + return owner.nodeType === 1 || owner.nodeType === 9 || !( +owner.nodeType ); +}; + + + + +function Data() { + this.expando = jQuery.expando + Data.uid++; +} + +Data.uid = 1; + +Data.prototype = { + + cache: function( owner ) { + + // Check if the owner object already has a cache + var value = owner[ this.expando ]; + + // If not, create one + if ( !value ) { + value = {}; + + // We can accept data for non-element nodes in modern browsers, + // but we should not, see #8335. + // Always return an empty object. + if ( acceptData( owner ) ) { + + // If it is a node unlikely to be stringify-ed or looped over + // use plain assignment + if ( owner.nodeType ) { + owner[ this.expando ] = value; + + // Otherwise secure it in a non-enumerable property + // configurable must be true to allow the property to be + // deleted when data is removed + } else { + Object.defineProperty( owner, this.expando, { + value: value, + configurable: true + } ); + } + } + } + + return value; + }, + set: function( owner, data, value ) { + var prop, + cache = this.cache( owner ); + + // Handle: [ owner, key, value ] args + // Always use camelCase key (gh-2257) + if ( typeof data === "string" ) { + cache[ jQuery.camelCase( data ) ] = value; + + // Handle: [ owner, { properties } ] args + } else { + + // Copy the properties one-by-one to the cache object + for ( prop in data ) { + cache[ jQuery.camelCase( prop ) ] = data[ prop ]; + } + } + return cache; + }, + get: function( owner, key ) { + return key === undefined ? + this.cache( owner ) : + + // Always use camelCase key (gh-2257) + owner[ this.expando ] && owner[ this.expando ][ jQuery.camelCase( key ) ]; + }, + access: function( owner, key, value ) { + + // In cases where either: + // + // 1. No key was specified + // 2. A string key was specified, but no value provided + // + // Take the "read" path and allow the get method to determine + // which value to return, respectively either: + // + // 1. The entire cache object + // 2. The data stored at the key + // + if ( key === undefined || + ( ( key && typeof key === "string" ) && value === undefined ) ) { + + return this.get( owner, key ); + } + + // When the key is not a string, or both a key and value + // are specified, set or extend (existing objects) with either: + // + // 1. An object of properties + // 2. A key and value + // + this.set( owner, key, value ); + + // Since the "set" path can have two possible entry points + // return the expected data based on which path was taken[*] + return value !== undefined ? value : key; + }, + remove: function( owner, key ) { + var i, + cache = owner[ this.expando ]; + + if ( cache === undefined ) { + return; + } + + if ( key !== undefined ) { + + // Support array or space separated string of keys + if ( Array.isArray( key ) ) { + + // If key is an array of keys... + // We always set camelCase keys, so remove that. + key = key.map( jQuery.camelCase ); + } else { + key = jQuery.camelCase( key ); + + // If a key with the spaces exists, use it. + // Otherwise, create an array by matching non-whitespace + key = key in cache ? + [ key ] : + ( key.match( rnothtmlwhite ) || [] ); + } + + i = key.length; + + while ( i-- ) { + delete cache[ key[ i ] ]; + } + } + + // Remove the expando if there's no more data + if ( key === undefined || jQuery.isEmptyObject( cache ) ) { + + // Support: Chrome <=35 - 45 + // Webkit & Blink performance suffers when deleting properties + // from DOM nodes, so set to undefined instead + // https://bugs.chromium.org/p/chromium/issues/detail?id=378607 (bug restricted) + if ( owner.nodeType ) { + owner[ this.expando ] = undefined; + } else { + delete owner[ this.expando ]; + } + } + }, + hasData: function( owner ) { + var cache = owner[ this.expando ]; + return cache !== undefined && !jQuery.isEmptyObject( cache ); + } +}; +var dataPriv = new Data(); + +var dataUser = new Data(); + + + +// Implementation Summary +// +// 1. Enforce API surface and semantic compatibility with 1.9.x branch +// 2. Improve the module's maintainability by reducing the storage +// paths to a single mechanism. +// 3. Use the same single mechanism to support "private" and "user" data. +// 4. _Never_ expose "private" data to user code (TODO: Drop _data, _removeData) +// 5. Avoid exposing implementation details on user objects (eg. expando properties) +// 6. Provide a clear path for implementation upgrade to WeakMap in 2014 + +var rbrace = /^(?:\{[\w\W]*\}|\[[\w\W]*\])$/, + rmultiDash = /[A-Z]/g; + +function getData( data ) { + if ( data === "true" ) { + return true; + } + + if ( data === "false" ) { + return false; + } + + if ( data === "null" ) { + return null; + } + + // Only convert to a number if it doesn't change the string + if ( data === +data + "" ) { + return +data; + } + + if ( rbrace.test( data ) ) { + return JSON.parse( data ); + } + + return data; +} + +function dataAttr( elem, key, data ) { + var name; + + // If nothing was found internally, try to fetch any + // data from the HTML5 data-* attribute + if ( data === undefined && elem.nodeType === 1 ) { + name = "data-" + key.replace( rmultiDash, "-$&" ).toLowerCase(); + data = elem.getAttribute( name ); + + if ( typeof data === "string" ) { + try { + data = getData( data ); + } catch ( e ) {} + + // Make sure we set the data so it isn't changed later + dataUser.set( elem, key, data ); + } else { + data = undefined; + } + } + return data; +} + +jQuery.extend( { + hasData: function( elem ) { + return dataUser.hasData( elem ) || dataPriv.hasData( elem ); + }, + + data: function( elem, name, data ) { + return dataUser.access( elem, name, data ); + }, + + removeData: function( elem, name ) { + dataUser.remove( elem, name ); + }, + + // TODO: Now that all calls to _data and _removeData have been replaced + // with direct calls to dataPriv methods, these can be deprecated. + _data: function( elem, name, data ) { + return dataPriv.access( elem, name, data ); + }, + + _removeData: function( elem, name ) { + dataPriv.remove( elem, name ); + } +} ); + +jQuery.fn.extend( { + data: function( key, value ) { + var i, name, data, + elem = this[ 0 ], + attrs = elem && elem.attributes; + + // Gets all values + if ( key === undefined ) { + if ( this.length ) { + data = dataUser.get( elem ); + + if ( elem.nodeType === 1 && !dataPriv.get( elem, "hasDataAttrs" ) ) { + i = attrs.length; + while ( i-- ) { + + // Support: IE 11 only + // The attrs elements can be null (#14894) + if ( attrs[ i ] ) { + name = attrs[ i ].name; + if ( name.indexOf( "data-" ) === 0 ) { + name = jQuery.camelCase( name.slice( 5 ) ); + dataAttr( elem, name, data[ name ] ); + } + } + } + dataPriv.set( elem, "hasDataAttrs", true ); + } + } + + return data; + } + + // Sets multiple values + if ( typeof key === "object" ) { + return this.each( function() { + dataUser.set( this, key ); + } ); + } + + return access( this, function( value ) { + var data; + + // The calling jQuery object (element matches) is not empty + // (and therefore has an element appears at this[ 0 ]) and the + // `value` parameter was not undefined. An empty jQuery object + // will result in `undefined` for elem = this[ 0 ] which will + // throw an exception if an attempt to read a data cache is made. + if ( elem && value === undefined ) { + + // Attempt to get data from the cache + // The key will always be camelCased in Data + data = dataUser.get( elem, key ); + if ( data !== undefined ) { + return data; + } + + // Attempt to "discover" the data in + // HTML5 custom data-* attrs + data = dataAttr( elem, key ); + if ( data !== undefined ) { + return data; + } + + // We tried really hard, but the data doesn't exist. + return; + } + + // Set the data... + this.each( function() { + + // We always store the camelCased key + dataUser.set( this, key, value ); + } ); + }, null, value, arguments.length > 1, null, true ); + }, + + removeData: function( key ) { + return this.each( function() { + dataUser.remove( this, key ); + } ); + } +} ); + + +jQuery.extend( { + queue: function( elem, type, data ) { + var queue; + + if ( elem ) { + type = ( type || "fx" ) + "queue"; + queue = dataPriv.get( elem, type ); + + // Speed up dequeue by getting out quickly if this is just a lookup + if ( data ) { + if ( !queue || Array.isArray( data ) ) { + queue = dataPriv.access( elem, type, jQuery.makeArray( data ) ); + } else { + queue.push( data ); + } + } + return queue || []; + } + }, + + dequeue: function( elem, type ) { + type = type || "fx"; + + var queue = jQuery.queue( elem, type ), + startLength = queue.length, + fn = queue.shift(), + hooks = jQuery._queueHooks( elem, type ), + next = function() { + jQuery.dequeue( elem, type ); + }; + + // If the fx queue is dequeued, always remove the progress sentinel + if ( fn === "inprogress" ) { + fn = queue.shift(); + startLength--; + } + + if ( fn ) { + + // Add a progress sentinel to prevent the fx queue from being + // automatically dequeued + if ( type === "fx" ) { + queue.unshift( "inprogress" ); + } + + // Clear up the last queue stop function + delete hooks.stop; + fn.call( elem, next, hooks ); + } + + if ( !startLength && hooks ) { + hooks.empty.fire(); + } + }, + + // Not public - generate a queueHooks object, or return the current one + _queueHooks: function( elem, type ) { + var key = type + "queueHooks"; + return dataPriv.get( elem, key ) || dataPriv.access( elem, key, { + empty: jQuery.Callbacks( "once memory" ).add( function() { + dataPriv.remove( elem, [ type + "queue", key ] ); + } ) + } ); + } +} ); + +jQuery.fn.extend( { + queue: function( type, data ) { + var setter = 2; + + if ( typeof type !== "string" ) { + data = type; + type = "fx"; + setter--; + } + + if ( arguments.length < setter ) { + return jQuery.queue( this[ 0 ], type ); + } + + return data === undefined ? + this : + this.each( function() { + var queue = jQuery.queue( this, type, data ); + + // Ensure a hooks for this queue + jQuery._queueHooks( this, type ); + + if ( type === "fx" && queue[ 0 ] !== "inprogress" ) { + jQuery.dequeue( this, type ); + } + } ); + }, + dequeue: function( type ) { + return this.each( function() { + jQuery.dequeue( this, type ); + } ); + }, + clearQueue: function( type ) { + return this.queue( type || "fx", [] ); + }, + + // Get a promise resolved when queues of a certain type + // are emptied (fx is the type by default) + promise: function( type, obj ) { + var tmp, + count = 1, + defer = jQuery.Deferred(), + elements = this, + i = this.length, + resolve = function() { + if ( !( --count ) ) { + defer.resolveWith( elements, [ elements ] ); + } + }; + + if ( typeof type !== "string" ) { + obj = type; + type = undefined; + } + type = type || "fx"; + + while ( i-- ) { + tmp = dataPriv.get( elements[ i ], type + "queueHooks" ); + if ( tmp && tmp.empty ) { + count++; + tmp.empty.add( resolve ); + } + } + resolve(); + return defer.promise( obj ); + } +} ); +var pnum = ( /[+-]?(?:\d*\.|)\d+(?:[eE][+-]?\d+|)/ ).source; + +var rcssNum = new RegExp( "^(?:([+-])=|)(" + pnum + ")([a-z%]*)$", "i" ); + + +var cssExpand = [ "Top", "Right", "Bottom", "Left" ]; + +var isHiddenWithinTree = function( elem, el ) { + + // isHiddenWithinTree might be called from jQuery#filter function; + // in that case, element will be second argument + elem = el || elem; + + // Inline style trumps all + return elem.style.display === "none" || + elem.style.display === "" && + + // Otherwise, check computed style + // Support: Firefox <=43 - 45 + // Disconnected elements can have computed display: none, so first confirm that elem is + // in the document. + jQuery.contains( elem.ownerDocument, elem ) && + + jQuery.css( elem, "display" ) === "none"; + }; + +var swap = function( elem, options, callback, args ) { + var ret, name, + old = {}; + + // Remember the old values, and insert the new ones + for ( name in options ) { + old[ name ] = elem.style[ name ]; + elem.style[ name ] = options[ name ]; + } + + ret = callback.apply( elem, args || [] ); + + // Revert the old values + for ( name in options ) { + elem.style[ name ] = old[ name ]; + } + + return ret; +}; + + + + +function adjustCSS( elem, prop, valueParts, tween ) { + var adjusted, + scale = 1, + maxIterations = 20, + currentValue = tween ? + function() { + return tween.cur(); + } : + function() { + return jQuery.css( elem, prop, "" ); + }, + initial = currentValue(), + unit = valueParts && valueParts[ 3 ] || ( jQuery.cssNumber[ prop ] ? "" : "px" ), + + // Starting value computation is required for potential unit mismatches + initialInUnit = ( jQuery.cssNumber[ prop ] || unit !== "px" && +initial ) && + rcssNum.exec( jQuery.css( elem, prop ) ); + + if ( initialInUnit && initialInUnit[ 3 ] !== unit ) { + + // Trust units reported by jQuery.css + unit = unit || initialInUnit[ 3 ]; + + // Make sure we update the tween properties later on + valueParts = valueParts || []; + + // Iteratively approximate from a nonzero starting point + initialInUnit = +initial || 1; + + do { + + // If previous iteration zeroed out, double until we get *something*. + // Use string for doubling so we don't accidentally see scale as unchanged below + scale = scale || ".5"; + + // Adjust and apply + initialInUnit = initialInUnit / scale; + jQuery.style( elem, prop, initialInUnit + unit ); + + // Update scale, tolerating zero or NaN from tween.cur() + // Break the loop if scale is unchanged or perfect, or if we've just had enough. + } while ( + scale !== ( scale = currentValue() / initial ) && scale !== 1 && --maxIterations + ); + } + + if ( valueParts ) { + initialInUnit = +initialInUnit || +initial || 0; + + // Apply relative offset (+=/-=) if specified + adjusted = valueParts[ 1 ] ? + initialInUnit + ( valueParts[ 1 ] + 1 ) * valueParts[ 2 ] : + +valueParts[ 2 ]; + if ( tween ) { + tween.unit = unit; + tween.start = initialInUnit; + tween.end = adjusted; + } + } + return adjusted; +} + + +var defaultDisplayMap = {}; + +function getDefaultDisplay( elem ) { + var temp, + doc = elem.ownerDocument, + nodeName = elem.nodeName, + display = defaultDisplayMap[ nodeName ]; + + if ( display ) { + return display; + } + + temp = doc.body.appendChild( doc.createElement( nodeName ) ); + display = jQuery.css( temp, "display" ); + + temp.parentNode.removeChild( temp ); + + if ( display === "none" ) { + display = "block"; + } + defaultDisplayMap[ nodeName ] = display; + + return display; +} + +function showHide( elements, show ) { + var display, elem, + values = [], + index = 0, + length = elements.length; + + // Determine new display value for elements that need to change + for ( ; index < length; index++ ) { + elem = elements[ index ]; + if ( !elem.style ) { + continue; + } + + display = elem.style.display; + if ( show ) { + + // Since we force visibility upon cascade-hidden elements, an immediate (and slow) + // check is required in this first loop unless we have a nonempty display value (either + // inline or about-to-be-restored) + if ( display === "none" ) { + values[ index ] = dataPriv.get( elem, "display" ) || null; + if ( !values[ index ] ) { + elem.style.display = ""; + } + } + if ( elem.style.display === "" && isHiddenWithinTree( elem ) ) { + values[ index ] = getDefaultDisplay( elem ); + } + } else { + if ( display !== "none" ) { + values[ index ] = "none"; + + // Remember what we're overwriting + dataPriv.set( elem, "display", display ); + } + } + } + + // Set the display of the elements in a second loop to avoid constant reflow + for ( index = 0; index < length; index++ ) { + if ( values[ index ] != null ) { + elements[ index ].style.display = values[ index ]; + } + } + + return elements; +} + +jQuery.fn.extend( { + show: function() { + return showHide( this, true ); + }, + hide: function() { + return showHide( this ); + }, + toggle: function( state ) { + if ( typeof state === "boolean" ) { + return state ? this.show() : this.hide(); + } + + return this.each( function() { + if ( isHiddenWithinTree( this ) ) { + jQuery( this ).show(); + } else { + jQuery( this ).hide(); + } + } ); + } +} ); +var rcheckableType = ( /^(?:checkbox|radio)$/i ); + +var rtagName = ( /<([a-z][^\/\0>\x20\t\r\n\f]+)/i ); + +var rscriptType = ( /^$|\/(?:java|ecma)script/i ); + + + +// We have to close these tags to support XHTML (#13200) +var wrapMap = { + + // Support: IE <=9 only + option: [ 1, "" ], + + // XHTML parsers do not magically insert elements in the + // same way that tag soup parsers do. So we cannot shorten + // this by omitting or other required elements. + thead: [ 1, "", "
" ], + col: [ 2, "", "
" ], + tr: [ 2, "", "
" ], + td: [ 3, "", "
" ], + + _default: [ 0, "", "" ] +}; + +// Support: IE <=9 only +wrapMap.optgroup = wrapMap.option; + +wrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead; +wrapMap.th = wrapMap.td; + + +function getAll( context, tag ) { + + // Support: IE <=9 - 11 only + // Use typeof to avoid zero-argument method invocation on host objects (#15151) + var ret; + + if ( typeof context.getElementsByTagName !== "undefined" ) { + ret = context.getElementsByTagName( tag || "*" ); + + } else if ( typeof context.querySelectorAll !== "undefined" ) { + ret = context.querySelectorAll( tag || "*" ); + + } else { + ret = []; + } + + if ( tag === undefined || tag && nodeName( context, tag ) ) { + return jQuery.merge( [ context ], ret ); + } + + return ret; +} + + +// Mark scripts as having already been evaluated +function setGlobalEval( elems, refElements ) { + var i = 0, + l = elems.length; + + for ( ; i < l; i++ ) { + dataPriv.set( + elems[ i ], + "globalEval", + !refElements || dataPriv.get( refElements[ i ], "globalEval" ) + ); + } +} + + +var rhtml = /<|&#?\w+;/; + +function buildFragment( elems, context, scripts, selection, ignored ) { + var elem, tmp, tag, wrap, contains, j, + fragment = context.createDocumentFragment(), + nodes = [], + i = 0, + l = elems.length; + + for ( ; i < l; i++ ) { + elem = elems[ i ]; + + if ( elem || elem === 0 ) { + + // Add nodes directly + if ( jQuery.type( elem ) === "object" ) { + + // Support: Android <=4.0 only, PhantomJS 1 only + // push.apply(_, arraylike) throws on ancient WebKit + jQuery.merge( nodes, elem.nodeType ? [ elem ] : elem ); + + // Convert non-html into a text node + } else if ( !rhtml.test( elem ) ) { + nodes.push( context.createTextNode( elem ) ); + + // Convert html into DOM nodes + } else { + tmp = tmp || fragment.appendChild( context.createElement( "div" ) ); + + // Deserialize a standard representation + tag = ( rtagName.exec( elem ) || [ "", "" ] )[ 1 ].toLowerCase(); + wrap = wrapMap[ tag ] || wrapMap._default; + tmp.innerHTML = wrap[ 1 ] + jQuery.htmlPrefilter( elem ) + wrap[ 2 ]; + + // Descend through wrappers to the right content + j = wrap[ 0 ]; + while ( j-- ) { + tmp = tmp.lastChild; + } + + // Support: Android <=4.0 only, PhantomJS 1 only + // push.apply(_, arraylike) throws on ancient WebKit + jQuery.merge( nodes, tmp.childNodes ); + + // Remember the top-level container + tmp = fragment.firstChild; + + // Ensure the created nodes are orphaned (#12392) + tmp.textContent = ""; + } + } + } + + // Remove wrapper from fragment + fragment.textContent = ""; + + i = 0; + while ( ( elem = nodes[ i++ ] ) ) { + + // Skip elements already in the context collection (trac-4087) + if ( selection && jQuery.inArray( elem, selection ) > -1 ) { + if ( ignored ) { + ignored.push( elem ); + } + continue; + } + + contains = jQuery.contains( elem.ownerDocument, elem ); + + // Append to fragment + tmp = getAll( fragment.appendChild( elem ), "script" ); + + // Preserve script evaluation history + if ( contains ) { + setGlobalEval( tmp ); + } + + // Capture executables + if ( scripts ) { + j = 0; + while ( ( elem = tmp[ j++ ] ) ) { + if ( rscriptType.test( elem.type || "" ) ) { + scripts.push( elem ); + } + } + } + } + + return fragment; +} + + +( function() { + var fragment = document.createDocumentFragment(), + div = fragment.appendChild( document.createElement( "div" ) ), + input = document.createElement( "input" ); + + // Support: Android 4.0 - 4.3 only + // Check state lost if the name is set (#11217) + // Support: Windows Web Apps (WWA) + // `name` and `type` must use .setAttribute for WWA (#14901) + input.setAttribute( "type", "radio" ); + input.setAttribute( "checked", "checked" ); + input.setAttribute( "name", "t" ); + + div.appendChild( input ); + + // Support: Android <=4.1 only + // Older WebKit doesn't clone checked state correctly in fragments + support.checkClone = div.cloneNode( true ).cloneNode( true ).lastChild.checked; + + // Support: IE <=11 only + // Make sure textarea (and checkbox) defaultValue is properly cloned + div.innerHTML = ""; + support.noCloneChecked = !!div.cloneNode( true ).lastChild.defaultValue; +} )(); +var documentElement = document.documentElement; + + + +var + rkeyEvent = /^key/, + rmouseEvent = /^(?:mouse|pointer|contextmenu|drag|drop)|click/, + rtypenamespace = /^([^.]*)(?:\.(.+)|)/; + +function returnTrue() { + return true; +} + +function returnFalse() { + return false; +} + +// Support: IE <=9 only +// See #13393 for more info +function safeActiveElement() { + try { + return document.activeElement; + } catch ( err ) { } +} + +function on( elem, types, selector, data, fn, one ) { + var origFn, type; + + // Types can be a map of types/handlers + if ( typeof types === "object" ) { + + // ( types-Object, selector, data ) + if ( typeof selector !== "string" ) { + + // ( types-Object, data ) + data = data || selector; + selector = undefined; + } + for ( type in types ) { + on( elem, type, selector, data, types[ type ], one ); + } + return elem; + } + + if ( data == null && fn == null ) { + + // ( types, fn ) + fn = selector; + data = selector = undefined; + } else if ( fn == null ) { + if ( typeof selector === "string" ) { + + // ( types, selector, fn ) + fn = data; + data = undefined; + } else { + + // ( types, data, fn ) + fn = data; + data = selector; + selector = undefined; + } + } + if ( fn === false ) { + fn = returnFalse; + } else if ( !fn ) { + return elem; + } + + if ( one === 1 ) { + origFn = fn; + fn = function( event ) { + + // Can use an empty set, since event contains the info + jQuery().off( event ); + return origFn.apply( this, arguments ); + }; + + // Use same guid so caller can remove using origFn + fn.guid = origFn.guid || ( origFn.guid = jQuery.guid++ ); + } + return elem.each( function() { + jQuery.event.add( this, types, fn, data, selector ); + } ); +} + +/* + * Helper functions for managing events -- not part of the public interface. + * Props to Dean Edwards' addEvent library for many of the ideas. + */ +jQuery.event = { + + global: {}, + + add: function( elem, types, handler, data, selector ) { + + var handleObjIn, eventHandle, tmp, + events, t, handleObj, + special, handlers, type, namespaces, origType, + elemData = dataPriv.get( elem ); + + // Don't attach events to noData or text/comment nodes (but allow plain objects) + if ( !elemData ) { + return; + } + + // Caller can pass in an object of custom data in lieu of the handler + if ( handler.handler ) { + handleObjIn = handler; + handler = handleObjIn.handler; + selector = handleObjIn.selector; + } + + // Ensure that invalid selectors throw exceptions at attach time + // Evaluate against documentElement in case elem is a non-element node (e.g., document) + if ( selector ) { + jQuery.find.matchesSelector( documentElement, selector ); + } + + // Make sure that the handler has a unique ID, used to find/remove it later + if ( !handler.guid ) { + handler.guid = jQuery.guid++; + } + + // Init the element's event structure and main handler, if this is the first + if ( !( events = elemData.events ) ) { + events = elemData.events = {}; + } + if ( !( eventHandle = elemData.handle ) ) { + eventHandle = elemData.handle = function( e ) { + + // Discard the second event of a jQuery.event.trigger() and + // when an event is called after a page has unloaded + return typeof jQuery !== "undefined" && jQuery.event.triggered !== e.type ? + jQuery.event.dispatch.apply( elem, arguments ) : undefined; + }; + } + + // Handle multiple events separated by a space + types = ( types || "" ).match( rnothtmlwhite ) || [ "" ]; + t = types.length; + while ( t-- ) { + tmp = rtypenamespace.exec( types[ t ] ) || []; + type = origType = tmp[ 1 ]; + namespaces = ( tmp[ 2 ] || "" ).split( "." ).sort(); + + // There *must* be a type, no attaching namespace-only handlers + if ( !type ) { + continue; + } + + // If event changes its type, use the special event handlers for the changed type + special = jQuery.event.special[ type ] || {}; + + // If selector defined, determine special event api type, otherwise given type + type = ( selector ? special.delegateType : special.bindType ) || type; + + // Update special based on newly reset type + special = jQuery.event.special[ type ] || {}; + + // handleObj is passed to all event handlers + handleObj = jQuery.extend( { + type: type, + origType: origType, + data: data, + handler: handler, + guid: handler.guid, + selector: selector, + needsContext: selector && jQuery.expr.match.needsContext.test( selector ), + namespace: namespaces.join( "." ) + }, handleObjIn ); + + // Init the event handler queue if we're the first + if ( !( handlers = events[ type ] ) ) { + handlers = events[ type ] = []; + handlers.delegateCount = 0; + + // Only use addEventListener if the special events handler returns false + if ( !special.setup || + special.setup.call( elem, data, namespaces, eventHandle ) === false ) { + + if ( elem.addEventListener ) { + elem.addEventListener( type, eventHandle ); + } + } + } + + if ( special.add ) { + special.add.call( elem, handleObj ); + + if ( !handleObj.handler.guid ) { + handleObj.handler.guid = handler.guid; + } + } + + // Add to the element's handler list, delegates in front + if ( selector ) { + handlers.splice( handlers.delegateCount++, 0, handleObj ); + } else { + handlers.push( handleObj ); + } + + // Keep track of which events have ever been used, for event optimization + jQuery.event.global[ type ] = true; + } + + }, + + // Detach an event or set of events from an element + remove: function( elem, types, handler, selector, mappedTypes ) { + + var j, origCount, tmp, + events, t, handleObj, + special, handlers, type, namespaces, origType, + elemData = dataPriv.hasData( elem ) && dataPriv.get( elem ); + + if ( !elemData || !( events = elemData.events ) ) { + return; + } + + // Once for each type.namespace in types; type may be omitted + types = ( types || "" ).match( rnothtmlwhite ) || [ "" ]; + t = types.length; + while ( t-- ) { + tmp = rtypenamespace.exec( types[ t ] ) || []; + type = origType = tmp[ 1 ]; + namespaces = ( tmp[ 2 ] || "" ).split( "." ).sort(); + + // Unbind all events (on this namespace, if provided) for the element + if ( !type ) { + for ( type in events ) { + jQuery.event.remove( elem, type + types[ t ], handler, selector, true ); + } + continue; + } + + special = jQuery.event.special[ type ] || {}; + type = ( selector ? special.delegateType : special.bindType ) || type; + handlers = events[ type ] || []; + tmp = tmp[ 2 ] && + new RegExp( "(^|\\.)" + namespaces.join( "\\.(?:.*\\.|)" ) + "(\\.|$)" ); + + // Remove matching events + origCount = j = handlers.length; + while ( j-- ) { + handleObj = handlers[ j ]; + + if ( ( mappedTypes || origType === handleObj.origType ) && + ( !handler || handler.guid === handleObj.guid ) && + ( !tmp || tmp.test( handleObj.namespace ) ) && + ( !selector || selector === handleObj.selector || + selector === "**" && handleObj.selector ) ) { + handlers.splice( j, 1 ); + + if ( handleObj.selector ) { + handlers.delegateCount--; + } + if ( special.remove ) { + special.remove.call( elem, handleObj ); + } + } + } + + // Remove generic event handler if we removed something and no more handlers exist + // (avoids potential for endless recursion during removal of special event handlers) + if ( origCount && !handlers.length ) { + if ( !special.teardown || + special.teardown.call( elem, namespaces, elemData.handle ) === false ) { + + jQuery.removeEvent( elem, type, elemData.handle ); + } + + delete events[ type ]; + } + } + + // Remove data and the expando if it's no longer used + if ( jQuery.isEmptyObject( events ) ) { + dataPriv.remove( elem, "handle events" ); + } + }, + + dispatch: function( nativeEvent ) { + + // Make a writable jQuery.Event from the native event object + var event = jQuery.event.fix( nativeEvent ); + + var i, j, ret, matched, handleObj, handlerQueue, + args = new Array( arguments.length ), + handlers = ( dataPriv.get( this, "events" ) || {} )[ event.type ] || [], + special = jQuery.event.special[ event.type ] || {}; + + // Use the fix-ed jQuery.Event rather than the (read-only) native event + args[ 0 ] = event; + + for ( i = 1; i < arguments.length; i++ ) { + args[ i ] = arguments[ i ]; + } + + event.delegateTarget = this; + + // Call the preDispatch hook for the mapped type, and let it bail if desired + if ( special.preDispatch && special.preDispatch.call( this, event ) === false ) { + return; + } + + // Determine handlers + handlerQueue = jQuery.event.handlers.call( this, event, handlers ); + + // Run delegates first; they may want to stop propagation beneath us + i = 0; + while ( ( matched = handlerQueue[ i++ ] ) && !event.isPropagationStopped() ) { + event.currentTarget = matched.elem; + + j = 0; + while ( ( handleObj = matched.handlers[ j++ ] ) && + !event.isImmediatePropagationStopped() ) { + + // Triggered event must either 1) have no namespace, or 2) have namespace(s) + // a subset or equal to those in the bound event (both can have no namespace). + if ( !event.rnamespace || event.rnamespace.test( handleObj.namespace ) ) { + + event.handleObj = handleObj; + event.data = handleObj.data; + + ret = ( ( jQuery.event.special[ handleObj.origType ] || {} ).handle || + handleObj.handler ).apply( matched.elem, args ); + + if ( ret !== undefined ) { + if ( ( event.result = ret ) === false ) { + event.preventDefault(); + event.stopPropagation(); + } + } + } + } + } + + // Call the postDispatch hook for the mapped type + if ( special.postDispatch ) { + special.postDispatch.call( this, event ); + } + + return event.result; + }, + + handlers: function( event, handlers ) { + var i, handleObj, sel, matchedHandlers, matchedSelectors, + handlerQueue = [], + delegateCount = handlers.delegateCount, + cur = event.target; + + // Find delegate handlers + if ( delegateCount && + + // Support: IE <=9 + // Black-hole SVG instance trees (trac-13180) + cur.nodeType && + + // Support: Firefox <=42 + // Suppress spec-violating clicks indicating a non-primary pointer button (trac-3861) + // https://www.w3.org/TR/DOM-Level-3-Events/#event-type-click + // Support: IE 11 only + // ...but not arrow key "clicks" of radio inputs, which can have `button` -1 (gh-2343) + !( event.type === "click" && event.button >= 1 ) ) { + + for ( ; cur !== this; cur = cur.parentNode || this ) { + + // Don't check non-elements (#13208) + // Don't process clicks on disabled elements (#6911, #8165, #11382, #11764) + if ( cur.nodeType === 1 && !( event.type === "click" && cur.disabled === true ) ) { + matchedHandlers = []; + matchedSelectors = {}; + for ( i = 0; i < delegateCount; i++ ) { + handleObj = handlers[ i ]; + + // Don't conflict with Object.prototype properties (#13203) + sel = handleObj.selector + " "; + + if ( matchedSelectors[ sel ] === undefined ) { + matchedSelectors[ sel ] = handleObj.needsContext ? + jQuery( sel, this ).index( cur ) > -1 : + jQuery.find( sel, this, null, [ cur ] ).length; + } + if ( matchedSelectors[ sel ] ) { + matchedHandlers.push( handleObj ); + } + } + if ( matchedHandlers.length ) { + handlerQueue.push( { elem: cur, handlers: matchedHandlers } ); + } + } + } + } + + // Add the remaining (directly-bound) handlers + cur = this; + if ( delegateCount < handlers.length ) { + handlerQueue.push( { elem: cur, handlers: handlers.slice( delegateCount ) } ); + } + + return handlerQueue; + }, + + addProp: function( name, hook ) { + Object.defineProperty( jQuery.Event.prototype, name, { + enumerable: true, + configurable: true, + + get: jQuery.isFunction( hook ) ? + function() { + if ( this.originalEvent ) { + return hook( this.originalEvent ); + } + } : + function() { + if ( this.originalEvent ) { + return this.originalEvent[ name ]; + } + }, + + set: function( value ) { + Object.defineProperty( this, name, { + enumerable: true, + configurable: true, + writable: true, + value: value + } ); + } + } ); + }, + + fix: function( originalEvent ) { + return originalEvent[ jQuery.expando ] ? + originalEvent : + new jQuery.Event( originalEvent ); + }, + + special: { + load: { + + // Prevent triggered image.load events from bubbling to window.load + noBubble: true + }, + focus: { + + // Fire native event if possible so blur/focus sequence is correct + trigger: function() { + if ( this !== safeActiveElement() && this.focus ) { + this.focus(); + return false; + } + }, + delegateType: "focusin" + }, + blur: { + trigger: function() { + if ( this === safeActiveElement() && this.blur ) { + this.blur(); + return false; + } + }, + delegateType: "focusout" + }, + click: { + + // For checkbox, fire native event so checked state will be right + trigger: function() { + if ( this.type === "checkbox" && this.click && nodeName( this, "input" ) ) { + this.click(); + return false; + } + }, + + // For cross-browser consistency, don't fire native .click() on links + _default: function( event ) { + return nodeName( event.target, "a" ); + } + }, + + beforeunload: { + postDispatch: function( event ) { + + // Support: Firefox 20+ + // Firefox doesn't alert if the returnValue field is not set. + if ( event.result !== undefined && event.originalEvent ) { + event.originalEvent.returnValue = event.result; + } + } + } + } +}; + +jQuery.removeEvent = function( elem, type, handle ) { + + // This "if" is needed for plain objects + if ( elem.removeEventListener ) { + elem.removeEventListener( type, handle ); + } +}; + +jQuery.Event = function( src, props ) { + + // Allow instantiation without the 'new' keyword + if ( !( this instanceof jQuery.Event ) ) { + return new jQuery.Event( src, props ); + } + + // Event object + if ( src && src.type ) { + this.originalEvent = src; + this.type = src.type; + + // Events bubbling up the document may have been marked as prevented + // by a handler lower down the tree; reflect the correct value. + this.isDefaultPrevented = src.defaultPrevented || + src.defaultPrevented === undefined && + + // Support: Android <=2.3 only + src.returnValue === false ? + returnTrue : + returnFalse; + + // Create target properties + // Support: Safari <=6 - 7 only + // Target should not be a text node (#504, #13143) + this.target = ( src.target && src.target.nodeType === 3 ) ? + src.target.parentNode : + src.target; + + this.currentTarget = src.currentTarget; + this.relatedTarget = src.relatedTarget; + + // Event type + } else { + this.type = src; + } + + // Put explicitly provided properties onto the event object + if ( props ) { + jQuery.extend( this, props ); + } + + // Create a timestamp if incoming event doesn't have one + this.timeStamp = src && src.timeStamp || jQuery.now(); + + // Mark it as fixed + this[ jQuery.expando ] = true; +}; + +// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding +// https://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html +jQuery.Event.prototype = { + constructor: jQuery.Event, + isDefaultPrevented: returnFalse, + isPropagationStopped: returnFalse, + isImmediatePropagationStopped: returnFalse, + isSimulated: false, + + preventDefault: function() { + var e = this.originalEvent; + + this.isDefaultPrevented = returnTrue; + + if ( e && !this.isSimulated ) { + e.preventDefault(); + } + }, + stopPropagation: function() { + var e = this.originalEvent; + + this.isPropagationStopped = returnTrue; + + if ( e && !this.isSimulated ) { + e.stopPropagation(); + } + }, + stopImmediatePropagation: function() { + var e = this.originalEvent; + + this.isImmediatePropagationStopped = returnTrue; + + if ( e && !this.isSimulated ) { + e.stopImmediatePropagation(); + } + + this.stopPropagation(); + } +}; + +// Includes all common event props including KeyEvent and MouseEvent specific props +jQuery.each( { + altKey: true, + bubbles: true, + cancelable: true, + changedTouches: true, + ctrlKey: true, + detail: true, + eventPhase: true, + metaKey: true, + pageX: true, + pageY: true, + shiftKey: true, + view: true, + "char": true, + charCode: true, + key: true, + keyCode: true, + button: true, + buttons: true, + clientX: true, + clientY: true, + offsetX: true, + offsetY: true, + pointerId: true, + pointerType: true, + screenX: true, + screenY: true, + targetTouches: true, + toElement: true, + touches: true, + + which: function( event ) { + var button = event.button; + + // Add which for key events + if ( event.which == null && rkeyEvent.test( event.type ) ) { + return event.charCode != null ? event.charCode : event.keyCode; + } + + // Add which for click: 1 === left; 2 === middle; 3 === right + if ( !event.which && button !== undefined && rmouseEvent.test( event.type ) ) { + if ( button & 1 ) { + return 1; + } + + if ( button & 2 ) { + return 3; + } + + if ( button & 4 ) { + return 2; + } + + return 0; + } + + return event.which; + } +}, jQuery.event.addProp ); + +// Create mouseenter/leave events using mouseover/out and event-time checks +// so that event delegation works in jQuery. +// Do the same for pointerenter/pointerleave and pointerover/pointerout +// +// Support: Safari 7 only +// Safari sends mouseenter too often; see: +// https://bugs.chromium.org/p/chromium/issues/detail?id=470258 +// for the description of the bug (it existed in older Chrome versions as well). +jQuery.each( { + mouseenter: "mouseover", + mouseleave: "mouseout", + pointerenter: "pointerover", + pointerleave: "pointerout" +}, function( orig, fix ) { + jQuery.event.special[ orig ] = { + delegateType: fix, + bindType: fix, + + handle: function( event ) { + var ret, + target = this, + related = event.relatedTarget, + handleObj = event.handleObj; + + // For mouseenter/leave call the handler if related is outside the target. + // NB: No relatedTarget if the mouse left/entered the browser window + if ( !related || ( related !== target && !jQuery.contains( target, related ) ) ) { + event.type = handleObj.origType; + ret = handleObj.handler.apply( this, arguments ); + event.type = fix; + } + return ret; + } + }; +} ); + +jQuery.fn.extend( { + + on: function( types, selector, data, fn ) { + return on( this, types, selector, data, fn ); + }, + one: function( types, selector, data, fn ) { + return on( this, types, selector, data, fn, 1 ); + }, + off: function( types, selector, fn ) { + var handleObj, type; + if ( types && types.preventDefault && types.handleObj ) { + + // ( event ) dispatched jQuery.Event + handleObj = types.handleObj; + jQuery( types.delegateTarget ).off( + handleObj.namespace ? + handleObj.origType + "." + handleObj.namespace : + handleObj.origType, + handleObj.selector, + handleObj.handler + ); + return this; + } + if ( typeof types === "object" ) { + + // ( types-object [, selector] ) + for ( type in types ) { + this.off( type, selector, types[ type ] ); + } + return this; + } + if ( selector === false || typeof selector === "function" ) { + + // ( types [, fn] ) + fn = selector; + selector = undefined; + } + if ( fn === false ) { + fn = returnFalse; + } + return this.each( function() { + jQuery.event.remove( this, types, fn, selector ); + } ); + } +} ); + + +var + + /* eslint-disable max-len */ + + // See https://github.com/eslint/eslint/issues/3229 + rxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([a-z][^\/\0>\x20\t\r\n\f]*)[^>]*)\/>/gi, + + /* eslint-enable */ + + // Support: IE <=10 - 11, Edge 12 - 13 + // In IE/Edge using regex groups here causes severe slowdowns. + // See https://connect.microsoft.com/IE/feedback/details/1736512/ + rnoInnerhtml = /\s*$/g; + +// Prefer a tbody over its parent table for containing new rows +function manipulationTarget( elem, content ) { + if ( nodeName( elem, "table" ) && + nodeName( content.nodeType !== 11 ? content : content.firstChild, "tr" ) ) { + + return jQuery( ">tbody", elem )[ 0 ] || elem; + } + + return elem; +} + +// Replace/restore the type attribute of script elements for safe DOM manipulation +function disableScript( elem ) { + elem.type = ( elem.getAttribute( "type" ) !== null ) + "/" + elem.type; + return elem; +} +function restoreScript( elem ) { + var match = rscriptTypeMasked.exec( elem.type ); + + if ( match ) { + elem.type = match[ 1 ]; + } else { + elem.removeAttribute( "type" ); + } + + return elem; +} + +function cloneCopyEvent( src, dest ) { + var i, l, type, pdataOld, pdataCur, udataOld, udataCur, events; + + if ( dest.nodeType !== 1 ) { + return; + } + + // 1. Copy private data: events, handlers, etc. + if ( dataPriv.hasData( src ) ) { + pdataOld = dataPriv.access( src ); + pdataCur = dataPriv.set( dest, pdataOld ); + events = pdataOld.events; + + if ( events ) { + delete pdataCur.handle; + pdataCur.events = {}; + + for ( type in events ) { + for ( i = 0, l = events[ type ].length; i < l; i++ ) { + jQuery.event.add( dest, type, events[ type ][ i ] ); + } + } + } + } + + // 2. Copy user data + if ( dataUser.hasData( src ) ) { + udataOld = dataUser.access( src ); + udataCur = jQuery.extend( {}, udataOld ); + + dataUser.set( dest, udataCur ); + } +} + +// Fix IE bugs, see support tests +function fixInput( src, dest ) { + var nodeName = dest.nodeName.toLowerCase(); + + // Fails to persist the checked state of a cloned checkbox or radio button. + if ( nodeName === "input" && rcheckableType.test( src.type ) ) { + dest.checked = src.checked; + + // Fails to return the selected option to the default selected state when cloning options + } else if ( nodeName === "input" || nodeName === "textarea" ) { + dest.defaultValue = src.defaultValue; + } +} + +function domManip( collection, args, callback, ignored ) { + + // Flatten any nested arrays + args = concat.apply( [], args ); + + var fragment, first, scripts, hasScripts, node, doc, + i = 0, + l = collection.length, + iNoClone = l - 1, + value = args[ 0 ], + isFunction = jQuery.isFunction( value ); + + // We can't cloneNode fragments that contain checked, in WebKit + if ( isFunction || + ( l > 1 && typeof value === "string" && + !support.checkClone && rchecked.test( value ) ) ) { + return collection.each( function( index ) { + var self = collection.eq( index ); + if ( isFunction ) { + args[ 0 ] = value.call( this, index, self.html() ); + } + domManip( self, args, callback, ignored ); + } ); + } + + if ( l ) { + fragment = buildFragment( args, collection[ 0 ].ownerDocument, false, collection, ignored ); + first = fragment.firstChild; + + if ( fragment.childNodes.length === 1 ) { + fragment = first; + } + + // Require either new content or an interest in ignored elements to invoke the callback + if ( first || ignored ) { + scripts = jQuery.map( getAll( fragment, "script" ), disableScript ); + hasScripts = scripts.length; + + // Use the original fragment for the last item + // instead of the first because it can end up + // being emptied incorrectly in certain situations (#8070). + for ( ; i < l; i++ ) { + node = fragment; + + if ( i !== iNoClone ) { + node = jQuery.clone( node, true, true ); + + // Keep references to cloned scripts for later restoration + if ( hasScripts ) { + + // Support: Android <=4.0 only, PhantomJS 1 only + // push.apply(_, arraylike) throws on ancient WebKit + jQuery.merge( scripts, getAll( node, "script" ) ); + } + } + + callback.call( collection[ i ], node, i ); + } + + if ( hasScripts ) { + doc = scripts[ scripts.length - 1 ].ownerDocument; + + // Reenable scripts + jQuery.map( scripts, restoreScript ); + + // Evaluate executable scripts on first document insertion + for ( i = 0; i < hasScripts; i++ ) { + node = scripts[ i ]; + if ( rscriptType.test( node.type || "" ) && + !dataPriv.access( node, "globalEval" ) && + jQuery.contains( doc, node ) ) { + + if ( node.src ) { + + // Optional AJAX dependency, but won't run scripts if not present + if ( jQuery._evalUrl ) { + jQuery._evalUrl( node.src ); + } + } else { + DOMEval( node.textContent.replace( rcleanScript, "" ), doc ); + } + } + } + } + } + } + + return collection; +} + +function remove( elem, selector, keepData ) { + var node, + nodes = selector ? jQuery.filter( selector, elem ) : elem, + i = 0; + + for ( ; ( node = nodes[ i ] ) != null; i++ ) { + if ( !keepData && node.nodeType === 1 ) { + jQuery.cleanData( getAll( node ) ); + } + + if ( node.parentNode ) { + if ( keepData && jQuery.contains( node.ownerDocument, node ) ) { + setGlobalEval( getAll( node, "script" ) ); + } + node.parentNode.removeChild( node ); + } + } + + return elem; +} + +jQuery.extend( { + htmlPrefilter: function( html ) { + return html.replace( rxhtmlTag, "<$1>" ); + }, + + clone: function( elem, dataAndEvents, deepDataAndEvents ) { + var i, l, srcElements, destElements, + clone = elem.cloneNode( true ), + inPage = jQuery.contains( elem.ownerDocument, elem ); + + // Fix IE cloning issues + if ( !support.noCloneChecked && ( elem.nodeType === 1 || elem.nodeType === 11 ) && + !jQuery.isXMLDoc( elem ) ) { + + // We eschew Sizzle here for performance reasons: https://jsperf.com/getall-vs-sizzle/2 + destElements = getAll( clone ); + srcElements = getAll( elem ); + + for ( i = 0, l = srcElements.length; i < l; i++ ) { + fixInput( srcElements[ i ], destElements[ i ] ); + } + } + + // Copy the events from the original to the clone + if ( dataAndEvents ) { + if ( deepDataAndEvents ) { + srcElements = srcElements || getAll( elem ); + destElements = destElements || getAll( clone ); + + for ( i = 0, l = srcElements.length; i < l; i++ ) { + cloneCopyEvent( srcElements[ i ], destElements[ i ] ); + } + } else { + cloneCopyEvent( elem, clone ); + } + } + + // Preserve script evaluation history + destElements = getAll( clone, "script" ); + if ( destElements.length > 0 ) { + setGlobalEval( destElements, !inPage && getAll( elem, "script" ) ); + } + + // Return the cloned set + return clone; + }, + + cleanData: function( elems ) { + var data, elem, type, + special = jQuery.event.special, + i = 0; + + for ( ; ( elem = elems[ i ] ) !== undefined; i++ ) { + if ( acceptData( elem ) ) { + if ( ( data = elem[ dataPriv.expando ] ) ) { + if ( data.events ) { + for ( type in data.events ) { + if ( special[ type ] ) { + jQuery.event.remove( elem, type ); + + // This is a shortcut to avoid jQuery.event.remove's overhead + } else { + jQuery.removeEvent( elem, type, data.handle ); + } + } + } + + // Support: Chrome <=35 - 45+ + // Assign undefined instead of using delete, see Data#remove + elem[ dataPriv.expando ] = undefined; + } + if ( elem[ dataUser.expando ] ) { + + // Support: Chrome <=35 - 45+ + // Assign undefined instead of using delete, see Data#remove + elem[ dataUser.expando ] = undefined; + } + } + } + } +} ); + +jQuery.fn.extend( { + detach: function( selector ) { + return remove( this, selector, true ); + }, + + remove: function( selector ) { + return remove( this, selector ); + }, + + text: function( value ) { + return access( this, function( value ) { + return value === undefined ? + jQuery.text( this ) : + this.empty().each( function() { + if ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) { + this.textContent = value; + } + } ); + }, null, value, arguments.length ); + }, + + append: function() { + return domManip( this, arguments, function( elem ) { + if ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) { + var target = manipulationTarget( this, elem ); + target.appendChild( elem ); + } + } ); + }, + + prepend: function() { + return domManip( this, arguments, function( elem ) { + if ( this.nodeType === 1 || this.nodeType === 11 || this.nodeType === 9 ) { + var target = manipulationTarget( this, elem ); + target.insertBefore( elem, target.firstChild ); + } + } ); + }, + + before: function() { + return domManip( this, arguments, function( elem ) { + if ( this.parentNode ) { + this.parentNode.insertBefore( elem, this ); + } + } ); + }, + + after: function() { + return domManip( this, arguments, function( elem ) { + if ( this.parentNode ) { + this.parentNode.insertBefore( elem, this.nextSibling ); + } + } ); + }, + + empty: function() { + var elem, + i = 0; + + for ( ; ( elem = this[ i ] ) != null; i++ ) { + if ( elem.nodeType === 1 ) { + + // Prevent memory leaks + jQuery.cleanData( getAll( elem, false ) ); + + // Remove any remaining nodes + elem.textContent = ""; + } + } + + return this; + }, + + clone: function( dataAndEvents, deepDataAndEvents ) { + dataAndEvents = dataAndEvents == null ? false : dataAndEvents; + deepDataAndEvents = deepDataAndEvents == null ? dataAndEvents : deepDataAndEvents; + + return this.map( function() { + return jQuery.clone( this, dataAndEvents, deepDataAndEvents ); + } ); + }, + + html: function( value ) { + return access( this, function( value ) { + var elem = this[ 0 ] || {}, + i = 0, + l = this.length; + + if ( value === undefined && elem.nodeType === 1 ) { + return elem.innerHTML; + } + + // See if we can take a shortcut and just use innerHTML + if ( typeof value === "string" && !rnoInnerhtml.test( value ) && + !wrapMap[ ( rtagName.exec( value ) || [ "", "" ] )[ 1 ].toLowerCase() ] ) { + + value = jQuery.htmlPrefilter( value ); + + try { + for ( ; i < l; i++ ) { + elem = this[ i ] || {}; + + // Remove element nodes and prevent memory leaks + if ( elem.nodeType === 1 ) { + jQuery.cleanData( getAll( elem, false ) ); + elem.innerHTML = value; + } + } + + elem = 0; + + // If using innerHTML throws an exception, use the fallback method + } catch ( e ) {} + } + + if ( elem ) { + this.empty().append( value ); + } + }, null, value, arguments.length ); + }, + + replaceWith: function() { + var ignored = []; + + // Make the changes, replacing each non-ignored context element with the new content + return domManip( this, arguments, function( elem ) { + var parent = this.parentNode; + + if ( jQuery.inArray( this, ignored ) < 0 ) { + jQuery.cleanData( getAll( this ) ); + if ( parent ) { + parent.replaceChild( elem, this ); + } + } + + // Force callback invocation + }, ignored ); + } +} ); + +jQuery.each( { + appendTo: "append", + prependTo: "prepend", + insertBefore: "before", + insertAfter: "after", + replaceAll: "replaceWith" +}, function( name, original ) { + jQuery.fn[ name ] = function( selector ) { + var elems, + ret = [], + insert = jQuery( selector ), + last = insert.length - 1, + i = 0; + + for ( ; i <= last; i++ ) { + elems = i === last ? this : this.clone( true ); + jQuery( insert[ i ] )[ original ]( elems ); + + // Support: Android <=4.0 only, PhantomJS 1 only + // .get() because push.apply(_, arraylike) throws on ancient WebKit + push.apply( ret, elems.get() ); + } + + return this.pushStack( ret ); + }; +} ); +var rmargin = ( /^margin/ ); + +var rnumnonpx = new RegExp( "^(" + pnum + ")(?!px)[a-z%]+$", "i" ); + +var getStyles = function( elem ) { + + // Support: IE <=11 only, Firefox <=30 (#15098, #14150) + // IE throws on elements created in popups + // FF meanwhile throws on frame elements through "defaultView.getComputedStyle" + var view = elem.ownerDocument.defaultView; + + if ( !view || !view.opener ) { + view = window; + } + + return view.getComputedStyle( elem ); + }; + + + +( function() { + + // Executing both pixelPosition & boxSizingReliable tests require only one layout + // so they're executed at the same time to save the second computation. + function computeStyleTests() { + + // This is a singleton, we need to execute it only once + if ( !div ) { + return; + } + + div.style.cssText = + "box-sizing:border-box;" + + "position:relative;display:block;" + + "margin:auto;border:1px;padding:1px;" + + "top:1%;width:50%"; + div.innerHTML = ""; + documentElement.appendChild( container ); + + var divStyle = window.getComputedStyle( div ); + pixelPositionVal = divStyle.top !== "1%"; + + // Support: Android 4.0 - 4.3 only, Firefox <=3 - 44 + reliableMarginLeftVal = divStyle.marginLeft === "2px"; + boxSizingReliableVal = divStyle.width === "4px"; + + // Support: Android 4.0 - 4.3 only + // Some styles come back with percentage values, even though they shouldn't + div.style.marginRight = "50%"; + pixelMarginRightVal = divStyle.marginRight === "4px"; + + documentElement.removeChild( container ); + + // Nullify the div so it wouldn't be stored in the memory and + // it will also be a sign that checks already performed + div = null; + } + + var pixelPositionVal, boxSizingReliableVal, pixelMarginRightVal, reliableMarginLeftVal, + container = document.createElement( "div" ), + div = document.createElement( "div" ); + + // Finish early in limited (non-browser) environments + if ( !div.style ) { + return; + } + + // Support: IE <=9 - 11 only + // Style of cloned element affects source element cloned (#8908) + div.style.backgroundClip = "content-box"; + div.cloneNode( true ).style.backgroundClip = ""; + support.clearCloneStyle = div.style.backgroundClip === "content-box"; + + container.style.cssText = "border:0;width:8px;height:0;top:0;left:-9999px;" + + "padding:0;margin-top:1px;position:absolute"; + container.appendChild( div ); + + jQuery.extend( support, { + pixelPosition: function() { + computeStyleTests(); + return pixelPositionVal; + }, + boxSizingReliable: function() { + computeStyleTests(); + return boxSizingReliableVal; + }, + pixelMarginRight: function() { + computeStyleTests(); + return pixelMarginRightVal; + }, + reliableMarginLeft: function() { + computeStyleTests(); + return reliableMarginLeftVal; + } + } ); +} )(); + + +function curCSS( elem, name, computed ) { + var width, minWidth, maxWidth, ret, + + // Support: Firefox 51+ + // Retrieving style before computed somehow + // fixes an issue with getting wrong values + // on detached elements + style = elem.style; + + computed = computed || getStyles( elem ); + + // getPropertyValue is needed for: + // .css('filter') (IE 9 only, #12537) + // .css('--customProperty) (#3144) + if ( computed ) { + ret = computed.getPropertyValue( name ) || computed[ name ]; + + if ( ret === "" && !jQuery.contains( elem.ownerDocument, elem ) ) { + ret = jQuery.style( elem, name ); + } + + // A tribute to the "awesome hack by Dean Edwards" + // Android Browser returns percentage for some values, + // but width seems to be reliably pixels. + // This is against the CSSOM draft spec: + // https://drafts.csswg.org/cssom/#resolved-values + if ( !support.pixelMarginRight() && rnumnonpx.test( ret ) && rmargin.test( name ) ) { + + // Remember the original values + width = style.width; + minWidth = style.minWidth; + maxWidth = style.maxWidth; + + // Put in the new values to get a computed value out + style.minWidth = style.maxWidth = style.width = ret; + ret = computed.width; + + // Revert the changed values + style.width = width; + style.minWidth = minWidth; + style.maxWidth = maxWidth; + } + } + + return ret !== undefined ? + + // Support: IE <=9 - 11 only + // IE returns zIndex value as an integer. + ret + "" : + ret; +} + + +function addGetHookIf( conditionFn, hookFn ) { + + // Define the hook, we'll check on the first run if it's really needed. + return { + get: function() { + if ( conditionFn() ) { + + // Hook not needed (or it's not possible to use it due + // to missing dependency), remove it. + delete this.get; + return; + } + + // Hook needed; redefine it so that the support test is not executed again. + return ( this.get = hookFn ).apply( this, arguments ); + } + }; +} + + +var + + // Swappable if display is none or starts with table + // except "table", "table-cell", or "table-caption" + // See here for display values: https://developer.mozilla.org/en-US/docs/CSS/display + rdisplayswap = /^(none|table(?!-c[ea]).+)/, + rcustomProp = /^--/, + cssShow = { position: "absolute", visibility: "hidden", display: "block" }, + cssNormalTransform = { + letterSpacing: "0", + fontWeight: "400" + }, + + cssPrefixes = [ "Webkit", "Moz", "ms" ], + emptyStyle = document.createElement( "div" ).style; + +// Return a css property mapped to a potentially vendor prefixed property +function vendorPropName( name ) { + + // Shortcut for names that are not vendor prefixed + if ( name in emptyStyle ) { + return name; + } + + // Check for vendor prefixed names + var capName = name[ 0 ].toUpperCase() + name.slice( 1 ), + i = cssPrefixes.length; + + while ( i-- ) { + name = cssPrefixes[ i ] + capName; + if ( name in emptyStyle ) { + return name; + } + } +} + +// Return a property mapped along what jQuery.cssProps suggests or to +// a vendor prefixed property. +function finalPropName( name ) { + var ret = jQuery.cssProps[ name ]; + if ( !ret ) { + ret = jQuery.cssProps[ name ] = vendorPropName( name ) || name; + } + return ret; +} + +function setPositiveNumber( elem, value, subtract ) { + + // Any relative (+/-) values have already been + // normalized at this point + var matches = rcssNum.exec( value ); + return matches ? + + // Guard against undefined "subtract", e.g., when used as in cssHooks + Math.max( 0, matches[ 2 ] - ( subtract || 0 ) ) + ( matches[ 3 ] || "px" ) : + value; +} + +function augmentWidthOrHeight( elem, name, extra, isBorderBox, styles ) { + var i, + val = 0; + + // If we already have the right measurement, avoid augmentation + if ( extra === ( isBorderBox ? "border" : "content" ) ) { + i = 4; + + // Otherwise initialize for horizontal or vertical properties + } else { + i = name === "width" ? 1 : 0; + } + + for ( ; i < 4; i += 2 ) { + + // Both box models exclude margin, so add it if we want it + if ( extra === "margin" ) { + val += jQuery.css( elem, extra + cssExpand[ i ], true, styles ); + } + + if ( isBorderBox ) { + + // border-box includes padding, so remove it if we want content + if ( extra === "content" ) { + val -= jQuery.css( elem, "padding" + cssExpand[ i ], true, styles ); + } + + // At this point, extra isn't border nor margin, so remove border + if ( extra !== "margin" ) { + val -= jQuery.css( elem, "border" + cssExpand[ i ] + "Width", true, styles ); + } + } else { + + // At this point, extra isn't content, so add padding + val += jQuery.css( elem, "padding" + cssExpand[ i ], true, styles ); + + // At this point, extra isn't content nor padding, so add border + if ( extra !== "padding" ) { + val += jQuery.css( elem, "border" + cssExpand[ i ] + "Width", true, styles ); + } + } + } + + return val; +} + +function getWidthOrHeight( elem, name, extra ) { + + // Start with computed style + var valueIsBorderBox, + styles = getStyles( elem ), + val = curCSS( elem, name, styles ), + isBorderBox = jQuery.css( elem, "boxSizing", false, styles ) === "border-box"; + + // Computed unit is not pixels. Stop here and return. + if ( rnumnonpx.test( val ) ) { + return val; + } + + // Check for style in case a browser which returns unreliable values + // for getComputedStyle silently falls back to the reliable elem.style + valueIsBorderBox = isBorderBox && + ( support.boxSizingReliable() || val === elem.style[ name ] ); + + // Fall back to offsetWidth/Height when value is "auto" + // This happens for inline elements with no explicit setting (gh-3571) + if ( val === "auto" ) { + val = elem[ "offset" + name[ 0 ].toUpperCase() + name.slice( 1 ) ]; + } + + // Normalize "", auto, and prepare for extra + val = parseFloat( val ) || 0; + + // Use the active box-sizing model to add/subtract irrelevant styles + return ( val + + augmentWidthOrHeight( + elem, + name, + extra || ( isBorderBox ? "border" : "content" ), + valueIsBorderBox, + styles + ) + ) + "px"; +} + +jQuery.extend( { + + // Add in style property hooks for overriding the default + // behavior of getting and setting a style property + cssHooks: { + opacity: { + get: function( elem, computed ) { + if ( computed ) { + + // We should always get a number back from opacity + var ret = curCSS( elem, "opacity" ); + return ret === "" ? "1" : ret; + } + } + } + }, + + // Don't automatically add "px" to these possibly-unitless properties + cssNumber: { + "animationIterationCount": true, + "columnCount": true, + "fillOpacity": true, + "flexGrow": true, + "flexShrink": true, + "fontWeight": true, + "lineHeight": true, + "opacity": true, + "order": true, + "orphans": true, + "widows": true, + "zIndex": true, + "zoom": true + }, + + // Add in properties whose names you wish to fix before + // setting or getting the value + cssProps: { + "float": "cssFloat" + }, + + // Get and set the style property on a DOM Node + style: function( elem, name, value, extra ) { + + // Don't set styles on text and comment nodes + if ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) { + return; + } + + // Make sure that we're working with the right name + var ret, type, hooks, + origName = jQuery.camelCase( name ), + isCustomProp = rcustomProp.test( name ), + style = elem.style; + + // Make sure that we're working with the right name. We don't + // want to query the value if it is a CSS custom property + // since they are user-defined. + if ( !isCustomProp ) { + name = finalPropName( origName ); + } + + // Gets hook for the prefixed version, then unprefixed version + hooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ]; + + // Check if we're setting a value + if ( value !== undefined ) { + type = typeof value; + + // Convert "+=" or "-=" to relative numbers (#7345) + if ( type === "string" && ( ret = rcssNum.exec( value ) ) && ret[ 1 ] ) { + value = adjustCSS( elem, name, ret ); + + // Fixes bug #9237 + type = "number"; + } + + // Make sure that null and NaN values aren't set (#7116) + if ( value == null || value !== value ) { + return; + } + + // If a number was passed in, add the unit (except for certain CSS properties) + if ( type === "number" ) { + value += ret && ret[ 3 ] || ( jQuery.cssNumber[ origName ] ? "" : "px" ); + } + + // background-* props affect original clone's values + if ( !support.clearCloneStyle && value === "" && name.indexOf( "background" ) === 0 ) { + style[ name ] = "inherit"; + } + + // If a hook was provided, use that value, otherwise just set the specified value + if ( !hooks || !( "set" in hooks ) || + ( value = hooks.set( elem, value, extra ) ) !== undefined ) { + + if ( isCustomProp ) { + style.setProperty( name, value ); + } else { + style[ name ] = value; + } + } + + } else { + + // If a hook was provided get the non-computed value from there + if ( hooks && "get" in hooks && + ( ret = hooks.get( elem, false, extra ) ) !== undefined ) { + + return ret; + } + + // Otherwise just get the value from the style object + return style[ name ]; + } + }, + + css: function( elem, name, extra, styles ) { + var val, num, hooks, + origName = jQuery.camelCase( name ), + isCustomProp = rcustomProp.test( name ); + + // Make sure that we're working with the right name. We don't + // want to modify the value if it is a CSS custom property + // since they are user-defined. + if ( !isCustomProp ) { + name = finalPropName( origName ); + } + + // Try prefixed name followed by the unprefixed name + hooks = jQuery.cssHooks[ name ] || jQuery.cssHooks[ origName ]; + + // If a hook was provided get the computed value from there + if ( hooks && "get" in hooks ) { + val = hooks.get( elem, true, extra ); + } + + // Otherwise, if a way to get the computed value exists, use that + if ( val === undefined ) { + val = curCSS( elem, name, styles ); + } + + // Convert "normal" to computed value + if ( val === "normal" && name in cssNormalTransform ) { + val = cssNormalTransform[ name ]; + } + + // Make numeric if forced or a qualifier was provided and val looks numeric + if ( extra === "" || extra ) { + num = parseFloat( val ); + return extra === true || isFinite( num ) ? num || 0 : val; + } + + return val; + } +} ); + +jQuery.each( [ "height", "width" ], function( i, name ) { + jQuery.cssHooks[ name ] = { + get: function( elem, computed, extra ) { + if ( computed ) { + + // Certain elements can have dimension info if we invisibly show them + // but it must have a current display style that would benefit + return rdisplayswap.test( jQuery.css( elem, "display" ) ) && + + // Support: Safari 8+ + // Table columns in Safari have non-zero offsetWidth & zero + // getBoundingClientRect().width unless display is changed. + // Support: IE <=11 only + // Running getBoundingClientRect on a disconnected node + // in IE throws an error. + ( !elem.getClientRects().length || !elem.getBoundingClientRect().width ) ? + swap( elem, cssShow, function() { + return getWidthOrHeight( elem, name, extra ); + } ) : + getWidthOrHeight( elem, name, extra ); + } + }, + + set: function( elem, value, extra ) { + var matches, + styles = extra && getStyles( elem ), + subtract = extra && augmentWidthOrHeight( + elem, + name, + extra, + jQuery.css( elem, "boxSizing", false, styles ) === "border-box", + styles + ); + + // Convert to pixels if value adjustment is needed + if ( subtract && ( matches = rcssNum.exec( value ) ) && + ( matches[ 3 ] || "px" ) !== "px" ) { + + elem.style[ name ] = value; + value = jQuery.css( elem, name ); + } + + return setPositiveNumber( elem, value, subtract ); + } + }; +} ); + +jQuery.cssHooks.marginLeft = addGetHookIf( support.reliableMarginLeft, + function( elem, computed ) { + if ( computed ) { + return ( parseFloat( curCSS( elem, "marginLeft" ) ) || + elem.getBoundingClientRect().left - + swap( elem, { marginLeft: 0 }, function() { + return elem.getBoundingClientRect().left; + } ) + ) + "px"; + } + } +); + +// These hooks are used by animate to expand properties +jQuery.each( { + margin: "", + padding: "", + border: "Width" +}, function( prefix, suffix ) { + jQuery.cssHooks[ prefix + suffix ] = { + expand: function( value ) { + var i = 0, + expanded = {}, + + // Assumes a single number if not a string + parts = typeof value === "string" ? value.split( " " ) : [ value ]; + + for ( ; i < 4; i++ ) { + expanded[ prefix + cssExpand[ i ] + suffix ] = + parts[ i ] || parts[ i - 2 ] || parts[ 0 ]; + } + + return expanded; + } + }; + + if ( !rmargin.test( prefix ) ) { + jQuery.cssHooks[ prefix + suffix ].set = setPositiveNumber; + } +} ); + +jQuery.fn.extend( { + css: function( name, value ) { + return access( this, function( elem, name, value ) { + var styles, len, + map = {}, + i = 0; + + if ( Array.isArray( name ) ) { + styles = getStyles( elem ); + len = name.length; + + for ( ; i < len; i++ ) { + map[ name[ i ] ] = jQuery.css( elem, name[ i ], false, styles ); + } + + return map; + } + + return value !== undefined ? + jQuery.style( elem, name, value ) : + jQuery.css( elem, name ); + }, name, value, arguments.length > 1 ); + } +} ); + + +function Tween( elem, options, prop, end, easing ) { + return new Tween.prototype.init( elem, options, prop, end, easing ); +} +jQuery.Tween = Tween; + +Tween.prototype = { + constructor: Tween, + init: function( elem, options, prop, end, easing, unit ) { + this.elem = elem; + this.prop = prop; + this.easing = easing || jQuery.easing._default; + this.options = options; + this.start = this.now = this.cur(); + this.end = end; + this.unit = unit || ( jQuery.cssNumber[ prop ] ? "" : "px" ); + }, + cur: function() { + var hooks = Tween.propHooks[ this.prop ]; + + return hooks && hooks.get ? + hooks.get( this ) : + Tween.propHooks._default.get( this ); + }, + run: function( percent ) { + var eased, + hooks = Tween.propHooks[ this.prop ]; + + if ( this.options.duration ) { + this.pos = eased = jQuery.easing[ this.easing ]( + percent, this.options.duration * percent, 0, 1, this.options.duration + ); + } else { + this.pos = eased = percent; + } + this.now = ( this.end - this.start ) * eased + this.start; + + if ( this.options.step ) { + this.options.step.call( this.elem, this.now, this ); + } + + if ( hooks && hooks.set ) { + hooks.set( this ); + } else { + Tween.propHooks._default.set( this ); + } + return this; + } +}; + +Tween.prototype.init.prototype = Tween.prototype; + +Tween.propHooks = { + _default: { + get: function( tween ) { + var result; + + // Use a property on the element directly when it is not a DOM element, + // or when there is no matching style property that exists. + if ( tween.elem.nodeType !== 1 || + tween.elem[ tween.prop ] != null && tween.elem.style[ tween.prop ] == null ) { + return tween.elem[ tween.prop ]; + } + + // Passing an empty string as a 3rd parameter to .css will automatically + // attempt a parseFloat and fallback to a string if the parse fails. + // Simple values such as "10px" are parsed to Float; + // complex values such as "rotate(1rad)" are returned as-is. + result = jQuery.css( tween.elem, tween.prop, "" ); + + // Empty strings, null, undefined and "auto" are converted to 0. + return !result || result === "auto" ? 0 : result; + }, + set: function( tween ) { + + // Use step hook for back compat. + // Use cssHook if its there. + // Use .style if available and use plain properties where available. + if ( jQuery.fx.step[ tween.prop ] ) { + jQuery.fx.step[ tween.prop ]( tween ); + } else if ( tween.elem.nodeType === 1 && + ( tween.elem.style[ jQuery.cssProps[ tween.prop ] ] != null || + jQuery.cssHooks[ tween.prop ] ) ) { + jQuery.style( tween.elem, tween.prop, tween.now + tween.unit ); + } else { + tween.elem[ tween.prop ] = tween.now; + } + } + } +}; + +// Support: IE <=9 only +// Panic based approach to setting things on disconnected nodes +Tween.propHooks.scrollTop = Tween.propHooks.scrollLeft = { + set: function( tween ) { + if ( tween.elem.nodeType && tween.elem.parentNode ) { + tween.elem[ tween.prop ] = tween.now; + } + } +}; + +jQuery.easing = { + linear: function( p ) { + return p; + }, + swing: function( p ) { + return 0.5 - Math.cos( p * Math.PI ) / 2; + }, + _default: "swing" +}; + +jQuery.fx = Tween.prototype.init; + +// Back compat <1.8 extension point +jQuery.fx.step = {}; + + + + +var + fxNow, inProgress, + rfxtypes = /^(?:toggle|show|hide)$/, + rrun = /queueHooks$/; + +function schedule() { + if ( inProgress ) { + if ( document.hidden === false && window.requestAnimationFrame ) { + window.requestAnimationFrame( schedule ); + } else { + window.setTimeout( schedule, jQuery.fx.interval ); + } + + jQuery.fx.tick(); + } +} + +// Animations created synchronously will run synchronously +function createFxNow() { + window.setTimeout( function() { + fxNow = undefined; + } ); + return ( fxNow = jQuery.now() ); +} + +// Generate parameters to create a standard animation +function genFx( type, includeWidth ) { + var which, + i = 0, + attrs = { height: type }; + + // If we include width, step value is 1 to do all cssExpand values, + // otherwise step value is 2 to skip over Left and Right + includeWidth = includeWidth ? 1 : 0; + for ( ; i < 4; i += 2 - includeWidth ) { + which = cssExpand[ i ]; + attrs[ "margin" + which ] = attrs[ "padding" + which ] = type; + } + + if ( includeWidth ) { + attrs.opacity = attrs.width = type; + } + + return attrs; +} + +function createTween( value, prop, animation ) { + var tween, + collection = ( Animation.tweeners[ prop ] || [] ).concat( Animation.tweeners[ "*" ] ), + index = 0, + length = collection.length; + for ( ; index < length; index++ ) { + if ( ( tween = collection[ index ].call( animation, prop, value ) ) ) { + + // We're done with this property + return tween; + } + } +} + +function defaultPrefilter( elem, props, opts ) { + var prop, value, toggle, hooks, oldfire, propTween, restoreDisplay, display, + isBox = "width" in props || "height" in props, + anim = this, + orig = {}, + style = elem.style, + hidden = elem.nodeType && isHiddenWithinTree( elem ), + dataShow = dataPriv.get( elem, "fxshow" ); + + // Queue-skipping animations hijack the fx hooks + if ( !opts.queue ) { + hooks = jQuery._queueHooks( elem, "fx" ); + if ( hooks.unqueued == null ) { + hooks.unqueued = 0; + oldfire = hooks.empty.fire; + hooks.empty.fire = function() { + if ( !hooks.unqueued ) { + oldfire(); + } + }; + } + hooks.unqueued++; + + anim.always( function() { + + // Ensure the complete handler is called before this completes + anim.always( function() { + hooks.unqueued--; + if ( !jQuery.queue( elem, "fx" ).length ) { + hooks.empty.fire(); + } + } ); + } ); + } + + // Detect show/hide animations + for ( prop in props ) { + value = props[ prop ]; + if ( rfxtypes.test( value ) ) { + delete props[ prop ]; + toggle = toggle || value === "toggle"; + if ( value === ( hidden ? "hide" : "show" ) ) { + + // Pretend to be hidden if this is a "show" and + // there is still data from a stopped show/hide + if ( value === "show" && dataShow && dataShow[ prop ] !== undefined ) { + hidden = true; + + // Ignore all other no-op show/hide data + } else { + continue; + } + } + orig[ prop ] = dataShow && dataShow[ prop ] || jQuery.style( elem, prop ); + } + } + + // Bail out if this is a no-op like .hide().hide() + propTween = !jQuery.isEmptyObject( props ); + if ( !propTween && jQuery.isEmptyObject( orig ) ) { + return; + } + + // Restrict "overflow" and "display" styles during box animations + if ( isBox && elem.nodeType === 1 ) { + + // Support: IE <=9 - 11, Edge 12 - 13 + // Record all 3 overflow attributes because IE does not infer the shorthand + // from identically-valued overflowX and overflowY + opts.overflow = [ style.overflow, style.overflowX, style.overflowY ]; + + // Identify a display type, preferring old show/hide data over the CSS cascade + restoreDisplay = dataShow && dataShow.display; + if ( restoreDisplay == null ) { + restoreDisplay = dataPriv.get( elem, "display" ); + } + display = jQuery.css( elem, "display" ); + if ( display === "none" ) { + if ( restoreDisplay ) { + display = restoreDisplay; + } else { + + // Get nonempty value(s) by temporarily forcing visibility + showHide( [ elem ], true ); + restoreDisplay = elem.style.display || restoreDisplay; + display = jQuery.css( elem, "display" ); + showHide( [ elem ] ); + } + } + + // Animate inline elements as inline-block + if ( display === "inline" || display === "inline-block" && restoreDisplay != null ) { + if ( jQuery.css( elem, "float" ) === "none" ) { + + // Restore the original display value at the end of pure show/hide animations + if ( !propTween ) { + anim.done( function() { + style.display = restoreDisplay; + } ); + if ( restoreDisplay == null ) { + display = style.display; + restoreDisplay = display === "none" ? "" : display; + } + } + style.display = "inline-block"; + } + } + } + + if ( opts.overflow ) { + style.overflow = "hidden"; + anim.always( function() { + style.overflow = opts.overflow[ 0 ]; + style.overflowX = opts.overflow[ 1 ]; + style.overflowY = opts.overflow[ 2 ]; + } ); + } + + // Implement show/hide animations + propTween = false; + for ( prop in orig ) { + + // General show/hide setup for this element animation + if ( !propTween ) { + if ( dataShow ) { + if ( "hidden" in dataShow ) { + hidden = dataShow.hidden; + } + } else { + dataShow = dataPriv.access( elem, "fxshow", { display: restoreDisplay } ); + } + + // Store hidden/visible for toggle so `.stop().toggle()` "reverses" + if ( toggle ) { + dataShow.hidden = !hidden; + } + + // Show elements before animating them + if ( hidden ) { + showHide( [ elem ], true ); + } + + /* eslint-disable no-loop-func */ + + anim.done( function() { + + /* eslint-enable no-loop-func */ + + // The final step of a "hide" animation is actually hiding the element + if ( !hidden ) { + showHide( [ elem ] ); + } + dataPriv.remove( elem, "fxshow" ); + for ( prop in orig ) { + jQuery.style( elem, prop, orig[ prop ] ); + } + } ); + } + + // Per-property setup + propTween = createTween( hidden ? dataShow[ prop ] : 0, prop, anim ); + if ( !( prop in dataShow ) ) { + dataShow[ prop ] = propTween.start; + if ( hidden ) { + propTween.end = propTween.start; + propTween.start = 0; + } + } + } +} + +function propFilter( props, specialEasing ) { + var index, name, easing, value, hooks; + + // camelCase, specialEasing and expand cssHook pass + for ( index in props ) { + name = jQuery.camelCase( index ); + easing = specialEasing[ name ]; + value = props[ index ]; + if ( Array.isArray( value ) ) { + easing = value[ 1 ]; + value = props[ index ] = value[ 0 ]; + } + + if ( index !== name ) { + props[ name ] = value; + delete props[ index ]; + } + + hooks = jQuery.cssHooks[ name ]; + if ( hooks && "expand" in hooks ) { + value = hooks.expand( value ); + delete props[ name ]; + + // Not quite $.extend, this won't overwrite existing keys. + // Reusing 'index' because we have the correct "name" + for ( index in value ) { + if ( !( index in props ) ) { + props[ index ] = value[ index ]; + specialEasing[ index ] = easing; + } + } + } else { + specialEasing[ name ] = easing; + } + } +} + +function Animation( elem, properties, options ) { + var result, + stopped, + index = 0, + length = Animation.prefilters.length, + deferred = jQuery.Deferred().always( function() { + + // Don't match elem in the :animated selector + delete tick.elem; + } ), + tick = function() { + if ( stopped ) { + return false; + } + var currentTime = fxNow || createFxNow(), + remaining = Math.max( 0, animation.startTime + animation.duration - currentTime ), + + // Support: Android 2.3 only + // Archaic crash bug won't allow us to use `1 - ( 0.5 || 0 )` (#12497) + temp = remaining / animation.duration || 0, + percent = 1 - temp, + index = 0, + length = animation.tweens.length; + + for ( ; index < length; index++ ) { + animation.tweens[ index ].run( percent ); + } + + deferred.notifyWith( elem, [ animation, percent, remaining ] ); + + // If there's more to do, yield + if ( percent < 1 && length ) { + return remaining; + } + + // If this was an empty animation, synthesize a final progress notification + if ( !length ) { + deferred.notifyWith( elem, [ animation, 1, 0 ] ); + } + + // Resolve the animation and report its conclusion + deferred.resolveWith( elem, [ animation ] ); + return false; + }, + animation = deferred.promise( { + elem: elem, + props: jQuery.extend( {}, properties ), + opts: jQuery.extend( true, { + specialEasing: {}, + easing: jQuery.easing._default + }, options ), + originalProperties: properties, + originalOptions: options, + startTime: fxNow || createFxNow(), + duration: options.duration, + tweens: [], + createTween: function( prop, end ) { + var tween = jQuery.Tween( elem, animation.opts, prop, end, + animation.opts.specialEasing[ prop ] || animation.opts.easing ); + animation.tweens.push( tween ); + return tween; + }, + stop: function( gotoEnd ) { + var index = 0, + + // If we are going to the end, we want to run all the tweens + // otherwise we skip this part + length = gotoEnd ? animation.tweens.length : 0; + if ( stopped ) { + return this; + } + stopped = true; + for ( ; index < length; index++ ) { + animation.tweens[ index ].run( 1 ); + } + + // Resolve when we played the last frame; otherwise, reject + if ( gotoEnd ) { + deferred.notifyWith( elem, [ animation, 1, 0 ] ); + deferred.resolveWith( elem, [ animation, gotoEnd ] ); + } else { + deferred.rejectWith( elem, [ animation, gotoEnd ] ); + } + return this; + } + } ), + props = animation.props; + + propFilter( props, animation.opts.specialEasing ); + + for ( ; index < length; index++ ) { + result = Animation.prefilters[ index ].call( animation, elem, props, animation.opts ); + if ( result ) { + if ( jQuery.isFunction( result.stop ) ) { + jQuery._queueHooks( animation.elem, animation.opts.queue ).stop = + jQuery.proxy( result.stop, result ); + } + return result; + } + } + + jQuery.map( props, createTween, animation ); + + if ( jQuery.isFunction( animation.opts.start ) ) { + animation.opts.start.call( elem, animation ); + } + + // Attach callbacks from options + animation + .progress( animation.opts.progress ) + .done( animation.opts.done, animation.opts.complete ) + .fail( animation.opts.fail ) + .always( animation.opts.always ); + + jQuery.fx.timer( + jQuery.extend( tick, { + elem: elem, + anim: animation, + queue: animation.opts.queue + } ) + ); + + return animation; +} + +jQuery.Animation = jQuery.extend( Animation, { + + tweeners: { + "*": [ function( prop, value ) { + var tween = this.createTween( prop, value ); + adjustCSS( tween.elem, prop, rcssNum.exec( value ), tween ); + return tween; + } ] + }, + + tweener: function( props, callback ) { + if ( jQuery.isFunction( props ) ) { + callback = props; + props = [ "*" ]; + } else { + props = props.match( rnothtmlwhite ); + } + + var prop, + index = 0, + length = props.length; + + for ( ; index < length; index++ ) { + prop = props[ index ]; + Animation.tweeners[ prop ] = Animation.tweeners[ prop ] || []; + Animation.tweeners[ prop ].unshift( callback ); + } + }, + + prefilters: [ defaultPrefilter ], + + prefilter: function( callback, prepend ) { + if ( prepend ) { + Animation.prefilters.unshift( callback ); + } else { + Animation.prefilters.push( callback ); + } + } +} ); + +jQuery.speed = function( speed, easing, fn ) { + var opt = speed && typeof speed === "object" ? jQuery.extend( {}, speed ) : { + complete: fn || !fn && easing || + jQuery.isFunction( speed ) && speed, + duration: speed, + easing: fn && easing || easing && !jQuery.isFunction( easing ) && easing + }; + + // Go to the end state if fx are off + if ( jQuery.fx.off ) { + opt.duration = 0; + + } else { + if ( typeof opt.duration !== "number" ) { + if ( opt.duration in jQuery.fx.speeds ) { + opt.duration = jQuery.fx.speeds[ opt.duration ]; + + } else { + opt.duration = jQuery.fx.speeds._default; + } + } + } + + // Normalize opt.queue - true/undefined/null -> "fx" + if ( opt.queue == null || opt.queue === true ) { + opt.queue = "fx"; + } + + // Queueing + opt.old = opt.complete; + + opt.complete = function() { + if ( jQuery.isFunction( opt.old ) ) { + opt.old.call( this ); + } + + if ( opt.queue ) { + jQuery.dequeue( this, opt.queue ); + } + }; + + return opt; +}; + +jQuery.fn.extend( { + fadeTo: function( speed, to, easing, callback ) { + + // Show any hidden elements after setting opacity to 0 + return this.filter( isHiddenWithinTree ).css( "opacity", 0 ).show() + + // Animate to the value specified + .end().animate( { opacity: to }, speed, easing, callback ); + }, + animate: function( prop, speed, easing, callback ) { + var empty = jQuery.isEmptyObject( prop ), + optall = jQuery.speed( speed, easing, callback ), + doAnimation = function() { + + // Operate on a copy of prop so per-property easing won't be lost + var anim = Animation( this, jQuery.extend( {}, prop ), optall ); + + // Empty animations, or finishing resolves immediately + if ( empty || dataPriv.get( this, "finish" ) ) { + anim.stop( true ); + } + }; + doAnimation.finish = doAnimation; + + return empty || optall.queue === false ? + this.each( doAnimation ) : + this.queue( optall.queue, doAnimation ); + }, + stop: function( type, clearQueue, gotoEnd ) { + var stopQueue = function( hooks ) { + var stop = hooks.stop; + delete hooks.stop; + stop( gotoEnd ); + }; + + if ( typeof type !== "string" ) { + gotoEnd = clearQueue; + clearQueue = type; + type = undefined; + } + if ( clearQueue && type !== false ) { + this.queue( type || "fx", [] ); + } + + return this.each( function() { + var dequeue = true, + index = type != null && type + "queueHooks", + timers = jQuery.timers, + data = dataPriv.get( this ); + + if ( index ) { + if ( data[ index ] && data[ index ].stop ) { + stopQueue( data[ index ] ); + } + } else { + for ( index in data ) { + if ( data[ index ] && data[ index ].stop && rrun.test( index ) ) { + stopQueue( data[ index ] ); + } + } + } + + for ( index = timers.length; index--; ) { + if ( timers[ index ].elem === this && + ( type == null || timers[ index ].queue === type ) ) { + + timers[ index ].anim.stop( gotoEnd ); + dequeue = false; + timers.splice( index, 1 ); + } + } + + // Start the next in the queue if the last step wasn't forced. + // Timers currently will call their complete callbacks, which + // will dequeue but only if they were gotoEnd. + if ( dequeue || !gotoEnd ) { + jQuery.dequeue( this, type ); + } + } ); + }, + finish: function( type ) { + if ( type !== false ) { + type = type || "fx"; + } + return this.each( function() { + var index, + data = dataPriv.get( this ), + queue = data[ type + "queue" ], + hooks = data[ type + "queueHooks" ], + timers = jQuery.timers, + length = queue ? queue.length : 0; + + // Enable finishing flag on private data + data.finish = true; + + // Empty the queue first + jQuery.queue( this, type, [] ); + + if ( hooks && hooks.stop ) { + hooks.stop.call( this, true ); + } + + // Look for any active animations, and finish them + for ( index = timers.length; index--; ) { + if ( timers[ index ].elem === this && timers[ index ].queue === type ) { + timers[ index ].anim.stop( true ); + timers.splice( index, 1 ); + } + } + + // Look for any animations in the old queue and finish them + for ( index = 0; index < length; index++ ) { + if ( queue[ index ] && queue[ index ].finish ) { + queue[ index ].finish.call( this ); + } + } + + // Turn off finishing flag + delete data.finish; + } ); + } +} ); + +jQuery.each( [ "toggle", "show", "hide" ], function( i, name ) { + var cssFn = jQuery.fn[ name ]; + jQuery.fn[ name ] = function( speed, easing, callback ) { + return speed == null || typeof speed === "boolean" ? + cssFn.apply( this, arguments ) : + this.animate( genFx( name, true ), speed, easing, callback ); + }; +} ); + +// Generate shortcuts for custom animations +jQuery.each( { + slideDown: genFx( "show" ), + slideUp: genFx( "hide" ), + slideToggle: genFx( "toggle" ), + fadeIn: { opacity: "show" }, + fadeOut: { opacity: "hide" }, + fadeToggle: { opacity: "toggle" } +}, function( name, props ) { + jQuery.fn[ name ] = function( speed, easing, callback ) { + return this.animate( props, speed, easing, callback ); + }; +} ); + +jQuery.timers = []; +jQuery.fx.tick = function() { + var timer, + i = 0, + timers = jQuery.timers; + + fxNow = jQuery.now(); + + for ( ; i < timers.length; i++ ) { + timer = timers[ i ]; + + // Run the timer and safely remove it when done (allowing for external removal) + if ( !timer() && timers[ i ] === timer ) { + timers.splice( i--, 1 ); + } + } + + if ( !timers.length ) { + jQuery.fx.stop(); + } + fxNow = undefined; +}; + +jQuery.fx.timer = function( timer ) { + jQuery.timers.push( timer ); + jQuery.fx.start(); +}; + +jQuery.fx.interval = 13; +jQuery.fx.start = function() { + if ( inProgress ) { + return; + } + + inProgress = true; + schedule(); +}; + +jQuery.fx.stop = function() { + inProgress = null; +}; + +jQuery.fx.speeds = { + slow: 600, + fast: 200, + + // Default speed + _default: 400 +}; + + +// Based off of the plugin by Clint Helfers, with permission. +// https://web.archive.org/web/20100324014747/http://blindsignals.com/index.php/2009/07/jquery-delay/ +jQuery.fn.delay = function( time, type ) { + time = jQuery.fx ? jQuery.fx.speeds[ time ] || time : time; + type = type || "fx"; + + return this.queue( type, function( next, hooks ) { + var timeout = window.setTimeout( next, time ); + hooks.stop = function() { + window.clearTimeout( timeout ); + }; + } ); +}; + + +( function() { + var input = document.createElement( "input" ), + select = document.createElement( "select" ), + opt = select.appendChild( document.createElement( "option" ) ); + + input.type = "checkbox"; + + // Support: Android <=4.3 only + // Default value for a checkbox should be "on" + support.checkOn = input.value !== ""; + + // Support: IE <=11 only + // Must access selectedIndex to make default options select + support.optSelected = opt.selected; + + // Support: IE <=11 only + // An input loses its value after becoming a radio + input = document.createElement( "input" ); + input.value = "t"; + input.type = "radio"; + support.radioValue = input.value === "t"; +} )(); + + +var boolHook, + attrHandle = jQuery.expr.attrHandle; + +jQuery.fn.extend( { + attr: function( name, value ) { + return access( this, jQuery.attr, name, value, arguments.length > 1 ); + }, + + removeAttr: function( name ) { + return this.each( function() { + jQuery.removeAttr( this, name ); + } ); + } +} ); + +jQuery.extend( { + attr: function( elem, name, value ) { + var ret, hooks, + nType = elem.nodeType; + + // Don't get/set attributes on text, comment and attribute nodes + if ( nType === 3 || nType === 8 || nType === 2 ) { + return; + } + + // Fallback to prop when attributes are not supported + if ( typeof elem.getAttribute === "undefined" ) { + return jQuery.prop( elem, name, value ); + } + + // Attribute hooks are determined by the lowercase version + // Grab necessary hook if one is defined + if ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) { + hooks = jQuery.attrHooks[ name.toLowerCase() ] || + ( jQuery.expr.match.bool.test( name ) ? boolHook : undefined ); + } + + if ( value !== undefined ) { + if ( value === null ) { + jQuery.removeAttr( elem, name ); + return; + } + + if ( hooks && "set" in hooks && + ( ret = hooks.set( elem, value, name ) ) !== undefined ) { + return ret; + } + + elem.setAttribute( name, value + "" ); + return value; + } + + if ( hooks && "get" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) { + return ret; + } + + ret = jQuery.find.attr( elem, name ); + + // Non-existent attributes return null, we normalize to undefined + return ret == null ? undefined : ret; + }, + + attrHooks: { + type: { + set: function( elem, value ) { + if ( !support.radioValue && value === "radio" && + nodeName( elem, "input" ) ) { + var val = elem.value; + elem.setAttribute( "type", value ); + if ( val ) { + elem.value = val; + } + return value; + } + } + } + }, + + removeAttr: function( elem, value ) { + var name, + i = 0, + + // Attribute names can contain non-HTML whitespace characters + // https://html.spec.whatwg.org/multipage/syntax.html#attributes-2 + attrNames = value && value.match( rnothtmlwhite ); + + if ( attrNames && elem.nodeType === 1 ) { + while ( ( name = attrNames[ i++ ] ) ) { + elem.removeAttribute( name ); + } + } + } +} ); + +// Hooks for boolean attributes +boolHook = { + set: function( elem, value, name ) { + if ( value === false ) { + + // Remove boolean attributes when set to false + jQuery.removeAttr( elem, name ); + } else { + elem.setAttribute( name, name ); + } + return name; + } +}; + +jQuery.each( jQuery.expr.match.bool.source.match( /\w+/g ), function( i, name ) { + var getter = attrHandle[ name ] || jQuery.find.attr; + + attrHandle[ name ] = function( elem, name, isXML ) { + var ret, handle, + lowercaseName = name.toLowerCase(); + + if ( !isXML ) { + + // Avoid an infinite loop by temporarily removing this function from the getter + handle = attrHandle[ lowercaseName ]; + attrHandle[ lowercaseName ] = ret; + ret = getter( elem, name, isXML ) != null ? + lowercaseName : + null; + attrHandle[ lowercaseName ] = handle; + } + return ret; + }; +} ); + + + + +var rfocusable = /^(?:input|select|textarea|button)$/i, + rclickable = /^(?:a|area)$/i; + +jQuery.fn.extend( { + prop: function( name, value ) { + return access( this, jQuery.prop, name, value, arguments.length > 1 ); + }, + + removeProp: function( name ) { + return this.each( function() { + delete this[ jQuery.propFix[ name ] || name ]; + } ); + } +} ); + +jQuery.extend( { + prop: function( elem, name, value ) { + var ret, hooks, + nType = elem.nodeType; + + // Don't get/set properties on text, comment and attribute nodes + if ( nType === 3 || nType === 8 || nType === 2 ) { + return; + } + + if ( nType !== 1 || !jQuery.isXMLDoc( elem ) ) { + + // Fix name and attach hooks + name = jQuery.propFix[ name ] || name; + hooks = jQuery.propHooks[ name ]; + } + + if ( value !== undefined ) { + if ( hooks && "set" in hooks && + ( ret = hooks.set( elem, value, name ) ) !== undefined ) { + return ret; + } + + return ( elem[ name ] = value ); + } + + if ( hooks && "get" in hooks && ( ret = hooks.get( elem, name ) ) !== null ) { + return ret; + } + + return elem[ name ]; + }, + + propHooks: { + tabIndex: { + get: function( elem ) { + + // Support: IE <=9 - 11 only + // elem.tabIndex doesn't always return the + // correct value when it hasn't been explicitly set + // https://web.archive.org/web/20141116233347/http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/ + // Use proper attribute retrieval(#12072) + var tabindex = jQuery.find.attr( elem, "tabindex" ); + + if ( tabindex ) { + return parseInt( tabindex, 10 ); + } + + if ( + rfocusable.test( elem.nodeName ) || + rclickable.test( elem.nodeName ) && + elem.href + ) { + return 0; + } + + return -1; + } + } + }, + + propFix: { + "for": "htmlFor", + "class": "className" + } +} ); + +// Support: IE <=11 only +// Accessing the selectedIndex property +// forces the browser to respect setting selected +// on the option +// The getter ensures a default option is selected +// when in an optgroup +// eslint rule "no-unused-expressions" is disabled for this code +// since it considers such accessions noop +if ( !support.optSelected ) { + jQuery.propHooks.selected = { + get: function( elem ) { + + /* eslint no-unused-expressions: "off" */ + + var parent = elem.parentNode; + if ( parent && parent.parentNode ) { + parent.parentNode.selectedIndex; + } + return null; + }, + set: function( elem ) { + + /* eslint no-unused-expressions: "off" */ + + var parent = elem.parentNode; + if ( parent ) { + parent.selectedIndex; + + if ( parent.parentNode ) { + parent.parentNode.selectedIndex; + } + } + } + }; +} + +jQuery.each( [ + "tabIndex", + "readOnly", + "maxLength", + "cellSpacing", + "cellPadding", + "rowSpan", + "colSpan", + "useMap", + "frameBorder", + "contentEditable" +], function() { + jQuery.propFix[ this.toLowerCase() ] = this; +} ); + + + + + // Strip and collapse whitespace according to HTML spec + // https://html.spec.whatwg.org/multipage/infrastructure.html#strip-and-collapse-whitespace + function stripAndCollapse( value ) { + var tokens = value.match( rnothtmlwhite ) || []; + return tokens.join( " " ); + } + + +function getClass( elem ) { + return elem.getAttribute && elem.getAttribute( "class" ) || ""; +} + +jQuery.fn.extend( { + addClass: function( value ) { + var classes, elem, cur, curValue, clazz, j, finalValue, + i = 0; + + if ( jQuery.isFunction( value ) ) { + return this.each( function( j ) { + jQuery( this ).addClass( value.call( this, j, getClass( this ) ) ); + } ); + } + + if ( typeof value === "string" && value ) { + classes = value.match( rnothtmlwhite ) || []; + + while ( ( elem = this[ i++ ] ) ) { + curValue = getClass( elem ); + cur = elem.nodeType === 1 && ( " " + stripAndCollapse( curValue ) + " " ); + + if ( cur ) { + j = 0; + while ( ( clazz = classes[ j++ ] ) ) { + if ( cur.indexOf( " " + clazz + " " ) < 0 ) { + cur += clazz + " "; + } + } + + // Only assign if different to avoid unneeded rendering. + finalValue = stripAndCollapse( cur ); + if ( curValue !== finalValue ) { + elem.setAttribute( "class", finalValue ); + } + } + } + } + + return this; + }, + + removeClass: function( value ) { + var classes, elem, cur, curValue, clazz, j, finalValue, + i = 0; + + if ( jQuery.isFunction( value ) ) { + return this.each( function( j ) { + jQuery( this ).removeClass( value.call( this, j, getClass( this ) ) ); + } ); + } + + if ( !arguments.length ) { + return this.attr( "class", "" ); + } + + if ( typeof value === "string" && value ) { + classes = value.match( rnothtmlwhite ) || []; + + while ( ( elem = this[ i++ ] ) ) { + curValue = getClass( elem ); + + // This expression is here for better compressibility (see addClass) + cur = elem.nodeType === 1 && ( " " + stripAndCollapse( curValue ) + " " ); + + if ( cur ) { + j = 0; + while ( ( clazz = classes[ j++ ] ) ) { + + // Remove *all* instances + while ( cur.indexOf( " " + clazz + " " ) > -1 ) { + cur = cur.replace( " " + clazz + " ", " " ); + } + } + + // Only assign if different to avoid unneeded rendering. + finalValue = stripAndCollapse( cur ); + if ( curValue !== finalValue ) { + elem.setAttribute( "class", finalValue ); + } + } + } + } + + return this; + }, + + toggleClass: function( value, stateVal ) { + var type = typeof value; + + if ( typeof stateVal === "boolean" && type === "string" ) { + return stateVal ? this.addClass( value ) : this.removeClass( value ); + } + + if ( jQuery.isFunction( value ) ) { + return this.each( function( i ) { + jQuery( this ).toggleClass( + value.call( this, i, getClass( this ), stateVal ), + stateVal + ); + } ); + } + + return this.each( function() { + var className, i, self, classNames; + + if ( type === "string" ) { + + // Toggle individual class names + i = 0; + self = jQuery( this ); + classNames = value.match( rnothtmlwhite ) || []; + + while ( ( className = classNames[ i++ ] ) ) { + + // Check each className given, space separated list + if ( self.hasClass( className ) ) { + self.removeClass( className ); + } else { + self.addClass( className ); + } + } + + // Toggle whole class name + } else if ( value === undefined || type === "boolean" ) { + className = getClass( this ); + if ( className ) { + + // Store className if set + dataPriv.set( this, "__className__", className ); + } + + // If the element has a class name or if we're passed `false`, + // then remove the whole classname (if there was one, the above saved it). + // Otherwise bring back whatever was previously saved (if anything), + // falling back to the empty string if nothing was stored. + if ( this.setAttribute ) { + this.setAttribute( "class", + className || value === false ? + "" : + dataPriv.get( this, "__className__" ) || "" + ); + } + } + } ); + }, + + hasClass: function( selector ) { + var className, elem, + i = 0; + + className = " " + selector + " "; + while ( ( elem = this[ i++ ] ) ) { + if ( elem.nodeType === 1 && + ( " " + stripAndCollapse( getClass( elem ) ) + " " ).indexOf( className ) > -1 ) { + return true; + } + } + + return false; + } +} ); + + + + +var rreturn = /\r/g; + +jQuery.fn.extend( { + val: function( value ) { + var hooks, ret, isFunction, + elem = this[ 0 ]; + + if ( !arguments.length ) { + if ( elem ) { + hooks = jQuery.valHooks[ elem.type ] || + jQuery.valHooks[ elem.nodeName.toLowerCase() ]; + + if ( hooks && + "get" in hooks && + ( ret = hooks.get( elem, "value" ) ) !== undefined + ) { + return ret; + } + + ret = elem.value; + + // Handle most common string cases + if ( typeof ret === "string" ) { + return ret.replace( rreturn, "" ); + } + + // Handle cases where value is null/undef or number + return ret == null ? "" : ret; + } + + return; + } + + isFunction = jQuery.isFunction( value ); + + return this.each( function( i ) { + var val; + + if ( this.nodeType !== 1 ) { + return; + } + + if ( isFunction ) { + val = value.call( this, i, jQuery( this ).val() ); + } else { + val = value; + } + + // Treat null/undefined as ""; convert numbers to string + if ( val == null ) { + val = ""; + + } else if ( typeof val === "number" ) { + val += ""; + + } else if ( Array.isArray( val ) ) { + val = jQuery.map( val, function( value ) { + return value == null ? "" : value + ""; + } ); + } + + hooks = jQuery.valHooks[ this.type ] || jQuery.valHooks[ this.nodeName.toLowerCase() ]; + + // If set returns undefined, fall back to normal setting + if ( !hooks || !( "set" in hooks ) || hooks.set( this, val, "value" ) === undefined ) { + this.value = val; + } + } ); + } +} ); + +jQuery.extend( { + valHooks: { + option: { + get: function( elem ) { + + var val = jQuery.find.attr( elem, "value" ); + return val != null ? + val : + + // Support: IE <=10 - 11 only + // option.text throws exceptions (#14686, #14858) + // Strip and collapse whitespace + // https://html.spec.whatwg.org/#strip-and-collapse-whitespace + stripAndCollapse( jQuery.text( elem ) ); + } + }, + select: { + get: function( elem ) { + var value, option, i, + options = elem.options, + index = elem.selectedIndex, + one = elem.type === "select-one", + values = one ? null : [], + max = one ? index + 1 : options.length; + + if ( index < 0 ) { + i = max; + + } else { + i = one ? index : 0; + } + + // Loop through all the selected options + for ( ; i < max; i++ ) { + option = options[ i ]; + + // Support: IE <=9 only + // IE8-9 doesn't update selected after form reset (#2551) + if ( ( option.selected || i === index ) && + + // Don't return options that are disabled or in a disabled optgroup + !option.disabled && + ( !option.parentNode.disabled || + !nodeName( option.parentNode, "optgroup" ) ) ) { + + // Get the specific value for the option + value = jQuery( option ).val(); + + // We don't need an array for one selects + if ( one ) { + return value; + } + + // Multi-Selects return an array + values.push( value ); + } + } + + return values; + }, + + set: function( elem, value ) { + var optionSet, option, + options = elem.options, + values = jQuery.makeArray( value ), + i = options.length; + + while ( i-- ) { + option = options[ i ]; + + /* eslint-disable no-cond-assign */ + + if ( option.selected = + jQuery.inArray( jQuery.valHooks.option.get( option ), values ) > -1 + ) { + optionSet = true; + } + + /* eslint-enable no-cond-assign */ + } + + // Force browsers to behave consistently when non-matching value is set + if ( !optionSet ) { + elem.selectedIndex = -1; + } + return values; + } + } + } +} ); + +// Radios and checkboxes getter/setter +jQuery.each( [ "radio", "checkbox" ], function() { + jQuery.valHooks[ this ] = { + set: function( elem, value ) { + if ( Array.isArray( value ) ) { + return ( elem.checked = jQuery.inArray( jQuery( elem ).val(), value ) > -1 ); + } + } + }; + if ( !support.checkOn ) { + jQuery.valHooks[ this ].get = function( elem ) { + return elem.getAttribute( "value" ) === null ? "on" : elem.value; + }; + } +} ); + + + + +// Return jQuery for attributes-only inclusion + + +var rfocusMorph = /^(?:focusinfocus|focusoutblur)$/; + +jQuery.extend( jQuery.event, { + + trigger: function( event, data, elem, onlyHandlers ) { + + var i, cur, tmp, bubbleType, ontype, handle, special, + eventPath = [ elem || document ], + type = hasOwn.call( event, "type" ) ? event.type : event, + namespaces = hasOwn.call( event, "namespace" ) ? event.namespace.split( "." ) : []; + + cur = tmp = elem = elem || document; + + // Don't do events on text and comment nodes + if ( elem.nodeType === 3 || elem.nodeType === 8 ) { + return; + } + + // focus/blur morphs to focusin/out; ensure we're not firing them right now + if ( rfocusMorph.test( type + jQuery.event.triggered ) ) { + return; + } + + if ( type.indexOf( "." ) > -1 ) { + + // Namespaced trigger; create a regexp to match event type in handle() + namespaces = type.split( "." ); + type = namespaces.shift(); + namespaces.sort(); + } + ontype = type.indexOf( ":" ) < 0 && "on" + type; + + // Caller can pass in a jQuery.Event object, Object, or just an event type string + event = event[ jQuery.expando ] ? + event : + new jQuery.Event( type, typeof event === "object" && event ); + + // Trigger bitmask: & 1 for native handlers; & 2 for jQuery (always true) + event.isTrigger = onlyHandlers ? 2 : 3; + event.namespace = namespaces.join( "." ); + event.rnamespace = event.namespace ? + new RegExp( "(^|\\.)" + namespaces.join( "\\.(?:.*\\.|)" ) + "(\\.|$)" ) : + null; + + // Clean up the event in case it is being reused + event.result = undefined; + if ( !event.target ) { + event.target = elem; + } + + // Clone any incoming data and prepend the event, creating the handler arg list + data = data == null ? + [ event ] : + jQuery.makeArray( data, [ event ] ); + + // Allow special events to draw outside the lines + special = jQuery.event.special[ type ] || {}; + if ( !onlyHandlers && special.trigger && special.trigger.apply( elem, data ) === false ) { + return; + } + + // Determine event propagation path in advance, per W3C events spec (#9951) + // Bubble up to document, then to window; watch for a global ownerDocument var (#9724) + if ( !onlyHandlers && !special.noBubble && !jQuery.isWindow( elem ) ) { + + bubbleType = special.delegateType || type; + if ( !rfocusMorph.test( bubbleType + type ) ) { + cur = cur.parentNode; + } + for ( ; cur; cur = cur.parentNode ) { + eventPath.push( cur ); + tmp = cur; + } + + // Only add window if we got to document (e.g., not plain obj or detached DOM) + if ( tmp === ( elem.ownerDocument || document ) ) { + eventPath.push( tmp.defaultView || tmp.parentWindow || window ); + } + } + + // Fire handlers on the event path + i = 0; + while ( ( cur = eventPath[ i++ ] ) && !event.isPropagationStopped() ) { + + event.type = i > 1 ? + bubbleType : + special.bindType || type; + + // jQuery handler + handle = ( dataPriv.get( cur, "events" ) || {} )[ event.type ] && + dataPriv.get( cur, "handle" ); + if ( handle ) { + handle.apply( cur, data ); + } + + // Native handler + handle = ontype && cur[ ontype ]; + if ( handle && handle.apply && acceptData( cur ) ) { + event.result = handle.apply( cur, data ); + if ( event.result === false ) { + event.preventDefault(); + } + } + } + event.type = type; + + // If nobody prevented the default action, do it now + if ( !onlyHandlers && !event.isDefaultPrevented() ) { + + if ( ( !special._default || + special._default.apply( eventPath.pop(), data ) === false ) && + acceptData( elem ) ) { + + // Call a native DOM method on the target with the same name as the event. + // Don't do default actions on window, that's where global variables be (#6170) + if ( ontype && jQuery.isFunction( elem[ type ] ) && !jQuery.isWindow( elem ) ) { + + // Don't re-trigger an onFOO event when we call its FOO() method + tmp = elem[ ontype ]; + + if ( tmp ) { + elem[ ontype ] = null; + } + + // Prevent re-triggering of the same event, since we already bubbled it above + jQuery.event.triggered = type; + elem[ type ](); + jQuery.event.triggered = undefined; + + if ( tmp ) { + elem[ ontype ] = tmp; + } + } + } + } + + return event.result; + }, + + // Piggyback on a donor event to simulate a different one + // Used only for `focus(in | out)` events + simulate: function( type, elem, event ) { + var e = jQuery.extend( + new jQuery.Event(), + event, + { + type: type, + isSimulated: true + } + ); + + jQuery.event.trigger( e, null, elem ); + } + +} ); + +jQuery.fn.extend( { + + trigger: function( type, data ) { + return this.each( function() { + jQuery.event.trigger( type, data, this ); + } ); + }, + triggerHandler: function( type, data ) { + var elem = this[ 0 ]; + if ( elem ) { + return jQuery.event.trigger( type, data, elem, true ); + } + } +} ); + + +jQuery.each( ( "blur focus focusin focusout resize scroll click dblclick " + + "mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave " + + "change select submit keydown keypress keyup contextmenu" ).split( " " ), + function( i, name ) { + + // Handle event binding + jQuery.fn[ name ] = function( data, fn ) { + return arguments.length > 0 ? + this.on( name, null, data, fn ) : + this.trigger( name ); + }; +} ); + +jQuery.fn.extend( { + hover: function( fnOver, fnOut ) { + return this.mouseenter( fnOver ).mouseleave( fnOut || fnOver ); + } +} ); + + + + +support.focusin = "onfocusin" in window; + + +// Support: Firefox <=44 +// Firefox doesn't have focus(in | out) events +// Related ticket - https://bugzilla.mozilla.org/show_bug.cgi?id=687787 +// +// Support: Chrome <=48 - 49, Safari <=9.0 - 9.1 +// focus(in | out) events fire after focus & blur events, +// which is spec violation - http://www.w3.org/TR/DOM-Level-3-Events/#events-focusevent-event-order +// Related ticket - https://bugs.chromium.org/p/chromium/issues/detail?id=449857 +if ( !support.focusin ) { + jQuery.each( { focus: "focusin", blur: "focusout" }, function( orig, fix ) { + + // Attach a single capturing handler on the document while someone wants focusin/focusout + var handler = function( event ) { + jQuery.event.simulate( fix, event.target, jQuery.event.fix( event ) ); + }; + + jQuery.event.special[ fix ] = { + setup: function() { + var doc = this.ownerDocument || this, + attaches = dataPriv.access( doc, fix ); + + if ( !attaches ) { + doc.addEventListener( orig, handler, true ); + } + dataPriv.access( doc, fix, ( attaches || 0 ) + 1 ); + }, + teardown: function() { + var doc = this.ownerDocument || this, + attaches = dataPriv.access( doc, fix ) - 1; + + if ( !attaches ) { + doc.removeEventListener( orig, handler, true ); + dataPriv.remove( doc, fix ); + + } else { + dataPriv.access( doc, fix, attaches ); + } + } + }; + } ); +} +var location = window.location; + +var nonce = jQuery.now(); + +var rquery = ( /\?/ ); + + + +// Cross-browser xml parsing +jQuery.parseXML = function( data ) { + var xml; + if ( !data || typeof data !== "string" ) { + return null; + } + + // Support: IE 9 - 11 only + // IE throws on parseFromString with invalid input. + try { + xml = ( new window.DOMParser() ).parseFromString( data, "text/xml" ); + } catch ( e ) { + xml = undefined; + } + + if ( !xml || xml.getElementsByTagName( "parsererror" ).length ) { + jQuery.error( "Invalid XML: " + data ); + } + return xml; +}; + + +var + rbracket = /\[\]$/, + rCRLF = /\r?\n/g, + rsubmitterTypes = /^(?:submit|button|image|reset|file)$/i, + rsubmittable = /^(?:input|select|textarea|keygen)/i; + +function buildParams( prefix, obj, traditional, add ) { + var name; + + if ( Array.isArray( obj ) ) { + + // Serialize array item. + jQuery.each( obj, function( i, v ) { + if ( traditional || rbracket.test( prefix ) ) { + + // Treat each array item as a scalar. + add( prefix, v ); + + } else { + + // Item is non-scalar (array or object), encode its numeric index. + buildParams( + prefix + "[" + ( typeof v === "object" && v != null ? i : "" ) + "]", + v, + traditional, + add + ); + } + } ); + + } else if ( !traditional && jQuery.type( obj ) === "object" ) { + + // Serialize object item. + for ( name in obj ) { + buildParams( prefix + "[" + name + "]", obj[ name ], traditional, add ); + } + + } else { + + // Serialize scalar item. + add( prefix, obj ); + } +} + +// Serialize an array of form elements or a set of +// key/values into a query string +jQuery.param = function( a, traditional ) { + var prefix, + s = [], + add = function( key, valueOrFunction ) { + + // If value is a function, invoke it and use its return value + var value = jQuery.isFunction( valueOrFunction ) ? + valueOrFunction() : + valueOrFunction; + + s[ s.length ] = encodeURIComponent( key ) + "=" + + encodeURIComponent( value == null ? "" : value ); + }; + + // If an array was passed in, assume that it is an array of form elements. + if ( Array.isArray( a ) || ( a.jquery && !jQuery.isPlainObject( a ) ) ) { + + // Serialize the form elements + jQuery.each( a, function() { + add( this.name, this.value ); + } ); + + } else { + + // If traditional, encode the "old" way (the way 1.3.2 or older + // did it), otherwise encode params recursively. + for ( prefix in a ) { + buildParams( prefix, a[ prefix ], traditional, add ); + } + } + + // Return the resulting serialization + return s.join( "&" ); +}; + +jQuery.fn.extend( { + serialize: function() { + return jQuery.param( this.serializeArray() ); + }, + serializeArray: function() { + return this.map( function() { + + // Can add propHook for "elements" to filter or add form elements + var elements = jQuery.prop( this, "elements" ); + return elements ? jQuery.makeArray( elements ) : this; + } ) + .filter( function() { + var type = this.type; + + // Use .is( ":disabled" ) so that fieldset[disabled] works + return this.name && !jQuery( this ).is( ":disabled" ) && + rsubmittable.test( this.nodeName ) && !rsubmitterTypes.test( type ) && + ( this.checked || !rcheckableType.test( type ) ); + } ) + .map( function( i, elem ) { + var val = jQuery( this ).val(); + + if ( val == null ) { + return null; + } + + if ( Array.isArray( val ) ) { + return jQuery.map( val, function( val ) { + return { name: elem.name, value: val.replace( rCRLF, "\r\n" ) }; + } ); + } + + return { name: elem.name, value: val.replace( rCRLF, "\r\n" ) }; + } ).get(); + } +} ); + + +var + r20 = /%20/g, + rhash = /#.*$/, + rantiCache = /([?&])_=[^&]*/, + rheaders = /^(.*?):[ \t]*([^\r\n]*)$/mg, + + // #7653, #8125, #8152: local protocol detection + rlocalProtocol = /^(?:about|app|app-storage|.+-extension|file|res|widget):$/, + rnoContent = /^(?:GET|HEAD)$/, + rprotocol = /^\/\//, + + /* Prefilters + * 1) They are useful to introduce custom dataTypes (see ajax/jsonp.js for an example) + * 2) These are called: + * - BEFORE asking for a transport + * - AFTER param serialization (s.data is a string if s.processData is true) + * 3) key is the dataType + * 4) the catchall symbol "*" can be used + * 5) execution will start with transport dataType and THEN continue down to "*" if needed + */ + prefilters = {}, + + /* Transports bindings + * 1) key is the dataType + * 2) the catchall symbol "*" can be used + * 3) selection will start with transport dataType and THEN go to "*" if needed + */ + transports = {}, + + // Avoid comment-prolog char sequence (#10098); must appease lint and evade compression + allTypes = "*/".concat( "*" ), + + // Anchor tag for parsing the document origin + originAnchor = document.createElement( "a" ); + originAnchor.href = location.href; + +// Base "constructor" for jQuery.ajaxPrefilter and jQuery.ajaxTransport +function addToPrefiltersOrTransports( structure ) { + + // dataTypeExpression is optional and defaults to "*" + return function( dataTypeExpression, func ) { + + if ( typeof dataTypeExpression !== "string" ) { + func = dataTypeExpression; + dataTypeExpression = "*"; + } + + var dataType, + i = 0, + dataTypes = dataTypeExpression.toLowerCase().match( rnothtmlwhite ) || []; + + if ( jQuery.isFunction( func ) ) { + + // For each dataType in the dataTypeExpression + while ( ( dataType = dataTypes[ i++ ] ) ) { + + // Prepend if requested + if ( dataType[ 0 ] === "+" ) { + dataType = dataType.slice( 1 ) || "*"; + ( structure[ dataType ] = structure[ dataType ] || [] ).unshift( func ); + + // Otherwise append + } else { + ( structure[ dataType ] = structure[ dataType ] || [] ).push( func ); + } + } + } + }; +} + +// Base inspection function for prefilters and transports +function inspectPrefiltersOrTransports( structure, options, originalOptions, jqXHR ) { + + var inspected = {}, + seekingTransport = ( structure === transports ); + + function inspect( dataType ) { + var selected; + inspected[ dataType ] = true; + jQuery.each( structure[ dataType ] || [], function( _, prefilterOrFactory ) { + var dataTypeOrTransport = prefilterOrFactory( options, originalOptions, jqXHR ); + if ( typeof dataTypeOrTransport === "string" && + !seekingTransport && !inspected[ dataTypeOrTransport ] ) { + + options.dataTypes.unshift( dataTypeOrTransport ); + inspect( dataTypeOrTransport ); + return false; + } else if ( seekingTransport ) { + return !( selected = dataTypeOrTransport ); + } + } ); + return selected; + } + + return inspect( options.dataTypes[ 0 ] ) || !inspected[ "*" ] && inspect( "*" ); +} + +// A special extend for ajax options +// that takes "flat" options (not to be deep extended) +// Fixes #9887 +function ajaxExtend( target, src ) { + var key, deep, + flatOptions = jQuery.ajaxSettings.flatOptions || {}; + + for ( key in src ) { + if ( src[ key ] !== undefined ) { + ( flatOptions[ key ] ? target : ( deep || ( deep = {} ) ) )[ key ] = src[ key ]; + } + } + if ( deep ) { + jQuery.extend( true, target, deep ); + } + + return target; +} + +/* Handles responses to an ajax request: + * - finds the right dataType (mediates between content-type and expected dataType) + * - returns the corresponding response + */ +function ajaxHandleResponses( s, jqXHR, responses ) { + + var ct, type, finalDataType, firstDataType, + contents = s.contents, + dataTypes = s.dataTypes; + + // Remove auto dataType and get content-type in the process + while ( dataTypes[ 0 ] === "*" ) { + dataTypes.shift(); + if ( ct === undefined ) { + ct = s.mimeType || jqXHR.getResponseHeader( "Content-Type" ); + } + } + + // Check if we're dealing with a known content-type + if ( ct ) { + for ( type in contents ) { + if ( contents[ type ] && contents[ type ].test( ct ) ) { + dataTypes.unshift( type ); + break; + } + } + } + + // Check to see if we have a response for the expected dataType + if ( dataTypes[ 0 ] in responses ) { + finalDataType = dataTypes[ 0 ]; + } else { + + // Try convertible dataTypes + for ( type in responses ) { + if ( !dataTypes[ 0 ] || s.converters[ type + " " + dataTypes[ 0 ] ] ) { + finalDataType = type; + break; + } + if ( !firstDataType ) { + firstDataType = type; + } + } + + // Or just use first one + finalDataType = finalDataType || firstDataType; + } + + // If we found a dataType + // We add the dataType to the list if needed + // and return the corresponding response + if ( finalDataType ) { + if ( finalDataType !== dataTypes[ 0 ] ) { + dataTypes.unshift( finalDataType ); + } + return responses[ finalDataType ]; + } +} + +/* Chain conversions given the request and the original response + * Also sets the responseXXX fields on the jqXHR instance + */ +function ajaxConvert( s, response, jqXHR, isSuccess ) { + var conv2, current, conv, tmp, prev, + converters = {}, + + // Work with a copy of dataTypes in case we need to modify it for conversion + dataTypes = s.dataTypes.slice(); + + // Create converters map with lowercased keys + if ( dataTypes[ 1 ] ) { + for ( conv in s.converters ) { + converters[ conv.toLowerCase() ] = s.converters[ conv ]; + } + } + + current = dataTypes.shift(); + + // Convert to each sequential dataType + while ( current ) { + + if ( s.responseFields[ current ] ) { + jqXHR[ s.responseFields[ current ] ] = response; + } + + // Apply the dataFilter if provided + if ( !prev && isSuccess && s.dataFilter ) { + response = s.dataFilter( response, s.dataType ); + } + + prev = current; + current = dataTypes.shift(); + + if ( current ) { + + // There's only work to do if current dataType is non-auto + if ( current === "*" ) { + + current = prev; + + // Convert response if prev dataType is non-auto and differs from current + } else if ( prev !== "*" && prev !== current ) { + + // Seek a direct converter + conv = converters[ prev + " " + current ] || converters[ "* " + current ]; + + // If none found, seek a pair + if ( !conv ) { + for ( conv2 in converters ) { + + // If conv2 outputs current + tmp = conv2.split( " " ); + if ( tmp[ 1 ] === current ) { + + // If prev can be converted to accepted input + conv = converters[ prev + " " + tmp[ 0 ] ] || + converters[ "* " + tmp[ 0 ] ]; + if ( conv ) { + + // Condense equivalence converters + if ( conv === true ) { + conv = converters[ conv2 ]; + + // Otherwise, insert the intermediate dataType + } else if ( converters[ conv2 ] !== true ) { + current = tmp[ 0 ]; + dataTypes.unshift( tmp[ 1 ] ); + } + break; + } + } + } + } + + // Apply converter (if not an equivalence) + if ( conv !== true ) { + + // Unless errors are allowed to bubble, catch and return them + if ( conv && s.throws ) { + response = conv( response ); + } else { + try { + response = conv( response ); + } catch ( e ) { + return { + state: "parsererror", + error: conv ? e : "No conversion from " + prev + " to " + current + }; + } + } + } + } + } + } + + return { state: "success", data: response }; +} + +jQuery.extend( { + + // Counter for holding the number of active queries + active: 0, + + // Last-Modified header cache for next request + lastModified: {}, + etag: {}, + + ajaxSettings: { + url: location.href, + type: "GET", + isLocal: rlocalProtocol.test( location.protocol ), + global: true, + processData: true, + async: true, + contentType: "application/x-www-form-urlencoded; charset=UTF-8", + + /* + timeout: 0, + data: null, + dataType: null, + username: null, + password: null, + cache: null, + throws: false, + traditional: false, + headers: {}, + */ + + accepts: { + "*": allTypes, + text: "text/plain", + html: "text/html", + xml: "application/xml, text/xml", + json: "application/json, text/javascript" + }, + + contents: { + xml: /\bxml\b/, + html: /\bhtml/, + json: /\bjson\b/ + }, + + responseFields: { + xml: "responseXML", + text: "responseText", + json: "responseJSON" + }, + + // Data converters + // Keys separate source (or catchall "*") and destination types with a single space + converters: { + + // Convert anything to text + "* text": String, + + // Text to html (true = no transformation) + "text html": true, + + // Evaluate text as a json expression + "text json": JSON.parse, + + // Parse text as xml + "text xml": jQuery.parseXML + }, + + // For options that shouldn't be deep extended: + // you can add your own custom options here if + // and when you create one that shouldn't be + // deep extended (see ajaxExtend) + flatOptions: { + url: true, + context: true + } + }, + + // Creates a full fledged settings object into target + // with both ajaxSettings and settings fields. + // If target is omitted, writes into ajaxSettings. + ajaxSetup: function( target, settings ) { + return settings ? + + // Building a settings object + ajaxExtend( ajaxExtend( target, jQuery.ajaxSettings ), settings ) : + + // Extending ajaxSettings + ajaxExtend( jQuery.ajaxSettings, target ); + }, + + ajaxPrefilter: addToPrefiltersOrTransports( prefilters ), + ajaxTransport: addToPrefiltersOrTransports( transports ), + + // Main method + ajax: function( url, options ) { + + // If url is an object, simulate pre-1.5 signature + if ( typeof url === "object" ) { + options = url; + url = undefined; + } + + // Force options to be an object + options = options || {}; + + var transport, + + // URL without anti-cache param + cacheURL, + + // Response headers + responseHeadersString, + responseHeaders, + + // timeout handle + timeoutTimer, + + // Url cleanup var + urlAnchor, + + // Request state (becomes false upon send and true upon completion) + completed, + + // To know if global events are to be dispatched + fireGlobals, + + // Loop variable + i, + + // uncached part of the url + uncached, + + // Create the final options object + s = jQuery.ajaxSetup( {}, options ), + + // Callbacks context + callbackContext = s.context || s, + + // Context for global events is callbackContext if it is a DOM node or jQuery collection + globalEventContext = s.context && + ( callbackContext.nodeType || callbackContext.jquery ) ? + jQuery( callbackContext ) : + jQuery.event, + + // Deferreds + deferred = jQuery.Deferred(), + completeDeferred = jQuery.Callbacks( "once memory" ), + + // Status-dependent callbacks + statusCode = s.statusCode || {}, + + // Headers (they are sent all at once) + requestHeaders = {}, + requestHeadersNames = {}, + + // Default abort message + strAbort = "canceled", + + // Fake xhr + jqXHR = { + readyState: 0, + + // Builds headers hashtable if needed + getResponseHeader: function( key ) { + var match; + if ( completed ) { + if ( !responseHeaders ) { + responseHeaders = {}; + while ( ( match = rheaders.exec( responseHeadersString ) ) ) { + responseHeaders[ match[ 1 ].toLowerCase() ] = match[ 2 ]; + } + } + match = responseHeaders[ key.toLowerCase() ]; + } + return match == null ? null : match; + }, + + // Raw string + getAllResponseHeaders: function() { + return completed ? responseHeadersString : null; + }, + + // Caches the header + setRequestHeader: function( name, value ) { + if ( completed == null ) { + name = requestHeadersNames[ name.toLowerCase() ] = + requestHeadersNames[ name.toLowerCase() ] || name; + requestHeaders[ name ] = value; + } + return this; + }, + + // Overrides response content-type header + overrideMimeType: function( type ) { + if ( completed == null ) { + s.mimeType = type; + } + return this; + }, + + // Status-dependent callbacks + statusCode: function( map ) { + var code; + if ( map ) { + if ( completed ) { + + // Execute the appropriate callbacks + jqXHR.always( map[ jqXHR.status ] ); + } else { + + // Lazy-add the new callbacks in a way that preserves old ones + for ( code in map ) { + statusCode[ code ] = [ statusCode[ code ], map[ code ] ]; + } + } + } + return this; + }, + + // Cancel the request + abort: function( statusText ) { + var finalText = statusText || strAbort; + if ( transport ) { + transport.abort( finalText ); + } + done( 0, finalText ); + return this; + } + }; + + // Attach deferreds + deferred.promise( jqXHR ); + + // Add protocol if not provided (prefilters might expect it) + // Handle falsy url in the settings object (#10093: consistency with old signature) + // We also use the url parameter if available + s.url = ( ( url || s.url || location.href ) + "" ) + .replace( rprotocol, location.protocol + "//" ); + + // Alias method option to type as per ticket #12004 + s.type = options.method || options.type || s.method || s.type; + + // Extract dataTypes list + s.dataTypes = ( s.dataType || "*" ).toLowerCase().match( rnothtmlwhite ) || [ "" ]; + + // A cross-domain request is in order when the origin doesn't match the current origin. + if ( s.crossDomain == null ) { + urlAnchor = document.createElement( "a" ); + + // Support: IE <=8 - 11, Edge 12 - 13 + // IE throws exception on accessing the href property if url is malformed, + // e.g. http://example.com:80x/ + try { + urlAnchor.href = s.url; + + // Support: IE <=8 - 11 only + // Anchor's host property isn't correctly set when s.url is relative + urlAnchor.href = urlAnchor.href; + s.crossDomain = originAnchor.protocol + "//" + originAnchor.host !== + urlAnchor.protocol + "//" + urlAnchor.host; + } catch ( e ) { + + // If there is an error parsing the URL, assume it is crossDomain, + // it can be rejected by the transport if it is invalid + s.crossDomain = true; + } + } + + // Convert data if not already a string + if ( s.data && s.processData && typeof s.data !== "string" ) { + s.data = jQuery.param( s.data, s.traditional ); + } + + // Apply prefilters + inspectPrefiltersOrTransports( prefilters, s, options, jqXHR ); + + // If request was aborted inside a prefilter, stop there + if ( completed ) { + return jqXHR; + } + + // We can fire global events as of now if asked to + // Don't fire events if jQuery.event is undefined in an AMD-usage scenario (#15118) + fireGlobals = jQuery.event && s.global; + + // Watch for a new set of requests + if ( fireGlobals && jQuery.active++ === 0 ) { + jQuery.event.trigger( "ajaxStart" ); + } + + // Uppercase the type + s.type = s.type.toUpperCase(); + + // Determine if request has content + s.hasContent = !rnoContent.test( s.type ); + + // Save the URL in case we're toying with the If-Modified-Since + // and/or If-None-Match header later on + // Remove hash to simplify url manipulation + cacheURL = s.url.replace( rhash, "" ); + + // More options handling for requests with no content + if ( !s.hasContent ) { + + // Remember the hash so we can put it back + uncached = s.url.slice( cacheURL.length ); + + // If data is available, append data to url + if ( s.data ) { + cacheURL += ( rquery.test( cacheURL ) ? "&" : "?" ) + s.data; + + // #9682: remove data so that it's not used in an eventual retry + delete s.data; + } + + // Add or update anti-cache param if needed + if ( s.cache === false ) { + cacheURL = cacheURL.replace( rantiCache, "$1" ); + uncached = ( rquery.test( cacheURL ) ? "&" : "?" ) + "_=" + ( nonce++ ) + uncached; + } + + // Put hash and anti-cache on the URL that will be requested (gh-1732) + s.url = cacheURL + uncached; + + // Change '%20' to '+' if this is encoded form body content (gh-2658) + } else if ( s.data && s.processData && + ( s.contentType || "" ).indexOf( "application/x-www-form-urlencoded" ) === 0 ) { + s.data = s.data.replace( r20, "+" ); + } + + // Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode. + if ( s.ifModified ) { + if ( jQuery.lastModified[ cacheURL ] ) { + jqXHR.setRequestHeader( "If-Modified-Since", jQuery.lastModified[ cacheURL ] ); + } + if ( jQuery.etag[ cacheURL ] ) { + jqXHR.setRequestHeader( "If-None-Match", jQuery.etag[ cacheURL ] ); + } + } + + // Set the correct header, if data is being sent + if ( s.data && s.hasContent && s.contentType !== false || options.contentType ) { + jqXHR.setRequestHeader( "Content-Type", s.contentType ); + } + + // Set the Accepts header for the server, depending on the dataType + jqXHR.setRequestHeader( + "Accept", + s.dataTypes[ 0 ] && s.accepts[ s.dataTypes[ 0 ] ] ? + s.accepts[ s.dataTypes[ 0 ] ] + + ( s.dataTypes[ 0 ] !== "*" ? ", " + allTypes + "; q=0.01" : "" ) : + s.accepts[ "*" ] + ); + + // Check for headers option + for ( i in s.headers ) { + jqXHR.setRequestHeader( i, s.headers[ i ] ); + } + + // Allow custom headers/mimetypes and early abort + if ( s.beforeSend && + ( s.beforeSend.call( callbackContext, jqXHR, s ) === false || completed ) ) { + + // Abort if not done already and return + return jqXHR.abort(); + } + + // Aborting is no longer a cancellation + strAbort = "abort"; + + // Install callbacks on deferreds + completeDeferred.add( s.complete ); + jqXHR.done( s.success ); + jqXHR.fail( s.error ); + + // Get transport + transport = inspectPrefiltersOrTransports( transports, s, options, jqXHR ); + + // If no transport, we auto-abort + if ( !transport ) { + done( -1, "No Transport" ); + } else { + jqXHR.readyState = 1; + + // Send global event + if ( fireGlobals ) { + globalEventContext.trigger( "ajaxSend", [ jqXHR, s ] ); + } + + // If request was aborted inside ajaxSend, stop there + if ( completed ) { + return jqXHR; + } + + // Timeout + if ( s.async && s.timeout > 0 ) { + timeoutTimer = window.setTimeout( function() { + jqXHR.abort( "timeout" ); + }, s.timeout ); + } + + try { + completed = false; + transport.send( requestHeaders, done ); + } catch ( e ) { + + // Rethrow post-completion exceptions + if ( completed ) { + throw e; + } + + // Propagate others as results + done( -1, e ); + } + } + + // Callback for when everything is done + function done( status, nativeStatusText, responses, headers ) { + var isSuccess, success, error, response, modified, + statusText = nativeStatusText; + + // Ignore repeat invocations + if ( completed ) { + return; + } + + completed = true; + + // Clear timeout if it exists + if ( timeoutTimer ) { + window.clearTimeout( timeoutTimer ); + } + + // Dereference transport for early garbage collection + // (no matter how long the jqXHR object will be used) + transport = undefined; + + // Cache response headers + responseHeadersString = headers || ""; + + // Set readyState + jqXHR.readyState = status > 0 ? 4 : 0; + + // Determine if successful + isSuccess = status >= 200 && status < 300 || status === 304; + + // Get response data + if ( responses ) { + response = ajaxHandleResponses( s, jqXHR, responses ); + } + + // Convert no matter what (that way responseXXX fields are always set) + response = ajaxConvert( s, response, jqXHR, isSuccess ); + + // If successful, handle type chaining + if ( isSuccess ) { + + // Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode. + if ( s.ifModified ) { + modified = jqXHR.getResponseHeader( "Last-Modified" ); + if ( modified ) { + jQuery.lastModified[ cacheURL ] = modified; + } + modified = jqXHR.getResponseHeader( "etag" ); + if ( modified ) { + jQuery.etag[ cacheURL ] = modified; + } + } + + // if no content + if ( status === 204 || s.type === "HEAD" ) { + statusText = "nocontent"; + + // if not modified + } else if ( status === 304 ) { + statusText = "notmodified"; + + // If we have data, let's convert it + } else { + statusText = response.state; + success = response.data; + error = response.error; + isSuccess = !error; + } + } else { + + // Extract error from statusText and normalize for non-aborts + error = statusText; + if ( status || !statusText ) { + statusText = "error"; + if ( status < 0 ) { + status = 0; + } + } + } + + // Set data for the fake xhr object + jqXHR.status = status; + jqXHR.statusText = ( nativeStatusText || statusText ) + ""; + + // Success/Error + if ( isSuccess ) { + deferred.resolveWith( callbackContext, [ success, statusText, jqXHR ] ); + } else { + deferred.rejectWith( callbackContext, [ jqXHR, statusText, error ] ); + } + + // Status-dependent callbacks + jqXHR.statusCode( statusCode ); + statusCode = undefined; + + if ( fireGlobals ) { + globalEventContext.trigger( isSuccess ? "ajaxSuccess" : "ajaxError", + [ jqXHR, s, isSuccess ? success : error ] ); + } + + // Complete + completeDeferred.fireWith( callbackContext, [ jqXHR, statusText ] ); + + if ( fireGlobals ) { + globalEventContext.trigger( "ajaxComplete", [ jqXHR, s ] ); + + // Handle the global AJAX counter + if ( !( --jQuery.active ) ) { + jQuery.event.trigger( "ajaxStop" ); + } + } + } + + return jqXHR; + }, + + getJSON: function( url, data, callback ) { + return jQuery.get( url, data, callback, "json" ); + }, + + getScript: function( url, callback ) { + return jQuery.get( url, undefined, callback, "script" ); + } +} ); + +jQuery.each( [ "get", "post" ], function( i, method ) { + jQuery[ method ] = function( url, data, callback, type ) { + + // Shift arguments if data argument was omitted + if ( jQuery.isFunction( data ) ) { + type = type || callback; + callback = data; + data = undefined; + } + + // The url can be an options object (which then must have .url) + return jQuery.ajax( jQuery.extend( { + url: url, + type: method, + dataType: type, + data: data, + success: callback + }, jQuery.isPlainObject( url ) && url ) ); + }; +} ); + + +jQuery._evalUrl = function( url ) { + return jQuery.ajax( { + url: url, + + // Make this explicit, since user can override this through ajaxSetup (#11264) + type: "GET", + dataType: "script", + cache: true, + async: false, + global: false, + "throws": true + } ); +}; + + +jQuery.fn.extend( { + wrapAll: function( html ) { + var wrap; + + if ( this[ 0 ] ) { + if ( jQuery.isFunction( html ) ) { + html = html.call( this[ 0 ] ); + } + + // The elements to wrap the target around + wrap = jQuery( html, this[ 0 ].ownerDocument ).eq( 0 ).clone( true ); + + if ( this[ 0 ].parentNode ) { + wrap.insertBefore( this[ 0 ] ); + } + + wrap.map( function() { + var elem = this; + + while ( elem.firstElementChild ) { + elem = elem.firstElementChild; + } + + return elem; + } ).append( this ); + } + + return this; + }, + + wrapInner: function( html ) { + if ( jQuery.isFunction( html ) ) { + return this.each( function( i ) { + jQuery( this ).wrapInner( html.call( this, i ) ); + } ); + } + + return this.each( function() { + var self = jQuery( this ), + contents = self.contents(); + + if ( contents.length ) { + contents.wrapAll( html ); + + } else { + self.append( html ); + } + } ); + }, + + wrap: function( html ) { + var isFunction = jQuery.isFunction( html ); + + return this.each( function( i ) { + jQuery( this ).wrapAll( isFunction ? html.call( this, i ) : html ); + } ); + }, + + unwrap: function( selector ) { + this.parent( selector ).not( "body" ).each( function() { + jQuery( this ).replaceWith( this.childNodes ); + } ); + return this; + } +} ); + + +jQuery.expr.pseudos.hidden = function( elem ) { + return !jQuery.expr.pseudos.visible( elem ); +}; +jQuery.expr.pseudos.visible = function( elem ) { + return !!( elem.offsetWidth || elem.offsetHeight || elem.getClientRects().length ); +}; + + + + +jQuery.ajaxSettings.xhr = function() { + try { + return new window.XMLHttpRequest(); + } catch ( e ) {} +}; + +var xhrSuccessStatus = { + + // File protocol always yields status code 0, assume 200 + 0: 200, + + // Support: IE <=9 only + // #1450: sometimes IE returns 1223 when it should be 204 + 1223: 204 + }, + xhrSupported = jQuery.ajaxSettings.xhr(); + +support.cors = !!xhrSupported && ( "withCredentials" in xhrSupported ); +support.ajax = xhrSupported = !!xhrSupported; + +jQuery.ajaxTransport( function( options ) { + var callback, errorCallback; + + // Cross domain only allowed if supported through XMLHttpRequest + if ( support.cors || xhrSupported && !options.crossDomain ) { + return { + send: function( headers, complete ) { + var i, + xhr = options.xhr(); + + xhr.open( + options.type, + options.url, + options.async, + options.username, + options.password + ); + + // Apply custom fields if provided + if ( options.xhrFields ) { + for ( i in options.xhrFields ) { + xhr[ i ] = options.xhrFields[ i ]; + } + } + + // Override mime type if needed + if ( options.mimeType && xhr.overrideMimeType ) { + xhr.overrideMimeType( options.mimeType ); + } + + // X-Requested-With header + // For cross-domain requests, seeing as conditions for a preflight are + // akin to a jigsaw puzzle, we simply never set it to be sure. + // (it can always be set on a per-request basis or even using ajaxSetup) + // For same-domain requests, won't change header if already provided. + if ( !options.crossDomain && !headers[ "X-Requested-With" ] ) { + headers[ "X-Requested-With" ] = "XMLHttpRequest"; + } + + // Set headers + for ( i in headers ) { + xhr.setRequestHeader( i, headers[ i ] ); + } + + // Callback + callback = function( type ) { + return function() { + if ( callback ) { + callback = errorCallback = xhr.onload = + xhr.onerror = xhr.onabort = xhr.onreadystatechange = null; + + if ( type === "abort" ) { + xhr.abort(); + } else if ( type === "error" ) { + + // Support: IE <=9 only + // On a manual native abort, IE9 throws + // errors on any property access that is not readyState + if ( typeof xhr.status !== "number" ) { + complete( 0, "error" ); + } else { + complete( + + // File: protocol always yields status 0; see #8605, #14207 + xhr.status, + xhr.statusText + ); + } + } else { + complete( + xhrSuccessStatus[ xhr.status ] || xhr.status, + xhr.statusText, + + // Support: IE <=9 only + // IE9 has no XHR2 but throws on binary (trac-11426) + // For XHR2 non-text, let the caller handle it (gh-2498) + ( xhr.responseType || "text" ) !== "text" || + typeof xhr.responseText !== "string" ? + { binary: xhr.response } : + { text: xhr.responseText }, + xhr.getAllResponseHeaders() + ); + } + } + }; + }; + + // Listen to events + xhr.onload = callback(); + errorCallback = xhr.onerror = callback( "error" ); + + // Support: IE 9 only + // Use onreadystatechange to replace onabort + // to handle uncaught aborts + if ( xhr.onabort !== undefined ) { + xhr.onabort = errorCallback; + } else { + xhr.onreadystatechange = function() { + + // Check readyState before timeout as it changes + if ( xhr.readyState === 4 ) { + + // Allow onerror to be called first, + // but that will not handle a native abort + // Also, save errorCallback to a variable + // as xhr.onerror cannot be accessed + window.setTimeout( function() { + if ( callback ) { + errorCallback(); + } + } ); + } + }; + } + + // Create the abort callback + callback = callback( "abort" ); + + try { + + // Do send the request (this may raise an exception) + xhr.send( options.hasContent && options.data || null ); + } catch ( e ) { + + // #14683: Only rethrow if this hasn't been notified as an error yet + if ( callback ) { + throw e; + } + } + }, + + abort: function() { + if ( callback ) { + callback(); + } + } + }; + } +} ); + + + + +// Prevent auto-execution of scripts when no explicit dataType was provided (See gh-2432) +jQuery.ajaxPrefilter( function( s ) { + if ( s.crossDomain ) { + s.contents.script = false; + } +} ); + +// Install script dataType +jQuery.ajaxSetup( { + accepts: { + script: "text/javascript, application/javascript, " + + "application/ecmascript, application/x-ecmascript" + }, + contents: { + script: /\b(?:java|ecma)script\b/ + }, + converters: { + "text script": function( text ) { + jQuery.globalEval( text ); + return text; + } + } +} ); + +// Handle cache's special case and crossDomain +jQuery.ajaxPrefilter( "script", function( s ) { + if ( s.cache === undefined ) { + s.cache = false; + } + if ( s.crossDomain ) { + s.type = "GET"; + } +} ); + +// Bind script tag hack transport +jQuery.ajaxTransport( "script", function( s ) { + + // This transport only deals with cross domain requests + if ( s.crossDomain ) { + var script, callback; + return { + send: function( _, complete ) { + script = jQuery( " - + + - + @@ -106,24 +120,42 @@

Extracted CMake API referencePublic CMake functions / macros
  • mrt_add_executable
  • mrt_add_library
  • -
  • mrt_add_node_and_nodelet
  • -
  • mrt_add_nodelet
  • -
  • mrt_add_nosetests
  • -
  • mrt_add_python_api
  • -
  • mrt_add_ros_tests
  • -
  • mrt_add_tests
  • -
  • mrt_add_to_ide
  • -
  • mrt_install
  • -
  • mrt_python_module_setup
  • -
  • Non-public CMake functions / macros
  • -
  • _list_append_deduplicate
  • -
  • _list_append_unique
  • -
  • _mrt_register_test
  • -
  • _pack_libraries_with_build_configuration
  • -
  • _unpack_libraries_with_build_configuration
  • -
  • generate_ros_parameter_files
  • -
  • Not documented CMake functions / macros
  • -
  • generate_ros_interface_files
  • +
  • mrt_add_links
  • +
  • mrt_add_node_and_nodelet
  • +
  • mrt_add_nodelet
  • +
  • mrt_add_nosetests
  • +
  • mrt_add_python_api
  • +
  • mrt_add_ros_tests
  • +
  • mrt_add_tests
  • +
  • mrt_add_to_ide
  • +
  • mrt_install
  • +
  • mrt_parse_package_xml
  • +
  • mrt_python_module_setup
  • +
  • Non-public CMake functions / macros
  • +
  • _mrt_run_test
  • +
  • generate_ros_parameter_files
  • +
  • glob_folders
  • +
  • glob_ros_files
  • +
  • mrt_add_action_files
  • +
  • mrt_add_message_files
  • +
  • mrt_add_service_files
  • +
  • mrt_glob_files
  • +
  • mrt_glob_files_recurse
  • +
  • mrt_glob_folders
  • +
  • Not documented CMake functions / macros
  • +
  • _mrt_add_nosetests_impl
  • +
  • _mrt_create_executable_gtest
  • +
  • _mrt_export_package
  • +
  • _mrt_get_python_destination
  • +
  • _setup_coverage_info
  • +
  • catkin_install_python
  • +
  • catkin_package
  • +
  • catkin_package_xml
  • +
  • generate_ros_interface_files
  • +
  • mrt_add_gtest
  • +
  • mrt_add_rostest
  • +
  • mrt_add_rostest_gtest
  • +
  • mrt_init_testing
  • @@ -134,6 +166,7 @@

    Public CMake functions / macros @@ -151,7 +185,7 @@

    Public CMake functions / macros
    mrt_add_executable(execname)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds an executable.

    This command ensures the executable is compiled with all necessary dependencies.

    @@ -188,7 +222,7 @@

    Public CMake functions / macros
    mrt_add_library(libname)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds a library.

    This command ensures the library is compiled with all necessary dependencies. If no files are passed, the command will return silently.

    @@ -201,34 +235,59 @@

    Public CMake functions / macros Parameters:
      -
    • libname (string) – Name of the library to generate as first argument (without lib or .so)
    • -
    • INCLUDES (list of strings) – Include files needed for the library, absolute or relative to ${PROJECT_SOURCE_DIR}
    • -
    • SOURCES (list of strings) – Source files to be added. If empty, a header-only library is assumed
    • -
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects.
    • -
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects
    • +
    • libname (string) – Name of the library to generate as first argument (without lib or .so)
    • +
    • INCLUDES (list of strings) – Public include files needed to use the library, absolute or relative to ${PROJECT_SOURCE_DIR}
    • +
    • SOURCES (list of strings) – Source files and private headers to be added. If no source files are passed, a header-only library is assumed
    • +
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) dependencies. This should only be required for including external projects.
    • +
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects

    Example:

    -
    mrt_add_library( example_package
    -    INCLUDES include/example_package/myclass.h include/example_package/myclass2.h
    -    SOURCES src/myclass.cpp src/myclass.cpp
    -    )
    +
    mrt_add_library( example_package
    +    INCLUDES include/example_package/myclass.h include/example_package/myclass2.h
    +    SOURCES src/myclass.cpp src/myclass.cpp
    +    )
    +
    +
    +

    + + +
    -

    mrt_add_node_and_nodelet

    +

    mrt_add_node_and_nodelet

    mrt_add_node_and_nodelet(basename)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds a node and a corresponding nodelet.

    -

    This command ensures the node/nodelet are compiled with all necessary dependencies. Make sure to add lib{NAME}_nodelet to the nodelet_plugins.xml file.

    +

    This command ensures the node/nodelet are compiled with all necessary dependencies. Make sure to add lib<package_name>-<basename>-nodelet to the nodelet_plugins.xml file.

    Note

    Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible.

    @@ -241,33 +300,33 @@

    Public CMake functions / macros Parameters:
      -
    • basename (string) – base name of the node/nodelet (_nodelet will be appended for the nodelet name to avoid conflicts with library packages)
    • -
    • FOLDER (string) – Folder with cpp files for the executable, relative to ${PROJECT_SOURCE_DIR}
    • -
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects.
    • -
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects
    • +
    • basename (string) – base name of the node/nodelet (_nodelet will be appended for the nodelet name to avoid conflicts with library packages)
    • +
    • FOLDER (string) – Folder with cpp files for the executable, relative to ${PROJECT_SOURCE_DIR}
    • +
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects.
    • +
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects

    Example:

    -
    mrt_add_node_and_nodelet( example_package
    -    FOLDER src/example_package
    -    )
    +
    mrt_add_node_and_nodelet( example_package
    +    FOLDER src/example_package
    +    )
     
    -

    The resulting entry in the nodelet_plugins.xml is thus: <library path=”lib/libexample_package_nodelet”>

    +

    The resulting entry in the nodelet_plugins.xml is thus (for a package named example_package): <library path=”lib/libexample_package-example_package-nodelet”>

    -

    mrt_add_nodelet

    +

    mrt_add_nodelet

    mrt_add_nodelet(nodeletname)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds a nodelet.

    -

    This command ensures the nodelet is compiled with all necessary dependencies. Make sure to add lib{NAME}_nodelet to the nodelet_plugins.xml file.

    +

    This command ensures the nodelet is compiled with all necessary dependencies. Make sure to add lib{PROJECT_NAME}-{NAME}-nodelet to the nodelet_plugins.xml file.

    Note

    Make sure to call this after all messages and parameter generation CMAKE-Commands so that all dependencies are visible.

    @@ -280,61 +339,61 @@

    Public CMake functions / macros Parameters:
      -
    • nodeletname (string) – base name of the nodelet (_nodelet will be appended to the base name to avoid conflicts with library packages)
    • -
    • FOLDER (string) – Folder with cpp files for the executable, relative to ${PROJECT_SOURCE_DIR}
    • -
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects.
    • -
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects
    • -
    • TARGETNAME (string) – Choose the name of the internal CMAKE target. Will be autogenerated if not specified.
    • +
    • nodeletname (string) – base name of the nodelet (_nodelet will be appended to the base name to avoid conflicts with library packages)
    • +
    • FOLDER (string) – Folder with cpp files for the executable, relative to ${PROJECT_SOURCE_DIR}
    • +
    • DEPENDS (list of strings) – List of extra (non-catkin, non-mrt) CMAKE dependencies. This should only be required for including external projects.
    • +
    • LIBRARIES (list of strings) – Extra (non-catkin, non-mrt) libraries to link to. This should only be required for external projects
    • +
    • TARGETNAME (string) – Choose the name of the internal CMAKE target. Will be autogenerated if not specified.

    Example:

    -
    mrt_add_nodelet( example_package
    -    FOLDER src/example_package
    -    )
    +
    mrt_add_nodelet( example_package
    +    FOLDER src/example_package
    +    )
     
    -

    The resulting entry in the nodelet_plugins.xml is thus: <library path=”lib/libexample_package_nodelet”>

    +

    The resulting entry in the nodelet_plugins.xml is thus: <library path=”lib/libexample_package-example_package-nodelet”>

    -

    mrt_add_nosetests

    +

    mrt_add_nosetests

    mrt_add_nosetests(folder)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds python nosetest contained in a folder. Wraps the function catkin_add_nosetests.

    Parameters:
      -
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • -
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)
    • -
    • DEPENDENCIES (list of strings) – Alias for DEPENDS
    • +
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • +
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)
    • +
    • DEPENDENCIES (list of strings) – Alias for DEPENDS

    Example:

    -
    mrt_add_nosetests(test)
    +
    mrt_add_nosetests(test)
     
    -

    mrt_add_python_api

    +

    mrt_add_python_api

    mrt_add_python_api(modulename)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Generates a python module from boost-python cpp files.

    -

    Each <file>.cpp will become a seperate <file>.py submodule within <modulename>. After building and sourcing you can use the modules simply with “import <modulename>.<file>”.

    +

    Each <file>.cpp will become a seperate <file>.py submodule within <modulename>. After building and sourcing you can use the modules simply with “import <modulename>.<file>”.

    The files are automatically linked with boost-python libraries and a python module is generated and installed from the resulting library. If this project declares any libraries with mrt_add_library(), they will automatically be linked with this library.

    This function will define the compiler variable PYTHON_API_MODULE_NAME with the name of the generated library. This can be used in the BOOST_PYTHON_MODULE C++ Macro.

    @@ -347,49 +406,49 @@

    Public CMake functions / macros Parameters:
      -
    • modulename (string) – Name of the module needs to be passed as first parameter.
    • -
    • FILES (list of strings) – list of C++ files defining the BOOST-Python API.
    • +
    • modulename (string) – Name of the module needs to be passed as first parameter.
    • +
    • FILES (list of strings) – list of C++ files defining the BOOST-Python API.

    Example:

    -
    mrt_add_python_api( example_package
    -    FILES python_api/python.cpp
    -    )
    +
    mrt_add_python_api( example_package
    +    FILES python_api/python.cpp
    +    )
     

    -

    mrt_add_ros_tests

    +

    mrt_add_ros_tests

    mrt_add_ros_tests(folder)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds all rostests (identified by a .test file) contained in a folder as unittests.

    If a .cpp file exists with the same name, it will be added and comiled as a gtest test. -Unittests can be run with “catkin run_tests” or similar. “-test” will be appended to the name of the test node to avoid conflicts (i.e. the type argument should then be <test ... type=”mytest-test”/> in a mytest.test file).

    -

    Unittests will always be executed with the folder as cwd. E.g. if the test folder contains a sub-folder “test_data”, it can simply be accessed as “test_data”.

    -

    If coverage information is enabled (by setting MRT_ENABLE_COVARAGE to true), coverage analysis will be performed after unittests have run. The results can be found in the package’s build folder in the folder “coverage”.

    +Unittests can be run with “catkin run_tests” or similar. “-test” will be appended to the name of the test node to avoid conflicts (i.e. the type argument should then be <test … type=”mytest-test”/> in a mytest.test file).

    +

    Unittests will always be executed with the folder as cwd. E.g. if the test folder contains a sub-folder “test_data”, it can simply be accessed as “test_data”.

    +

    If coverage information is enabled (by setting MRT_ENABLE_COVARAGE to true), coverage analysis will be performed after unittests have run. The results can be found in the package’s build folder in the folder “coverage”.

    Unless the variable ${MRT_NO_FAIL_ON_TESTS} is set, failing unittests will result in a failed build.

    Parameters:
      -
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • -
    • LIBRARIES (list of strings) – Additional (non-catkin, non-mrt) libraries to link to
    • -
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)
    • +
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • +
    • LIBRARIES (list of strings) – Additional (non-catkin, non-mrt) libraries to link to
    • +
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)

    Example:

    -
    mrt_add_ros_tests( test
    +
    mrt_add_ros_tests( test
         )
     
    @@ -397,30 +456,31 @@

    Public CMake functions / macros
    -

    mrt_add_tests

    +

    mrt_add_tests

    mrt_add_tests(folder)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Adds all gtests (without a corresponding .test file) contained in a folder as unittests.

    Parameters:
      -
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • -
    • LIBRARIES (list of strings) – Additional (non-catkin, non-mrt) libraries to link to
    • -
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)
    • +
    • folder (string) – folder containing the tests (relative to ${PROJECT_SOURCE_DIR}) as first argument
    • +
    • LIBRARIES (list of strings) – Additional (non-catkin, non-mrt) libraries to link to
    • +
    • DEPENDS (list of strings) – Additional (non-catkin, non-mrt) dependencies (e.g. with catkin_download_test_data)
    -

    Unittests will always be executed with the folder as cwd. E.g. if the test folder contains a sub-folder “test_data”, it can simply be accessed as “test_data”.

    +

    Unittests will be executed with the folder as cwd if ctest or the run_test target is used. E.g. if the test folder contains a sub-folder “test_data”, it can simply be accessed as “test_data”. +Another way of getting the location of the project root folder path is to #include "test/test_utility.hpp" and use the variable <project_name>::test::projectRootDir.

    Unless the variable ${MRT_NO_FAIL_ON_TESTS} is set, failing unittests will result in a failed build.

    -

    If coverage information is enabled (by setting MRT_ENABLE_COVARAGE to true), coverage analysis will be performed after unittests have run. The results can be found in the package’s build folder in the folder “coverage”.

    +

    If coverage information is enabled (by setting MRT_ENABLE_COVARAGE to true), coverage analysis will be performed after unittests have run. The results can be found in the package’s build folder in the folder “coverage”.

    Example:

    -
    mrt_add_tests( test
    +
    mrt_add_tests( test
         )
     
    @@ -428,169 +488,317 @@

    Public CMake functions / macros
    -

    mrt_add_to_ide

    +

    mrt_add_to_ide

    mrt_add_to_ide(files)
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    -

    Adds a file or folder or a list of each to the list of files shown by the IDE -The files will not be marked for installation. Paths should be relative to PROJECT_SOURCE_DIR

    -

    If a file or folder does not exist, it will be ignored without warning.

    -

    Example:

    -
    mrt_add_to_ide(
    -    myfile1 myfile2.txt myFolder
    -    )
    -
    -
    +

    [function defined in mrt_cmake_modules-macros.cmake]

    +

    Once upon a time this used to make non-code files known to IDEs that parse Cmake output. But as this +messes up with the target determination mechanism used by most ides and garbages up the target view.

    +

    Therefore this function is no longer used and only here for backwards compability.

    -

    mrt_install

    +

    mrt_install

    mrt_install()
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Installs all relevant project files.

    -

    All targets added by the mrt_add_<library/executable/nodelet/...> commands will be installed automatically when using this command. Other files/folders (launchfiles, scripts) need to be specified explicitly. -Non existing files and folders will be silently ignored. All files will be marked as project files for IDEs.

    +

    All targets added by the mrt_add_<library/executable/nodelet/…> commands will be installed automatically when using this command. Other files/folders (launchfiles, scripts) need to be specified explicitly. +Non existing files and folders will be silently ignored.

    +

    If the project contains a file cmake/<project-name>-extras.cmake[.in], it will be automatically included by all depending projects. This allows to export cmake functions, etc. If the file ends with [.in], it will be configured by cmake +and the variables “@DEVELSPACE@” “@INSTALLSPACE@” will be replaced by true or files depending on the build type, @PROJECT_SPACE_DIR@ to the devel/install folder and @PKT_CMAKE_DIR@ to the cmake folder

    Parameters:
      -
    • PROGRAMS (list of strings) – List of all folders and files that are programs (python scripts will be indentified and treated separately). Files will be made executable.
    • -
    • FILES (list of strings) – List of non-executable files and folders. Subfolders will be installed recursively.
    • +
    • PROGRAMS (list of strings) – List of all folders and files that are programs (python scripts will be indentified and treated separately). Files will be made executable.
    • +
    • FILES (list of strings) – List of non-executable files and folders. Subfolders will be installed recursively.
    • +
    • EXPORT_LIBS (list of (interface) library targets) – List of non-mrt-created libraries that should be installed and exported

    Example:

    -
    mrt_install(
    -    PROGRAMS scripts
    -    FILES launch nodelet_plugins.xml
    -    )
    +
    mrt_install(
    +    PROGRAMS scripts
    +    FILES launch nodelet_plugins.xml
    +    )
     
    +
    +
    +

    mrt_parse_package_xml

    +
    +
    +mrt_parse_package_xml()
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Parses the package.xml and sets its information in form of cmake variables as ${PACKAGE_NAME}_<info>, where info is +one of version, VERSION, MAINTAINER, PACKAGE_FORMAT, <BUILD/BUILD_EXPORT/TEST/EXEC/…>_DEPENDS, URL_<WEBSITE/BUGTRACKER/REPOSITORY>

    +

    This function must be called before any other of the mrt_* functions can be called.

    +
    +
    -

    mrt_python_module_setup

    +

    mrt_python_module_setup

    mrt_python_module_setup()
    -

    [function defined in mrt_cmake_modules-extras.cmake]

    +

    [function defined in mrt_cmake_modules-macros.cmake]

    Automatically sets up and installs python modules located under src/${PROJECT_NAME}. -Modules can afterwards simply be included using “import <project_name>” in python.

    +Modules can afterwards simply be included using “import <project_name>” in python.

    The python folder (under src/${PROJECT_NAME}) is required to have an __init__.py file.

    The command will automatically generate a setup.py in your project folder. This file should not be commited, as it will be regenerated at every new CMAKE run. Due to restrictions imposed by catkin (searches hardcoded for this setup.py), the file cannot be placed elsewhere.

    Example:

    -
    mrt_python_module_setup()
    +
    mrt_python_module_setup()
     
    -
    -

    _list_append_deduplicate

    +
    +

    _mrt_run_test

    -
    -_list_append_deduplicate(listname)
    -

    [macro defined in mrt_cmake_modulesConfig.cmake]

    -

    append elements to a list and remove existing duplicates from the list -copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig -self contained

    +
    +_mrt_run_test(target_name, working_dir, result_xml_path)
    +

    [function defined in Modules/MrtTesting.cmake]

    +

    All paths have to be absolute

    -
    -

    _list_append_unique

    +
    +

    generate_ros_parameter_files

    -
    -_list_append_unique(listname)
    -

    [macro defined in mrt_cmake_modulesConfig.cmake]

    -

    append elements to a list if they are not already in the list -copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig -self contained

    +
    +generate_ros_parameter_files()
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    define rosparam/rosinterface_handler macro for compability. Macros will be overriden by the actual macros defined by the packages, if existing.

    -
    -

    _mrt_register_test

    +
    +

    glob_folders

    -
    -_mrt_register_test()
    -

    [macro defined in mrt_cmake_modules-extras.cmake]

    -

    Registers the custom check_tests command and adds a dependency for a certain unittest

    -

    Example:

    -
    _mrt_register_test(
    -    )
    -
    +
    +glob_folders()
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Deprecated function. Use ‘mrt_glob_folders’ instead.

    +
    +
    +
    +

    glob_ros_files

    +
    +
    +glob_ros_files(excecutable_name, extension_name)
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Deprecated function. Use one of ‘mrt_add_message_files’, ‘mrt_add_service_files’ or ‘mrt_add_action_files’.

    -
    -

    _pack_libraries_with_build_configuration

    +
    +

    mrt_add_action_files

    -
    -_pack_libraries_with_build_configuration(VAR)
    -

    [macro defined in mrt_cmake_modulesConfig.cmake]

    -

    pack a list of libraries with optional build configuration keywords -copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig -self contained

    +
    +mrt_add_action_files(folder_name)
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Globs for action files and calls add_action_files

    -
    -

    _unpack_libraries_with_build_configuration

    +
    +

    mrt_add_message_files

    -
    -_unpack_libraries_with_build_configuration(VAR)
    -

    [macro defined in mrt_cmake_modulesConfig.cmake]

    -

    unpack a list of libraries with optional build configuration keyword prefixes -copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig -self contained

    +
    +mrt_add_message_files(folder_name)
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Globs for message files and calls add_message_files

    -
    -

    generate_ros_parameter_files

    +
    +

    mrt_add_service_files

    -
    -generate_ros_parameter_files()
    -

    [macro defined in mrt_cmake_modules-extras.cmake]

    -

    define rosparam/rosinterface_handler macro for compability. Macros will be overriden by the actual macros defined by the packages, if existing.

    +
    +mrt_add_service_files(folder_name)
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +

    Globs for service files and calls add_service_files

    +
    + +
    +
    +

    mrt_glob_files

    +
    +
    +mrt_glob_files(varname)
    +

    [function defined in mrt_cmake_modules-macros.cmake]

    +

    Globs files in the currect project dir.

    +
    + +
    +
    +

    mrt_glob_files_recurse

    +
    +
    +mrt_glob_files_recurse(varname)
    +

    [function defined in mrt_cmake_modules-macros.cmake]

    +

    Globs files recursivly in the currect project dir.

    +
    + +
    +
    +

    mrt_glob_folders

    +
    +
    +mrt_glob_folders(DIRECTORY_LIST, SEARCH_DIRECTORY)
    +

    [function defined in mrt_cmake_modules-macros.cmake]

    +

    Glob for folders in the search directory.

    +
    +

    _mrt_add_nosetests_impl

    +
    +
    +_mrt_add_nosetests_impl(folder)
    +

    [function defined in Modules/MrtTesting.cmake]

    +
    + +
    +
    +

    _mrt_create_executable_gtest

    +
    +
    +_mrt_create_executable_gtest(target, file)
    +

    [function defined in Modules/MrtTesting.cmake]

    +
    + +
    +
    +

    _mrt_export_package

    +
    +
    +_mrt_export_package()
    +

    [function defined in Modules/ExportPackage.cmake]

    +
    + +
    +
    +

    _mrt_get_python_destination

    +
    +
    +_mrt_get_python_destination(output_var)
    +

    [function defined in mrt_cmake_modules-macros.cmake]

    +
    + +
    +
    +

    _setup_coverage_info

    +
    +
    +_setup_coverage_info()
    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +
    + +
    +
    +

    catkin_install_python

    +
    +
    +catkin_install_python(programs)
    +

    [function defined in Modules/CatkinMockForConan.cmake]

    +
    + +
    +
    +

    catkin_package

    +
    +
    +catkin_package()
    +

    [function defined in Modules/CatkinMockForConan.cmake]

    +
    + +
    +
    +

    catkin_package_xml

    +
    +
    +catkin_package_xml()
    +

    [function defined in Modules/CatkinMockForConan.cmake]

    +
    +
    -

    generate_ros_interface_files

    +

    generate_ros_interface_files

    generate_ros_interface_files()
    -

    [macro defined in mrt_cmake_modules-extras.cmake]

    +

    [macro defined in mrt_cmake_modules-macros.cmake]

    +
    + +
    +
    +

    mrt_add_gtest

    +
    +
    +mrt_add_gtest(target, file)
    +

    [function defined in Modules/MrtTesting.cmake]

    +
    + +
    +
    +

    mrt_add_rostest

    +
    +
    +mrt_add_rostest(target, launch_file)
    +

    [function defined in Modules/MrtTesting.cmake]

    +
    + +
    +
    +

    mrt_add_rostest_gtest

    +
    +
    +mrt_add_rostest_gtest(target, launch_file, cpp_file)
    +

    [function defined in Modules/MrtTesting.cmake]

    +
    + +
    +
    +

    mrt_init_testing

    +
    +
    +mrt_init_testing()
    +

    [function defined in Modules/MrtTesting.cmake]

    @@ -608,12 +816,12 @@

    Navigation

  • index
  • - +
    \ No newline at end of file diff --git a/mrt_cmake_modules/doc/genindex.html b/mrt_cmake_modules/doc/genindex.html index f21d542dec7..5d74c17adcc 100644 --- a/mrt_cmake_modules/doc/genindex.html +++ b/mrt_cmake_modules/doc/genindex.html @@ -1,39 +1,38 @@ + - - - Index — mrt_cmake_modules 1.0.0 documentation - + Index — mrt_cmake_modules 1.0.3 documentation - - + + - + @@ -70,104 +66,113 @@

    Index

    _ + | C | G | M

    _

    - - + +
    - -
    _list_append_deduplicate() (CMake macro) -
    - - -
    _list_append_unique() (CMake macro) -
    - - -
    _mrt_register_test() (CMake macro) -
    - -
    - -
    _pack_libraries_with_build_configuration() (CMake macro) -
    - - -
    _unpack_libraries_with_build_configuration() (CMake macro) -
    +
    -

    +

    C

    + + +

    G

    - - + +
    - -
    generate_ros_interface_files() (CMake macro) -
    - -
    - -
    generate_ros_parameter_files() (CMake macro) -
    - -

    M

    - - + +
    - -
    mrt_add_executable() (CMake macro) -
    - - -
    mrt_add_library() (CMake macro) -
    - - -
    mrt_add_node_and_nodelet() (CMake macro) -
    - - -
    mrt_add_nodelet() (CMake macro) -
    - - -
    mrt_add_nosetests() (CMake macro) -
    - - -
    mrt_add_python_api() (CMake macro) -
    - -
    - -
    mrt_add_ros_tests() (CMake macro) -
    - - -
    mrt_add_tests() (CMake macro) -
    - - -
    mrt_add_to_ide() (CMake macro) -
    - - -
    mrt_install() (CMake macro) -
    - - -
    mrt_python_module_setup() (CMake macro) -
    - -
    @@ -183,12 +188,12 @@

    Navigation

  • index
  • - +
    \ No newline at end of file diff --git a/mrt_cmake_modules/doc/objects.inv b/mrt_cmake_modules/doc/objects.inv index cc28f0655018cdce21fbfbba947c667d9588630e..42b2afe310d27282b37aef3c4f73cd8f026b103a 100644 GIT binary patch delta 862 zcmV-k1EKtk1<(hONdYsFN;-d~m&5nIjUyg262qj*I$M2LtGv4SkdWs^LZ5iLUzZiVGH=d6+E;hEsSZV1o6L&tWj- zKE#Z9_7EGNQvrV)d>d0AxmJH3&SEZwruzMc9o4VDuN9hs1zm%uwz`4GZU~_@5?=k+ zELBqmjWUsBagZy{CUR4;ejZn|m$6QGlN3fae2S?f4(=^nIBATf9M8ByqI~seC2k?~ zGptq@#@c9U&Z`54!*UO0q;2uQASY$UPHlO8!D6FsL&krWa{0mFCw<`^XXK~V3M-g2 zAP^xEB6HpHwL?_AIeNDS5Q2k zup9S#G9&N&_)Z0nayiHFNczGa%E)>3$MD&|nf$H9;*bM20);s_u%6U_)SMiy&NMjz zFk9`}drMNb)z)HHkFwya2(abtidLe5mx?5v4c5GMWlLtqti52v?{d*gWC#5&1sBQB oYGkToJPsp4#M)){+|y4ZC|keh2C*%sr+=~kudfLH1JMBuDT@=X&j0`b delta 536 zcmV+z0_XkE2aE-fNdYjCN;-eFmP>BiFc60KK81jGI{~`Q4Z0{$AO|35acmQzNRdvUq#;{;H z9tHB{;s^EPX9ov%%LrQj3vKejdS>w)A!wOL=bO|c@84qvN6W25$3B0gzp!JFD(*J= zB+nsArO{2yp#KAPT4dHZCUrdQiTB7(QlTSrMsE3lsc_AlRCX=|!%ysk=SPJUb*a&n zBGpF363R)5Q45n6lD61v zkWY8V2Jb|KnFxspnFtGF$>>S@hK}2iX<(ePb?BoskO$!h)Fk>KNa!QYU9*zNO z5;Nvr5-XpSgwz5*H)c6n9J=4>`4Bt7&erh?(?Z?-CwGiVw3&ZVjc-X5!?!peXv&0h~mqTim)l3wR1iC?uVhZ@}(w*-?Sj(u4!T)vsx zxlC|L@6YxqGjTb-3H&X4#m&>50yYqZOLAu2j{in(Rn5@)``(v9BfVZ|AwVX~PCN92 aLvH)a(xAj@&v^_h8~*Y$9=-tR7v#tzBmi>& diff --git a/mrt_cmake_modules/doc/search.html b/mrt_cmake_modules/doc/search.html index 39cd0919e79..5546b710c8b 100644 --- a/mrt_cmake_modules/doc/search.html +++ b/mrt_cmake_modules/doc/search.html @@ -1,30 +1,29 @@ + - - - Search — mrt_cmake_modules 1.0.0 documentation - + Search — mrt_cmake_modules 1.0.3 documentation - - + + @@ -33,14 +32,14 @@ - + \ No newline at end of file diff --git a/mrt_cmake_modules/doc/searchindex.js b/mrt_cmake_modules/doc/searchindex.js index 0a55b302fb8..48326a0440b 100644 --- a/mrt_cmake_modules/doc/searchindex.js +++ b/mrt_cmake_modules/doc/searchindex.js @@ -1 +1 @@ -Search.setIndex({envversion:46,filenames:["generated_cmake_api"],objects:{"":{"_list_append_deduplicate":[0,0,1,""],"_list_append_unique":[0,0,1,""],"_mrt_register_test":[0,0,1,""],"_pack_libraries_with_build_configuration":[0,0,1,""],"_unpack_libraries_with_build_configuration":[0,0,1,""],generate_ros_interface_files:[0,0,1,""],generate_ros_parameter_files:[0,0,1,""],mrt_add_executable:[0,0,1,""],mrt_add_library:[0,0,1,""],mrt_add_node_and_nodelet:[0,0,1,""],mrt_add_nodelet:[0,0,1,""],mrt_add_nosetests:[0,0,1,""],mrt_add_python_api:[0,0,1,""],mrt_add_ros_tests:[0,0,1,""],mrt_add_tests:[0,0,1,""],mrt_add_to_ide:[0,0,1,""],mrt_install:[0,0,1,""],mrt_python_module_setup:[0,0,1,""]}},objnames:{"0":["cmake","macro","CMake macro"]},objtypes:{"0":"cmake:macro"},terms:{"__init__":0,"_node":0,"_nodelet":0,"import":0,"new":0,"return":0,"true":0,"var":0,absolut:0,access:0,actual:0,add:0,addit:0,after:0,afterward:0,alia:0,all:0,alreadi:0,alwai:0,analysi:0,ani:0,append:0,argument:0,assum:0,auto:0,autogener:0,automat:0,avoid:0,base:0,basenam:0,becom:0,boost:0,boost_python_modul:0,build:0,call:0,can:0,cannot:0,catkin:0,catkin_add_nosetest:0,catkin_download_test_data:0,catkin_librari:0,certain:0,check_test:0,choos:0,cmake_curent_lists_dir:[],cmake_current_list_dir:[],cmake_current_lists_dir:[],comil:0,command:0,commit:0,compabl:0,compil:0,configur:0,conflict:0,contain:0,copi:0,correspond:0,coverag:0,cpp:0,creat:0,custom:0,cwd:0,declar:0,defin:0,depend:0,doe:0,due:0,duplic:0,each:0,element:0,elsewher:0,empti:0,enabl:0,ensur:0,entri:0,everi:0,exampl:0,example_packag:0,execnam:0,execut:0,exist:0,explicitli:0,extern:0,extra:0,fail:0,file:0,first:0,fli:[],folder:0,found:0,from:0,gener:0,generate_cmake_rst:0,gtest:0,hardcod:0,have:0,header:0,hpp:0,identifi:0,ignor:0,impos:0,includ:0,indentifi:0,inform:0,instal:0,intern:0,keep:0,keyword:0,launch:0,launchfil:0,lib:0,libexample_package_nodelet:0,libnam:0,librari:0,link:0,list:0,list_append_dedupl:0,list_append_uniqu:0,listnam:0,locat:0,look:0,made:0,main:0,make:0,mandatori:0,mark:0,messag:0,modul:0,modulenam:0,mrt:0,mrt_add_:0,mrt_cmake_modul:0,mrt_cmake_modulesconfig:0,mrt_enable_covarag:0,mrt_no_fail_on_test:0,myclass2:0,myclass:0,myfile1:0,myfile2:0,myfold:0,mytest:0,name:0,necessari:0,need:0,node:0,nodelet:0,nodelet_plugin:0,nodeletnam:0,nosetest:0,onc:0,onli:0,option:0,other:0,overriden:0,pack:0,packag:0,page:0,paramet:0,pass:0,path:0,per:0,perform:0,pkgconfig:0,place:0,prefix:0,present:0,privat:[],program:0,project:0,project_nam:0,project_source_dir:0,python:0,python_api:0,python_api_module_nam:0,recurs:0,regener:0,regist:0,rel:0,relev:0,remov:0,requir:0,restrict:0,result:0,rosinterface_handl:0,rosparam:0,rostest:0,run:0,run_test:0,same:0,script:0,search:0,self:0,separ:0,seper:0,set:0,setup:0,should:0,shown:0,silent:0,similar:0,simpli:0,sourc:0,specifi:0,src:0,string:0,sub:0,subfold:0,submodul:0,sure:0,target:0,targetnam:0,test:0,test_data:0,thei:0,them:0,thi:0,thu:0,treat:0,txt:0,type:0,under:0,unittest:0,unless:0,unpack:0,variabl:0,visibl:0,warn:0,when:0,within:0,without:0,wrap:0,xml:0,you:0,your:0},titles:["Extracted CMake API reference"],titleterms:{"_list_append_dedupl":0,"_list_append_uniqu":0,"_mrt_register_test":0,"_pack_libraries_with_build_configur":0,"_unpack_libraries_with_build_configur":0,"function":0,"public":0,api:0,cmake:0,content:0,document:0,extract:0,generate_ros_interface_fil:0,generate_ros_parameter_fil:0,macro:0,mrt_add_execut:0,mrt_add_librari:0,mrt_add_node_and_nodelet:0,mrt_add_nodelet:0,mrt_add_nosetest:0,mrt_add_python_api:0,mrt_add_ros_test:0,mrt_add_test:0,mrt_add_to_id:0,mrt_instal:0,mrt_python_module_setup:0,non:0,refer:0}}) \ No newline at end of file +Search.setIndex({docnames:["generated_cmake_api"],envversion:52,filenames:["generated_cmake_api.rst"],objects:{"":{_mrt_add_nosetests_impl:[0,0,1,""],_mrt_create_executable_gtest:[0,0,1,""],_mrt_export_package:[0,0,1,""],_mrt_get_python_destination:[0,0,1,""],_mrt_run_test:[0,0,1,""],_setup_coverage_info:[0,0,1,""],catkin_install_python:[0,0,1,""],catkin_package:[0,0,1,""],catkin_package_xml:[0,0,1,""],generate_ros_interface_files:[0,0,1,""],generate_ros_parameter_files:[0,0,1,""],glob_folders:[0,0,1,""],glob_ros_files:[0,0,1,""],mrt_add_action_files:[0,0,1,""],mrt_add_executable:[0,0,1,""],mrt_add_gtest:[0,0,1,""],mrt_add_library:[0,0,1,""],mrt_add_links:[0,0,1,""],mrt_add_message_files:[0,0,1,""],mrt_add_node_and_nodelet:[0,0,1,""],mrt_add_nodelet:[0,0,1,""],mrt_add_nosetests:[0,0,1,""],mrt_add_python_api:[0,0,1,""],mrt_add_ros_tests:[0,0,1,""],mrt_add_rostest:[0,0,1,""],mrt_add_rostest_gtest:[0,0,1,""],mrt_add_service_files:[0,0,1,""],mrt_add_tests:[0,0,1,""],mrt_add_to_ide:[0,0,1,""],mrt_glob_files:[0,0,1,""],mrt_glob_files_recurse:[0,0,1,""],mrt_glob_folders:[0,0,1,""],mrt_init_testing:[0,0,1,""],mrt_install:[0,0,1,""],mrt_parse_package_xml:[0,0,1,""],mrt_python_module_setup:[0,0,1,""]}},objnames:{"0":["cmake","macro","CMake macro"]},objtypes:{"0":"cmake:macro"},terms:{"export":0,"import":0,"new":0,"return":0,"true":0,But:0,IDEs:0,The:0,Use:0,Will:0,__init__:0,_depend:0,_node:0,_nodelet:0,absolut:0,access:0,action:0,actual:0,add:0,add_action_fil:0,add_message_fil:0,add_service_fil:0,added:0,addit:0,after:0,afterward:0,against:0,alia:0,all:0,allow:0,also:0,alwai:0,analysi:0,ani:0,anoth:0,append:0,argument:0,assum:0,auto:0,autodep:0,autogener:0,automat:0,avoid:0,backward:0,base:0,basenam:0,becom:0,befor:0,boost:0,boost_python_modul:0,bugtrack:0,build:0,build_export:0,call:0,can:0,cannot:0,catkin:0,catkin_add_nosetest:0,catkin_download_test_data:0,catkinmockforconan:0,choos:0,code:0,comil:0,command:0,commit:0,compabl:0,compil:0,configur:0,conflict:0,contain:0,correspond:0,coverag:0,cpp:0,cpp_file:0,creat:0,ctest:0,cuda:0,currect:0,cwd:0,declar:0,defin:0,depend:0,deprec:0,determin:0,devel:0,develspac:0,dir:0,directori:0,directory_list:0,due:0,each:0,elsewher:0,enabl:0,end:0,ensur:0,entri:0,etc:0,everi:0,exampl:0,example_packag:0,excecutable_nam:0,exec:0,execnam:0,execut:0,exist:0,explicitli:0,export_lib:0,exportpackag:0,extension_nam:0,extern:0,extra:0,fail:0,file:0,first:0,flag:0,folder:0,folder_nam:0,form:0,found:0,from:0,garbag:0,gener:0,generate_cmake_rst:0,get:0,glob:0,gtest:0,hardcod:0,have:0,header:0,here:0,hpp:0,identifi:0,ides:0,ignor:0,impos:0,includ:0,indentifi:0,indic:0,info:0,inform:0,instal:0,installspac:0,instead:0,interfac:0,intern:0,its:0,known:0,launch:0,launch_fil:0,launchfil:0,lib:0,libexample_packag:0,libnam:0,librar:0,librari:0,link:0,list:0,local:0,locat:0,longer:0,look:0,made:0,main:0,maintain:0,make:0,mandatori:0,mark:0,mechan:0,mess:0,messag:0,modul:0,modulenam:0,most:0,mrt:0,mrt_:0,mrt_add_:0,mrt_cmake_modul:0,mrt_enable_covarag:0,mrt_no_fail_on_test:0,mrttest:0,must:0,my_target:0,myclass2:0,myclass:0,mytest:0,name:0,necessari:0,need:0,node:0,nodelet:0,nodelet_plugin:0,nodeletnam:0,nosetest:0,onc:0,one:0,onli:0,other:0,output:0,output_var:0,overriden:0,packag:0,package_format:0,package_nam:0,page:0,paramet:0,pars:0,pass:0,path:0,per:0,perform:0,pkt_cmake_dir:0,place:0,present:0,privat:0,program:0,project:0,project_nam:0,project_source_dir:0,project_space_dir:0,projectrootdir:0,python:0,python_api:0,python_api_module_nam:0,recurs:0,recursivli:0,regener:0,rel:0,relev:0,remov:0,replac:0,repositori:0,requir:0,restrict:0,result:0,result_xml_path:0,root:0,rosinterface_handl:0,rosparam:0,rostest:0,run:0,run_test:0,same:0,sanit:0,script:0,search:0,search_directori:0,separ:0,seper:0,servic:0,set:0,setup:0,should:0,silent:0,similar:0,simpli:0,sourc:0,specifi:0,src:0,string:0,sub:0,subfold:0,submodul:0,sure:0,target:0,target_nam:0,targetnam:0,test:0,test_data:0,test_util:0,thei:0,them:0,therefor:0,thi:0,thu:0,time:0,treat:0,type:0,under:0,unittest:0,unless:0,upon:0,url_:0,use:0,used:0,using:0,usual:0,variabl:0,varnam:0,version:0,view:0,visibl:0,wai:0,websit:0,when:0,where:0,within:0,without:0,working_dir:0,wrap:0,xml:0,you:0,your:0},titles:["Extracted CMake API reference"],titleterms:{"function":0,"public":0,Not:0,_mrt_add_nosetests_impl:0,_mrt_create_executable_gtest:0,_mrt_export_packag:0,_mrt_get_python_destin:0,_mrt_run_test:0,_setup_coverage_info:0,api:0,catkin_install_python:0,catkin_packag:0,catkin_package_xml:0,cmake:0,content:0,document:0,extract:0,generate_ros_interface_fil:0,generate_ros_parameter_fil:0,glob_fold:0,glob_ros_fil:0,macro:0,mrt_add_action_fil:0,mrt_add_execut:0,mrt_add_gtest:0,mrt_add_librari:0,mrt_add_link:0,mrt_add_message_fil:0,mrt_add_node_and_nodelet:0,mrt_add_nodelet:0,mrt_add_nosetest:0,mrt_add_python_api:0,mrt_add_ros_test:0,mrt_add_rostest:0,mrt_add_rostest_gtest:0,mrt_add_service_fil:0,mrt_add_test:0,mrt_add_to_id:0,mrt_glob_fil:0,mrt_glob_files_recurs:0,mrt_glob_fold:0,mrt_init_test:0,mrt_instal:0,mrt_parse_package_xml:0,mrt_python_module_setup:0,non:0,refer:0}}) \ No newline at end of file diff --git a/mrt_cmake_modules/package.xml b/mrt_cmake_modules/package.xml index b96f1925b69..ab9e4367ff6 100644 --- a/mrt_cmake_modules/package.xml +++ b/mrt_cmake_modules/package.xml @@ -1,18 +1,45 @@ - + mrt_cmake_modules - 1.0.0 - CMake Functions and Modules which are commonly used by MRT's ROS packages. + 1.0.8 + CMake Functions and Modules for automating CMake - GPL-3.0+ - Piotr Orzechowski - Fabian Poggenhans + BSD + Kevin Rösch + Fabian Poggenhans + Fabian Poggenhans Johannes Beck - https://gitlab.mrt.uni-karlsruhe.de/MRT/mrt_cmake_modules.git + https://github.com/KIT-MRT/mrt_cmake_modules.git + http://wiki.ros.org/mrt_cmake_modules + http://wiki.ros.org/mrt_cmake_modules/issues - catkin - lcov + catkin + ament_cmake_core + gtest_vendor + + ros_environment + ros_environment + lcov + python-catkin-pkg-modules + python3-catkin-pkg-modules + python-yaml + python3-yaml + python-rospkg + python3-rospkg + python-setuptools + python3-setuptools + + + python-catkin-pkg-modules + python3-catkin-pkg-modules + python-yaml + python3-yaml + python-rospkg + python3-rospkg + python-setuptools + python3-setuptools + diff --git a/mrt_cmake_modules/rosdoc.yaml b/mrt_cmake_modules/rosdoc.yaml new file mode 100644 index 00000000000..41b1afcf563 --- /dev/null +++ b/mrt_cmake_modules/rosdoc.yaml @@ -0,0 +1,2 @@ + - builder: sphinx + sphinx_root_dir: doc/generate_doc diff --git a/mrt_cmake_modules/scripts/eval_coverage.py b/mrt_cmake_modules/scripts/eval_coverage.py new file mode 100755 index 00000000000..996f894fdef --- /dev/null +++ b/mrt_cmake_modules/scripts/eval_coverage.py @@ -0,0 +1,153 @@ +#!/usr/bin/env python +# This Python file uses the following encoding: utf-8 +from __future__ import print_function +import subprocess +import sys +import argparse +import shutil +import os +import re + + +def sync_gcno_files(path, build_dir): + # sync the gcno files into this folder + copied_something = False + for root, dirs, files in os.walk(path): + for file in files: + if file.endswith(".gcda"): + file_gcno = file[:len(file) - 4] + "gcno" + gcda_file = os.path.join(root, file_gcno)[len(path):] + if not os.path.exists(gcda_file): + raise Exception("No gcno file found matching {} (expected {})".format(file, gcda_file)) + shutil.copy(gcda_file, os.path.join(root, file_gcno)) + copied_something = True + return copied_something + + +def print_coverage(output, coverage_dir, to_stderr): + regex = re.search(r"\((?P\d*) of (?P\d*) lines\)", output) + lines = int(regex.group("lines")) if regex else 0 + total = int(regex.group("total")) if regex else 0 + # search for python coverage + for file in os.listdir(coverage_dir): + if file.endswith("coverage.xml"): + from xml.dom import minidom + cov_xml = minidom.parse(os.path.join(coverage_dir, file)) + coverage = cov_xml.getElementsByTagName("coverage")[0] + lines += int(coverage.attributes["lines-covered"].value) + total += int(coverage.attributes["lines-valid"].value) + percent = float(lines) / total if total else 1 + file = sys.stderr if to_stderr else sys.stdout + print("\n\033[1mTotal test coverage: {:.2%}\033[0m ({} of {} lines)".format(percent, lines, total), file=file) + + +def is_empty(tracefile): + # lcov only tells us a tracefile is empty when it is too late. + # This function tries to do the check efficently before we pass all tracefiles to lcov. + with open(tracefile) as f: + for line in f: + if line.startswith("DA") or line.startswith("FN"): + return False + return True + + +def build_coverage(args): + if not args.coverage_dir: + return 0 + lcov_baseline = os.path.join(args.coverage_dir, "baseline.lcov") + # check with --summary that the tracefile has valid records + if not os.path.exists(lcov_baseline) or is_empty(lcov_baseline): + print("No C++ coverage files found.") + return 0 + + # evaluate individual coverage + lcovs = [lcov_baseline] + for folder in os.listdir(args.coverage_dir): + path = os.path.join(args.coverage_dir, folder) + lcov_file = path + ".lcov" + has_coverage = sync_gcno_files(path, args.build_dir) + if not has_coverage: + continue + cmd = ["lcov", "-d", path, "-c", "-o", lcov_file, "-t", folder.replace("-", "_"), "-q"] + fail = subprocess.call(cmd) + if not fail and not is_empty(lcov_file): + lcovs.append(lcov_file) + + # build full coverage (including files outside project) + lcov_full = os.path.join(args.coverage_dir, "full_coverage.lcov") + add_args = [] + for lcov in lcovs: + add_args += ("-a", lcov) + cmd = ["lcov", "-o", lcov_full, "-q"] + add_args + fail = subprocess.call(cmd) + if fail: + print("No C++ coverage was generated") + print_coverage("", args.coverage_dir, args.coverage_stderr) + return 0 + + # strip coverage of files outside project + lcov_project = os.path.join(args.coverage_dir, "project_coverage.lcov") + cmd = ["lcov", "-o", lcov_project, "--extract", lcov_full, args.project_dir + "/*", "-q"] + fail = subprocess.call(cmd) + if fail or os.path.getsize(lcov_project) == 0: + # this is most likely because the test did not create any results + print("No C++ coverage was generated") + print_coverage("", args.coverage_dir, args.coverage_stderr) + return 0 + + # build html coverage + html_dir = os.path.join(args.coverage_dir, "coverage") + cmd = ["genhtml", "-o", html_dir, lcov_project, "-s"] + proc = subprocess.Popen(cmd, universal_newlines=True, stdout=subprocess.PIPE) + out, err = proc.communicate() + if proc.returncode: + print("No C++ coverage was generated") + print_coverage("", args.coverage_dir, args.coverage_stderr) + return 0 + + # print & show + print_coverage(out, args.coverage_dir, args.coverage_stderr) + index_html = os.path.join(html_dir, "index.html") + file = sys.stderr if args.coverage_stderr else sys.stdout + print(" Coverage report: file://{}".format(index_html), file=file) + if args.show: + subprocess.call(["firefox", index_html]) + return 0 + + +def main(argv=sys.argv[1:]): + parser = argparse.ArgumentParser( + description='Cleans up results of old tests and coverage runs, initializes coverage counters.') + parser.add_argument('project_dir', help='Path of the project') + parser.add_argument('build_dir', help='The path where cmake was configured') + parser.add_argument('test_results_dir', help='The directory where test results will be written') + parser.add_argument('coverage_dir', nargs='?', default="", help='the directory for the coverage') + parser.add_argument('--show', action='store_true', help='Display results after run') + parser.add_argument('--coverage_stderr', action='store_true', help='Print coverage to stderr instead') + parser.add_argument('--fail_on_test', action='store_true', help='Report failure if tests failed') + args = parser.parse_args(argv) + fail = build_coverage(args) + if fail: + return fail + + # for ros2 we currently don't handle processing the results + if os.environ.get("ROS_VERSION", "1") == "2": + return 0 + + # print unittests + with open(os.devnull, "w") as f: + has_ccat = subprocess.call(["which", "pygmentize"], stdout=f, stderr=f) == 0 + ccat_cmd = " | pygmentize" if has_ccat else "" + verbose = " --verbose" if args.coverage_stderr else "" + to_err = " 1>&2" if args.coverage_stderr else "" + cmd = '/bin/bash -c "set -o pipefail; catkin_test_results{} {}{}{}"'.format( + verbose, args.test_results_dir, ccat_cmd, to_err) + fail = subprocess.call(cmd, shell=True) + sys.stderr.write("\n") + if args.fail_on_test: + return fail + return 0 + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py b/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py index a9be5b88fbb..71e5c620970 100755 --- a/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py +++ b/mrt_cmake_modules/scripts/generate_cmake_dependency_file.py @@ -18,12 +18,19 @@ import os import sys import subprocess -import distro as dist -import xml.etree.ElementTree as ET +from rospkg.os_detect import OsDetect import yaml from catkin_pkg.packages import find_packages - -import sys +from string import Template +try: + import xml.etree.cElementTree as ET +except ImportError: + import xml.etree.ElementTree as ET +try: + from yaml import CLoader as Loader +except ImportError: + from yaml import Loader +eval_expr = eval def eprint(*args, **kwargs): @@ -43,9 +50,12 @@ class Dependency: build_export_depend = False test_depend = False + def isCatkin(self): + return self.packageType == PackageType.catkin + def __repr__(self): - return "Dependency(name:%s type:%s buld_depend:%s build_export_depend:%s test_depend:%s)" % (self.name, self.packageType, self.build_depend, - self.build_export_depend, self.test_depend) + return "Dependency(name:%s type:%s buld_depend:%s build_export_depend:%s test_depend:%s)" % ( + self.name, self.packageType, self.build_depend, self.build_export_depend, self.test_depend) class PackageCMakeData: @@ -63,16 +73,24 @@ class PackageCMakeData: components = list() """contains the components, which are used in find_package (e.g. defined by a call to find_package( COMPONENTS ...))""" - def __init__(self, data): + targets = list() + """contains the targets which are defined when calling find_package(...)""" + + def __init__(self, data={}): """Init cmake package data from a dict""" - self.name = data["name"] - self.includeDirs = data["include_dirs"] + self.name = data.get("name", "") + self.includeDirs = data.get("include_dirs", list()) self.libraryDirs = data.get("library_dirs", list()) self.libraries = data.get("libraries", list()) self.components = data.get("components", list()) + self.targets = data.get("targets", list()) + self.warning = data.get("warning", "") + + def __nonzero__(self): + return bool(self.name) def __repr__(self): - return "PackageCMakeData(name:" + self.name + " include_dirs:" + str(self.includeDirs) + " librariy_dirs:" + \ + return "PackageCMakeData(name:" + self.name + " include_dirs:" + str(self.includeDirs) + " library_dirs:" + \ str(self.libraryDirs) + " libraries:" + \ str(self.libraries) + " components:" + str(self.components) @@ -105,50 +123,107 @@ def findWorkspaceRoot(packageXmlFilename): def readPackageCMakeData(rosDebYamlFileName): """ - Read the cmake meta data for packages from a rosdep yaml file. - The yaml file format is extended with a cmake node: + Read the cmake meta data for packages from a cmake yaml file: package1: - ubuntu: [ ... ] - cmake: xenial/trusty: - name: ... - include_dirs: [] - library_dirs: [] - libraries: [] - components: [] + name: ... + include_dirs: [] + library_dirs: [] + libraries: [] + components: [] """ # load ros dep yaml file f = open(rosDebYamlFileName, "r") - rosDebYamlData = yaml.safe_load(f) + rosDebYamlData = yaml.load(f, Loader=Loader) # dictionary for storing cmake dependencies # e.g. { "" -> PackageCMakeData, "" -> PackageCMakeData ... } data = {} + distribution = OsDetect().detect_os()[2] + for packageName, packageCMakeData in rosDebYamlData.items(): - # check if cmake part is available. There could also be entries with no - # cmake part (only ubuntu, etc.) - if "cmake" in packageCMakeData: - # find out which distribution - distro = dist.linux_distribution()[2] - if 'ROS_OS_OVERRIDE' in os.environ: - ros_os_override = os.environ['ROS_OS_OVERRIDE'].split(':') - if len(ros_os_override) == 2: - distro = ros_os_override[1] - - if "name" in packageCMakeData["cmake"]: - data[packageName] = PackageCMakeData(packageCMakeData["cmake"]) - elif distro in packageCMakeData["cmake"]: - data[packageName] = PackageCMakeData( - packageCMakeData["cmake"][distro]) + # find out which distribution + if "name" in packageCMakeData: + data[packageName] = PackageCMakeData(packageCMakeData) + elif distribution in packageCMakeData: + data[packageName] = PackageCMakeData(packageCMakeData[distribution]) + elif not packageCMakeData: + data[packageName] = PackageCMakeData() # placeholder return data +def parseManifest(parsed_xml, catkin_packages): + # check catkin package xml file + if parsed_xml.tag != 'package': + raise Exception("Cannot find package node in xml file") + if 'format' not in parsed_xml.attrib: + raise Exception( + "Catkin package format must be 2. Change package.xml to ") + if not (parsed_xml.attrib['format'] == "2" or parsed_xml.attrib['format'] == "3"): + raise Exception("Package format must be 2 or 3") + + # variable used to hold the Dependency classes from the package xml + depends = [] + cuda_depends = [] + + for child in parsed_xml: + depend = Dependency() + + # check conditions + condition = child.get("condition") + if condition: + import re + # according to REP149, unquoted literals are also strings, except and and or + expr = Template(condition).substitute(os.environ) + quote_literals = lambda m: m.group(0) if m.group(0).startswith(('"', "'")) or m.group(0) in ("or", "and") else '"{}"'.format(m.group(0)) + expr = re.sub(r'"?\'?([a-zA-Z-_]+)', quote_literals, expr) + is_fulfilled = eval_expr(expr) + if not is_fulfilled: + continue + + # check tag + if child.tag == "depend": + depend.build_depend = True + depend.build_export_depend = True + depend.test_depend = True + elif child.tag == "build_depend": + depend.build_depend = True + depend.build_export_depend = False + depend.test_depend = False + elif child.tag == "build_export_depend": + depend.build_depend = True + depend.build_export_depend = True + depend.test_depend = False + elif child.tag == "test_depend": + depend.build_depend = False + depend.build_export_depend = False + depend.test_depend = True + elif child.tag == "export": + for export_child in child: + if export_child.tag == "cuda_depend": + cuda_depends.append(export_child.text) + continue + else: + continue + + # get name + depend.name = child.text + + # check if catkin package + depend.packageType = PackageType.catkin if depend.name in catkin_packages else PackageType.other + + depends.append(depend) + return depends, cuda_depends + + def getCatkinPackages(workspaceRoot): """Get all available catkin packages""" manifest = "package.xml" catkin_ignore = "CATKIN_IGNORE" + catkin_marker = ".catkin" nosubdirs = "rospack_nosubdirs" - ros_package_env = "ROS_PACKAGE_PATH" + ros2 = os.environ.get("ROS_VERSION", "1") == "2" + cmake_env = "CMAKE_PREFIX_PATH" if not ros2 else "AMENT_PREFIX_PATH" def getPackagesInPath(packages, path): for root, dirs, files in os.walk(path, topdown=True, followlinks=True): @@ -160,21 +235,38 @@ def getPackagesInPath(packages, path): export = package.find("export") # ignore metapackages if export is None or export.find("metapackage") is None: - name = package.get("name", default=os.path.basename(root)) - packages.add(name) + name = package.find("name").text + if name not in packages: + packages[name] = package dirs[:] = [] continue if nosubdirs in files: dirs[:] = [] # package is tagged to not recurse continue - package_paths = set() - paths = os.environ.get(ros_package_env, "").split(":") - paths.append(workspaceRoot) - packages = set() - for path in paths: + def getWorkspacesInPath(path, workspaces): + # in ros2 every path is a package, no need to search markerfiles + if ros2: + workspaces.append(path) + return + markerfile = os.path.join(path, catkin_marker) + if not os.path.isfile(markerfile): + return + with open(markerfile) as f: + data = f.read() + if not data: + # catkin_marker contains no refernce to a source dir, the whole path is a ws + workspaces.append(path) + return + workspaces += data.split(";") + workspaces = [] + for path in os.environ.get(cmake_env, '').split(os.pathsep): + getWorkspacesInPath(path, workspaces) + + packages = {} + for path in set(workspaces): getPackagesInPath(packages, path) - return list(packages) + return packages def main(packageXmlFile, rosDepYamlFileName, outputFile): @@ -192,17 +284,8 @@ def main(packageXmlFile, rosDepYamlFileName, outputFile): @param[out] outputFile: File name to the generated cmake file """ # read package xml file - tree = ET.parse(packageXmlFile) - - # check catkin package xml file - root = tree.getroot() - if root.tag != 'package': - raise Exception("Cannot find package node in xml file") - if 'format' not in root.attrib: - raise Exception( - "Catkin package format must be 2. Change package.xml to ") - if root.attrib['format'] != "2": - raise Exception("Package format must be 2") + tree = ET.parse(packageXmlFile).getroot() + pkg_name = tree.find("name").text # get all catkin packages to distinguish between # catkin and non-catkin packages @@ -212,131 +295,52 @@ def main(packageXmlFile, rosDepYamlFileName, outputFile): # to automatically create a find_package(...) cmakeVarData = readPackageCMakeData(rosDepYamlFileName) - # variable used to hold the Dependency classes from the package xml - depends = [] - cuda_depends = [] - - for child in root: - depend = Dependency() - - # check tag - if child.tag == "depend": - depend.build_depend = True - depend.build_export_depend = True - depend.test_depend = True - elif child.tag == "build_depend": - depend.build_depend = True - depend.build_export_depend = False - depend.test_depend = False - elif child.tag == "build_export_depend": - depend.build_depend = True - depend.build_export_depend = True - depend.test_depend = False - elif child.tag == "test_depend": - depend.build_depend = False - depend.build_export_depend = False - depend.test_depend = True - elif child.tag == "export": - for export_child in child: - if export_child.tag == "cuda_depend": - cuda_depends.append(export_child.text) - else: - continue - - # get name - depend.name = child.text - - # check if catkin package - if depend.name in catkin_packages: - depend.packageType = PackageType.catkin - else: - depend.packageType = PackageType.other - - depends.append(depend) - + depends, cuda_depends = parseManifest(tree, catkin_packages) # check CUDA depends and categorize them as either catkin or other package depends_names = {d.name for d in depends} - cuda_catkin_depends = [] - cuda_other_depends = [] for cuda_depend in cuda_depends: if cuda_depend not in depends_names: raise Exception(("CUDA package {0} specified as dependency but not specified " "as regular . Please add a depend like {0}" " to your package.xml.").format(cuda_depend)) - if cuda_depend in catkin_packages: - cuda_catkin_depends.append(cuda_depend) - else: - cuda_other_depends.append(cuda_depend) + # output variables + out = {} + out["dependend_packages"] = " ".join(depend.name for depend in depends) + out["catkin_pkgs"] = " ".join(s.name for s in depends if s.isCatkin()) + out["pkgs"] = " ".join(s.name for s in depends if s.build_depend) + out["exp_pkgs"] = " ".join(s.name for s in depends if s.build_export_depend) + out["test_pkgs"] = " ".join(s.name for s in depends if s.test_depend) + out["cuda_pkgs"] = " ".join(cuda_depends) + out["pkg_name"] = pkg_name # generate output file f = open(outputFile, "w") - # write auto generate content - f.write("#This is an autogenerated file. Do not edit!\n") - f.write("#Changes will be overritten the next time cmake runs.\n") - f.write("\n") - - # write all dependend packages - packages = set() - for depend in depends: - packages.add(depend.name) - - f.write("set(DEPENDEND_PACKAGES %s)\n" % ' '.join(packages)) + text = ("#This is an autogenerated file. Do not edit!\n" + "#Changes will be overritten the next time cmake runs.\n" + "\n" + "set(DEPENDEND_PACKAGES $dependend_packages)\n" + "set(_${pkg_name}_CATKIN_PACKAGES_ $catkin_pkgs)\n" + "set(_${pkg_name}_PACKAGES_ $pkgs)\n" + "set(_${pkg_name}_EXPORT_PACKAGES_ $exp_pkgs)\n" + "set(_${pkg_name}_TEST_PACKAGES_ $test_pkgs)\n" + ) - # write catkin packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.catkin and s.build_depend == True): - packages.add(depend.name) - - f.write("set(_CATKIN_PACKAGES_ %s)\n" % ' '.join(packages)) - - # write catkin export packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.catkin and s.build_export_depend == True): - packages.add(depend.name) - - f.write("set(_CATKIN_EXPORT_PACKAGES_ %s)\n" % ' '.join(packages)) - - # write catkin test packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.catkin and s.test_depend == True): - packages.add(depend.name) - - f.write("set(_CATKIN_TEST_PACKAGES_ %s)\n" % ' '.join(packages)) - - # write non-catkin packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.other and s.build_depend == True): - packages.add(depend.name) - - f.write("set(_OTHER_PACKAGES_ %s)\n" % ' '.join(packages)) - - # write non-catkin export packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.other and s.build_export_depend == True): - packages.add(depend.name) - - f.write("set(_OTHER_EXPORT_PACKAGES_ %s)\n" % ' '.join(packages)) - - # write non-catkin test packages - packages = set() - for depend in (s for s in depends if s.packageType == PackageType.other and s.test_depend == True): - packages.add(depend.name) - - f.write("set(_OTHER_TEST_PACKAGES_ %s)\n" % ' '.join(packages)) + f.write(Template(text).substitute(out)) # write CUDA catkin / other packages - if cuda_catkin_depends: - f.write("set(_CUDA_CATKIN_PACKAGES_ %s)\n" % - ' '.join(cuda_catkin_depends)) - if cuda_other_depends: - f.write("set(_CUDA_OTHER_PACKAGES_ %s)\n" % - ' '.join(cuda_other_depends)) + if cuda_depends: + f.write(Template("set(_${pkg_name}_CUDA_PACKAGES_ $cuda_pkgs)\n").substitute(out)) # write cmake variables (only those which are used in this package) for depend in (s for s in depends if s.name in cmakeVarData): cmakeData = cmakeVarData[depend.name] + if not cmakeData: + # package needs no cmake definition + f.write("set(_{}_NO_CMAKE_ 1)\n".format(depend.name)) + continue + f.write("set(_" + depend.name + "_CMAKE_NAME_ " + cmakeData.name + ")\n") if cmakeData.includeDirs: f.write("set(_" + depend.name + "_CMAKE_INCLUDE_DIRS_ " + @@ -350,11 +354,13 @@ def main(packageXmlFile, rosDepYamlFileName, outputFile): if cmakeData.components: f.write("set(_" + depend.name + "_CMAKE_COMPONENTS_ " + ' '.join(cmakeData.components) + ")\n") + if cmakeData.targets: + f.write("set(_" + depend.name + "_CMAKE_TARGETS_ " + + ' '.join(cmakeData.targets) + ")\n") + if cmakeData.warning: + eprint(cmakeData.warning) if __name__ == "__main__": - try: - main(sys.argv[1], sys.argv[2], sys.argv[3]) - except BaseException as e: - eprint(str(e)) - sys.exit(1) + print("called: {}".format(" ".join(sys.argv))) + main(sys.argv[1], sys.argv[2], sys.argv[3]) diff --git a/mrt_cmake_modules/scripts/generate_cmakelists.py b/mrt_cmake_modules/scripts/generate_cmakelists.py new file mode 100755 index 00000000000..28549efbc17 --- /dev/null +++ b/mrt_cmake_modules/scripts/generate_cmakelists.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python +# This Python file uses the following encoding: utf-8 +import argparse +import os +import sys +import subprocess + +parser = argparse.ArgumentParser(description='Generates a CMakeLists.txt for a project.') +parser.add_argument('package_name', type=str, help='name of the package') +parser.add_argument('-r', '--ros', action='store_true', help='add ROS support (messages, ...)') +parser.add_argument('-e', '--exe', action='store_true', help='create an executable/node package') +args = parser.parse_args() + +# figure out where the template file is +currdir = os.path.dirname(os.path.abspath(__file__)) +devel_template = os.path.join(currdir, "../ci_templates/CMakeLists.txt") +install_template = os.path.join(currdir, "../../share/mrt_cmake_modules/CMakeLists.txt") +if os.path.exists(devel_template): + template = devel_template +elif os.path.exists(install_template): + template = install_template +else: + print("Failed to find the CMakeLists template file. Was this script moved?") + sys.exit(1) + +pattern = "@" +if args.ros: + pattern += ".x" +else: + pattern += "x." +pattern += "|" + +if not args.exe: + pattern += "x.@" +else: + pattern += ".x@" + +with open("CMakeLists.txt", "w") as file: + with open(template) as template_file: + file.write(template_file.read()) + +subprocess.call("sed -i " + + "-e 's/^" + pattern + " //g' " + + "-e '/^@..|..@/d' " + + r"-e 's/\${CMAKE_PACKAGE_NAME}/" + args.package_name + "/g' " + + "CMakeLists.txt", shell=True) diff --git a/mrt_cmake_modules/scripts/init_coverage.py b/mrt_cmake_modules/scripts/init_coverage.py new file mode 100755 index 00000000000..9209023728e --- /dev/null +++ b/mrt_cmake_modules/scripts/init_coverage.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python +# This Python file uses the following encoding: utf-8 +import subprocess +import sys +import argparse +import shutil +import os + + +def get_source_file(gcno_file, build_dir): + # the gcno path should have the structure: /CMakeFiles//.gcno. + # We want to extract the sourcepath part + relpath = os.path.relpath(gcno_file, os.path.join(build_dir, "CMakeFiles")) + return os.path.join(*(relpath.rstrip(".gcno").split(os.path.sep)[1:])) + + +def cleanup_orphaned_gcnos(build_dir, project_dir): + # cmake does not delete gcno files after their source file is gone. this confuses lcov. + for root, dirs, files in os.walk(os.path.join(build_dir, "CMakeFiles")): + for file in files: + if not file.endswith(".gcno"): + continue + gcno_file = os.path.join(root, file) + src_file = os.path.join(project_dir, get_source_file(gcno_file, build_dir)) + if not os.path.exists(src_file): + print("Removing orphaned {}".format(file)) + os.remove(gcno_file) + + +def main(argv=sys.argv[1:]): + parser = argparse.ArgumentParser( + description='Cleans up results of old tests and coverage runs, initializes coverage counters.') + parser.add_argument('project_name', help='Name of the project') + parser.add_argument('build_dir', help='The path where cmake was configured') + parser.add_argument('project_dir', help='Path to the project') + parser.add_argument('test_results_dir', help='The directory where test results will be written') + parser.add_argument('coverage_dir', nargs='?', default="", help='the directory for the coverage') + args = parser.parse_args(argv) + + test_dir = os.path.join(args.test_results_dir) + print("Removing {}".format(test_dir)) + if os.path.exists(test_dir): + shutil.rmtree(test_dir) + os.makedirs(test_dir) + + if not args.coverage_dir: + return + + if os.path.exists(args.coverage_dir): + print("Removing {}".format(args.coverage_dir)) + shutil.rmtree(args.coverage_dir) + if os.path.exists(args.build_dir): + cleanup_orphaned_gcnos(args.build_dir, args.project_dir) + os.mkdir(args.coverage_dir) + out_file = os.path.join(args.coverage_dir, "baseline.lcov") + cmd = ["lcov", "-i", "-c", "-o", out_file, "--directory", args.build_dir, "-q"] + print("Initializing counters") + return subprocess.call(cmd) + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/mrt_cmake_modules/scripts/run_test.py b/mrt_cmake_modules/scripts/run_test.py new file mode 100644 index 00000000000..8c517bc075d --- /dev/null +++ b/mrt_cmake_modules/scripts/run_test.py @@ -0,0 +1,128 @@ +#!/usr/bin/env python +# This Python file uses the following encoding: utf-8 +from __future__ import print_function +import argparse +import os +import sys +import subprocess +import sys +try: + import xml.etree.cElementTree as ET +except ImportError: + import xml.etree.ElementTree as ET + + +def get_missing_junit_result_filename(filename): + return os.path.join(os.path.dirname(filename), 'MISSING-%s' % os.path.basename(filename)) + + +def remove_junit_result(filename): + # if result file exists remove it before test execution + if os.path.exists(filename): + os.remove(filename) + # if placeholder (indicating previous failure) exists remove it before test execution + missing_filename = get_missing_junit_result_filename(filename) + if os.path.exists(missing_filename): + os.remove(missing_filename) + + +def ensure_junit_result_exist(filename, errors): + if os.path.exists(filename): + # if result file exists ensure that it contains valid xml + try: + ET.parse(filename) + except ParseError: + from catkin.tidy_xml import tidy_xml + tidy_xml(filename) + try: + ET.parse(filename) + except ParseError as e: + print("Invalid XML in result file '%s' (even after trying to tidy it): %s " % (filename, str(e)), file=sys.stderr) + return True + # if result file does not exist create placeholder which indicates failure + missing_filename = get_missing_junit_result_filename(filename) + print("Cannot find results, writing failure results to '%s'" % missing_filename, file=sys.stderr) + # create folder if necessary + if not os.path.exists(os.path.dirname(filename)): + try: + os.makedirs(os.path.dirname(filename)) + except OSError as e: + # catch case where folder has been created in the mean time + if e.errno != errno.EEXIST: + raise + cdata = "".format(errors) if errors else "" + cdata = cdata.replace("\033", "") + with open(missing_filename, 'w') as f: + data = {'test': os.path.basename(filename), 'test_file': filename, 'cdata': cdata} + f.write( + ('\n' + '\n' + ' \n' + ' ' + '%(cdata)s' + ' \n' + ' \n' + '\n') % + data) + return False + + +def main(argv=sys.argv[1:]): + parser = argparse.ArgumentParser( + description='Runs the test command passed as an argument and verifies that the expected result file has been generated.') + parser.add_argument('results', help='The path to the xunit result file') + parser.add_argument('command', nargs='+', help='The test command to execute') + parser.add_argument('--working-dir', nargs='?', help='The working directory for the executed command') + parser.add_argument('--coverage-dir', nargs='?', help='The directory where coverage data should be generated') + parser.add_argument( + '--return-code', + action='store_true', + help='Set the return code based on the success of the test command') + parser.add_argument('--redirect-stderr', action='store_true', help='Redirect stderr to stdout') + args = parser.parse_args(argv) + + remove_junit_result(args.results) + + try: + os.mkdir(os.path.dirname(args.results)) + except OSError: + pass + + work_dir_msg = ' with working directory "%s"' % args.working_dir if args.working_dir is not None else '' + cmds_msg = ''.join(['\n %s' % cmd for cmd in args.command]) + print('-- run_test.py: execute commands%s%s' % (work_dir_msg, cmds_msg)) + + if args.coverage_dir: + env = os.environ.copy() + print("Coverage goes to {}".format(args.coverage_dir)) + env['GCOV_PREFIX'] = args.coverage_dir + if not os.path.exists(args.coverage_dir): + os.mkdir(args.coverage_dir) + else: + env = os.environ + + rc = 0 + errors = [] + for cmd in args.command: + stream = sys.stderr if not args.redirect_stderr else sys.stdout + proc = subprocess.Popen(cmd + " | tee", cwd=args.working_dir, shell=True, env=env, stderr=subprocess.PIPE, universal_newlines=True) + stdout, stderr = proc.communicate() + if stderr: + print(stderr, file=stream) + errors.append(stderr) + if proc.returncode: + rc = proc.returncode + break + + print('-- run_test.py: verify result "%s"' % args.results) + exists = ensure_junit_result_exist(args.results, u"\n".join(errors)) + if not exists: + rc = 1 + + if args.return_code: + return rc + return 0 + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/mrt_cmake_modules/setup.py b/mrt_cmake_modules/setup.py deleted file mode 100644 index 17ff5017cf9..00000000000 --- a/mrt_cmake_modules/setup.py +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/env python3 - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup( - packages=['mrt_cmake_modules'], - package_dir={'': 'src'}, - requires=[] -) - -setup(**d) diff --git a/mrt_cmake_modules/src/mrt_cmake_modules/parameter_generator_catkin.py b/mrt_cmake_modules/src/mrt_cmake_modules/parameter_generator_catkin.py deleted file mode 100644 index fc39698e2c0..00000000000 --- a/mrt_cmake_modules/src/mrt_cmake_modules/parameter_generator_catkin.py +++ /dev/null @@ -1,3 +0,0 @@ -import rosparam_handler.parameter_generator_catkin - -ParameterGenerator = rosparam_handler.parameter_generator_catkin.ParameterGenerator \ No newline at end of file diff --git a/mrt_cmake_modules/yaml/base-vanilla.yaml b/mrt_cmake_modules/yaml/base-vanilla.yaml deleted file mode 100644 index 588cf5b250c..00000000000 --- a/mrt_cmake_modules/yaml/base-vanilla.yaml +++ /dev/null @@ -1,453 +0,0 @@ -aravis: - cmake: - include_dirs: - - Aravis_INCLUDE_DIRS - libraries: - - Aravis_LIBRARIES - library_dirs: [] - name: Aravis -boost: - cmake: - components: - - math_c99l wserialization math_tr1l thread random serialization log_setup prg_exec_monitor - wave system chrono math_c99 filesystem context locale timer math_tr1 - date_time regex graph program_options unit_test_framework math_tr1f math_c99f - log atomic - include_dirs: - - Boost_INCLUDE_DIRS - libraries: - - Boost_LIBRARIES - library_dirs: - - Boost_LIBRARY_DIRS - name: Boost -cuda: - cmake: - components: [] - include_dirs: - - CUDA_INCLUDE_DIRS - libraries: - - CUDA_LIBRARIES - library_dirs: [] - name: CUDA -ebus: - cmake: - components: [] - include_dirs: - - ebus-sdk_INCLUDE_DIRS - libraries: - - ebus-sdk_LIBRARIES - library_dirs: [] - name: ebus-sdk -eigen: - cmake: - components: [] - include_dirs: - - EIGEN3_INCLUDE_DIR - libraries: [] - library_dirs: [] - name: Eigen3 -eigen2: - cmake: - include_dirs: - - EIGEN2_INCLUDE_DIR - libraries: [] - name: Eigen2 -freeglut3-dev: - ubuntu: - - freeglut3-dev -glut: - cmake: - components: [] - include_dirs: - - GLUT_INCLUDE_DIR - libraries: - - GLUT_LIBRARIES - library_dirs: [] - name: GLUT -gpsd: - ubuntu: - - gpsd -gtest: - cmake: - include_dirs: - - gtest_INCLUDE_DIRS - libraries: - - gtest_LIBRARIES - name: gtest -gtest-headers: - cmake: - include_dirs: - - GTest-headers_INCLUDE_DIRS - libraries: [] - name: GTest-headers - ubuntu: - - libgtest-dev -gtestsrc: - cmake: - include_dirs: [] - libraries: - - GTEST_LIBRARIES - name: MrtGTest - ubuntu: - - libgtest-dev -gtkmm: - cmake: - components: [] - include_dirs: - - GTKMM_INCLUDE_DIRS - libraries: - - GTKMM_LIBRARIES - library_dirs: - - GTKMM_LIBRARY_DIRS - name: GTKMM - ubuntu: - - libgtkmm-3.0-dev -lcov: - ubuntu: - - lcov -libcairo2-dev: - cmake: - components: [] - include_dirs: - - CAIRO_INCLUDE_DIRS - libraries: - - CAIRO_LIBRARIES - library_dirs: [] - name: Cairo -libgoogle-glog-dev: - cmake: - components: [] - include_dirs: - - GLOG_INCLUDE_DIRS - libraries: - - GLOG_LIBRARY - library_dirs: [] - name: Glog -libgps: - cmake: - include_dirs: - - LIBGPS_INCLUDE_DIR - libraries: - - LIBGPS_LIBRARY - name: libgps -libgsl: - cmake: - components: [] - include_dirs: - - GSL_INCLUDE_DIRS - libraries: - - GSL_LIBRARIES - library_dirs: - - GSL_LINK_DIRECTORIES - name: GSL -liblapack-dev: - cmake: - include_dirs: [] - libraries: - - LAPACK_LIBRARIES - name: LAPACK -libmagick: - cmake: - components: - - Magick++ MagickWand MagickCore - include_dirs: - - ImageMagick_INCLUDE_DIRS - libraries: - - ImageMagick_LIBRARIES - name: ImageMagick -libopenscenegraph: - cmake: - components: - - osg osgAnimation osgDB osgFX osgGA osgManipulator osgParticle osgPresentation - osgQt osgShadow osgSim osgTerrain osgText osgUtil osgViewer osgVolume osgWidget - include_dirs: - - OPENSCENEGRAPH_INCLUDE_DIRS - libraries: - - OPENSCENEGRAPH_LIBRARIES - library_dirs: [] - name: OpenSceneGraph -libpcap-dev: - cmake: - include_dirs: - - PCAP_INCLUDE_DIR - libraries: - - PCAP_LIBRARY - name: PCAP -libqwt5-qt4-dev: - cmake: - components: [] - include_dirs: - - QWT_INCLUDE_DIRS - libraries: - - QWT_LIBRARIES - library_dirs: [] - name: Qwt -libsqlite3-dev: - cmake: - components: [] - include_dirs: - - SQLITE3_INCLUDE_DIRS - libraries: - - SQLITE3_LIBRARIES - library_dirs: [] - name: Sqlite3 -libudev-dev: - ubuntu: - - libudev-dev -libxext-dev: - ubuntu: - - libxext-dev -libxrandr-dev: - ubuntu: - - libxrandr-dev -mesa-common-dev: - ubuntu: - - mesa-common-dev -mrt_ann: - cmake: - components: [] - include_dirs: - - ANN_INCLUDE_DIR - libraries: - - ANN_LIBRARIES - library_dirs: [] - name: MrtANN -mrt_caffe: - cmake: - components: [] - include_dirs: - - Caffe_INCLUDE_DIRS - libraries: - - Caffe_LIBRARIES - library_dirs: [] - name: MrtCaffe -mrt_cereal: - cmake: - components: [] - include_dirs: - - Cereal_INCLUDE_DIR - libraries: [] - library_dirs: [] - name: MrtCereal -mrt_ceres: - cmake: - components: [] - include_dirs: - - CERES_INCLUDE_DIRS - libraries: - - CERES_LIBRARIES - library_dirs: [] - name: MrtCeres -mrt_cgal: - cmake: - components: [] - include_dirs: - - CGAL_INCLUDE_DIRS - libraries: - - CGAL_LIBRARIES - library_dirs: [] - name: MrtCGAL -mrt_ebus: - cmake: - components: [] - include_dirs: - - ebus-sdk_INCLUDE_DIR - libraries: - - ebus-sdk_LIBRARIES - library_dirs: [] - name: Mrtebus-sdk -mrt_f2c_old: - cmake: - components: [] - include_dirs: - - f2c_INCLUDE_DIR - libraries: - - f2c_LIBRARIES - library_dirs: [] - name: Mrtf2c -mrt_leptonica: - cmake: - components: [] - include_dirs: - - Leptonica_INCLUDE_DIR - libraries: - - Leptonica_LIBRARIES - library_dirs: [] - name: MrtLeptonica -mrt_metis: - cmake: - components: [] - include_dirs: - - Metis_INCLUDE_DIR - libraries: - - Metis_LIBRARIES - library_dirs: [] - name: MrtMetis -mrt_nlopt: - cmake: - components: [] - include_dirs: - - nlopt_INCLUDE_DIR - libraries: - - nlopt_LIBRARIES - library_dirs: [] - name: Mrtnlopt -mrt_opencv: - cmake: - components: [] - include_dirs: - - OpenCV_INCLUDE_DIRS - libraries: - - OpenCV_LIBS - library_dirs: [] - name: MrtOpenCV -mrt_pcl: - cmake: - components: [] - include_dirs: - - PCL_INCLUDE_DIRS - libraries: - - PCL_LIBRARIES - library_dirs: - - PCL_LIBRARY_DIRS - name: MrtPCL -mrt_qt4-dev: - cmake: - components: - - Qt5Core Qt5Gui Qt5DBus Qt5Network Qt5OpenGL Qt5OpenGLExtensions Qt5Sql Qt5Test Qt5Xml Qt5Widgets Qt5Concurrent - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt5 -mrt_qt-dev: - cmake: - trusty: - components: - - QtCore QTGui Qt3Support QtDBus QtDesigner QtDesignerComponents QtHelp QtNetwork - QtOpenGL QtScript QtScriptTools QtSql QtSvg QtTest QtUiTools QtWebKit QtXml - QtXmlPatterns - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt4 - xenial: - components: - - Qt5Core Qt5Gui Qt5DBus Qt5Network Qt5OpenGL Qt5OpenGLExtensions Qt5Sql Qt5Test Qt5Xml Qt5Widgets Qt5Concurrent - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt5 - bionic: - components: - - Qt5Core Qt5Gui Qt5DBus Qt5Network Qt5OpenGL Qt5OpenGLExtensions Qt5Sql Qt5Test Qt5Xml Qt5Widgets Qt5Concurrent - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt5 - ubuntu: - trusty: - - libqt4-dev - xenial: - - qt5-default -mrt_suitesparse: - cmake: - components: [] - include_dirs: - - SUITESPARSE_INCLUDE_DIRS - libraries: - - SUITESPARSE_LIBRARIES - library_dirs: [] - name: MrtSuiteSparse -mrt_tesseract: - cmake: - components: [] - include_dirs: - - Tesseract_INCLUDE_DIR - libraries: - - Tesseract_LIBRARIES - library_dirs: [] - name: MrtTesseract -mrt_vtk: - cmake: - components: [] - include_dirs: - - VTK_INCLUDE_DIRS - libraries: - - VTK_LIBRARIES - library_dirs: [] - name: MrtVTK -opencv: - cmake: - components: [] - include_dirs: - - OpenCV_INCLUDE_DIRS - libraries: - - OpenCV_LIBS - library_dirs: [] - name: OpenCV - ubuntu: - - libopencv-dev -opengl: - cmake: - components: [] - include_dirs: - - OPENGL_INCLUDE_DIR - libraries: - - OPENGL_LIBRARIES - library_dirs: [] - name: OpenGL -png: - cmake: - components: [] - include_dirs: - - PNG_INCLUDE_DIRS - libraries: - - PNG_LIBRARIES - library_dirs: [] - name: PNG - ubuntu: - - libpng12-dev -png++: - cmake: - components: [] - include_dirs: - - PNG++_INCLUDE_DIRS - libraries: [] - library_dirs: [] - name: PNG++ - ubuntu: - - libpng++-dev -poco: - cmake: - components: - - XML Zip Crypto Data Net - include_dirs: - - Poco_INCLUDE_DIRS - libraries: - - Poco_LIBRARIES - library_dirs: [] - name: Poco - ubuntu: - - libpoco-dev -python-gdal: - ubuntu: - - python-gdal -python-vte: - ubuntu: - - python-vte -uuid-dev: - ubuntu: - - uuid-dev -yaml-cpp: - cmake: - components: [] - include_dirs: - - yaml-cpp_INCLUDE_DIRS - libraries: - - yaml-cpp_LIBRARIES - library_dirs: [] - name: yaml-cpp diff --git a/mrt_cmake_modules/yaml/base.yaml b/mrt_cmake_modules/yaml/base.yaml deleted file mode 100644 index 7eec4c69008..00000000000 --- a/mrt_cmake_modules/yaml/base.yaml +++ /dev/null @@ -1,797 +0,0 @@ -aravis: - cmake: - include_dirs: - - Aravis_INCLUDE_DIRS - libraries: - - Aravis_LIBRARIES - library_dirs: [] - name: Aravis - ubuntu: - - mrt-libaravis-dev -pybind11-dev: - cmake: - # Only find_package pybind as it is needed only for python cpp files. - # This is linked manually. - name: pybind11 - include_dirs: [] - libraries: [] - library_dirs: [] - ubuntu: - - mrt-pybind11-dev -armadillo: - cmake: - include_dirs: - - ARMADILLO_INCLUDE_DIRS - libraries: - - ARMADILLO_LIBRARIES - library_dirs: [] - name: Armadillo - ubuntu: - - libarmadillo-dev -coverage: - ubuntu: - - lcov -boost: - cmake: - components: - - wserialization thread random serialization log_setup prg_exec_monitor - wave system chrono filesystem locale timer date_time regex graph - program_options unit_test_framework log atomic - include_dirs: - - Boost_INCLUDE_DIRS - libraries: - - Boost_LIBRARIES - library_dirs: - - Boost_LIBRARY_DIRS - name: Boost -boost-python: - cmake: - include_dirs: - - BoostPython_INCLUDE_DIRS - libraries: - - BoostPython_LIBRARIES - name: BoostPython - ubuntu: - - libpython-dev - - libboost-python-dev -libboost-python: # official rosdep key - cmake: - include_dirs: - - BoostPython_INCLUDE_DIRS - libraries: - - BoostPython_LIBRARIES - name: BoostPython - ubuntu: - - libpython-dev - - libboost-python-dev -cuda: - cmake: - components: [] - include_dirs: - - CUDA_INCLUDE_DIRS - libraries: - - CUDA_LIBRARIES - library_dirs: [] - name: MrtCUDA - ubuntu: - xenial: - - cuda-toolkit-9-2 - - g++-6 - bionic: - - cuda-toolkit-10-2 - - g++-8 -eigen: - cmake: - components: [] - include_dirs: - - EIGEN3_INCLUDE_DIR - libraries: [] - library_dirs: [] - name: Eigen3 -eigen2: - cmake: - include_dirs: - - EIGEN2_INCLUDE_DIR - libraries: [] - name: Eigen2 -flann: - ubuntu: - - libflann-dev - cmake: - include_dirs: - - FLANN_INCLUDE_DIRS - libraries: - - FLANN_LIBRARIES - library_dirs: [] - name: Flann -glew: - ubuntu: - - libglew-dev - cmake: - include_dirs: - - GLEW_INCLUDE_DIR - libraries: - - GLEW_LIBRARIES - library_dirs: [] - name: GLEW -glfw: - ubuntu: - - libglfw3-dev - cmake: - include_dirs: - - GLFW3_INCLUDE_DIR - libraries: - - GLFW3_LIBRARY - library_dirs: [] - name: glfw3 -freeglut3-dev: - ubuntu: - - freeglut3-dev -glut: - cmake: - components: [] - include_dirs: - - GLUT_INCLUDE_DIR - libraries: - - GLUT_LIBRARIES - library_dirs: [] - name: GLUT -gpsd: - ubuntu: - - gpsd -gtest: - cmake: - include_dirs: - - gtest_INCLUDE_DIRS - libraries: - - gtest_LIBRARIES - name: gtest -gtest-headers: - cmake: - include_dirs: - - GTest-headers_INCLUDE_DIRS - libraries: [] - name: GTest-headers - ubuntu: - - libgtest-dev -gtestsrc: - cmake: - include_dirs: [] - libraries: - - GTEST_LIBRARIES - name: MrtGTest - ubuntu: - - libgtest-dev -gtkmm: - cmake: - components: [] - include_dirs: - - GTKMM_INCLUDE_DIRS - libraries: - - GTKMM_LIBRARIES - library_dirs: - - GTKMM_LIBRARY_DIRS - name: GTKMM - ubuntu: - - libgtkmm-3.0-dev -libcairo2-dev: - cmake: - components: [] - include_dirs: - - CAIRO_INCLUDE_DIRS - libraries: - - CAIRO_LIBRARIES - library_dirs: [] - name: Cairo -libgeographic-dev: - cmake: - components: [] - include_dirs: - - GeographicLib_INCLUDE_DIRS - libraries: - - GeographicLib_LIBRARIES - library_dirs: [] - name: GeographicLib - ubuntu: - - libgeographic-dev -geographiclib: # official rosdep key - cmake: - components: [] - include_dirs: - - GeographicLib_INCLUDE_DIRS - libraries: - - GeographicLib_LIBRARIES - library_dirs: [] - name: GeographicLib - ubuntu: - - libgeographic-dev -libgoogle-glog-dev: - cmake: - components: [] - include_dirs: - - GLOG_INCLUDE_DIRS - libraries: - - GLOG_LIBRARY - library_dirs: [] - name: Glog -libgps: - cmake: - include_dirs: - - LIBGPS_INCLUDE_DIR - libraries: - - LIBGPS_LIBRARY - name: libgps -libgsl: - cmake: - components: [] - include_dirs: - - GSL_INCLUDE_DIRS - libraries: - - GSL_LIBRARIES - name: GSL - ubuntu: - - libgsl-dev -libigl: - cmake: - components: [] - include_dirs: [] - libraries: - - IGL_LIBRARIES - library_dirs: [] - name: IGL -liblapack-dev: - cmake: - include_dirs: [] - libraries: - - LAPACK_LIBRARIES - name: MrtLAPACK -libmagick: - cmake: - components: - - Magick++ MagickWand MagickCore - include_dirs: - - ImageMagick_INCLUDE_DIRS - libraries: - - ImageMagick_LIBRARIES - name: ImageMagick -liblmdb: - ubuntu: - - liblmdb-dev -libopenscenegraph: - cmake: - components: - - osg osgAnimation osgDB osgFX osgGA osgManipulator osgParticle osgPresentation - osgQt osgShadow osgSim osgTerrain osgText osgUtil osgViewer osgVolume osgWidget - include_dirs: - - OPENSCENEGRAPH_INCLUDE_DIRS - libraries: - - OPENSCENEGRAPH_LIBRARIES - library_dirs: [] - name: OpenSceneGraph -libpcap-dev: - cmake: - include_dirs: - - PCAP_INCLUDE_DIR - libraries: - - PCAP_LIBRARY - name: PCAP - ubuntu: - - libpcap-dev -libqwt5-qt4-dev: - cmake: - components: [] - include_dirs: - - QWT_INCLUDE_DIRS - libraries: - - QWT_LIBRARIES - library_dirs: [] - name: Qwt -libsqlite3-dev: - cmake: - components: [] - include_dirs: - - SQLITE3_INCLUDE_DIRS - libraries: - - SQLITE3_LIBRARIES - library_dirs: [] - name: Sqlite3 -libssl-dev: - cmake: - include_dirs: - - OPENSSL_INCLUDE_DIR - libraries: - - OPENSSL_LIBRARIES - library_dirs: [] - name: OpenSSL -libudev-dev: - ubuntu: - - libudev-dev -libxext-dev: - ubuntu: - - libxext-dev -libxrandr-dev: - ubuntu: - - libxrandr-dev -mbed_cli: - ubuntu: - - mrt-mbed-cli -mesa-common-dev: - ubuntu: - - mesa-common-dev -minpack: - cmake: - components: [] - include_dirs: - - MINPACK_INCLUDE_DIRS - libraries: - - MINPACK_LIBRARIES - library_dirs: [] - name: Minpack - ubuntu: - - minpack-dev -mrt_ann: - cmake: - components: [] - include_dirs: - - ANN_INCLUDE_DIR - libraries: - - ANN_LIBRARIES - library_dirs: [] - name: MrtANN - ubuntu: - - libann-dev -mrt_benchmark: - cmake: - components: [] - include_dirs: [] - libraries: - - benchmark_LIBRARIES - library_dirs: [] - name: Mrtbenchmark - ubuntu: - - mrt-benchmark-dev -mrt_caffe: - cmake: - components: [] - include_dirs: - - Caffe_INCLUDE_DIRS - libraries: - - Caffe_LIBRARIES - library_dirs: [] - name: MrtCaffe - ubuntu: - trusty: - - mrt-caffe-dev -mrt_cereal: - cmake: - components: [] - include_dirs: - - Cereal_INCLUDE_DIR - libraries: [] - library_dirs: [] - name: MrtCereal - ubuntu: - - libcereal-dev -mrt_ceres: - cmake: - components: [] - include_dirs: - - CERES_INCLUDE_DIRS - libraries: - - CERES_LIBRARIES - library_dirs: [] - name: MrtCeres - ubuntu: - - mrt-libceres-dev -mrt_cgal: - cmake: - components: [] - include_dirs: - - CGAL_INCLUDE_DIRS - libraries: - - CGAL_LIBRARIES - library_dirs: [] - name: CGAL - ubuntu: - - libcgal-dev -mrt_ebus: - cmake: - components: [] - include_dirs: - - ebus-sdk_INCLUDE_DIR - libraries: - - ebus-sdk_LIBRARIES - library_dirs: [] - name: Mrtebus-sdk - ubuntu: - - ebus-sdk -mrt_f2c_old: - cmake: - components: [] - include_dirs: - - f2c_INCLUDE_DIR - libraries: - - f2c_LIBRARIES - library_dirs: [] - name: Mrtf2c - ubuntu: - trusty: - - mrt-ftwoc-dev -mrt_gnu_arm_embedded_toolchain: - ubuntu: - xenial: - - mrt-gnu-arm-embedded-toolchain - bionic: - - gcc-arm-embedded -mrt_leptonica: - cmake: - components: [] - include_dirs: - - Leptonica_INCLUDE_DIR - libraries: - - Leptonica_LIBRARIES - library_dirs: [] - name: MrtLeptonica - ubuntu: - - libleptonica-dev -mrt_metis: - cmake: - components: [] - include_dirs: - - Metis_INCLUDE_DIR - libraries: - - Metis_LIBRARIES - library_dirs: [] - name: MrtMetis - ubuntu: - - libmetis-dev -mrt_nlopt: - cmake: - components: [] - include_dirs: - - nlopt_INCLUDE_DIR - libraries: - - nlopt_LIBRARIES - library_dirs: [] - name: Mrtnlopt - ubuntu: - - libnlopt-dev -mrt_opencv: - cmake: - components: [] - include_dirs: - - OpenCV_INCLUDE_DIRS - libraries: - - OpenCV_LIBS - library_dirs: [] - name: MrtOpenCV - ubuntu: - - mrt-libopencv-dev -mrt_pcl: - cmake: - components: [] - include_dirs: - - PCL_INCLUDE_DIRS - libraries: - - PCL_LIBRARIES - library_dirs: - - PCL_LIBRARY_DIRS - name: MrtPCL - ubuntu: - xenial: - - mrt-libpcl-all-dev - bionic: - - libpcl-dev -mrt_protobuf: - cmake: - components: [] - include_dirs: - - PROTOBUF_INCLUDE_DIR - libraries: - - PROTOBUF_LIBRARIES - library_dirs: [] - name: Protobuf - ubuntu: - - libprotobuf-dev - - protobuf-compiler - - libprotoc-dev - - python-protobuf -mrt_qt4-dev: - cmake: - components: - - QtCore QTGui Qt3Support QtDBus QtDesigner QtDesignerComponents QtHelp QtNetwork - QtOpenGL QtScript QtScriptTools QtSql QtSvg QtTest QtUiTools QtWebKit QtXml - QtXmlPatterns - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt4 - ubuntu: - - libqt4-dev - - libqt4-opengl-dev - - libqtwebkit-dev -mrt_qt-dev: - cmake: - components: - - Core Gui DBus Network OpenGL OpenGLExtensions Sql Test Xml Widgets Concurrent Svg - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt5 - ubuntu: - - qt5-default - - libqt5svg5-dev -mrt_qt5-dev: - cmake: - components: - - Core Gui DBus Network OpenGL OpenGLExtensions Sql Test Xml Widgets Concurrent Svg - include_dirs: - - QT_INCLUDES - libraries: - - QT_LIBRARIES - name: MrtQt5 - ubuntu: - - qt5-default - - libqt5svg5-dev -mrt_sdl2: - cmake: - components: [] - include_dirs: - - SDL2_INCLUDE_DIRS - libraries: - - SDL2_LIBRARIES - library_dirs: [] - name: MrtSDL2 - ubuntu: - - libsdl2-dev -mrt_suitesparse: - cmake: - components: [] - include_dirs: - - SUITESPARSE_INCLUDE_DIRS - libraries: - - SUITESPARSE_LIBRARIES - library_dirs: [] - name: MrtSuiteSparse - ubuntu: - - libsuitesparse-dev -mrt_tensorflow: - cmake: - components: [] - include_dirs: - - TENSORFLOW_INCLUDE_DIRS - libraries: - - TENSORFLOW_LIBRARIES - library_dirs: [] - name: MrtTensorflow - ubuntu: - - mrt-tensorflow-dev -mrt_tensorflow_addons: - ubuntu: - - mrt-tensorflow-addons -mrt_c_tensorflow: - cmake: - components: [] - include_dirs: - - TENSORFLOW_C_INCLUDE_DIRS - libraries: - - TENSORFLOW_LIBRARIES - library_dirs: [] - name: MrtCTensorflow - ubuntu: - - mrt-tensorflow-dev -mrt_tesseract: - cmake: - components: [] - include_dirs: - - Tesseract_INCLUDE_DIR - libraries: - - Tesseract_LIBRARIES - library_dirs: [] - name: MrtTesseract - ubuntu: - - libtesseract-dev -mrt_vtk: - cmake: - components: [] - include_dirs: - - VTK_INCLUDE_DIRS - libraries: - - VTK_LIBRARIES - library_dirs: [] - name: MrtVTK - ubuntu: - trusty: - - mrt-vtk-dev - xenial: - - mrt-libvtk-dev - bionic: - - libvtk6-dev -opencv: - cmake: - components: [] - include_dirs: - - OpenCV_INCLUDE_DIRS - libraries: - - OpenCV_LIBS - library_dirs: [] - name: OpenCV - ubuntu: - - mrt-libopencv-dev -python-opencv: - ubuntu: - bionic: - - mrt-libopencv-dev -python3-opencv: - ubuntu: - bionic: - - mrt-libopencv-dev -libopencv-contrib-dev: - ubuntu: - bionic: - - mrt-libopencv-dev -libopencv-dev: - cmake: - components: [] - include_dirs: - - OpenCV_INCLUDE_DIRS - libraries: - - OpenCV_LIBS - library_dirs: [] - name: OpenCV - ubuntu: - - mrt-libopencv-dev -opengl: - cmake: - components: [] - include_dirs: - - OPENGL_INCLUDE_DIR - libraries: - - OPENGL_LIBRARIES - library_dirs: [] - name: OpenGL -png: - cmake: - components: [] - include_dirs: - - PNG_INCLUDE_DIRS - libraries: - - PNG_LIBRARIES - library_dirs: [] - name: PNG - ubuntu: - xenial: - - libpng12-dev - bionic: - - libpng-dev -png++: - cmake: - components: [] - include_dirs: - - PNG++_INCLUDE_DIRS - libraries: [] - library_dirs: [] - name: PNG++ - ubuntu: - - libpng++-dev -poco: - cmake: - components: - - XML Zip Crypto Data Net - include_dirs: - - Poco_INCLUDE_DIRS - libraries: - - Poco_LIBRARIES - library_dirs: [] - name: Poco - ubuntu: - - libpoco-dev -pugixml: - cmake: - components: [] - include_dirs: - - PUGIXML_INCLUDE_DIRS - libraries: - - PUGIXML_LIBRARIES - library_dirs: [] - name: pugixml - ubuntu: - - libpugixml-dev -pugixml-dev: # official rosdep key - cmake: - components: [] - include_dirs: - - PUGIXML_INCLUDE_DIRS - libraries: - - PUGIXML_LIBRARIES - library_dirs: [] - name: pugixml - ubuntu: - - libpugixml-dev -python-cvxopt: - ubuntu: - pip: - packages: [cvxopt] -python-gdal: - ubuntu: - - python-gdal -python-libs: - cmake: - components: [] - include_dirs: - - PYTHON_INCLUDE_DIRS - libraries: - - PYTHON_LIBRARIES - library_dirs: [] - name: PythonLibs - ubuntu: - - libpython2.7-dev -python-nlopt: - ubuntu: - - python-nlopt -python-vte: - ubuntu: - - python-vte -range_v3: - cmake: - include_dirs: - - range-v3_INCLUDE_DIR - name: range-v3 - ubuntu: - - librange-v3-dev -sdl2: - cmake: - components: [] - include_dirs: - - SDL2_INCLUDE_DIRS - libraries: - - SDL2_LIBRARIES - library_dirs: [] - name: sdl2 - ubuntu: - - libsdl2-dev -tbb: - cmake: - include_dirs: - - TBB_INCLUDE_DIR - libraries: - - TBB_LIBRARIES - name: TBB -tinyxml: - cmake: - components: [] - include_dirs: - - TINYXML_INCLUDE_DIR - libraries: - - TINYXML_LIBRARIES - library_dirs: [] - name: TinyXML - ubuntu: - - libtinyxml-dev -uuid-dev: - ubuntu: - - uuid-dev -xerces-c: - ubuntu: - - libxerces-c-dev -yaml-cpp: - cmake: - components: [] - include_dirs: - - yaml-cpp_INCLUDE_DIRS - libraries: - - yaml-cpp_LIBRARIES - library_dirs: [] - name: yaml-cpp -coinor-libipopt-dev: - cmake: - components: [] - include_dirs: - - IPOPT_INCLUDE_DIRS - libraries: - - IPOPT_LIBRARIES - library_dirs: [] - name: Ipopt - ubuntu: [coinor-libipopt-dev] diff --git a/mrt_cmake_modules/yaml/cmake.yaml b/mrt_cmake_modules/yaml/cmake.yaml new file mode 100644 index 00000000000..3fd25077fcc --- /dev/null +++ b/mrt_cmake_modules/yaml/cmake.yaml @@ -0,0 +1,440 @@ +# This file helps mrt_cmake_modules to understand how to use external packages. +# Every package.xml entry here is resolved into a sequence of cmake calls and added to +# MRT_INCLUDE_DIRS, MRT_LIBRARY_DIRS and MRT_LIBRARIES, respectively. +# Every entry has the following format: +# name: The name of the findscript. Will be translated into Find.cmake. Scripts in the cmake folder of this package will be considered as well. +# components (optional): components to be specified in the 'find_package( COMPONENTS )' call in cmake. +# include_dirs (optional): [] +# libraries (optional): [] +# library_dirs (optional): [] +# targets (optional): [] +# warning (optional): Outputs this as a cmake warning whenever this dependency is used (useful for deprecating things) +aravis: + include_dirs: [Aravis_INCLUDE_DIRS] + libraries: [Aravis_LIBRARIES] + library_dirs: [] + name: Aravis +benchmark: + name: benchmark + targets: ['benchmark::benchmark'] +boost: + components: [wserialization thread random serialization log_setup prg_exec_monitor + wave system chrono filesystem locale timer date_time regex graph program_options + unit_test_framework log atomic] + include_dirs: [Boost_INCLUDE_DIRS] + libraries: [Boost_LIBRARIES] + library_dirs: [Boost_LIBRARY_DIRS] + name: Boost +boost-python: + include_dirs: [BoostPython_INCLUDE_DIRS] + libraries: [BoostPython_LIBRARIES] + name: BoostPython + warning: Usage of boost-python in package.xml is deprecated. Use 'libboost-python-dev' instead! +cgal: + components: [] + include_dirs: [CGAL_INCLUDE_DIRS] + libraries: [CGAL_LIBRARIES] + library_dirs: [] + name: CGAL + warning: Usage of cgal in package.xml is deprecated. Use 'mrt_cgal' instead! +coinor-libipopt-dev: + components: [] + include_dirs: [IPOPT_INCLUDE_DIRS] + libraries: [IPOPT_LIBRARIES] + library_dirs: [] + name: Ipopt +cuda: + components: [] + include_dirs: [CUDA_INCLUDE_DIRS] + libraries: [CUDA_LIBRARIES] + library_dirs: [] + name: MrtCUDA +eigen: + components: [] + include_dirs: [EIGEN3_INCLUDE_DIR] + libraries: [] + library_dirs: [] + name: Eigen3 +flann: + include_dirs: [FLANN_INCLUDE_DIRS] + libraries: [FLANN_LIBRARIES] + library_dirs: [] + name: Flann +geographiclib: + components: [] + include_dirs: [GeographicLib_INCLUDE_DIRS] + libraries: [GeographicLib_LIBRARIES] + library_dirs: [] + name: GeographicLib +glut: + components: [] + include_dirs: [GLUT_INCLUDE_DIR] + libraries: [GLUT_LIBRARIES] + library_dirs: [] + name: GLUT +gtest: + include_dirs: [gtest_INCLUDE_DIRS] + libraries: [gtest_LIBRARIES] + name: gtest +libann-dev: + components: [] + include_dirs: [ANN_INCLUDE_DIR] + libraries: [ANN_LIBRARIES] + library_dirs: [] + name: ANN +libboost-python: + include_dirs: [BoostPython_INCLUDE_DIRS] + libraries: [BoostPython_LIBRARIES] + name: BoostPython + warning: Usage of libboost-python in package.xml is deprecated. Use 'libboost-python-dev' instead! +libboost-python-dev: + include_dirs: [BoostPython_INCLUDE_DIRS] + libraries: [BoostPython_LIBRARIES] + name: BoostPython +libcairo2-dev: + components: [] + include_dirs: [CAIRO_INCLUDE_DIRS] + libraries: [CAIRO_LIBRARIES] + library_dirs: [] + name: Cairo +libcereal-dev: + components: [] + include_dirs: [Cereal_INCLUDE_DIR] + libraries: [] + library_dirs: [] + name: Cereal +libceres-dev: + name: Ceres + targets: [ceres] +libconsole-bridge-dev: + targets: ["console_bridge"] + name: console_bridge +libgeographic-dev: + components: [] + include_dirs: [GeographicLib_INCLUDE_DIRS] + libraries: [GeographicLib_LIBRARIES] + library_dirs: [] + name: GeographicLib + warning: Usage of libgeographic-dev in package.xml is deprecated. Use 'geographiclib' instead! +libgoogle-glog-dev: + components: [] + include_dirs: [GLOG_INCLUDE_DIRS] + libraries: [GLOG_LIBRARY] + library_dirs: [] + name: Glog +libgsl: + components: [] + include_dirs: [GSL_INCLUDE_DIRS] + libraries: [GSL_LIBRARIES] + name: GSL +libigl: + components: [] + include_dirs: [] + libraries: [IGL_LIBRARIES] + library_dirs: [] + name: IGL +libjsoncpp-dev: + name: JsonCpp + targets: ['JsonCpp::JsonCpp'] + components: [] +liblapack-dev: + name: LAPACK + libraries: [LAPACK_LIBRARIES] +libnlopt-cxx-dev: + components: [] + include_dirs: [nlopt_INCLUDE_DIR] + libraries: [nlopt_LIBRARIES] + library_dirs: [] + name: nlopt +libnlopt-dev: + components: [] + include_dirs: [nlopt_INCLUDE_DIR] + libraries: [nlopt_LIBRARIES] + library_dirs: [] + name: nlopt +libopencv-dev: + components: [] + include_dirs: [OpenCV_INCLUDE_DIRS] + libraries: [OpenCV_LIBS] + library_dirs: [] + name: OpenCV +libpcl-all-dev: + components: [] + targets: ['mrt_pcl::pcl'] + name: MrtPCL +libpoco-dev: + components: [Foundation] + libraries: [Poco_LIBRARIES] + name: Poco +libsqlite3-dev: + components: [] + include_dirs: [SQLITE3_INCLUDE_DIRS] + libraries: [SQLITE3_LIBRARIES] + library_dirs: [] + name: Sqlite3 +libssl-dev: + include_dirs: [OPENSSL_INCLUDE_DIR] + libraries: [OPENSSL_LIBRARIES] + library_dirs: [] + name: OpenSSL +libtesseract: + components: [] + include_dirs: [Tesseract_INCLUDE_DIR] + libraries: [Tesseract_LIBRARIES] + library_dirs: [] + name: Tesseract +libvtk: + components: [] + include_dirs: [VTK_INCLUDE_DIRS] + libraries: [VTK_LIBRARIES] + library_dirs: [] + name: MrtVTK +libpng++-dev: + components: [] + include_dirs: [PNG++_INCLUDE_DIRS] + libraries: [PNG++_LIBRARIES] + library_dirs: [] + name: PNG++ +mrt_ann: + components: [] + include_dirs: [ANN_INCLUDE_DIR] + libraries: [ANN_LIBRARIES] + library_dirs: [] + name: ANN + warning: Usage of mrt_ann in package.xml is deprecated. Use 'libann-dev' instead! +mrt_benchmark: + name: benchmark + targets: ['benchmark::benchmark'] + warning: Usage of mrt_benchmark in package.xml is deprecated. Use 'benchmark' instead! +mrt_blasfeo: + name: blasfeo + include_dirs: [blasfeo_INCLUDE_DIR] + libraries: [blasfeo_LIBRARIES] + targets: ['blasfeo'] +mrt_c_tensorflow: + components: [] + include_dirs: [TENSORFLOW_C_INCLUDE_DIRS] + libraries: [TENSORFLOW_LIBRARIES] + library_dirs: [] + name: CTensorflow +mrt_casadi: + name: casadi + include_dirs: [casadi_INCLUDE_DIR] + libraries: [casadi_LIBRARIES] + targets: ['casadi'] +mrt_cereal: + components: [] + include_dirs: [Cereal_INCLUDE_DIR] + libraries: [] + library_dirs: [] + name: Cereal + warning: Usage of mrt_cereal in package.xml is deprecated. Use 'libcereal-dev' instead! +mrt_ceres: + name: Ceres + targets: [ceres] + warning: Usage of mrt_ceres in package.xml is deprecated. Use 'libceres-dev' instead! +mrt_cgal: + components: [] + include_dirs: [CGAL_INCLUDE_DIRS] + libraries: [CGAL_LIBRARIES] + library_dirs: [] + name: CGAL +mrt_ebus: + components: [] + include_dirs: [ebus-sdk_INCLUDE_DIR] + libraries: [ebus-sdk_LIBRARIES] + library_dirs: [] + name: ebus-sdk +mrt_hpipm: + name: hpipm + include_dirs: [hpipm_INCLUDE_DIR] + libraries: [hpipm_LIBRARIES] + targets: ['hpipm'] +mrt_metis: + components: [] + include_dirs: [Metis_INCLUDE_DIR] + libraries: [Metis_LIBRARIES] + library_dirs: [] + name: Metis +mrt_nlopt: + components: [] + include_dirs: [nlopt_INCLUDE_DIR] + libraries: [nlopt_LIBRARIES] + library_dirs: [] + name: nlopt + warning: Usage of mrt_nlopt in package.xml is deprecated. Use 'libnlopt-dev' instead! +mrt_opencv: + components: [] + include_dirs: [OpenCV_INCLUDE_DIRS] + libraries: [OpenCV_LIBS] + library_dirs: [] + name: OpenCV + warning: Usage of mrt_opencv in package.xml is deprecated. Use 'libopencv-dev' instead! +mrt_pcl: + components: [] + targets: ['mrt_pcl::pcl'] + name: MrtPCL + warning: Usage of mrt_pcl in package.xml is deprecated. Use 'libpcl-all-dev' instead! +mrt_protobuf: + components: [] + include_dirs: [PROTOBUF_INCLUDE_DIR] + libraries: [PROTOBUF_LIBRARIES] + library_dirs: [] + name: Protobuf + warning: Usage of mrt_protobuf in package.xml is deprecated. Use 'protobuf-dev' + instead! +mrt_qt-dev: + components: [Core Gui DBus Network OpenGL OpenGLExtensions Sql Test Xml Widgets + Concurrent Svg Script] + include_dirs: [QT_INCLUDES] + libraries: [QT_LIBRARIES] + name: MrtQt5 +mrt_qt4-dev: + components: [QtCore QTGui Qt3Support QtDBus QtDesigner QtDesignerComponents QtHelp + QtNetwork QtOpenGL QtScript QtScriptTools QtSql QtSvg QtTest QtUiTools QtWebKit + QtXml QtXmlPatterns] + include_dirs: [QT_INCLUDES] + libraries: [QT_LIBRARIES] + name: MrtQt4 + warning: Usage of mrt_qt4-dev in package.xml is deprecated. Use 'mrt_qt-dev' instead! +mrt_qt5-dev: + components: [Core Gui DBus Network OpenGL OpenGLExtensions Sql Test Xml Widgets + Concurrent Svg Script] + include_dirs: [QT_INCLUDES] + libraries: [QT_LIBRARIES] + name: MrtQt5 +mrt_sdl2: + components: [] + include_dirs: [SDL2_INCLUDE_DIRS] + libraries: [SDL2_LIBRARIES] + library_dirs: [] + name: SDL2 + warning: Usage of mrt_sdl2 in package.xml is deprecated. Use 'sdl2' instead! +mrt_suitesparse: + components: [] + include_dirs: [SUITESPARSE_INCLUDE_DIRS] + libraries: [SUITESPARSE_LIBRARIES] + library_dirs: [] + name: SuiteSparse + warning: Usage of mrt_suitesparse in package.xml is deprecated. Use 'suitesparse' + instead! +mrt_tensorflow: + components: [] + include_dirs: [TENSORFLOW_INCLUDE_DIRS] + libraries: [TENSORFLOW_LIBRARIES] + library_dirs: [] + name: Tensorflow +mrt_tesseract: + components: [] + include_dirs: [Tesseract_INCLUDE_DIR] + libraries: [Tesseract_LIBRARIES] + library_dirs: [] + name: Tesseract + warning: Usage of mrt_tesseract in package.xml is deprecated. Use 'libtesseract' + instead! +mrt_vtk: + components: [] + include_dirs: [VTK_INCLUDE_DIRS] + libraries: [VTK_LIBRARIES] + library_dirs: [] + name: MrtVTK + warning: Usage of mrt_vtk in package.xml is deprecated. Use 'libvtk' instead! +opencv: + components: [] + include_dirs: [OpenCV_INCLUDE_DIRS] + libraries: [OpenCV_LIBS] + library_dirs: [] + name: OpenCV + warning: Usage of opencv in package.xml is deprecated. Use 'libopencv-dev' instead! +opengl: + components: [] + include_dirs: [OPENGL_INCLUDE_DIR] + libraries: [OPENGL_LIBRARIES] + library_dirs: [] + name: MrtOpenGL +pangolin: + include_dirs: [Pangolin_INCLUDE_DIRS] + libraries: [Pangolin_LIBRARIES] + name: Pangolin +png++: + components: [] + include_dirs: [PNG++_INCLUDE_DIRS] + libraries: [PNG++_LIBRARIES] + library_dirs: [] + name: PNG++ + warning: Usage of png++ in package.xml is deprecated. Use 'libpng++-dev' instead! +protobuf-dev: + components: [] + include_dirs: [PROTOBUF_INCLUDE_DIR] + libraries: [PROTOBUF_LIBRARIES] + library_dirs: [] + name: Protobuf +pugixml: + components: [] + include_dirs: [PUGIXML_INCLUDE_DIRS] + libraries: [PUGIXML_LIBRARIES] + library_dirs: [] + name: pugixml + warning: Usage of pugixml in package.xml is deprecated. Use 'pugixml-dev' instead! +pugixml-dev: + components: [] + include_dirs: [PUGIXML_INCLUDE_DIRS] + libraries: [PUGIXML_LIBRARIES] + library_dirs: [] + name: pugixml +pybind11-dev: + include_dirs: [] + libraries: [] + library_dirs: [] + name: pybind11 +qtbase5-dev: + components: [Core Gui Network] + include_dirs: [QT_INCLUDES] + libraries: [QT_LIBRARIES] + name: MrtQt5 +range_v3: + name: range-v3 + targets: [range-v3] +sdl2: + components: [] + include_dirs: [SDL2_INCLUDE_DIRS] + libraries: [SDL2_LIBRARIES] + library_dirs: [] + name: SDL2 +suitesparse: + components: [] + include_dirs: [SUITESPARSE_INCLUDE_DIRS] + libraries: [SUITESPARSE_LIBRARIES] + library_dirs: [] + name: SuiteSparse +tbb: + name: TBB + targets: [tbb] +tinyxml: + components: [] + include_dirs: [TINYXML_INCLUDE_DIR] + libraries: [TINYXML_LIBRARIES] + library_dirs: [] + name: TinyXML +tinyxml2: + components: [] + include_dirs: [TinyXML2_INCLUDE_DIR] + libraries: [TinyXML2_LIBRARIES] + library_dirs: [] + name: TinyXML2 +yaml-cpp: + name: yaml-cpp + targets: [yaml-cpp] +mrt-osqp: + name: osqp + include_dirs: [osqp_INCLUDE_DIR] + libraries: [osqp_LIBRARIES] + targets: ['osqp::osqp'] +mrt-osqp-eigen: + name: OsqpEigen + include_dirs: [osqp_eigen_INCLUDE-DIR] + libraries: [osqp_eigen_LIBRARIES] + targets: ['OsqpEigen::OsqpEigen'] +or-tools: + name: ortools + targets: [' ortools::ortools'] diff --git a/mrt_cmake_modules/yaml/external-mrt-ros-bionic.yaml b/mrt_cmake_modules/yaml/external-mrt-ros-bionic.yaml deleted file mode 100644 index 6283efebe68..00000000000 --- a/mrt_cmake_modules/yaml/external-mrt-ros-bionic.yaml +++ /dev/null @@ -1,6044 +0,0 @@ -abb: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb/1.3.1-1 -abb_driver: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_driver/1.3.1-1 -abb_irb2400_moveit_config: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb2400_moveit_config/1.3.1-1 -abb_irb2400_moveit_plugins: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb2400_moveit_plugins/1.3.1-1 -abb_irb2400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb2400_support/1.3.1-1 -abb_irb4400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb4400_support/1.3.1-1 -abb_irb5400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb5400_support/1.3.1-1 -abb_irb6600_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb6600_support/1.3.1-1 -abb_irb6640_moveit_config: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb6640_moveit_config/1.3.1-1 -abb_irb6640_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_irb6640_support/1.3.1-1 -abb_resources: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/melodic/abb_resources/1.3.1-1 -abseil_cpp: - url: https://github.com/Eurecat/abseil_cpp-release.git - vcs: git - version: release/melodic/abseil_cpp/0.4.2-1 -acado: - url: https://github.com/tud-cor/acado-release.git - vcs: git - version: release/melodic/acado/1.2.3-0 -access_point_control: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/access_point_control/1.0.16-1 -ackermann_msgs: - url: https://github.com/ros-drivers-gbp/ackermann_msgs-release.git - vcs: git - version: release/melodic/ackermann_msgs/1.0.1-0 -ackermann_steering_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/ackermann_steering_controller/0.15.0-0 -actionlib_lisp: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/actionlib_lisp/0.2.12-1 -adi_driver: - url: https://github.com/tork-a/adi_driver-release.git - vcs: git - version: release/melodic/adi_driver/1.0.3-0 -agni_tf_tools: - url: https://github.com/ubi-agni-gbp/agni_tf_tools-release.git - vcs: git - version: release/melodic/agni_tf_tools/0.1.2-1 -ainstein_radar: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar/2.0.2-1 -ainstein_radar_drivers: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_drivers/2.0.2-1 -ainstein_radar_filters: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_filters/2.0.2-1 -ainstein_radar_gazebo_plugins: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_gazebo_plugins/2.0.2-1 -ainstein_radar_msgs: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_msgs/2.0.2-1 -ainstein_radar_rviz_plugins: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_rviz_plugins/2.0.2-1 -ainstein_radar_tools: - url: https://github.com/AinsteinAI/ainstein_radar-release.git - vcs: git - version: release/melodic/ainstein_radar_tools/2.0.2-1 -allocators: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/melodic/allocators/1.0.25-0 -amcl: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/amcl/1.16.3-1 -app_manager: - url: https://github.com/ros-gbp/app_manager-release.git - vcs: git - version: release/melodic/app_manager/1.1.0-0 -apriltag: - url: https://github.com/AprilRobotics/apriltag-release.git - vcs: git - version: release/melodic/apriltag/3.1.1-1 -apriltag_ros: - url: https://github.com/AprilRobotics/apriltag_ros-release.git - vcs: git - version: release/melodic/apriltag_ros/3.1.1-1 -ar_track_alvar: - url: https://github.com/ros-gbp/ar_track_alvar-release.git - vcs: git - version: release/melodic/ar_track_alvar/0.7.1-0 -ar_track_alvar_msgs: - url: https://github.com/ros-gbp/ar_track_alvar-release.git - vcs: git - version: release/melodic/ar_track_alvar_msgs/0.7.1-0 -arbotix: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix/0.10.0-0 -arbotix_controllers: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix_controllers/0.10.0-0 -arbotix_firmware: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix_firmware/0.10.0-0 -arbotix_msgs: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix_msgs/0.10.0-0 -arbotix_python: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix_python/0.10.0-0 -arbotix_sensors: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/melodic/arbotix_sensors/0.10.0-0 -ariles_ros: - url: https://github.com/asherikov/ariles-release.git - vcs: git - version: release/melodic/ariles_ros/1.3.2-1 -aruco_detect: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/melodic/aruco_detect/0.11.0-1 -asmach: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/asmach/1.0.16-1 -asmach_tutorials: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/asmach_tutorials/1.0.16-1 -asr_msgs: - url: https://github.com/asr-ros/asr_msgs-release.git - vcs: git - version: release/melodic/asr_msgs/1.0.0-1 -assimp_devel: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/assimp_devel/2.1.13-1 -assisted_teleop: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/assisted_teleop/0.3.3-1 -astuff_sensor_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/astuff_sensor_msgs/2.3.1-0 -async_comm: - url: https://github.com/dpkoch/async_comm-release.git - vcs: git - version: release/melodic/async_comm/0.1.1-0 -async_web_server_cpp: - url: https://github.com/gt-rail-release/async_web_server_cpp-release.git - vcs: git - version: release/melodic/async_web_server_cpp/0.0.3-0 -audibot: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/melodic/audibot/0.1.0-1 -audibot_description: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/melodic/audibot_description/0.1.0-1 -audibot_gazebo: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/melodic/audibot_gazebo/0.1.0-1 -audio_capture: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/melodic/audio_capture/0.3.3-0 -audio_common: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/melodic/audio_common/0.3.3-0 -audio_common_msgs: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/melodic/audio_common_msgs/0.3.3-0 -audio_play: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/melodic/audio_play/0.3.3-0 -automotive_autonomy_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/melodic/automotive_autonomy_msgs/3.0.3-1 -automotive_navigation_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/melodic/automotive_navigation_msgs/3.0.3-1 -automotive_platform_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/melodic/automotive_platform_msgs/3.0.3-1 -autoware_can_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_can_msgs/1.13.0-1 -autoware_config_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_config_msgs/1.13.0-1 -autoware_external_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_external_msgs/1.13.0-1 -autoware_lanelet2_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_lanelet2_msgs/1.13.0-1 -autoware_map_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_map_msgs/1.13.0-1 -autoware_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_msgs/1.13.0-1 -autoware_system_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/autoware_system_msgs/1.13.0-1 -avt_vimba_camera: - url: https://github.com/astuff/avt_vimba_camera-release.git - vcs: git - version: release/melodic/avt_vimba_camera/0.0.11-1 -aws_common: - url: https://github.com/aws-gbp/aws_common-release.git - vcs: git - version: release/melodic/aws_common/2.1.0-1 -aws_ros1_common: - url: https://github.com/aws-gbp/aws_ros1_common-release.git - vcs: git - version: release/melodic/aws_ros1_common/2.0.1-1 -backward_ros: - url: https://github.com/pal-gbp/backward_ros-release.git - vcs: git - version: release/melodic/backward_ros/0.1.7-0 -bagger: - url: https://github.com/squarerobot/bagger-release.git - vcs: git - version: release/melodic/bagger/0.1.3-0 -baldor: - url: https://github.com/crigroup/baldor-release.git - vcs: git - version: release/melodic/baldor/0.1.2-1 -base_local_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/base_local_planner/1.16.3-1 -bayesian_belief_networks: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/bayesian_belief_networks/2.1.13-1 -behaviortree_cpp: - url: https://github.com/BehaviorTree/behaviortree_cpp-release.git - vcs: git - version: release/melodic/behaviortree_cpp/2.5.1-0 -behaviortree_cpp_v3: - url: https://github.com/BehaviorTree/behaviortree_cpp_v3-release.git - vcs: git - version: release/melodic/behaviortree_cpp_v3/3.1.0-2 -bfl: - url: https://github.com/ros-gbp/bfl-release.git - vcs: git - version: release/melodic/bfl/0.8.0-1 -blender_gazebo: - url: https://github.com/david0429-gbp/blender_gazebo_gbp.git - vcs: git - version: release/melodic/blender_gazebo/0.0.4-1 -brics_actuator: - url: https://github.com/wnowak/brics_actuator-release.git - vcs: git - version: release/melodic/brics_actuator/0.7.0-0 -calibration: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/calibration/0.10.14-0 -calibration_estimation: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/calibration_estimation/0.10.14-0 -calibration_launch: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/calibration_launch/0.10.14-0 -calibration_msgs: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/calibration_msgs/0.10.14-0 -calibration_setup_helper: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/calibration_setup_helper/0.10.14-0 -camera_info_manager_py: - url: https://github.com/ros-gbp/camera_info_manager_py-release.git - vcs: git - version: release/melodic/camera_info_manager_py/0.2.3-1 -camera_umd: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/melodic/camera_umd/0.2.7-0 -can_msgs: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/can_msgs/0.8.2-1 -canopen_402: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/canopen_402/0.8.2-1 -canopen_chain_node: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/canopen_chain_node/0.8.2-1 -canopen_master: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/canopen_master/0.8.2-1 -canopen_motor_node: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/canopen_motor_node/0.8.2-1 -capabilities: - url: https://github.com/ros-gbp/capabilities-release.git - vcs: git - version: release/melodic/capabilities/0.2.0-0 -carrot_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/carrot_planner/1.16.3-1 -cartesian_msgs: - url: https://github.com/PickNikRobotics/cartesian_msgs-release.git - vcs: git - version: release/melodic/cartesian_msgs/0.0.3-0 -cartographer: - url: https://github.com/ros-gbp/cartographer-release.git - vcs: git - version: release/melodic/cartographer/1.0.0-0 -cartographer_ros: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/melodic/cartographer_ros/1.0.0-1 -cartographer_ros_msgs: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/melodic/cartographer_ros_msgs/1.0.0-1 -cartographer_rviz: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/melodic/cartographer_rviz/1.0.0-1 -catch_ros: - url: https://github.com/AIS-Bonn/catch_ros-release.git - vcs: git - version: release/melodic/catch_ros/0.3.0-0 -catkin_pip: - url: https://github.com/pyros-dev/catkin_pip-release.git - vcs: git - version: release/melodic/catkin_pip/0.2.3-1 -catkin_virtualenv: - url: https://github.com/locusrobotics/catkin_virtualenv-release.git - vcs: git - version: release/melodic/catkin_virtualenv/0.5.1-1 -checkerboard_detector: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/checkerboard_detector/1.2.10-0 -chomp_motion_planner: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/chomp_motion_planner/1.0.2-1 -cis_camera: - url: https://github.com/tork-a/cis_camera-release.git - vcs: git - version: release/melodic/cis_camera/0.0.4-1 -cl_tf: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_tf/0.2.12-1 -cl_tf2: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_tf2/0.2.12-1 -cl_transforms: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_transforms/0.2.12-1 -cl_transforms_stamped: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_transforms_stamped/0.2.12-1 -cl_urdf: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_urdf/0.2.12-1 -cl_utils: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/cl_utils/0.2.12-1 -clear_costmap_recovery: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/clear_costmap_recovery/1.16.3-1 -clock_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/clock_relay/0.0.2-1 -cloudwatch_logger: - url: https://github.com/aws-gbp/cloudwatch_logger-release.git - vcs: git - version: release/melodic/cloudwatch_logger/2.2.1-1 -cloudwatch_logs_common: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/melodic/cloudwatch_logs_common/1.1.2-1 -cloudwatch_metrics_collector: - url: https://github.com/aws-gbp/cloudwatch_metrics_collector-release.git - vcs: git - version: release/melodic/cloudwatch_metrics_collector/2.1.1-1 -cloudwatch_metrics_common: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/melodic/cloudwatch_metrics_common/1.1.2-1 -cnn_bridge: - url: https://github.com/wew84/cnn_bridge-release.git - vcs: git - version: release/melodic/cnn_bridge/0.8.5-1 -cob_3d_mapping_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_3d_mapping_msgs/0.6.14-1 -cob_actions: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/cob_actions/0.7.1-1 -cob_android: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/melodic/cob_android/0.1.6-1 -cob_android_msgs: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/melodic/cob_android_msgs/0.1.6-1 -cob_android_resource_server: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/melodic/cob_android_resource_server/0.1.6-1 -cob_android_script_server: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/melodic/cob_android_script_server/0.1.6-1 -cob_android_settings: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/melodic/cob_android_settings/0.1.6-1 -cob_base_controller_utils: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_base_controller_utils/0.8.1-1 -cob_base_drive_chain: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_base_drive_chain/0.7.1-1 -cob_base_velocity_smoother: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_base_velocity_smoother/0.8.1-1 -cob_bms_driver: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_bms_driver/0.7.1-1 -cob_calibration_data: - url: https://github.com/ipa320/cob_calibration_data-release.git - vcs: git - version: release/melodic/cob_calibration_data/0.6.13-1 -cob_cam3d_throttle: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_cam3d_throttle/0.6.14-1 -cob_camera_sensors: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_camera_sensors/0.7.1-1 -cob_canopen_motor: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_canopen_motor/0.7.1-1 -cob_cartesian_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_cartesian_controller/0.8.1-1 -cob_collision_monitor: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_collision_monitor/0.7.3-1 -cob_collision_velocity_filter: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_collision_velocity_filter/0.8.1-1 -cob_command_gui: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_command_gui/0.6.15-1 -cob_command_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_command_tools/0.6.15-1 -cob_common: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/cob_common/0.7.1-1 -cob_control: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_control/0.8.1-1 -cob_control_mode_adapter: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_control_mode_adapter/0.8.1-1 -cob_control_msgs: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_control_msgs/0.8.1-1 -cob_dashboard: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_dashboard/0.6.15-1 -cob_default_env_config: - url: https://github.com/ipa320/cob_environments-release.git - vcs: git - version: release/melodic/cob_default_env_config/0.6.10-1 -cob_default_robot_behavior: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/melodic/cob_default_robot_behavior/0.7.2-1 -cob_default_robot_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/melodic/cob_default_robot_config/0.7.2-1 -cob_description: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/cob_description/0.7.1-1 -cob_docker_control: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/melodic/cob_docker_control/0.6.8-1 -cob_driver: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_driver/0.7.1-1 -cob_elmo_homing: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_elmo_homing/0.7.1-1 -cob_environments: - url: https://github.com/ipa320/cob_environments-release.git - vcs: git - version: release/melodic/cob_environments/0.6.10-1 -cob_extern: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/cob_extern/0.6.14-1 -cob_footprint_observer: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_footprint_observer/0.8.1-1 -cob_frame_tracker: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_frame_tracker/0.8.1-1 -cob_gazebo_objects: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/melodic/cob_gazebo_objects/0.7.3-1 -cob_gazebo_plugins: - url: https://github.com/ipa320/cob_gazebo_plugins-release.git - vcs: git - version: release/melodic/cob_gazebo_plugins/0.7.3-1 -cob_gazebo_ros_control: - url: https://github.com/ipa320/cob_gazebo_plugins-release.git - vcs: git - version: release/melodic/cob_gazebo_ros_control/0.7.3-1 -cob_gazebo_tools: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/melodic/cob_gazebo_tools/0.7.3-1 -cob_gazebo_worlds: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/melodic/cob_gazebo_worlds/0.7.3-1 -cob_generic_can: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_generic_can/0.7.1-1 -cob_grasp_generation: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_grasp_generation/0.7.3-1 -cob_hand: - url: https://github.com/ipa320/cob_hand-release.git - vcs: git - version: release/melodic/cob_hand/0.6.6-1 -cob_hand_bridge: - url: https://github.com/ipa320/cob_hand-release.git - vcs: git - version: release/melodic/cob_hand_bridge/0.6.6-1 -cob_hardware_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/melodic/cob_hardware_config/0.7.2-1 -cob_hardware_emulation: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_hardware_emulation/0.8.1-1 -cob_helper_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_helper_tools/0.6.15-1 -cob_image_flip: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_image_flip/0.6.14-1 -cob_interactive_teleop: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_interactive_teleop/0.6.15-1 -cob_light: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_light/0.7.1-1 -cob_linear_nav: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_linear_nav/0.6.9-1 -cob_lookat_action: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_lookat_action/0.7.3-1 -cob_manipulation: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_manipulation/0.7.3-1 -cob_map_accessibility_analysis: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_map_accessibility_analysis/0.6.9-1 -cob_mapping_slam: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_mapping_slam/0.6.9-1 -cob_mimic: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_mimic/0.7.1-1 -cob_model_identifier: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_model_identifier/0.8.1-1 -cob_monitoring: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_monitoring/0.6.15-1 -cob_moveit_bringup: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_moveit_bringup/0.7.3-1 -cob_moveit_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/melodic/cob_moveit_config/0.7.2-1 -cob_moveit_interface: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_moveit_interface/0.7.3-1 -cob_msgs: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/cob_msgs/0.7.1-1 -cob_navigation: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_navigation/0.6.9-1 -cob_navigation_config: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_navigation_config/0.6.9-1 -cob_navigation_global: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_navigation_global/0.6.9-1 -cob_navigation_local: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_navigation_local/0.6.9-1 -cob_navigation_slam: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/melodic/cob_navigation_slam/0.6.9-1 -cob_object_detection_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_object_detection_msgs/0.6.14-1 -cob_object_detection_visualizer: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_object_detection_visualizer/0.6.14-1 -cob_obstacle_distance: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_obstacle_distance/0.8.1-1 -cob_obstacle_distance_moveit: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/melodic/cob_obstacle_distance_moveit/0.7.3-1 -cob_omni_drive_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_omni_drive_controller/0.8.1-1 -cob_perception_common: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_perception_common/0.6.14-1 -cob_perception_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_perception_msgs/0.6.14-1 -cob_phidget_em_state: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_phidget_em_state/0.7.1-1 -cob_phidget_power_state: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_phidget_power_state/0.7.1-1 -cob_phidgets: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_phidgets/0.7.1-1 -cob_reflector_referencing: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/melodic/cob_reflector_referencing/0.6.8-1 -cob_relayboard: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_relayboard/0.7.1-1 -cob_safety_controller: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/melodic/cob_safety_controller/0.6.8-1 -cob_scan_unifier: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_scan_unifier/0.7.1-1 -cob_script_server: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_script_server/0.6.15-1 -cob_sick_lms1xx: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_sick_lms1xx/0.7.1-1 -cob_sick_s300: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_sick_s300/0.7.1-1 -cob_sound: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_sound/0.7.1-1 -cob_srvs: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/cob_srvs/0.7.1-1 -cob_substitute: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/melodic/cob_substitute/0.6.8-1 -cob_supported_robots: - url: https://github.com/ipa320/cob_supported_robots-release.git - vcs: git - version: release/melodic/cob_supported_robots/0.6.13-1 -cob_teleop: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/cob_teleop/0.6.15-1 -cob_trajectory_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_trajectory_controller/0.8.1-1 -cob_tricycle_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_tricycle_controller/0.8.1-1 -cob_twist_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/melodic/cob_twist_controller/0.8.1-1 -cob_undercarriage_ctrl: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_undercarriage_ctrl/0.7.1-1 -cob_utilities: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_utilities/0.7.1-1 -cob_vision_utils: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/cob_vision_utils/0.6.14-1 -cob_voltage_control: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/cob_voltage_control/0.7.1-1 -code_coverage: - url: https://github.com/mikeferguson/code_coverage-gbp.git - vcs: git - version: release/melodic/code_coverage/0.3.0-1 -codec_image_transport: - url: https://github.com/yoshito-n-students/codec_image_transport-release.git - vcs: git - version: release/melodic/codec_image_transport/0.0.4-0 -collada_parser: - url: https://github.com/ros-gbp/collada_urdf-release.git - vcs: git - version: release/melodic/collada_parser/1.12.12-0 -collada_urdf: - url: https://github.com/ros-gbp/collada_urdf-release.git - vcs: git - version: release/melodic/collada_urdf/1.12.12-0 -collada_urdf_jsk_patch: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/collada_urdf_jsk_patch/2.1.13-1 -combined_robot_hw: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/melodic/combined_robot_hw/0.15.1-0 -combined_robot_hw_tests: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/melodic/combined_robot_hw_tests/0.15.1-0 -concert_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/concert_msgs/0.9.0-0 -concert_service_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/concert_service_msgs/0.9.0-0 -concert_workflow_engine_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/concert_workflow_engine_msgs/0.9.0-0 -controller_manager_tests: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/melodic/controller_manager_tests/0.15.1-0 -convex_decomposition: - url: https://github.com/ros-gbp/convex_decomposition-release.git - vcs: git - version: release/melodic/convex_decomposition/0.1.12-0 -costmap_converter: - url: https://github.com/rst-tu-dortmund/costmap_converter-release.git - vcs: git - version: release/melodic/costmap_converter/0.0.12-1 -costmap_cspace: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/costmap_cspace/0.5.1-1 -costmap_cspace_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/costmap_cspace_msgs/0.5.0-1 -costmap_queue: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/costmap_queue/0.2.5-1 -cpr_multimaster_tools: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/cpr_multimaster_tools/0.0.2-1 -criutils: - url: https://github.com/crigroup/criutils-release.git - vcs: git - version: release/melodic/criutils/0.1.3-2 -cv_camera: - url: https://github.com/OTL/cv_camera-release.git - vcs: git - version: release/melodic/cv_camera/0.4.0-1 -dataflow_lite: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/melodic/dataflow_lite/1.1.2-1 -dataspeed_can: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/melodic/dataspeed_can/1.0.12-0 -dataspeed_can_msg_filters: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/melodic/dataspeed_can_msg_filters/1.0.12-0 -dataspeed_can_tools: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/melodic/dataspeed_can_tools/1.0.12-0 -dataspeed_can_usb: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/melodic/dataspeed_can_usb/1.0.12-0 -dataspeed_pds: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/melodic/dataspeed_pds/1.0.2-0 -dataspeed_pds_can: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/melodic/dataspeed_pds_can/1.0.2-0 -dataspeed_pds_msgs: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/melodic/dataspeed_pds_msgs/1.0.2-0 -dataspeed_pds_rqt: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/melodic/dataspeed_pds_rqt/1.0.2-0 -dataspeed_pds_scripts: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/melodic/dataspeed_pds_scripts/1.0.2-0 -dataspeed_ulc: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/melodic/dataspeed_ulc/0.0.5-1 -dataspeed_ulc_can: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/melodic/dataspeed_ulc_can/0.0.5-1 -dataspeed_ulc_msgs: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/melodic/dataspeed_ulc_msgs/0.0.5-1 -dbw_fca: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/melodic/dbw_fca/1.0.6-1 -dbw_fca_can: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/melodic/dbw_fca_can/1.0.6-1 -dbw_fca_description: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/melodic/dbw_fca_description/1.0.6-1 -dbw_fca_joystick_demo: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/melodic/dbw_fca_joystick_demo/1.0.6-1 -dbw_fca_msgs: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/melodic/dbw_fca_msgs/1.0.6-1 -dbw_mkz: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz/1.2.3-1 -dbw_mkz_can: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz_can/1.2.3-1 -dbw_mkz_description: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz_description/1.2.3-1 -dbw_mkz_joystick_demo: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz_joystick_demo/1.2.3-1 -dbw_mkz_msgs: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz_msgs/1.2.3-1 -dbw_mkz_twist_controller: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/melodic/dbw_mkz_twist_controller/1.2.3-1 -dccomms_ros: - url: https://github.com/dcentelles/dccomms_ros_pkgs-release.git - vcs: git - version: release/melodic/dccomms_ros/0.0.2-3 -dccomms_ros_msgs: - url: https://github.com/dcentelles/dccomms_ros_pkgs-release.git - vcs: git - version: release/melodic/dccomms_ros_msgs/0.0.2-3 -ddwrt_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/ddwrt_access_point/1.0.16-1 -ddynamic_reconfigure: - url: https://github.com/pal-gbp/ddynamic_reconfigure.git - vcs: git - version: release/melodic/ddynamic_reconfigure/0.2.0-0 -ddynamic_reconfigure_python: - url: https://github.com/pal-gbp/ddynamic_reconfigure_python-release.git - vcs: git - version: release/melodic/ddynamic_reconfigure_python/0.0.1-0 -default_cfg_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/default_cfg_fkie/0.8.12-0 -delphi_esr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/delphi_esr_msgs/2.3.1-0 -delphi_mrr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/delphi_mrr_msgs/2.3.1-0 -delphi_srr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/delphi_srr_msgs/2.3.1-0 -depthcloud_encoder: - url: https://github.com/RobotWebTools-release/depthcloud_encoder-release.git - vcs: git - version: release/melodic/depthcloud_encoder/0.1.1-1 -depthimage_to_laserscan: - url: https://github.com/ros-gbp/depthimage_to_laserscan-release.git - vcs: git - version: release/melodic/depthimage_to_laserscan/1.0.8-0 -derived_object_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/derived_object_msgs/2.3.1-0 -desistek_saga_control: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/melodic/desistek_saga_control/0.3.2-0 -desistek_saga_description: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/melodic/desistek_saga_description/0.3.2-0 -desistek_saga_gazebo: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/melodic/desistek_saga_gazebo/0.3.2-0 -distance_map: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map/0.1.0-1 -distance_map_core: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_core/0.1.0-1 -distance_map_deadreck: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_deadreck/0.1.0-1 -distance_map_msgs: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_msgs/0.1.0-1 -distance_map_node: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_node/0.1.0-1 -distance_map_opencv: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_opencv/0.1.0-1 -distance_map_rviz: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_rviz/0.1.0-1 -distance_map_tools: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/melodic/distance_map_tools/0.1.0-1 -dlux_global_planner: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dlux_global_planner/0.2.5-1 -dlux_plugins: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dlux_plugins/0.2.5-1 -dockeros: - url: https://github.com/ct2034/dockeros-release.git - vcs: git - version: release/melodic/dockeros/1.1.0-1 -downward: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/downward/2.1.13-1 -driver_base: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/melodic/driver_base/1.6.8-0 -driver_common: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/melodic/driver_common/1.6.8-0 -dwa_local_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/dwa_local_planner/1.16.3-1 -dwb_critics: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dwb_critics/0.2.5-1 -dwb_local_planner: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dwb_local_planner/0.2.5-1 -dwb_msgs: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dwb_msgs/0.2.5-1 -dwb_plugins: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/dwb_plugins/0.2.5-1 -dynamic_edt_3d: - url: https://github.com/ros-gbp/octomap-release.git - vcs: git - version: release/melodic/dynamic_edt_3d/1.9.0-1 -dynamic_robot_state_publisher: - url: https://github.com/peci1/dynamic_robot_state_publisher-release.git - vcs: git - version: release/melodic/dynamic_robot_state_publisher/1.1.1-0 -dynamic_tf_publisher: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/dynamic_tf_publisher/2.2.10-0 -dynamixel_sdk: - url: https://github.com/ROBOTIS-GIT-release/DynamixelSDK-release.git - vcs: git - version: release/melodic/dynamixel_sdk/3.7.21-1 -dynamixel_workbench: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench/2.0.0-0 -dynamixel_workbench_controllers: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench_controllers/2.0.0-0 -dynamixel_workbench_msgs: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-msgs-release.git - vcs: git - version: release/melodic/dynamixel_workbench_msgs/2.0.0-0 -dynamixel_workbench_operators: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench_operators/2.0.0-0 -dynamixel_workbench_single_manager: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench_single_manager/2.0.0-0 -dynamixel_workbench_single_manager_gui: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench_single_manager_gui/2.0.0-0 -dynamixel_workbench_toolbox: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/melodic/dynamixel_workbench_toolbox/2.0.0-0 -easy_markers: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/melodic/easy_markers/0.2.4-0 -eca_a9_control: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/melodic/eca_a9_control/0.1.6-0 -eca_a9_description: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/melodic/eca_a9_description/0.1.6-0 -eca_a9_gazebo: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/melodic/eca_a9_gazebo/0.1.6-0 -ecl: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/melodic/ecl/0.60.3-0 -ecl_build: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/melodic/ecl_build/0.61.8-1 -ecl_command_line: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_command_line/0.62.2-0 -ecl_concepts: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_concepts/0.62.2-0 -ecl_config: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_config/0.61.6-0 -ecl_console: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_console/0.61.6-0 -ecl_containers: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_containers/0.62.2-0 -ecl_converters: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_converters/0.62.2-0 -ecl_converters_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_converters_lite/0.61.6-0 -ecl_core: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_core/0.62.2-0 -ecl_core_apps: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_core_apps/0.62.2-0 -ecl_devices: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_devices/0.62.2-0 -ecl_eigen: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_eigen/0.62.2-0 -ecl_errors: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_errors/0.61.6-0 -ecl_exceptions: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_exceptions/0.62.2-0 -ecl_filesystem: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_filesystem/0.62.2-0 -ecl_formatters: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_formatters/0.62.2-0 -ecl_geometry: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_geometry/0.62.2-0 -ecl_io: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_io/0.61.6-0 -ecl_ipc: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_ipc/0.62.2-0 -ecl_license: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/melodic/ecl_license/0.61.8-1 -ecl_linear_algebra: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_linear_algebra/0.62.2-0 -ecl_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_lite/0.61.6-0 -ecl_manipulation: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/melodic/ecl_manipulation/0.60.3-0 -ecl_manipulators: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/melodic/ecl_manipulators/0.60.3-0 -ecl_math: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_math/0.62.2-0 -ecl_mobile_robot: - url: https://github.com/yujinrobot-release/ecl_navigation-release.git - vcs: git - version: release/melodic/ecl_mobile_robot/0.60.3-0 -ecl_mpl: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_mpl/0.62.2-0 -ecl_navigation: - url: https://github.com/yujinrobot-release/ecl_navigation-release.git - vcs: git - version: release/melodic/ecl_navigation/0.60.3-0 -ecl_sigslots: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_sigslots/0.62.2-0 -ecl_sigslots_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_sigslots_lite/0.61.6-0 -ecl_statistics: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_statistics/0.62.2-0 -ecl_streams: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_streams/0.62.2-0 -ecl_threads: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_threads/0.62.2-0 -ecl_time: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_time/0.62.2-0 -ecl_time_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/melodic/ecl_time_lite/0.61.6-0 -ecl_tools: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/melodic/ecl_tools/0.61.8-1 -ecl_type_traits: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_type_traits/0.62.2-0 -ecl_utilities: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/melodic/ecl_utilities/0.62.2-0 -effort_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/effort_controllers/0.15.0-0 -eigenpy: - url: https://github.com/ipab-slmc/eigenpy_catkin-release.git - vcs: git - version: release/melodic/eigenpy/1.6.9-1 -eml: - url: https://github.com/ros-gbp/eml-release.git - vcs: git - version: release/melodic/eml/1.8.15-2 -epos2_motor_controller: - url: https://github.com/uos-gbp/epos2_motor_controller-release.git - vcs: git - version: release/melodic/epos2_motor_controller/1.0.0-4 -ethercat_grant: - url: https://github.com/shadow-robot/ethercat_grant-release.git - vcs: git - version: release/melodic/ethercat_grant/0.2.5-0 -ethercat_hardware: - url: https://github.com/pr2-gbp/pr2_ethercat_drivers-release.git - vcs: git - version: release/melodic/ethercat_hardware/1.8.19-1 -ethercat_trigger_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/ethercat_trigger_controllers/1.10.17-1 -eus_assimp: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/melodic/eus_assimp/0.4.3-0 -euscollada: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/melodic/euscollada/0.4.3-0 -euslisp: - url: https://github.com/tork-a/euslisp-release.git - vcs: git - version: release/melodic/euslisp/9.26.0-1 -eusurdf: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/melodic/eusurdf/0.4.3-0 -executive_smach_visualization: - url: https://github.com/jbohren/executive_smach_visualization-release.git - vcs: git - version: release/melodic/executive_smach_visualization/3.0.0-1 -exotica: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica/5.0.0-0 -exotica_aico_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_aico_solver/5.0.0-0 -exotica_collision_scene_fcl: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_collision_scene_fcl/5.0.0-0 -exotica_collision_scene_fcl_latest: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_collision_scene_fcl_latest/5.0.0-0 -exotica_core: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_core/5.0.0-0 -exotica_core_task_maps: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_core_task_maps/5.0.0-0 -exotica_examples: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_examples/5.0.0-0 -exotica_ik_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_ik_solver/5.0.0-0 -exotica_levenberg_marquardt_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_levenberg_marquardt_solver/5.0.0-0 -exotica_ompl_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_ompl_solver/5.0.0-0 -exotica_python: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_python/5.0.0-0 -exotica_time_indexed_rrt_connect_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/melodic/exotica_time_indexed_rrt_connect_solver/5.0.0-0 -exotica_val_description: - url: https://github.com/wxmerkt/exotica_val_description-release.git - vcs: git - version: release/melodic/exotica_val_description/1.0.0-1 -face_detector: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/face_detector/1.2.0-1 -fake_joint: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/melodic/fake_joint/0.0.4-1 -fake_joint_driver: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/melodic/fake_joint_driver/0.0.4-1 -fake_joint_launch: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/melodic/fake_joint_launch/0.0.4-1 -fake_localization: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/fake_localization/1.16.3-1 -fcl_catkin: - url: https://github.com/wxmerkt/fcl_catkin-release.git - vcs: git - version: release/melodic/fcl_catkin/0.5.99-1 -fetch_auto_dock_msgs: - url: https://github.com/fetchrobotics-gbp/fetch_msgs-release.git - vcs: git - version: release/melodic/fetch_auto_dock_msgs/1.1.1-0 -fetch_bringup: - url: https://github.com/fetchrobotics-gbp/fetch_robots-release.git - vcs: git - version: release/melodic/fetch_bringup/0.8.8-1 -fetch_calibration: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_calibration/0.8.2-1 -fetch_depth_layer: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_depth_layer/0.8.2-1 -fetch_description: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_description/0.8.2-1 -fetch_driver_msgs: - url: https://github.com/fetchrobotics-gbp/fetch_msgs-release.git - vcs: git - version: release/melodic/fetch_driver_msgs/1.1.1-0 -fetch_drivers: - url: https://github.com/fetchrobotics-gbp/fetch_robots-release.git - vcs: git - version: release/melodic/fetch_drivers/0.8.8-1 -fetch_gazebo: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/melodic/fetch_gazebo/0.9.2-1 -fetch_gazebo_demo: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/melodic/fetch_gazebo_demo/0.9.2-1 -fetch_ikfast_plugin: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_ikfast_plugin/0.8.2-1 -fetch_maps: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_maps/0.8.2-1 -fetch_moveit_config: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_moveit_config/0.8.2-1 -fetch_navigation: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_navigation/0.8.2-1 -fetch_open_auto_dock: - url: https://github.com/fetchrobotics-gbp/fetch_open_auto_dock-gbp.git - vcs: git - version: release/melodic/fetch_open_auto_dock/0.1.2-0 -fetch_ros: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_ros/0.8.2-1 -fetch_simple_linear_controller: - url: https://github.com/gt-rail-release/fetch_simple_linear_controller-release.git - vcs: git - version: release/melodic/fetch_simple_linear_controller/0.0.1-1 -fetch_simulation: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/melodic/fetch_simulation/0.9.2-1 -fetch_teleop: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/melodic/fetch_teleop/0.8.2-1 -fetch_tools: - url: https://github.com/fetchrobotics-gbp/fetch_tools-release.git - vcs: git - version: release/melodic/fetch_tools/0.2.1-0 -fetchit_challenge: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/melodic/fetchit_challenge/0.9.2-1 -ff: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/ff/2.1.13-1 -ffha: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/ffha/2.1.13-1 -fiducial_msgs: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/melodic/fiducial_msgs/0.11.0-1 -fiducial_slam: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/melodic/fiducial_slam/0.11.0-1 -fiducials: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/melodic/fiducials/0.11.0-1 -file_management: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/melodic/file_management/1.1.2-1 -find_object_2d: - url: https://github.com/introlab/find_object_2d-release.git - vcs: git - version: release/melodic/find_object_2d/0.6.2-1 -fingertip_pressure: - url: https://github.com/pr2-gbp/pr2_ethercat_drivers-release.git - vcs: git - version: release/melodic/fingertip_pressure/1.8.19-1 -fkie_message_filters: - url: https://github.com/fkie-release/message_filters-release.git - vcs: git - version: release/melodic/fkie_message_filters/1.0.1-1 -fkie_potree_rviz_plugin: - url: https://github.com/fkie-release/potree_rviz_plugin-release.git - vcs: git - version: release/melodic/fkie_potree_rviz_plugin/1.0.0-0 -flatbuffers: - url: https://github.com/yujinrobot-release/flatbuffers-release.git - vcs: git - version: release/melodic/flatbuffers/1.1.0-0 -flexbe_behavior_engine: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_behavior_engine/1.2.2-1 -flexbe_core: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_core/1.2.2-1 -flexbe_input: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_input/1.2.2-1 -flexbe_mirror: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_mirror/1.2.2-1 -flexbe_msgs: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_msgs/1.2.2-1 -flexbe_onboard: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_onboard/1.2.2-1 -flexbe_states: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_states/1.2.2-1 -flexbe_testing: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_testing/1.2.2-1 -flexbe_widget: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/melodic/flexbe_widget/1.2.2-1 -flir_boson_usb: - url: https://github.com/astuff/flir_boson_usb-release.git - vcs: git - version: release/melodic/flir_boson_usb/1.2.1-1 -fmi_adapter: - url: https://github.com/boschresearch/fmi_adapter-release.git - vcs: git - version: release/melodic/fmi_adapter/1.0.2-0 -fmi_adapter_examples: - url: https://github.com/boschresearch/fmi_adapter-release.git - vcs: git - version: release/melodic/fmi_adapter_examples/1.0.2-0 -force_torque_sensor_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/force_torque_sensor_controller/0.15.0-0 -four_wheel_steering_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/four_wheel_steering_controller/0.15.0-0 -four_wheel_steering_msgs: - url: https://github.com/ros-drivers-gbp/four_wheel_steering_msgs-release.git - vcs: git - version: release/melodic/four_wheel_steering_msgs/1.0.0-0 -franka_control: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_control/0.6.0-1 -franka_description: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_description/0.6.0-1 -franka_example_controllers: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_example_controllers/0.6.0-1 -franka_gripper: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_gripper/0.6.0-1 -franka_hw: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_hw/0.6.0-1 -franka_msgs: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_msgs/0.6.0-1 -franka_ros: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_ros/0.6.0-1 -franka_visualization: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/melodic/franka_visualization/0.6.0-1 -freight_bringup: - url: https://github.com/fetchrobotics-gbp/fetch_robots-release.git - vcs: git - version: release/melodic/freight_bringup/0.8.8-1 -fsrobo_r: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r/0.7.1-1 -fsrobo_r_bringup: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_bringup/0.7.1-1 -fsrobo_r_description: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_description/0.7.1-1 -fsrobo_r_driver: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_driver/0.7.1-1 -fsrobo_r_moveit_config: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_moveit_config/0.7.1-1 -fsrobo_r_msgs: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_msgs/0.7.1-1 -fsrobo_r_trajectory_filters: - url: https://github.com/FUJISOFT-Robotics/fsrobo_r-release.git - vcs: git - version: release/melodic/fsrobo_r_trajectory_filters/0.7.1-1 -gateway_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/gateway_msgs/0.9.0-0 -generic_throttle: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/generic_throttle/0.6.15-1 -geographic_info: - url: https://github.com/ros-geographic-info/geographic_info-release.git - vcs: git - version: release/melodic/geographic_info/0.5.3-0 -geometric_shapes: - url: https://github.com/ros-gbp/geometric_shapes-release.git - vcs: git - version: release/melodic/geometric_shapes/0.6.1-0 -geometry2: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/melodic/geometry2/0.6.5-0 -global_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/global_planner/1.16.3-1 -global_planner_tests: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/global_planner_tests/0.2.5-1 -gmapping: - url: https://github.com/ros-gbp/slam_gmapping-release.git - vcs: git - version: release/melodic/gmapping/1.4.0-1 -goal_passer: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/goal_passer/0.3.3-1 -gps_common: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/melodic/gps_common/0.3.0-1 -gps_umd: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/melodic/gps_umd/0.3.0-1 -gpsd_client: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/melodic/gpsd_client/0.3.0-1 -graft: - url: https://github.com/ros-gbp/graft-release.git - vcs: git - version: release/melodic/graft/0.2.3-2 -grasping_msgs: - url: https://github.com/mikeferguson/grasping_msgs-gbp.git - vcs: git - version: release/melodic/grasping_msgs/0.3.1-0 -grid_map_costmap_2d: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/melodic/grid_map_costmap_2d/1.6.2-1 -grid_map_pcl: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/melodic/grid_map_pcl/1.6.2-1 -grid_map_sdf: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/melodic/grid_map_sdf/1.6.2-1 -gripper_action_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/gripper_action_controller/0.15.0-0 -grpc: - url: https://github.com/CogRobRelease/catkin_grpc-release.git - vcs: git - version: release/melodic/grpc/0.0.10-0 -gscam: - url: https://github.com/ros-drivers-gbp/gscam-release.git - vcs: git - version: release/melodic/gscam/1.0.1-0 -h264_encoder_core: - url: https://github.com/aws-gbp/h264_encoder_core-release.git - vcs: git - version: release/melodic/h264_encoder_core/2.0.3-1 -h264_video_encoder: - url: https://github.com/aws-gbp/h264_video_encoder-release.git - vcs: git - version: release/melodic/h264_video_encoder/1.1.4-1 -handeye: - url: https://github.com/crigroup/handeye-release.git - vcs: git - version: release/melodic/handeye/0.1.1-2 -haros_catkin: - url: https://github.com/rosin-project/haros_catkin-release.git - vcs: git - version: release/melodic/haros_catkin/0.1.1-1 -health_metric_collector: - url: https://github.com/aws-gbp/health_metric_collector-release.git - vcs: git - version: release/melodic/health_metric_collector/2.0.1-1 -hebi_cpp_api: - url: https://github.com/HebiRobotics/hebi_cpp_api_ros-release.git - vcs: git - version: release/melodic/hebi_cpp_api/3.1.1-1 -hebi_description: - url: https://github.com/HebiRobotics/hebi_description-release.git - vcs: git - version: release/melodic/hebi_description/0.1.0-1 -hector_components_description: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/melodic/hector_components_description/0.5.0-0 -hector_compressed_map_transport: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_compressed_map_transport/0.4.0-1 -hector_gazebo: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/melodic/hector_gazebo/0.5.1-0 -hector_gazebo_plugins: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/melodic/hector_gazebo_plugins/0.5.1-0 -hector_gazebo_thermal_camera: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/melodic/hector_gazebo_thermal_camera/0.5.1-0 -hector_gazebo_worlds: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/melodic/hector_gazebo_worlds/0.5.1-0 -hector_geotiff: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_geotiff/0.4.0-1 -hector_geotiff_plugins: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_geotiff_plugins/0.4.0-1 -hector_imu_attitude_to_tf: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_imu_attitude_to_tf/0.4.0-1 -hector_imu_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_imu_tools/0.4.0-1 -hector_map_server: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_map_server/0.4.0-1 -hector_map_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_map_tools/0.4.0-1 -hector_mapping: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_mapping/0.4.0-1 -hector_marker_drawing: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_marker_drawing/0.4.0-1 -hector_models: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/melodic/hector_models/0.5.0-0 -hector_nav_msgs: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_nav_msgs/0.4.0-1 -hector_sensors_description: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/melodic/hector_sensors_description/0.5.0-0 -hector_sensors_gazebo: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/melodic/hector_sensors_gazebo/0.5.1-0 -hector_slam: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_slam/0.4.0-1 -hector_slam_launch: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_slam_launch/0.4.0-1 -hector_trajectory_server: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/melodic/hector_trajectory_server/0.4.0-1 -hector_xacro_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/melodic/hector_xacro_tools/0.5.0-0 -hls_lfcd_lds_driver: - url: https://github.com/ROBOTIS-GIT-release/hls-lfcd-lds-driver-release.git - vcs: git - version: release/melodic/hls_lfcd_lds_driver/1.1.0-1 -hostapd_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/hostapd_access_point/1.0.16-1 -hpp-fcl: - url: https://github.com/ipab-slmc/hpp-fcl_catkin-release.git - vcs: git - version: release/melodic/hpp-fcl/1.0.1-2 -husky_base: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_base/0.4.2-1 -husky_bringup: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_bringup/0.4.2-1 -husky_control: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_control/0.4.2-1 -husky_description: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_description/0.4.2-1 -husky_desktop: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_desktop/0.4.2-1 -husky_gazebo: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_gazebo/0.4.2-1 -husky_msgs: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_msgs/0.4.2-1 -husky_navigation: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_navigation/0.4.2-1 -husky_robot: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_robot/0.4.2-1 -husky_simulator: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_simulator/0.4.2-1 -husky_viz: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/melodic/husky_viz/0.4.2-1 -ibeo_core: - url: https://github.com/astuff/ibeo_core-release.git - vcs: git - version: release/melodic/ibeo_core/2.0.2-0 -ibeo_lux: - url: https://github.com/astuff/ibeo_lux-release.git - vcs: git - version: release/melodic/ibeo_lux/2.0.1-0 -ibeo_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/ibeo_msgs/2.3.1-0 -ieee80211_channels: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/ieee80211_channels/1.0.16-1 -ifopt: - url: https://github.com/ethz-adrl/ifopt-release.git - vcs: git - version: release/melodic/ifopt/2.0.7-1 -igvc_self_drive_description: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/melodic/igvc_self_drive_description/0.1.4-1 -igvc_self_drive_gazebo: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/melodic/igvc_self_drive_gazebo/0.1.4-1 -igvc_self_drive_gazebo_plugins: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/melodic/igvc_self_drive_gazebo_plugins/0.1.4-1 -igvc_self_drive_sim: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/melodic/igvc_self_drive_sim/0.1.4-1 -iirob_filters: - url: https://github.com/KITrobotics/iirob_filters-release.git - vcs: git - version: release/melodic/iirob_filters/0.8.1-2 -image_cb_detector: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/image_cb_detector/0.10.14-0 -image_view2: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/image_view2/2.2.10-0 -imagesift: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/imagesift/1.2.10-0 -imagezero: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/melodic/imagezero/0.2.4-0 -imagezero_image_transport: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/melodic/imagezero_image_transport/0.2.4-0 -imagezero_ros: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/melodic/imagezero_ros/0.2.4-0 -imu_complementary_filter: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/melodic/imu_complementary_filter/1.2.1-1 -imu_filter_madgwick: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/melodic/imu_filter_madgwick/1.2.1-1 -imu_pipeline: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/melodic/imu_pipeline/0.2.3-0 -imu_processors: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/melodic/imu_processors/0.2.3-0 -imu_sensor_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/imu_sensor_controller/0.15.0-0 -imu_tools: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/melodic/imu_tools/1.2.1-1 -imu_transformer: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/melodic/imu_transformer/0.2.3-0 -industrial_core: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_core/0.7.1-1 -industrial_deprecated: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_deprecated/0.7.1-1 -industrial_msgs: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_msgs/0.7.1-1 -industrial_robot_client: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_robot_client/0.7.1-1 -industrial_robot_simulator: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_robot_simulator/0.7.1-1 -industrial_robot_status_controller: - url: https://github.com/gavanderhoorn/industrial_robot_status_controller-release.git - vcs: git - version: release/melodic/industrial_robot_status_controller/0.1.2-1 -industrial_robot_status_interface: - url: https://github.com/gavanderhoorn/industrial_robot_status_controller-release.git - vcs: git - version: release/melodic/industrial_robot_status_interface/0.1.2-1 -industrial_trajectory_filters: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_trajectory_filters/0.7.1-1 -industrial_utils: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/industrial_utils/0.7.1-1 -interactive_marker_proxy: - url: https://github.com/RobotWebTools-release/interactive_marker_proxy-release.git - vcs: git - version: release/melodic/interactive_marker_proxy/0.1.2-0 -interactive_marker_twist_server: - url: https://github.com/ros-gbp/interactive_marker_twist_server-release.git - vcs: git - version: release/melodic/interactive_marker_twist_server/1.2.0-0 -interval_intersection: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/interval_intersection/0.10.14-0 -ipa_3d_fov_visualization: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/melodic/ipa_3d_fov_visualization/0.6.14-1 -ipr_extern: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/melodic/ipr_extern/0.8.8-1 -ivcon: - url: https://github.com/ros-gbp/ivcon-release.git - vcs: git - version: release/melodic/ivcon/0.1.7-0 -jackal_control: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/melodic/jackal_control/0.6.3-1 -jackal_description: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/melodic/jackal_description/0.6.3-1 -jackal_desktop: - url: https://github.com/clearpath-gbp/jackal_desktop-release.git - vcs: git - version: release/melodic/jackal_desktop/0.3.2-1 -jackal_gazebo: - url: https://github.com/clearpath-gbp/jackal_simulator-release.git - vcs: git - version: release/melodic/jackal_gazebo/0.3.0-1 -jackal_msgs: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/melodic/jackal_msgs/0.6.3-1 -jackal_navigation: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/melodic/jackal_navigation/0.6.3-1 -jackal_simulator: - url: https://github.com/clearpath-gbp/jackal_simulator-release.git - vcs: git - version: release/melodic/jackal_simulator/0.3.0-1 -jackal_tutorials: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/melodic/jackal_tutorials/0.6.3-1 -jackal_viz: - url: https://github.com/clearpath-gbp/jackal_desktop-release.git - vcs: git - version: release/melodic/jackal_viz/0.3.2-1 -joint_states_settler: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/joint_states_settler/0.10.14-0 -joint_trajectory_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/joint_trajectory_action/1.10.17-1 -joint_trajectory_action_tools: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/joint_trajectory_action_tools/0.0.11-0 -joint_trajectory_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/joint_trajectory_controller/0.15.0-0 -joint_trajectory_generator: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/joint_trajectory_generator/0.0.11-0 -jointstick: - url: https://github.com/gstavrinos/jointstick-release.git - vcs: git - version: release/melodic/jointstick/0.9.1-2 -joy: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/melodic/joy/1.13.0-1 -joy_listener: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/melodic/joy_listener/0.2.4-0 -joy_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/melodic/joy_teleop/0.3.0-0 -joystick_drivers: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/melodic/joystick_drivers/1.13.0-1 -joystick_interrupt: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/joystick_interrupt/0.5.1-1 -jpeg_streamer: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/melodic/jpeg_streamer/0.2.7-0 -jsk_3rdparty: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/jsk_3rdparty/2.1.13-1 -jsk_common: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_common/2.2.10-0 -jsk_common_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/jsk_common_msgs/4.3.1-0 -jsk_data: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_data/2.2.10-0 -jsk_footstep_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/jsk_footstep_msgs/4.3.1-0 -jsk_gui_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/jsk_gui_msgs/4.3.1-0 -jsk_hark_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/jsk_hark_msgs/4.3.1-0 -jsk_interactive: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_interactive/2.1.5-0 -jsk_interactive_marker: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_interactive_marker/2.1.5-0 -jsk_interactive_test: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_interactive_test/2.1.5-0 -jsk_model_tools: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/melodic/jsk_model_tools/0.4.3-0 -jsk_network_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_network_tools/2.2.10-0 -jsk_pcl_ros: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_pcl_ros/1.2.10-0 -jsk_pcl_ros_utils: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_pcl_ros_utils/1.2.10-0 -jsk_perception: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_perception/1.2.10-0 -jsk_pr2eus: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/melodic/jsk_pr2eus/0.3.14-3 -jsk_recognition: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_recognition/1.2.10-0 -jsk_recognition_msgs: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_recognition_msgs/1.2.10-0 -jsk_recognition_utils: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/jsk_recognition_utils/1.2.10-0 -jsk_roseus: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/melodic/jsk_roseus/1.7.4-1 -jsk_rqt_plugins: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_rqt_plugins/2.1.5-0 -jsk_rviz_plugins: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_rviz_plugins/2.1.5-0 -jsk_tilt_laser: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_tilt_laser/2.2.10-0 -jsk_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_tools/2.2.10-0 -jsk_topic_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/jsk_topic_tools/2.2.10-0 -jsk_visualization: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/melodic/jsk_visualization/2.1.5-0 -jskeus: - url: https://github.com/tork-a/jskeus-release.git - vcs: git - version: release/melodic/jskeus/1.2.1-1 -json_msgs: - url: https://github.com/locusrobotics/json_transport-release.git - vcs: git - version: release/melodic/json_msgs/0.0.3-0 -json_transport: - url: https://github.com/locusrobotics/json_transport-release.git - vcs: git - version: release/melodic/json_transport/0.0.3-0 -julius: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/julius/2.1.13-1 -julius_ros: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/julius_ros/2.1.13-1 -kalman_filter: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/melodic/kalman_filter/0.2.4-0 -kartech_linear_actuator_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/kartech_linear_actuator_msgs/2.3.1-0 -key_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/melodic/key_teleop/0.3.0-0 -kinesis_manager: - url: https://github.com/aws-gbp/kinesis_manager-release.git - vcs: git - version: release/melodic/kinesis_manager/2.0.1-1 -kinesis_video_msgs: - url: https://github.com/aws-gbp/kinesis_video_streamer-release.git - vcs: git - version: release/melodic/kinesis_video_msgs/2.0.2-1 -kinesis_video_streamer: - url: https://github.com/aws-gbp/kinesis_video_streamer-release.git - vcs: git - version: release/melodic/kinesis_video_streamer/2.0.2-1 -kobuki_core: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/melodic/kobuki_core/0.7.8-0 -kobuki_dock_drive: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/melodic/kobuki_dock_drive/0.7.8-0 -kobuki_driver: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/melodic/kobuki_driver/0.7.8-0 -kobuki_ftdi: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/melodic/kobuki_ftdi/0.7.8-0 -kobuki_msgs: - url: https://github.com/yujinrobot-release/kobuki_msgs-release.git - vcs: git - version: release/melodic/kobuki_msgs/0.7.0-1 -ksql_airport: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/melodic/ksql_airport/0.0.1-1 -laptop_battery_monitor: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/melodic/laptop_battery_monitor/0.2.1-1 -laser_cb_detector: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/laser_cb_detector/0.10.14-0 -laser_filtering: - url: https://github.com/wu-robotics/laser_filtering_release.git - vcs: git - version: release/melodic/laser_filtering/0.0.4-0 -laser_filters_jsk_patch: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/laser_filters_jsk_patch/2.1.13-1 -laser_proc: - url: https://github.com/ros-gbp/laser_proc-release.git - vcs: git - version: release/melodic/laser_proc/0.1.5-0 -laser_scan_densifier: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/melodic/laser_scan_densifier/0.7.1-1 -laser_scan_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/laser_scan_publisher_tutorial/0.2.3-1 -laser_tilt_controller_filter: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/laser_tilt_controller_filter/0.1.28-1 -lauv_control: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/melodic/lauv_control/0.1.6-0 -lauv_description: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/melodic/lauv_description/0.1.6-0 -lauv_gazebo: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/melodic/lauv_gazebo/0.1.6-0 -leg_detector: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/leg_detector/1.2.0-1 -leuze_bringup: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_bringup/1.0.1-1 -leuze_description: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_description/1.0.1-1 -leuze_msgs: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_msgs/1.0.1-1 -leuze_phidget_driver: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_phidget_driver/1.0.1-1 -leuze_ros_drivers: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_ros_drivers/1.0.1-1 -leuze_rsl_driver: - url: https://github.com/ipa-led/leuze_ros_drivers-release.git - vcs: git - version: release/melodic/leuze_rsl_driver/1.0.1-1 -lex_common: - url: https://github.com/aws-gbp/lex_common-release.git - vcs: git - version: release/melodic/lex_common/1.0.0-1 -lex_common_msgs: - url: https://github.com/aws-gbp/lex_node-release.git - vcs: git - version: release/melodic/lex_common_msgs/2.0.1-1 -lex_node: - url: https://github.com/aws-gbp/lex_node-release.git - vcs: git - version: release/melodic/lex_node/2.0.1-1 -lgsvl_msgs: - url: https://github.com/lgsvl/lgsvl_msgs-release.git - vcs: git - version: release/melodic/lgsvl_msgs/0.0.1-0 -libcmt: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/libcmt/2.1.13-1 -libcreate: - url: https://github.com/AutonomyLab/libcreate-release.git - vcs: git - version: release/melodic/libcreate/2.0.0-1 -libdlib: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/libdlib/0.6.14-1 -libfranka: - url: https://github.com/frankaemika/libfranka-release.git - vcs: git - version: release/melodic/libfranka/0.7.1-1 -libg2o: - url: https://github.com/ros-gbp/libg2o-release.git - vcs: git - version: release/melodic/libg2o/2018.3.25-0 -libmavconn: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/melodic/libmavconn/1.0.0-1 -libmodbus: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/melodic/libmodbus/0.8.8-1 -libntcan: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/libntcan/0.6.14-1 -libpcan: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/libpcan/0.6.14-1 -libphidget21: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/libphidget21/0.7.9-1 -libphidgets: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/libphidgets/0.6.14-1 -libqt_concurrent: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_concurrent/1.0.1-0 -libqt_core: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_core/1.0.1-0 -libqt_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_dev/1.0.1-0 -libqt_gui: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_gui/1.0.1-0 -libqt_network: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_network/1.0.1-0 -libqt_opengl: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_opengl/1.0.1-0 -libqt_opengl_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_opengl_dev/1.0.1-0 -libqt_svg_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_svg_dev/1.0.1-0 -libqt_widgets: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/libqt_widgets/1.0.1-0 -librealsense2: - url: https://github.com/IntelRealSense/librealsense2-release.git - vcs: git - version: release/melodic/librealsense2/2.31.0-3 -libreflexxestype2: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/melodic/libreflexxestype2/0.8.8-1 -libsensors_monitor: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/melodic/libsensors_monitor/0.2.1-1 -libsiftfast: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/libsiftfast/2.1.13-1 -libuvc: - url: https://github.com/ros-drivers-gbp/libuvc-release.git - vcs: git - version: release/melodic/libuvc/0.0.6-0 -libuvc_camera: - url: https://github.com/ros-drivers-gbp/libuvc_ros-release.git - vcs: git - version: release/melodic/libuvc_camera/0.0.10-1 -libuvc_ros: - url: https://github.com/ros-drivers-gbp/libuvc_ros-release.git - vcs: git - version: release/melodic/libuvc_ros/0.0.10-1 -linksys_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/linksys_access_point/1.0.16-1 -linux_networking: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/linux_networking/1.0.16-1 -linux_peripheral_interfaces: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/melodic/linux_peripheral_interfaces/0.2.1-1 -lms1xx: - url: https://github.com/clearpath-gbp/lms1xx-release.git - vcs: git - version: release/melodic/lms1xx/0.2.0-1 -lockfree: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/melodic/lockfree/1.0.25-0 -locomotor: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/locomotor/0.2.5-1 -locomotor_msgs: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/locomotor_msgs/0.2.5-1 -locomove_base: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/locomove_base/0.2.5-1 -lpg_planner: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/lpg_planner/2.1.13-1 -lusb: - url: https://github.com/DataspeedInc-release/lusb-release.git - vcs: git - version: release/melodic/lusb/1.1.0-0 -lvr2: - url: https://github.com/uos-gbp/lvr2-release.git - vcs: git - version: release/melodic/lvr2/19.12.1-1 -map_laser: - url: https://github.com/wu-robotics/laser_filtering_release.git - vcs: git - version: release/melodic/map_laser/0.0.4-0 -map_merge_3d: - url: https://github.com/hrnr/map-merge-release.git - vcs: git - version: release/melodic/map_merge_3d/0.1.1-0 -map_organizer: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/map_organizer/0.5.1-1 -map_organizer_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/map_organizer_msgs/0.5.0-1 -mapviz: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/melodic/mapviz/1.2.0-1 -mapviz_plugins: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/melodic/mapviz_plugins/1.2.0-1 -marker_msgs: - url: https://github.com/tuw-robotics/marker_msgs-release.git - vcs: git - version: release/melodic/marker_msgs/0.0.6-0 -marti_can_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_can_msgs/0.8.0-0 -marti_common_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_common_msgs/0.8.0-0 -marti_data_structures: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/marti_data_structures/2.11.0-1 -marti_nav_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_nav_msgs/0.8.0-0 -marti_perception_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_perception_msgs/0.8.0-0 -marti_sensor_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_sensor_msgs/0.8.0-0 -marti_status_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_status_msgs/0.8.0-0 -marti_visualization_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/melodic/marti_visualization_msgs/0.8.0-0 -master_discovery_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/master_discovery_fkie/0.8.12-0 -master_sync_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/master_sync_fkie/0.8.12-0 -mav_comm: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/melodic/mav_comm/3.3.2-0 -mav_msgs: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/melodic/mav_msgs/3.3.2-0 -mav_planning_msgs: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/melodic/mav_planning_msgs/3.3.2-0 -mavlink: - url: https://github.com/mavlink/mavlink-gbp-release.git - vcs: git - version: release/melodic/mavlink/2019.12.30-1 -mavros: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/melodic/mavros/1.0.0-1 -mavros_extras: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/melodic/mavros_extras/1.0.0-1 -mavros_msgs: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/melodic/mavros_msgs/1.0.0-1 -mbf_abstract_core: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_abstract_core/0.2.5-1 -mbf_abstract_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_abstract_nav/0.2.5-1 -mbf_costmap_core: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_costmap_core/0.2.5-1 -mbf_costmap_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_costmap_nav/0.2.5-1 -mbf_msgs: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_msgs/0.2.5-1 -mbf_simple_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_simple_nav/0.2.5-1 -mbf_utility: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/mbf_utility/0.2.5-1 -mcl_3dl: - url: https://github.com/at-wat/mcl_3dl-release.git - vcs: git - version: release/melodic/mcl_3dl/0.1.7-1 -mcl_3dl_msgs: - url: https://github.com/at-wat/mcl_3dl_msgs-release.git - vcs: git - version: release/melodic/mcl_3dl_msgs/0.1.2-0 -mcmillan_airfield: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/melodic/mcmillan_airfield/0.0.1-1 -md49_base_controller: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/melodic/md49_base_controller/0.1.4-1 -md49_messages: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/melodic/md49_messages/0.1.4-1 -md49_serialport: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/melodic/md49_serialport/0.1.4-1 -mecanum_gazebo_plugin: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/melodic/mecanum_gazebo_plugin/0.1.0-1 -message_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/message_relay/0.0.2-1 -microstrain_3dmgx2_imu: - url: https://github.com/ros-gbp/microstrain_3dmgx2_imu-release.git - vcs: git - version: release/melodic/microstrain_3dmgx2_imu/1.5.13-1 -microstrain_mips: - url: https://github.com/ros-drivers-gbp/microstrain_mips-release.git - vcs: git - version: release/melodic/microstrain_mips/0.0.3-1 -mini_maxwell: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/mini_maxwell/2.1.13-1 -mir_actions: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_actions/1.0.4-1 -mir_description: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_description/1.0.4-1 -mir_driver: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_driver/1.0.4-1 -mir_dwb_critics: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_dwb_critics/1.0.4-1 -mir_gazebo: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_gazebo/1.0.4-1 -mir_msgs: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_msgs/1.0.4-1 -mir_navigation: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_navigation/1.0.4-1 -mir_robot: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/melodic/mir_robot/1.0.4-1 -ml_classifiers: - url: https://github.com/astuff/ml_classifiers-release.git - vcs: git - version: release/melodic/ml_classifiers/1.0.1-1 -mobileye_560_660_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/mobileye_560_660_msgs/2.3.1-0 -mongodb_log: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/melodic/mongodb_log/0.5.2-1 -mongodb_store: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/melodic/mongodb_store/0.5.2-1 -mongodb_store_msgs: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/melodic/mongodb_store_msgs/0.5.2-1 -monocam_settler: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/monocam_settler/0.10.14-0 -mouse_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/melodic/mouse_teleop/0.3.0-0 -move_base: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/move_base/1.16.3-1 -move_base_flex: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/melodic/move_base_flex/0.2.5-1 -move_base_msgs: - url: https://github.com/ros-gbp/navigation_msgs-release.git - vcs: git - version: release/melodic/move_base_msgs/1.13.0-0 -move_slow_and_clear: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/move_slow_and_clear/1.16.3-1 -moveit: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit/1.0.2-1 -moveit_chomp_optimizer_adapter: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_chomp_optimizer_adapter/1.0.2-1 -moveit_commander: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_commander/1.0.2-1 -moveit_controller_manager_example: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_controller_manager_example/1.0.2-1 -moveit_core: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_core/1.0.2-1 -moveit_experimental: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_experimental/1.0.2-1 -moveit_fake_controller_manager: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_fake_controller_manager/1.0.2-1 -moveit_kinematics: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_kinematics/1.0.2-1 -moveit_msgs: - url: https://github.com/ros-gbp/moveit_msgs-release.git - vcs: git - version: release/melodic/moveit_msgs/0.10.0-0 -moveit_planners: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_planners/1.0.2-1 -moveit_planners_chomp: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_planners_chomp/1.0.2-1 -moveit_planners_ompl: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_planners_ompl/1.0.2-1 -moveit_plugins: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_plugins/1.0.2-1 -moveit_pr2: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/melodic/moveit_pr2/0.7.3-1 -moveit_python: - url: https://github.com/mikeferguson/moveit_python-release.git - vcs: git - version: release/melodic/moveit_python/0.3.3-1 -moveit_resources: - url: https://github.com/ros-gbp/moveit_resources-release.git - vcs: git - version: release/melodic/moveit_resources/0.6.4-0 -moveit_ros: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros/1.0.2-1 -moveit_ros_benchmarks: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_benchmarks/1.0.2-1 -moveit_ros_control_interface: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_control_interface/1.0.2-1 -moveit_ros_manipulation: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_manipulation/1.0.2-1 -moveit_ros_move_group: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_move_group/1.0.2-1 -moveit_ros_perception: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_perception/1.0.2-1 -moveit_ros_planning: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_planning/1.0.2-1 -moveit_ros_planning_interface: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_planning_interface/1.0.2-1 -moveit_ros_robot_interaction: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_robot_interaction/1.0.2-1 -moveit_ros_visualization: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_visualization/1.0.2-1 -moveit_ros_warehouse: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_ros_warehouse/1.0.2-1 -moveit_runtime: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_runtime/1.0.2-1 -moveit_setup_assistant: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_setup_assistant/1.0.2-1 -moveit_sim_controller: - url: https://github.com/PickNikRobotics/moveit_sim_controller-release.git - vcs: git - version: release/melodic/moveit_sim_controller/0.2.0-1 -moveit_simple_controller_manager: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/melodic/moveit_simple_controller_manager/1.0.2-1 -moveit_visual_tools: - url: https://github.com/ros-gbp/moveit_visual_tools-release.git - vcs: git - version: release/melodic/moveit_visual_tools/3.5.2-0 -movie_publisher: - url: https://github.com/peci1/movie_publisher-release.git - vcs: git - version: release/melodic/movie_publisher/1.3.0-1 -mrpt1: - url: https://github.com/mrpt-ros-pkg-release/mrpt1-release.git - vcs: git - version: release/melodic/mrpt1/1.5.9-1 -mrpt_bridge: - url: https://github.com/mrpt-ros-pkg-release/mrpt_bridge-release.git - vcs: git - version: release/melodic/mrpt_bridge/0.1.25-0 -mrpt_ekf_slam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_ekf_slam_2d/0.1.10-1 -mrpt_ekf_slam_3d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_ekf_slam_3d/0.1.10-1 -mrpt_graphslam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_graphslam_2d/0.1.10-1 -mrpt_icp_slam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_icp_slam_2d/0.1.10-1 -mrpt_local_obstacles: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_local_obstacles/0.1.26-1 -mrpt_localization: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_localization/0.1.26-1 -mrpt_map: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_map/0.1.26-1 -mrpt_msgs: - url: https://github.com/mrpt-ros-pkg-release/mrpt_msgs-release.git - vcs: git - version: release/melodic/mrpt_msgs/0.1.22-0 -mrpt_navigation: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_navigation/0.1.26-1 -mrpt_rawlog: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_rawlog/0.1.26-1 -mrpt_rbpf_slam: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_rbpf_slam/0.1.10-1 -mrpt_reactivenav2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_reactivenav2d/0.1.26-1 -mrpt_slam: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/melodic/mrpt_slam/0.1.10-1 -mrpt_tutorials: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/melodic/mrpt_tutorials/0.1.26-1 -multi_interface_roam: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/multi_interface_roam/1.0.16-1 -multi_map_server: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/multi_map_server/2.2.10-0 -multi_object_tracking_lidar: - url: https://github.com/praveen-palanisamy/multi_object_tracking_lidar-release.git - vcs: git - version: release/melodic/multi_object_tracking_lidar/1.0.2-1 -multimaster_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/multimaster_fkie/0.8.12-0 -multimaster_launch: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/multimaster_launch/0.0.2-1 -multimaster_msgs: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/multimaster_msgs/0.0.2-1 -multimaster_msgs_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/multimaster_msgs_fkie/0.8.12-0 -multires_image: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/melodic/multires_image/1.2.0-1 -multisense: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense/4.0.3-1 -multisense_bringup: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense_bringup/4.0.3-1 -multisense_cal_check: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense_cal_check/4.0.3-1 -multisense_description: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense_description/4.0.3-1 -multisense_lib: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense_lib/4.0.3-1 -multisense_ros: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/melodic/multisense_ros/4.0.3-1 -mvsim: - url: https://github.com/ual-arm-ros-pkg-release/mvsim-release.git - vcs: git - version: release/melodic/mvsim/0.2.1-0 -nanomsg: - url: https://github.com/yujinrobot-release/nanomsg-release.git - vcs: git - version: release/melodic/nanomsg/0.4.1-0 -nao_meshes: - url: https://github.com/ros-naoqi/nao_meshes-release.git - vcs: git - version: release/melodic/nao_meshes/0.1.12-2 -naoqi_bridge_msgs: - url: https://github.com/ros-naoqi/naoqi_bridge_msgs-release.git - vcs: git - version: release/melodic/naoqi_bridge_msgs/0.0.8-0 -naoqi_driver: - url: https://github.com/ros-naoqi/naoqi_driver-release.git - vcs: git - version: release/melodic/naoqi_driver/0.5.11-0 -naoqi_libqi: - url: https://github.com/ros-naoqi/libqi-release.git - vcs: git - version: release/melodic/naoqi_libqi/2.9.0-8 -naoqi_libqicore: - url: https://github.com/ros-naoqi/libqicore-release.git - vcs: git - version: release/melodic/naoqi_libqicore/2.9.0-5 -nav2d: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d/0.4.2-0 -nav2d_exploration: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_exploration/0.4.2-0 -nav2d_karto: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_karto/0.4.2-0 -nav2d_localizer: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_localizer/0.4.2-0 -nav2d_msgs: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_msgs/0.4.2-0 -nav2d_navigator: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_navigator/0.4.2-0 -nav2d_operator: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_operator/0.4.2-0 -nav2d_remote: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_remote/0.4.2-0 -nav2d_tutorials: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/melodic/nav2d_tutorials/0.4.2-0 -nav_2d_msgs: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_2d_msgs/0.2.5-1 -nav_2d_utils: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_2d_utils/0.2.5-1 -nav_core: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/nav_core/1.16.3-1 -nav_core2: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_core2/0.2.5-1 -nav_core_adapter: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_core_adapter/0.2.5-1 -nav_grid: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_grid/0.2.5-1 -nav_grid_iterators: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_grid_iterators/0.2.5-1 -nav_grid_pub_sub: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/nav_grid_pub_sub/0.2.5-1 -navfn: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/navfn/1.16.3-1 -navigation: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/navigation/1.16.3-1 -navigation_experimental: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/navigation_experimental/0.3.3-1 -navigation_layers: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/melodic/navigation_layers/0.5.0-0 -navigation_stage: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/navigation_stage/0.2.3-1 -navigation_tutorials: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/navigation_tutorials/0.2.3-1 -neobotix_usboard_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/neobotix_usboard_msgs/2.3.1-0 -neonavigation: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/neonavigation/0.5.1-1 -neonavigation_common: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/neonavigation_common/0.5.1-1 -neonavigation_launch: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/neonavigation_launch/0.5.1-1 -neonavigation_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/neonavigation_msgs/0.5.0-1 -neonavigation_rviz_plugins: - url: https://github.com/at-wat/neonavigation_rviz_plugins-release.git - vcs: git - version: release/melodic/neonavigation_rviz_plugins/0.3.0-0 -nerian_stereo: - url: https://github.com/nerian-vision/nerian_stereo-release.git - vcs: git - version: release/melodic/nerian_stereo/3.6.0-1 -network_autoconfig: - url: https://github.com/LucidOne-release/network_autoconfig.git - vcs: git - version: release/melodic/network_autoconfig/0.1.1-2 -network_control_tests: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/network_control_tests/1.0.16-1 -network_detector: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/network_detector/1.0.16-1 -network_interface: - url: https://github.com/astuff/network_interface-release.git - vcs: git - version: release/melodic/network_interface/2.1.0-0 -network_monitor_udp: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/network_monitor_udp/1.0.16-1 -network_traffic_control: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/melodic/network_traffic_control/1.0.16-1 -nlopt: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/nlopt/2.1.13-1 -nmea_comms: - url: https://github.com/ros-drivers-gbp/nmea_comms-release.git - vcs: git - version: release/melodic/nmea_comms/1.2.0-0 -nmea_gps_plugin: - url: https://github.com/OUXT-Polaris/nmea_gps_plugin-release.git - vcs: git - version: release/melodic/nmea_gps_plugin/0.0.2-1 -nmea_msgs: - url: https://github.com/ros-drivers-gbp/nmea_msgs-release.git - vcs: git - version: release/melodic/nmea_msgs/1.1.0-0 -nmea_navsat_driver: - url: https://github.com/ros-drivers-gbp/nmea_navsat_driver-release.git - vcs: git - version: release/melodic/nmea_navsat_driver/0.5.1-0 -nmea_to_geopose: - url: https://github.com/OUXT-Polaris/nmea_to_geopose-release.git - vcs: git - version: release/melodic/nmea_to_geopose/0.0.1-1 -node_manager_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/melodic/node_manager_fkie/0.8.12-0 -nonpersistent_voxel_layer: - url: https://github.com/SteveMacenski/nonpersistent_voxel_layer-release.git - vcs: git - version: release/melodic/nonpersistent_voxel_layer/1.2.3-2 -novatel_gps_driver: - url: https://github.com/swri-robotics-gbp/novatel_gps_driver-release.git - vcs: git - version: release/melodic/novatel_gps_driver/3.9.0-1 -novatel_gps_msgs: - url: https://github.com/swri-robotics-gbp/novatel_gps_driver-release.git - vcs: git - version: release/melodic/novatel_gps_msgs/3.9.0-1 -novatel_msgs: - url: https://github.com/ros-drivers-gbp/novatel_span_driver-release.git - vcs: git - version: release/melodic/novatel_msgs/1.1.0-0 -novatel_span_driver: - url: https://github.com/ros-drivers-gbp/novatel_span_driver-release.git - vcs: git - version: release/melodic/novatel_span_driver/1.1.0-0 -ntpd_driver: - url: https://github.com/vooon/ntpd_driver-release.git - vcs: git - version: release/melodic/ntpd_driver/1.2.0-1 -obj_to_pointcloud: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/obj_to_pointcloud/0.5.1-1 -object_recognition_msgs: - url: https://github.com/ros-gbp/object_recognition_msgs-release.git - vcs: git - version: release/melodic/object_recognition_msgs/0.4.1-0 -ocean_battery_driver: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/melodic/ocean_battery_driver/1.1.7-0 -octomap_mapping: - url: https://github.com/ros-gbp/octomap_mapping-release.git - vcs: git - version: release/melodic/octomap_mapping/0.6.4-1 -octomap_ros: - url: https://github.com/ros-gbp/octomap_ros-release.git - vcs: git - version: release/melodic/octomap_ros/0.4.0-0 -octomap_rviz_plugins: - url: https://github.com/ros-gbp/octomap_rviz_plugins-release.git - vcs: git - version: release/melodic/octomap_rviz_plugins/0.2.2-1 -octomap_server: - url: https://github.com/ros-gbp/octomap_mapping-release.git - vcs: git - version: release/melodic/octomap_server/0.6.4-1 -octovis: - url: https://github.com/ros-gbp/octomap-release.git - vcs: git - version: release/melodic/octovis/1.9.0-1 -odom_frame_publisher: - url: https://github.com/OUXT-Polaris/odom_frame_publisher-release.git - vcs: git - version: release/melodic/odom_frame_publisher/0.0.1-1 -odometry_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/odometry_publisher_tutorial/0.2.3-1 -odva_ethernetip: - url: https://github.com/ros-drivers-gbp/odva_ethernetip-release.git - vcs: git - version: release/melodic/odva_ethernetip/0.1.4-0 -ompl: - url: https://github.com/ros-gbp/ompl-release.git - vcs: git - version: release/melodic/ompl/1.4.2-5 -omron_os32c_driver: - url: https://github.com/ros-drivers-gbp/omron-release.git - vcs: git - version: release/melodic/omron_os32c_driver/1.0.0-0 -open_karto: - url: https://github.com/ros-gbp/open_karto-release.git - vcs: git - version: release/melodic/open_karto/1.2.0-0 -open_manipulator: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator/2.0.1-0 -open_manipulator_control_gui: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_control_gui/2.0.1-0 -open_manipulator_controller: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_controller/2.0.1-0 -open_manipulator_description: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_description/2.0.1-0 -open_manipulator_gazebo: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_simulations-release.git - vcs: git - version: release/melodic/open_manipulator_gazebo/1.1.0-1 -open_manipulator_libs: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_libs/2.0.1-0 -open_manipulator_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_moveit/2.0.1-0 -open_manipulator_msgs: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_msgs-release.git - vcs: git - version: release/melodic/open_manipulator_msgs/1.0.0-0 -open_manipulator_simulations: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_simulations-release.git - vcs: git - version: release/melodic/open_manipulator_simulations/1.1.0-1 -open_manipulator_teleop: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/melodic/open_manipulator_teleop/2.0.1-0 -open_manipulator_with_tb3: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3/1.1.0-2 -open_manipulator_with_tb3_description: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_description/1.1.0-2 -open_manipulator_with_tb3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3_simulations-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_gazebo/1.1.0-2 -open_manipulator_with_tb3_simulations: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3_simulations-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_simulations/1.1.0-2 -open_manipulator_with_tb3_tools: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_tools/1.1.0-2 -open_manipulator_with_tb3_waffle_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_waffle_moveit/1.1.0-2 -open_manipulator_with_tb3_waffle_pi_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/melodic/open_manipulator_with_tb3_waffle_pi_moveit/1.1.0-2 -opencv_apps: - url: https://github.com/ros-perception/opencv_apps-release.git - vcs: git - version: release/melodic/opencv_apps/2.0.1-1 -opengm: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/melodic/opengm/0.6.14-1 -openhrp3: - url: https://github.com/tork-a/openhrp3-release.git - vcs: git - version: release/melodic/openhrp3/3.1.9-2 -openni2_camera: - url: https://github.com/ros-gbp/openni2_camera-release.git - vcs: git - version: release/melodic/openni2_camera/0.4.2-0 -openni2_launch: - url: https://github.com/ros-gbp/openni2_camera-release.git - vcs: git - version: release/melodic/openni2_launch/0.4.2-0 -openni_camera: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/melodic/openni_camera/1.11.1-0 -openni_description: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/melodic/openni_description/1.11.1-0 -openni_launch: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/melodic/openni_launch/1.11.1-0 -openrtm_aist: - url: https://github.com/tork-a/openrtm_aist-release.git - vcs: git - version: release/melodic/openrtm_aist/1.1.2-3 -openrtm_aist_python: - url: https://github.com/tork-a/openrtm_aist_python-release.git - vcs: git - version: release/melodic/openrtm_aist_python/1.1.0-0 -openslam_gmapping: - url: https://github.com/ros-gbp/openslam_gmapping-release.git - vcs: git - version: release/melodic/openslam_gmapping/0.2.1-1 -opt_camera: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/opt_camera/2.1.13-1 -optpp_catkin: - url: https://github.com/ipab-slmc/optpp_catkin-release.git - vcs: git - version: release/melodic/optpp_catkin/2.4.0-1 -orocos_kinematics_dynamics: - url: https://github.com/orocos/orocos-kdl-release.git - vcs: git - version: release/melodic/orocos_kinematics_dynamics/1.4.0-0 -osg_interactive_markers: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/melodic/osg_interactive_markers/1.0.2-2 -osg_markers: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/melodic/osg_markers/1.0.2-2 -osg_utils: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/melodic/osg_utils/1.0.2-2 -ouster_driver: - url: https://github.com/CPFL/ouster-release.git - vcs: git - version: release/melodic/ouster_driver/0.1.7-0 -oxford_gps_eth: - url: https://github.com/DataspeedInc-release/oxford_gps_eth-release.git - vcs: git - version: release/melodic/oxford_gps_eth/1.1.1-1 -p2os_doc: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_doc/2.1.1-3 -p2os_driver: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_driver/2.1.1-3 -p2os_launch: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_launch/2.1.1-3 -p2os_msgs: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_msgs/2.1.1-3 -p2os_teleop: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_teleop/2.1.1-3 -p2os_urdf: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/melodic/p2os_urdf/2.1.1-3 -pacmod3: - url: https://github.com/astuff/pacmod3-release.git - vcs: git - version: release/melodic/pacmod3/1.2.1-0 -pacmod_game_control: - url: https://github.com/astuff/pacmod_game_control-release.git - vcs: git - version: release/melodic/pacmod_game_control/2.3.0-0 -pacmod_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/pacmod_msgs/2.3.1-0 -panda_moveit_config: - url: https://github.com/ros-gbp/panda_moveit_config-release.git - vcs: git - version: release/melodic/panda_moveit_config/0.7.3-1 -parameter_assertions: - url: https://github.com/RoboJackets/rj-ros-common-release.git - vcs: git - version: release/melodic/parameter_assertions/0.1.0-1 -parrot_arsdk: - url: https://github.com/AutonomyLab/parrot_arsdk-release.git - vcs: git - version: release/melodic/parrot_arsdk/3.14.1-0 -people: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/people/1.2.0-1 -people_msgs: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/people_msgs/1.2.0-1 -people_tracking_filter: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/people_tracking_filter/1.2.0-1 -people_velocity_tracker: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/melodic/people_velocity_tracker/1.2.0-1 -pepper_meshes: - url: https://github.com/ros-naoqi/pepper_meshes-release.git - vcs: git - version: release/melodic/pepper_meshes/0.2.4-3 -pepperl_fuchs_r2000: - url: https://github.com/dillenberger/pepperl_fuchs-release.git - vcs: git - version: release/melodic/pepperl_fuchs_r2000/0.1.3-0 -pgm_learner: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/pgm_learner/2.1.13-1 -pheeno_ros_description: - url: https://github.com/acslaboratory/pheeno_ros_description-release.git - vcs: git - version: release/melodic/pheeno_ros_description/0.1.0-0 -phidgets_api: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/phidgets_api/0.7.9-1 -phidgets_drivers: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/phidgets_drivers/0.7.9-1 -phidgets_high_speed_encoder: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/phidgets_high_speed_encoder/0.7.9-1 -phidgets_ik: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/phidgets_ik/0.7.9-1 -phidgets_imu: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/melodic/phidgets_imu/0.7.9-1 -photo: - url: https://github.com/bosch-ros-pkg/photo-release.git - vcs: git - version: release/melodic/photo/1.0.3-1 -pid: - url: https://github.com/AndyZe/pid-release.git - vcs: git - version: release/melodic/pid/0.0.27-0 -pilz_control: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/pilz_control/0.5.13-1 -pilz_extensions: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_extensions/0.4.10-1 -pilz_industrial_motion: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_industrial_motion/0.4.10-1 -pilz_industrial_motion_testutils: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_industrial_motion_testutils/0.4.10-1 -pilz_msgs: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_msgs/0.4.10-1 -pilz_robot_programming: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_robot_programming/0.4.10-1 -pilz_robots: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/pilz_robots/0.5.13-1 -pilz_testutils: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/pilz_testutils/0.5.13-1 -pilz_trajectory_generation: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/melodic/pilz_trajectory_generation/0.4.10-1 -pilz_utils: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/pilz_utils/0.5.13-1 -pinocchio: - url: https://github.com/ipab-slmc/pinocchio_catkin-release.git - vcs: git - version: release/melodic/pinocchio/2.2.1-1 -planner_cspace: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/planner_cspace/0.5.1-1 -planner_cspace_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/planner_cspace_msgs/0.5.0-1 -plotjuggler: - url: https://github.com/facontidavide/plotjuggler-release.git - vcs: git - version: release/melodic/plotjuggler/2.5.0-1 -point_cloud_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/point_cloud_publisher_tutorial/0.2.3-1 -pointcloud_to_laserscan: - url: https://github.com/ros-gbp/pointcloud_to_laserscan-release.git - vcs: git - version: release/melodic/pointcloud_to_laserscan/1.4.1-1 -pose_base_controller: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/pose_base_controller/0.3.3-1 -pose_cov_ops: - url: https://github.com/mrpt-ros-pkg-release/pose_cov_ops-release.git - vcs: git - version: release/melodic/pose_cov_ops/0.2.1-0 -pose_follower: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/pose_follower/0.3.3-1 -posedetection_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/posedetection_msgs/4.3.1-0 -power_monitor: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/melodic/power_monitor/1.1.7-0 -power_msgs: - url: https://github.com/fetchrobotics-gbp/power_msgs-release.git - vcs: git - version: release/melodic/power_msgs/0.4.0-1 -pr2_app_manager: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_app_manager/0.6.1-0 -pr2_apps: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_apps/0.6.1-0 -pr2_arm_kinematics: - url: https://github.com/pr2-gbp/pr2_kinematics-release.git - vcs: git - version: release/melodic/pr2_arm_kinematics/1.0.10-0 -pr2_arm_move_ik: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/pr2_arm_move_ik/0.0.11-0 -pr2_calibration_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_calibration_controllers/1.10.17-1 -pr2_common: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/melodic/pr2_common/1.12.4-1 -pr2_common_action_msgs: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/pr2_common_action_msgs/0.0.11-0 -pr2_common_actions: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/pr2_common_actions/0.0.11-0 -pr2_controller_configuration_gazebo: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/melodic/pr2_controller_configuration_gazebo/2.0.14-0 -pr2_controller_interface: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_controller_interface/1.8.18-0 -pr2_controller_manager: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_controller_manager/1.8.18-0 -pr2_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_controllers/1.10.17-1 -pr2_controllers_msgs: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_controllers_msgs/1.10.17-1 -pr2_dashboard_aggregator: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/melodic/pr2_dashboard_aggregator/1.12.4-1 -pr2_description: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/melodic/pr2_description/1.12.4-1 -pr2_ethercat_drivers: - url: https://github.com/pr2-gbp/pr2_ethercat_drivers-release.git - vcs: git - version: release/melodic/pr2_ethercat_drivers/1.8.19-1 -pr2_gazebo: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/melodic/pr2_gazebo/2.0.14-0 -pr2_gazebo_plugins: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/melodic/pr2_gazebo_plugins/2.0.14-0 -pr2_gripper_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_gripper_action/1.10.17-1 -pr2_hardware_interface: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_hardware_interface/1.8.18-0 -pr2_head_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_head_action/1.10.17-1 -pr2_kinematics: - url: https://github.com/pr2-gbp/pr2_kinematics-release.git - vcs: git - version: release/melodic/pr2_kinematics/1.0.10-0 -pr2_machine: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/melodic/pr2_machine/1.12.4-1 -pr2_mannequin_mode: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_mannequin_mode/0.6.1-0 -pr2_mechanism: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_mechanism/1.8.18-0 -pr2_mechanism_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/pr2_mechanism_controllers/1.10.17-1 -pr2_mechanism_diagnostics: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_mechanism_diagnostics/1.8.18-0 -pr2_mechanism_model: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/melodic/pr2_mechanism_model/1.8.18-0 -pr2_mechanism_msgs: - url: https://github.com/ros-gbp/pr2_mechanism_msgs-release.git - vcs: git - version: release/melodic/pr2_mechanism_msgs/1.8.2-0 -pr2_move_base: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_move_base/0.1.28-1 -pr2_moveit_config: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/melodic/pr2_moveit_config/0.7.3-1 -pr2_moveit_plugins: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/melodic/pr2_moveit_plugins/0.7.3-1 -pr2_msgs: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/melodic/pr2_msgs/1.12.4-1 -pr2_navigation: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation/0.1.28-1 -pr2_navigation_config: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_config/0.1.28-1 -pr2_navigation_global: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_global/0.1.28-1 -pr2_navigation_local: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_local/0.1.28-1 -pr2_navigation_perception: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_perception/0.1.28-1 -pr2_navigation_self_filter: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_self_filter/0.1.28-1 -pr2_navigation_slam: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_slam/0.1.28-1 -pr2_navigation_teleop: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/pr2_navigation_teleop/0.1.28-1 -pr2_position_scripts: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_position_scripts/0.6.1-0 -pr2_power_board: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/melodic/pr2_power_board/1.1.7-0 -pr2_power_drivers: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/melodic/pr2_power_drivers/1.1.7-0 -pr2_simulator: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/melodic/pr2_simulator/2.0.14-0 -pr2_teleop: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_teleop/0.6.1-0 -pr2_teleop_general: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_teleop_general/0.6.1-0 -pr2_tilt_laser_interface: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/pr2_tilt_laser_interface/0.0.11-0 -pr2_tuck_arms_action: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/melodic/pr2_tuck_arms_action/0.0.11-0 -pr2_tuckarm: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/melodic/pr2_tuckarm/0.6.1-0 -pr2eus: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/melodic/pr2eus/0.3.14-3 -pr2eus_moveit: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/melodic/pr2eus_moveit/0.3.14-3 -pr2eus_tutorials: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/melodic/pr2eus_tutorials/0.3.14-3 -prbt_gazebo: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/prbt_gazebo/0.5.13-1 -prbt_grippers: - url: https://github.com/PilzDE/prbt_grippers-release.git - vcs: git - version: release/melodic/prbt_grippers/0.0.4-1 -prbt_hardware_support: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/prbt_hardware_support/0.5.13-1 -prbt_ikfast_manipulator_plugin: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/prbt_ikfast_manipulator_plugin/0.5.13-1 -prbt_moveit_config: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/prbt_moveit_config/0.5.13-1 -prbt_pg70_support: - url: https://github.com/PilzDE/prbt_grippers-release.git - vcs: git - version: release/melodic/prbt_pg70_support/0.0.4-1 -prbt_support: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/melodic/prbt_support/0.5.13-1 -prosilica_camera: - url: https://github.com/ros-drivers-gbp/prosilica_driver-release.git - vcs: git - version: release/melodic/prosilica_camera/1.9.4-1 -prosilica_gige_sdk: - url: https://github.com/ros-drivers-gbp/prosilica_gige_sdk-release.git - vcs: git - version: release/melodic/prosilica_gige_sdk/1.26.3-1 -ps3joy: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/melodic/ps3joy/1.13.0-1 -psen_scan: - url: https://github.com/PilzDE/psen_scan-release.git - vcs: git - version: release/melodic/psen_scan/1.0.2-1 -px4_msgs: - url: https://github.com/PX4/px4_msgs-release.git - vcs: git - version: release/melodic/px4_msgs/1.0.0-1 -py_trees: - url: https://github.com/stonier/py_trees-release.git - vcs: git - version: release/melodic/py_trees/0.6.8-0 -py_trees_msgs: - url: https://github.com/stonier/py_trees_msgs-release.git - vcs: git - version: release/melodic/py_trees_msgs/0.3.6-0 -py_trees_ros: - url: https://github.com/stonier/py_trees_ros-release.git - vcs: git - version: release/melodic/py_trees_ros/0.5.18-0 -pybind11_catkin: - url: https://github.com/wxmerkt/pybind11_catkin-release.git - vcs: git - version: release/melodic/pybind11_catkin/2.4.3-1 -pyros_test: - url: https://github.com/pyros-dev/pyros-test-release.git - vcs: git - version: release/melodic/pyros_test/0.0.6-1 -pyros_utils: - url: https://github.com/pyros-dev/pyros-utils-release.git - vcs: git - version: release/melodic/pyros_utils/0.1.4-1 -qb_chain: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/melodic/qb_chain/2.0.0-0 -qb_chain_control: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/melodic/qb_chain_control/2.0.0-0 -qb_chain_description: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/melodic/qb_chain_description/2.0.0-0 -qb_device: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device/2.0.1-0 -qb_device_bringup: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_bringup/2.0.1-0 -qb_device_control: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_control/2.0.1-0 -qb_device_description: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_description/2.0.1-0 -qb_device_driver: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_driver/2.0.1-0 -qb_device_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_hardware_interface/2.0.1-0 -qb_device_msgs: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_msgs/2.0.1-0 -qb_device_srvs: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_srvs/2.0.1-0 -qb_device_utils: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/melodic/qb_device_utils/2.0.1-0 -qb_hand: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/melodic/qb_hand/2.0.0-1 -qb_hand_control: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/melodic/qb_hand_control/2.0.0-1 -qb_hand_description: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/melodic/qb_hand_description/2.0.0-1 -qb_hand_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/melodic/qb_hand_hardware_interface/2.0.0-1 -qb_move: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/melodic/qb_move/2.0.0-1 -qb_move_control: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/melodic/qb_move_control/2.0.0-1 -qb_move_description: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/melodic/qb_move_description/2.0.0-1 -qb_move_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/melodic/qb_move_hardware_interface/2.0.0-1 -qpmad: - url: https://github.com/asherikov/qpmad-release.git - vcs: git - version: release/melodic/qpmad/1.0.2-1 -qpoases_vendor: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/qpoases_vendor-release.git - vcs: git - version: release/melodic/qpoases_vendor/3.2.1-1 -qt_gui_app: - url: https://github.com/ros-gbp/qt_gui_core-release.git - vcs: git - version: release/melodic/qt_gui_app/0.3.16-1 -qt_gui_core: - url: https://github.com/ros-gbp/qt_gui_core-release.git - vcs: git - version: release/melodic/qt_gui_core/0.3.16-1 -qt_qmake: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/melodic/qt_qmake/1.0.1-0 -quaternion_operation: - url: https://github.com/OUXT-Polaris/quaternion_operation-release.git - vcs: git - version: release/melodic/quaternion_operation/0.0.3-2 -radar_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/melodic/radar_msgs/2.3.1-0 -radar_omnipresense: - url: https://github.com/SCU-RSL-ROS/radar_omnipresense-release.git - vcs: git - version: release/melodic/radar_omnipresense/0.3.0-0 -rail_manipulation_msgs: - url: https://github.com/gt-rail-release/rail_manipulation_msgs-release.git - vcs: git - version: release/melodic/rail_manipulation_msgs/0.0.14-1 -rail_mesh_icp: - url: https://github.com/gt-rail-release/rail_mesh_icp-release.git - vcs: git - version: release/melodic/rail_mesh_icp/0.0.4-1 -rail_segmentation: - url: https://github.com/gt-rail-release/rail_segmentation.git - vcs: git - version: release/melodic/rail_segmentation/0.1.15-1 -random_numbers: - url: https://github.com/ros-gbp/random_numbers-release.git - vcs: git - version: release/melodic/random_numbers/0.3.2-0 -range_sensor_layer: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/melodic/range_sensor_layer/0.5.0-0 -raw_description: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/melodic/raw_description/0.7.1-1 -rc_cloud_accumulator: - url: https://github.com/roboception-gbp/rc_cloud_accumulator-release.git - vcs: git - version: release/melodic/rc_cloud_accumulator/1.0.4-0 -rc_common_msgs: - url: https://github.com/roboception-gbp/rc_common_msgs-release.git - vcs: git - version: release/melodic/rc_common_msgs/0.4.0-1 -rc_dynamics_api: - url: https://github.com/roboception-gbp/rc_dynamics_api-release.git - vcs: git - version: release/melodic/rc_dynamics_api/0.10.0-1 -rc_genicam_api: - url: https://github.com/roboception-gbp/rc_genicam_api-release.git - vcs: git - version: release/melodic/rc_genicam_api/2.2.3-1 -rc_hand_eye_calibration_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_hand_eye_calibration_client/2.7.0-1 -rc_pick_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_pick_client/2.7.0-1 -rc_roi_manager_gui: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_roi_manager_gui/2.7.0-1 -rc_tagdetect_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_tagdetect_client/2.7.0-1 -rc_visard: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_visard/2.7.0-1 -rc_visard_description: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_visard_description/2.7.0-1 -rc_visard_driver: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/melodic/rc_visard_driver/2.7.0-1 -rcdiscover: - url: https://github.com/roboception-gbp/rcdiscover-release.git - vcs: git - version: release/melodic/rcdiscover/1.0.0-1 -rdl: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl/3.2.0-1 -rdl_benchmark: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_benchmark/3.2.0-1 -rdl_cmake: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_cmake/3.2.0-1 -rdl_dynamics: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_dynamics/3.2.0-1 -rdl_msgs: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_msgs/3.2.0-1 -rdl_ros_tools: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_ros_tools/3.2.0-1 -rdl_urdfreader: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/melodic/rdl_urdfreader/3.2.0-1 -realsense2_camera: - url: https://github.com/IntelRealSense/realsense-ros-release.git - vcs: git - version: release/melodic/realsense2_camera/2.2.11-1 -realsense2_description: - url: https://github.com/IntelRealSense/realsense-ros-release.git - vcs: git - version: release/melodic/realsense2_description/2.2.11-1 -resized_image_transport: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/melodic/resized_image_transport/1.2.10-0 -respeaker_ros: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/respeaker_ros/2.1.13-1 -rexrov2_control: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/melodic/rexrov2_control/0.1.3-0 -rexrov2_description: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/melodic/rexrov2_description/0.1.3-0 -rexrov2_gazebo: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/melodic/rexrov2_gazebo/0.1.3-0 -rgbd_launch: - url: https://github.com/ros-gbp/rgbd_launch-release.git - vcs: git - version: release/melodic/rgbd_launch/2.2.2-0 -ridgeback_control: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/melodic/ridgeback_control/0.2.2-2 -ridgeback_description: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/melodic/ridgeback_description/0.2.2-2 -ridgeback_desktop: - url: https://github.com/clearpath-gbp/ridgeback_desktop-release.git - vcs: git - version: release/melodic/ridgeback_desktop/0.1.1-1 -ridgeback_gazebo: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/melodic/ridgeback_gazebo/0.1.0-1 -ridgeback_gazebo_plugins: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/melodic/ridgeback_gazebo_plugins/0.1.0-1 -ridgeback_msgs: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/melodic/ridgeback_msgs/0.2.2-2 -ridgeback_navigation: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/melodic/ridgeback_navigation/0.2.2-2 -ridgeback_simulator: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/melodic/ridgeback_simulator/0.1.0-1 -ridgeback_viz: - url: https://github.com/clearpath-gbp/ridgeback_desktop-release.git - vcs: git - version: release/melodic/ridgeback_viz/0.1.1-1 -robot_activity: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/melodic/robot_activity/0.1.1-0 -robot_activity_msgs: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/melodic/robot_activity_msgs/0.1.1-0 -robot_activity_tutorials: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/melodic/robot_activity_tutorials/0.1.1-0 -robot_body_filter: - url: https://github.com/peci1/robot_body_filter-release.git - vcs: git - version: release/melodic/robot_body_filter/1.1.6-1 -robot_calibration: - url: https://github.com/ros-gbp/robot_calibration-release.git - vcs: git - version: release/melodic/robot_calibration/0.6.1-1 -robot_calibration_msgs: - url: https://github.com/ros-gbp/robot_calibration-release.git - vcs: git - version: release/melodic/robot_calibration_msgs/0.6.1-1 -robot_controllers: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/melodic/robot_controllers/0.6.0-0 -robot_controllers_interface: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/melodic/robot_controllers_interface/0.6.0-0 -robot_controllers_msgs: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/melodic/robot_controllers_msgs/0.6.0-0 -robot_localization: - url: https://github.com/cra-ros-pkg/robot_localization-release.git - vcs: git - version: release/melodic/robot_localization/2.6.5-1 -robot_mechanism_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/robot_mechanism_controllers/1.10.17-1 -robot_navigation: - url: https://github.com/DLu/robot_navigation-release.git - vcs: git - version: release/melodic/robot_navigation/0.2.5-1 -robot_one: - url: https://github.com/AlexanderSilvaB/robot-one-ros-release.git - vcs: git - version: release/melodic/robot_one/0.1.1-1 -robot_pose_ekf: - url: https://github.com/ros-gbp/robot_pose_ekf-release.git - vcs: git - version: release/melodic/robot_pose_ekf/1.14.5-0 -robot_self_filter: - url: https://github.com/pr2-gbp/robot_self_filter-gbp.git - vcs: git - version: release/melodic/robot_self_filter/0.1.31-0 -robot_setup_tf_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/robot_setup_tf_tutorial/0.2.3-1 -robot_upstart: - url: https://github.com/clearpath-gbp/robot_upstart-release.git - vcs: git - version: release/melodic/robot_upstart/0.3.0-0 -robotis_manipulator: - url: https://github.com/ROBOTIS-GIT-release/robotis_manipulator-release.git - vcs: git - version: release/melodic/robotis_manipulator/1.0.0-0 -rocon_app_manager_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_app_manager_msgs/0.9.0-0 -rocon_bubble_icons: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_bubble_icons/0.3.2-0 -rocon_console: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_console/0.3.2-0 -rocon_device_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_device_msgs/0.9.0-0 -rocon_ebnf: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_ebnf/0.3.2-0 -rocon_icons: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_icons/0.3.2-0 -rocon_interaction_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_interaction_msgs/0.9.0-0 -rocon_interactions: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_interactions/0.3.2-0 -rocon_launch: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_launch/0.3.2-0 -rocon_master_info: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_master_info/0.3.2-0 -rocon_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_msgs/0.9.0-0 -rocon_python_comms: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_python_comms/0.3.2-0 -rocon_python_redis: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_python_redis/0.3.2-0 -rocon_python_utils: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_python_utils/0.3.2-0 -rocon_python_wifi: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_python_wifi/0.3.2-0 -rocon_semantic_version: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_semantic_version/0.3.2-0 -rocon_service_pair_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_service_pair_msgs/0.9.0-0 -rocon_std_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_std_msgs/0.9.0-0 -rocon_tools: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_tools/0.3.2-0 -rocon_tutorial_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/rocon_tutorial_msgs/0.9.0-0 -rocon_uri: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/melodic/rocon_uri/0.3.2-0 -roomba_stage: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/roomba_stage/0.2.3-1 -ros_canopen: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/ros_canopen/0.8.2-1 -ros_control: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/melodic/ros_control/0.15.1-0 -ros_control_boilerplate: - url: https://github.com/PickNikRobotics/ros_control_boilerplate-release.git - vcs: git - version: release/melodic/ros_control_boilerplate/0.5.0-1 -ros_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/ros_controllers/0.15.0-0 -ros_emacs_utils: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/melodic/ros_emacs_utils/0.4.13-0 -ros_introspection: - url: https://github.com/wu-robotics/roscompile-release.git - vcs: git - version: release/melodic/ros_introspection/1.0.1-0 -ros_monitoring_msgs: - url: https://github.com/aws-gbp/ros_monitoring_msgs-release.git - vcs: git - version: release/melodic/ros_monitoring_msgs/1.0.1-1 -ros_pytest: - url: https://github.com/machinekoder/ros_pytest-release.git - vcs: git - version: release/melodic/ros_pytest/0.1.2-2 -ros_realtime: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/melodic/ros_realtime/1.0.25-0 -ros_reflexxes: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/melodic/ros_reflexxes/0.8.8-1 -ros_speech_recognition: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/ros_speech_recognition/2.1.13-1 -ros_type_introspection: - url: https://github.com/facontidavide/ros_type_introspection-release.git - vcs: git - version: release/melodic/ros_type_introspection/2.0.4-1 -rosatomic: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/melodic/rosatomic/1.0.25-0 -rosbag_editor: - url: https://github.com/facontidavide/rosbag_editor-release.git - vcs: git - version: release/melodic/rosbag_editor/0.4.2-1 -rosbag_fancy: - url: https://github.com/xqms/rosbag_fancy-release.git - vcs: git - version: release/melodic/rosbag_fancy/0.1.1-1 -rosbag_pandas: - url: https://github.com/eurogroep/rosbag_pandas-release.git - vcs: git - version: release/melodic/rosbag_pandas/0.5.3-0 -rosbaglive: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/melodic/rosbaglive/0.2.4-0 -rosbash_params: - url: https://github.com/peci1/rosbash_params-release.git - vcs: git - version: release/melodic/rosbash_params/1.0.2-0 -rosbridge_suite: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/melodic/rosbridge_suite/0.11.3-1 -roscompile: - url: https://github.com/wu-robotics/roscompile-release.git - vcs: git - version: release/melodic/roscompile/1.0.1-0 -rosdiagnostic: - url: https://github.com/ros-gbp/diagnostics-release.git - vcs: git - version: release/melodic/rosdiagnostic/1.9.3-0 -rosdoc_lite: - url: https://github.com/ros-gbp/rosdoc_lite-release.git - vcs: git - version: release/melodic/rosdoc_lite/0.2.9-0 -rosemacs: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/melodic/rosemacs/0.4.13-0 -roseus: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/melodic/roseus/1.7.4-1 -roseus_mongo: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/melodic/roseus_mongo/1.7.4-1 -roseus_smach: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/melodic/roseus_smach/1.7.4-1 -roseus_tutorials: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/melodic/roseus_tutorials/1.7.4-1 -rosfmt: - url: https://github.com/xqms/rosfmt-release.git - vcs: git - version: release/melodic/rosfmt/6.2.0-1 -roslisp_common: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/roslisp_common/0.2.12-1 -roslisp_repl: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/melodic/roslisp_repl/0.4.13-0 -roslisp_utilities: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/melodic/roslisp_utilities/0.2.12-1 -rosmon: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/melodic/rosmon/2.2.1-1 -rosmon_core: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/melodic/rosmon_core/2.2.1-1 -rosmon_msgs: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/melodic/rosmon_msgs/2.2.1-1 -rosparam_handler: - url: https://github.com/cbandera/rosparam_handler-release.git - vcs: git - version: release/melodic/rosparam_handler/0.1.4-1 -rosparam_shortcuts: - url: https://github.com/PickNikRobotics/rosparam_shortcuts-release.git - vcs: git - version: release/melodic/rosparam_shortcuts/0.3.3-1 -rospatlite: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/rospatlite/2.1.13-1 -rospilot: - url: https://github.com/rospilot/rospilot-release.git - vcs: git - version: release/melodic/rospilot/1.5.6-0 -rosping: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/rosping/2.1.13-1 -rospy_message_converter: - url: https://github.com/uos-gbp/rospy_message_converter-release.git - vcs: git - version: release/melodic/rospy_message_converter/0.5.0-0 -rosrt: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/melodic/rosrt/1.0.25-0 -rosserial: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial/0.8.0-0 -rosserial_arduino: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_arduino/0.8.0-0 -rosserial_client: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_client/0.8.0-0 -rosserial_embeddedlinux: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_embeddedlinux/0.8.0-0 -rosserial_mbed: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_mbed/0.8.0-0 -rosserial_msgs: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_msgs/0.8.0-0 -rosserial_python: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_python/0.8.0-0 -rosserial_server: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_server/0.8.0-0 -rosserial_tivac: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_tivac/0.8.0-0 -rosserial_vex_cortex: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_vex_cortex/0.8.0-0 -rosserial_vex_v5: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_vex_v5/0.8.0-0 -rosserial_windows: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_windows/0.8.0-0 -rosserial_xbee: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/melodic/rosserial_xbee/0.8.0-0 -rostate_machine: - url: https://github.com/OUXT-Polaris/rostate_machine-release.git - vcs: git - version: release/melodic/rostate_machine/0.0.2-3 -rosthrottle: - url: https://github.com/UTNuclearRoboticsPublic/rosthrottle-release.git - vcs: git - version: release/melodic/rosthrottle/1.2.0-3 -rostwitter: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/rostwitter/2.1.13-1 -roswww: - url: https://github.com/ros-gbp/roswww-release.git - vcs: git - version: release/melodic/roswww/0.1.12-0 -rotate_recovery: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/melodic/rotate_recovery/1.16.3-1 -rotors_comm: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_comm/2.2.3-0 -rotors_control: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_control/2.2.3-0 -rotors_description: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_description/2.2.3-0 -rotors_evaluation: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_evaluation/2.2.3-0 -rotors_gazebo: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_gazebo/2.2.3-0 -rotors_gazebo_plugins: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_gazebo_plugins/2.2.3-0 -rotors_hil_interface: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_hil_interface/2.2.3-0 -rotors_joy_interface: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_joy_interface/2.2.3-0 -rotors_simulator: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rotors_simulator/2.2.3-0 -rplidar_ros: - url: https://github.com/Slamtec/rplidar_ros-release.git - vcs: git - version: release/melodic/rplidar_ros/1.7.0-0 -rqt: - url: https://github.com/ros-gbp/rqt-release.git - vcs: git - version: release/melodic/rqt/0.5.0-0 -rqt_controller_manager: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/melodic/rqt_controller_manager/0.15.1-0 -rqt_ez_publisher: - url: https://github.com/OTL/rqt_ez_publisher-release.git - vcs: git - version: release/melodic/rqt_ez_publisher/0.5.0-1 -rqt_joint_trajectory_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/rqt_joint_trajectory_controller/0.15.0-0 -rqt_launchtree: - url: https://github.com/pschillinger/rqt_launchtree-release.git - vcs: git - version: release/melodic/rqt_launchtree/0.2.0-1 -rqt_multiplot: - url: https://github.com/anybotics/rqt_multiplot_plugin-release.git - vcs: git - version: release/melodic/rqt_multiplot/0.0.10-0 -rqt_py_trees: - url: https://github.com/stonier/rqt_py_trees-release.git - vcs: git - version: release/melodic/rqt_py_trees/0.3.1-0 -rqt_rosmon: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/melodic/rqt_rosmon/2.2.1-1 -rqt_rotors: - url: https://github.com/ethz-asl/rotors_simulator-release.git - vcs: git - version: release/melodic/rqt_rotors/2.2.3-0 -rslidar: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/melodic/rslidar/1.0.2-0 -rslidar_driver: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/melodic/rslidar_driver/1.0.2-0 -rslidar_msgs: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/melodic/rslidar_msgs/1.0.2-0 -rslidar_pointcloud: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/melodic/rslidar_pointcloud/1.0.2-0 -rtabmap: - url: https://github.com/introlab/rtabmap-release.git - vcs: git - version: release/melodic/rtabmap/0.19.3-2 -rtabmap_ros: - url: https://github.com/introlab/rtabmap_ros-release.git - vcs: git - version: release/melodic/rtabmap_ros/0.19.3-1 -rtctree: - url: https://github.com/tork-a/rtctree-release.git - vcs: git - version: release/melodic/rtctree/3.0.1-0 -rtshell: - url: https://github.com/tork-a/rtshell-release.git - vcs: git - version: release/melodic/rtshell/3.0.1-2 -rtsprofile: - url: https://github.com/tork-a/rtsprofile-release.git - vcs: git - version: release/melodic/rtsprofile/2.0.0-1 -rviz_imu_plugin: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/melodic/rviz_imu_plugin/1.2.1-1 -rxcpp_vendor: - url: https://github.com/rosin-project/rxcpp_vendor-release.git - vcs: git - version: release/melodic/rxcpp_vendor/4.1.0-1 -rxros: - url: https://github.com/rosin-project/rxros-release.git - vcs: git - version: release/melodic/rxros/0.1.0-1 -rxros_tf: - url: https://github.com/rosin-project/rxros-release.git - vcs: git - version: release/melodic/rxros_tf/0.1.0-1 -safe_teleop_base: - url: https://github.com/ros-gbp/shared_autonomy_manipulation-release.git - vcs: git - version: release/melodic/safe_teleop_base/0.0.3-1 -safe_teleop_pr2: - url: https://github.com/ros-gbp/shared_autonomy_manipulation-release.git - vcs: git - version: release/melodic/safe_teleop_pr2/0.0.3-1 -safe_teleop_stage: - url: https://github.com/ros-gbp/shared_autonomy_manipulation-release.git - vcs: git - version: release/melodic/safe_teleop_stage/0.0.3-1 -safety_limiter: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/safety_limiter/0.5.1-1 -safety_limiter_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/safety_limiter_msgs/0.5.0-1 -sainsmart_relay_usb: - url: https://github.com/DataspeedInc-release/sainsmart_relay_usb-release.git - vcs: git - version: release/melodic/sainsmart_relay_usb/0.0.2-0 -sand_island: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/melodic/sand_island/0.0.1-1 -sbg_driver: - url: https://github.com/SBG-Systems/sbg_ros_driver-release.git - vcs: git - version: release/melodic/sbg_driver/2.0.0-1 -sbpl: - url: https://github.com/ros-gbp/sbpl-release.git - vcs: git - version: release/melodic/sbpl/1.3.1-0 -sbpl_lattice_planner: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/sbpl_lattice_planner/0.3.3-1 -sbpl_recovery: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/sbpl_recovery/0.3.3-1 -scheduler_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/melodic/scheduler_msgs/0.9.0-0 -schunk_description: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_description/0.6.14-1 -schunk_libm5api: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_libm5api/0.6.14-1 -schunk_modular_robotics: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_modular_robotics/0.6.14-1 -schunk_powercube_chain: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_powercube_chain/0.6.14-1 -schunk_sdh: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_sdh/0.6.14-1 -schunk_simulated_tactile_sensors: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/melodic/schunk_simulated_tactile_sensors/0.6.14-1 -sdhlibrary_cpp: - url: https://github.com/ipab-slmc/SDHLibrary-CPP-release.git - vcs: git - version: release/melodic/sdhlibrary_cpp/0.2.10-1 -seed_r7_bringup: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_bringup/0.3.3-1 -seed_r7_description: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_description/0.3.3-1 -seed_r7_moveit_config: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_moveit_config/0.3.3-1 -seed_r7_navigation: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_navigation/0.3.3-1 -seed_r7_robot_interface: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_robot_interface/0.3.3-1 -seed_r7_ros_controller: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_ros_controller/0.3.3-1 -seed_r7_ros_pkg: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_ros_pkg/0.3.3-1 -seed_r7_samples: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_samples/0.3.3-1 -seed_r7_typef_moveit_config: - url: https://github.com/seed-solutions/seed_r7_ros_pkg-release.git - vcs: git - version: release/melodic/seed_r7_typef_moveit_config/0.3.3-1 -seed_smartactuator_sdk: - url: https://github.com/seed-solutions/seed_smartactuator_sdk-release.git - vcs: git - version: release/melodic/seed_smartactuator_sdk/0.0.4-1 -semantic_point_annotator: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/melodic/semantic_point_annotator/0.1.28-1 -serial: - url: https://github.com/wjwwood/serial-release.git - vcs: git - version: release/melodic/serial/1.2.1-0 -service_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/melodic/service_tools/0.6.15-1 -settlerlib: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/melodic/settlerlib/0.10.14-0 -sick_safetyscanners: - url: https://github.com/SICKAG/sick_safetyscanners-release.git - vcs: git - version: release/melodic/sick_safetyscanners/1.0.4-1 -sick_scan: - url: https://github.com/SICKAG/sick_scan-release.git - vcs: git - version: release/melodic/sick_scan/1.4.2-1 -sick_tim: - url: https://github.com/uos-gbp/sick_tim-release.git - vcs: git - version: release/melodic/sick_tim/0.0.16-1 -simple_grasping: - url: https://github.com/ros-gbp/simple_grasping-release.git - vcs: git - version: release/melodic/simple_grasping/0.3.1-0 -simple_message: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/melodic/simple_message/0.7.1-1 -simple_navigation_goals_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/melodic/simple_navigation_goals_tutorial/0.2.3-1 -single_joint_position_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/melodic/single_joint_position_action/1.10.17-1 -slam_gmapping: - url: https://github.com/ros-gbp/slam_gmapping-release.git - vcs: git - version: release/melodic/slam_gmapping/1.4.0-1 -slam_karto: - url: https://github.com/ros-gbp/slam_karto-release.git - vcs: git - version: release/melodic/slam_karto/0.8.1-0 -slam_toolbox: - url: https://github.com/SteveMacenski/slam_toolbox-release.git - vcs: git - version: release/melodic/slam_toolbox/1.1.2-1 -slic: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/slic/2.1.13-1 -slime_ros: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/melodic/slime_ros/0.4.13-0 -slime_wrapper: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/melodic/slime_wrapper/0.4.13-0 -smach_viewer: - url: https://github.com/jbohren/executive_smach_visualization-release.git - vcs: git - version: release/melodic/smach_viewer/3.0.0-1 -social_navigation_layers: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/melodic/social_navigation_layers/0.5.0-0 -socketcan_bridge: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/melodic/socketcan_bridge/0.8.2-1 -soem: - url: https://github.com/mgruhler/soem-gbp.git - vcs: git - version: release/melodic/soem/1.4.0-1 -sophus: - url: https://github.com/yujinrobot-release/sophus-release.git - vcs: git - version: release/melodic/sophus/1.0.1-1 -sound_play: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/melodic/sound_play/0.3.3-0 -spacenav_node: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/melodic/spacenav_node/1.13.0-1 -sparse_bundle_adjustment: - url: https://github.com/ros-gbp/sparse_bundle_adjustment-release.git - vcs: git - version: release/melodic/sparse_bundle_adjustment/0.4.2-0 -spatio_temporal_voxel_layer: - url: https://github.com/SteveMacenski/spatio_temporal_voxel_layer-release.git - vcs: git - version: release/melodic/spatio_temporal_voxel_layer/1.3.5-2 -speech_recognition_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/melodic/speech_recognition_msgs/4.3.1-0 -srdfdom: - url: https://github.com/ros-gbp/srdfdom-release.git - vcs: git - version: release/melodic/srdfdom/0.5.1-0 -static_tf: - url: https://github.com/wu-robotics/static_tf_release.git - vcs: git - version: release/melodic/static_tf/0.0.2-0 -static_transform_mux: - url: https://github.com/peci1/static_transform_mux-release.git - vcs: git - version: release/melodic/static_transform_mux/1.1.0-0 -std_capabilities: - url: https://github.com/ros-gbp/std_capabilities-release.git - vcs: git - version: release/melodic/std_capabilities/0.1.0-0 -swri_console: - url: https://github.com/swri-robotics-gbp/swri_console-release.git - vcs: git - version: release/melodic/swri_console/1.1.0-0 -swri_console_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_console_util/2.11.0-1 -swri_dbw_interface: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_dbw_interface/2.11.0-1 -swri_geometry_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_geometry_util/2.11.0-1 -swri_image_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_image_util/2.11.0-1 -swri_math_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_math_util/2.11.0-1 -swri_nodelet: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_nodelet/2.11.0-1 -swri_opencv_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_opencv_util/2.11.0-1 -swri_prefix_tools: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_prefix_tools/2.11.0-1 -swri_profiler: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/melodic/swri_profiler/0.2.2-1 -swri_profiler_msgs: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/melodic/swri_profiler_msgs/0.2.2-1 -swri_profiler_tools: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/melodic/swri_profiler_tools/0.2.2-1 -swri_roscpp: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_roscpp/2.11.0-1 -swri_rospy: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_rospy/2.11.0-1 -swri_route_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_route_util/2.11.0-1 -swri_serial_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_serial_util/2.11.0-1 -swri_string_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_string_util/2.11.0-1 -swri_system_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_system_util/2.11.0-1 -swri_transform_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_transform_util/2.11.0-1 -swri_yaml_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/melodic/swri_yaml_util/2.11.0-1 -tablet_socket_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/tablet_socket_msgs/1.13.0-1 -talos_description: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/melodic/talos_description/1.0.45-0 -talos_description_calibration: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/melodic/talos_description_calibration/1.0.45-0 -talos_description_inertial: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/melodic/talos_description_inertial/1.0.45-0 -teb_local_planner: - url: https://github.com/rst-tu-dortmund/teb_local_planner-release.git - vcs: git - version: release/melodic/teb_local_planner/0.8.4-1 -teb_local_planner_tutorials: - url: https://github.com/rst-tu-dortmund/teb_local_planner_tutorials-release.git - vcs: git - version: release/melodic/teb_local_planner_tutorials/0.2.4-1 -teleop_tools: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/melodic/teleop_tools/0.3.0-0 -teleop_tools_msgs: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/melodic/teleop_tools_msgs/0.3.0-0 -teleop_twist_joy: - url: https://github.com/ros-teleop/teleop_twist_joy-release.git - vcs: git - version: release/melodic/teleop_twist_joy/0.1.3-0 -teleop_twist_keyboard: - url: https://github.com/ros-gbp/teleop_twist_keyboard-release.git - vcs: git - version: release/melodic/teleop_twist_keyboard/0.6.2-0 -teraranger: - url: https://github.com/Terabee/teraranger-release.git - vcs: git - version: release/melodic/teraranger/2.1.0-1 -teraranger_array: - url: https://github.com/Terabee/teraranger_array-release.git - vcs: git - version: release/melodic/teraranger_array/2.0.0-1 -test_diagnostic_aggregator: - url: https://github.com/ros-gbp/diagnostics-release.git - vcs: git - version: release/melodic/test_diagnostic_aggregator/1.9.3-0 -test_mavros: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/melodic/test_mavros/1.0.0-1 -tf2_bullet: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/melodic/tf2_bullet/0.6.5-0 -tf2_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/melodic/tf2_relay/0.0.2-1 -tf2_tools: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/melodic/tf2_tools/0.6.5-0 -tf2_web_republisher: - url: https://github.com/RobotWebTools-release/tf2_web_republisher-release.git - vcs: git - version: release/melodic/tf2_web_republisher/0.3.2-0 -tf_remapper_cpp: - url: https://github.com/peci1/tf_remapper_cpp-release.git - vcs: git - version: release/melodic/tf_remapper_cpp/1.1.1-0 -tile_map: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/melodic/tile_map/1.2.0-1 -timestamp_tools: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/melodic/timestamp_tools/1.6.8-0 -toposens: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens/1.3.0-1 -toposens_description: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_description/1.3.0-1 -toposens_driver: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_driver/1.3.0-1 -toposens_markers: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_markers/1.3.0-1 -toposens_msgs: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_msgs/1.3.0-1 -toposens_pointcloud: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_pointcloud/1.3.0-1 -toposens_sync: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/melodic/toposens_sync/1.3.0-1 -towr: - url: https://github.com/ethz-adrl/towr-release.git - vcs: git - version: release/melodic/towr/1.4.1-0 -towr_ros: - url: https://github.com/ethz-adrl/towr-release.git - vcs: git - version: release/melodic/towr_ros/1.4.1-0 -trac_ik: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/melodic/trac_ik/1.5.1-1 -trac_ik_examples: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/melodic/trac_ik_examples/1.5.1-1 -trac_ik_kinematics_plugin: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/melodic/trac_ik_kinematics_plugin/1.5.1-1 -trac_ik_lib: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/melodic/trac_ik_lib/1.5.1-1 -trac_ik_python: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/melodic/trac_ik_python/1.5.1-1 -tracetools: - url: https://github.com/boschresearch/ros1-tracetools-release.git - vcs: git - version: release/melodic/tracetools/0.2.1-1 -track_odometry: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/track_odometry/0.5.1-1 -trajectory_tracker: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/melodic/trajectory_tracker/0.5.1-1 -trajectory_tracker_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/melodic/trajectory_tracker_msgs/0.5.0-1 -trajectory_tracker_rviz_plugins: - url: https://github.com/at-wat/neonavigation_rviz_plugins-release.git - vcs: git - version: release/melodic/trajectory_tracker_rviz_plugins/0.3.0-0 -tts: - url: https://github.com/aws-gbp/tts-release.git - vcs: git - version: release/melodic/tts/1.0.2-1 -turtlebot3: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3/1.2.2-1 -turtlebot3_applications: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_applications/1.1.0-0 -turtlebot3_applications_msgs: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications_msgs-release.git - vcs: git - version: release/melodic/turtlebot3_applications_msgs/1.0.0-1 -turtlebot3_automatic_parking: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_automatic_parking/1.1.0-0 -turtlebot3_automatic_parking_vision: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_automatic_parking_vision/1.1.0-0 -turtlebot3_autorace: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/melodic/turtlebot3_autorace/1.2.0-0 -turtlebot3_autorace_camera: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/melodic/turtlebot3_autorace_camera/1.2.0-0 -turtlebot3_autorace_control: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/melodic/turtlebot3_autorace_control/1.2.0-0 -turtlebot3_autorace_core: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/melodic/turtlebot3_autorace_core/1.2.0-0 -turtlebot3_autorace_detect: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/melodic/turtlebot3_autorace_detect/1.2.0-0 -turtlebot3_bringup: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_bringup/1.2.2-1 -turtlebot3_description: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_description/1.2.2-1 -turtlebot3_example: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_example/1.2.2-1 -turtlebot3_fake: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/melodic/turtlebot3_fake/1.2.0-0 -turtlebot3_follow_filter: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_follow_filter/1.1.0-0 -turtlebot3_follower: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_follower/1.1.0-0 -turtlebot3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/melodic/turtlebot3_gazebo/1.2.0-0 -turtlebot3_msgs: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_msgs-release.git - vcs: git - version: release/melodic/turtlebot3_msgs/1.0.0-0 -turtlebot3_navigation: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_navigation/1.2.2-1 -turtlebot3_panorama: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/melodic/turtlebot3_panorama/1.1.0-0 -turtlebot3_simulations: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/melodic/turtlebot3_simulations/1.2.0-0 -turtlebot3_slam: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_slam/1.2.2-1 -turtlebot3_teleop: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/melodic/turtlebot3_teleop/1.2.2-1 -turtlesim_dash_tutorial: - url: https://github.com/banerjs-ros-release/turtlesim_dash_tutorial-release.git - vcs: git - version: release/melodic/turtlesim_dash_tutorial/1.0.0-2 -tuw_airskin_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_airskin_msgs/0.0.13-0 -tuw_aruco: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/melodic/tuw_aruco/0.1.1-1 -tuw_checkerboard: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/melodic/tuw_checkerboard/0.1.1-1 -tuw_ellipses: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/melodic/tuw_ellipses/0.1.1-1 -tuw_gazebo_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_gazebo_msgs/0.0.13-0 -tuw_geometry: - url: https://github.com/tuw-robotics/tuw_geometry-release.git - vcs: git - version: release/melodic/tuw_geometry/0.0.3-0 -tuw_geometry_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_geometry_msgs/0.0.13-0 -tuw_marker_detection: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/melodic/tuw_marker_detection/0.1.1-1 -tuw_marker_pose_estimation: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/melodic/tuw_marker_pose_estimation/0.1.1-1 -tuw_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_msgs/0.0.13-0 -tuw_multi_robot_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_multi_robot_msgs/0.0.13-0 -tuw_nav_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_nav_msgs/0.0.13-0 -tuw_object_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_object_msgs/0.0.13-0 -tuw_vehicle_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/melodic/tuw_vehicle_msgs/0.0.13-0 -twist_mux: - url: https://github.com/ros-gbp/twist_mux-release.git - vcs: git - version: release/melodic/twist_mux/3.1.0-1 -twist_mux_msgs: - url: https://github.com/ros-gbp/twist_mux_msgs-release.git - vcs: git - version: release/melodic/twist_mux_msgs/2.1.0-6 -twist_recovery: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/melodic/twist_recovery/0.3.3-1 -ubiquity_motor: - url: https://github.com/UbiquityRobotics-release/ubiquity_motor-release.git - vcs: git - version: release/melodic/ubiquity_motor/0.10.0-1 -ublox: - url: https://github.com/KumarRobotics/ublox-release.git - vcs: git - version: release/melodic/ublox/1.2.0-1 -ublox_gps: - url: https://github.com/KumarRobotics/ublox-release.git - vcs: git - version: release/melodic/ublox_gps/1.2.0-1 -ublox_msgs: - url: https://github.com/KumarRobotics/ublox-release.git - vcs: git - version: release/melodic/ublox_msgs/1.2.0-1 -ublox_serialization: - url: https://github.com/KumarRobotics/ublox-release.git - vcs: git - version: release/melodic/ublox_serialization/1.2.0-1 -um6: - url: https://github.com/ros-drivers-gbp/um6-release.git - vcs: git - version: release/melodic/um6/1.1.3-1 -um7: - url: https://github.com/ros-drivers-gbp/um7-release.git - vcs: git - version: release/melodic/um7/0.0.6-1 -underwater_sensor_msgs: - url: https://github.com/uji-ros-pkg/underwater_simulation-release.git - vcs: git - version: release/melodic/underwater_sensor_msgs/1.4.2-1 -underwater_vehicle_dynamics: - url: https://github.com/uji-ros-pkg/underwater_simulation-release.git - vcs: git - version: release/melodic/underwater_vehicle_dynamics/1.4.2-1 -unique_identifier: - url: https://github.com/ros-geographic-info/unique_identifier-release.git - vcs: git - version: release/melodic/unique_identifier/1.0.6-0 -urdf_geometry_parser: - url: https://github.com/ros-gbp/urdf_geometry_parser-release.git - vcs: git - version: release/melodic/urdf_geometry_parser/0.0.3-0 -urdf_test: - url: https://github.com/pal-gbp/urdf_test-release.git - vcs: git - version: release/melodic/urdf_test/1.0.4-0 -urg_c: - url: https://github.com/ros-gbp/urg_c-release.git - vcs: git - version: release/melodic/urg_c/1.0.405-0 -urg_node: - url: https://github.com/ros-gbp/urg_node-release.git - vcs: git - version: release/melodic/urg_node/0.1.11-0 -urg_stamped: - url: https://github.com/seqsense/urg_stamped-release.git - vcs: git - version: release/melodic/urg_stamped/0.0.3-1 -usb_cam: - url: https://github.com/ros-gbp/usb_cam-release.git - vcs: git - version: release/melodic/usb_cam/0.3.6-0 -usb_cam_controllers: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/melodic/usb_cam_controllers/0.0.4-0 -usb_cam_hardware: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/melodic/usb_cam_hardware/0.0.4-0 -usb_cam_hardware_interface: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/melodic/usb_cam_hardware_interface/0.0.4-0 -usv_gazebo_plugins: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/usv_gazebo_plugins/1.3.0-1 -uuv_assistants: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_assistants/0.6.13-0 -uuv_auv_control_allocator: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_auv_control_allocator/0.6.13-0 -uuv_control_cascaded_pid: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_control_cascaded_pid/0.6.13-0 -uuv_control_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_control_msgs/0.6.13-0 -uuv_control_utils: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_control_utils/0.6.13-0 -uuv_descriptions: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_descriptions/0.6.13-0 -uuv_gazebo: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_gazebo/0.6.13-0 -uuv_gazebo_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_gazebo_plugins/0.6.13-0 -uuv_gazebo_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_gazebo_ros_plugins/0.6.13-0 -uuv_gazebo_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_gazebo_ros_plugins_msgs/0.6.13-0 -uuv_gazebo_worlds: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_gazebo_worlds/0.6.13-0 -uuv_sensor_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_sensor_ros_plugins/0.6.13-0 -uuv_sensor_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_sensor_ros_plugins_msgs/0.6.13-0 -uuv_simulator: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_simulator/0.6.13-0 -uuv_teleop: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_teleop/0.6.13-0 -uuv_thruster_manager: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_thruster_manager/0.6.13-0 -uuv_trajectory_control: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_trajectory_control/0.6.13-0 -uuv_world_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_world_plugins/0.6.13-0 -uuv_world_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_world_ros_plugins/0.6.13-0 -uuv_world_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/melodic/uuv_world_ros_plugins_msgs/0.6.13-0 -uvc_camera: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/melodic/uvc_camera/0.2.7-0 -uwsim: - url: https://github.com/uji-ros-pkg/underwater_simulation-release.git - vcs: git - version: release/melodic/uwsim/1.4.2-1 -uwsim_bullet: - url: https://github.com/uji-ros-pkg/uwsim_bullet-release.git - vcs: git - version: release/melodic/uwsim_bullet/2.82.2-1 -uwsim_osgbullet: - url: https://github.com/uji-ros-pkg/uwsim_osgbullet-release.git - vcs: git - version: release/melodic/uwsim_osgbullet/3.0.1-3 -uwsim_osgocean: - url: https://github.com/uji-ros-pkg/uwsim_osgocean-release.git - vcs: git - version: release/melodic/uwsim_osgocean/1.0.4-1 -uwsim_osgworks: - url: https://github.com/uji-ros-pkg/uwsim_osgworks-release.git - vcs: git - version: release/melodic/uwsim_osgworks/3.0.3-2 -vapor_master: - url: https://github.com/roshub/vapor_master-release.git - vcs: git - version: release/melodic/vapor_master/0.3.0-0 -variant: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/melodic/variant/0.1.5-0 -variant_msgs: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/melodic/variant_msgs/0.1.5-0 -variant_topic_test: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/melodic/variant_topic_test/0.1.5-0 -variant_topic_tools: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/melodic/variant_topic_tools/0.1.5-0 -vector_map_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/melodic/vector_map_msgs/1.13.0-1 -velocity_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/melodic/velocity_controllers/0.15.0-0 -velodyne: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/melodic/velodyne/1.5.2-0 -velodyne_description: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/melodic/velodyne_description/1.0.9-0 -velodyne_driver: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/melodic/velodyne_driver/1.5.2-0 -velodyne_gazebo_plugins: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/melodic/velodyne_gazebo_plugins/1.0.9-0 -velodyne_laserscan: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/melodic/velodyne_laserscan/1.5.2-0 -velodyne_msgs: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/melodic/velodyne_msgs/1.5.2-0 -velodyne_pointcloud: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/melodic/velodyne_pointcloud/1.5.2-0 -velodyne_simulator: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/melodic/velodyne_simulator/1.0.9-0 -video_stream_opencv: - url: https://github.com/ros-drivers/video_stream_opencv-release.git - vcs: git - version: release/melodic/video_stream_opencv/1.1.5-0 -view_controller_msgs: - url: https://github.com/ros-gbp/view_controller_msgs-release.git - vcs: git - version: release/melodic/view_controller_msgs/0.1.3-0 -virtual_force_publisher: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/melodic/virtual_force_publisher/2.2.10-0 -vision_msgs: - url: https://github.com/Kukanani/vision_msgs-release.git - vcs: git - version: release/melodic/vision_msgs/0.0.1-0 -vision_visp: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/vision_visp/0.11.1-1 -visp: - url: https://github.com/lagadic/visp-release.git - vcs: git - version: release/melodic/visp/3.2.0-1 -visp_auto_tracker: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/visp_auto_tracker/0.11.1-1 -visp_bridge: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/visp_bridge/0.11.1-1 -visp_camera_calibration: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/visp_camera_calibration/0.11.1-1 -visp_hand2eye_calibration: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/visp_hand2eye_calibration/0.11.1-1 -visp_tracker: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/melodic/visp_tracker/0.11.1-1 -visualization_osg: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/melodic/visualization_osg/1.0.2-2 -voice_text: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/melodic/voice_text/2.1.13-1 -volksbot_driver: - url: https://github.com/uos-gbp/volksbot_driver-release.git - vcs: git - version: release/melodic/volksbot_driver/1.0.0-3 -vrpn: - url: https://github.com/ros-drivers-gbp/vrpn-release.git - vcs: git - version: release/melodic/vrpn/7.34.0-1 -vrpn_client_ros: - url: https://github.com/ros-drivers-gbp/vrpn_client_ros-release.git - vcs: git - version: release/melodic/vrpn_client_ros/0.2.2-0 -vrx_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/vrx_gazebo/1.3.0-1 -wamv_description: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/wamv_description/1.3.0-1 -wamv_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/wamv_gazebo/1.3.0-1 -warehouse_ros: - url: https://github.com/ros-gbp/warehouse_ros-release.git - vcs: git - version: release/melodic/warehouse_ros/0.9.3-1 -warehouse_ros_mongo: - url: https://github.com/ros-gbp/warehouse_ros_mongo-release.git - vcs: git - version: release/melodic/warehouse_ros_mongo/0.9.1-1 -warthog_control: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/melodic/warthog_control/0.1.1-2 -warthog_description: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/melodic/warthog_description/0.1.1-2 -warthog_desktop: - url: https://github.com/clearpath-gbp/warthog_desktop-release.git - vcs: git - version: release/melodic/warthog_desktop/0.0.1-1 -warthog_gazebo: - url: https://github.com/clearpath-gbp/warthog_simulator-release.git - vcs: git - version: release/melodic/warthog_gazebo/0.2.0-1 -warthog_msgs: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/melodic/warthog_msgs/0.1.1-2 -warthog_simulator: - url: https://github.com/clearpath-gbp/warthog_simulator-release.git - vcs: git - version: release/melodic/warthog_simulator/0.2.0-1 -warthog_viz: - url: https://github.com/clearpath-gbp/warthog_desktop-release.git - vcs: git - version: release/melodic/warthog_viz/0.0.1-1 -wave_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/wave_gazebo/1.3.0-1 -wave_gazebo_plugins: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/melodic/wave_gazebo_plugins/1.3.0-1 -web_video_server: - url: https://github.com/RobotWebTools-release/web_video_server-release.git - vcs: git - version: release/melodic/web_video_server/0.2.1-1 -webots_ros: - url: https://github.com/cyberbotics/webots_ros-release.git - vcs: git - version: release/melodic/webots_ros/2.0.5-1 -webrtc: - url: https://github.com/RobotWebTools-release/webrtc_ros-release.git - vcs: git - version: release/melodic/webrtc/59.0.3-0 -webrtc_ros: - url: https://github.com/RobotWebTools-release/webrtc_ros-release.git - vcs: git - version: release/melodic/webrtc_ros/59.0.3-0 -wge100_camera: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/melodic/wge100_camera/1.8.2-1 -wge100_camera_firmware: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/melodic/wge100_camera_firmware/1.8.2-1 -wge100_driver: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/melodic/wge100_driver/1.8.2-1 -wifi_ddwrt: - url: https://github.com/ros-gbp/wifi_ddwrt-release.git - vcs: git - version: release/melodic/wifi_ddwrt/0.2.0-0 -wiimote: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/melodic/wiimote/1.13.0-1 -willow_maps: - url: https://github.com/ros-gbp/willow_maps-release.git - vcs: git - version: release/melodic/willow_maps/1.0.3-0 -wu_ros_tools: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/melodic/wu_ros_tools/0.2.4-0 -xpp: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp/1.0.10-0 -xpp_examples: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_examples/1.0.10-0 -xpp_hyq: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_hyq/1.0.10-0 -xpp_msgs: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_msgs/1.0.10-0 -xpp_quadrotor: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_quadrotor/1.0.10-0 -xpp_states: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_states/1.0.10-0 -xpp_vis: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/melodic/xpp_vis/1.0.10-0 -xsens_driver: - url: https://github.com/ethz-asl/ethzasl_xsens_driver-release.git - vcs: git - version: release/melodic/xsens_driver/2.2.2-0 -xv_11_laser_driver: - url: https://github.com/rohbotics/xv_11_laser_driver-release.git - vcs: git - version: release/melodic/xv_11_laser_driver/0.3.0-0 -yocs_ar_marker_tracking: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_ar_marker_tracking/0.8.2-0 -yocs_ar_pair_approach: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_ar_pair_approach/0.8.2-0 -yocs_ar_pair_tracking: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_ar_pair_tracking/0.8.2-0 -yocs_cmd_vel_mux: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_cmd_vel_mux/0.8.2-0 -yocs_controllers: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_controllers/0.8.2-0 -yocs_diff_drive_pose_controller: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_diff_drive_pose_controller/0.8.2-0 -yocs_joyop: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_joyop/0.8.2-0 -yocs_keyop: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_keyop/0.8.2-0 -yocs_localization_manager: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_localization_manager/0.8.2-0 -yocs_math_toolkit: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_math_toolkit/0.8.2-0 -yocs_msgs: - url: https://github.com/yujinrobot-release/yocs_msgs-release.git - vcs: git - version: release/melodic/yocs_msgs/0.7.0-0 -yocs_navi_toolkit: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_navi_toolkit/0.8.2-0 -yocs_navigator: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_navigator/0.8.2-0 -yocs_rapps: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_rapps/0.8.2-0 -yocs_safety_controller: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_safety_controller/0.8.2-0 -yocs_velocity_smoother: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_velocity_smoother/0.8.2-0 -yocs_virtual_sensor: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_virtual_sensor/0.8.2-0 -yocs_waypoint_provider: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_waypoint_provider/0.8.2-0 -yocs_waypoints_navi: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yocs_waypoints_navi/0.8.2-0 -yosemite_valley: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/melodic/yosemite_valley/0.0.1-1 -ypspur: - url: https://github.com/openspur/yp-spur-release.git - vcs: git - version: release/melodic/ypspur/1.17.1-1 -ypspur_ros: - url: https://github.com/openspur/ypspur_ros-release.git - vcs: git - version: release/melodic/ypspur_ros/0.3.1-1 -yujin_ocs: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/melodic/yujin_ocs/0.8.2-0 -zeroconf_msgs: - url: https://github.com/yujinrobot-release/zeroconf_msgs-release.git - vcs: git - version: release/melodic/zeroconf_msgs/0.2.1-0 diff --git a/mrt_cmake_modules/yaml/external-mrt-ros-xenial.yaml b/mrt_cmake_modules/yaml/external-mrt-ros-xenial.yaml deleted file mode 100644 index d62779d2eb2..00000000000 --- a/mrt_cmake_modules/yaml/external-mrt-ros-xenial.yaml +++ /dev/null @@ -1,9284 +0,0 @@ -abb: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb/1.3.0-1 -abb_driver: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_driver/1.3.0-1 -abb_irb2400_moveit_config: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb2400_moveit_config/1.3.0-1 -abb_irb2400_moveit_plugins: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb2400_moveit_plugins/1.3.0-1 -abb_irb2400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb2400_support/1.3.0-1 -abb_irb4400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb4400_support/1.3.0-1 -abb_irb5400_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb5400_support/1.3.0-1 -abb_irb6600_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb6600_support/1.3.0-1 -abb_irb6640_moveit_config: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb6640_moveit_config/1.3.0-1 -abb_irb6640_support: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_irb6640_support/1.3.0-1 -abb_resources: - url: https://github.com/ros-industrial-release/abb-release.git - vcs: git - version: release/kinetic/abb_resources/1.3.0-1 -abseil_cpp: - url: https://github.com/Eurecat/abseil_cpp-release.git - vcs: git - version: release/kinetic/abseil_cpp/0.4.2-3 -acado: - url: https://github.com/tud-cor/acado-release.git - vcs: git - version: release/kinetic/acado/1.2.2-0 -access_point_control: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/access_point_control/1.0.15-0 -ackermann_controller: - url: https://github.com/easymov/ackermann_controller-release.git - vcs: git - version: release/kinetic/ackermann_controller/0.1.2-0 -ackermann_msgs: - url: https://github.com/ros-drivers-gbp/ackermann_msgs-release.git - vcs: git - version: release/kinetic/ackermann_msgs/1.0.1-0 -ackermann_steering_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/ackermann_steering_controller/0.13.5-0 -actionlib_enhanced: - url: https://github.com/fannibal/actionlib-enhanced-release.git - vcs: git - version: release/kinetic/actionlib_enhanced/0.0.9-1 -actionlib_lisp: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/actionlib_lisp/0.2.12-1 -addwa_local_planner: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/addwa_local_planner/0.0.12-0 -adi_driver: - url: https://github.com/tork-a/adi_driver-release.git - vcs: git - version: release/kinetic/adi_driver/1.0.3-0 -agni_tf_tools: - url: https://github.com/ubi-agni-gbp/agni_tf_tools-release.git - vcs: git - version: release/kinetic/agni_tf_tools/0.1.2-1 -agvs_common: - url: https://github.com/RobotnikAutomation/agvs_common-release.git - vcs: git - version: release/kinetic/agvs_common/0.1.3-1 -agvs_control: - url: https://github.com/RobotnikAutomation/agvs_sim-release.git - vcs: git - version: release/kinetic/agvs_control/0.1.3-0 -agvs_description: - url: https://github.com/RobotnikAutomation/agvs_common-release.git - vcs: git - version: release/kinetic/agvs_description/0.1.3-1 -agvs_gazebo: - url: https://github.com/RobotnikAutomation/agvs_sim-release.git - vcs: git - version: release/kinetic/agvs_gazebo/0.1.3-0 -agvs_pad: - url: https://github.com/RobotnikAutomation/agvs_common-release.git - vcs: git - version: release/kinetic/agvs_pad/0.1.3-1 -agvs_robot_control: - url: https://github.com/RobotnikAutomation/agvs_sim-release.git - vcs: git - version: release/kinetic/agvs_robot_control/0.1.3-0 -agvs_sim: - url: https://github.com/RobotnikAutomation/agvs_sim-release.git - vcs: git - version: release/kinetic/agvs_sim/0.1.3-0 -agvs_sim_bringup: - url: https://github.com/RobotnikAutomation/agvs_sim-release.git - vcs: git - version: release/kinetic/agvs_sim_bringup/0.1.3-0 -allocators: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/kinetic/allocators/1.0.25-0 -amcl: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/amcl/1.14.4-0 -app_manager: - url: https://github.com/ros-gbp/app_manager-release.git - vcs: git - version: release/kinetic/app_manager/1.0.5-0 -ar_track_alvar: - url: https://github.com/ros-gbp/ar_track_alvar-release.git - vcs: git - version: release/kinetic/ar_track_alvar/0.7.1-0 -ar_track_alvar_msgs: - url: https://github.com/ros-gbp/ar_track_alvar-release.git - vcs: git - version: release/kinetic/ar_track_alvar_msgs/0.7.1-0 -arbotix: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix/0.10.0-1 -arbotix_controllers: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix_controllers/0.10.0-1 -arbotix_firmware: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix_firmware/0.10.0-1 -arbotix_msgs: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix_msgs/0.10.0-1 -arbotix_python: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix_python/0.10.0-1 -arbotix_sensors: - url: https://github.com/vanadiumlabs/arbotix_ros-release.git - vcs: git - version: release/kinetic/arbotix_sensors/0.10.0-1 -ardrone_autonomy: - url: https://github.com/AutonomyLab/ardrone_autonomy-release.git - vcs: git - version: release/kinetic/ardrone_autonomy/1.4.1-0 -arduino_daq: - url: https://github.com/ual-arm-ros-pkg-release/arduino_daq-release.git - vcs: git - version: release/kinetic/arduino_daq/1.0.1-0 -arm_navigation_msgs: - url: https://github.com/tork-a/openrave_planning-release.git - vcs: git - version: release/kinetic/arm_navigation_msgs/0.0.6-0 -aruco: - url: https://github.com/pal-gbp/aruco_ros-release.git - vcs: git - version: release/kinetic/aruco/0.2.3-0 -aruco_detect: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/kinetic/aruco_detect/0.11.0-1 -aruco_msgs: - url: https://github.com/pal-gbp/aruco_ros-release.git - vcs: git - version: release/kinetic/aruco_msgs/0.2.3-0 -aruco_ros: - url: https://github.com/pal-gbp/aruco_ros-release.git - vcs: git - version: release/kinetic/aruco_ros/0.2.3-0 -asmach: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/asmach/1.0.15-0 -asmach_tutorials: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/asmach_tutorials/1.0.15-0 -assimp_devel: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/assimp_devel/2.1.13-1 -assisted_teleop: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/assisted_teleop/0.2.1-0 -astra_camera: - url: https://github.com/ros-drivers-gbp/astra_camera-release.git - vcs: git - version: release/kinetic/astra_camera/0.2.2-1 -astra_launch: - url: https://github.com/ros-drivers-gbp/astra_launch-release.git - vcs: git - version: release/kinetic/astra_launch/0.2.2-0 -astuff_sensor_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/astuff_sensor_msgs/2.3.1-0 -async_comm: - url: https://github.com/dpkoch/async_comm-release.git - vcs: git - version: release/kinetic/async_comm/0.1.1-0 -async_web_server_cpp: - url: https://github.com/gt-rail-release/async_web_server_cpp-release.git - vcs: git - version: release/kinetic/async_web_server_cpp/0.0.3-0 -ati_ft_sensor: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/ati_ft_sensor/0.2.0-0 -audibot: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/kinetic/audibot/0.1.0-0 -audibot_description: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/kinetic/audibot_description/0.1.0-0 -audibot_gazebo: - url: https://github.com/robustify/audibot-release.git - vcs: git - version: release/kinetic/audibot_gazebo/0.1.0-0 -audio_capture: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/kinetic/audio_capture/0.3.3-0 -audio_common: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/kinetic/audio_common/0.3.3-0 -audio_common_msgs: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/kinetic/audio_common_msgs/0.3.3-0 -audio_play: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/kinetic/audio_play/0.3.3-0 -automotive_autonomy_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/kinetic/automotive_autonomy_msgs/2.0.3-0 -automotive_navigation_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/kinetic/automotive_navigation_msgs/2.0.3-0 -automotive_platform_msgs: - url: https://github.com/astuff/automotive_autonomy_msgs-release.git - vcs: git - version: release/kinetic/automotive_platform_msgs/2.0.3-0 -autoware_can_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_can_msgs/1.12.0-1 -autoware_config_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_config_msgs/1.12.0-1 -autoware_external_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_external_msgs/1.12.0-1 -autoware_map_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_map_msgs/1.12.0-1 -autoware_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_msgs/1.12.0-1 -autoware_system_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/autoware_system_msgs/1.12.0-1 -auv_msgs: - url: https://github.com/oceansystemslab/auv_msgs-release.git - vcs: git - version: release/kinetic/auv_msgs/0.1.0-0 -avt_vimba_camera: - url: https://github.com/srv/avt_vimba_camera-release.git - vcs: git - version: release/kinetic/avt_vimba_camera/0.0.10-0 -aws_common: - url: https://github.com/aws-gbp/aws_common-release.git - vcs: git - version: release/kinetic/aws_common/2.1.0-1 -aws_ros1_common: - url: https://github.com/aws-gbp/aws_ros1_common-release.git - vcs: git - version: release/kinetic/aws_ros1_common/2.0.1-1 -axcli: - url: https://github.com/po1/axcli-release.git - vcs: git - version: release/kinetic/axcli/0.1.0-0 -axis_camera: - url: https://github.com/ros-drivers-gbp/axis_camera-release.git - vcs: git - version: release/kinetic/axis_camera/0.3.0-0 -backward_ros: - url: https://github.com/pal-gbp/backward_ros-release.git - vcs: git - version: release/kinetic/backward_ros/0.1.7-0 -bagger: - url: https://github.com/squarerobot/bagger-release.git - vcs: git - version: release/kinetic/bagger/0.1.3-2 -baldor: - url: https://github.com/crigroup/baldor-release.git - vcs: git - version: release/kinetic/baldor/0.1.2-0 -barrett_hand: - url: https://github.com/RobotnikAutomation/barrett_hand-release.git - vcs: git - version: release/kinetic/barrett_hand/0.1.2-0 -barrett_hand_common: - url: https://github.com/RobotnikAutomation/barrett_hand_common-release.git - vcs: git - version: release/kinetic/barrett_hand_common/0.1.2-0 -barrett_hand_control: - url: https://github.com/RobotnikAutomation/barrett_hand_sim-release.git - vcs: git - version: release/kinetic/barrett_hand_control/0.1.2-0 -barrett_hand_description: - url: https://github.com/RobotnikAutomation/barrett_hand_common-release.git - vcs: git - version: release/kinetic/barrett_hand_description/0.1.2-0 -barrett_hand_gazebo: - url: https://github.com/RobotnikAutomation/barrett_hand_sim-release.git - vcs: git - version: release/kinetic/barrett_hand_gazebo/0.1.2-0 -barrett_hand_sim: - url: https://github.com/RobotnikAutomation/barrett_hand_sim-release.git - vcs: git - version: release/kinetic/barrett_hand_sim/0.1.2-0 -base_local_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/base_local_planner/1.14.4-0 -bayesian_belief_networks: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/bayesian_belief_networks/2.1.13-1 -bcap: - url: https://github.com/fsuarez6/bcap-release.git - vcs: git - version: release/kinetic/bcap/0.1.0-0 -bcap_core: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/bcap_core/3.0.2-1 -bcap_service: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/bcap_service/3.0.2-1 -bcap_service_test: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/bcap_service_test/3.0.2-1 -behaviortree_cpp: - url: https://github.com/BehaviorTree/behaviortree_cpp-release.git - vcs: git - version: release/kinetic/behaviortree_cpp/2.5.1-0 -behaviortree_cpp_v3: - url: https://github.com/BehaviorTree/behaviortree_cpp_v3-release.git - vcs: git - version: release/kinetic/behaviortree_cpp_v3/3.0.7-0 -bfl: - url: https://github.com/ros-gbp/bfl-release.git - vcs: git - version: release/kinetic/bfl/0.7.0-2 -bhand_controller: - url: https://github.com/RobotnikAutomation/barrett_hand-release.git - vcs: git - version: release/kinetic/bhand_controller/0.1.2-0 -bin_pose_emulator: - url: https://github.com/durovsky/binpicking_utils-release.git - vcs: git - version: release/kinetic/bin_pose_emulator/0.1.4-0 -bin_pose_msgs: - url: https://github.com/durovsky/binpicking_utils-release.git - vcs: git - version: release/kinetic/bin_pose_msgs/0.1.4-0 -binpicking_simple_utils: - url: https://github.com/durovsky/binpicking_utils-release.git - vcs: git - version: release/kinetic/binpicking_simple_utils/0.1.4-0 -binpicking_utils: - url: https://github.com/durovsky/binpicking_utils-release.git - vcs: git - version: release/kinetic/binpicking_utils/0.1.4-0 -brics_actuator: - url: https://github.com/wnowak/brics_actuator-release.git - vcs: git - version: release/kinetic/brics_actuator/0.7.0-0 -calibration: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/calibration/0.10.14-0 -calibration_estimation: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/calibration_estimation/0.10.14-0 -calibration_launch: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/calibration_launch/0.10.14-0 -calibration_msgs: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/calibration_msgs/0.10.14-0 -calibration_setup_helper: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/calibration_setup_helper/0.10.14-0 -camera1394: - url: https://github.com/ros-drivers-gbp/camera1394-release.git - vcs: git - version: release/kinetic/camera1394/1.10.1-0 -camera_info_manager_py: - url: https://github.com/ros-gbp/camera_info_manager_py-release.git - vcs: git - version: release/kinetic/camera_info_manager_py/0.2.3-0 -camera_umd: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/kinetic/camera_umd/0.2.5-0 -can_msgs: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/can_msgs/0.7.11-1 -canopen_402: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/canopen_402/0.7.11-1 -canopen_chain_node: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/canopen_chain_node/0.7.11-1 -canopen_master: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/canopen_master/0.7.11-1 -canopen_motor_node: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/canopen_motor_node/0.7.11-1 -capabilities: - url: https://github.com/ros-gbp/capabilities-release.git - vcs: git - version: release/kinetic/capabilities/0.2.0-0 -care_o_bot: - url: https://github.com/ipa320/care-o-bot-release.git - vcs: git - version: release/kinetic/care_o_bot/0.6.7-0 -care_o_bot_desktop: - url: https://github.com/ipa320/care-o-bot-release.git - vcs: git - version: release/kinetic/care_o_bot_desktop/0.6.7-0 -care_o_bot_robot: - url: https://github.com/ipa320/care-o-bot-release.git - vcs: git - version: release/kinetic/care_o_bot_robot/0.6.7-0 -care_o_bot_simulation: - url: https://github.com/ipa320/care-o-bot-release.git - vcs: git - version: release/kinetic/care_o_bot_simulation/0.6.7-0 -carrot_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/carrot_planner/1.14.4-0 -cartesian_msgs: - url: https://github.com/davetcoleman/cartesian_msgs-release.git - vcs: git - version: release/kinetic/cartesian_msgs/0.0.3-1 -cartographer: - url: https://github.com/ros-gbp/cartographer-release.git - vcs: git - version: release/kinetic/cartographer/0.2.0-2 -cartographer_ros: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/kinetic/cartographer_ros/0.2.0-0 -cartographer_ros_msgs: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/kinetic/cartographer_ros_msgs/0.2.0-0 -cartographer_rviz: - url: https://github.com/ros-gbp/cartographer_ros-release.git - vcs: git - version: release/kinetic/cartographer_rviz/0.2.0-0 -catch_ros: - url: https://github.com/AIS-Bonn/catch_ros-release.git - vcs: git - version: release/kinetic/catch_ros/0.3.0-0 -catkin_pip: - url: https://github.com/pyros-dev/catkin_pip-release.git - vcs: git - version: release/kinetic/catkin_pip/0.2.3-0 -catkin_virtualenv: - url: https://github.com/locusrobotics/catkin_virtualenv-release.git - vcs: git - version: release/kinetic/catkin_virtualenv/0.4.1-2 -certifi: - url: https://github.com/asmodehn/certifi-rosrelease.git - vcs: git - version: release/kinetic/certifi/2015.11.20-3 -checkerboard_detector: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/checkerboard_detector/1.2.9-0 -chomp_motion_planner: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/chomp_motion_planner/0.9.17-1 -cht10_node: - url: https://github.com/Playfish/cht10_node_release.git - vcs: git - version: release/kinetic/cht10_node/0.0.1-1 -cl_tf: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_tf/0.2.12-1 -cl_tf2: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_tf2/0.2.12-1 -cl_transforms: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_transforms/0.2.12-1 -cl_transforms_stamped: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_transforms_stamped/0.2.12-1 -cl_urdf: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_urdf/0.2.12-1 -cl_utils: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/cl_utils/0.2.12-1 -clear_costmap_recovery: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/clear_costmap_recovery/1.14.4-0 -click: - url: https://github.com/asmodehn/click-rosrelease.git - vcs: git - version: release/kinetic/click/6.2.0-1 -clock_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/clock_relay/0.0.2-1 -cloudwatch_logger: - url: https://github.com/aws-gbp/cloudwatch_logger-release.git - vcs: git - version: release/kinetic/cloudwatch_logger/2.2.1-1 -cloudwatch_logs_common: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/kinetic/cloudwatch_logs_common/1.1.0-2 -cloudwatch_metrics_collector: - url: https://github.com/aws-gbp/cloudwatch_metrics_collector-release.git - vcs: git - version: release/kinetic/cloudwatch_metrics_collector/2.1.1-1 -cloudwatch_metrics_common: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/kinetic/cloudwatch_metrics_common/1.1.0-2 -cm_740_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/cm_740_module/0.2.1-0 -cmd_vel_smoother: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/cmd_vel_smoother/0.1.14-0 -cnn_bridge: - url: https://github.com/wew84/cnn_bridge-release.git - vcs: git - version: release/kinetic/cnn_bridge/0.8.5-1 -cob_3d_mapping_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_3d_mapping_msgs/0.6.14-1 -cob_actions: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/cob_actions/0.7.0-1 -cob_android: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/kinetic/cob_android/0.1.6-1 -cob_android_msgs: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/kinetic/cob_android_msgs/0.1.6-1 -cob_android_resource_server: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/kinetic/cob_android_resource_server/0.1.6-1 -cob_android_script_server: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/kinetic/cob_android_script_server/0.1.6-1 -cob_android_settings: - url: https://github.com/ipa320/cob_android-release.git - vcs: git - version: release/kinetic/cob_android_settings/0.1.6-1 -cob_base_controller_utils: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_base_controller_utils/0.7.8-1 -cob_base_drive_chain: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_base_drive_chain/0.7.0-1 -cob_base_velocity_smoother: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_base_velocity_smoother/0.7.8-1 -cob_bms_driver: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_bms_driver/0.7.0-1 -cob_bringup: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_bringup/0.7.1-1 -cob_bringup_sim: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/kinetic/cob_bringup_sim/0.7.1-2 -cob_calibration_data: - url: https://github.com/ipa320/cob_calibration_data-release.git - vcs: git - version: release/kinetic/cob_calibration_data/0.6.12-1 -cob_cam3d_throttle: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_cam3d_throttle/0.6.14-1 -cob_camera_sensors: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_camera_sensors/0.7.0-1 -cob_canopen_motor: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_canopen_motor/0.7.0-1 -cob_cartesian_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_cartesian_controller/0.7.8-1 -cob_collision_monitor: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_collision_monitor/0.7.2-1 -cob_collision_velocity_filter: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_collision_velocity_filter/0.7.8-1 -cob_command_gui: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_command_gui/0.6.14-1 -cob_command_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_command_tools/0.6.14-1 -cob_common: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/cob_common/0.7.0-1 -cob_control: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_control/0.7.8-1 -cob_control_mode_adapter: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_control_mode_adapter/0.7.8-1 -cob_control_msgs: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_control_msgs/0.7.8-1 -cob_dashboard: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_dashboard/0.6.14-1 -cob_default_env_config: - url: https://github.com/ipa320/cob_environments-release.git - vcs: git - version: release/kinetic/cob_default_env_config/0.6.10-1 -cob_default_robot_behavior: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_default_robot_behavior/0.7.1-1 -cob_default_robot_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_default_robot_config/0.7.1-1 -cob_description: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/cob_description/0.7.0-1 -cob_docker_control: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/kinetic/cob_docker_control/0.6.8-1 -cob_driver: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_driver/0.7.0-1 -cob_elmo_homing: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_elmo_homing/0.7.0-1 -cob_environments: - url: https://github.com/ipa320/cob_environments-release.git - vcs: git - version: release/kinetic/cob_environments/0.6.10-1 -cob_extern: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/cob_extern/0.6.13-1 -cob_footprint_observer: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_footprint_observer/0.7.8-1 -cob_frame_tracker: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_frame_tracker/0.7.8-1 -cob_gazebo: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/kinetic/cob_gazebo/0.7.1-2 -cob_gazebo_objects: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/kinetic/cob_gazebo_objects/0.7.1-2 -cob_gazebo_plugins: - url: https://github.com/ipa320/cob_gazebo_plugins-release.git - vcs: git - version: release/kinetic/cob_gazebo_plugins/0.7.3-1 -cob_gazebo_ros_control: - url: https://github.com/ipa320/cob_gazebo_plugins-release.git - vcs: git - version: release/kinetic/cob_gazebo_ros_control/0.7.3-1 -cob_gazebo_worlds: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/kinetic/cob_gazebo_worlds/0.7.1-2 -cob_generic_can: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_generic_can/0.7.0-1 -cob_grasp_generation: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_grasp_generation/0.7.2-1 -cob_hand: - url: https://github.com/ipa320/cob_hand-release.git - vcs: git - version: release/kinetic/cob_hand/0.6.6-1 -cob_hand_bridge: - url: https://github.com/ipa320/cob_hand-release.git - vcs: git - version: release/kinetic/cob_hand_bridge/0.6.6-1 -cob_hardware_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_hardware_config/0.7.1-1 -cob_helper_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_helper_tools/0.6.14-1 -cob_image_flip: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_image_flip/0.6.14-1 -cob_interactive_teleop: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_interactive_teleop/0.6.14-1 -cob_light: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_light/0.7.0-1 -cob_linear_nav: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_linear_nav/0.6.8-1 -cob_lookat_action: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_lookat_action/0.7.2-1 -cob_manipulation: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_manipulation/0.7.2-1 -cob_map_accessibility_analysis: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_map_accessibility_analysis/0.6.8-1 -cob_mapping_slam: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_mapping_slam/0.6.8-1 -cob_mimic: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_mimic/0.7.0-1 -cob_model_identifier: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_model_identifier/0.7.8-1 -cob_monitoring: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_monitoring/0.6.14-1 -cob_moveit_bringup: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_moveit_bringup/0.7.2-1 -cob_moveit_config: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_moveit_config/0.7.1-1 -cob_moveit_interface: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_moveit_interface/0.7.2-1 -cob_msgs: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/cob_msgs/0.7.0-1 -cob_navigation: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_navigation/0.6.8-1 -cob_navigation_config: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_navigation_config/0.6.8-1 -cob_navigation_global: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_navigation_global/0.6.8-1 -cob_navigation_local: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_navigation_local/0.6.8-1 -cob_navigation_slam: - url: https://github.com/ipa320/cob_navigation-release.git - vcs: git - version: release/kinetic/cob_navigation_slam/0.6.8-1 -cob_object_detection_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_object_detection_msgs/0.6.14-1 -cob_object_detection_visualizer: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_object_detection_visualizer/0.6.14-1 -cob_obstacle_distance: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_obstacle_distance/0.7.8-1 -cob_obstacle_distance_moveit: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_obstacle_distance_moveit/0.7.2-1 -cob_omni_drive_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_omni_drive_controller/0.7.8-1 -cob_perception_common: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_perception_common/0.6.14-1 -cob_perception_msgs: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_perception_msgs/0.6.14-1 -cob_phidget_em_state: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_phidget_em_state/0.7.0-1 -cob_phidget_power_state: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_phidget_power_state/0.7.0-1 -cob_phidgets: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_phidgets/0.7.0-1 -cob_pick_place_action: - url: https://github.com/ipa320/cob_manipulation-release.git - vcs: git - version: release/kinetic/cob_pick_place_action/0.7.2-1 -cob_reflector_referencing: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/kinetic/cob_reflector_referencing/0.6.8-1 -cob_relayboard: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_relayboard/0.7.0-1 -cob_robots: - url: https://github.com/ipa320/cob_robots-release.git - vcs: git - version: release/kinetic/cob_robots/0.7.1-1 -cob_safety_controller: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/kinetic/cob_safety_controller/0.6.8-1 -cob_scan_unifier: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_scan_unifier/0.7.0-1 -cob_script_server: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_script_server/0.6.14-1 -cob_sick_lms1xx: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_sick_lms1xx/0.7.0-1 -cob_sick_s300: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_sick_s300/0.7.0-1 -cob_simulation: - url: https://github.com/ipa320/cob_simulation-release.git - vcs: git - version: release/kinetic/cob_simulation/0.7.1-2 -cob_sound: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_sound/0.7.0-1 -cob_srvs: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/cob_srvs/0.7.0-1 -cob_substitute: - url: https://github.com/ipa320/cob_substitute-release.git - vcs: git - version: release/kinetic/cob_substitute/0.6.8-1 -cob_supported_robots: - url: https://github.com/ipa320/cob_supported_robots-release.git - vcs: git - version: release/kinetic/cob_supported_robots/0.6.12-1 -cob_teleop: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/cob_teleop/0.6.14-1 -cob_trajectory_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_trajectory_controller/0.7.8-1 -cob_tricycle_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_tricycle_controller/0.7.8-1 -cob_twist_controller: - url: https://github.com/ipa320/cob_control-release.git - vcs: git - version: release/kinetic/cob_twist_controller/0.7.8-1 -cob_undercarriage_ctrl: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_undercarriage_ctrl/0.7.0-1 -cob_utilities: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_utilities/0.7.0-1 -cob_vision_utils: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/cob_vision_utils/0.6.14-1 -cob_voltage_control: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/cob_voltage_control/0.7.0-1 -code_coverage: - url: https://github.com/mikeferguson/code_coverage-gbp.git - vcs: git - version: release/kinetic/code_coverage/0.2.4-1 -codec_image_transport: - url: https://github.com/yoshito-n-students/codec_image_transport-release.git - vcs: git - version: release/kinetic/codec_image_transport/0.0.3-0 -cog_publisher: - url: https://github.com/OUXT-Polaris/cog_publisher-release.git - vcs: git - version: release/kinetic/cog_publisher/1.0.1-4 -collada_robots: - url: https://github.com/tork-a/openrave_planning-release.git - vcs: git - version: release/kinetic/collada_robots/0.0.6-0 -collada_urdf_jsk_patch: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/collada_urdf_jsk_patch/2.1.13-1 -combined_robot_hw: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/combined_robot_hw/0.13.3-0 -combined_robot_hw_tests: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/combined_robot_hw_tests/0.13.3-0 -concert_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/concert_msgs/0.9.0-1 -concert_service_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/concert_service_msgs/0.9.0-1 -concert_workflow_engine_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/concert_workflow_engine_msgs/0.9.0-1 -contact_states_observer: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/contact_states_observer/0.1.14-0 -control_toolbox: - url: https://github.com/ros-gbp/control_toolbox-release.git - vcs: git - version: release/kinetic/control_toolbox/1.17.0-0 -controller_interface: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/controller_interface/0.13.3-0 -controller_manager: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/controller_manager/0.13.3-0 -controller_manager_msgs: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/controller_manager_msgs/0.13.3-0 -controller_manager_tests: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/controller_manager_tests/0.13.3-0 -convex_decomposition: - url: https://github.com/ros-gbp/convex_decomposition-release.git - vcs: git - version: release/kinetic/convex_decomposition/0.1.11-0 -cost_map: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map/0.3.3-0 -cost_map_core: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_core/0.3.3-0 -cost_map_cv: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_cv/0.3.3-0 -cost_map_demos: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_demos/0.3.3-0 -cost_map_msgs: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_msgs/0.3.3-0 -cost_map_ros: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_ros/0.3.3-0 -cost_map_visualisations: - url: https://github.com/stonier/cost_map-release.git - vcs: git - version: release/kinetic/cost_map_visualisations/0.3.3-0 -costmap_converter: - url: https://github.com/rst-tu-dortmund/costmap_converter-release.git - vcs: git - version: release/kinetic/costmap_converter/0.0.9-0 -costmap_cspace: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/costmap_cspace/0.4.2-1 -costmap_cspace_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/kinetic/costmap_cspace_msgs/0.3.1-0 -costmap_prohibition_layer: - url: https://github.com/rst-tu-dortmund/costmap_prohibition_layer-release.git - vcs: git - version: release/kinetic/costmap_prohibition_layer/0.0.5-0 -costmap_queue: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/costmap_queue/0.2.5-0 -cpr_multimaster_tools: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/cpr_multimaster_tools/0.0.2-1 -create_dashboard: - url: https://github.com/turtlebot-release/turtlebot_create_desktop-release.git - vcs: git - version: release/kinetic/create_dashboard/2.3.1-0 -create_description: - url: https://github.com/turtlebot-release/turtlebot_create-release.git - vcs: git - version: release/kinetic/create_description/2.3.1-0 -create_driver: - url: https://github.com/turtlebot-release/turtlebot_create-release.git - vcs: git - version: release/kinetic/create_driver/2.3.1-0 -create_node: - url: https://github.com/turtlebot-release/turtlebot_create-release.git - vcs: git - version: release/kinetic/create_node/2.3.1-0 -criutils: - url: https://github.com/crigroup/criutils-release.git - vcs: git - version: release/kinetic/criutils/0.1.3-0 -csm: - url: https://github.com/ros-gbp/csm-release.git - vcs: git - version: release/kinetic/csm/1.0.2-1 -cv_camera: - url: https://github.com/OTL/cv_camera-release.git - vcs: git - version: release/kinetic/cv_camera/0.3.0-0 -darknet_ros_msgs: - url: https://github.com/leggedrobotics/darknet_ros-release.git - vcs: git - version: release/kinetic/darknet_ros_msgs/1.1.4-0 -dartsim: - url: https://github.com/dartsim/ros-dartsim-release.git - vcs: git - version: release/kinetic/dartsim/6.3.1-2 -dataflow_lite: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/kinetic/dataflow_lite/1.1.0-2 -dataspeed_can: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/kinetic/dataspeed_can/1.0.12-0 -dataspeed_can_msg_filters: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/kinetic/dataspeed_can_msg_filters/1.0.12-0 -dataspeed_can_tools: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/kinetic/dataspeed_can_tools/1.0.12-0 -dataspeed_can_usb: - url: https://github.com/DataspeedInc-release/dataspeed_can-release.git - vcs: git - version: release/kinetic/dataspeed_can_usb/1.0.12-0 -dataspeed_pds: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/kinetic/dataspeed_pds/1.0.2-0 -dataspeed_pds_can: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/kinetic/dataspeed_pds_can/1.0.2-0 -dataspeed_pds_msgs: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/kinetic/dataspeed_pds_msgs/1.0.2-0 -dataspeed_pds_rqt: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/kinetic/dataspeed_pds_rqt/1.0.2-0 -dataspeed_pds_scripts: - url: https://github.com/DataspeedInc-release/dataspeed_pds-release.git - vcs: git - version: release/kinetic/dataspeed_pds_scripts/1.0.2-0 -dataspeed_ulc: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/kinetic/dataspeed_ulc/0.0.4-1 -dataspeed_ulc_can: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/kinetic/dataspeed_ulc_can/0.0.4-1 -dataspeed_ulc_msgs: - url: https://github.com/DataspeedInc-release/dataspeed_ulc_ros-release.git - vcs: git - version: release/kinetic/dataspeed_ulc_msgs/0.0.4-1 -dbw_fca: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/kinetic/dbw_fca/1.0.6-1 -dbw_fca_can: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/kinetic/dbw_fca_can/1.0.6-1 -dbw_fca_description: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/kinetic/dbw_fca_description/1.0.6-1 -dbw_fca_joystick_demo: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/kinetic/dbw_fca_joystick_demo/1.0.6-1 -dbw_fca_msgs: - url: https://github.com/DataspeedInc-release/dbw_fca_ros-release.git - vcs: git - version: release/kinetic/dbw_fca_msgs/1.0.6-1 -dbw_mkz: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz/1.2.3-1 -dbw_mkz_can: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz_can/1.2.3-1 -dbw_mkz_description: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz_description/1.2.3-1 -dbw_mkz_joystick_demo: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz_joystick_demo/1.2.3-1 -dbw_mkz_msgs: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz_msgs/1.2.3-1 -dbw_mkz_twist_controller: - url: https://github.com/DataspeedInc-release/dbw_mkz_ros-release.git - vcs: git - version: release/kinetic/dbw_mkz_twist_controller/1.2.3-1 -ddwrt_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/ddwrt_access_point/1.0.15-0 -ddynamic_reconfigure: - url: https://github.com/pal-gbp/ddynamic_reconfigure.git - vcs: git - version: release/kinetic/ddynamic_reconfigure/0.2.0-0 -ddynamic_reconfigure_python: - url: https://github.com/pal-gbp/ddynamic_reconfigure_python-release.git - vcs: git - version: release/kinetic/ddynamic_reconfigure_python/0.0.1-0 -declination: - url: https://github.com/clearpath-gbp/declination-release.git - vcs: git - version: release/kinetic/declination/0.0.2-0 -default_cfg_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/default_cfg_fkie/0.8.12-0 -delphi_esr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/delphi_esr_msgs/2.3.1-0 -delphi_mrr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/delphi_mrr_msgs/2.3.1-0 -delphi_srr_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/delphi_srr_msgs/2.3.1-0 -dense_laser_assembler: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/dense_laser_assembler/1.0.11-0 -denso: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/denso/2.0.3-0 -denso_launch: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/denso_launch/2.0.3-0 -denso_robot_bringup: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_bringup/3.0.2-1 -denso_robot_control: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_control/3.0.2-1 -denso_robot_core: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_core/3.0.2-1 -denso_robot_core_test: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_core_test/3.0.2-1 -denso_robot_descriptions: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_descriptions/3.0.2-1 -denso_robot_gazebo: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_gazebo/3.0.2-1 -denso_robot_moveit_config: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_moveit_config/3.0.2-1 -denso_robot_ros: - url: https://github.com/DENSORobot/denso_robot_ros-release.git - vcs: git - version: release/kinetic/denso_robot_ros/3.0.2-1 -denso_ros_control: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/denso_ros_control/2.0.3-0 -depthcloud_encoder: - url: https://github.com/RobotWebTools-release/depthcloud_encoder-release.git - vcs: git - version: release/kinetic/depthcloud_encoder/0.1.1-1 -depthimage_to_laserscan: - url: https://github.com/ros-gbp/depthimage_to_laserscan-release.git - vcs: git - version: release/kinetic/depthimage_to_laserscan/1.0.7-0 -derived_object_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/derived_object_msgs/2.3.1-0 -desistek_saga_control: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/kinetic/desistek_saga_control/0.3.2-0 -desistek_saga_description: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/kinetic/desistek_saga_description/0.3.2-0 -desistek_saga_gazebo: - url: https://github.com/uuvsimulator/desistek_saga-release.git - vcs: git - version: release/kinetic/desistek_saga_gazebo/0.3.2-0 -diff_drive_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/diff_drive_controller/0.13.5-0 -distance_map: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map/0.1.0-1 -distance_map_core: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_core/0.1.0-1 -distance_map_deadreck: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_deadreck/0.1.0-1 -distance_map_msgs: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_msgs/0.1.0-1 -distance_map_node: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_node/0.1.0-1 -distance_map_opencv: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_opencv/0.1.0-1 -distance_map_rviz: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_rviz/0.1.0-1 -distance_map_tools: - url: https://github.com/artivis/distance_map-release.git - vcs: git - version: release/kinetic/distance_map_tools/0.1.0-1 -dlux_global_planner: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dlux_global_planner/0.2.5-0 -dlux_plugins: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dlux_plugins/0.2.5-0 -dnn_detect: - url: https://github.com/UbiquityRobotics-release/dnn_detect-release.git - vcs: git - version: release/kinetic/dnn_detect/0.0.3-0 -dockeros: - url: https://github.com/ct2034/dockeros-release.git - vcs: git - version: release/kinetic/dockeros/1.0.3-0 -doosan_robot: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/doosan_robot/0.9.6-1 -doosan_robotics: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/doosan_robotics/0.9.6-1 -downward: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/downward/2.1.13-1 -dr_base: - url: https://github.com/delftrobotics/dr_base-release.git - vcs: git - version: release/kinetic/dr_base/1.0.0-0 -dr_cmake: - url: https://github.com/delftrobotics/dr_base-release.git - vcs: git - version: release/kinetic/dr_cmake/1.0.0-0 -driver_base: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/kinetic/driver_base/1.6.8-0 -driver_common: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/kinetic/driver_common/1.6.8-0 -drone_wrapper: - url: https://github.com/JdeRobot/drones-release.git - vcs: git - version: release/kinetic/drone_wrapper/1.0.1-1 -dsr_control: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_control/0.9.6-1 -dsr_description: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_description/0.9.6-1 -dsr_example_cpp: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_example_cpp/0.9.6-1 -dsr_example_py: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_example_py/0.9.6-1 -dsr_gazebo: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_gazebo/0.9.6-1 -dsr_launcher: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_launcher/0.9.6-1 -dsr_msgs: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/dsr_msgs/0.9.6-1 -dwa_local_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/dwa_local_planner/1.14.4-0 -dwb_critics: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dwb_critics/0.2.5-0 -dwb_local_planner: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dwb_local_planner/0.2.5-0 -dwb_msgs: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dwb_msgs/0.2.5-0 -dwb_plugins: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/dwb_plugins/0.2.5-0 -dynamic_edt_3d: - url: https://github.com/ros-gbp/octomap-release.git - vcs: git - version: release/kinetic/dynamic_edt_3d/1.8.1-0 -dynamic_robot_state_publisher: - url: https://github.com/peci1/dynamic_robot_state_publisher-release.git - vcs: git - version: release/kinetic/dynamic_robot_state_publisher/1.1.1-0 -dynamic_tf_publisher: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/dynamic_tf_publisher/2.2.10-0 -dynamixel_controllers: - url: https://github.com/arebgun/dynamixel_motor-release.git - vcs: git - version: release/kinetic/dynamixel_controllers/0.4.1-0 -dynamixel_driver: - url: https://github.com/arebgun/dynamixel_motor-release.git - vcs: git - version: release/kinetic/dynamixel_driver/0.4.1-0 -dynamixel_motor: - url: https://github.com/arebgun/dynamixel_motor-release.git - vcs: git - version: release/kinetic/dynamixel_motor/0.4.1-0 -dynamixel_msgs: - url: https://github.com/arebgun/dynamixel_motor-release.git - vcs: git - version: release/kinetic/dynamixel_msgs/0.4.1-0 -dynamixel_sdk: - url: https://github.com/ROBOTIS-GIT-release/DynamixelSDK-release.git - vcs: git - version: release/kinetic/dynamixel_sdk/3.7.11-1 -dynamixel_tutorials: - url: https://github.com/arebgun/dynamixel_motor-release.git - vcs: git - version: release/kinetic/dynamixel_tutorials/0.4.1-0 -dynamixel_workbench: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench/2.0.0-0 -dynamixel_workbench_controllers: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_controllers/2.0.0-0 -dynamixel_workbench_msgs: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-msgs-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_msgs/2.0.0-0 -dynamixel_workbench_operators: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_operators/2.0.0-0 -dynamixel_workbench_single_manager: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_single_manager/2.0.0-0 -dynamixel_workbench_single_manager_gui: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_single_manager_gui/2.0.0-0 -dynamixel_workbench_toolbox: - url: https://github.com/ROBOTIS-GIT-release/dynamixel-workbench-release.git - vcs: git - version: release/kinetic/dynamixel_workbench_toolbox/2.0.0-0 -dynpick_driver: - url: https://github.com/tork-a/dynpick_driver-release.git - vcs: git - version: release/kinetic/dynpick_driver/0.2.0-0 -earth_rover_localization: - url: https://github.com/earthrover/earth_rover_localization-release.git - vcs: git - version: release/kinetic/earth_rover_localization/1.2.0-0 -earth_rover_piksi: - url: https://github.com/earthrover/earth_rover_piksi-release.git - vcs: git - version: release/kinetic/earth_rover_piksi/1.8.2-1 -easy_markers: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/kinetic/easy_markers/0.2.4-0 -eband_local_planner: - url: https://github.com/utexas-bwi-gbp/eband_local_planner-release.git - vcs: git - version: release/kinetic/eband_local_planner/0.3.1-0 -eca_a9_control: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/kinetic/eca_a9_control/0.1.6-0 -eca_a9_description: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/kinetic/eca_a9_description/0.1.6-0 -eca_a9_gazebo: - url: https://github.com/uuvsimulator/eca_a9-release.git - vcs: git - version: release/kinetic/eca_a9_gazebo/0.1.6-0 -ecl: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/kinetic/ecl/0.60.1-1 -ecl_build: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/kinetic/ecl_build/0.61.6-0 -ecl_command_line: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_command_line/0.61.17-0 -ecl_concepts: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_concepts/0.61.17-0 -ecl_config: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_config/0.61.6-0 -ecl_console: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_console/0.61.6-0 -ecl_containers: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_containers/0.61.17-0 -ecl_converters: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_converters/0.61.17-0 -ecl_converters_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_converters_lite/0.61.6-0 -ecl_core: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_core/0.61.17-0 -ecl_core_apps: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_core_apps/0.61.17-0 -ecl_devices: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_devices/0.61.17-0 -ecl_eigen: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_eigen/0.61.17-0 -ecl_errors: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_errors/0.61.6-0 -ecl_exceptions: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_exceptions/0.61.17-0 -ecl_filesystem: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_filesystem/0.61.17-0 -ecl_formatters: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_formatters/0.61.17-0 -ecl_geometry: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_geometry/0.61.17-0 -ecl_io: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_io/0.61.6-0 -ecl_ipc: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_ipc/0.61.17-0 -ecl_license: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/kinetic/ecl_license/0.61.6-0 -ecl_linear_algebra: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_linear_algebra/0.61.17-0 -ecl_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_lite/0.61.6-0 -ecl_manipulation: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/kinetic/ecl_manipulation/0.60.1-1 -ecl_manipulators: - url: https://github.com/yujinrobot-release/ecl_manipulation-release.git - vcs: git - version: release/kinetic/ecl_manipulators/0.60.1-1 -ecl_math: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_math/0.61.17-0 -ecl_mobile_robot: - url: https://github.com/yujinrobot-release/ecl_navigation-release.git - vcs: git - version: release/kinetic/ecl_mobile_robot/0.60.3-0 -ecl_mpl: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_mpl/0.61.17-0 -ecl_navigation: - url: https://github.com/yujinrobot-release/ecl_navigation-release.git - vcs: git - version: release/kinetic/ecl_navigation/0.60.3-0 -ecl_sigslots: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_sigslots/0.61.17-0 -ecl_sigslots_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_sigslots_lite/0.61.6-0 -ecl_statistics: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_statistics/0.61.17-0 -ecl_streams: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_streams/0.61.17-0 -ecl_threads: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_threads/0.61.17-0 -ecl_time: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_time/0.61.17-0 -ecl_time_lite: - url: https://github.com/yujinrobot-release/ecl_lite-release.git - vcs: git - version: release/kinetic/ecl_time_lite/0.61.6-0 -ecl_tools: - url: https://github.com/yujinrobot-release/ecl_tools-release.git - vcs: git - version: release/kinetic/ecl_tools/0.61.6-0 -ecl_type_traits: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_type_traits/0.61.17-0 -ecl_utilities: - url: https://github.com/yujinrobot-release/ecl_core-release.git - vcs: git - version: release/kinetic/ecl_utilities/0.61.17-0 -ecto: - url: https://github.com/ros-gbp/ecto-release.git - vcs: git - version: release/kinetic/ecto/0.6.12-0 -ecto_image_pipeline: - url: https://github.com/ros-gbp/ecto_image_pipeline-release.git - vcs: git - version: release/kinetic/ecto_image_pipeline/0.5.7-0 -ecto_opencv: - url: https://github.com/ros-gbp/ecto_opencv-release.git - vcs: git - version: release/kinetic/ecto_opencv/0.7.2-0 -ecto_openni: - url: https://github.com/ros-gbp/ecto_openni-release.git - vcs: git - version: release/kinetic/ecto_openni/0.4.0-0 -ecto_pcl: - url: https://github.com/ros-gbp/ecto_pcl-release.git - vcs: git - version: release/kinetic/ecto_pcl/0.4.5-0 -ecto_ros: - url: https://github.com/ros-gbp/ecto_ros-release.git - vcs: git - version: release/kinetic/ecto_ros/0.4.8-0 -effort_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/effort_controllers/0.13.5-0 -eigen_typekit: - url: https://github.com/orocos-gbp/rtt_geometry-release.git - vcs: git - version: release/kinetic/eigen_typekit/2.9.3-1 -eigenpy: - url: https://github.com/ipab-slmc/eigenpy_catkin-release.git - vcs: git - version: release/kinetic/eigenpy/1.5.1-1 -eml: - url: https://github.com/ros-gbp/eml-release.git - vcs: git - version: release/kinetic/eml/1.8.15-6 -epos2_motor_controller: - url: https://github.com/uos-gbp/epos2_motor_controller-release.git - vcs: git - version: release/kinetic/epos2_motor_controller/1.0.1-1 -epson_imu_driver: - url: https://bitbucket.org/castacks/epson_g364_imu_driver-release.git - vcs: git - version: release/kinetic/epson_imu_driver/0.0.2-0 -ethercat_grant: - url: https://github.com/shadow-robot/ethercat_grant-release.git - vcs: git - version: release/kinetic/ethercat_grant/0.2.1-0 -ethercat_hardware: - url: https://github.com/PR2-prime/pr2_ethercat_drivers-release.git - vcs: git - version: release/kinetic/ethercat_hardware/1.8.18-1 -ethercat_manager: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/ethercat_manager/1.0.10-0 -ethercat_trigger_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/ethercat_trigger_controllers/1.10.14-0 -eus_assimp: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/kinetic/eus_assimp/0.4.2-0 -eus_nlopt: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/eus_nlopt/0.1.14-0 -eus_qp: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/eus_qp/0.1.14-0 -eus_qpoases: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/eus_qpoases/0.1.14-0 -euscollada: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/kinetic/euscollada/0.4.2-0 -euslisp: - url: https://github.com/tork-a/euslisp-release.git - vcs: git - version: release/kinetic/euslisp/9.26.0-1 -eusurdf: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/kinetic/eusurdf/0.4.2-0 -executive_smach_visualization: - url: https://github.com/jbohren/executive_smach_visualization-release.git - vcs: git - version: release/kinetic/executive_smach_visualization/2.0.2-0 -exotica: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica/5.0.0-0 -exotica_aico_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_aico_solver/5.0.0-0 -exotica_collision_scene_fcl: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_collision_scene_fcl/5.0.0-0 -exotica_collision_scene_fcl_latest: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_collision_scene_fcl_latest/5.0.0-0 -exotica_core: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_core/5.0.0-0 -exotica_core_task_maps: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_core_task_maps/5.0.0-0 -exotica_examples: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_examples/5.0.0-0 -exotica_ik_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_ik_solver/5.0.0-0 -exotica_levenberg_marquardt_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_levenberg_marquardt_solver/5.0.0-0 -exotica_ompl_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_ompl_solver/5.0.0-0 -exotica_python: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_python/5.0.0-0 -exotica_time_indexed_rrt_connect_solver: - url: https://github.com/ipab-slmc/exotica-release.git - vcs: git - version: release/kinetic/exotica_time_indexed_rrt_connect_solver/5.0.0-0 -exotica_val_description: - url: https://github.com/wxmerkt/exotica_val_description-release.git - vcs: git - version: release/kinetic/exotica_val_description/1.0.0-2 -explore_lite: - url: https://github.com/hrnr/m-explore-release.git - vcs: git - version: release/kinetic/explore_lite/2.1.1-0 -ez_interactive_marker: - url: https://github.com/neka-nat/ez_interactive_marker-release.git - vcs: git - version: release/kinetic/ez_interactive_marker/0.0.2-0 -face_detector: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/face_detector/1.1.3-1 -fake_joint: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/kinetic/fake_joint/0.0.2-1 -fake_joint_driver: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/kinetic/fake_joint_driver/0.0.2-1 -fake_joint_launch: - url: https://github.com/tork-a/fake_joint-release.git - vcs: git - version: release/kinetic/fake_joint_launch/0.0.2-1 -fake_localization: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/fake_localization/1.14.4-0 -fcl_catkin: - url: https://github.com/wxmerkt/fcl_catkin-release.git - vcs: git - version: release/kinetic/fcl_catkin/0.5.98-1 -feed_the_troll: - url: https://github.com/stonier/feed_the_troll-release.git - vcs: git - version: release/kinetic/feed_the_troll/0.1.1-0 -feed_the_troll_msgs: - url: https://github.com/stonier/feed_the_troll_msgs-release.git - vcs: git - version: release/kinetic/feed_the_troll_msgs/0.1.1-0 -fetch_calibration: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_calibration/0.7.15-0 -fetch_depth_layer: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_depth_layer/0.7.15-0 -fetch_description: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_description/0.7.15-0 -fetch_gazebo: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/kinetic/fetch_gazebo/0.8.2-0 -fetch_gazebo_demo: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/kinetic/fetch_gazebo_demo/0.8.2-0 -fetch_ikfast_plugin: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_ikfast_plugin/0.7.15-0 -fetch_maps: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_maps/0.7.15-0 -fetch_moveit_config: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_moveit_config/0.7.15-0 -fetch_navigation: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_navigation/0.7.15-0 -fetch_ros: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_ros/0.7.15-0 -fetch_simulation: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/kinetic/fetch_simulation/0.8.2-0 -fetch_teleop: - url: https://github.com/fetchrobotics-gbp/fetch_ros-release.git - vcs: git - version: release/kinetic/fetch_teleop/0.7.15-0 -fetchit_challenge: - url: https://github.com/fetchrobotics-gbp/fetch_gazebo-release.git - vcs: git - version: release/kinetic/fetchit_challenge/0.8.2-0 -ff: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/ff/2.1.13-1 -ffha: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/ffha/2.1.13-1 -fiducial_msgs: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/kinetic/fiducial_msgs/0.11.0-1 -fiducial_slam: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/kinetic/fiducial_slam/0.11.0-1 -fiducials: - url: https://github.com/UbiquityRobotics-release/fiducials-release.git - vcs: git - version: release/kinetic/fiducials/0.11.0-1 -file_management: - url: https://github.com/aws-gbp/cloudwatch_common-release.git - vcs: git - version: release/kinetic/file_management/1.1.0-2 -find_object_2d: - url: https://github.com/introlab/find_object_2d-release.git - vcs: git - version: release/kinetic/find_object_2d/0.6.2-0 -fingertip_pressure: - url: https://github.com/PR2-prime/pr2_ethercat_drivers-release.git - vcs: git - version: release/kinetic/fingertip_pressure/1.8.18-1 -fkie_potree_rviz_plugin: - url: https://github.com/fkie-release/potree_rviz_plugin-release.git - vcs: git - version: release/kinetic/fkie_potree_rviz_plugin/1.0.0-0 -flask_cors: - url: https://github.com/pyros-dev/flask-cors-rosrelease.git - vcs: git - version: release/kinetic/flask_cors/3.0.3-2 -flask_reverse_proxy: - url: https://github.com/pyros-dev/flask-reverse-proxy-rosrelease.git - vcs: git - version: release/kinetic/flask_reverse_proxy/0.2.0-0 -flatbuffers: - url: https://github.com/yujinrobot-release/flatbuffers-release.git - vcs: git - version: release/kinetic/flatbuffers/1.1.0-0 -flexbe_behavior_engine: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_behavior_engine/1.2.1-1 -flexbe_core: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_core/1.2.1-1 -flexbe_input: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_input/1.2.1-1 -flexbe_mirror: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_mirror/1.2.1-1 -flexbe_msgs: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_msgs/1.2.1-1 -flexbe_onboard: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_onboard/1.2.1-1 -flexbe_states: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_states/1.2.1-1 -flexbe_testing: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_testing/1.2.1-1 -flexbe_widget: - url: https://github.com/FlexBE/flexbe_behavior_engine-release.git - vcs: git - version: release/kinetic/flexbe_widget/1.2.1-1 -flir_boson_usb: - url: https://github.com/astuff/flir_boson_usb-release.git - vcs: git - version: release/kinetic/flir_boson_usb/1.2.1-1 -flir_camera_driver: - url: https://github.com/ros-drivers-gbp/flir_camera_driver-release.git - vcs: git - version: release/kinetic/flir_camera_driver/0.1.3-0 -flir_ptu_description: - url: https://github.com/ros-drivers-gbp/flir_ptu-release.git - vcs: git - version: release/kinetic/flir_ptu_description/0.2.0-0 -flir_ptu_driver: - url: https://github.com/ros-drivers-gbp/flir_ptu-release.git - vcs: git - version: release/kinetic/flir_ptu_driver/0.2.0-0 -flir_ptu_viz: - url: https://github.com/ros-drivers-gbp/flir_ptu-release.git - vcs: git - version: release/kinetic/flir_ptu_viz/0.2.0-0 -follow_waypoints: - url: https://github.com/danielsnider/follow_waypoints-release.git - vcs: git - version: release/kinetic/follow_waypoints/0.3.0-2 -footstep_planner: - url: https://github.com/ROBOTIS-GIT-release/humanoid_navigation-release.git - vcs: git - version: release/kinetic/footstep_planner/0.4.2-0 -force_torque_sensor: - url: https://github.com/KITrobotics/force_torque_sensor-release.git - vcs: git - version: release/kinetic/force_torque_sensor/0.8.1-1 -force_torque_sensor_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/force_torque_sensor_controller/0.13.5-0 -forward_command_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/forward_command_controller/0.13.5-0 -four_wheel_steering_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/four_wheel_steering_controller/0.13.5-0 -four_wheel_steering_msgs: - url: https://github.com/ros-drivers-gbp/four_wheel_steering_msgs-release.git - vcs: git - version: release/kinetic/four_wheel_steering_msgs/1.0.0-0 -frame_editor: - url: https://github.com/ipa320/rqt_frame_editor_plugin-release.git - vcs: git - version: release/kinetic/frame_editor/1.0.4-0 -franka_control: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_control/0.6.0-1 -franka_description: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_description/0.6.0-1 -franka_example_controllers: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_example_controllers/0.6.0-1 -franka_gripper: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_gripper/0.6.0-1 -franka_hw: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_hw/0.6.0-1 -franka_msgs: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_msgs/0.6.0-1 -franka_ros: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_ros/0.6.0-1 -franka_visualization: - url: https://github.com/frankaemika/franka_ros-release.git - vcs: git - version: release/kinetic/franka_visualization/0.6.0-1 -freenect_camera: - url: https://github.com/ros-drivers-gbp/freenect_stack-release.git - vcs: git - version: release/kinetic/freenect_camera/0.4.2-0 -freenect_launch: - url: https://github.com/ros-drivers-gbp/freenect_stack-release.git - vcs: git - version: release/kinetic/freenect_launch/0.4.2-0 -freenect_stack: - url: https://github.com/ros-drivers-gbp/freenect_stack-release.git - vcs: git - version: release/kinetic/freenect_stack/0.4.2-0 -frontier_exploration: - url: https://github.com/paulbovbel/frontier_exploration-release.git - vcs: git - version: release/kinetic/frontier_exploration/0.3.1-0 -ftm_msgs: - url: https://github.com/guykhazma/ftm_msgs-release.git - vcs: git - version: release/kinetic/ftm_msgs/1.0.0-0 -futaba_serial_servo: - url: https://github.com/raspberrypigibbon/raspigibbon_ros-release.git - vcs: git - version: release/kinetic/futaba_serial_servo/0.2.1-0 -fzi_icl_can: - url: https://github.com/fzi-forschungszentrum-informatik/fzi_icl_can-release.git - vcs: git - version: release/kinetic/fzi_icl_can/1.0.11-0 -fzi_icl_comm: - url: https://github.com/fzi-forschungszentrum-informatik/fzi_icl_comm-release.git - vcs: git - version: release/kinetic/fzi_icl_comm/0.0.2-0 -fzi_icl_core: - url: https://github.com/fzi-forschungszentrum-informatik/fzi_icl_core-release.git - vcs: git - version: release/kinetic/fzi_icl_core/1.0.6-0 -gateway_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/gateway_msgs/0.9.0-1 -gazebo_ros_control: - url: https://github.com/ros-gbp/gazebo_ros_pkgs-release.git - vcs: git - version: release/kinetic/gazebo_ros_control/2.5.19-1 -gcloud_speech: - url: https://github.com/CogRobRelease/gcloud_speech-release.git - vcs: git - version: release/kinetic/gcloud_speech/0.0.5-0 -gcloud_speech_msgs: - url: https://github.com/CogRobRelease/gcloud_speech-release.git - vcs: git - version: release/kinetic/gcloud_speech_msgs/0.0.5-0 -gcloud_speech_utils: - url: https://github.com/CogRobRelease/gcloud_speech-release.git - vcs: git - version: release/kinetic/gcloud_speech_utils/0.0.5-0 -generic_throttle: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/generic_throttle/0.6.14-1 -genrs: - url: https://github.com/adnanademovic/genrs-release.git - vcs: git - version: release/kinetic/genrs/0.1.0-1 -geographic_info: - url: https://github.com/ros-geographic-info/geographic_info-release.git - vcs: git - version: release/kinetic/geographic_info/0.5.2-0 -geometry2: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/kinetic/geometry2/0.5.20-0 -glkh_solver: - url: https://github.com/crigroup/lkh-release.git - vcs: git - version: release/kinetic/glkh_solver/0.1.1-0 -global_planner: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/global_planner/1.14.4-0 -global_planner_tests: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/global_planner_tests/0.2.5-0 -gmapping: - url: https://github.com/ros-gbp/slam_gmapping-release.git - vcs: git - version: release/kinetic/gmapping/1.3.10-0 -gmplot: - url: https://github.com/robustify/gmplot_ros-release.git - vcs: git - version: release/kinetic/gmplot/1.0.1-0 -gmplot_msgs: - url: https://github.com/robustify/gmplot_ros-release.git - vcs: git - version: release/kinetic/gmplot_msgs/1.0.1-0 -gmplot_ros: - url: https://github.com/robustify/gmplot_ros-release.git - vcs: git - version: release/kinetic/gmplot_ros/1.0.1-0 -goal_passer: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/goal_passer/0.2.1-0 -gps_common: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/kinetic/gps_common/0.2.0-0 -gps_goal: - url: https://github.com/danielsnider/gps_goal-release.git - vcs: git - version: release/kinetic/gps_goal/0.1.0-0 -gps_umd: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/kinetic/gps_umd/0.2.0-0 -gpsd_client: - url: https://github.com/swri-robotics-gbp/gps_umd-release.git - vcs: git - version: release/kinetic/gpsd_client/0.2.0-0 -grasping_msgs: - url: https://github.com/mikeferguson/grasping_msgs-gbp.git - vcs: git - version: release/kinetic/grasping_msgs/0.3.1-0 -grid_map: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map/1.6.1-0 -grid_map_core: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_core/1.6.1-0 -grid_map_costmap_2d: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_costmap_2d/1.6.1-0 -grid_map_cv: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_cv/1.6.1-0 -grid_map_demos: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_demos/1.6.1-0 -grid_map_filters: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_filters/1.6.1-0 -grid_map_loader: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_loader/1.6.1-0 -grid_map_msgs: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_msgs/1.6.1-0 -grid_map_octomap: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_octomap/1.6.1-0 -grid_map_pcl: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_pcl/1.6.1-0 -grid_map_ros: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_ros/1.6.1-0 -grid_map_rviz_plugin: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_rviz_plugin/1.6.1-0 -grid_map_sdf: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_sdf/1.6.1-0 -grid_map_visualization: - url: https://github.com/anybotics/grid_map-release.git - vcs: git - version: release/kinetic/grid_map_visualization/1.6.1-0 -gridmap_2d: - url: https://github.com/ROBOTIS-GIT-release/humanoid_navigation-release.git - vcs: git - version: release/kinetic/gridmap_2d/0.4.2-0 -gripit: - url: https://github.com/Yannick-Oderri/gripit-release.git - vcs: git - version: release/kinetic/gripit/0.0.3-0 -gripper_action_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/gripper_action_controller/0.13.5-0 -grizzly_control: - url: https://github.com/clearpath-gbp/grizzly-release.git - vcs: git - version: release/kinetic/grizzly_control/0.4.2-0 -grizzly_description: - url: https://github.com/clearpath-gbp/grizzly-release.git - vcs: git - version: release/kinetic/grizzly_description/0.4.2-0 -grizzly_desktop: - url: https://github.com/clearpath-gbp/grizzly_desktop-release.git - vcs: git - version: release/kinetic/grizzly_desktop/0.3.2-0 -grizzly_gazebo: - url: https://github.com/clearpath-gbp/grizzly_simulator-release.git - vcs: git - version: release/kinetic/grizzly_gazebo/0.3.1-0 -grizzly_msgs: - url: https://github.com/clearpath-gbp/grizzly-release.git - vcs: git - version: release/kinetic/grizzly_msgs/0.4.2-0 -grizzly_navigation: - url: https://github.com/clearpath-gbp/grizzly-release.git - vcs: git - version: release/kinetic/grizzly_navigation/0.4.2-0 -grizzly_simulator: - url: https://github.com/clearpath-gbp/grizzly_simulator-release.git - vcs: git - version: release/kinetic/grizzly_simulator/0.3.1-0 -grizzly_viz: - url: https://github.com/clearpath-gbp/grizzly_desktop-release.git - vcs: git - version: release/kinetic/grizzly_viz/0.3.2-0 -grpc: - url: https://github.com/CogRobRelease/catkin_grpc-release.git - vcs: git - version: release/kinetic/grpc/0.0.10-0 -gscam: - url: https://github.com/ros-drivers-gbp/gscam-release.git - vcs: git - version: release/kinetic/gscam/0.2.0-0 -gx_sound: - url: https://github.com/groove-x/gx_sound-release.git - vcs: git - version: release/kinetic/gx_sound/0.2.2-0 -gx_sound_msgs: - url: https://github.com/groove-x/gx_sound-release.git - vcs: git - version: release/kinetic/gx_sound_msgs/0.2.2-0 -gx_sound_player: - url: https://github.com/groove-x/gx_sound-release.git - vcs: git - version: release/kinetic/gx_sound_player/0.2.2-0 -h264_encoder_core: - url: https://github.com/aws-gbp/h264_encoder_core-release.git - vcs: git - version: release/kinetic/h264_encoder_core/2.0.1-1 -h264_video_encoder: - url: https://github.com/aws-gbp/h264_video_encoder-release.git - vcs: git - version: release/kinetic/h264_video_encoder/1.1.3-1 -handeye: - url: https://github.com/crigroup/handeye-release.git - vcs: git - version: release/kinetic/handeye/0.1.1-0 -handle_detector: - url: https://github.com/atenpas/handle_detector-release.git - vcs: git - version: release/kinetic/handle_detector/1.3.1-0 -hardware_interface: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/hardware_interface/0.13.3-0 -health_metric_collector: - url: https://github.com/aws-gbp/health_metric_collector-release.git - vcs: git - version: release/kinetic/health_metric_collector/2.0.1-1 -hebi_cpp_api: - url: https://github.com/HebiRobotics/hebi_cpp_api_ros-release.git - vcs: git - version: release/kinetic/hebi_cpp_api/2.1.0-1 -hebiros_description: - url: https://github.com/HebiRobotics/hebiros-release.git - vcs: git - version: release/kinetic/hebiros_description/0.0.4-1 -hector_components_description: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/kinetic/hector_components_description/0.4.2-0 -hector_compressed_map_transport: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_compressed_map_transport/0.3.5-0 -hector_gazebo: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/kinetic/hector_gazebo/0.5.0-0 -hector_gazebo_plugins: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/kinetic/hector_gazebo_plugins/0.5.0-0 -hector_gazebo_thermal_camera: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/kinetic/hector_gazebo_thermal_camera/0.5.0-0 -hector_gazebo_worlds: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/kinetic/hector_gazebo_worlds/0.5.0-0 -hector_geotiff: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_geotiff/0.3.5-0 -hector_geotiff_plugins: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_geotiff_plugins/0.3.5-0 -hector_imu_attitude_to_tf: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_imu_attitude_to_tf/0.3.5-0 -hector_imu_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_imu_tools/0.3.5-0 -hector_localization: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_localization-release.git - vcs: git - version: release/kinetic/hector_localization/0.3.0-0 -hector_map_server: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_map_server/0.3.5-0 -hector_map_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_map_tools/0.3.5-0 -hector_mapping: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_mapping/0.3.5-0 -hector_marker_drawing: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_marker_drawing/0.3.5-0 -hector_models: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/kinetic/hector_models/0.4.2-0 -hector_nav_msgs: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_nav_msgs/0.3.5-0 -hector_object_tracker: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_worldmodel-release.git - vcs: git - version: release/kinetic/hector_object_tracker/0.3.4-0 -hector_pose_estimation: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_localization-release.git - vcs: git - version: release/kinetic/hector_pose_estimation/0.3.0-0 -hector_pose_estimation_core: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_localization-release.git - vcs: git - version: release/kinetic/hector_pose_estimation_core/0.3.0-0 -hector_sensors_description: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/kinetic/hector_sensors_description/0.4.2-0 -hector_sensors_gazebo: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_gazebo-release.git - vcs: git - version: release/kinetic/hector_sensors_gazebo/0.5.0-0 -hector_slam: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_slam/0.3.5-0 -hector_slam_launch: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_slam_launch/0.3.5-0 -hector_trajectory_server: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_slam-release.git - vcs: git - version: release/kinetic/hector_trajectory_server/0.3.5-0 -hector_worldmodel: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_worldmodel-release.git - vcs: git - version: release/kinetic/hector_worldmodel/0.3.4-0 -hector_worldmodel_geotiff_plugins: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_worldmodel-release.git - vcs: git - version: release/kinetic/hector_worldmodel_geotiff_plugins/0.3.4-0 -hector_worldmodel_msgs: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_worldmodel-release.git - vcs: git - version: release/kinetic/hector_worldmodel_msgs/0.3.4-0 -hector_xacro_tools: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_models-release.git - vcs: git - version: release/kinetic/hector_xacro_tools/0.4.2-0 -heron_control: - url: https://github.com/clearpath-gbp/heron-release.git - vcs: git - version: release/kinetic/heron_control/0.3.1-0 -heron_description: - url: https://github.com/clearpath-gbp/heron-release.git - vcs: git - version: release/kinetic/heron_description/0.3.1-0 -heron_desktop: - url: https://github.com/clearpath-gbp/heron_desktop-release.git - vcs: git - version: release/kinetic/heron_desktop/0.0.3-0 -heron_msgs: - url: https://github.com/clearpath-gbp/heron-release.git - vcs: git - version: release/kinetic/heron_msgs/0.3.1-0 -heron_viz: - url: https://github.com/clearpath-gbp/heron_desktop-release.git - vcs: git - version: release/kinetic/heron_viz/0.0.3-0 -hironx_calibration: - url: https://github.com/tork-a/rtmros_hironx-release.git - vcs: git - version: release/kinetic/hironx_calibration/2.1.1-0 -hironx_moveit_config: - url: https://github.com/tork-a/rtmros_hironx-release.git - vcs: git - version: release/kinetic/hironx_moveit_config/2.1.1-0 -hironx_ros_bridge: - url: https://github.com/tork-a/rtmros_hironx-release.git - vcs: git - version: release/kinetic/hironx_ros_bridge/2.1.1-0 -hls_lfcd_lds_driver: - url: https://github.com/ROBOTIS-GIT-release/hls-lfcd-lds-driver-release.git - vcs: git - version: release/kinetic/hls_lfcd_lds_driver/1.1.0-0 -hokuyo3d: - url: https://github.com/at-wat/hokuyo3d-release.git - vcs: git - version: release/kinetic/hokuyo3d/0.2.0-0 -homer_map_manager: - url: https://gitlab.uni-koblenz.de/robbie/homer_map_manager-release.git - vcs: git - version: release/kinetic/homer_map_manager/0.1.54-0 -homer_mapnav_msgs: - url: https://gitlab.uni-koblenz.de/robbie/homer_mapnav_msgs-release.git - vcs: git - version: release/kinetic/homer_mapnav_msgs/0.1.53-0 -homer_mapping: - url: https://gitlab.uni-koblenz.de/robbie/homer_mapping-release.git - vcs: git - version: release/kinetic/homer_mapping/0.1.53-0 -homer_mary_tts: - url: https://gitlab.uni-koblenz.de/robbie/homer_robot_face-release.git - vcs: git - version: release/kinetic/homer_mary_tts/1.0.18-1 -homer_msgs: - url: https://gitlab.uni-koblenz.de/robbie/homer_msgs-release.git - vcs: git - version: release/kinetic/homer_msgs/0.1.6-1 -homer_nav_libs: - url: https://gitlab.uni-koblenz.de/robbie/homer_nav_libs-release.git - vcs: git - version: release/kinetic/homer_nav_libs/0.1.53-0 -homer_navigation: - url: https://gitlab.uni-koblenz.de/robbie/homer_navigation-release.git - vcs: git - version: release/kinetic/homer_navigation/0.1.53-0 -homer_ptu_msgs: - url: https://gitlab.uni-koblenz.de/robbie/homer_ptu_msgs-release.git - vcs: git - version: release/kinetic/homer_ptu_msgs/0.1.7-2 -homer_robbie_architecture: - url: https://gitlab.uni-koblenz.de/robbie/homer_robbie_architecture.git - vcs: git - version: release/kinetic/homer_robbie_architecture/1.0.2-3 -homer_robot_face: - url: https://gitlab.uni-koblenz.de/robbie/homer_robot_face-release.git - vcs: git - version: release/kinetic/homer_robot_face/1.0.18-1 -homer_tts: - url: https://gitlab.uni-koblenz.de/robbie/homer_tts-release.git - vcs: git - version: release/kinetic/homer_tts/1.0.29-0 -hostapd_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/hostapd_access_point/1.0.15-0 -household_objects_database_msgs: - url: https://github.com/ros-gbp/household_objects_database_msgs-release.git - vcs: git - version: release/kinetic/household_objects_database_msgs/0.1.2-0 -hpp-fcl: - url: https://github.com/ipab-slmc/hpp-fcl_catkin-release.git - vcs: git - version: release/kinetic/hpp-fcl/1.0.1-1 -hrpsys: - url: https://github.com/tork-a/hrpsys-release.git - vcs: git - version: release/kinetic/hrpsys/315.14.0-0 -hrpsys_ros_bridge: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/hrpsys_ros_bridge/1.4.2-0 -hrpsys_tools: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/hrpsys_tools/1.4.2-0 -hsr_description: - url: https://github.com/ToyotaResearchInstitute/hsr_description-release.git - vcs: git - version: release/kinetic/hsr_description/1.1.0-0 -hsr_meshes: - url: https://github.com/ToyotaResearchInstitute/hsr_meshes-release.git - vcs: git - version: release/kinetic/hsr_meshes/1.1.0-0 -hugin_panorama: - url: https://github.com/danielsnider/hugin_panorama-release.git - vcs: git - version: release/kinetic/hugin_panorama/0.1.0-0 -humanoid_localization: - url: https://github.com/ROBOTIS-GIT-release/humanoid_navigation-release.git - vcs: git - version: release/kinetic/humanoid_localization/0.4.2-0 -humanoid_msgs: - url: https://github.com/ros-gbp/humanoid_msgs-release.git - vcs: git - version: release/kinetic/humanoid_msgs/0.3.0-0 -humanoid_nav_msgs: - url: https://github.com/ros-gbp/humanoid_msgs-release.git - vcs: git - version: release/kinetic/humanoid_nav_msgs/0.3.0-0 -humanoid_navigation: - url: https://github.com/ROBOTIS-GIT-release/humanoid_navigation-release.git - vcs: git - version: release/kinetic/humanoid_navigation/0.4.2-0 -humanoid_planner_2d: - url: https://github.com/ROBOTIS-GIT-release/humanoid_navigation-release.git - vcs: git - version: release/kinetic/humanoid_planner_2d/0.4.2-0 -husky_base: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_base/0.3.4-1 -husky_bringup: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_bringup/0.3.4-1 -husky_control: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_control/0.3.4-1 -husky_description: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_description/0.3.4-1 -husky_desktop: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_desktop/0.3.4-1 -husky_gazebo: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_gazebo/0.3.4-1 -husky_msgs: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_msgs/0.3.4-1 -husky_navigation: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_navigation/0.3.4-1 -husky_robot: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_robot/0.3.4-1 -husky_simulator: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_simulator/0.3.4-1 -husky_viz: - url: https://github.com/clearpath-gbp/husky-release.git - vcs: git - version: release/kinetic/husky_viz/0.3.4-1 -ibeo_core: - url: https://github.com/astuff/ibeo_core-release.git - vcs: git - version: release/kinetic/ibeo_core/2.0.2-0 -ibeo_lux: - url: https://github.com/astuff/ibeo_lux-release.git - vcs: git - version: release/kinetic/ibeo_lux/2.0.1-0 -ibeo_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/ibeo_msgs/2.3.1-0 -ieee80211_channels: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/ieee80211_channels/1.0.15-0 -ifm_o3mxxx: - url: https://github.com/takiaine/ifm_o3mxxx-release.git - vcs: git - version: release/kinetic/ifm_o3mxxx/1.0.1-0 -ifopt: - url: https://github.com/ethz-adrl/ifopt-release.git - vcs: git - version: release/kinetic/ifopt/2.0.6-0 -igvc_self_drive_description: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/kinetic/igvc_self_drive_description/0.1.4-1 -igvc_self_drive_gazebo: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/kinetic/igvc_self_drive_gazebo/0.1.4-1 -igvc_self_drive_gazebo_plugins: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/kinetic/igvc_self_drive_gazebo_plugins/0.1.4-1 -igvc_self_drive_sim: - url: https://github.com/robustify/igvc_self_drive_sim-release.git - vcs: git - version: release/kinetic/igvc_self_drive_sim/0.1.4-1 -iirob_filters: - url: https://github.com/KITrobotics/iirob_filters-release.git - vcs: git - version: release/kinetic/iirob_filters/0.8.1-3 -image_cb_detector: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/image_cb_detector/0.10.14-0 -image_exposure_msgs: - url: https://github.com/ros-drivers-gbp/pointgrey_camera_driver-release.git - vcs: git - version: release/kinetic/image_exposure_msgs/0.13.4-0 -image_overlay_scale_and_compass: - url: https://github.com/danielsnider/image_overlay_scale_and_compass-release.git - vcs: git - version: release/kinetic/image_overlay_scale_and_compass/0.2.1-0 -image_recognition: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/image_recognition/0.0.4-0 -image_recognition_msgs: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/image_recognition_msgs/0.0.4-0 -image_recognition_rqt: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/image_recognition_rqt/0.0.4-0 -image_recognition_util: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/image_recognition_util/0.0.4-0 -image_stream: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/image_stream/1.0.7-0 -image_view2: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/image_view2/2.2.10-0 -imagesift: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/imagesift/1.2.9-0 -imagezero: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/kinetic/imagezero/0.2.4-0 -imagezero_image_transport: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/kinetic/imagezero_image_transport/0.2.4-0 -imagezero_ros: - url: https://github.com/swri-robotics-gbp/imagezero_transport-release.git - vcs: git - version: release/kinetic/imagezero_ros/0.2.4-0 -imu_compass: - url: https://github.com/clearpath-gbp/imu_compass-release.git - vcs: git - version: release/kinetic/imu_compass/0.0.5-0 -imu_complementary_filter: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/kinetic/imu_complementary_filter/1.1.7-1 -imu_filter_madgwick: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/kinetic/imu_filter_madgwick/1.1.7-1 -imu_monitor: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/imu_monitor/1.6.30-0 -imu_pipeline: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/kinetic/imu_pipeline/0.2.3-0 -imu_processors: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/kinetic/imu_processors/0.2.3-0 -imu_sensor_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/imu_sensor_controller/0.13.5-0 -imu_tools: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/kinetic/imu_tools/1.1.7-1 -imu_transformer: - url: https://github.com/ros-gbp/imu_pipeline-release.git - vcs: git - version: release/kinetic/imu_transformer/0.2.3-0 -indoor_localization: - url: https://github.com/inomuh/indoor_localization-release.git - vcs: git - version: release/kinetic/indoor_localization/0.1.0-1 -indoor_positioning: - url: https://github.com/metratec/indoor_positioning-release.git - vcs: git - version: release/kinetic/indoor_positioning/1.1.0-0 -industrial_core: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_core/0.7.0-0 -industrial_deprecated: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_deprecated/0.7.0-0 -industrial_msgs: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_msgs/0.7.0-0 -industrial_robot_client: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_robot_client/0.7.0-0 -industrial_robot_simulator: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_robot_simulator/0.7.0-0 -industrial_robot_status_controller: - url: https://github.com/gavanderhoorn/industrial_robot_status_controller-release.git - vcs: git - version: release/kinetic/industrial_robot_status_controller/0.1.2-1 -industrial_robot_status_interface: - url: https://github.com/gavanderhoorn/industrial_robot_status_controller-release.git - vcs: git - version: release/kinetic/industrial_robot_status_interface/0.1.2-1 -industrial_trajectory_filters: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_trajectory_filters/0.7.0-0 -industrial_utils: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/industrial_utils/0.7.0-0 -innok_heros_driver: - url: https://github.com/innokrobotics/innok_heros_driver-release.git - vcs: git - version: release/kinetic/innok_heros_driver/1.0.4-0 -interactive_marker_proxy: - url: https://github.com/RobotWebTools-release/interactive_marker_proxy-release.git - vcs: git - version: release/kinetic/interactive_marker_proxy/0.1.2-0 -interactive_marker_twist_server: - url: https://github.com/ros-gbp/interactive_marker_twist_server-release.git - vcs: git - version: release/kinetic/interactive_marker_twist_server/1.2.0-0 -interval_intersection: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/interval_intersection/0.10.14-0 -iot_bridge: - url: https://github.com/ros-gbp/iot_bridge-release.git - vcs: git - version: release/kinetic/iot_bridge/0.9.0-0 -ipa_3d_fov_visualization: - url: https://github.com/ipa320/cob_perception_common-release.git - vcs: git - version: release/kinetic/ipa_3d_fov_visualization/0.6.14-1 -ipcamera_driver: - url: https://github.com/alireza-hosseini/ipcamera_driver-release.git - vcs: git - version: release/kinetic/ipcamera_driver/0.1.1-1 -ipr_extern: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/kinetic/ipr_extern/0.8.8-0 -ira_laser_tools: - url: https://github.com/iralabdisco/ira_laser_tools-release.git - vcs: git - version: release/kinetic/ira_laser_tools/1.0.2-0 -ivcon: - url: https://github.com/ros-gbp/ivcon-release.git - vcs: git - version: release/kinetic/ivcon/0.1.6-0 -jackal_control: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/kinetic/jackal_control/0.6.2-0 -jackal_description: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/kinetic/jackal_description/0.6.2-0 -jackal_desktop: - url: https://github.com/clearpath-gbp/jackal_desktop-release.git - vcs: git - version: release/kinetic/jackal_desktop/0.3.2-0 -jackal_gazebo: - url: https://github.com/clearpath-gbp/jackal_simulator-release.git - vcs: git - version: release/kinetic/jackal_gazebo/0.3.0-0 -jackal_msgs: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/kinetic/jackal_msgs/0.6.2-0 -jackal_navigation: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/kinetic/jackal_navigation/0.6.2-0 -jackal_simulator: - url: https://github.com/clearpath-gbp/jackal_simulator-release.git - vcs: git - version: release/kinetic/jackal_simulator/0.3.0-0 -jackal_tutorials: - url: https://github.com/clearpath-gbp/jackal-release.git - vcs: git - version: release/kinetic/jackal_tutorials/0.6.2-0 -jackal_viz: - url: https://github.com/clearpath-gbp/jackal_desktop-release.git - vcs: git - version: release/kinetic/jackal_viz/0.3.2-0 -jaguar_control: - url: https://github.com/gstavrinos/jaguar-release.git - vcs: git - version: release/kinetic/jaguar_control/0.1.0-0 -jaguar_description: - url: https://github.com/gstavrinos/jaguar-release.git - vcs: git - version: release/kinetic/jaguar_description/0.1.0-0 -jaguar_msgs: - url: https://github.com/gstavrinos/jaguar-release.git - vcs: git - version: release/kinetic/jaguar_msgs/0.1.0-0 -jaguar_navigation: - url: https://github.com/gstavrinos/jaguar-release.git - vcs: git - version: release/kinetic/jaguar_navigation/0.1.0-0 -jderobot_assets: - url: https://github.com/JdeRobot/assets-release.git - vcs: git - version: release/kinetic/jderobot_assets/0.1.0-1 -jog_arm: - url: https://github.com/UTNuclearRoboticsPublic/jog_arm-release.git - vcs: git - version: release/kinetic/jog_arm/0.0.3-2 -jog_control: - url: https://github.com/tork-a/jog_control-release.git - vcs: git - version: release/kinetic/jog_control/0.0.1-0 -jog_controller: - url: https://github.com/tork-a/jog_control-release.git - vcs: git - version: release/kinetic/jog_controller/0.0.1-0 -jog_launch: - url: https://github.com/tork-a/jog_control-release.git - vcs: git - version: release/kinetic/jog_launch/0.0.1-0 -jog_msgs: - url: https://github.com/tork-a/jog_control-release.git - vcs: git - version: release/kinetic/jog_msgs/0.0.1-0 -joint_limits_interface: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/joint_limits_interface/0.13.3-0 -joint_qualification_controllers: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/joint_qualification_controllers/1.0.15-1 -joint_state_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/joint_state_controller/0.13.5-0 -joint_states_settler: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/joint_states_settler/0.10.14-0 -joint_trajectory_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/joint_trajectory_action/1.10.14-0 -joint_trajectory_action_tools: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/joint_trajectory_action_tools/0.0.10-0 -joint_trajectory_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/joint_trajectory_controller/0.13.5-0 -joint_trajectory_generator: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/joint_trajectory_generator/0.0.10-0 -jointstick: - url: https://github.com/gstavrinos/jointstick-release.git - vcs: git - version: release/kinetic/jointstick/0.9.1-1 -joy: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/kinetic/joy/1.13.0-1 -joy_listener: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/kinetic/joy_listener/0.2.4-0 -joy_mouse: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/joy_mouse/0.1.14-0 -joy_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/kinetic/joy_teleop/0.3.0-0 -joystick_drivers: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/kinetic/joystick_drivers/1.13.0-1 -joystick_interrupt: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/joystick_interrupt/0.4.2-1 -jpeg_streamer: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/kinetic/jpeg_streamer/0.2.5-0 -jsk_3rdparty: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/jsk_3rdparty/2.1.13-1 -jsk_calibration: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_calibration/0.1.14-0 -jsk_common: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_common/2.2.10-0 -jsk_common_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/jsk_common_msgs/4.3.1-0 -jsk_control: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_control/0.1.14-0 -jsk_data: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_data/2.2.10-0 -jsk_footstep_controller: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_footstep_controller/0.1.14-0 -jsk_footstep_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/jsk_footstep_msgs/4.3.1-0 -jsk_footstep_planner: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_footstep_planner/0.1.14-0 -jsk_gui_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/jsk_gui_msgs/4.3.1-0 -jsk_hark_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/jsk_hark_msgs/4.3.1-0 -jsk_ik_server: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_ik_server/0.1.14-0 -jsk_interactive: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_interactive/2.1.5-0 -jsk_interactive_marker: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_interactive_marker/2.1.5-0 -jsk_interactive_test: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_interactive_test/2.1.5-0 -jsk_model_tools: - url: https://github.com/tork-a/jsk_model_tools-release.git - vcs: git - version: release/kinetic/jsk_model_tools/0.4.2-0 -jsk_network_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_network_tools/2.2.10-0 -jsk_pcl_ros: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_pcl_ros/1.2.9-0 -jsk_pcl_ros_utils: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_pcl_ros_utils/1.2.9-0 -jsk_perception: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_perception/1.2.9-0 -jsk_planning: - url: https://github.com/tork-a/jsk_planning-release.git - vcs: git - version: release/kinetic/jsk_planning/0.1.10-0 -jsk_pr2eus: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/kinetic/jsk_pr2eus/0.3.14-0 -jsk_recognition: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_recognition/1.2.9-0 -jsk_recognition_msgs: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_recognition_msgs/1.2.9-0 -jsk_recognition_utils: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/jsk_recognition_utils/1.2.9-0 -jsk_roseus: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/kinetic/jsk_roseus/1.7.4-0 -jsk_rqt_plugins: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_rqt_plugins/2.1.5-0 -jsk_rviz_plugins: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_rviz_plugins/2.1.5-0 -jsk_teleop_joy: - url: https://github.com/tork-a/jsk_control-release.git - vcs: git - version: release/kinetic/jsk_teleop_joy/0.1.14-0 -jsk_tilt_laser: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_tilt_laser/2.2.10-0 -jsk_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_tools/2.2.10-0 -jsk_topic_tools: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/jsk_topic_tools/2.2.10-0 -jsk_visualization: - url: https://github.com/tork-a/jsk_visualization-release.git - vcs: git - version: release/kinetic/jsk_visualization/2.1.5-0 -jskeus: - url: https://github.com/tork-a/jskeus-release.git - vcs: git - version: release/kinetic/jskeus/1.2.1-1 -json_msgs: - url: https://github.com/locusrobotics/json_transport-release.git - vcs: git - version: release/kinetic/json_msgs/0.0.1-0 -json_transport: - url: https://github.com/locusrobotics/json_transport-release.git - vcs: git - version: release/kinetic/json_transport/0.0.1-0 -julius: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/julius/2.1.13-1 -julius_ros: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/julius_ros/2.1.13-1 -kalman_filter: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/kinetic/kalman_filter/0.2.4-0 -kartech_linear_actuator_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/kartech_linear_actuator_msgs/2.3.1-0 -katana: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana/1.1.2-0 -katana_arm_gazebo: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_arm_gazebo/1.1.2-0 -katana_description: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_description/1.1.2-0 -katana_driver: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_driver/1.1.2-0 -katana_gazebo_plugins: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_gazebo_plugins/1.1.2-0 -katana_moveit_ikfast_plugin: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_moveit_ikfast_plugin/1.1.2-0 -katana_msgs: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_msgs/1.1.2-0 -katana_teleop: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_teleop/1.1.2-0 -katana_tutorials: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/katana_tutorials/1.1.2-0 -kdl_parser_py: - url: https://github.com/ros-gbp/kdl_parser-release.git - vcs: git - version: release/kinetic/kdl_parser_py/1.12.11-0 -kdl_typekit: - url: https://github.com/orocos-gbp/rtt_geometry-release.git - vcs: git - version: release/kinetic/kdl_typekit/2.9.3-1 -key_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/kinetic/key_teleop/0.3.0-0 -khi_duaro_description: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_duaro_description/1.1.2-1 -khi_duaro_gazebo: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_duaro_gazebo/1.1.2-1 -khi_duaro_ikfast_plugin: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_duaro_ikfast_plugin/1.1.2-1 -khi_duaro_moveit_config: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_duaro_moveit_config/1.1.2-1 -khi_robot: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_robot/1.1.2-1 -khi_robot_bringup: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_robot_bringup/1.1.2-1 -khi_robot_control: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_robot_control/1.1.2-1 -khi_robot_msgs: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_robot_msgs/1.1.2-1 -khi_rs007l_moveit_config: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs007l_moveit_config/1.1.2-1 -khi_rs007n_moveit_config: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs007n_moveit_config/1.1.2-1 -khi_rs080n_moveit_config: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs080n_moveit_config/1.1.2-1 -khi_rs_description: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs_description/1.1.2-1 -khi_rs_gazebo: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs_gazebo/1.1.2-1 -khi_rs_ikfast_plugin: - url: https://github.com/Kawasaki-Robotics/khi_robot-release.git - vcs: git - version: release/kinetic/khi_rs_ikfast_plugin/1.1.2-1 -kinesis_manager: - url: https://github.com/aws-gbp/kinesis_manager-release.git - vcs: git - version: release/kinetic/kinesis_manager/2.0.1-1 -kinesis_video_msgs: - url: https://github.com/aws-gbp/kinesis_video_streamer-release.git - vcs: git - version: release/kinetic/kinesis_video_msgs/2.0.2-1 -kinesis_video_streamer: - url: https://github.com/aws-gbp/kinesis_video_streamer-release.git - vcs: git - version: release/kinetic/kinesis_video_streamer/2.0.2-1 -kni: - url: https://github.com/uos-gbp/katana_driver-release.git - vcs: git - version: release/kinetic/kni/1.1.2-0 -kobuki: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki/0.7.6-0 -kobuki_auto_docking: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_auto_docking/0.7.6-0 -kobuki_bumper2pc: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_bumper2pc/0.7.6-0 -kobuki_capabilities: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_capabilities/0.7.6-0 -kobuki_controller_tutorial: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_controller_tutorial/0.7.6-0 -kobuki_core: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/kinetic/kobuki_core/0.7.8-1 -kobuki_dashboard: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_dashboard/0.5.7-0 -kobuki_description: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_description/0.7.6-0 -kobuki_desktop: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_desktop/0.5.7-0 -kobuki_dock_drive: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/kinetic/kobuki_dock_drive/0.7.8-1 -kobuki_driver: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/kinetic/kobuki_driver/0.7.8-1 -kobuki_ftdi: - url: https://github.com/yujinrobot-release/kobuki_core-release.git - vcs: git - version: release/kinetic/kobuki_ftdi/0.7.8-1 -kobuki_gazebo: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_gazebo/0.5.7-0 -kobuki_gazebo_plugins: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_gazebo_plugins/0.5.7-0 -kobuki_keyop: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_keyop/0.7.6-0 -kobuki_msgs: - url: https://github.com/yujinrobot-release/kobuki_msgs-release.git - vcs: git - version: release/kinetic/kobuki_msgs/0.7.0-0 -kobuki_node: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_node/0.7.6-0 -kobuki_qtestsuite: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_qtestsuite/0.5.7-0 -kobuki_random_walker: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_random_walker/0.7.6-0 -kobuki_rapps: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_rapps/0.7.6-0 -kobuki_rviz_launchers: - url: https://github.com/yujinrobot-release/kobuki_desktop-release.git - vcs: git - version: release/kinetic/kobuki_rviz_launchers/0.5.7-0 -kobuki_safety_controller: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_safety_controller/0.7.6-0 -kobuki_soft: - url: https://github.com/yujinrobot-release/kobuki_soft-release.git - vcs: git - version: release/kinetic/kobuki_soft/0.1.3-0 -kobuki_softapps: - url: https://github.com/yujinrobot-release/kobuki_soft-release.git - vcs: git - version: release/kinetic/kobuki_softapps/0.1.3-0 -kobuki_softnode: - url: https://github.com/yujinrobot-release/kobuki_soft-release.git - vcs: git - version: release/kinetic/kobuki_softnode/0.1.3-0 -kobuki_testsuite: - url: https://github.com/yujinrobot-release/kobuki-release.git - vcs: git - version: release/kinetic/kobuki_testsuite/0.7.6-0 -korg_nanokontrol: - url: https://github.com/ros-gbp/korg_nanokontrol-release.git - vcs: git - version: release/kinetic/korg_nanokontrol/0.1.2-0 -ksql_airport: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/kinetic/ksql_airport/0.0.1-1 -kvh: - url: https://github.com/ros-drivers-gbp/kvh_drivers-release.git - vcs: git - version: release/kinetic/kvh/1.0.3-0 -laptop_battery_monitor: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/kinetic/laptop_battery_monitor/0.2.0-0 -laser_cb_detector: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/laser_cb_detector/0.10.14-0 -laser_filtering: - url: https://github.com/wu-robotics/laser_filtering_release.git - vcs: git - version: release/kinetic/laser_filtering/0.0.4-0 -laser_filters_jsk_patch: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/laser_filters_jsk_patch/2.1.13-1 -laser_joint_processor: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/laser_joint_processor/1.0.11-0 -laser_joint_projector: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/laser_joint_projector/1.0.11-0 -laser_ortho_projector: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/laser_ortho_projector/0.3.2-0 -laser_proc: - url: https://github.com/ros-gbp/laser_proc-release.git - vcs: git - version: release/kinetic/laser_proc/0.1.4-0 -laser_scan_densifier: - url: https://github.com/ipa320/cob_driver-release.git - vcs: git - version: release/kinetic/laser_scan_densifier/0.7.0-1 -laser_scan_matcher: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/laser_scan_matcher/0.3.2-0 -laser_scan_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/laser_scan_publisher_tutorial/0.2.3-0 -laser_scan_sparsifier: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/laser_scan_sparsifier/0.3.2-0 -laser_scan_splitter: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/laser_scan_splitter/0.3.2-0 -laser_tilt_controller_filter: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/laser_tilt_controller_filter/0.1.28-0 -launch_tools: - url: https://github.com/srv/srv_tools-release.git - vcs: git - version: release/kinetic/launch_tools/0.0.3-0 -launchman: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/launchman/1.0.7-0 -lauv_control: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/kinetic/lauv_control/0.1.6-0 -lauv_description: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/kinetic/lauv_description/0.1.6-0 -lauv_gazebo: - url: https://github.com/uuvsimulator/lauv_gazebo-release.git - vcs: git - version: release/kinetic/lauv_gazebo/0.1.6-0 -leap_motion: - url: https://github.com/ros-gbp/leap_motion-release.git - vcs: git - version: release/kinetic/leap_motion/0.0.11-0 -leg_detector: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/leg_detector/1.1.3-1 -lex_common_msgs: - url: https://github.com/aws-gbp/lex_node-release.git - vcs: git - version: release/kinetic/lex_common_msgs/2.0.1-1 -lex_node: - url: https://github.com/aws-gbp/lex_node-release.git - vcs: git - version: release/kinetic/lex_node/2.0.1-1 -lgsvl_msgs: - url: https://github.com/lgsvl/lgsvl_msgs-release.git - vcs: git - version: release/kinetic/lgsvl_msgs/0.0.1-0 -libcmt: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/libcmt/2.1.13-1 -libconcorde_tsp_solver: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libconcorde_tsp_solver/0.6.12-0 -libcreate: - url: https://github.com/AutonomyLab/libcreate-release.git - vcs: git - version: release/kinetic/libcreate/1.6.1-0 -libdlib: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libdlib/0.6.13-1 -libfranka: - url: https://github.com/frankaemika/libfranka-release.git - vcs: git - version: release/kinetic/libfranka/0.7.1-1 -libfreenect: - url: https://github.com/ros-drivers-gbp/libfreenect-ros-release.git - vcs: git - version: release/kinetic/libfreenect/0.5.1-0 -libg2o: - url: https://github.com/ros-gbp/libg2o-release.git - vcs: git - version: release/kinetic/libg2o/2016.4.24-0 -libmavconn: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/kinetic/libmavconn/0.32.1-1 -libmodbus: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/kinetic/libmodbus/0.8.8-0 -libmongocxx_ros: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/kinetic/libmongocxx_ros/0.4.5-1 -libmynteye: - url: https://github.com/harjeb/libmynteye-release.git - vcs: git - version: release/kinetic/libmynteye/0.1.3-0 -libntcan: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libntcan/0.6.13-1 -libpcan: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libpcan/0.6.13-1 -libphidget21: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/libphidget21/0.7.9-1 -libphidgets: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libphidgets/0.6.13-1 -libqsopt: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/libqsopt/0.6.12-0 -libqt_concurrent: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_concurrent/1.0.1-0 -libqt_core: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_core/1.0.1-0 -libqt_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_dev/1.0.1-0 -libqt_gui: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_gui/1.0.1-0 -libqt_network: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_network/1.0.1-0 -libqt_opengl: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_opengl/1.0.1-0 -libqt_opengl_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_opengl_dev/1.0.1-0 -libqt_svg_dev: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_svg_dev/1.0.1-0 -libqt_widgets: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/libqt_widgets/1.0.1-0 -librealsense: - url: https://github.com/intel-ros/librealsense-release.git - vcs: git - version: release/kinetic/librealsense/1.12.1-0 -librealsense2: - url: https://github.com/IntelRealSense/librealsense2-release.git - vcs: git - version: release/kinetic/librealsense2/2.25.2-1 -libreflexxestype2: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/kinetic/libreflexxestype2/0.8.8-0 -libsensors_monitor: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/kinetic/libsensors_monitor/0.2.0-0 -libsiftfast: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/libsiftfast/2.1.13-1 -libuvc: - url: https://github.com/ktossell/libuvc-release.git - vcs: git - version: release/kinetic/libuvc/0.0.6-1 -libuvc_camera: - url: https://github.com/ros-drivers-gbp/libuvc_ros-release.git - vcs: git - version: release/kinetic/libuvc_camera/0.0.10-0 -libuvc_ros: - url: https://github.com/ros-drivers-gbp/libuvc_ros-release.git - vcs: git - version: release/kinetic/libuvc_ros/0.0.10-0 -linksys_access_point: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/linksys_access_point/1.0.15-0 -linux_networking: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/linux_networking/1.0.15-0 -linux_peripheral_interfaces: - url: https://github.com/ros-gbp/linux_peripheral_interfaces-release.git - vcs: git - version: release/kinetic/linux_peripheral_interfaces/0.2.0-0 -lkh: - url: https://github.com/crigroup/lkh-release.git - vcs: git - version: release/kinetic/lkh/0.1.1-0 -lkh_solver: - url: https://github.com/crigroup/lkh-release.git - vcs: git - version: release/kinetic/lkh_solver/0.1.1-0 -lms1xx: - url: https://github.com/clearpath-gbp/lms1xx-release.git - vcs: git - version: release/kinetic/lms1xx/0.1.6-0 -lockfree: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/kinetic/lockfree/1.0.25-0 -locomotor: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/locomotor/0.2.5-0 -locomotor_msgs: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/locomotor_msgs/0.2.5-0 -locomove_base: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/locomove_base/0.2.5-0 -log4cpp: - url: https://github.com/orocos-gbp/log4cpp-release.git - vcs: git - version: release/kinetic/log4cpp/2.9.1-1 -log_server: - url: https://github.com/easymov/log_server-release.git - vcs: git - version: release/kinetic/log_server/0.1.4-1 -loki_base_node: - url: https://github.com/UbiquityRobotics-release/loki_base_node-release.git - vcs: git - version: release/kinetic/loki_base_node/0.2.2-0 -loki_bringup: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_bringup/0.0.2-0 -loki_demos: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_demos/0.0.2-0 -loki_description: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_description/0.0.2-0 -loki_nav: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_nav/0.0.2-0 -loki_robot: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_robot/0.0.2-0 -loki_teleop: - url: https://github.com/UbiquityRobotics-release/loki_robot-release.git - vcs: git - version: release/kinetic/loki_teleop/0.0.2-0 -look_at_pose: - url: https://github.com/UTNuclearRoboticsPublic/look_at_pose-release.git - vcs: git - version: release/kinetic/look_at_pose/0.7.7-0 -lost_comms_recovery: - url: https://github.com/danielsnider/lost_comms_recovery-release.git - vcs: git - version: release/kinetic/lost_comms_recovery/0.1.0-0 -lpg_planner: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/lpg_planner/2.1.13-1 -lusb: - url: https://github.com/DataspeedInc-release/lusb-release.git - vcs: git - version: release/kinetic/lusb/1.1.0-0 -lyap_control: - url: https://github.com/AndyZe/lyap_control-release.git - vcs: git - version: release/kinetic/lyap_control/0.0.13-0 -magni_bringup: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_bringup/0.4.2-0 -magni_demos: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_demos/0.4.2-0 -magni_description: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_description/0.4.2-0 -magni_nav: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_nav/0.4.2-0 -magni_robot: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_robot/0.4.2-0 -magni_teleop: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_teleop/0.4.2-0 -magni_viz: - url: https://github.com/UbiquityRobotics-release/magni_robot-release.git - vcs: git - version: release/kinetic/magni_viz/0.4.2-0 -manipulation_msgs: - url: https://github.com/ros-gbp/manipulation_msgs-release.git - vcs: git - version: release/kinetic/manipulation_msgs/0.2.1-0 -manipulator_h: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h/0.3.1-0 -manipulator_h_base_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_base_module/0.3.1-0 -manipulator_h_base_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_base_module_msgs/0.3.1-0 -manipulator_h_bringup: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_bringup/0.3.1-0 -manipulator_h_description: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_description/0.3.1-0 -manipulator_h_gazebo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_gazebo/0.3.1-0 -manipulator_h_gui: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_gui/0.3.1-0 -manipulator_h_kinematics_dynamics: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_kinematics_dynamics/0.3.1-0 -manipulator_h_manager: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-MANIPULATOR-H-release.git - vcs: git - version: release/kinetic/manipulator_h_manager/0.3.1-0 -map_laser: - url: https://github.com/wu-robotics/laser_filtering_release.git - vcs: git - version: release/kinetic/map_laser/0.0.4-0 -map_organizer: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/map_organizer/0.4.2-1 -map_organizer_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/kinetic/map_organizer_msgs/0.3.1-0 -mapviz: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/kinetic/mapviz/1.1.1-1 -mapviz_plugins: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/kinetic/mapviz_plugins/1.1.1-1 -marker_msgs: - url: https://github.com/tuw-robotics/marker_msgs-release.git - vcs: git - version: release/kinetic/marker_msgs/0.0.6-0 -marker_rviz_plugin: - url: https://github.com/tuw-robotics/marker_rviz_plugin-release.git - vcs: git - version: release/kinetic/marker_rviz_plugin/0.0.2-0 -marshmallow: - url: https://github.com/asmodehn/marshmallow-rosrelease.git - vcs: git - version: release/kinetic/marshmallow/2.9.1-1 -marti_can_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_can_msgs/0.8.0-0 -marti_common_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_common_msgs/0.8.0-0 -marti_data_structures: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/marti_data_structures/2.9.0-1 -marti_nav_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_nav_msgs/0.8.0-0 -marti_perception_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_perception_msgs/0.8.0-0 -marti_sensor_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_sensor_msgs/0.8.0-0 -marti_status_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_status_msgs/0.8.0-0 -marti_visualization_msgs: - url: https://github.com/swri-robotics-gbp/marti_messages-release.git - vcs: git - version: release/kinetic/marti_visualization_msgs/0.8.0-0 -marvelmind_nav: - url: https://github.com/MarvelmindRobotics/marvelmind_nav-release.git - vcs: git - version: release/kinetic/marvelmind_nav/1.0.8-0 -master_discovery_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/master_discovery_fkie/0.8.12-0 -master_sync_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/master_sync_fkie/0.8.12-0 -mav_comm: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/kinetic/mav_comm/3.3.2-0 -mav_msgs: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/kinetic/mav_msgs/3.3.2-0 -mav_planning_msgs: - url: https://github.com/ethz-asl/mav_comm-release.git - vcs: git - version: release/kinetic/mav_planning_msgs/3.3.2-0 -mavlink: - url: https://github.com/mavlink/mavlink-gbp-release.git - vcs: git - version: release/kinetic/mavlink/2019.8.8-1 -mavros: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/kinetic/mavros/0.32.1-1 -mavros_extras: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/kinetic/mavros_extras/0.32.1-1 -mavros_msgs: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/kinetic/mavros_msgs/0.32.1-1 -mbf_abstract_core: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_abstract_core/0.2.4-1 -mbf_abstract_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_abstract_nav/0.2.4-1 -mbf_costmap_core: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_costmap_core/0.2.4-1 -mbf_costmap_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_costmap_nav/0.2.4-1 -mbf_msgs: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_msgs/0.2.4-1 -mbf_simple_nav: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_simple_nav/0.2.4-1 -mbf_utility: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/mbf_utility/0.2.4-1 -mcl_3dl: - url: https://github.com/at-wat/mcl_3dl-release.git - vcs: git - version: release/kinetic/mcl_3dl/0.1.5-1 -mcl_3dl_msgs: - url: https://github.com/at-wat/mcl_3dl_msgs-release.git - vcs: git - version: release/kinetic/mcl_3dl_msgs/0.1.2-0 -mcmillan_airfield: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/kinetic/mcmillan_airfield/0.0.1-1 -md49_base_controller: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/kinetic/md49_base_controller/0.1.4-1 -md49_messages: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/kinetic/md49_messages/0.1.4-1 -md49_serialport: - url: https://github.com/Scheik/md49_base_controller-release.git - vcs: git - version: release/kinetic/md49_serialport/0.1.4-1 -mecanum_gazebo_plugin: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/kinetic/mecanum_gazebo_plugin/0.0.3-0 -melfa_description: - url: https://github.com/tork-a/melfa_robot-release.git - vcs: git - version: release/kinetic/melfa_description/0.0.4-0 -melfa_driver: - url: https://github.com/tork-a/melfa_robot-release.git - vcs: git - version: release/kinetic/melfa_driver/0.0.4-0 -melfa_robot: - url: https://github.com/tork-a/melfa_robot-release.git - vcs: git - version: release/kinetic/melfa_robot/0.0.4-0 -message_multiplexing: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/message_multiplexing/0.2.4-0 -message_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/message_relay/0.0.2-1 -message_to_tf: - url: https://github.com/tu-darmstadt-ros-pkg-gbp/hector_localization-release.git - vcs: git - version: release/kinetic/message_to_tf/0.3.0-0 -micros_swarm_framework: - url: https://github.com/xuefengchang/micros_swarm_framework-release.git - vcs: git - version: release/kinetic/micros_swarm_framework/0.0.17-2 -microstrain_3dmgx2_imu: - url: https://github.com/ros-gbp/microstrain_3dmgx2_imu-release.git - vcs: git - version: release/kinetic/microstrain_3dmgx2_imu/1.5.13-1 -microstrain_mips: - url: https://github.com/ros-drivers-gbp/microstrain_mips-release.git - vcs: git - version: release/kinetic/microstrain_mips/0.0.3-1 -minas: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/minas/1.0.10-0 -minas_control: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/minas_control/1.0.10-0 -mini_maxwell: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/mini_maxwell/2.1.13-1 -mir_actions: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_actions/1.0.4-1 -mir_description: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_description/1.0.4-1 -mir_driver: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_driver/1.0.4-1 -mir_dwb_critics: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_dwb_critics/1.0.4-1 -mir_gazebo: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_gazebo/1.0.4-1 -mir_msgs: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_msgs/1.0.4-1 -mir_navigation: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_navigation/1.0.4-1 -mir_robot: - url: https://github.com/uos-gbp/mir_robot-release.git - vcs: git - version: release/kinetic/mir_robot/1.0.4-1 -ml_classifiers: - url: https://github.com/astuff/ml_classifiers-release.git - vcs: git - version: release/kinetic/ml_classifiers/1.0.1-1 -mm_core_msgs: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/mm_core_msgs/0.2.4-0 -mm_eigen_msgs: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/mm_eigen_msgs/0.2.4-0 -mm_messages: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/mm_messages/0.2.4-0 -mm_mux_demux: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/mm_mux_demux/0.2.4-0 -mm_radio: - url: https://github.com/yujinrobot-release/message_multiplexing-release.git - vcs: git - version: release/kinetic/mm_radio/0.2.4-0 -mobileye_560_660_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/mobileye_560_660_msgs/2.3.1-0 -modelica_bridge: - url: https://github.com/ModROS/modelica_bridge-release.git - vcs: git - version: release/kinetic/modelica_bridge/0.1.1-0 -mongodb_log: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/kinetic/mongodb_log/0.4.5-1 -mongodb_store: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/kinetic/mongodb_store/0.4.5-1 -mongodb_store_msgs: - url: https://github.com/strands-project-releases/mongodb_store.git - vcs: git - version: release/kinetic/mongodb_store_msgs/0.4.5-1 -monocam_settler: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/monocam_settler/0.10.14-0 -motion_module_tutorial: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/motion_module_tutorial/0.2.0-0 -mouse_teleop: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/kinetic/mouse_teleop/0.3.0-0 -move_base: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/move_base/1.14.4-0 -move_base_flex: - url: https://github.com/uos-gbp/move_base_flex-release.git - vcs: git - version: release/kinetic/move_base_flex/0.2.4-1 -move_base_msgs: - url: https://github.com/ros-gbp/navigation_msgs-release.git - vcs: git - version: release/kinetic/move_base_msgs/1.13.0-0 -move_base_to_manip: - url: https://github.com/UTNuclearRoboticsPublic/move_base_to_manip-release.git - vcs: git - version: release/kinetic/move_base_to_manip/1.0.18-1 -move_basic: - url: https://github.com/UbiquityRobotics-release/move_basic-release.git - vcs: git - version: release/kinetic/move_basic/0.3.2-0 -move_slow_and_clear: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/move_slow_and_clear/1.14.4-0 -moveit: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit/0.9.17-1 -moveit_chomp_optimizer_adapter: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_chomp_optimizer_adapter/0.9.17-1 -moveit_commander: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_commander/0.9.17-1 -moveit_config_m0609: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/moveit_config_m0609/0.9.6-1 -moveit_config_m0617: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/moveit_config_m0617/0.9.6-1 -moveit_config_m1013: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/moveit_config_m1013/0.9.6-1 -moveit_config_m1509: - url: https://github.com/doosan-robotics/doosan-robot-release.git - vcs: git - version: release/kinetic/moveit_config_m1509/0.9.6-1 -moveit_controller_manager_example: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_controller_manager_example/0.9.17-1 -moveit_core: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_core/0.9.17-1 -moveit_experimental: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_experimental/0.9.17-1 -moveit_fake_controller_manager: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_fake_controller_manager/0.9.17-1 -moveit_kinematics: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_kinematics/0.9.17-1 -moveit_msgs: - url: https://github.com/ros-gbp/moveit_msgs-release.git - vcs: git - version: release/kinetic/moveit_msgs/0.9.1-0 -moveit_planners: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_planners/0.9.17-1 -moveit_planners_chomp: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_planners_chomp/0.9.17-1 -moveit_planners_ompl: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_planners_ompl/0.9.17-1 -moveit_plugins: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_plugins/0.9.17-1 -moveit_pr2: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/kinetic/moveit_pr2/0.7.1-0 -moveit_python: - url: https://github.com/mikeferguson/moveit_python-release.git - vcs: git - version: release/kinetic/moveit_python/0.3.1-0 -moveit_resources: - url: https://github.com/ros-gbp/moveit_resources-release.git - vcs: git - version: release/kinetic/moveit_resources/0.6.4-0 -moveit_ros: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros/0.9.17-1 -moveit_ros_benchmarks: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_benchmarks/0.9.17-1 -moveit_ros_control_interface: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_control_interface/0.9.17-1 -moveit_ros_manipulation: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_manipulation/0.9.17-1 -moveit_ros_move_group: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_move_group/0.9.17-1 -moveit_ros_perception: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_perception/0.9.17-1 -moveit_ros_planning: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_planning/0.9.17-1 -moveit_ros_planning_interface: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_planning_interface/0.9.17-1 -moveit_ros_robot_interaction: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_robot_interaction/0.9.17-1 -moveit_ros_visualization: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_visualization/0.9.17-1 -moveit_ros_warehouse: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_ros_warehouse/0.9.17-1 -moveit_runtime: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_runtime/0.9.17-1 -moveit_setup_assistant: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_setup_assistant/0.9.17-1 -moveit_sim_controller: - url: https://github.com/davetcoleman/moveit_sim_controller-release.git - vcs: git - version: release/kinetic/moveit_sim_controller/0.1.0-0 -moveit_simple_controller_manager: - url: https://github.com/ros-gbp/moveit-release.git - vcs: git - version: release/kinetic/moveit_simple_controller_manager/0.9.17-1 -moveit_visual_tools: - url: https://github.com/ros-gbp/moveit_visual_tools-release.git - vcs: git - version: release/kinetic/moveit_visual_tools/3.4.1-0 -movie_publisher: - url: https://github.com/peci1/movie_publisher-release.git - vcs: git - version: release/kinetic/movie_publisher/1.2.2-1 -mqtt_bridge: - url: https://github.com/groove-x/mqtt_bridge-release.git - vcs: git - version: release/kinetic/mqtt_bridge/0.1.6-0 -mrpt1: - url: https://github.com/mrpt-ros-pkg-release/mrpt1-release.git - vcs: git - version: release/kinetic/mrpt1/1.5.8-0 -mrpt_bridge: - url: https://github.com/mrpt-ros-pkg-release/mrpt_bridge-release.git - vcs: git - version: release/kinetic/mrpt_bridge/0.1.25-0 -mrpt_ekf_slam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_ekf_slam_2d/0.1.9-0 -mrpt_ekf_slam_3d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_ekf_slam_3d/0.1.9-0 -mrpt_graphslam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_graphslam_2d/0.1.9-0 -mrpt_icp_slam_2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_icp_slam_2d/0.1.9-0 -mrpt_local_obstacles: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_local_obstacles/0.1.24-0 -mrpt_localization: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_localization/0.1.24-0 -mrpt_map: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_map/0.1.24-0 -mrpt_msgs: - url: https://github.com/mrpt-ros-pkg-release/mrpt_msgs-release.git - vcs: git - version: release/kinetic/mrpt_msgs/0.1.23-0 -mrpt_navigation: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_navigation/0.1.24-0 -mrpt_rawlog: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_rawlog/0.1.24-0 -mrpt_rbpf_slam: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_rbpf_slam/0.1.9-0 -mrpt_reactivenav2d: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_reactivenav2d/0.1.24-0 -mrpt_slam: - url: https://github.com/mrpt-ros-pkg-release/mrpt_slam-release.git - vcs: git - version: release/kinetic/mrpt_slam/0.1.9-0 -mrpt_tutorials: - url: https://github.com/mrpt-ros-pkg-release/mrpt_navigation-release.git - vcs: git - version: release/kinetic/mrpt_tutorials/0.1.24-0 -msp: - url: https://github.com/christianrauch/msp-release.git - vcs: git - version: release/kinetic/msp/2.2.1-1 -multi_interface_roam: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/multi_interface_roam/1.0.15-0 -multi_jackal_base: - url: https://github.com/NicksSimulationsROS/multi_jackal-release.git - vcs: git - version: release/kinetic/multi_jackal_base/0.0.5-0 -multi_jackal_control: - url: https://github.com/NicksSimulationsROS/multi_jackal-release.git - vcs: git - version: release/kinetic/multi_jackal_control/0.0.5-0 -multi_jackal_description: - url: https://github.com/NicksSimulationsROS/multi_jackal-release.git - vcs: git - version: release/kinetic/multi_jackal_description/0.0.5-0 -multi_jackal_nav: - url: https://github.com/NicksSimulationsROS/multi_jackal-release.git - vcs: git - version: release/kinetic/multi_jackal_nav/0.0.5-0 -multi_jackal_tutorials: - url: https://github.com/NicksSimulationsROS/multi_jackal-release.git - vcs: git - version: release/kinetic/multi_jackal_tutorials/0.0.5-0 -multi_map_server: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/multi_map_server/2.2.10-0 -multi_object_tracking_lidar: - url: https://github.com/praveen-palanisamy/multi_object_tracking_lidar-release.git - vcs: git - version: release/kinetic/multi_object_tracking_lidar/1.0.1-1 -multikey_teleop: - url: https://github.com/easymov/multikey_teleop-release.git - vcs: git - version: release/kinetic/multikey_teleop/1.0.0-0 -multimaster_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/multimaster_fkie/0.8.12-0 -multimaster_launch: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/multimaster_launch/0.0.2-1 -multimaster_msgs: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/multimaster_msgs/0.0.2-1 -multimaster_msgs_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/multimaster_msgs_fkie/0.8.12-0 -multires_image: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/kinetic/multires_image/1.1.1-1 -multirobot_map_merge: - url: https://github.com/hrnr/m-explore-release.git - vcs: git - version: release/kinetic/multirobot_map_merge/2.1.1-0 -multisense: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense/4.0.0-0 -multisense_bringup: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense_bringup/4.0.0-0 -multisense_cal_check: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense_cal_check/4.0.0-0 -multisense_description: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense_description/4.0.0-0 -multisense_lib: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense_lib/4.0.0-0 -multisense_ros: - url: https://github.com/carnegieroboticsllc/multisense_ros-release.git - vcs: git - version: release/kinetic/multisense_ros/4.0.0-0 -multiwii: - url: https://github.com/christianrauch/ros-multiwii-release.git - vcs: git - version: release/kinetic/multiwii/2.1.0-0 -mvsim: - url: https://github.com/ual-arm-ros-pkg-release/mvsim-release.git - vcs: git - version: release/kinetic/mvsim/0.2.1-0 -myahrs_driver: - url: https://github.com/robotpilot/myahrs_driver-release.git - vcs: git - version: release/kinetic/myahrs_driver/0.1.2-0 -nanomsg: - url: https://github.com/yujinrobot-release/nanomsg-release.git - vcs: git - version: release/kinetic/nanomsg/0.4.1-0 -nao_apps: - url: https://github.com/ros-naoqi/nao_robot-release.git - vcs: git - version: release/kinetic/nao_apps/0.5.15-0 -nao_audio: - url: https://github.com/ros-naoqi/nao_interaction-release.git - vcs: git - version: release/kinetic/nao_audio/0.1.5-0 -nao_bringup: - url: https://github.com/ros-naoqi/nao_robot-release.git - vcs: git - version: release/kinetic/nao_bringup/0.5.15-0 -nao_control: - url: https://github.com/ros-naoqi/nao_virtual-release.git - vcs: git - version: release/kinetic/nao_control/0.0.6-0 -nao_dcm_bringup: - url: https://github.com/ros-naoqi/nao_dcm_robot-release.git - vcs: git - version: release/kinetic/nao_dcm_bringup/0.0.5-0 -nao_description: - url: https://github.com/ros-naoqi/nao_robot-release.git - vcs: git - version: release/kinetic/nao_description/0.5.15-0 -nao_interaction: - url: https://github.com/ros-naoqi/nao_interaction-release.git - vcs: git - version: release/kinetic/nao_interaction/0.1.5-0 -nao_interaction_launchers: - url: https://github.com/ros-naoqi/nao_interaction-release.git - vcs: git - version: release/kinetic/nao_interaction_launchers/0.1.5-0 -nao_interaction_msgs: - url: https://github.com/ros-naoqi/nao_interaction-release.git - vcs: git - version: release/kinetic/nao_interaction_msgs/0.1.5-0 -nao_meshes: - url: https://github.com/ros-naoqi/nao_meshes-release.git - vcs: git - version: release/kinetic/nao_meshes/0.1.11-1 -nao_moveit_config: - url: https://github.com/ros-naoqi/nao_moveit_config-release.git - vcs: git - version: release/kinetic/nao_moveit_config/0.0.11-0 -nao_robot: - url: https://github.com/ros-naoqi/nao_robot-release.git - vcs: git - version: release/kinetic/nao_robot/0.5.15-0 -nao_vision: - url: https://github.com/ros-naoqi/nao_interaction-release.git - vcs: git - version: release/kinetic/nao_vision/0.1.5-0 -naoqi_apps: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_apps/0.5.5-0 -naoqi_bridge: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_bridge/0.5.5-0 -naoqi_bridge_msgs: - url: https://github.com/ros-naoqi/naoqi_bridge_msgs-release.git - vcs: git - version: release/kinetic/naoqi_bridge_msgs/0.0.8-0 -naoqi_dcm_driver: - url: https://github.com/ros-naoqi/naoqi_dcm_driver-release.git - vcs: git - version: release/kinetic/naoqi_dcm_driver/0.0.3-0 -naoqi_driver: - url: https://github.com/ros-naoqi/naoqi_driver-release.git - vcs: git - version: release/kinetic/naoqi_driver/0.5.10-0 -naoqi_driver_py: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_driver_py/0.5.5-0 -naoqi_libqi: - url: https://github.com/ros-naoqi/libqi-release.git - vcs: git - version: release/kinetic/naoqi_libqi/2.5.0-3 -naoqi_libqicore: - url: https://github.com/ros-naoqi/libqicore-release.git - vcs: git - version: release/kinetic/naoqi_libqicore/2.3.1-1 -naoqi_pose: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_pose/0.5.5-0 -naoqi_sensors_py: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_sensors_py/0.5.5-0 -naoqi_tools: - url: https://github.com/ros-naoqi/naoqi_bridge-release.git - vcs: git - version: release/kinetic/naoqi_tools/0.5.5-0 -nav2d: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d/0.3.2-0 -nav2d_exploration: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_exploration/0.3.2-0 -nav2d_karto: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_karto/0.3.2-0 -nav2d_localizer: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_localizer/0.3.2-0 -nav2d_msgs: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_msgs/0.3.2-0 -nav2d_navigator: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_navigator/0.3.2-0 -nav2d_operator: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_operator/0.3.2-0 -nav2d_remote: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_remote/0.3.2-0 -nav2d_tutorials: - url: https://github.com/skasperski/navigation_2d-release.git - vcs: git - version: release/kinetic/nav2d_tutorials/0.3.2-0 -nav_2d_msgs: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_2d_msgs/0.2.5-0 -nav_2d_utils: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_2d_utils/0.2.5-0 -nav_core: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/nav_core/1.14.4-0 -nav_core2: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_core2/0.2.5-0 -nav_core_adapter: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_core_adapter/0.2.5-0 -nav_grid: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_grid/0.2.5-0 -nav_grid_iterators: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_grid_iterators/0.2.5-0 -nav_grid_pub_sub: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/nav_grid_pub_sub/0.2.5-0 -nav_pcontroller: - url: https://github.com/code-iai-release/nav_pcontroller-release.git - vcs: git - version: release/kinetic/nav_pcontroller/0.1.4-0 -navfn: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/navfn/1.14.4-0 -navigation: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/navigation/1.14.4-0 -navigation_experimental: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/navigation_experimental/0.2.1-0 -navigation_layers: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/kinetic/navigation_layers/0.3.1-1 -navigation_stage: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/navigation_stage/0.2.3-0 -navigation_tutorials: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/navigation_tutorials/0.2.3-0 -ncd_parser: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/ncd_parser/0.3.2-0 -neobotix_usboard_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/neobotix_usboard_msgs/2.3.1-0 -neonavigation: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/neonavigation/0.4.2-1 -neonavigation_common: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/neonavigation_common/0.4.2-1 -neonavigation_launch: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/neonavigation_launch/0.4.2-1 -neonavigation_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/kinetic/neonavigation_msgs/0.3.1-0 -neonavigation_rviz_plugins: - url: https://github.com/at-wat/neonavigation_rviz_plugins-release.git - vcs: git - version: release/kinetic/neonavigation_rviz_plugins/0.3.0-0 -nerian_sp1: - url: https://github.com/nerian-vision/nerian_sp1-release.git - vcs: git - version: release/kinetic/nerian_sp1/1.6.3-0 -nerian_stereo: - url: https://github.com/nerian-vision/nerian_stereo-release.git - vcs: git - version: release/kinetic/nerian_stereo/3.5.0-1 -network_control_tests: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/network_control_tests/1.0.15-0 -network_detector: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/network_detector/1.0.15-0 -network_interface: - url: https://github.com/astuff/network_interface-release.git - vcs: git - version: release/kinetic/network_interface/2.1.0-0 -network_monitor_udp: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/network_monitor_udp/1.0.15-0 -network_traffic_control: - url: https://github.com/pr2-gbp/linux_networking-release.git - vcs: git - version: release/kinetic/network_traffic_control/1.0.15-0 -nextage_calibration: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_calibration/0.8.5-1 -nextage_description: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_description/0.8.5-1 -nextage_gazebo: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_gazebo/0.8.5-1 -nextage_ik_plugin: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_ik_plugin/0.8.5-1 -nextage_moveit_config: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_moveit_config/0.8.5-1 -nextage_ros_bridge: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/nextage_ros_bridge/0.8.5-1 -nlopt: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/nlopt/2.1.13-1 -nmea_comms: - url: https://github.com/ros-drivers-gbp/nmea_comms-release.git - vcs: git - version: release/kinetic/nmea_comms/1.1.0-0 -nmea_gps_plugin: - url: https://github.com/OUXT-Polaris/nmea_gps_plugin-release.git - vcs: git - version: release/kinetic/nmea_gps_plugin/0.0.2-1 -nmea_msgs: - url: https://github.com/ros-drivers-gbp/nmea_msgs-release.git - vcs: git - version: release/kinetic/nmea_msgs/1.1.0-0 -nmea_navsat_driver: - url: https://github.com/ros-drivers-gbp/nmea_navsat_driver-release.git - vcs: git - version: release/kinetic/nmea_navsat_driver/0.5.1-0 -node_manager_fkie: - url: https://github.com/fkie-release/multimaster_fkie-release.git - vcs: git - version: release/kinetic/node_manager_fkie/0.8.12-0 -nonpersistent_voxel_layer: - url: https://github.com/SteveMacenski/nonpersistent_voxel_layer-release.git - vcs: git - version: release/kinetic/nonpersistent_voxel_layer/1.1.3-0 -novatel_gps_driver: - url: https://github.com/swri-robotics-gbp/novatel_gps_driver-release.git - vcs: git - version: release/kinetic/novatel_gps_driver/3.8.0-1 -novatel_gps_msgs: - url: https://github.com/swri-robotics-gbp/novatel_gps_driver-release.git - vcs: git - version: release/kinetic/novatel_gps_msgs/3.8.0-1 -novatel_msgs: - url: https://github.com/ros-drivers-gbp/novatel_span_driver-release.git - vcs: git - version: release/kinetic/novatel_msgs/1.1.0-0 -novatel_span_driver: - url: https://github.com/ros-drivers-gbp/novatel_span_driver-release.git - vcs: git - version: release/kinetic/novatel_span_driver/1.1.0-0 -ntpd_driver: - url: https://github.com/vooon/ntpd_driver-release.git - vcs: git - version: release/kinetic/ntpd_driver/1.2.0-0 -o3m151_driver: - url: https://github.com/labex-imobs3-gbp/o3m151_driver-release.git - vcs: git - version: release/kinetic/o3m151_driver/1.2.1-0 -obj_to_pointcloud: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/obj_to_pointcloud/0.4.2-1 -object_recognition_capture: - url: https://github.com/ros-gbp/object_recognition_capture-release.git - vcs: git - version: release/kinetic/object_recognition_capture/0.3.2-0 -object_recognition_core: - url: https://github.com/ros-gbp/object_recognition_core-release.git - vcs: git - version: release/kinetic/object_recognition_core/0.6.7-0 -object_recognition_msgs: - url: https://github.com/ros-gbp/object_recognition_msgs-release.git - vcs: git - version: release/kinetic/object_recognition_msgs/0.4.1-0 -object_recognition_reconstruction: - url: https://github.com/ros-gbp/object_recognition_reconstruction-release.git - vcs: git - version: release/kinetic/object_recognition_reconstruction/0.3.6-0 -object_recognition_ros: - url: https://github.com/ros-gbp/object_recognition_ros-release.git - vcs: git - version: release/kinetic/object_recognition_ros/0.3.7-0 -object_recognition_ros_visualization: - url: https://github.com/ros-gbp/object_recognition_ros_visualization-release.git - vcs: git - version: release/kinetic/object_recognition_ros_visualization/0.3.8-0 -object_recognition_tod: - url: https://github.com/ros-gbp/object_recognition_tod-release.git - vcs: git - version: release/kinetic/object_recognition_tod/0.5.6-0 -object_recognition_transparent_objects: - url: https://github.com/ros-gbp/object_recognition_transparent_objects-release.git - vcs: git - version: release/kinetic/object_recognition_transparent_objects/0.4.3-0 -ocean_battery_driver: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/kinetic/ocean_battery_driver/1.1.7-0 -ocl: - url: https://github.com/orocos-gbp/ocl-release.git - vcs: git - version: release/kinetic/ocl/2.9.2-1 -octomap_mapping: - url: https://github.com/ros-gbp/octomap_mapping-release.git - vcs: git - version: release/kinetic/octomap_mapping/0.6.1-0 -octomap_msgs: - url: https://github.com/ros-gbp/octomap_msgs-release.git - vcs: git - version: release/kinetic/octomap_msgs/0.3.3-0 -octomap_pa: - url: https://github.com/TUC-ProAut/ros_octomap-release.git - vcs: git - version: release/kinetic/octomap_pa/1.3.3-0 -octomap_ros: - url: https://github.com/ros-gbp/octomap_ros-release.git - vcs: git - version: release/kinetic/octomap_ros/0.4.0-0 -octomap_rviz_plugins: - url: https://github.com/ros-gbp/octomap_rviz_plugins-release.git - vcs: git - version: release/kinetic/octomap_rviz_plugins/0.2.0-0 -octomap_server: - url: https://github.com/ros-gbp/octomap_mapping-release.git - vcs: git - version: release/kinetic/octomap_server/0.6.1-0 -octovis: - url: https://github.com/ros-gbp/octomap-release.git - vcs: git - version: release/kinetic/octovis/1.8.1-0 -oculusprime: - url: https://github.com/xaxxontech/oculusprime_ros-release.git - vcs: git - version: release/kinetic/oculusprime/0.1.3-0 -odometry_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/odometry_publisher_tutorial/0.2.3-0 -odva_ethernetip: - url: https://github.com/ros-drivers-gbp/odva_ethernetip-release.git - vcs: git - version: release/kinetic/odva_ethernetip/0.1.4-0 -ompl: - url: https://github.com/ros-gbp/ompl-release.git - vcs: git - version: release/kinetic/ompl/1.2.3-1 -omron_os32c_driver: - url: https://github.com/ros-drivers-gbp/omron-release.git - vcs: git - version: release/kinetic/omron_os32c_driver/1.0.0-0 -op3_action_editor: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_action_editor/0.2.2-0 -op3_action_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_action_module/0.2.1-0 -op3_action_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-msgs-release.git - vcs: git - version: release/kinetic/op3_action_module_msgs/0.1.1-0 -op3_balance_control: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_balance_control/0.2.1-0 -op3_ball_detector: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_demo-release.git - vcs: git - version: release/kinetic/op3_ball_detector/0.1.0-0 -op3_base_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_base_module/0.2.1-0 -op3_bringup: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_demo-release.git - vcs: git - version: release/kinetic/op3_bringup/0.1.0-0 -op3_camera_setting_tool: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_camera_setting_tool/0.2.2-0 -op3_demo: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_demo-release.git - vcs: git - version: release/kinetic/op3_demo/0.1.0-0 -op3_description: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-Common-release.git - vcs: git - version: release/kinetic/op3_description/0.1.1-0 -op3_direct_control_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_direct_control_module/0.2.1-0 -op3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-Common-release.git - vcs: git - version: release/kinetic/op3_gazebo/0.1.1-0 -op3_gui_demo: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_gui_demo/0.2.2-0 -op3_head_control_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_head_control_module/0.2.1-0 -op3_kinematics_dynamics: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_kinematics_dynamics/0.2.1-0 -op3_localization: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_localization/0.2.1-0 -op3_manager: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_manager/0.2.1-0 -op3_navigation: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_navigation/0.2.2-0 -op3_offset_tuner_client: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_offset_tuner_client/0.2.2-0 -op3_offset_tuner_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-msgs-release.git - vcs: git - version: release/kinetic/op3_offset_tuner_msgs/0.1.1-0 -op3_offset_tuner_server: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_offset_tuner_server/0.2.2-0 -op3_online_walking_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_online_walking_module/0.2.1-0 -op3_online_walking_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-msgs-release.git - vcs: git - version: release/kinetic/op3_online_walking_module_msgs/0.1.1-0 -op3_walking_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/op3_walking_module/0.2.1-0 -op3_walking_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-msgs-release.git - vcs: git - version: release/kinetic/op3_walking_module_msgs/0.1.1-0 -op3_web_setting_tool: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/op3_web_setting_tool/0.2.2-0 -open_cr_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/open_cr_module/0.2.1-0 -open_karto: - url: https://github.com/ros-gbp/open_karto-release.git - vcs: git - version: release/kinetic/open_karto/1.1.4-0 -open_manipulator: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator/2.0.1-1 -open_manipulator_ar_markers: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_perceptions-release.git - vcs: git - version: release/kinetic/open_manipulator_ar_markers/1.0.0-1 -open_manipulator_control_gui: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_control_gui/2.0.1-1 -open_manipulator_controller: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_controller/2.0.1-1 -open_manipulator_description: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_description/2.0.1-1 -open_manipulator_gazebo: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_simulations-release.git - vcs: git - version: release/kinetic/open_manipulator_gazebo/1.1.0-0 -open_manipulator_libs: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_libs/2.0.1-1 -open_manipulator_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_moveit/2.0.1-1 -open_manipulator_msgs: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_msgs-release.git - vcs: git - version: release/kinetic/open_manipulator_msgs/1.0.0-0 -open_manipulator_perceptions: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_perceptions-release.git - vcs: git - version: release/kinetic/open_manipulator_perceptions/1.0.0-1 -open_manipulator_simulations: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_simulations-release.git - vcs: git - version: release/kinetic/open_manipulator_simulations/1.1.0-0 -open_manipulator_teleop: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator-release.git - vcs: git - version: release/kinetic/open_manipulator_teleop/2.0.1-1 -open_manipulator_with_tb3: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3/1.1.0-0 -open_manipulator_with_tb3_description: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_description/1.1.0-0 -open_manipulator_with_tb3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3_simulations-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_gazebo/1.1.0-0 -open_manipulator_with_tb3_simulations: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3_simulations-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_simulations/1.1.0-0 -open_manipulator_with_tb3_tools: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_tools/1.1.0-0 -open_manipulator_with_tb3_waffle_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_waffle_moveit/1.1.0-0 -open_manipulator_with_tb3_waffle_pi_moveit: - url: https://github.com/ROBOTIS-GIT-release/open_manipulator_with_tb3-release.git - vcs: git - version: release/kinetic/open_manipulator_with_tb3_waffle_pi_moveit/1.1.0-0 -opencv_apps: - url: https://github.com/ros-perception/opencv_apps-release.git - vcs: git - version: release/kinetic/opencv_apps/2.0.1-1 -opencv_candidate: - url: https://github.com/ros-gbp/opencv_candidate-release.git - vcs: git - version: release/kinetic/opencv_candidate/0.2.5-0 -openface_ros: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/openface_ros/0.0.4-0 -opengm: - url: https://github.com/ipa320/cob_extern-release.git - vcs: git - version: release/kinetic/opengm/0.6.13-1 -openhrp3: - url: https://github.com/tork-a/openhrp3-release.git - vcs: git - version: release/kinetic/openhrp3/3.1.9-3 -openni2_camera: - url: https://github.com/ros-gbp/openni2_camera-release.git - vcs: git - version: release/kinetic/openni2_camera/0.4.2-0 -openni2_launch: - url: https://github.com/ros-gbp/openni2_camera-release.git - vcs: git - version: release/kinetic/openni2_launch/0.4.2-0 -openni_camera: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/kinetic/openni_camera/1.11.0-0 -openni_description: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/kinetic/openni_description/1.11.0-0 -openni_launch: - url: https://github.com/ros-gbp/openni_camera-release.git - vcs: git - version: release/kinetic/openni_launch/1.11.0-0 -openrave: - url: https://github.com/tork-a/openrave_planning-release.git - vcs: git - version: release/kinetic/openrave/0.0.6-0 -openrave_planning: - url: https://github.com/tork-a/openrave_planning-release.git - vcs: git - version: release/kinetic/openrave_planning/0.0.6-0 -openrtm_aist: - url: https://github.com/tork-a/openrtm_aist-release.git - vcs: git - version: release/kinetic/openrtm_aist/1.1.0-2 -openrtm_aist_python: - url: https://github.com/tork-a/openrtm_aist_python-release.git - vcs: git - version: release/kinetic/openrtm_aist_python/1.1.0-1 -openrtm_ros_bridge: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/openrtm_ros_bridge/1.4.2-0 -openrtm_tools: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/openrtm_tools/1.4.2-0 -openslam_gmapping: - url: https://github.com/ros-gbp/openslam_gmapping-release.git - vcs: git - version: release/kinetic/openslam_gmapping/0.1.2-0 -opt_camera: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/opt_camera/2.1.13-1 -optpp_catkin: - url: https://github.com/ipab-slmc/optpp_catkin-release.git - vcs: git - version: release/kinetic/optpp_catkin/2.4.0-3 -orocos_kinematics_dynamics: - url: https://github.com/smits/orocos-kdl-release.git - vcs: git - version: release/kinetic/orocos_kinematics_dynamics/1.3.1-0 -oros_tools: - url: https://github.com/easymov/oros_tools-release.git - vcs: git - version: release/kinetic/oros_tools/0.1.1-0 -oros_tools_examples: - url: https://github.com/easymov/oros_tools_examples-release.git - vcs: git - version: release/kinetic/oros_tools_examples/0.1.3-0 -osg_interactive_markers: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/kinetic/osg_interactive_markers/1.0.2-0 -osg_markers: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/kinetic/osg_markers/1.0.2-0 -osg_utils: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/kinetic/osg_utils/1.0.2-0 -osm_cartography: - url: https://github.com/ros-geographic-info/open_street_map-release.git - vcs: git - version: release/kinetic/osm_cartography/0.2.4-0 -ouster_driver: - url: https://github.com/CPFL/ouster-release.git - vcs: git - version: release/kinetic/ouster_driver/0.1.7-0 -oxford_gps_eth: - url: https://github.com/DataspeedInc-release/oxford_gps_eth-release.git - vcs: git - version: release/kinetic/oxford_gps_eth/1.0.0-0 -p2os_doc: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_doc/2.1.0-0 -p2os_driver: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_driver/2.1.0-0 -p2os_launch: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_launch/2.1.0-0 -p2os_msgs: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_msgs/2.1.0-0 -p2os_teleop: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_teleop/2.1.0-0 -p2os_urdf: - url: https://github.com/allenh1/p2os-release.git - vcs: git - version: release/kinetic/p2os_urdf/2.1.0-0 -pacmod: - url: https://github.com/astuff/pacmod-release.git - vcs: git - version: release/kinetic/pacmod/2.0.2-0 -pacmod3: - url: https://github.com/astuff/pacmod3-release.git - vcs: git - version: release/kinetic/pacmod3/1.2.1-0 -pacmod_game_control: - url: https://github.com/astuff/pacmod_game_control-release.git - vcs: git - version: release/kinetic/pacmod_game_control/2.3.0-0 -pacmod_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/pacmod_msgs/2.3.1-0 -pal_hardware_interfaces: - url: https://github.com/pal-gbp/pal_hardware_interfaces-release.git - vcs: git - version: release/kinetic/pal_hardware_interfaces/0.0.3-0 -panda_moveit_config: - url: https://github.com/ros-gbp/panda_moveit_config-release.git - vcs: git - version: release/kinetic/panda_moveit_config/0.7.2-1 -parameter_pa: - url: https://github.com/tuc-proaut/ros_parameter-release.git - vcs: git - version: release/kinetic/parameter_pa/1.2.1-0 -parrot_arsdk: - url: https://github.com/AutonomyLab/parrot_arsdk-release.git - vcs: git - version: release/kinetic/parrot_arsdk/3.14.1-0 -pcdfilter_pa: - url: https://github.com/tuc-proaut/ros_pcdfilter-release.git - vcs: git - version: release/kinetic/pcdfilter_pa/1.2.0-0 -pddl_msgs: - url: https://github.com/tork-a/jsk_planning-release.git - vcs: git - version: release/kinetic/pddl_msgs/0.1.10-0 -pddl_planner: - url: https://github.com/tork-a/jsk_planning-release.git - vcs: git - version: release/kinetic/pddl_planner/0.1.10-0 -pddl_planner_viewer: - url: https://github.com/tork-a/jsk_planning-release.git - vcs: git - version: release/kinetic/pddl_planner_viewer/0.1.10-0 -people: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/people/1.1.3-1 -people_msgs: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/people_msgs/1.1.3-1 -people_tracking_filter: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/people_tracking_filter/1.1.3-1 -people_velocity_tracker: - url: https://github.com/OSUrobotics/people-release.git - vcs: git - version: release/kinetic/people_velocity_tracker/1.1.3-1 -pepper_bringup: - url: https://github.com/ros-naoqi/pepper_robot-release.git - vcs: git - version: release/kinetic/pepper_bringup/0.1.10-0 -pepper_control: - url: https://github.com/ros-naoqi/pepper_virtual-release.git - vcs: git - version: release/kinetic/pepper_control/0.0.4-0 -pepper_dcm_bringup: - url: https://github.com/ros-naoqi/pepper_dcm_robot-release.git - vcs: git - version: release/kinetic/pepper_dcm_bringup/0.0.5-0 -pepper_description: - url: https://github.com/ros-naoqi/pepper_robot-release.git - vcs: git - version: release/kinetic/pepper_description/0.1.10-0 -pepper_gazebo_plugin: - url: https://github.com/ros-naoqi/pepper_virtual-release.git - vcs: git - version: release/kinetic/pepper_gazebo_plugin/0.0.4-0 -pepper_meshes: - url: https://github.com/ros-naoqi/pepper_meshes-release.git - vcs: git - version: release/kinetic/pepper_meshes/0.2.3-2 -pepper_moveit_config: - url: https://github.com/ros-naoqi/pepper_moveit_config-release.git - vcs: git - version: release/kinetic/pepper_moveit_config/0.0.8-0 -pepper_robot: - url: https://github.com/ros-naoqi/pepper_robot-release.git - vcs: git - version: release/kinetic/pepper_robot/0.1.10-0 -pepper_sensors_py: - url: https://github.com/ros-naoqi/pepper_robot-release.git - vcs: git - version: release/kinetic/pepper_sensors_py/0.1.10-0 -pepperl_fuchs_r2000: - url: https://github.com/dillenberger/pepperl_fuchs-release.git - vcs: git - version: release/kinetic/pepperl_fuchs_r2000/0.1.3-0 -pgm_learner: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/pgm_learner/2.1.13-1 -pheeno_ros: - url: https://github.com/ACSLaboratory/pheeno_ros-release.git - vcs: git - version: release/kinetic/pheeno_ros/0.1.1-3 -pheeno_ros_description: - url: https://github.com/acslaboratory/pheeno_ros_description-release.git - vcs: git - version: release/kinetic/pheeno_ros_description/0.1.0-0 -pheeno_ros_sim: - url: https://github.com/ACSLaboratory/pheeno_ros_sim-release.git - vcs: git - version: release/kinetic/pheeno_ros_sim/0.1.5-0 -phidgets_api: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/phidgets_api/0.7.9-1 -phidgets_drivers: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/phidgets_drivers/0.7.9-1 -phidgets_high_speed_encoder: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/phidgets_high_speed_encoder/0.7.9-1 -phidgets_ik: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/phidgets_ik/0.7.9-1 -phidgets_imu: - url: https://github.com/ros-drivers-gbp/phidgets_drivers-release.git - vcs: git - version: release/kinetic/phidgets_imu/0.7.9-1 -pid: - url: https://github.com/AndyZe/pid-release.git - vcs: git - version: release/kinetic/pid/0.0.27-0 -piksi_multi_rtk: - url: https://github.com/earthrover/earth_rover_piksi-release.git - vcs: git - version: release/kinetic/piksi_multi_rtk/1.8.2-1 -piksi_rtk_msgs: - url: https://github.com/earthrover/earth_rover_piksi-release.git - vcs: git - version: release/kinetic/piksi_rtk_msgs/1.8.2-1 -pilz_control: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/pilz_control/0.4.9-1 -pilz_extensions: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_extensions/0.3.8-0 -pilz_industrial_motion: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_industrial_motion/0.3.8-0 -pilz_industrial_motion_testutils: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_industrial_motion_testutils/0.3.8-0 -pilz_msgs: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_msgs/0.3.8-0 -pilz_robot_programming: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_robot_programming/0.3.8-0 -pilz_robots: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/pilz_robots/0.4.9-1 -pilz_testutils: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/pilz_testutils/0.4.9-1 -pilz_trajectory_generation: - url: https://github.com/PilzDE/pilz_industrial_motion-release.git - vcs: git - version: release/kinetic/pilz_trajectory_generation/0.3.8-0 -pinocchio: - url: https://github.com/ipab-slmc/pinocchio_catkin-release.git - vcs: git - version: release/kinetic/pinocchio/2.1.3-1 -planner_cspace: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/planner_cspace/0.4.2-1 -planner_cspace_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/kinetic/planner_cspace_msgs/0.3.1-0 -play_motion: - url: https://github.com/pal-gbp/play_motion-release2.git - vcs: git - version: release/kinetic/play_motion/0.4.5-0 -play_motion_msgs: - url: https://github.com/pal-gbp/play_motion-release2.git - vcs: git - version: release/kinetic/play_motion_msgs/0.4.5-0 -plot_tools: - url: https://github.com/srv/srv_tools-release.git - vcs: git - version: release/kinetic/plot_tools/0.0.3-0 -plotjuggler: - url: https://github.com/facontidavide/plotjuggler-release.git - vcs: git - version: release/kinetic/plotjuggler/2.3.0-1 -point_cloud_publisher_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/point_cloud_publisher_tutorial/0.2.3-0 -pointcloud_to_laserscan: - url: https://github.com/ros-gbp/pointcloud_to_laserscan-release.git - vcs: git - version: release/kinetic/pointcloud_to_laserscan/1.3.1-0 -pointcloud_tools: - url: https://github.com/srv/srv_tools-release.git - vcs: git - version: release/kinetic/pointcloud_tools/0.0.3-0 -pointgrey_camera_description: - url: https://github.com/ros-drivers-gbp/pointgrey_camera_driver-release.git - vcs: git - version: release/kinetic/pointgrey_camera_description/0.13.4-0 -pointgrey_camera_driver: - url: https://github.com/ros-drivers-gbp/pointgrey_camera_driver-release.git - vcs: git - version: release/kinetic/pointgrey_camera_driver/0.13.4-0 -polar_scan_matcher: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/polar_scan_matcher/0.3.2-0 -pose_base_controller: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/pose_base_controller/0.2.1-0 -pose_cov_ops: - url: https://github.com/mrpt-ros-pkg-release/pose_cov_ops-release.git - vcs: git - version: release/kinetic/pose_cov_ops/0.2.0-0 -pose_follower: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/pose_follower/0.2.1-0 -posedetection_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/posedetection_msgs/4.3.1-0 -position_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/position_controllers/0.13.5-0 -power_monitor: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/kinetic/power_monitor/1.1.7-0 -pr2: - url: https://github.com/PR2-prime/pr2_metapackages-release.git - vcs: git - version: release/kinetic/pr2/1.1.3-0 -pr2_2dnav: - url: https://github.com/pr2-gbp/pr2_navigation_apps-release.git - vcs: git - version: release/kinetic/pr2_2dnav/1.0.2-0 -pr2_2dnav_local: - url: https://github.com/pr2-gbp/pr2_navigation_apps-release.git - vcs: git - version: release/kinetic/pr2_2dnav_local/1.0.2-0 -pr2_2dnav_slam: - url: https://github.com/pr2-gbp/pr2_navigation_apps-release.git - vcs: git - version: release/kinetic/pr2_2dnav_slam/1.0.2-0 -pr2_app_manager: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_app_manager/0.6.0-0 -pr2_apps: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_apps/0.6.0-0 -pr2_arm_kinematics: - url: https://github.com/pr2-gbp/pr2_kinematics-release.git - vcs: git - version: release/kinetic/pr2_arm_kinematics/1.0.9-0 -pr2_arm_move_ik: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/pr2_arm_move_ik/0.0.10-0 -pr2_base: - url: https://github.com/PR2-prime/pr2_metapackages-release.git - vcs: git - version: release/kinetic/pr2_base/1.1.3-0 -pr2_bringup: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_bringup/1.6.30-0 -pr2_bringup_tests: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/pr2_bringup_tests/1.0.15-1 -pr2_calibration: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/pr2_calibration/1.0.11-0 -pr2_calibration_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_calibration_controllers/1.10.14-0 -pr2_calibration_launch: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/pr2_calibration_launch/1.0.11-0 -pr2_camera_synchronizer: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_camera_synchronizer/1.6.30-0 -pr2_common: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/kinetic/pr2_common/1.12.4-1 -pr2_common_action_msgs: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/pr2_common_action_msgs/0.0.10-0 -pr2_common_actions: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/pr2_common_actions/0.0.10-0 -pr2_computer_monitor: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_computer_monitor/1.6.30-0 -pr2_controller_configuration: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_controller_configuration/1.6.30-0 -pr2_controller_configuration_gazebo: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/kinetic/pr2_controller_configuration_gazebo/2.0.11-0 -pr2_controller_interface: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_controller_interface/1.8.17-0 -pr2_controller_manager: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_controller_manager/1.8.17-0 -pr2_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_controllers/1.10.14-0 -pr2_controllers_msgs: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_controllers_msgs/1.10.14-0 -pr2_counterbalance_check: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/pr2_counterbalance_check/1.0.15-1 -pr2_dashboard_aggregator: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/kinetic/pr2_dashboard_aggregator/1.12.4-1 -pr2_dense_laser_snapshotter: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/pr2_dense_laser_snapshotter/1.0.11-0 -pr2_description: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/kinetic/pr2_description/1.12.4-1 -pr2_desktop: - url: https://github.com/PR2-prime/pr2_metapackages-release.git - vcs: git - version: release/kinetic/pr2_desktop/1.1.3-0 -pr2_ethercat: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_ethercat/1.6.30-0 -pr2_ethercat_drivers: - url: https://github.com/PR2-prime/pr2_ethercat_drivers-release.git - vcs: git - version: release/kinetic/pr2_ethercat_drivers/1.8.18-1 -pr2_gazebo: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/kinetic/pr2_gazebo/2.0.11-0 -pr2_gazebo_plugins: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/kinetic/pr2_gazebo_plugins/2.0.11-0 -pr2_gripper_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_gripper_action/1.10.14-0 -pr2_gripper_sensor: - url: https://github.com/pr2-gbp/pr2_gripper_sensor-release.git - vcs: git - version: release/kinetic/pr2_gripper_sensor/1.0.10-0 -pr2_gripper_sensor_action: - url: https://github.com/pr2-gbp/pr2_gripper_sensor-release.git - vcs: git - version: release/kinetic/pr2_gripper_sensor_action/1.0.10-0 -pr2_gripper_sensor_controller: - url: https://github.com/pr2-gbp/pr2_gripper_sensor-release.git - vcs: git - version: release/kinetic/pr2_gripper_sensor_controller/1.0.10-0 -pr2_gripper_sensor_msgs: - url: https://github.com/pr2-gbp/pr2_gripper_sensor-release.git - vcs: git - version: release/kinetic/pr2_gripper_sensor_msgs/1.0.10-0 -pr2_hardware_interface: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_hardware_interface/1.8.17-0 -pr2_head_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_head_action/1.10.14-0 -pr2_kinematics: - url: https://github.com/pr2-gbp/pr2_kinematics-release.git - vcs: git - version: release/kinetic/pr2_kinematics/1.0.9-0 -pr2_machine: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/kinetic/pr2_machine/1.12.4-1 -pr2_mannequin_mode: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_mannequin_mode/0.6.0-0 -pr2_mechanism: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_mechanism/1.8.17-0 -pr2_mechanism_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/pr2_mechanism_controllers/1.10.14-0 -pr2_mechanism_diagnostics: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_mechanism_diagnostics/1.8.17-0 -pr2_mechanism_model: - url: https://github.com/pr2-gbp/pr2_mechanism-release.git - vcs: git - version: release/kinetic/pr2_mechanism_model/1.8.17-0 -pr2_mechanism_msgs: - url: https://github.com/ros-gbp/pr2_mechanism_msgs-release.git - vcs: git - version: release/kinetic/pr2_mechanism_msgs/1.8.2-0 -pr2_motor_diagnostic_tool: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/pr2_motor_diagnostic_tool/1.0.15-1 -pr2_move_base: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_move_base/0.1.28-0 -pr2_moveit_config: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/kinetic/pr2_moveit_config/0.7.1-0 -pr2_moveit_plugins: - url: https://github.com/ros-gbp/moveit_pr2-release.git - vcs: git - version: release/kinetic/pr2_moveit_plugins/0.7.1-0 -pr2_msgs: - url: https://github.com/pr2-gbp/pr2_common-release.git - vcs: git - version: release/kinetic/pr2_msgs/1.12.4-1 -pr2_navigation: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation/0.1.28-0 -pr2_navigation_apps: - url: https://github.com/pr2-gbp/pr2_navigation_apps-release.git - vcs: git - version: release/kinetic/pr2_navigation_apps/1.0.2-0 -pr2_navigation_config: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_config/0.1.28-0 -pr2_navigation_global: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_global/0.1.28-0 -pr2_navigation_local: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_local/0.1.28-0 -pr2_navigation_perception: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_perception/0.1.28-0 -pr2_navigation_self_filter: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_self_filter/0.1.28-0 -pr2_navigation_slam: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_slam/0.1.28-0 -pr2_navigation_teleop: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/pr2_navigation_teleop/0.1.28-0 -pr2_position_scripts: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_position_scripts/0.6.0-0 -pr2_power_board: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/kinetic/pr2_power_board/1.1.7-0 -pr2_power_drivers: - url: https://github.com/pr2-gbp/pr2_power_drivers-release.git - vcs: git - version: release/kinetic/pr2_power_drivers/1.1.7-0 -pr2_robot: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_robot/1.6.30-0 -pr2_run_stop_auto_restart: - url: https://github.com/pr2-gbp/pr2_robot-release.git - vcs: git - version: release/kinetic/pr2_run_stop_auto_restart/1.6.30-0 -pr2_se_calibration_launch: - url: https://github.com/UNR-RoboticsResearchLab/pr2_calibration-release.git - vcs: git - version: release/kinetic/pr2_se_calibration_launch/1.0.11-0 -pr2_self_test: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/pr2_self_test/1.0.15-1 -pr2_self_test_msgs: - url: https://github.com/pr2-gbp/pr2_self_test-release.git - vcs: git - version: release/kinetic/pr2_self_test_msgs/1.0.15-1 -pr2_simulator: - url: https://github.com/pr2-gbp/pr2_simulator-release.git - vcs: git - version: release/kinetic/pr2_simulator/2.0.11-0 -pr2_teleop: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_teleop/0.6.0-0 -pr2_teleop_general: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_teleop_general/0.6.0-0 -pr2_tilt_laser_interface: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/pr2_tilt_laser_interface/0.0.10-0 -pr2_tuck_arms_action: - url: https://github.com/pr2-gbp/pr2_common_actions-release.git - vcs: git - version: release/kinetic/pr2_tuck_arms_action/0.0.10-0 -pr2_tuckarm: - url: https://github.com/pr2-gbp/pr2_apps-release.git - vcs: git - version: release/kinetic/pr2_tuckarm/0.6.0-0 -pr2eus: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/kinetic/pr2eus/0.3.14-0 -pr2eus_moveit: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/kinetic/pr2eus_moveit/0.3.14-0 -pr2eus_tutorials: - url: https://github.com/tork-a/jsk_pr2eus-release.git - vcs: git - version: release/kinetic/pr2eus_tutorials/0.3.14-0 -prbt_gazebo: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/prbt_gazebo/0.4.9-1 -prbt_grippers: - url: https://github.com/PilzDE/prbt_grippers-release.git - vcs: git - version: release/kinetic/prbt_grippers/0.0.4-1 -prbt_hardware_support: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/prbt_hardware_support/0.4.9-1 -prbt_ikfast_manipulator_plugin: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/prbt_ikfast_manipulator_plugin/0.4.9-1 -prbt_moveit_config: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/prbt_moveit_config/0.4.9-1 -prbt_pg70_support: - url: https://github.com/PilzDE/prbt_grippers-release.git - vcs: git - version: release/kinetic/prbt_pg70_support/0.0.4-1 -prbt_support: - url: https://github.com/PilzDE/pilz_robots-release.git - vcs: git - version: release/kinetic/prbt_support/0.4.9-1 -prosilica_camera: - url: https://github.com/ros-drivers-gbp/prosilica_driver-release.git - vcs: git - version: release/kinetic/prosilica_camera/1.9.4-1 -prosilica_gige_sdk: - url: https://github.com/ros-drivers-gbp/prosilica_gige_sdk-release.git - vcs: git - version: release/kinetic/prosilica_gige_sdk/1.26.3-0 -ps3joy: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/kinetic/ps3joy/1.13.0-1 -ps4eye: - url: https://github.com/tork-a/ps4eye-release.git - vcs: git - version: release/kinetic/ps4eye/0.0.4-1 -puma_motor_driver: - url: https://github.com/clearpath-gbp/puma_motor_driver-release.git - vcs: git - version: release/kinetic/puma_motor_driver/0.1.2-0 -puma_motor_msgs: - url: https://github.com/clearpath-gbp/puma_motor_driver-release.git - vcs: git - version: release/kinetic/puma_motor_msgs/0.1.2-0 -py_trees: - url: https://github.com/stonier/py_trees-release.git - vcs: git - version: release/kinetic/py_trees/0.5.12-0 -py_trees_msgs: - url: https://github.com/stonier/py_trees_msgs-release.git - vcs: git - version: release/kinetic/py_trees_msgs/0.3.6-0 -py_trees_ros: - url: https://github.com/stonier/py_trees_ros-release.git - vcs: git - version: release/kinetic/py_trees_ros/0.5.18-0 -pybind11_catkin: - url: https://github.com/wxmerkt/pybind11_catkin-release.git - vcs: git - version: release/kinetic/pybind11_catkin/2.2.4-4 -pyclearsilver: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/pyclearsilver/1.0.7-0 -pyros: - url: https://github.com/asmodehn/pyros-rosrelease.git - vcs: git - version: release/kinetic/pyros/0.4.3-1 -pyros_common: - url: https://github.com/asmodehn/pyros-common-rosrelease.git - vcs: git - version: release/kinetic/pyros_common/0.5.4-0 -pyros_config: - url: https://github.com/asmodehn/pyros-config-rosrelease.git - vcs: git - version: release/kinetic/pyros_config/0.2.0-0 -pyros_interfaces_ros: - url: https://github.com/asmodehn/pyros-rosinterface-rosrelease.git - vcs: git - version: release/kinetic/pyros_interfaces_ros/0.4.2-0 -pyros_test: - url: https://github.com/asmodehn/pyros-test-release.git - vcs: git - version: release/kinetic/pyros_test/0.0.6-0 -pyros_utils: - url: https://github.com/asmodehn/pyros-utils-release.git - vcs: git - version: release/kinetic/pyros_utils/0.1.4-0 -python-ftputil: - url: https://github.com/asmodehn/ftputil-rosrelease.git - vcs: git - version: release/kinetic/python-ftputil/3.3.0-3 -python_trep: - url: https://github.com/MurpheyLab/trep-release.git - vcs: git - version: release/kinetic/python_trep/1.0.3-1 -pyzmp: - url: https://github.com/asmodehn/pyzmp-rosrelease.git - vcs: git - version: release/kinetic/pyzmp/0.0.17-0 -qb_chain: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/kinetic/qb_chain/2.1.1-1 -qb_chain_control: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/kinetic/qb_chain_control/2.1.1-1 -qb_chain_controllers: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/kinetic/qb_chain_controllers/2.1.1-1 -qb_chain_description: - url: https://bitbucket.org/qbrobotics/qbchain-ros-release.git - vcs: git - version: release/kinetic/qb_chain_description/2.1.1-1 -qb_device: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device/2.1.0-1 -qb_device_bringup: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_bringup/2.1.0-1 -qb_device_control: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_control/2.1.0-1 -qb_device_description: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_description/2.1.0-1 -qb_device_driver: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_driver/2.1.0-1 -qb_device_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_hardware_interface/2.1.0-1 -qb_device_msgs: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_msgs/2.1.0-1 -qb_device_srvs: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_srvs/2.1.0-1 -qb_device_utils: - url: https://bitbucket.org/qbrobotics/qbdevice-ros-release.git - vcs: git - version: release/kinetic/qb_device_utils/2.1.0-1 -qb_hand: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/kinetic/qb_hand/2.0.0-0 -qb_hand_control: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/kinetic/qb_hand_control/2.0.0-0 -qb_hand_description: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/kinetic/qb_hand_description/2.0.0-0 -qb_hand_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbhand-ros-release.git - vcs: git - version: release/kinetic/qb_hand_hardware_interface/2.0.0-0 -qb_move: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/kinetic/qb_move/2.1.2-1 -qb_move_control: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/kinetic/qb_move_control/2.1.2-1 -qb_move_description: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/kinetic/qb_move_description/2.1.2-1 -qb_move_hardware_interface: - url: https://bitbucket.org/qbrobotics/qbmove-ros-release.git - vcs: git - version: release/kinetic/qb_move_hardware_interface/2.1.2-1 -qt_build: - url: https://github.com/yujinrobot-release/qt_ros-release.git - vcs: git - version: release/kinetic/qt_build/0.2.10-0 -qt_create: - url: https://github.com/yujinrobot-release/qt_ros-release.git - vcs: git - version: release/kinetic/qt_create/0.2.10-0 -qt_gui_app: - url: https://github.com/ros-gbp/qt_gui_core-release.git - vcs: git - version: release/kinetic/qt_gui_app/0.3.11-0 -qt_gui_core: - url: https://github.com/ros-gbp/qt_gui_core-release.git - vcs: git - version: release/kinetic/qt_gui_core/0.3.11-0 -qt_qmake: - url: https://github.com/swri-robotics-gbp/qt_metapackages-release.git - vcs: git - version: release/kinetic/qt_qmake/1.0.1-0 -qt_ros: - url: https://github.com/yujinrobot-release/qt_ros-release.git - vcs: git - version: release/kinetic/qt_ros/0.2.10-0 -qt_tutorials: - url: https://github.com/yujinrobot-release/qt_ros-release.git - vcs: git - version: release/kinetic/qt_tutorials/0.2.10-0 -quaternion_operation: - url: https://github.com/OUXT-Polaris/quaternion_operation-release.git - vcs: git - version: release/kinetic/quaternion_operation/0.0.3-1 -radar_msgs: - url: https://github.com/astuff/astuff_sensor_msgs-release.git - vcs: git - version: release/kinetic/radar_msgs/2.3.1-0 -radar_omnipresense: - url: https://github.com/SCU-RSL-ROS/radar_omnipresense-release.git - vcs: git - version: release/kinetic/radar_omnipresense/0.3.0-0 -rail_manipulation_msgs: - url: https://github.com/gt-rail-release/rail_manipulation_msgs-release.git - vcs: git - version: release/kinetic/rail_manipulation_msgs/0.0.12-0 -rail_segmentation: - url: https://github.com/gt-rail-release/rail_segmentation.git - vcs: git - version: release/kinetic/rail_segmentation/0.1.12-0 -range_sensor_layer: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/kinetic/range_sensor_layer/0.3.1-1 -raspi_temperature: - url: https://github.com/bberrevoets/raspi_temperature-release.git - vcs: git - version: release/kinetic/raspi_temperature/0.1.1-0 -raspigibbon_bringup: - url: https://github.com/raspberrypigibbon/raspigibbon_ros-release.git - vcs: git - version: release/kinetic/raspigibbon_bringup/0.2.1-0 -raspigibbon_control: - url: https://github.com/raspberrypigibbon/raspigibbon_sim-release.git - vcs: git - version: release/kinetic/raspigibbon_control/0.0.1-0 -raspigibbon_description: - url: https://github.com/raspberrypigibbon/raspigibbon_ros-release.git - vcs: git - version: release/kinetic/raspigibbon_description/0.2.1-0 -raspigibbon_gazebo: - url: https://github.com/raspberrypigibbon/raspigibbon_sim-release.git - vcs: git - version: release/kinetic/raspigibbon_gazebo/0.0.1-0 -raspigibbon_msgs: - url: https://github.com/raspberrypigibbon/raspigibbon_ros-release.git - vcs: git - version: release/kinetic/raspigibbon_msgs/0.2.1-0 -raspigibbon_ros: - url: https://github.com/raspberrypigibbon/raspigibbon_ros-release.git - vcs: git - version: release/kinetic/raspigibbon_ros/0.2.1-0 -raspigibbon_sim: - url: https://github.com/raspberrypigibbon/raspigibbon_sim-release.git - vcs: git - version: release/kinetic/raspigibbon_sim/0.0.1-0 -raw_description: - url: https://github.com/ipa320/cob_common-release.git - vcs: git - version: release/kinetic/raw_description/0.7.0-1 -razor_imu_9dof: - url: https://github.com/KristofRobot/razor_imu_9dof-release.git - vcs: git - version: release/kinetic/razor_imu_9dof/1.2.0-0 -rb1_base_2dnav: - url: https://github.com/RobotnikAutomation/rb1_base_sim-release.git - vcs: git - version: release/kinetic/rb1_base_2dnav/1.0.2-0 -rb1_base_common: - url: https://github.com/RobotnikAutomation/rb1_base_common-release.git - vcs: git - version: release/kinetic/rb1_base_common/1.1.0-0 -rb1_base_control: - url: https://github.com/RobotnikAutomation/rb1_base_sim-release.git - vcs: git - version: release/kinetic/rb1_base_control/1.0.2-0 -rb1_base_description: - url: https://github.com/RobotnikAutomation/rb1_base_common-release.git - vcs: git - version: release/kinetic/rb1_base_description/1.1.0-0 -rb1_base_gazebo: - url: https://github.com/RobotnikAutomation/rb1_base_sim-release.git - vcs: git - version: release/kinetic/rb1_base_gazebo/1.0.2-0 -rb1_base_pad: - url: https://github.com/RobotnikAutomation/rb1_base_common-release.git - vcs: git - version: release/kinetic/rb1_base_pad/1.1.0-0 -rb1_base_purepursuit: - url: https://github.com/RobotnikAutomation/rb1_base_sim-release.git - vcs: git - version: release/kinetic/rb1_base_purepursuit/1.0.2-0 -rb1_base_sim: - url: https://github.com/RobotnikAutomation/rb1_base_sim-release.git - vcs: git - version: release/kinetic/rb1_base_sim/1.0.2-0 -rbcar_common: - url: https://github.com/RobotnikAutomation/rbcar_common-release.git - vcs: git - version: release/kinetic/rbcar_common/1.0.5-1 -rbcar_control: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_control/1.0.4-1 -rbcar_description: - url: https://github.com/RobotnikAutomation/rbcar_common-release.git - vcs: git - version: release/kinetic/rbcar_description/1.0.5-1 -rbcar_gazebo: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_gazebo/1.0.4-1 -rbcar_joystick: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_joystick/1.0.4-1 -rbcar_pad: - url: https://github.com/RobotnikAutomation/rbcar_common-release.git - vcs: git - version: release/kinetic/rbcar_pad/1.0.5-1 -rbcar_robot_control: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_robot_control/1.0.4-1 -rbcar_sim: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_sim/1.0.4-1 -rbcar_sim_bringup: - url: https://github.com/RobotnikAutomation/rbcar_sim-release.git - vcs: git - version: release/kinetic/rbcar_sim_bringup/1.0.4-1 -rc_cloud_accumulator: - url: https://github.com/roboception-gbp/rc_cloud_accumulator-release.git - vcs: git - version: release/kinetic/rc_cloud_accumulator/1.0.4-0 -rc_common_msgs: - url: https://github.com/roboception-gbp/rc_common_msgs-release.git - vcs: git - version: release/kinetic/rc_common_msgs/0.2.1-1 -rc_dynamics_api: - url: https://github.com/roboception-gbp/rc_dynamics_api-release.git - vcs: git - version: release/kinetic/rc_dynamics_api/0.8.0-1 -rc_genicam_api: - url: https://github.com/roboception-gbp/rc_genicam_api-release.git - vcs: git - version: release/kinetic/rc_genicam_api/2.2.2-1 -rc_hand_eye_calibration_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_hand_eye_calibration_client/2.7.0-1 -rc_pick_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_pick_client/2.7.0-1 -rc_roi_manager_gui: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_roi_manager_gui/2.7.0-1 -rc_tagdetect_client: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_tagdetect_client/2.7.0-1 -rc_visard: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_visard/2.7.0-1 -rc_visard_description: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_visard_description/2.7.0-1 -rc_visard_driver: - url: https://github.com/roboception-gbp/rc_visard-release.git - vcs: git - version: release/kinetic/rc_visard_driver/2.7.0-1 -rcdiscover: - url: https://github.com/roboception-gbp/rcdiscover-release.git - vcs: git - version: release/kinetic/rcdiscover/1.0.0-1 -rdl: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl/1.1.0-0 -rdl_benchmark: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_benchmark/1.1.0-0 -rdl_cmake: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_cmake/1.1.0-0 -rdl_dynamics: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_dynamics/1.1.0-0 -rdl_msgs: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_msgs/1.1.0-0 -rdl_ros_tools: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_ros_tools/1.1.0-0 -rdl_urdfreader: - url: https://gitlab.com/jlack/rdl_release.git - vcs: git - version: release/kinetic/rdl_urdfreader/1.1.0-0 -realsense2_camera: - url: https://github.com/IntelRealSense/realsense-ros-release.git - vcs: git - version: release/kinetic/realsense2_camera/2.2.6-2 -realsense2_description: - url: https://github.com/IntelRealSense/realsense-ros-release.git - vcs: git - version: release/kinetic/realsense2_description/2.2.6-2 -realsense_camera: - url: https://github.com/intel-ros/realsense-release.git - vcs: git - version: release/kinetic/realsense_camera/1.8.1-1 -realtime_tools: - url: https://github.com/ros-gbp/realtime_tools-release.git - vcs: git - version: release/kinetic/realtime_tools/1.11.1-0 -recordit: - url: https://github.com/ipa-jfh/robot_recorder-release.git - vcs: git - version: release/kinetic/recordit/1.0.1-0 -resized_image_transport: - url: https://github.com/tork-a/jsk_recognition-release.git - vcs: git - version: release/kinetic/resized_image_transport/1.2.9-0 -respeaker_ros: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/respeaker_ros/2.1.13-1 -rexrov2_control: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/kinetic/rexrov2_control/0.1.3-0 -rexrov2_description: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/kinetic/rexrov2_description/0.1.3-0 -rexrov2_gazebo: - url: https://github.com/uuvsimulator/rexrov2-release.git - vcs: git - version: release/kinetic/rexrov2_gazebo/0.1.3-0 -rfsm: - url: https://github.com/orocos-gbp/rfsm-release.git - vcs: git - version: release/kinetic/rfsm/1.0.1-0 -rgbd_launch: - url: https://github.com/ros-gbp/rgbd_launch-release.git - vcs: git - version: release/kinetic/rgbd_launch/2.2.2-0 -rh_p12_rn: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn/0.1.0-0 -rh_p12_rn_base_module: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_base_module/0.1.0-0 -rh_p12_rn_base_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_base_module_msgs/0.1.0-0 -rh_p12_rn_description: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_description/0.1.0-0 -rh_p12_rn_gazebo: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_gazebo/0.1.0-0 -rh_p12_rn_gui: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_gui/0.1.0-0 -rh_p12_rn_manager: - url: https://github.com/ROBOTIS-GIT-release/RH-P12-RN-release.git - vcs: git - version: release/kinetic/rh_p12_rn_manager/0.1.0-0 -ridgeback_control: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/kinetic/ridgeback_control/0.2.2-0 -ridgeback_description: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/kinetic/ridgeback_description/0.2.2-0 -ridgeback_desktop: - url: https://github.com/clearpath-gbp/ridgeback_desktop-release.git - vcs: git - version: release/kinetic/ridgeback_desktop/0.1.1-0 -ridgeback_gazebo: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/kinetic/ridgeback_gazebo/0.0.3-0 -ridgeback_gazebo_plugins: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/kinetic/ridgeback_gazebo_plugins/0.0.3-0 -ridgeback_msgs: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/kinetic/ridgeback_msgs/0.2.2-0 -ridgeback_navigation: - url: https://github.com/clearpath-gbp/ridgeback-release.git - vcs: git - version: release/kinetic/ridgeback_navigation/0.2.2-0 -ridgeback_simulator: - url: https://github.com/clearpath-gbp/ridgeback_simulator-release.git - vcs: git - version: release/kinetic/ridgeback_simulator/0.0.3-0 -ridgeback_viz: - url: https://github.com/clearpath-gbp/ridgeback_desktop-release.git - vcs: git - version: release/kinetic/ridgeback_viz/0.1.1-0 -robot_activity: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/kinetic/robot_activity/0.1.1-0 -robot_activity_msgs: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/kinetic/robot_activity_msgs/0.1.1-0 -robot_activity_tutorials: - url: https://github.com/snt-robotics/robot_activity-release.git - vcs: git - version: release/kinetic/robot_activity_tutorials/0.1.1-0 -robot_calibration: - url: https://github.com/ros-gbp/robot_calibration-release.git - vcs: git - version: release/kinetic/robot_calibration/0.6.0-0 -robot_calibration_msgs: - url: https://github.com/ros-gbp/robot_calibration-release.git - vcs: git - version: release/kinetic/robot_calibration_msgs/0.6.0-0 -robot_controllers: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/kinetic/robot_controllers/0.5.2-0 -robot_controllers_interface: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/kinetic/robot_controllers_interface/0.5.2-0 -robot_controllers_msgs: - url: https://github.com/fetchrobotics-gbp/robot_controllers-release.git - vcs: git - version: release/kinetic/robot_controllers_msgs/0.5.2-0 -robot_localization: - url: https://github.com/cra-ros-pkg/robot_localization-release.git - vcs: git - version: release/kinetic/robot_localization/2.4.8-1 -robot_mechanism_controllers: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/robot_mechanism_controllers/1.10.14-0 -robot_navigation: - url: https://github.com/locusrobotics/robot_navigation-release.git - vcs: git - version: release/kinetic/robot_navigation/0.2.5-0 -robot_pose_ekf: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/robot_pose_ekf/1.14.4-0 -robot_pose_publisher: - url: https://github.com/gt-rail-release/robot_pose_publisher-release.git - vcs: git - version: release/kinetic/robot_pose_publisher/0.2.4-0 -robot_recorder: - url: https://github.com/ipa-jfh/robot_recorder-release.git - vcs: git - version: release/kinetic/robot_recorder/1.0.1-0 -robot_self_filter: - url: https://github.com/pr2-gbp/robot_self_filter-gbp.git - vcs: git - version: release/kinetic/robot_self_filter/0.1.30-1 -robot_setup_tf_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/robot_setup_tf_tutorial/0.2.3-0 -robot_statemachine: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/robot_statemachine/1.1.1-1 -robot_upstart: - url: https://github.com/clearpath-gbp/robot_upstart-release.git - vcs: git - version: release/kinetic/robot_upstart/0.3.0-0 -robotis_controller: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Framework-release.git - vcs: git - version: release/kinetic/robotis_controller/0.2.9-0 -robotis_controller_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Framework-msgs-release.git - vcs: git - version: release/kinetic/robotis_controller_msgs/0.1.4-0 -robotis_device: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Framework-release.git - vcs: git - version: release/kinetic/robotis_device/0.2.9-0 -robotis_framework: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Framework-release.git - vcs: git - version: release/kinetic/robotis_framework/0.2.9-0 -robotis_framework_common: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Framework-release.git - vcs: git - version: release/kinetic/robotis_framework_common/0.2.9-0 -robotis_manipulator: - url: https://github.com/ROBOTIS-GIT-release/robotis_manipulator-release.git - vcs: git - version: release/kinetic/robotis_manipulator/1.0.0-0 -robotis_math: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Math-release.git - vcs: git - version: release/kinetic/robotis_math/0.2.6-0 -robotis_op3: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-release.git - vcs: git - version: release/kinetic/robotis_op3/0.2.1-0 -robotis_op3_common: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-Common-release.git - vcs: git - version: release/kinetic/robotis_op3_common/0.1.1-0 -robotis_op3_demo: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_demo-release.git - vcs: git - version: release/kinetic/robotis_op3_demo/0.1.0-0 -robotis_op3_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-OP3-msgs-release.git - vcs: git - version: release/kinetic/robotis_op3_msgs/0.1.1-0 -robotis_op3_tools: - url: https://github.com/ROBOTIS-GIT-release/robotis_op3_tools-release.git - vcs: git - version: release/kinetic/robotis_op3_tools/0.2.2-0 -robotis_utility: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Utility-release.git - vcs: git - version: release/kinetic/robotis_utility/0.1.3-0 -robotnik_msgs: - url: https://github.com/RobotnikAutomation/robotnik_msgs-release.git - vcs: git - version: release/kinetic/robotnik_msgs/0.2.5-0 -robotnik_sensors: - url: https://github.com/RobotnikAutomation/robotnik_sensors-release.git - vcs: git - version: release/kinetic/robotnik_sensors/1.1.2-0 -roch: - url: https://github.com/SawYerRobotics-release/roch-release.git - vcs: git - version: release/kinetic/roch/2.0.12-0 -roch_base: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_base/2.0.15-0 -roch_bringup: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_bringup/2.0.15-0 -roch_capabilities: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_capabilities/2.0.15-0 -roch_control: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_control/2.0.15-0 -roch_description: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_description/2.0.15-0 -roch_follower: - url: https://github.com/SawYerRobotics-release/roch-release.git - vcs: git - version: release/kinetic/roch_follower/2.0.12-0 -roch_ftdi: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_ftdi/2.0.15-0 -roch_gazebo: - url: https://github.com/SawYerRobotics-release/roch_simulator-release.git - vcs: git - version: release/kinetic/roch_gazebo/2.0.12-5 -roch_msgs: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_msgs/2.0.15-0 -roch_navigation: - url: https://github.com/SawYerRobotics-release/roch-release.git - vcs: git - version: release/kinetic/roch_navigation/2.0.12-0 -roch_rapps: - url: https://github.com/SawYerRobotics-release/roch-release.git - vcs: git - version: release/kinetic/roch_rapps/2.0.12-0 -roch_robot: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_robot/2.0.15-0 -roch_safety_controller: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_safety_controller/2.0.15-0 -roch_sensorpc: - url: https://github.com/SawYerRobotics-release/roch_robot-release.git - vcs: git - version: release/kinetic/roch_sensorpc/2.0.15-0 -roch_simulator: - url: https://github.com/SawYerRobotics-release/roch_simulator-release.git - vcs: git - version: release/kinetic/roch_simulator/2.0.12-5 -roch_teleop: - url: https://github.com/SawYerRobotics-release/roch-release.git - vcs: git - version: release/kinetic/roch_teleop/2.0.12-0 -roch_viz: - url: https://github.com/SawYerRobotics-release/roch_viz-release.git - vcs: git - version: release/kinetic/roch_viz/2.0.10-0 -rocon_app_manager: - url: https://github.com/yujinrobot-release/rocon_app_platform-release.git - vcs: git - version: release/kinetic/rocon_app_manager/0.9.1-0 -rocon_app_manager_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_app_manager_msgs/0.9.0-1 -rocon_app_platform: - url: https://github.com/yujinrobot-release/rocon_app_platform-release.git - vcs: git - version: release/kinetic/rocon_app_platform/0.9.1-0 -rocon_app_utilities: - url: https://github.com/yujinrobot-release/rocon_app_platform-release.git - vcs: git - version: release/kinetic/rocon_app_utilities/0.9.1-0 -rocon_apps: - url: https://github.com/yujinrobot-release/rocon_app_platform-release.git - vcs: git - version: release/kinetic/rocon_apps/0.9.1-0 -rocon_bubble_icons: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_bubble_icons/0.3.2-1 -rocon_console: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_console/0.3.2-1 -rocon_device_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_device_msgs/0.9.0-1 -rocon_ebnf: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_ebnf/0.3.2-1 -rocon_gateway: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_gateway/0.8.1-2 -rocon_gateway_tests: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_gateway_tests/0.8.1-2 -rocon_gateway_utils: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_gateway_utils/0.8.1-2 -rocon_hub: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_hub/0.8.1-2 -rocon_hub_client: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_hub_client/0.8.1-2 -rocon_icons: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_icons/0.3.2-1 -rocon_interaction_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_interaction_msgs/0.9.0-1 -rocon_interactions: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_interactions/0.3.2-1 -rocon_launch: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_launch/0.3.2-1 -rocon_master_info: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_master_info/0.3.2-1 -rocon_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_msgs/0.9.0-1 -rocon_multimaster: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_multimaster/0.8.1-2 -rocon_python_comms: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_python_comms/0.3.2-1 -rocon_python_redis: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_python_redis/0.3.2-1 -rocon_python_utils: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_python_utils/0.3.2-1 -rocon_python_wifi: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_python_wifi/0.3.2-1 -rocon_semantic_version: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_semantic_version/0.3.2-1 -rocon_service_pair_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_service_pair_msgs/0.9.0-1 -rocon_std_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_std_msgs/0.9.0-1 -rocon_test: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_test/0.8.1-2 -rocon_tools: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_tools/0.3.2-1 -rocon_tutorial_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/rocon_tutorial_msgs/0.9.0-1 -rocon_unreliable_experiments: - url: https://github.com/yujinrobot-release/rocon_multimaster-release.git - vcs: git - version: release/kinetic/rocon_unreliable_experiments/0.8.1-2 -rocon_uri: - url: https://github.com/yujinrobot-release/rocon_tools-release.git - vcs: git - version: release/kinetic/rocon_uri/0.3.2-1 -rodi_robot: - url: https://github.com/benjayah/rodi_robot-release.git - vcs: git - version: release/kinetic/rodi_robot/0.0.1-0 -romeo_bringup: - url: https://github.com/ros-aldebaran/romeo_robot-release.git - vcs: git - version: release/kinetic/romeo_bringup/0.1.5-0 -romeo_control: - url: https://github.com/ros-aldebaran/romeo_virtual-release.git - vcs: git - version: release/kinetic/romeo_control/0.2.3-0 -romeo_description: - url: https://github.com/ros-aldebaran/romeo_robot-release.git - vcs: git - version: release/kinetic/romeo_description/0.1.5-0 -romeo_gazebo_plugin: - url: https://github.com/ros-aldebaran/romeo_virtual-release.git - vcs: git - version: release/kinetic/romeo_gazebo_plugin/0.2.3-0 -romeo_moveit_config: - url: https://github.com/ros-aldebaran/romeo_moveit_config-release.git - vcs: git - version: release/kinetic/romeo_moveit_config/0.2.8-0 -romeo_robot: - url: https://github.com/ros-aldebaran/romeo_robot-release.git - vcs: git - version: release/kinetic/romeo_robot/0.1.5-0 -romeo_sensors_py: - url: https://github.com/ros-aldebaran/romeo_robot-release.git - vcs: git - version: release/kinetic/romeo_sensors_py/0.1.5-0 -roomba_stage: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/roomba_stage/0.2.3-0 -roomblock: - url: https://github.com/tork-a/roomblock-release.git - vcs: git - version: release/kinetic/roomblock/0.0.2-0 -roomblock_bringup: - url: https://github.com/tork-a/roomblock-release.git - vcs: git - version: release/kinetic/roomblock_bringup/0.0.2-0 -roomblock_description: - url: https://github.com/tork-a/roomblock-release.git - vcs: git - version: release/kinetic/roomblock_description/0.0.2-0 -roomblock_mapping: - url: https://github.com/tork-a/roomblock-release.git - vcs: git - version: release/kinetic/roomblock_mapping/0.0.2-0 -roomblock_navigation: - url: https://github.com/tork-a/roomblock-release.git - vcs: git - version: release/kinetic/roomblock_navigation/0.0.2-0 -ros_apache2: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/ros_apache2/1.0.7-0 -ros_canopen: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/ros_canopen/0.7.11-1 -ros_control: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/ros_control/0.13.3-0 -ros_control_boilerplate: - url: https://github.com/davetcoleman/ros_control_boilerplate-release.git - vcs: git - version: release/kinetic/ros_control_boilerplate/0.4.1-0 -ros_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/ros_controllers/0.13.5-0 -ros_emacs_utils: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/kinetic/ros_emacs_utils/0.4.12-0 -ros_ethercat_eml: - url: https://github.com/shadow-robot/ros_ethercat_eml-release.git - vcs: git - version: release/kinetic/ros_ethercat_eml/0.3.1-0 -ros_explorer: - url: https://github.com/jstnhuang-release/ros_explorer-release.git - vcs: git - version: release/kinetic/ros_explorer/0.1.0-0 -ros_introspection: - url: https://github.com/wu-robotics/roscompile-release.git - vcs: git - version: release/kinetic/ros_introspection/1.0.1-0 -ros_madplay_player: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Utility-release.git - vcs: git - version: release/kinetic/ros_madplay_player/0.1.3-0 -ros_monitoring_msgs: - url: https://github.com/aws-gbp/ros_monitoring_msgs-release.git - vcs: git - version: release/kinetic/ros_monitoring_msgs/1.0.1-1 -ros_mpg321_player: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-Utility-release.git - vcs: git - version: release/kinetic/ros_mpg321_player/0.1.3-0 -ros_numpy: - url: https://github.com/eric-wieser/ros_numpy-release.git - vcs: git - version: release/kinetic/ros_numpy/0.0.2-0 -ros_peerjs: - url: https://github.com/easymov/ros_peerjs-release.git - vcs: git - version: release/kinetic/ros_peerjs/0.1.8-0 -ros_pytest: - url: https://github.com/machinekoder/ros_pytest-release.git - vcs: git - version: release/kinetic/ros_pytest/0.1.2-3 -ros_realtime: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/kinetic/ros_realtime/1.0.25-0 -ros_reflexxes: - url: https://github.com/KITrobotics/ipr_extern-release.git - vcs: git - version: release/kinetic/ros_reflexxes/0.8.8-0 -ros_speech_recognition: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/ros_speech_recognition/2.1.13-1 -ros_type_introspection: - url: https://github.com/facontidavide/ros_type_introspection-release.git - vcs: git - version: release/kinetic/ros_type_introspection/1.3.3-1 -ros_wild: - url: https://github.com/yuma-m/ros_wild-release.git - vcs: git - version: release/kinetic/ros_wild/0.5.0-0 -rosapi: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/kinetic/rosapi/0.11.3-1 -rosatomic: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/kinetic/rosatomic/1.0.25-0 -rosauth: - url: https://github.com/gt-rail-release/rosauth-release.git - vcs: git - version: release/kinetic/rosauth/0.1.7-0 -rosbag_pandas: - url: https://github.com/eurogroep/rosbag_pandas-release.git - vcs: git - version: release/kinetic/rosbag_pandas/0.5.3-0 -rosbaglive: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/kinetic/rosbaglive/0.2.4-0 -rosbash_params: - url: https://github.com/peci1/rosbash_params-release.git - vcs: git - version: release/kinetic/rosbash_params/1.0.2-0 -rosbridge_library: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/kinetic/rosbridge_library/0.11.3-1 -rosbridge_msgs: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/kinetic/rosbridge_msgs/0.11.3-1 -rosbridge_server: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/kinetic/rosbridge_server/0.11.3-1 -rosbridge_suite: - url: https://github.com/RobotWebTools-release/rosbridge_suite-release.git - vcs: git - version: release/kinetic/rosbridge_suite/0.11.3-1 -roscompile: - url: https://github.com/wu-robotics/roscompile-release.git - vcs: git - version: release/kinetic/roscompile/1.0.1-0 -rosdiagnostic: - url: https://github.com/ros-gbp/diagnostics-release.git - vcs: git - version: release/kinetic/rosdiagnostic/1.9.3-0 -rosdoc_lite: - url: https://github.com/ros-gbp/rosdoc_lite-release.git - vcs: git - version: release/kinetic/rosdoc_lite/0.2.9-0 -rosemacs: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/kinetic/rosemacs/0.4.12-0 -roseus: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/kinetic/roseus/1.7.4-0 -roseus_mongo: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/kinetic/roseus_mongo/1.7.4-0 -roseus_smach: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/kinetic/roseus_smach/1.7.4-0 -roseus_tutorials: - url: https://github.com/tork-a/jsk_roseus-release.git - vcs: git - version: release/kinetic/roseus_tutorials/1.7.4-0 -rosflight: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight/1.0.0-1 -rosflight_firmware: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight_firmware/1.0.0-1 -rosflight_msgs: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight_msgs/1.0.0-1 -rosflight_pkgs: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight_pkgs/1.0.0-1 -rosflight_sim: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight_sim/1.0.0-1 -rosflight_utils: - url: https://github.com/rosflight/rosflight-release.git - vcs: git - version: release/kinetic/rosflight_utils/1.0.0-1 -rosfmt: - url: https://github.com/xqms/rosfmt-release.git - vcs: git - version: release/kinetic/rosfmt/6.0.0-0 -rosjava: - url: https://github.com/rosjava-release/rosjava-release.git - vcs: git - version: release/kinetic/rosjava/0.3.0-0 -rosjava_bootstrap: - url: https://github.com/rosjava-release/rosjava_bootstrap-release.git - vcs: git - version: release/kinetic/rosjava_bootstrap/0.3.3-1 -rosjava_build_tools: - url: https://github.com/rosjava-release/rosjava_build_tools-release.git - vcs: git - version: release/kinetic/rosjava_build_tools/0.3.3-1 -rosjava_core: - url: https://github.com/rosjava-release/rosjava_core-release.git - vcs: git - version: release/kinetic/rosjava_core/0.3.7-0 -rosjava_extras: - url: https://github.com/rosjava-release/rosjava_extras-release.git - vcs: git - version: release/kinetic/rosjava_extras/0.3.4-0 -rosjava_messages: - url: https://github.com/rosjava-release/rosjava_messages-release.git - vcs: git - version: release/kinetic/rosjava_messages/0.3.0-0 -rosjava_test_msgs: - url: https://github.com/rosjava-release/rosjava_test_msgs-release.git - vcs: git - version: release/kinetic/rosjava_test_msgs/0.3.0-0 -rosjson: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/rosjson/1.0.7-0 -roslisp_common: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/roslisp_common/0.2.12-1 -roslisp_repl: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/kinetic/roslisp_repl/0.4.12-0 -roslisp_utilities: - url: https://github.com/ros-gbp/roslisp_common-release.git - vcs: git - version: release/kinetic/roslisp_utilities/0.2.12-1 -rosmon: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/kinetic/rosmon/2.1.1-1 -rosmon_core: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/kinetic/rosmon_core/2.1.1-1 -rosmon_msgs: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/kinetic/rosmon_msgs/2.1.1-1 -rosnode_rtc: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/rosnode_rtc/1.4.2-0 -rosparam_handler: - url: https://github.com/cbandera/rosparam_handler-release.git - vcs: git - version: release/kinetic/rosparam_handler/0.1.4-0 -rosparam_shortcuts: - url: https://github.com/davetcoleman/rosparam_shortcuts-release.git - vcs: git - version: release/kinetic/rosparam_shortcuts/0.2.1-0 -rospatlite: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/rospatlite/2.1.13-1 -rospilot: - url: https://github.com/rospilot/rospilot-release.git - vcs: git - version: release/kinetic/rospilot/1.4.1-0 -rosping: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/rosping/2.1.13-1 -rospy_message_converter: - url: https://github.com/uos-gbp/rospy_message_converter-release.git - vcs: git - version: release/kinetic/rospy_message_converter/0.5.0-0 -rospy_wrapper: - url: https://github.com/sean-hackett/rospy_wrapper-release.git - vcs: git - version: release/kinetic/rospy_wrapper/1.0.0-1 -rosrt: - url: https://github.com/ros-gbp/ros_realtime-release.git - vcs: git - version: release/kinetic/rosrt/1.0.25-0 -rosserial: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial/0.7.7-0 -rosserial_arduino: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_arduino/0.7.7-0 -rosserial_client: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_client/0.7.7-0 -rosserial_embeddedlinux: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_embeddedlinux/0.7.7-0 -rosserial_leonardo_cmake: - url: https://github.com/clearpath-gbp/rosserial_leonardo_cmake-release.git - vcs: git - version: release/kinetic/rosserial_leonardo_cmake/0.1.4-0 -rosserial_mbed: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_mbed/0.7.7-0 -rosserial_msgs: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_msgs/0.7.7-0 -rosserial_python: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_python/0.7.7-0 -rosserial_server: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_server/0.7.7-0 -rosserial_tivac: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_tivac/0.7.7-0 -rosserial_windows: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_windows/0.7.7-0 -rosserial_xbee: - url: https://github.com/ros-gbp/rosserial-release.git - vcs: git - version: release/kinetic/rosserial_xbee/0.7.7-0 -rostate_machine: - url: https://github.com/OUXT-Polaris/rostate_machine-release.git - vcs: git - version: release/kinetic/rostate_machine/0.0.2-1 -rostful: - url: https://github.com/pyros-dev/rostful-rosrelease.git - vcs: git - version: release/kinetic/rostful/0.2.1-0 -rostune: - url: https://github.com/roboskel/rostune-release.git - vcs: git - version: release/kinetic/rostune/1.0.7-0 -rostwitter: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/rostwitter/2.1.13-1 -rosweb: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/rosweb/1.0.7-0 -roswww: - url: https://github.com/ros-gbp/roswww-release.git - vcs: git - version: release/kinetic/roswww/0.1.12-0 -rotate_recovery: - url: https://github.com/ros-gbp/navigation-release.git - vcs: git - version: release/kinetic/rotate_recovery/1.14.4-0 -route_network: - url: https://github.com/ros-geographic-info/open_street_map-release.git - vcs: git - version: release/kinetic/route_network/0.2.4-0 -rplidar_ros: - url: https://github.com/Slamtec/rplidar_ros-release.git - vcs: git - version: release/kinetic/rplidar_ros/1.7.0-0 -rqt: - url: https://github.com/ros-gbp/rqt-release.git - vcs: git - version: release/kinetic/rqt/0.5.0-0 -rqt_bhand: - url: https://github.com/RobotnikAutomation/barrett_hand-release.git - vcs: git - version: release/kinetic/rqt_bhand/0.1.2-0 -rqt_controller_manager: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/rqt_controller_manager/0.13.3-0 -rqt_drone_teleop: - url: https://github.com/JdeRobot/drones-release.git - vcs: git - version: release/kinetic/rqt_drone_teleop/1.0.1-1 -rqt_ez_publisher: - url: https://github.com/OTL/rqt_ez_publisher-release.git - vcs: git - version: release/kinetic/rqt_ez_publisher/0.5.0-0 -rqt_gauges: - url: https://github.com/UTNuclearRoboticsPublic/gauges-release.git - vcs: git - version: release/kinetic/rqt_gauges/1.0.7-0 -rqt_ground_robot_teleop: - url: https://github.com/JdeRobot/ground_robots-release.git - vcs: git - version: release/kinetic/rqt_ground_robot_teleop/0.0.1-1 -rqt_joint_trajectory_controller: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/rqt_joint_trajectory_controller/0.13.5-0 -rqt_joint_trajectory_plot: - url: https://github.com/tork-a/rqt_joint_trajectory_plot-release.git - vcs: git - version: release/kinetic/rqt_joint_trajectory_plot/0.0.2-0 -rqt_launchtree: - url: https://github.com/pschillinger/rqt_launchtree-release.git - vcs: git - version: release/kinetic/rqt_launchtree/0.2.0-0 -rqt_multiplot: - url: https://github.com/anybotics/rqt_multiplot_plugin-release.git - vcs: git - version: release/kinetic/rqt_multiplot/0.0.10-0 -rqt_pr2_dashboard: - url: https://github.com/ros-gbp/rqt_pr2_dashboard-release.git - vcs: git - version: release/kinetic/rqt_pr2_dashboard/0.4.0-0 -rqt_py_trees: - url: https://github.com/stonier/rqt_py_trees-release.git - vcs: git - version: release/kinetic/rqt_py_trees/0.3.1-0 -rqt_rosmon: - url: https://github.com/xqms/rosmon-release.git - vcs: git - version: release/kinetic/rqt_rosmon/2.1.1-1 -rqt_wrapper: - url: https://github.com/yujinrobot-release/rqt_wrapper-release.git - vcs: git - version: release/kinetic/rqt_wrapper/0.1.4-0 -rr_control_input_manager: - url: https://github.com/RoverRobotics-release/rr_openrover_stack-release.git - vcs: git - version: release/kinetic/rr_control_input_manager/0.7.2-1 -rr_openrover_basic: - url: https://github.com/RoverRobotics-release/rr_openrover_basic-release.git - vcs: git - version: release/kinetic/rr_openrover_basic/0.7.1-2 -rr_openrover_driver: - url: https://github.com/RoverRobotics-release/rr_openrover_stack-release.git - vcs: git - version: release/kinetic/rr_openrover_driver/0.7.2-1 -rr_openrover_driver_msgs: - url: https://github.com/RoverRobotics-release/rr_openrover_stack-release.git - vcs: git - version: release/kinetic/rr_openrover_driver_msgs/0.7.2-1 -rr_openrover_stack: - url: https://github.com/RoverRobotics-release/rr_openrover_stack-release.git - vcs: git - version: release/kinetic/rr_openrover_stack/0.7.2-1 -rr_swiftnav_piksi: - url: https://github.com/RoverRobotics/rr_swiftnav_piksi-release.git - vcs: git - version: release/kinetic/rr_swiftnav_piksi/0.0.1-1 -rslidar: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/kinetic/rslidar/1.0.2-0 -rslidar_driver: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/kinetic/rslidar_driver/1.0.2-0 -rslidar_msgs: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/kinetic/rslidar_msgs/1.0.2-0 -rslidar_pointcloud: - url: https://github.com/CPFL/robosense-release.git - vcs: git - version: release/kinetic/rslidar_pointcloud/1.0.2-0 -rsm_additions: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/rsm_additions/1.1.1-1 -rsm_core: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/rsm_core/1.1.1-1 -rsm_msgs: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/rsm_msgs/1.1.1-1 -rsm_rqt_plugins: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/rsm_rqt_plugins/1.1.1-1 -rsm_rviz_plugins: - url: https://github.com/MarcoStb1993/robot_statemachine-release.git - vcs: git - version: release/kinetic/rsm_rviz_plugins/1.1.1-1 -rtabmap: - url: https://github.com/introlab/rtabmap-release.git - vcs: git - version: release/kinetic/rtabmap/0.19.3-1 -rtabmap_ros: - url: https://github.com/introlab/rtabmap_ros-release.git - vcs: git - version: release/kinetic/rtabmap_ros/0.19.3-1 -rtctree: - url: https://github.com/tork-a/rtctree-release.git - vcs: git - version: release/kinetic/rtctree/3.0.1-0 -rtmbuild: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/rtmbuild/1.4.2-0 -rtmros_common: - url: https://github.com/tork-a/rtmros_common-release.git - vcs: git - version: release/kinetic/rtmros_common/1.4.2-0 -rtmros_hironx: - url: https://github.com/tork-a/rtmros_hironx-release.git - vcs: git - version: release/kinetic/rtmros_hironx/2.1.1-0 -rtmros_nextage: - url: https://github.com/tork-a/rtmros_nextage-release.git - vcs: git - version: release/kinetic/rtmros_nextage/0.8.5-1 -rtshell: - url: https://github.com/tork-a/rtshell-release.git - vcs: git - version: release/kinetic/rtshell/3.0.1-2 -rtsprofile: - url: https://github.com/tork-a/rtsprofile-release.git - vcs: git - version: release/kinetic/rtsprofile/2.0.0-0 -rtt: - url: https://github.com/orocos-gbp/rtt-release.git - vcs: git - version: release/kinetic/rtt/2.9.2-1 -rtt_actionlib: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_actionlib/2.9.2-1 -rtt_actionlib_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_actionlib_msgs/2.9.2-1 -rtt_common_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_common_msgs/2.9.2-1 -rtt_control_msgs: - url: https://github.com/orocos-gbp/rtt_ros_control-release.git - vcs: git - version: release/kinetic/rtt_control_msgs/0.1.1-0 -rtt_controller_manager_msgs: - url: https://github.com/orocos-gbp/rtt_ros_control-release.git - vcs: git - version: release/kinetic/rtt_controller_manager_msgs/0.1.1-0 -rtt_diagnostic_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_diagnostic_msgs/2.9.2-1 -rtt_dynamic_reconfigure: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_dynamic_reconfigure/2.9.2-1 -rtt_geometry: - url: https://github.com/orocos-gbp/rtt_geometry-release.git - vcs: git - version: release/kinetic/rtt_geometry/2.9.3-1 -rtt_geometry_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_geometry_msgs/2.9.2-1 -rtt_kdl_conversions: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_kdl_conversions/2.9.2-1 -rtt_nav_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_nav_msgs/2.9.2-1 -rtt_ros: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_ros/2.9.2-1 -rtt_ros_comm: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_ros_comm/2.9.2-1 -rtt_ros_integration: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_ros_integration/2.9.2-1 -rtt_ros_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_ros_msgs/2.9.2-1 -rtt_rosclock: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rosclock/2.9.2-1 -rtt_roscomm: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_roscomm/2.9.2-1 -rtt_rosdeployment: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rosdeployment/2.9.2-1 -rtt_rosgraph_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rosgraph_msgs/2.9.2-1 -rtt_rosnode: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rosnode/2.9.2-1 -rtt_rospack: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rospack/2.9.2-1 -rtt_rosparam: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_rosparam/2.9.2-1 -rtt_sensor_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_sensor_msgs/2.9.2-1 -rtt_shape_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_shape_msgs/2.9.2-1 -rtt_std_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_std_msgs/2.9.2-1 -rtt_std_srvs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_std_srvs/2.9.2-1 -rtt_stereo_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_stereo_msgs/2.9.2-1 -rtt_tf: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_tf/2.9.2-1 -rtt_trajectory_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_trajectory_msgs/2.9.2-1 -rtt_visualization_msgs: - url: https://github.com/orocos-gbp/rtt_ros_integration-release.git - vcs: git - version: release/kinetic/rtt_visualization_msgs/2.9.2-1 -rv4fl_moveit_config: - url: https://github.com/tork-a/melfa_robot-release.git - vcs: git - version: release/kinetic/rv4fl_moveit_config/0.0.4-0 -rv7fl_moveit_config: - url: https://github.com/tork-a/melfa_robot-release.git - vcs: git - version: release/kinetic/rv7fl_moveit_config/0.0.4-0 -rviz_imu_plugin: - url: https://github.com/uos-gbp/imu_tools-release.git - vcs: git - version: release/kinetic/rviz_imu_plugin/1.1.7-1 -rviz_recorder_buttons: - url: https://github.com/ipa-jfh/robot_recorder-release.git - vcs: git - version: release/kinetic/rviz_recorder_buttons/1.0.1-0 -safe_teleop_base: - url: https://github.com/ros-gbp/shared_autonomy_manipulation-release.git - vcs: git - version: release/kinetic/safe_teleop_base/0.0.2-0 -safe_teleop_stage: - url: https://github.com/ros-gbp/shared_autonomy_manipulation-release.git - vcs: git - version: release/kinetic/safe_teleop_stage/0.0.2-0 -safety_limiter: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/safety_limiter/0.4.2-1 -sainsmart_relay_usb: - url: https://github.com/DataspeedInc-release/sainsmart_relay_usb-release.git - vcs: git - version: release/kinetic/sainsmart_relay_usb/0.0.2-0 -sand_island: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/kinetic/sand_island/0.0.1-1 -sbg_driver: - url: https://github.com/SBG-Systems/sbg_ros_driver-release.git - vcs: git - version: release/kinetic/sbg_driver/1.1.7-0 -sbpl: - url: https://github.com/ros-gbp/sbpl-release.git - vcs: git - version: release/kinetic/sbpl/1.3.1-0 -sbpl_lattice_planner: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/sbpl_lattice_planner/0.2.1-0 -sbpl_recovery: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/sbpl_recovery/0.2.1-0 -scan_to_cloud_converter: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/scan_to_cloud_converter/0.3.2-0 -scan_tools: - url: https://github.com/ros-gbp/scan_tools-release.git - vcs: git - version: release/kinetic/scan_tools/0.3.2-0 -scheduler_msgs: - url: https://github.com/yujinrobot-release/rocon_msgs-release.git - vcs: git - version: release/kinetic/scheduler_msgs/0.9.0-1 -schunk_canopen_driver: - url: https://github.com/fzi-forschungszentrum-informatik/schunk_canopen_driver-release.git - vcs: git - version: release/kinetic/schunk_canopen_driver/1.0.7-0 -schunk_description: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_description/0.6.13-1 -schunk_libm5api: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_libm5api/0.6.13-1 -schunk_modular_robotics: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_modular_robotics/0.6.13-1 -schunk_powercube_chain: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_powercube_chain/0.6.13-1 -schunk_sdh: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_sdh/0.6.13-1 -schunk_simulated_tactile_sensors: - url: https://github.com/ipa320/schunk_modular_robotics-release.git - vcs: git - version: release/kinetic/schunk_simulated_tactile_sensors/0.6.13-1 -schunk_svh_driver: - url: https://github.com/fzi-forschungszentrum-informatik/schunk_svh_driver-release.git - vcs: git - version: release/kinetic/schunk_svh_driver/0.2.0-0 -scratch4robots: - url: https://github.com/JdeRobot/Scratch4Robots-release.git - vcs: git - version: release/kinetic/scratch4robots/0.0.2-0 -sdhlibrary_cpp: - url: https://github.com/ipab-slmc/SDHLibrary-CPP-release.git - vcs: git - version: release/kinetic/sdhlibrary_cpp/0.2.10-1 -seed_smartactuator_sdk: - url: https://github.com/seed-solutions/seed_smartactuator_sdk-release.git - vcs: git - version: release/kinetic/seed_smartactuator_sdk/0.0.3-1 -semantic_point_annotator: - url: https://github.com/pr2-gbp/pr2_navigation-release.git - vcs: git - version: release/kinetic/semantic_point_annotator/0.1.28-0 -sensor_module_tutorial: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/sensor_module_tutorial/0.2.0-0 -serial: - url: https://github.com/wjwwood/serial-release.git - vcs: git - version: release/kinetic/serial/1.2.1-0 -serial_utils: - url: https://github.com/wjwwood/serial_utils-release.git - vcs: git - version: release/kinetic/serial_utils/0.1.0-0 -service_tools: - url: https://github.com/ipa320/cob_command_tools-release.git - vcs: git - version: release/kinetic/service_tools/0.6.14-1 -settlerlib: - url: https://github.com/ros-gbp/calibration-release.git - vcs: git - version: release/kinetic/settlerlib/0.10.14-0 -sick_safetyscanners: - url: https://github.com/SICKAG/sick_safetyscanners-release.git - vcs: git - version: release/kinetic/sick_safetyscanners/1.0.3-1 -sick_scan: - url: https://github.com/SICKAG/sick_scan-release.git - vcs: git - version: release/kinetic/sick_scan/1.3.21-0 -sick_tim: - url: https://github.com/uos-gbp/sick_tim-release.git - vcs: git - version: release/kinetic/sick_tim/0.0.16-1 -sick_visionary_t: - url: https://github.com/SICKAG/sick_visionary_t-release.git - vcs: git - version: release/kinetic/sick_visionary_t/0.0.5-0 -sick_visionary_t_driver: - url: https://github.com/SICKAG/sick_visionary_t-release.git - vcs: git - version: release/kinetic/sick_visionary_t_driver/0.0.5-0 -sicktoolbox: - url: https://github.com/ros-gbp/sicktoolbox-release.git - vcs: git - version: release/kinetic/sicktoolbox/1.0.104-2 -sicktoolbox_wrapper: - url: https://github.com/ros-gbp/sicktoolbox_wrapper-release.git - vcs: git - version: release/kinetic/sicktoolbox_wrapper/2.5.4-1 -simple_arm: - url: https://github.com/danielsnider/simple_arm-release.git - vcs: git - version: release/kinetic/simple_arm/0.1.0-0 -simple_drive: - url: https://github.com/danielsnider/simple_drive-release.git - vcs: git - version: release/kinetic/simple_drive/0.1.0-0 -simple_grasping: - url: https://github.com/ros-gbp/simple_grasping-release.git - vcs: git - version: release/kinetic/simple_grasping/0.2.2-0 -simple_message: - url: https://github.com/ros-industrial-release/industrial_core-release.git - vcs: git - version: release/kinetic/simple_message/0.7.0-0 -simple_navigation_goals_tutorial: - url: https://github.com/ros-gbp/navigation_tutorials-release.git - vcs: git - version: release/kinetic/simple_navigation_goals_tutorial/0.2.3-0 -single_joint_position_action: - url: https://github.com/pr2-gbp/pr2_controllers-release.git - vcs: git - version: release/kinetic/single_joint_position_action/1.10.14-0 -skybiometry_ros: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/skybiometry_ros/0.0.4-0 -slam_constructor: - url: https://github.com/OSLL/slam_constructor-release.git - vcs: git - version: release/kinetic/slam_constructor/0.9.3-0 -slam_gmapping: - url: https://github.com/ros-gbp/slam_gmapping-release.git - vcs: git - version: release/kinetic/slam_gmapping/1.3.10-0 -slam_karto: - url: https://github.com/ros-gbp/slam_karto-release.git - vcs: git - version: release/kinetic/slam_karto/0.7.3-0 -slic: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/slic/2.1.13-1 -slime_ros: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/kinetic/slime_ros/0.4.12-0 -slime_wrapper: - url: https://github.com/code-iai-release/ros_emacs_utils-release.git - vcs: git - version: release/kinetic/slime_wrapper/0.4.12-0 -smach_viewer: - url: https://github.com/jbohren/executive_smach_visualization-release.git - vcs: git - version: release/kinetic/smach_viewer/2.0.2-0 -smacha: - url: https://github.com/ReconCell/smacha-release.git - vcs: git - version: release/kinetic/smacha/0.5.0-1 -smacha_ros: - url: https://github.com/ReconCell/smacha-release.git - vcs: git - version: release/kinetic/smacha_ros/0.5.0-1 -smp_ros: - url: https://github.com/ksatyaki/smp_ros-release.git - vcs: git - version: release/kinetic/smp_ros/1.0.1-0 -sns_ik_lib: - url: https://github.com/RethinkRobotics-release/sns_ik-release.git - vcs: git - version: release/kinetic/sns_ik_lib/0.2.3-0 -social_navigation_layers: - url: https://github.com/wu-robotics/navigation_layers_release.git - vcs: git - version: release/kinetic/social_navigation_layers/0.3.1-1 -socketcan_bridge: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/socketcan_bridge/0.7.11-1 -socketcan_interface: - url: https://github.com/ros-industrial-release/ros_canopen-release.git - vcs: git - version: release/kinetic/socketcan_interface/0.7.11-1 -soem: - url: https://github.com/smits/soem-gbp.git - vcs: git - version: release/kinetic/soem/1.3.0-0 -sophus: - url: https://github.com/yujinrobot-release/sophus-release.git - vcs: git - version: release/kinetic/sophus/0.9.1-0 -sophus_ros_conversions: - url: https://github.com/yujinrobot-release/sophus_ros_toolkit-release.git - vcs: git - version: release/kinetic/sophus_ros_conversions/0.1.3-0 -sound_play: - url: https://github.com/ros-gbp/audio_common-release.git - vcs: git - version: release/kinetic/sound_play/0.3.3-0 -spacenav_node: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/kinetic/spacenav_node/1.13.0-1 -sparse_bundle_adjustment: - url: https://github.com/ros-gbp/sparse_bundle_adjustment-release.git - vcs: git - version: release/kinetic/sparse_bundle_adjustment/0.3.2-0 -spatio_temporal_voxel_layer: - url: https://github.com/SteveMacenski/spatio_temporal_voxel_layer-release.git - vcs: git - version: release/kinetic/spatio_temporal_voxel_layer/1.2.1-0 -speech_recognition_msgs: - url: https://github.com/tork-a/jsk_common_msgs-release.git - vcs: git - version: release/kinetic/speech_recognition_msgs/4.3.1-0 -srdfdom: - url: https://github.com/ros-gbp/srdfdom-release.git - vcs: git - version: release/kinetic/srdfdom/0.4.2-1 -srv_tools: - url: https://github.com/srv/srv_tools-release.git - vcs: git - version: release/kinetic/srv_tools/0.0.3-0 -static_tf: - url: https://github.com/wu-robotics/static_tf_release.git - vcs: git - version: release/kinetic/static_tf/0.0.2-0 -static_transform_mux: - url: https://github.com/peci1/static_transform_mux-release.git - vcs: git - version: release/kinetic/static_transform_mux/1.1.0-0 -statistics_msgs: - url: https://github.com/ros-drivers-gbp/pointgrey_camera_driver-release.git - vcs: git - version: release/kinetic/statistics_msgs/0.13.4-0 -std_capabilities: - url: https://github.com/ros-gbp/std_capabilities-release.git - vcs: git - version: release/kinetic/std_capabilities/0.1.0-0 -stdr_gui: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_gui/0.3.2-0 -stdr_launchers: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_launchers/0.3.2-0 -stdr_msgs: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_msgs/0.3.2-0 -stdr_parser: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_parser/0.3.2-0 -stdr_resources: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_resources/0.3.2-0 -stdr_robot: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_robot/0.3.2-0 -stdr_samples: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_samples/0.3.2-0 -stdr_server: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_server/0.3.2-0 -stdr_simulator: - url: https://github.com/stdr-simulator-ros-pkg/stdr_simulator-release.git - vcs: git - version: release/kinetic/stdr_simulator/0.3.2-0 -summit_x_common: - url: https://github.com/RobotnikAutomation/summit_x_common-release.git - vcs: git - version: release/kinetic/summit_x_common/0.1.0-0 -summit_x_control: - url: https://github.com/RobotnikAutomation/summit_x_sim-release.git - vcs: git - version: release/kinetic/summit_x_control/1.1.1-0 -summit_x_description: - url: https://github.com/RobotnikAutomation/summit_x_common-release.git - vcs: git - version: release/kinetic/summit_x_description/0.1.0-0 -summit_x_gazebo: - url: https://github.com/RobotnikAutomation/summit_x_sim-release.git - vcs: git - version: release/kinetic/summit_x_gazebo/1.1.1-0 -summit_x_robot_control: - url: https://github.com/RobotnikAutomation/summit_x_sim-release.git - vcs: git - version: release/kinetic/summit_x_robot_control/1.1.1-0 -summit_x_sim: - url: https://github.com/RobotnikAutomation/summit_x_sim-release.git - vcs: git - version: release/kinetic/summit_x_sim/1.1.1-0 -summit_x_sim_bringup: - url: https://github.com/RobotnikAutomation/summit_x_sim-release.git - vcs: git - version: release/kinetic/summit_x_sim_bringup/1.1.1-0 -summit_xl_common: - url: https://github.com/RobotnikAutomation/summit_xl_common-release.git - vcs: git - version: release/kinetic/summit_xl_common/1.1.2-0 -summit_xl_control: - url: https://github.com/RobotnikAutomation/summit_xl_sim-release.git - vcs: git - version: release/kinetic/summit_xl_control/1.1.1-0 -summit_xl_description: - url: https://github.com/RobotnikAutomation/summit_xl_common-release.git - vcs: git - version: release/kinetic/summit_xl_description/1.1.2-0 -summit_xl_gazebo: - url: https://github.com/RobotnikAutomation/summit_xl_sim-release.git - vcs: git - version: release/kinetic/summit_xl_gazebo/1.1.1-0 -summit_xl_localization: - url: https://github.com/RobotnikAutomation/summit_xl_common-release.git - vcs: git - version: release/kinetic/summit_xl_localization/1.1.2-0 -summit_xl_navigation: - url: https://github.com/RobotnikAutomation/summit_xl_common-release.git - vcs: git - version: release/kinetic/summit_xl_navigation/1.1.2-0 -summit_xl_pad: - url: https://github.com/RobotnikAutomation/summit_xl_common-release.git - vcs: git - version: release/kinetic/summit_xl_pad/1.1.2-0 -summit_xl_robot_control: - url: https://github.com/RobotnikAutomation/summit_xl_sim-release.git - vcs: git - version: release/kinetic/summit_xl_robot_control/1.1.1-0 -summit_xl_sim: - url: https://github.com/RobotnikAutomation/summit_xl_sim-release.git - vcs: git - version: release/kinetic/summit_xl_sim/1.1.1-0 -summit_xl_sim_bringup: - url: https://github.com/RobotnikAutomation/summit_xl_sim-release.git - vcs: git - version: release/kinetic/summit_xl_sim_bringup/1.1.1-0 -swri_console: - url: https://github.com/swri-robotics-gbp/swri_console-release.git - vcs: git - version: release/kinetic/swri_console/1.1.0-0 -swri_console_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_console_util/2.9.0-1 -swri_dbw_interface: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_dbw_interface/2.9.0-1 -swri_geometry_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_geometry_util/2.9.0-1 -swri_image_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_image_util/2.9.0-1 -swri_math_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_math_util/2.9.0-1 -swri_nodelet: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_nodelet/2.9.0-1 -swri_opencv_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_opencv_util/2.9.0-1 -swri_prefix_tools: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_prefix_tools/2.9.0-1 -swri_profiler: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/kinetic/swri_profiler/0.1.0-0 -swri_profiler_msgs: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/kinetic/swri_profiler_msgs/0.1.0-0 -swri_profiler_tools: - url: https://github.com/swri-robotics-gbp/swri_profiler-release.git - vcs: git - version: release/kinetic/swri_profiler_tools/0.1.0-0 -swri_roscpp: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_roscpp/2.9.0-1 -swri_rospy: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_rospy/2.9.0-1 -swri_route_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_route_util/2.9.0-1 -swri_serial_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_serial_util/2.9.0-1 -swri_string_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_string_util/2.9.0-1 -swri_system_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_system_util/2.9.0-1 -swri_transform_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_transform_util/2.9.0-1 -swri_yaml_util: - url: https://github.com/swri-robotics-gbp/marti_common-release.git - vcs: git - version: release/kinetic/swri_yaml_util/2.9.0-1 -sync_params: - url: https://github.com/NicksSimulationsROS/sync_params-release.git - vcs: git - version: release/kinetic/sync_params/1.0.1-0 -tablet_socket_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/tablet_socket_msgs/1.12.0-1 -talos_description: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/kinetic/talos_description/1.0.45-1 -talos_description_calibration: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/kinetic/talos_description_calibration/1.0.45-1 -talos_description_inertial: - url: https://github.com/pal-gbp/talos_robot-release.git - vcs: git - version: release/kinetic/talos_description_inertial/1.0.45-1 -tango_ros_messages: - url: https://github.com/Intermodalics/tango_ros-release.git - vcs: git - version: release/kinetic/tango_ros_messages/2.0.0-0 -task_compiler: - url: https://github.com/tork-a/jsk_planning-release.git - vcs: git - version: release/kinetic/task_compiler/0.1.10-0 -tblib: - url: https://github.com/asmodehn/tblib-rosrelease.git - vcs: git - version: release/kinetic/tblib/1.2.0-2 -teb_local_planner: - url: https://github.com/rst-tu-dortmund/teb_local_planner-release.git - vcs: git - version: release/kinetic/teb_local_planner/0.6.13-1 -teb_local_planner_tutorials: - url: https://github.com/rst-tu-dortmund/teb_local_planner_tutorials-release.git - vcs: git - version: release/kinetic/teb_local_planner_tutorials/0.2.4-1 -teleop_tools: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/kinetic/teleop_tools/0.3.0-0 -teleop_tools_msgs: - url: https://github.com/ros-gbp/teleop_tools-release.git - vcs: git - version: release/kinetic/teleop_tools_msgs/0.3.0-0 -teleop_twist_joy: - url: https://github.com/ros-teleop/teleop_twist_joy-release.git - vcs: git - version: release/kinetic/teleop_twist_joy/0.1.3-0 -teleop_twist_keyboard: - url: https://github.com/ros-gbp/teleop_twist_keyboard-release.git - vcs: git - version: release/kinetic/teleop_twist_keyboard/0.6.2-0 -tensorflow_ros: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/tensorflow_ros/0.0.4-0 -tensorflow_ros_rqt: - url: https://github.com/tue-robotics/image_recognition-release.git - vcs: git - version: release/kinetic/tensorflow_ros_rqt/0.0.4-0 -teraranger: - url: https://github.com/Terabee/teraranger-release.git - vcs: git - version: release/kinetic/teraranger/2.1.0-2 -teraranger_array: - url: https://github.com/Terabee/teraranger_array-release.git - vcs: git - version: release/kinetic/teraranger_array/2.0.0-1 -teraranger_array_converter: - url: https://github.com/Terabee/teraranger_array_converter-release.git - vcs: git - version: release/kinetic/teraranger_array_converter/1.1.1-0 -teraranger_description: - url: https://github.com/Terabee/teraranger_description-release.git - vcs: git - version: release/kinetic/teraranger_description/1.1.0-0 -test_diagnostic_aggregator: - url: https://github.com/ros-gbp/diagnostics-release.git - vcs: git - version: release/kinetic/test_diagnostic_aggregator/1.9.3-0 -test_mavros: - url: https://github.com/mavlink/mavros-release.git - vcs: git - version: release/kinetic/test_mavros/0.32.1-1 -test_osm: - url: https://github.com/ros-geographic-info/open_street_map-release.git - vcs: git - version: release/kinetic/test_osm/0.2.4-0 -tf2_bullet: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/kinetic/tf2_bullet/0.5.20-0 -tf2_relay: - url: https://github.com/clearpath-gbp/cpr_multimaster_tools-release.git - vcs: git - version: release/kinetic/tf2_relay/0.0.2-1 -tf2_sensor_msgs: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/kinetic/tf2_sensor_msgs/0.5.20-0 -tf2_tools: - url: https://github.com/ros-gbp/geometry2-release.git - vcs: git - version: release/kinetic/tf2_tools/0.5.20-0 -tf2_web_republisher: - url: https://github.com/RobotWebTools-release/tf2_web_republisher-release.git - vcs: git - version: release/kinetic/tf2_web_republisher/0.3.2-0 -tf_remapper_cpp: - url: https://github.com/peci1/tf_remapper_cpp-release.git - vcs: git - version: release/kinetic/tf_remapper_cpp/1.1.1-0 -tf_tools: - url: https://github.com/srv/srv_tools-release.git - vcs: git - version: release/kinetic/tf_tools/0.0.3-0 -thormang3_action_editor: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Tools-release.git - vcs: git - version: release/kinetic/thormang3_action_editor/0.2.0-0 -thormang3_action_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_action_module/0.2.0-0 -thormang3_action_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_action_module_msgs/0.3.0-0 -thormang3_action_script_player: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_action_script_player/0.3.0-0 -thormang3_balance_control: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_balance_control/0.2.0-0 -thormang3_base_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_base_module/0.2.0-0 -thormang3_common: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Common-release.git - vcs: git - version: release/kinetic/thormang3_common/0.2.0-0 -thormang3_demo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_demo/0.3.0-0 -thormang3_description: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Common-release.git - vcs: git - version: release/kinetic/thormang3_description/0.2.0-0 -thormang3_feet_ft_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_feet_ft_module/0.2.0-0 -thormang3_feet_ft_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_feet_ft_module_msgs/0.3.0-0 -thormang3_foot_step_generator: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_foot_step_generator/0.3.0-0 -thormang3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Common-release.git - vcs: git - version: release/kinetic/thormang3_gazebo/0.2.0-0 -thormang3_gripper_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_gripper_module/0.2.0-0 -thormang3_head_control_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_head_control_module/0.2.0-0 -thormang3_head_control_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_head_control_module_msgs/0.3.0-0 -thormang3_imu_3dm_gx4: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-SENSORs-release.git - vcs: git - version: release/kinetic/thormang3_imu_3dm_gx4/0.2.0-0 -thormang3_kinematics_dynamics: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_kinematics_dynamics/0.2.0-0 -thormang3_manager: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_manager/0.2.0-0 -thormang3_manipulation_demo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-PPC-release.git - vcs: git - version: release/kinetic/thormang3_manipulation_demo/0.2.0-0 -thormang3_manipulation_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_manipulation_module/0.2.0-0 -thormang3_manipulation_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_manipulation_module_msgs/0.3.0-0 -thormang3_mpc: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_mpc/0.2.0-0 -thormang3_mpc_sensors: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-SENSORs-release.git - vcs: git - version: release/kinetic/thormang3_mpc_sensors/0.2.0-0 -thormang3_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_msgs/0.3.0-0 -thormang3_navigation: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_navigation/0.3.0-0 -thormang3_offset_tuner_client: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_offset_tuner_client/0.3.0-0 -thormang3_offset_tuner_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_offset_tuner_msgs/0.3.0-0 -thormang3_offset_tuner_server: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Tools-release.git - vcs: git - version: release/kinetic/thormang3_offset_tuner_server/0.2.0-0 -thormang3_opc: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-OPC-release.git - vcs: git - version: release/kinetic/thormang3_opc/0.3.0-0 -thormang3_ppc: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-PPC-release.git - vcs: git - version: release/kinetic/thormang3_ppc/0.2.0-0 -thormang3_sensors: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-PPC-release.git - vcs: git - version: release/kinetic/thormang3_sensors/0.2.0-0 -thormang3_tools: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-Tools-release.git - vcs: git - version: release/kinetic/thormang3_tools/0.2.0-0 -thormang3_walking_demo: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-PPC-release.git - vcs: git - version: release/kinetic/thormang3_walking_demo/0.2.0-0 -thormang3_walking_module: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-MPC-release.git - vcs: git - version: release/kinetic/thormang3_walking_module/0.2.0-0 -thormang3_walking_module_msgs: - url: https://github.com/ROBOTIS-GIT-release/ROBOTIS-THORMANG-msgs-release.git - vcs: git - version: release/kinetic/thormang3_walking_module_msgs/0.3.0-0 -tile_map: - url: https://github.com/swri-robotics-gbp/mapviz-release.git - vcs: git - version: release/kinetic/tile_map/1.1.1-1 -timed_roslaunch: - url: https://github.com/MoriKen254/timed_roslaunch-release.git - vcs: git - version: release/kinetic/timed_roslaunch/0.1.3-0 -timestamp_tools: - url: https://github.com/ros-gbp/driver_common-release.git - vcs: git - version: release/kinetic/timestamp_tools/1.6.8-0 -topic_switch: - url: https://github.com/hakuturu583/topic_switch-release.git - vcs: git - version: release/kinetic/topic_switch/0.0.1-2 -toposens: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens/1.2.2-1 -toposens_description: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_description/1.2.2-1 -toposens_driver: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_driver/1.2.2-1 -toposens_markers: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_markers/1.2.2-1 -toposens_msgs: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_msgs/1.2.2-1 -toposens_pointcloud: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_pointcloud/1.2.2-1 -toposens_sync: - url: https://gitlab.com/toposens/public/toposens-release.git - vcs: git - version: release/kinetic/toposens_sync/1.2.2-1 -towr: - url: https://github.com/ethz-adrl/towr-release.git - vcs: git - version: release/kinetic/towr/1.4.1-0 -towr_ros: - url: https://github.com/ethz-adrl/towr-release.git - vcs: git - version: release/kinetic/towr_ros/1.4.1-0 -tra1_bringup: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/tra1_bringup/1.0.10-0 -tra1_description: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/tra1_description/1.0.10-0 -tra1_moveit_config: - url: https://github.com/tork-a/minas-release.git - vcs: git - version: release/kinetic/tra1_moveit_config/1.0.10-0 -trac_ik: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/kinetic/trac_ik/1.5.0-0 -trac_ik_examples: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/kinetic/trac_ik_examples/1.5.0-0 -trac_ik_kinematics_plugin: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/kinetic/trac_ik_kinematics_plugin/1.5.0-0 -trac_ik_lib: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/kinetic/trac_ik_lib/1.5.0-0 -trac_ik_python: - url: https://github.com/traclabs/trac_ik-release.git - vcs: git - version: release/kinetic/trac_ik_python/1.5.0-0 -tracetools: - url: https://github.com/bosch-robotics-cr/tracetools-release.git - vcs: git - version: release/kinetic/tracetools/0.2.1-0 -track_odometry: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/track_odometry/0.4.2-1 -trajectory_tracker: - url: https://github.com/at-wat/neonavigation-release.git - vcs: git - version: release/kinetic/trajectory_tracker/0.4.2-1 -trajectory_tracker_msgs: - url: https://github.com/at-wat/neonavigation_msgs-release.git - vcs: git - version: release/kinetic/trajectory_tracker_msgs/0.3.1-0 -trajectory_tracker_rviz_plugins: - url: https://github.com/at-wat/neonavigation_rviz_plugins-release.git - vcs: git - version: release/kinetic/trajectory_tracker_rviz_plugins/0.3.0-0 -transmission_interface: - url: https://github.com/ros-gbp/ros_control-release.git - vcs: git - version: release/kinetic/transmission_interface/0.13.3-0 -tts: - url: https://github.com/aws-gbp/tts-release.git - vcs: git - version: release/kinetic/tts/1.0.2-1 -turtlebot: - url: https://github.com/turtlebot-release/turtlebot-release.git - vcs: git - version: release/kinetic/turtlebot/2.4.2-0 -turtlebot3: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3/1.2.1-1 -turtlebot3_applications: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_applications/1.1.0-0 -turtlebot3_applications_msgs: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications_msgs-release.git - vcs: git - version: release/kinetic/turtlebot3_applications_msgs/1.0.0-0 -turtlebot3_automatic_parking: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_automatic_parking/1.1.0-0 -turtlebot3_automatic_parking_vision: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_automatic_parking_vision/1.1.0-0 -turtlebot3_autorace: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/kinetic/turtlebot3_autorace/1.2.0-0 -turtlebot3_autorace_camera: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/kinetic/turtlebot3_autorace_camera/1.2.0-0 -turtlebot3_autorace_control: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/kinetic/turtlebot3_autorace_control/1.2.0-0 -turtlebot3_autorace_core: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/kinetic/turtlebot3_autorace_core/1.2.0-0 -turtlebot3_autorace_detect: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_autorace-release.git - vcs: git - version: release/kinetic/turtlebot3_autorace_detect/1.2.0-0 -turtlebot3_bringup: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_bringup/1.2.1-1 -turtlebot3_description: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_description/1.2.1-1 -turtlebot3_example: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_example/1.2.1-1 -turtlebot3_fake: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/kinetic/turtlebot3_fake/1.2.0-0 -turtlebot3_follow_filter: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_follow_filter/1.1.0-0 -turtlebot3_follower: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_follower/1.1.0-0 -turtlebot3_gazebo: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/kinetic/turtlebot3_gazebo/1.2.0-0 -turtlebot3_msgs: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_msgs-release.git - vcs: git - version: release/kinetic/turtlebot3_msgs/1.0.0-0 -turtlebot3_navigation: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_navigation/1.2.1-1 -turtlebot3_panorama: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_applications-release.git - vcs: git - version: release/kinetic/turtlebot3_panorama/1.1.0-0 -turtlebot3_simulations: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3_simulations-release.git - vcs: git - version: release/kinetic/turtlebot3_simulations/1.2.0-0 -turtlebot3_slam: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_slam/1.2.1-1 -turtlebot3_teleop: - url: https://github.com/ROBOTIS-GIT-release/turtlebot3-release.git - vcs: git - version: release/kinetic/turtlebot3_teleop/1.2.1-1 -turtlebot_actions: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_actions/2.3.7-0 -turtlebot_apps: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_apps/2.3.7-0 -turtlebot_bringup: - url: https://github.com/turtlebot-release/turtlebot-release.git - vcs: git - version: release/kinetic/turtlebot_bringup/2.4.2-0 -turtlebot_calibration: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_calibration/2.3.7-0 -turtlebot_capabilities: - url: https://github.com/turtlebot-release/turtlebot-release.git - vcs: git - version: release/kinetic/turtlebot_capabilities/2.4.2-0 -turtlebot_create: - url: https://github.com/turtlebot-release/turtlebot_create-release.git - vcs: git - version: release/kinetic/turtlebot_create/2.3.1-0 -turtlebot_dashboard: - url: https://github.com/turtlebot-release/turtlebot_interactions-release.git - vcs: git - version: release/kinetic/turtlebot_dashboard/2.3.1-0 -turtlebot_description: - url: https://github.com/turtlebot-release/turtlebot-release.git - vcs: git - version: release/kinetic/turtlebot_description/2.4.2-0 -turtlebot_follower: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_follower/2.3.7-0 -turtlebot_gazebo: - url: https://github.com/turtlebot-release/turtlebot_simulator-release.git - vcs: git - version: release/kinetic/turtlebot_gazebo/2.2.3-0 -turtlebot_interactions: - url: https://github.com/turtlebot-release/turtlebot_interactions-release.git - vcs: git - version: release/kinetic/turtlebot_interactions/2.3.1-0 -turtlebot_interactive_markers: - url: https://github.com/turtlebot-release/turtlebot_interactions-release.git - vcs: git - version: release/kinetic/turtlebot_interactive_markers/2.3.1-0 -turtlebot_msgs: - url: https://github.com/turtlebot-release/turtlebot_msgs-release.git - vcs: git - version: release/kinetic/turtlebot_msgs/2.2.1-0 -turtlebot_navigation: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_navigation/2.3.7-0 -turtlebot_rapps: - url: https://github.com/turtlebot-release/turtlebot_apps-release.git - vcs: git - version: release/kinetic/turtlebot_rapps/2.3.7-0 -turtlebot_rviz_launchers: - url: https://github.com/turtlebot-release/turtlebot_interactions-release.git - vcs: git - version: release/kinetic/turtlebot_rviz_launchers/2.3.1-0 -turtlebot_simulator: - url: https://github.com/turtlebot-release/turtlebot_simulator-release.git - vcs: git - version: release/kinetic/turtlebot_simulator/2.2.3-0 -turtlebot_stage: - url: https://github.com/turtlebot-release/turtlebot_simulator-release.git - vcs: git - version: release/kinetic/turtlebot_stage/2.2.3-0 -turtlebot_stdr: - url: https://github.com/turtlebot-release/turtlebot_simulator-release.git - vcs: git - version: release/kinetic/turtlebot_stdr/2.2.3-0 -turtlebot_teleop: - url: https://github.com/turtlebot-release/turtlebot-release.git - vcs: git - version: release/kinetic/turtlebot_teleop/2.4.2-0 -tuw_airskin_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_airskin_msgs/0.0.11-0 -tuw_aruco: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/kinetic/tuw_aruco/0.0.7-0 -tuw_ellipses: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/kinetic/tuw_ellipses/0.0.7-0 -tuw_gazebo_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_gazebo_msgs/0.0.11-0 -tuw_geometry_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_geometry_msgs/0.0.11-0 -tuw_marker_detection: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/kinetic/tuw_marker_detection/0.0.7-0 -tuw_marker_pose_estimation: - url: https://github.com/tuw-robotics/tuw_marker_detection-release.git - vcs: git - version: release/kinetic/tuw_marker_pose_estimation/0.0.7-0 -tuw_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_msgs/0.0.11-0 -tuw_multi_robot_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_multi_robot_msgs/0.0.11-0 -tuw_nav_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_nav_msgs/0.0.11-0 -tuw_object_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_object_msgs/0.0.11-0 -tuw_vehicle_msgs: - url: https://github.com/tuw-robotics/tuw_msgs-release.git - vcs: git - version: release/kinetic/tuw_vehicle_msgs/0.0.11-0 -twist_mux: - url: https://github.com/ros-gbp/twist_mux-release.git - vcs: git - version: release/kinetic/twist_mux/3.0.0-0 -twist_mux_msgs: - url: https://github.com/ros-gbp/twist_mux_msgs-release.git - vcs: git - version: release/kinetic/twist_mux_msgs/2.0.0-0 -twist_recovery: - url: https://github.com/ros-gbp/navigation_experimental-release.git - vcs: git - version: release/kinetic/twist_recovery/0.2.1-0 -twistimu: - url: https://github.com/easymov/twistimu-release.git - vcs: git - version: release/kinetic/twistimu/1.0.0-0 -ubiquity_motor: - url: https://github.com/UbiquityRobotics-release/ubiquity_motor-release.git - vcs: git - version: release/kinetic/ubiquity_motor/0.9.0-0 -ueye: - url: https://github.com/kmhallen/ueye-release.git - vcs: git - version: release/kinetic/ueye/0.0.10-0 -ueye_cam: - url: https://github.com/anqixu/ueye_cam-release.git - vcs: git - version: release/kinetic/ueye_cam/1.0.16-0 -um6: - url: https://github.com/ros-drivers-gbp/um6-release.git - vcs: git - version: release/kinetic/um6/1.1.2-0 -um7: - url: https://github.com/ros-drivers-gbp/um7-release.git - vcs: git - version: release/kinetic/um7/0.0.4-0 -underwater_sensor_msgs: - url: https://github.com/uji-ros-pkg/underwater_simulation-release.git - vcs: git - version: release/kinetic/underwater_sensor_msgs/1.4.1-0 -underwater_vehicle_dynamics: - url: https://github.com/uji-ros-pkg/underwater_simulation-release.git - vcs: git - version: release/kinetic/underwater_vehicle_dynamics/1.4.1-0 -unique_identifier: - url: https://github.com/ros-geographic-info/unique_identifier-release.git - vcs: git - version: release/kinetic/unique_identifier/1.0.5-0 -universal_robot: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/universal_robot/1.2.5-0 -universal_robots: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/universal_robots/1.2.5-0 -ur10_e_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur10_e_moveit_config/1.2.5-0 -ur10_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur10_moveit_config/1.2.5-0 -ur3_e_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur3_e_moveit_config/1.2.5-0 -ur3_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur3_moveit_config/1.2.5-0 -ur5_e_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur5_e_moveit_config/1.2.5-0 -ur5_moveit_config: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur5_moveit_config/1.2.5-0 -ur_bringup: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_bringup/1.2.5-0 -ur_description: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_description/1.2.5-0 -ur_driver: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_driver/1.2.5-0 -ur_e_description: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_e_description/1.2.5-0 -ur_e_gazebo: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_e_gazebo/1.2.5-0 -ur_gazebo: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_gazebo/1.2.5-0 -ur_kinematics: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_kinematics/1.2.5-0 -ur_msgs: - url: https://github.com/ros-industrial-release/universal_robot-release.git - vcs: git - version: release/kinetic/ur_msgs/1.2.5-0 -urdf_geometry_parser: - url: https://github.com/ros-gbp/urdf_geometry_parser-release.git - vcs: git - version: release/kinetic/urdf_geometry_parser/0.0.3-0 -urdf_sim_tutorial: - url: https://github.com/ros-gbp/urdf_tutorial-release.git - vcs: git - version: release/kinetic/urdf_sim_tutorial/0.3.0-1 -urdf_test: - url: https://github.com/pal-gbp/urdf_test-release.git - vcs: git - version: release/kinetic/urdf_test/1.0.4-0 -urdfdom_py: - url: https://github.com/ros-gbp/urdfdom_py-release.git - vcs: git - version: release/kinetic/urdfdom_py/0.3.3-0 -urg_c: - url: https://github.com/ros-gbp/urg_c-release.git - vcs: git - version: release/kinetic/urg_c/1.0.405-0 -urg_node: - url: https://github.com/ros-gbp/urg_node-release.git - vcs: git - version: release/kinetic/urg_node/0.1.11-0 -urg_stamped: - url: https://github.com/seqsense/urg_stamped-release.git - vcs: git - version: release/kinetic/urg_stamped/0.0.3-1 -usb_cam: - url: https://github.com/ros-gbp/usb_cam-release.git - vcs: git - version: release/kinetic/usb_cam/0.3.5-0 -usb_cam_controllers: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/kinetic/usb_cam_controllers/0.0.3-0 -usb_cam_hardware: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/kinetic/usb_cam_hardware/0.0.3-0 -usb_cam_hardware_interface: - url: https://github.com/yoshito-n-students/usb_cam_hardware-release.git - vcs: git - version: release/kinetic/usb_cam_hardware_interface/0.0.3-0 -usv_gazebo_plugins: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/usv_gazebo_plugins/1.2.0-1 -uuv_assistants: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_assistants/0.6.13-0 -uuv_auv_control_allocator: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_auv_control_allocator/0.6.13-0 -uuv_control_cascaded_pid: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_control_cascaded_pid/0.6.13-0 -uuv_control_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_control_msgs/0.6.13-0 -uuv_control_utils: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_control_utils/0.6.13-0 -uuv_cpc_sensor: - url: https://github.com/uuvsimulator/uuv_plume_simulator-release.git - vcs: git - version: release/kinetic/uuv_cpc_sensor/0.3.1-0 -uuv_descriptions: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_descriptions/0.6.13-0 -uuv_gazebo: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_gazebo/0.6.13-0 -uuv_gazebo_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_gazebo_plugins/0.6.13-0 -uuv_gazebo_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_gazebo_ros_plugins/0.6.13-0 -uuv_gazebo_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_gazebo_ros_plugins_msgs/0.6.13-0 -uuv_gazebo_worlds: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_gazebo_worlds/0.6.13-0 -uuv_plume_msgs: - url: https://github.com/uuvsimulator/uuv_plume_simulator-release.git - vcs: git - version: release/kinetic/uuv_plume_msgs/0.3.1-0 -uuv_plume_simulator: - url: https://github.com/uuvsimulator/uuv_plume_simulator-release.git - vcs: git - version: release/kinetic/uuv_plume_simulator/0.3.1-0 -uuv_sensor_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_sensor_ros_plugins/0.6.13-0 -uuv_sensor_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_sensor_ros_plugins_msgs/0.6.13-0 -uuv_simulator: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_simulator/0.6.13-0 -uuv_teleop: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_teleop/0.6.13-0 -uuv_thruster_manager: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_thruster_manager/0.6.13-0 -uuv_trajectory_control: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_trajectory_control/0.6.13-0 -uuv_world_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_world_plugins/0.6.13-0 -uuv_world_ros_plugins: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_world_ros_plugins/0.6.13-0 -uuv_world_ros_plugins_msgs: - url: https://github.com/uuvsimulator/uuv_simulator-release.git - vcs: git - version: release/kinetic/uuv_world_ros_plugins_msgs/0.6.13-0 -uvc_camera: - url: https://github.com/ros-drivers-gbp/camera_umd-release.git - vcs: git - version: release/kinetic/uvc_camera/0.2.5-0 -uwsim_bullet: - url: https://github.com/uji-ros-pkg/uwsim_bullet-release.git - vcs: git - version: release/kinetic/uwsim_bullet/2.82.1-0 -uwsim_osgbullet: - url: https://github.com/uji-ros-pkg/uwsim_osgbullet-release.git - vcs: git - version: release/kinetic/uwsim_osgbullet/3.0.1-0 -uwsim_osgocean: - url: https://github.com/uji-ros-pkg/uwsim_osgocean-release.git - vcs: git - version: release/kinetic/uwsim_osgocean/1.0.3-0 -uwsim_osgworks: - url: https://github.com/uji-ros-pkg/uwsim_osgworks-release.git - vcs: git - version: release/kinetic/uwsim_osgworks/3.0.3-1 -variant: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/kinetic/variant/0.1.5-0 -variant_msgs: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/kinetic/variant_msgs/0.1.5-0 -variant_topic_test: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/kinetic/variant_topic_test/0.1.5-0 -variant_topic_tools: - url: https://github.com/anybotics/variant-release.git - vcs: git - version: release/kinetic/variant_topic_tools/0.1.5-0 -vector_map_msgs: - url: https://gitlab.com/autowarefoundation/autoware.ai-ros-releases/messages-release.git - vcs: git - version: release/kinetic/vector_map_msgs/1.12.0-1 -velocity_controllers: - url: https://github.com/ros-gbp/ros_controllers-release.git - vcs: git - version: release/kinetic/velocity_controllers/0.13.5-0 -velodyne: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/kinetic/velodyne/1.5.2-0 -velodyne_description: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/kinetic/velodyne_description/1.0.9-0 -velodyne_driver: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/kinetic/velodyne_driver/1.5.2-0 -velodyne_gazebo_plugins: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/kinetic/velodyne_gazebo_plugins/1.0.9-0 -velodyne_laserscan: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/kinetic/velodyne_laserscan/1.5.2-0 -velodyne_msgs: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/kinetic/velodyne_msgs/1.5.2-0 -velodyne_pointcloud: - url: https://github.com/ros-drivers-gbp/velodyne-release.git - vcs: git - version: release/kinetic/velodyne_pointcloud/1.5.2-0 -velodyne_simulator: - url: https://github.com/DataspeedInc-release/velodyne_simulator-release.git - vcs: git - version: release/kinetic/velodyne_simulator/1.0.9-0 -video_stream_opencv: - url: https://github.com/ros-drivers/video_stream_opencv-release.git - vcs: git - version: release/kinetic/video_stream_opencv/1.1.5-0 -view_controller_msgs: - url: https://github.com/ros-gbp/view_controller_msgs-release.git - vcs: git - version: release/kinetic/view_controller_msgs/0.1.2-0 -virtual_force_publisher: - url: https://github.com/tork-a/jsk_common-release.git - vcs: git - version: release/kinetic/virtual_force_publisher/2.2.10-0 -vision_msgs: - url: https://github.com/Kukanani/vision_msgs-release.git - vcs: git - version: release/kinetic/vision_msgs/0.0.1-0 -vision_visp: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/vision_visp/0.11.1-1 -visp: - url: https://github.com/lagadic/visp-release.git - vcs: git - version: release/kinetic/visp/3.2.0-3 -visp_auto_tracker: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/visp_auto_tracker/0.11.1-1 -visp_bridge: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/visp_bridge/0.11.1-1 -visp_camera_calibration: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/visp_camera_calibration/0.11.1-1 -visp_hand2eye_calibration: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/visp_hand2eye_calibration/0.11.1-1 -visp_tracker: - url: https://github.com/lagadic/vision_visp-release.git - vcs: git - version: release/kinetic/visp_tracker/0.11.1-1 -visualization_osg: - url: https://github.com/uji-ros-pkg/visualization_osg-release.git - vcs: git - version: release/kinetic/visualization_osg/1.0.2-0 -visualstates: - url: https://github.com/JdeRobot/VisualStates-release.git - vcs: git - version: release/kinetic/visualstates/0.2.2-0 -voice_text: - url: https://github.com/tork-a/jsk_3rdparty-release.git - vcs: git - version: release/kinetic/voice_text/2.1.13-1 -vrpn: - url: https://github.com/ros-drivers-gbp/vrpn-release.git - vcs: git - version: release/kinetic/vrpn/7.33.1-1 -vrpn_client_ros: - url: https://github.com/ros-drivers-gbp/vrpn_client_ros-release.git - vcs: git - version: release/kinetic/vrpn_client_ros/0.2.2-0 -vrx_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/vrx_gazebo/1.2.0-1 -vs060: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/vs060/2.0.3-0 -vs060_gazebo: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/vs060_gazebo/2.0.3-0 -vs060_moveit_config: - url: https://github.com/start-jsk/denso-release.git - vcs: git - version: release/kinetic/vs060_moveit_config/2.0.3-0 -wamv_description: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/wamv_description/1.2.0-1 -wamv_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/wamv_gazebo/1.2.0-1 -warehouse_ros: - url: https://github.com/ros-gbp/warehouse_ros-release.git - vcs: git - version: release/kinetic/warehouse_ros/0.9.3-1 -warthog_control: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/kinetic/warthog_control/0.1.1-1 -warthog_description: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/kinetic/warthog_description/0.1.1-1 -warthog_desktop: - url: https://github.com/clearpath-gbp/warthog_desktop-release.git - vcs: git - version: release/kinetic/warthog_desktop/0.0.1-1 -warthog_gazebo: - url: https://github.com/clearpath-gbp/warthog_simulator-release.git - vcs: git - version: release/kinetic/warthog_gazebo/0.1.0-1 -warthog_msgs: - url: https://github.com/clearpath-gbp/warthog-release.git - vcs: git - version: release/kinetic/warthog_msgs/0.1.1-1 -warthog_simulator: - url: https://github.com/clearpath-gbp/warthog_simulator-release.git - vcs: git - version: release/kinetic/warthog_simulator/0.1.0-1 -warthog_viz: - url: https://github.com/clearpath-gbp/warthog_desktop-release.git - vcs: git - version: release/kinetic/warthog_viz/0.0.1-1 -wave_gazebo: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/wave_gazebo/1.2.0-1 -wave_gazebo_plugins: - url: https://github.com/ros-gbp/vrx-release.git - vcs: git - version: release/kinetic/wave_gazebo_plugins/1.2.0-1 -waypoint_generator: - url: https://github.com/jihoonl/waypoint-release.git - vcs: git - version: release/kinetic/waypoint_generator/0.0.1-0 -waypoint_meta: - url: https://github.com/jihoonl/waypoint-release.git - vcs: git - version: release/kinetic/waypoint_meta/0.0.1-0 -waypoint_touring: - url: https://github.com/jihoonl/waypoint-release.git - vcs: git - version: release/kinetic/waypoint_touring/0.0.1-0 -web_interface: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/web_interface/1.0.7-0 -web_msgs: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/web_msgs/1.0.7-0 -web_video_server: - url: https://github.com/RobotWebTools-release/web_video_server-release.git - vcs: git - version: release/kinetic/web_video_server/0.2.1-1 -webargs: - url: https://github.com/asmodehn/webargs-rosrelease.git - vcs: git - version: release/kinetic/webargs/1.5.3-1 -webots_ros: - url: https://github.com/omichel/webots_ros-release.git - vcs: git - version: release/kinetic/webots_ros/2.0.5-1 -webrtc: - url: https://github.com/RobotWebTools-release/webrtc_ros-release.git - vcs: git - version: release/kinetic/webrtc/59.0.3-0 -webrtc_ros: - url: https://github.com/RobotWebTools-release/webrtc_ros-release.git - vcs: git - version: release/kinetic/webrtc_ros/59.0.3-0 -webtest: - url: https://github.com/asmodehn/webtest-rosrelease.git - vcs: git - version: release/kinetic/webtest/2.0.18-1 -webui: - url: https://github.com/UNR-RoboticsResearchLab/web_interface-release.git - vcs: git - version: release/kinetic/webui/1.0.7-0 -wfov_camera_msgs: - url: https://github.com/ros-drivers-gbp/pointgrey_camera_driver-release.git - vcs: git - version: release/kinetic/wfov_camera_msgs/0.13.4-0 -wge100_camera: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/kinetic/wge100_camera/1.8.2-0 -wge100_camera_firmware: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/kinetic/wge100_camera_firmware/1.8.2-0 -wge100_driver: - url: https://github.com/ros-drivers-gbp/wge100_driver-release.git - vcs: git - version: release/kinetic/wge100_driver/1.8.2-0 -wifi_ddwrt: - url: https://github.com/ros-gbp/wifi_ddwrt-release.git - vcs: git - version: release/kinetic/wifi_ddwrt/0.2.0-1 -wiimote: - url: https://github.com/ros-gbp/joystick_drivers-release.git - vcs: git - version: release/kinetic/wiimote/1.13.0-1 -willow_maps: - url: https://github.com/ros-gbp/willow_maps-release.git - vcs: git - version: release/kinetic/willow_maps/1.0.3-0 -wireless_msgs: - url: https://github.com/clearpath-gbp/wireless-release.git - vcs: git - version: release/kinetic/wireless_msgs/0.0.7-0 -wireless_watcher: - url: https://github.com/clearpath-gbp/wireless-release.git - vcs: git - version: release/kinetic/wireless_watcher/0.0.7-0 -world_canvas_client_cpp: - url: https://github.com/yujinrobot-release/world_canvas_libs-release.git - vcs: git - version: release/kinetic/world_canvas_client_cpp/0.2.0-0 -world_canvas_client_examples: - url: https://github.com/yujinrobot-release/world_canvas_libs-release.git - vcs: git - version: release/kinetic/world_canvas_client_examples/0.2.0-0 -world_canvas_client_py: - url: https://github.com/yujinrobot-release/world_canvas_libs-release.git - vcs: git - version: release/kinetic/world_canvas_client_py/0.2.0-0 -world_canvas_msgs: - url: https://github.com/yujinrobot-release/world_canvas_msgs-release.git - vcs: git - version: release/kinetic/world_canvas_msgs/0.2.0-1 -world_canvas_server: - url: https://github.com/yujinrobot-release/world_canvas-release.git - vcs: git - version: release/kinetic/world_canvas_server/0.2.0-0 -world_canvas_utils: - url: https://github.com/yujinrobot-release/world_canvas_libs-release.git - vcs: git - version: release/kinetic/world_canvas_utils/0.2.0-0 -wts_driver: - url: https://github.com/ksatyaki/wts_driver-release.git - vcs: git - version: release/kinetic/wts_driver/1.0.4-0 -wu_ros_tools: - url: https://github.com/wu-robotics/wu_ros_tools.git - vcs: git - version: release/kinetic/wu_ros_tools/0.2.4-0 -xiaoqiang: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang/0.0.12-0 -xiaoqiang_bringup: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_bringup/0.0.12-0 -xiaoqiang_controller: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_controller/0.0.12-0 -xiaoqiang_depth_image_proc: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_depth_image_proc/0.0.12-0 -xiaoqiang_description: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_description/0.0.12-0 -xiaoqiang_driver: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_driver/0.0.12-0 -xiaoqiang_freenect: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_freenect/0.0.12-0 -xiaoqiang_freenect_camera: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_freenect_camera/0.0.12-0 -xiaoqiang_freenect_launch: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_freenect_launch/0.0.12-0 -xiaoqiang_monitor: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_monitor/0.0.12-0 -xiaoqiang_msgs: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_msgs/0.0.12-0 -xiaoqiang_navigation: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_navigation/0.0.12-0 -xiaoqiang_navigation_example: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_navigation_example/0.0.12-0 -xiaoqiang_server: - url: https://github.com/BluewhaleRobot-release/xiaoqiang-release.git - vcs: git - version: release/kinetic/xiaoqiang_server/0.0.12-0 -xpp: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp/1.0.10-0 -xpp_examples: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_examples/1.0.10-0 -xpp_hyq: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_hyq/1.0.10-0 -xpp_msgs: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_msgs/1.0.10-0 -xpp_quadrotor: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_quadrotor/1.0.10-0 -xpp_states: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_states/1.0.10-0 -xpp_vis: - url: https://github.com/leggedrobotics/xpp-release.git - vcs: git - version: release/kinetic/xpp_vis/1.0.10-0 -xsens_driver: - url: https://github.com/ethz-asl/ethzasl_xsens_driver-release.git - vcs: git - version: release/kinetic/xsens_driver/2.2.2-0 -xv_11_laser_driver: - url: https://github.com/rohbotics/xv_11_laser_driver-release.git - vcs: git - version: release/kinetic/xv_11_laser_driver/0.3.0-0 -yaml_cpp_0_3: - url: https://github.com/yujinrobot-release/yaml_cpp_0_3-release.git - vcs: git - version: release/kinetic/yaml_cpp_0_3/0.3.1-0 -yocs_ar_marker_tracking: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_ar_marker_tracking/0.8.2-0 -yocs_ar_pair_approach: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_ar_pair_approach/0.8.2-0 -yocs_ar_pair_tracking: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_ar_pair_tracking/0.8.2-0 -yocs_cmd_vel_mux: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_cmd_vel_mux/0.8.2-0 -yocs_controllers: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_controllers/0.8.2-0 -yocs_diff_drive_pose_controller: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_diff_drive_pose_controller/0.8.2-0 -yocs_joyop: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_joyop/0.8.2-0 -yocs_keyop: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_keyop/0.8.2-0 -yocs_localization_manager: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_localization_manager/0.8.2-0 -yocs_math_toolkit: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_math_toolkit/0.8.2-0 -yocs_msgs: - url: https://github.com/yujinrobot-release/yocs_msgs-release.git - vcs: git - version: release/kinetic/yocs_msgs/0.6.3-0 -yocs_navi_toolkit: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_navi_toolkit/0.8.2-0 -yocs_navigator: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_navigator/0.8.2-0 -yocs_rapps: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_rapps/0.8.2-0 -yocs_safety_controller: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_safety_controller/0.8.2-0 -yocs_velocity_smoother: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_velocity_smoother/0.8.2-0 -yocs_virtual_sensor: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_virtual_sensor/0.8.2-0 -yocs_waypoint_provider: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_waypoint_provider/0.8.2-0 -yocs_waypoints_navi: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yocs_waypoints_navi/0.8.2-0 -yosemite_valley: - url: https://github.com/ros-gbp/uav_testing-release.git - vcs: git - version: release/kinetic/yosemite_valley/0.0.1-1 -youbot_description: - url: https://github.com/youbot-release/youbot_description-release.git - vcs: git - version: release/kinetic/youbot_description/0.8.1-0 -youbot_driver: - url: https://github.com/youbot-release/youbot_driver-release.git - vcs: git - version: release/kinetic/youbot_driver/1.1.0-0 -ypspur: - url: https://github.com/openspur/yp-spur-release.git - vcs: git - version: release/kinetic/ypspur/1.16.0-1 -ypspur_ros: - url: https://github.com/openspur/ypspur_ros-release.git - vcs: git - version: release/kinetic/ypspur_ros/0.3.0-1 -yujin_ocs: - url: https://github.com/yujinrobot-release/yujin_ocs-release.git - vcs: git - version: release/kinetic/yujin_ocs/0.8.2-0 -zbar_ros: - url: https://github.com/ros-drivers-gbp/zbar_ros-release.git - vcs: git - version: release/kinetic/zbar_ros/0.1.0-0 -zeroconf_avahi: - url: https://github.com/yujinrobot-release/zeroconf_avahi_suite-release.git - vcs: git - version: release/kinetic/zeroconf_avahi/0.2.3-0 -zeroconf_avahi_demos: - url: https://github.com/yujinrobot-release/zeroconf_avahi_suite-release.git - vcs: git - version: release/kinetic/zeroconf_avahi_demos/0.2.3-0 -zeroconf_avahi_suite: - url: https://github.com/yujinrobot-release/zeroconf_avahi_suite-release.git - vcs: git - version: release/kinetic/zeroconf_avahi_suite/0.2.3-0 -zeroconf_jmdns_suite: - url: https://github.com/rosjava-release/zeroconf_jmdns_suite-release.git - vcs: git - version: release/kinetic/zeroconf_jmdns_suite/0.3.1-0 -zeroconf_msgs: - url: https://github.com/yujinrobot-release/zeroconf_msgs-release.git - vcs: git - version: release/kinetic/zeroconf_msgs/0.2.1-0 diff --git a/mrt_cmake_modules/yaml/external.yaml b/mrt_cmake_modules/yaml/external.yaml deleted file mode 100644 index e766ddd1db0..00000000000 --- a/mrt_cmake_modules/yaml/external.yaml +++ /dev/null @@ -1,51 +0,0 @@ -# This file contains all packages that should be resolved externally -# Note that Gitlab will always be checked first when resolving dependencies! -# -# When adding new entries, please make sure that: -# 1. The package provided there is stable and can be relied on -# 2. The package is a normal catkin package -# 3. The package name, the name for the dependency and the name in its package.xml are all identical -# 4. New entries are always in alphabetical order -# 5. You know what you are doing. Pushing changes will affect all users globally. -# -# Entries must look like this: -# example_package: <-- Name for the dependency (matching its package.xml) -# url: https://github.com/me/example_package.git <-- required, any url pointing to a repository is possible here -# vcs: git <-- optional (defaults to "git"), everything that wstool supports: git, hg, svn, bzr -# version: master <-- optional (defaults to its default branch), branch, tag, commit, ... -# -# or this: -# example_package: https://github.com/me/example_package.git (short version assuming git packages) - -automated_driving_msgs: https://github.com/fzi-forschungszentrum-informatik/automated_driving_msgs.git -iai_kinect2: https://github.com/code-iai/iai_kinect2.git -image_undistort: https://github.com/ethz-asl/image_undistort.git -lanelet2: https://github.com/fzi-forschungszentrum-informatik/Lanelet2.git -libnabo: https://github.com/ethz-asl/libnabo -libpointmatcher: https://github.com/ethz-asl/libpointmatcher.git -mrt_cmake_modules: https://github.com/KIT-MRT/mrt_cmake_modules.git -rosinterface_handler: https://github.com/KIT-MRT/rosinterface_handler.git -rosparam_handler: https://github.com/cbandera/rosparam_handler.git -rviz_satellite: https://github.com/gareth-cross/rviz_satellite.git -ct: https://github.com/ethz-adrl/control-toolbox.git -kindr: https://github.com/ANYbotics/kindr.git - -# CoInCar-Sim (https://github.com/coincar-sim/coincarsim_getting_started) -desired_motion_rviz_plugin_ros: https://github.com/coincar-sim/desired_motion_rviz_plugin_ros.git -lanelet_rviz_plugin_ros: https://github.com/coincar-sim/lanelet_rviz_plugin_ros.git -lanelet2_interface_ros: https://github.com/coincar-sim/lanelet2_interface_ros.git -motion_state_rviz_plugin_ros: https://github.com/coincar-sim/motion_state_rviz_plugin_ros.git -object_state_array_rviz_plugin_ros: https://github.com/coincar-sim/object_state_array_rviz_plugin_ros.git -sim_sample_actuator_ros_tool: https://github.com/coincar-sim/sim_sample_actuator_ros_tool.git -sim_sample_communication_ros_tool: https://github.com/coincar-sim/sim_sample_communication_ros_tool.git -sim_sample_perception_ros_tool: https://github.com/coincar-sim/sim_sample_perception_ros_tool.git -sim_sample_planning_ros_tool: https://github.com/coincar-sim/sim_sample_planning_ros_tool.git -sim_sample_prediction_ros_tool: https://github.com/coincar-sim/sim_sample_prediction_ros_tool.git -simulation_initialization_ros_tool: https://github.com/coincar-sim/simulation_initialization_ros_tool.git -simulation_management_ros_tool: https://github.com/coincar-sim/simulation_management_ros_tool.git -simulation_only_msgs: https://github.com/coincar-sim/simulation_only_msgs.git -util_automated_driving_msgs: https://github.com/coincar-sim/util_automated_driving_msgs.git -util_eigen_geometry: https://github.com/coincar-sim/util_eigen_geometry.git -util_geometry_msgs: https://github.com/coincar-sim/util_geometry_msgs.git -util_rviz: https://github.com/coincar-sim/util_rviz.git -util_simulation_only_msgs: https://github.com/coincar-sim/util_simulation_only_msgs.git diff --git a/mrt_cmake_modules/yaml/metapackages.yaml b/mrt_cmake_modules/yaml/metapackages.yaml deleted file mode 100644 index 7248505eb90..00000000000 --- a/mrt_cmake_modules/yaml/metapackages.yaml +++ /dev/null @@ -1,51 +0,0 @@ -# This file contains a list of metapackages and the packages they contain. -# This is required for resolving dependencies that are part of metapackages. -# The format is : [, , ...] - -lanelet2: -- lanelet2 -- lanelet2_core -- lanelet2_io -- lanelet2_projection -- lanelet2_traffic_rules -- lanelet2_routing -- lanelet2_python -- lanelet2_maps -- lanelet2_validation -- lanelet2_examples - -sceneshot: -- sceneshot -- sceneshot_core -- sceneshot_free_space -- sceneshot_gridmap -- sceneshot_gridmap_elevation -- sceneshot_gridmap_fusion -- sceneshot_gridmap_pcl -- sceneshot_gridmap_recursion -- sceneshot_gridmap_sensor -- sceneshot_io -- sceneshot_io_simulation -- sceneshot_object_detection -- sceneshot_object_tracking - -sceneshot_ros_tool: -- sceneshot_dynamic_reconfigure_ros -- sceneshot_ros -- sceneshot_ros_tool - -ct: -- ct -- ct_optcon -- ct_models -- ct_core -- ct_rbd - -mesh_tools: -- hdf5_map_io -- label_manager -- mesh_msgs -- mesh_msgs_hdf5 -- mesh_msgs_transform -- mesh_tools -- rviz_mesh_plugin diff --git a/mrt_cmake_modules/yaml/mrt-ros.yaml b/mrt_cmake_modules/yaml/mrt-ros.yaml deleted file mode 100644 index 04454bcb8de..00000000000 --- a/mrt_cmake_modules/yaml/mrt-ros.yaml +++ /dev/null @@ -1,546 +0,0 @@ -actionlib: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -actionlib_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -actionlib_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -angles: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -bond: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -bond_core: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -bondcpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -bondpy: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -camera_calibration: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -camera_calibration_parsers: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -camera_info_manager: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -catkin: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -class_loader: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -cmake_modules: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -collada_parser: - ubuntu: {xenial: mrt-ros-xenial} -collada_urdf: - ubuntu: {xenial: mrt-ros-xenial} -common_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -common_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -compressed_depth_image_transport: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -compressed_image_transport: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -control_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -control_toolbox: - ubuntu: {bionic: mrt-ros-bionic} -controller_interface: - ubuntu: {bionic: mrt-ros-bionic} -controller_manager: - ubuntu: {bionic: mrt-ros-bionic} -controller_manager_msgs: - ubuntu: {bionic: mrt-ros-bionic} -costmap_2d: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -cpp_common: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -cv_bridge: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -depth_image_proc: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -desktop: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -desktop_full: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostic_aggregator: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostic_analysis: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostic_common_diagnostics: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostic_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostic_updater: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diagnostics: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -diff_drive_controller: - ubuntu: {bionic: mrt-ros-bionic} -dynamic_reconfigure: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -eigen_conversions: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -eigen_stl_containers: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -executive_smach: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -filters: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -forward_command_controller: - ubuntu: {bionic: mrt-ros-bionic} -gazebo_dev: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gazebo_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gazebo_plugins: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gazebo_ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gazebo_ros_control: - ubuntu: {bionic: mrt-ros-bionic} -gazebo_ros_pkgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gencpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geneus: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -genlisp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -genmsg: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gennodejs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -genpy: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geodesy: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geographic_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geometric_shapes: - ubuntu: {xenial: mrt-ros-xenial} -geometry: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geometry_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -geometry_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -gl_dependency: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -graph_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -grid_map: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_core: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_cv: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_demos: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_filters: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_loader: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_msgs: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_octomap: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_ros: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_rviz_plugin: - ubuntu: {bionic: mrt-ros-bionic} -grid_map_visualization: - ubuntu: {bionic: mrt-ros-bionic} -hardware_interface: - ubuntu: {bionic: mrt-ros-bionic} -image_common: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_geometry: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_pipeline: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_proc: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_publisher: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_rotate: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_transport: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_transport_plugins: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -image_view: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -interactive_marker_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -interactive_markers: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -joint_limits_interface: - ubuntu: {bionic: mrt-ros-bionic} -joint_state_controller: - ubuntu: {bionic: mrt-ros-bionic} -joint_state_publisher: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -kdl_conversions: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -kdl_parser: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -kdl_parser_py: - ubuntu: {bionic: mrt-ros-bionic} -laser_assembler: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -laser_filters: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -laser_geometry: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -laser_pipeline: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -librviz_tutorial: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -map_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -map_server: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -media_export: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -message_filters: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -message_generation: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -message_runtime: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -mk: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -nav_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -nodelet: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -nodelet_core: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -nodelet_topic_tools: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -nodelet_tutorial_math: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -octomap: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -octomap_msgs: - ubuntu: {bionic: mrt-ros-bionic} -opencv3: - ubuntu: {xenial: mrt-ros-xenial} -orocos_kdl: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -pcl_conversions: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -pcl_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -pcl_ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -perception: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -perception_pcl: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -pluginlib: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -pluginlib_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -polled_camera: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -position_controllers: - ubuntu: {bionic: mrt-ros-bionic} -python_orocos_kdl: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -python_qt_binding: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -qt_dotgraph: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -qt_gui: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -qt_gui_cpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -qt_gui_py_common: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -qwt_dependency: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -random_numbers: - ubuntu: {xenial: mrt-ros-xenial} -realtime_tools: - ubuntu: {bionic: mrt-ros-bionic} -resource_retriever: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -robot: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -robot_model: - ubuntu: {xenial: mrt-ros-xenial} -robot_state_publisher: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros_base: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros_comm: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros_core: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros_environment: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -ros_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosapi: - ubuntu: {bionic: mrt-ros-bionic} -rosauth: - ubuntu: {bionic: mrt-ros-bionic} -rosbag: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosbag_migration_rule: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosbag_storage: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosbash: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosboost_cfg: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosbridge_library: - ubuntu: {bionic: mrt-ros-bionic} -rosbridge_msgs: - ubuntu: {bionic: mrt-ros-bionic} -rosbridge_server: - ubuntu: {bionic: mrt-ros-bionic} -rosbuild: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosclean: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosconsole: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosconsole_bridge: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscpp_core: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscpp_serialization: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscpp_traits: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscpp_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roscreate: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosgraph: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosgraph_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslang: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslaunch: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslib: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslint: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslisp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roslz4: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosmake: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosmaster: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosmsg: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosnode: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosout: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rospack: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosparam: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rospy: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rospy_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosservice: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rostest: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rostime: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rostopic: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rosunit: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -roswtf: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_action: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_bag: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_bag_plugins: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_common_plugins: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_console: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_dep: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_graph: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_gui: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_gui_cpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_gui_py: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_image_view: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_launch: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_logger_level: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_moveit: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_msg: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_nav_view: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_plot: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_pose_view: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_publisher: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_py_common: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_py_console: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_reconfigure: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_robot_dashboard: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_robot_monitor: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_robot_plugins: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_robot_steering: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_runtime_monitor: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_rviz: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_service_caller: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_shell: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_srv: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_tf_tree: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_top: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_topic: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rqt_web: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rviz: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rviz_plugin_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rviz_python_tutorial: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -rviz_visual_tools: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -self_test: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -sensor_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -shape_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -simulators: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -smach: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -smach_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -smach_ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -smclib: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -socketcan_interface: - ubuntu: {bionic: mrt-ros-bionic} -stage: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -stage_ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -std_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -std_srvs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -stereo_image_proc: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -stereo_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_eigen: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_geometry_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_kdl: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_py: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_ros: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -tf2_sensor_msgs: - ubuntu: {bionic: mrt-ros-bionic} -tf_conversions: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -theora_image_transport: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -topic_tools: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -trajectory_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -transmission_interface: - ubuntu: {bionic: mrt-ros-bionic} -turtle_actionlib: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -turtle_tf: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -turtle_tf2: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -turtlesim: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -unique_id: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -urdf: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -urdf_parser_plugin: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -urdf_sim_tutorial: - ubuntu: {bionic: mrt-ros-bionic} -urdf_tutorial: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -urdfdom_py: - ubuntu: {bionic: mrt-ros-bionic} -uuid_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -vision_opencv: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -visualization_marker_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -visualization_msgs: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -visualization_tutorials: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -viz: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -voxel_grid: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -webkit_dependency: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -xacro: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} -xmlrpcpp: - ubuntu: {bionic: mrt-ros-bionic, xenial: mrt-ros-xenial} diff --git a/utilities/vehicle_socket/CMakeLists.txt b/utilities/vehicle_socket/CMakeLists.txt index ee316afb3bc..8a58f50fd88 100644 --- a/utilities/vehicle_socket/CMakeLists.txt +++ b/utilities/vehicle_socket/CMakeLists.txt @@ -1,29 +1,18 @@ cmake_minimum_required(VERSION 2.8.3) project(vehicle_socket) - find_package(autoware_build_flags REQUIRED) - -find_package(autoware_msgs REQUIRED) - -find_package(tablet_socket_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS + autoware_can_msgs + autoware_msgs roscpp std_msgs - autoware_msgs - autoware_can_msgs tablet_socket_msgs ) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") -catkin_package(CATKIN_DEPENDS - roscpp - std_msgs - autoware_can_msgs - autoware_msgs - tablet_socket_msgs -) +catkin_package() include_directories( ${catkin_INCLUDE_DIRS} @@ -31,17 +20,14 @@ include_directories( add_executable(vehicle_receiver nodes/vehicle_receiver/vehicle_receiver.cpp) target_link_libraries(vehicle_receiver ${catkin_LIBRARIES}) -add_dependencies(vehicle_receiver - ${catkin_EXPORTED_TARGETS} - ) +add_dependencies(vehicle_receiver ${catkin_EXPORTED_TARGETS}) add_executable(vehicle_sender nodes/vehicle_sender/vehicle_sender.cpp) target_link_libraries(vehicle_sender ${catkin_LIBRARIES}) -add_dependencies(vehicle_sender - ${catkin_EXPORTED_TARGETS} - ) +add_dependencies(vehicle_sender ${catkin_EXPORTED_TARGETS}) install(TARGETS vehicle_sender vehicle_receiver - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) \ No newline at end of file + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/utilities/vehicle_socket/nodes/vehicle_sender/vehicle_sender.cpp b/utilities/vehicle_socket/nodes/vehicle_sender/vehicle_sender.cpp index 70437419509..2957b3c8b62 100644 --- a/utilities/vehicle_socket/nodes/vehicle_sender/vehicle_sender.cpp +++ b/utilities/vehicle_socket/nodes/vehicle_sender/vehicle_sender.cpp @@ -16,7 +16,7 @@ #include #include "autoware_msgs/VehicleCmd.h" - +#include "autoware_msgs/Gear.h" #include #include #include @@ -27,7 +27,8 @@ #include #include -struct CommandData { +struct CommandData +{ double linear_x; double angular_z; int modeValue; @@ -42,16 +43,25 @@ struct CommandData { void reset(); }; +enum class ZMPGear +{ + Drive = 1, + Reverse = 2, + Low = 3, + Neutral = 4, + Park = 5, +}; + void CommandData::reset() { - linear_x = 0; - angular_z = 0; - modeValue = 0; - gearValue = 0; - lampValue = 0; - accellValue = 0; - brakeValue = 0; - steerValue = 0; + linear_x = 0; + angular_z = 0; + modeValue = 0; + gearValue = 0; + lampValue = 0; + accellValue = 0; + brakeValue = 0; + steerValue = 0; linear_velocity = -1; steering_angle = 0; } @@ -63,17 +73,41 @@ static void vehicleCmdCallback(const autoware_msgs::VehicleCmd& msg) command_data.linear_x = msg.twist_cmd.twist.linear.x; command_data.angular_z = msg.twist_cmd.twist.angular.z; command_data.modeValue = msg.mode; - command_data.gearValue = msg.gear; - if(msg.lamp_cmd.l == 0 && msg.lamp_cmd.r == 0) { + if (msg.gear_cmd.gear == autoware_msgs::Gear::DRIVE) + { + command_data.gearValue = static_cast(ZMPGear::Drive); + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::REVERSE) + { + command_data.gearValue = static_cast(ZMPGear::Reverse); + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::LOW) + { + command_data.gearValue = static_cast(ZMPGear::Low); + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::NEUTRAL) + { + command_data.gearValue = static_cast(ZMPGear::Neutral); + } + else if (msg.gear_cmd.gear == autoware_msgs::Gear::PARK) + { + command_data.gearValue = static_cast(ZMPGear::Park); + } + + if (msg.lamp_cmd.l == 0 && msg.lamp_cmd.r == 0) + { command_data.lampValue = 0; } - else if (msg.lamp_cmd.l == 1 && msg.lamp_cmd.r == 0) { + else if (msg.lamp_cmd.l == 1 && msg.lamp_cmd.r == 0) + { command_data.lampValue = 1; } - else if (msg.lamp_cmd.l == 0 && msg.lamp_cmd.r == 1) { + else if (msg.lamp_cmd.l == 0 && msg.lamp_cmd.r == 1) + { command_data.lampValue = 2; } - else if (msg.lamp_cmd.l == 1 && msg.lamp_cmd.r == 1) { + else if (msg.lamp_cmd.l == 1 && msg.lamp_cmd.r == 1) + { command_data.lampValue = 3; } command_data.accellValue = msg.accel_cmd.accel; @@ -83,9 +117,9 @@ static void vehicleCmdCallback(const autoware_msgs::VehicleCmd& msg) command_data.steering_angle = msg.ctrl_cmd.steering_angle; } -static void *sendCommand(void *arg) +static void* sendCommand(void* arg) { - int *client_sockp = static_cast(arg); + int* client_sockp = static_cast(arg); int client_sock = *client_sockp; delete client_sockp; @@ -103,12 +137,14 @@ static void *sendCommand(void *arg) std::string cmd(oss.str()); ssize_t n = write(client_sock, cmd.c_str(), cmd.size()); - if(n < 0){ + if (n < 0) + { std::perror("write"); return nullptr; } - if(close(client_sock) == -1){ + if (close(client_sock) == -1) + { std::perror("close"); return nullptr; } @@ -117,12 +153,13 @@ static void *sendCommand(void *arg) return nullptr; } -static void* receiverCaller(void *unused) +static void* receiverCaller(void* unused) { constexpr int listen_port = 10001; int sock = socket(AF_INET, SOCK_STREAM, 0); - if(sock == -1){ + if (sock == -1) + { std::perror("socket"); return nullptr; } @@ -136,25 +173,29 @@ static void* receiverCaller(void *unused) addr.sin_port = htons(listen_port); addr.sin_addr.s_addr = INADDR_ANY; - int ret = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); - if(ret == -1){ + int ret = bind(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret == -1) + { std::perror("bind"); goto error; } ret = listen(sock, 20); - if(ret == -1){ + if (ret == -1) + { std::perror("listen"); goto error; } - while(true){ - //get connect to android + while (true) + { + // get connect to android std::cout << "Waiting access..." << std::endl; - int *client_sock = new int(); + int* client_sock = new int(); *client_sock = accept(sock, reinterpret_cast(&client), &len); - if(*client_sock == -1){ + if (*client_sock == -1) + { std::perror("accept"); break; } @@ -162,12 +203,14 @@ static void* receiverCaller(void *unused) std::cout << "get connect." << std::endl; pthread_t th; - if(pthread_create(&th, nullptr, sendCommand, static_cast(client_sock)) != 0){ + if (pthread_create(&th, nullptr, sendCommand, static_cast(client_sock)) != 0) + { std::perror("pthread_create"); break; } - if(pthread_detach(th) != 0){ + if (pthread_detach(th) != 0) + { std::perror("pthread_detach"); break; } @@ -178,9 +221,9 @@ static void* receiverCaller(void *unused) return nullptr; } -int main(int argc, char **argv) +int main(int argc, char** argv) { - ros::init(argc ,argv, "vehicle_sender") ; + ros::init(argc, argv, "vehicle_sender"); ros::NodeHandle nh; std::cout << "vehicle sender" << std::endl; @@ -189,12 +232,14 @@ int main(int argc, char **argv) command_data.reset(); pthread_t th; - if(pthread_create(&th, nullptr, receiverCaller, nullptr) != 0){ + if (pthread_create(&th, nullptr, receiverCaller, nullptr) != 0) + { std::perror("pthread_create"); std::exit(1); } - if (pthread_detach(th) != 0){ + if (pthread_detach(th) != 0) + { std::perror("pthread_detach"); std::exit(1); } From 0e5c6007bf187256899ef7335b410722f52827d0 Mon Sep 17 00:00:00 2001 From: Patrick Musau Date: Sun, 4 Jul 2021 07:53:31 -0500 Subject: [PATCH 04/23] Feature/lanelet2 autoware update (#158) * lanelet and minimal autoware update Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * revert lanelet CMakelists.txt to ensure correct catkin imports * update autoware packages * revert back * revert ekf_localizer except tf_rate, broadcast, tf_rate * let map be configurable * new package upgrades --- common/CONTRIBUTING.md | 10 +- common/DISCLAIMER.md | 50 + common/README.md | 3 + common/SUPPORT.md | 4 +- common/amathutils_lib/CMakeLists.txt | 45 +- .../include/amathutils_lib/amathutils.hpp | 40 +- .../amathutils_lib/butterworth_filter.hpp | 26 +- .../include/amathutils_lib/kalman_filter.hpp | 22 +- .../time_delay_kalman_filter.hpp | 15 +- common/amathutils_lib/package.xml | 2 + common/amathutils_lib/src/Amathutils.cpp | 88 +- .../amathutils_lib/src/butterworth_filter.cpp | 197 +- common/amathutils_lib/src/kalman_filter.cpp | 8 +- .../src/time_delay_kalman_filter.cpp | 13 +- .../test/src/test_amathutils_lib.cpp | 538 +- .../test/src/test_butterworth_filter.cpp | 266 +- .../test/src/test_kalman_filter.cpp | 250 +- .../test/test_butterworth_filter.test | 2 +- common/build_depends.repos | 10 +- common/gnss/CMakeLists.txt | 60 +- common/gnss/include/gnss/geo_pos_conv.hpp | 47 +- common/gnss/package.xml | 1 + common/gnss/src/geo_pos_conv.cpp | 165 +- common/gnss/test/test_gnss.cpp | 36 +- .../lanelet2_extension/utility/query.h | 46 +- .../visualization/visualization.h | 8 + common/lanelet2_extension/lib/query.cpp | 128 +- common/lanelet2_extension/lib/utilities.cpp | 90 +- .../lanelet2_extension/lib/visualization.cpp | 133 +- .../test/src/test_query.cpp | 4 +- common/libvectormap/CMakeLists.txt | 8 + .../libvectormap/include/libvectormap/Math.h | 93 +- .../include/libvectormap/vector_map.h | 118 +- common/libvectormap/package.xml | 1 + common/libvectormap/src/vector_map.cpp | 219 +- common/libwaypoint_follower/CMakeLists.txt | 103 +- .../libwaypoint_follower.h | 43 +- .../libwaypoint_follower/pure_pursuit.h | 65 + .../test_libwaypoint_follower.h} | 23 +- common/libwaypoint_follower/package.xml | 2 + .../src/libwaypoint_follower.cpp | 232 +- .../libwaypoint_follower/src/pure_pursuit.cpp | 196 + .../test/src/test_libwaypoint_follower.cpp | 333 +- .../test/src/test_pure_pursuit.cpp | 62 + .../test/test_pure_pursuit.test | 5 + .../launch/lanelet2_map_loader.launch | 10 +- .../map_file/launch/points_map_loader.launch | 15 + .../map_file/launch/vector_map_loader.launch | 11 + .../lanelet2_map_visualization.cpp | 41 +- .../vector_map_loader/vector_map_loader.cpp | 347 +- common/map_file/package.xml | 1 + common/op_planner/CMakeLists.txt | 80 +- .../include/op_planner/BehaviorPrediction.h | 1552 ++--- .../include/op_planner/BehaviorStateMachine.h | 254 +- .../include/op_planner/DecisionMaker.h | 116 +- .../include/op_planner/LocalPlannerH.h | 256 +- .../include/op_planner/MappingHelpers.h | 390 +- .../include/op_planner/MatrixOperations.h | 106 +- .../include/op_planner/PassiveDecisionMaker.h | 18 +- .../include/op_planner/PlannerCommonDef.h | 152 +- .../op_planner/include/op_planner/PlannerH.h | 47 +- .../include/op_planner/PlanningHelpers.h | 187 +- .../include/op_planner/RoadNetwork.h | 1878 +++--- .../include/op_planner/SimuDecisionMaker.h | 66 +- .../include/op_planner/TrajectoryCosts.h | 44 +- .../op_planner/TrajectoryDynamicCosts.h | 78 +- common/op_planner/src/BehaviorPrediction.cpp | 1270 ++-- .../op_planner/src/BehaviorStateMachine.cpp | 620 +- common/op_planner/src/DecisionMaker.cpp | 674 +- common/op_planner/src/LocalPlannerH.cpp | 1244 ++-- common/op_planner/src/MappingHelpers.cpp | 5974 ++++++++--------- .../op_planner/src/PassiveDecisionMaker.cpp | 130 +- common/op_planner/src/PlannerH.cpp | 897 +-- common/op_planner/src/PlanningHelpers.cpp | 4875 +++++++------- common/op_planner/src/SimuDecisionMaker.cpp | 358 +- common/op_planner/src/TrajectoryCosts.cpp | 648 +- .../op_planner/src/TrajectoryDynamicCosts.cpp | 1582 ++--- .../src/test_BuildPlanningSearchTreeV2.cpp | 228 + common/op_ros_helpers/CMakeLists.txt | 29 +- .../include/op_ros_helpers/PolygonGenerator.h | 118 +- .../include/op_ros_helpers/op_ROSHelpers.h | 330 +- .../op_ros_helpers/src/PolygonGenerator.cpp | 166 +- common/op_ros_helpers/src/op_ROSHelpers.cpp | 3052 ++++----- common/op_utility/CMakeLists.txt | 7 +- common/op_utility/include/op_utility/DataRW.h | 1312 ++-- .../op_utility/include/op_utility/UtilityH.h | 122 +- common/op_utility/src/DataRW.cpp | 2804 ++++---- common/op_utility/src/UtilityH.cpp | 496 +- common/ros_observer/CMakeLists.txt | 16 +- common/ros_observer/src/ros_observer.cpp | 1 - common/tvm_utility/.gitignore | 3 + common/tvm_utility/CMakeLists.txt | 92 + common/tvm_utility/README.md | 36 + .../include/tvm_utility/pipeline.h | 310 + common/tvm_utility/package.xml | 23 + .../tvm_utility/test/yolo_v2_tiny/README.md | 35 + .../tvm_utility/test/yolo_v2_tiny/labels.txt | 80 + common/tvm_utility/test/yolo_v2_tiny/main.cpp | 331 + common/vector_map/CMakeLists.txt | 10 +- .../include/vector_map/vector_map.h | 50 +- .../vector_map/lib/vector_map/vector_map.cpp | 16 +- common/vector_map/package.xml | 1 + common/vector_map_server/CMakeLists.txt | 64 +- .../vector_map_client/vector_map_client.cpp | 10 +- .../vector_map_server/vector_map_server.cpp | 18 +- common/vector_map_server/package.xml | 1 + common/vehicle_sim_model/CMakeLists.txt | 65 + .../vehicle_model_constant_acceleration.h | 113 + .../vehicle_sim_model/vehicle_model_ideal.h | 174 + .../vehicle_model_interface.h | 129 + .../vehicle_model_time_delay.h | 242 + common/vehicle_sim_model/package.xml | 20 + .../scripts/README_fitParamDelayInputModel.md | 28 + .../scripts/fitParamDelayInputModel.py | 139 + .../vehicle_model_constant_acceleration.cpp | 92 + .../src/vehicle_model_ideal.cpp | 108 + .../src/vehicle_model_interface.cpp | 53 + .../src/vehicle_model_time_delay.cpp | 240 + .../test/src/test_vehicle_sim_model.cpp | 255 + .../test/test_vehicle_sim_model.test | 5 + .../include/ekf_localizer/ekf_localizer.h | 6 +- .../ekf_localizer/launch/ekf_localizer.launch | 4 +- .../ekf_localizer/src/ekf_localizer.cpp | 6 +- core_perception/gnss_localizer/CMakeLists.txt | 26 +- .../gnss_localizer/launch/nmea2tfpose.launch | 2 + .../gnss_localizer/test/nmea_test.cpp | 244 +- .../CHANGELOG.rst | 0 .../imm_ukf_pda_track/CMakeLists.txt | 80 + .../README.md | 0 .../include/imm_ukf_pda/imm_ukf_pda.h | 0 .../include/imm_ukf_pda/ukf.h | 0 .../imm_ukf_pda_lanelet2.h | 0 .../launch/imm_ukf_pda_track.launch | 52 + .../launch/imm_ukf_pda_track_lanelet2.launch | 52 + .../launch/imm_ukf_pda_track_option.launch | 66 + .../nodes/imm_ukf_pda/imm_ukf_pda.cpp | 6 +- .../nodes/imm_ukf_pda/imm_ukf_pda_main.cpp | 0 .../nodes/imm_ukf_pda/ukf.cpp | 0 .../imm_ukf_pda_lanelet2.cpp | 14 +- .../imm_ukf_pda_main_lanelet2.cpp | 5 +- .../package.xml | 0 .../CMakeLists.txt | 112 +- .../lidar_apollo_cnn_seg_detect/README.md | 20 +- .../include/cnn_segmentation.h | 6 +- .../include/feature_generator.h | 6 +- .../launch/lidar_apollo_cnn_seg_detect.launch | 10 + .../nodes/cnn_segmentation.cpp | 58 +- .../nodes/feature_generator.cpp | 65 +- .../lidar_apollo_cnn_seg_detect_node.cpp | 2 + .../lidar_euclidean_cluster_detect.cpp | 69 +- .../lidar_fake_perception/CMakeLists.txt | 25 +- .../nodes/lidar_fake_perception.cpp | 2 +- .../lidar_imm_ukf_pda_track/CMakeLists.txt | 84 - .../launch/imm_ukf_pda_track.launch | 51 - .../launch/imm_ukf_pda_track_lanelet2.launch | 51 - .../launch/imm_ukf_pda_track_option.launch | 2 +- .../lidar_kf_contour_track/CMakeLists.txt | 2 + .../lidar_kf_contour_track/package.xml | 2 + .../lidar_localizer/CMakeLists.txt | 191 +- .../launch/ndt_matching.launch | 6 +- .../approximate_ndt_mapping.cpp | 40 +- .../nodes/icp_matching/icp_matching.cpp | 43 +- .../nodes/ndt_mapping/ndt_mapping.cpp | 101 +- .../nodes/ndt_mapping_tku/mapping.cpp | 5 +- .../nodes/ndt_mapping_tku/ndt_mapping_tku.cpp | 43 +- .../nodes/ndt_matching/ndt_matching.cpp | 296 +- .../ndt_matching_monitor.h | 152 +- .../ndt_matching_monitor_node.cpp | 8 +- .../ndt_matching_tku/ndt_matching_tku.cpp | 41 +- .../nodes/queue_counter/queue_counter.cpp | 6 +- core_perception/lidar_localizer/package.xml | 1 + .../test/test_launch_ndt_matching.test | 7 +- .../lidar_point_pillars/CMakeLists.txt | 199 +- core_perception/lidar_point_pillars/README.md | 50 +- .../lidar_point_pillars/point_pillars.h | 129 +- .../point_pillars_pfe/pfe_tvm_pipeline.h | 85 + .../point_pillars_rpn/rpn_tvm_pipeline.h | 92 + .../nodes/pfe_tvm_pipeline.cpp | 90 + .../nodes/point_pillars.cpp | 162 +- .../nodes/point_pillars_ros.cpp | 18 +- .../nodes/rpn_tvm_pipeline.cpp | 90 + .../lidar_point_pillars/package.xml | 1 + .../test/data/{ => data_onnx}/dummy.onnx | Bin .../test/data/data_tvm/deploy_graph.json | 79 + .../test/data/data_tvm/deploy_lib.so | Bin 0 -> 16720 bytes .../test/data/data_tvm/deploy_param.params | Bin 0 -> 228 bytes .../test/src/test_point_pillars.cpp | 14 +- .../tvm_point_pillars_pfe/README.md | 8 + .../tvm_point_pillars_rpn/README.md | 8 + .../lidar_shape_estimation/CMakeLists.txt | 115 +- .../model_interface.hpp | 2 +- .../shape_estimator.hpp | 2 +- .../lidar_shape_estimation/package.xml | 3 +- .../src/model/bounding_box.cpp | 14 +- .../src/model/convex_hull.cpp | 4 +- .../src/model/cylinder.cpp | 16 +- .../src/shape_estimator.cpp | 5 +- .../test/src/test_lidar_shape_estimation.cpp | 6 +- .../naive_motion_predict/README.md | 2 +- core_perception/ndt_cpu/CMakeLists.txt | 92 +- .../ndt_cpu/NormalDistributionsTransform.h | 124 +- .../ndt_cpu/include/ndt_cpu/Octree.h | 110 +- .../ndt_cpu/include/ndt_cpu/Registration.h | 62 +- .../include/ndt_cpu/SymmetricEigenSolver.h | 354 +- .../ndt_cpu/include/ndt_cpu/VoxelGrid.h | 186 +- .../src/NormalDistributionsTransform.cpp | 1042 +-- core_perception/ndt_cpu/src/Octree.cpp | 1384 ++-- core_perception/ndt_cpu/src/Registration.cpp | 50 +- core_perception/ndt_cpu/src/VoxelGrid.cpp | 912 +-- .../points_preprocessor/CMakeLists.txt | 245 +- .../ray_ground_filter/atan2_utils.h | 83 + .../ray_ground_filter/ray_ground_filter.h | 120 +- .../launch/compare_map_filter.launch | 32 +- .../launch/ray_ground_filter.launch | 6 +- .../launch/space_filter.launch | 36 +- .../cloud_transformer_node.cpp | 276 +- .../ray_ground_filter/ray_ground_filter.cpp | 457 +- .../ring_ground_filter/ring_ground_filter.cpp | 586 +- .../nodes/space_filter/space_filter.cpp | 206 +- .../test/data/input_blob.bin | Bin 0 -> 1780192 bytes .../test/data/input_structured.txt | 30 + .../test/data/output_ground_blob.bin | Bin 0 -> 269632 bytes .../test/data/output_ground_structured.txt | 30 + .../test/data/output_no_ground_blob.bin | Bin 0 -> 1510560 bytes .../test/data/output_no_ground_structured.txt | 30 + .../test/data/transformed_blob.bin | Bin 0 -> 1780192 bytes .../test/data/transformed_structured.txt | 30 + .../test/include/sensor_msg_comparison.h | 414 ++ .../test/include/sensor_msg_serialization.h | 124 + .../test/include/test_fast_atan2.h | 44 + .../test/include/test_ray_groundfilter.h | 172 +- .../test/src/test_points_preprocessor.cpp | 16 + .../test/test_points_preprocessor.test | 9 +- .../feat_proj_lanelet2_core.h | 2 + .../launch/feat_proj_lanelet2.launch | 10 +- .../launch/feat_proj_option.launch | 34 +- .../nodes/feat_proj/feat_proj.cpp | 4 + .../feat_proj_lanelet2_core.cpp | 10 +- .../vel_pose_diff_checker/CMakeLists.txt | 72 +- .../config/health_checker.yaml | 13 + .../vel_pose_diff_checker/value_time_queue.h | 22 +- .../vel_pose_diff_checker_core.h | 117 +- .../launch/vel_pose_diff_checker.launch | 10 +- .../vel_pose_diff_checker/package.xml | 2 + .../src/value_time_queue.cpp | 14 +- .../src/vel_pose_diff_checker_core.cpp | 339 +- .../src/vel_pose_diff_checker_node.cpp | 4 +- .../test/src/test_vel_pose_diff_checker.cpp | 14 +- core_planning/astar_search/CMakeLists.txt | 29 +- .../astar_search/src/astar_search.cpp | 12 +- .../astar_search/test/src/test_astar_util.cpp | 202 +- .../astar_search/test/src/test_main.cpp | 10 +- .../decision_maker/decision_maker_node.hpp | 3 +- .../launch/decision_maker.launch | 2 + .../decision_maker_node_callback.cpp | 8 +- .../decision_maker_node_init.cpp | 12 +- .../decision_maker_node_state_motion.cpp | 35 +- .../test/src/test_node_decision.cpp | 6 +- .../test/src/test_node_state_drive.cpp | 12 +- core_planning/lane_planner/CMakeLists.txt | 18 +- core_planning/lane_planner/README.md | 3 +- .../lane_planner/lane_planner_vmap.hpp | 15 +- .../lane_planner/include/lane_select_core.h | 56 +- .../lane_planner/launch/lane_navi.launch | 16 +- .../launch/lane_rule_option.launch | 14 +- .../lane_planner/launch/lane_select.launch | 8 +- .../lib/lane_planner/lane_planner_vmap.cpp | 1113 +-- .../nodes/lane_navi/lane_navi.cpp | 308 +- .../nodes/lane_rule/lane_rule.cpp | 28 +- .../lane_rule_lanelet2/lane_rule_lanelet2.cpp | 6 +- .../nodes/lane_select/lane_select_core.cpp | 213 +- core_planning/lane_planner/package.xml | 8 +- .../test/src/test_lane_select.cpp | 6 +- .../ll2_global_planner/CMakeLists.txt | 89 + core_planning/ll2_global_planner/LICENSE | 19 + core_planning/ll2_global_planner/README.md | 36 + .../ll2_global_planner/config/params.yaml | 0 .../ll2_global_planner_nodelet.hpp | 69 + .../launch/ll2_global_planner_node.launch | 5 + core_planning/ll2_global_planner/nodelets.xml | 9 + core_planning/ll2_global_planner/package.xml | 24 + .../src/ll2_global_planner_node.cpp | 24 + .../src/ll2_global_planner_nodelet.cpp | 260 + .../op_global_planner/CMakeLists.txt | 14 - .../include/op_global_planner_core.h | 206 +- .../launch/op_global_planner.launch | 48 +- .../nodes/op_global_planner.cpp | 8 +- .../nodes/op_global_planner_core.cpp | 908 +-- core_planning/op_local_planner/CMakeLists.txt | 20 +- .../include/op_behavior_selector_core.h | 240 +- .../include/op_motion_predictor_core.h | 184 +- .../include/op_trajectory_evaluator_core.h | 104 +- .../include/op_trajectory_generator_core.h | 98 +- .../launch/op_behavior_selector.launch | 20 +- .../launch/op_common_params.launch | 190 +- .../launch/op_motion_predictor.launch | 48 +- .../launch/op_trajectory_evaluator.launch | 28 +- .../launch/op_trajectory_generator.launch | 30 +- .../op_behavior_selector.cpp | 8 +- .../op_behavior_selector_core.cpp | 1072 +-- .../op_common_params/op_common_params.cpp | 20 +- .../op_motion_predictor.cpp | 8 +- .../op_motion_predictor_core.cpp | 872 +-- .../op_trajectory_evaluator.cpp | 8 +- .../op_trajectory_evaluator_core.cpp | 510 +- .../op_trajectory_generator.cpp | 8 +- .../op_trajectory_generator_core.cpp | 408 +- core_planning/op_utilities/CMakeLists.txt | 16 +- .../op_utilities/include/BagTopicPlayer.h | 348 +- .../op_utilities/include/DrawingHelpers.h | 46 +- .../op_utilities/include/MainWindowWrapper.h | 186 +- .../op_utilities/include/op_bag_player_core.h | 68 +- .../include/op_data_logger_core.h | 78 +- .../include/op_map_converter_core.h | 106 +- .../op_utilities/include/op_pose2tf_core.h | 14 +- .../op_utilities/launch/op_bag_player.launch | 66 +- .../op_utilities/launch/op_data_logger.launch | 18 +- .../launch/op_map_converter.launch | 6 +- .../op_utilities/launch/op_pose2tf.launch | 16 +- .../nodes/op_bag_player/DrawingHelpers.cpp | 930 +-- .../nodes/op_bag_player/MainWindowWrapper.cpp | 348 +- .../nodes/op_bag_player/op_bag_player.cpp | 56 +- .../op_bag_player/op_bag_player_core.cpp | 516 +- .../nodes/op_data_logger/op_data_logger.cpp | 8 +- .../op_data_logger/op_data_logger_core.cpp | 534 +- .../nodes/op_pose2tf/op_pose2tf.cpp | 8 +- .../nodes/op_pose2tf/op_pose2tf_core.cpp | 46 +- core_planning/op_utilities/package.xml | 1 + .../include/pure_pursuit/pure_pursuit.h | 29 +- .../include/pure_pursuit/pure_pursuit_core.h | 46 +- .../include/pure_pursuit/pure_pursuit_viz.h | 16 +- .../pure_pursuit/src/pure_pursuit.cpp | 219 +- .../pure_pursuit/src/pure_pursuit_core.cpp | 228 +- .../pure_pursuit/src/pure_pursuit_viz.cpp | 98 +- .../test/src/test_pure_pursuit.cpp | 35 +- .../state_machine_lib/CMakeLists.txt | 4 +- .../include/state_machine_lib/state_flags.hpp | 8 - core_planning/way_planner/CMakeLists.txt | 13 +- .../way_planner/include/ROSHelpers.h | 226 +- .../way_planner/include/SocketServer.h | 73 +- .../way_planner/include/way_planner_core.h | 308 +- .../way_planner/launch/way_planner.launch | 49 +- .../way_planner/nodes/ROSHelpers.cpp | 781 ++- .../way_planner/nodes/SocketServer.cpp | 480 +- .../way_planner/nodes/way_planner.cpp | 12 +- .../way_planner/nodes/way_planner_core.cpp | 1420 ++-- core_planning/way_planner/package.xml | 1 + .../.github/workflows/native-ci.yaml | 42 + documentation/.gitlab-ci.yml | 95 - .../.gitlab/issue_templates/bug_report.md | 57 - .../issue_templates/feature_request.md | 26 - .../.gitlab/issue_templates/other_issue.md | 13 - .../merge_request_templates/bug_fix.md | 69 - .../feature_implementation.md | 39 - documentation/CONTRIBUTING.md | 10 +- documentation/DISCLAIMER.md | 50 + documentation/README.md | 2 + documentation/SUPPORT.md | 4 +- .../autoware_quickstart_examples/README.md | 8 +- .../launch/rosbag_demo/README.md | 2 +- .../launch/rosbag_demo/my_map.launch | 6 +- .../rosbag_demo/my_mission_planning.launch | 2 +- .../plugins/leaf/waypoint_loader.xml | 14 +- .../plugins/leaf/waypoint_loader.yaml | 13 +- .../calibration_publisher/CMakeLists.txt | 56 +- utilities/calibration_publisher/package.xml | 5 +- .../src/calibration_publisher.cpp | 64 +- .../nodes/get_Depth/get_Depth.cpp | 4 +- .../nodes/mqtt_receiver/mqtt_receiver.cpp | 2 +- .../multi_lidar_calibrator/CMakeLists.txt | 68 +- utilities/multi_lidar_calibrator/README.md | 6 +- .../include/multi_lidar_calibrator.h | 106 +- .../launch/multi_lidar_calibrator.launch | 57 +- .../src/multi_lidar_calibrator.cpp | 232 +- .../src/multi_lidar_calibrator_node.cpp | 8 +- utilities/runtime_manager/CMakeLists.txt | 195 +- .../runtime_manager/scripts/computing.yaml | 76 +- utilities/runtime_manager/scripts/map.yaml | 16 +- utilities/system_monitor/CHANGELOG.rst | 8 + utilities/system_monitor/CMakeLists.txt | 293 + utilities/system_monitor/README.md | 157 + utilities/system_monitor/cmake/FindNVML.cmake | 20 + .../system_monitor/config/system_monitor.yaml | 38 + .../system_monitor/docs/class_diagrams.md | 29 + utilities/system_monitor/docs/hdd_reader.md | 50 + .../docs/images/class_cpu_monitor.png | Bin 0 -> 127936 bytes .../docs/images/class_gpu_monitor.png | Bin 0 -> 135193 bytes .../docs/images/class_hdd_monitor.png | Bin 0 -> 47011 bytes .../docs/images/class_mem_monitor.png | Bin 0 -> 44561 bytes .../docs/images/class_net_monitor.png | Bin 0 -> 43396 bytes .../docs/images/class_ntp_monitor.png | Bin 0 -> 43371 bytes .../docs/images/class_process_monitor.png | Bin 0 -> 108046 bytes .../docs/images/seq_cpu_monitor.png | Bin 0 -> 108200 bytes .../docs/images/seq_gpu_monitor.png | Bin 0 -> 111248 bytes .../docs/images/seq_hdd_monitor.png | Bin 0 -> 63852 bytes .../docs/images/seq_mem_monitor.png | Bin 0 -> 60290 bytes .../docs/images/seq_net_monitor.png | Bin 0 -> 60053 bytes .../docs/images/seq_ntp_monitor.png | Bin 0 -> 60252 bytes .../docs/images/seq_process_monitor.png | Bin 0 -> 107081 bytes utilities/system_monitor/docs/msr_reader.md | 34 + .../system_monitor/docs/ros_parameters.md | 84 + utilities/system_monitor/docs/seq_diagrams.md | 29 + .../system_monitor/docs/topics_cpu_monitor.md | 98 + .../system_monitor/docs/topics_gpu_monitor.md | 107 + .../system_monitor/docs/topics_hdd_monitor.md | 45 + .../system_monitor/docs/topics_mem_monitor.md | 27 + .../system_monitor/docs/topics_net_monitor.md | 30 + .../system_monitor/docs/topics_ntp_monitor.md | 19 + .../docs/topics_process_monitor.md | 72 + .../include/hdd_reader/hdd_reader.h | 61 + .../include/msr_reader/msr_reader.h | 50 + .../cpu_monitor/arm_cpu_monitor.h | 51 + .../cpu_monitor/cpu_monitor_base.h | 163 + .../cpu_monitor/intel_cpu_monitor.h | 58 + .../cpu_monitor/raspi_cpu_monitor.h | 73 + .../cpu_monitor/tegra_cpu_monitor.h | 51 + .../cpu_monitor/unknown_cpu_monitor.h | 37 + .../gpu_monitor/gpu_monitor_base.h | 123 + .../gpu_monitor/nvml_gpu_monitor.h | 113 + .../gpu_monitor/tegra_gpu_monitor.h | 101 + .../gpu_monitor/unknown_gpu_monitor.h | 37 + .../system_monitor/hdd_monitor/hdd_monitor.h | 106 + .../system_monitor/mem_monitor/mem_monitor.h | 79 + .../system_monitor/net_monitor/net_monitor.h | 98 + .../system_monitor/net_monitor/nl80211.h | 58 + .../system_monitor/ntp_monitor/ntp_monitor.h | 74 + .../process_monitor/diag_task.h | 177 + .../process_monitor/process_monitor.h | 118 + .../system_monitor/system_monitor_utility.h | 91 + .../launch/system_monitor.launch | 15 + utilities/system_monitor/package.xml | 19 + .../reader/hdd_reader/hdd_reader.cpp | 606 ++ .../reader/msr_reader/msr_reader.cpp | 303 + .../src/cpu_monitor/arm_cpu_monitor.cpp | 46 + .../src/cpu_monitor/cpu_monitor_base.cpp | 295 + .../src/cpu_monitor/cpu_monitor_node.cpp | 52 + .../src/cpu_monitor/intel_cpu_monitor.cpp | 194 + .../src/cpu_monitor/raspi_cpu_monitor.cpp | 80 + .../src/cpu_monitor/tegra_cpu_monitor.cpp | 48 + .../src/cpu_monitor/unknown_cpu_monitor.cpp | 27 + .../src/gpu_monitor/gpu_monitor_base.cpp | 88 + .../src/gpu_monitor/gpu_monitor_node.cpp | 46 + .../src/gpu_monitor/nvml_gpu_monitor.cpp | 277 + .../src/gpu_monitor/tegra_gpu_monitor.cpp | 201 + .../src/gpu_monitor/unknown_gpu_monitor.cpp | 27 + .../src/hdd_monitor/hdd_monitor.cpp | 280 + .../src/hdd_monitor/hdd_monitor_node.cpp | 33 + .../src/mem_monitor/mem_monitor.cpp | 122 + .../src/mem_monitor/mem_monitor_node.cpp | 33 + .../src/net_monitor/net_monitor.cpp | 190 + .../src/net_monitor/net_monitor_node.cpp | 33 + .../src/net_monitor/nl80211.cpp | 200 + .../src/ntp_monitor/ntp_monitor.cpp | 115 + .../src/ntp_monitor/ntp_monitor_node.cpp | 33 + .../src/process_monitor/process_monitor.cpp | 320 + .../process_monitor/process_monitor_node.cpp | 33 + .../test/config/test_hdd_monitor.yaml | 5 + .../test/config/test_net_monitor.yaml | 2 + .../test/config/test_ntp_monitor.yaml | 3 + .../test/src/cpu_monitor/mpstat1.cpp | 25 + .../test/src/cpu_monitor/mpstat2.cpp | 25 + .../src/cpu_monitor/test_arm_cpu_monitor.cpp | 668 ++ .../cpu_monitor/test_intel_cpu_monitor.cpp | 952 +++ .../cpu_monitor/test_raspi_cpu_monitor.cpp | 668 ++ .../cpu_monitor/test_tegra_cpu_monitor.cpp | 653 ++ .../cpu_monitor/test_unknown_cpu_monitor.cpp | 72 + .../src/gpu_monitor/test_nvml_gpu_monitor.cpp | 534 ++ .../gpu_monitor/test_tegra_gpu_monitor.cpp | 483 ++ .../gpu_monitor/test_unknown_gpu_monitor.cpp | 70 + .../test/src/hdd_monitor/df1.cpp | 25 + .../test/src/hdd_monitor/test_hdd_monitor.cpp | 654 ++ .../test/src/mem_monitor/free1.cpp | 25 + .../test/src/mem_monitor/test_mem_monitor.cpp | 264 + .../test/src/net_monitor/test_net_monitor.cpp | 186 + .../test/src/ntp_monitor/ntpdate1.cpp | 25 + .../test/src/ntp_monitor/test_ntp_monitor.cpp | 289 + .../test/src/process_monitor/echo1.cpp | 25 + .../test/src/process_monitor/sed1.cpp | 25 + .../test/src/process_monitor/sort1.cpp | 25 + .../process_monitor/test_process_monitor.cpp | 356 + .../test/src/process_monitor/top1.cpp | 25 + .../test/src/process_monitor/top2.cpp | 27 + .../test/src/process_monitor/top3.cpp | 28 + .../system_monitor/test/test_cpu_monitor.test | 3 + .../system_monitor/test/test_gpu_monitor.test | 3 + .../system_monitor/test/test_hdd_monitor.test | 6 + .../system_monitor/test/test_mem_monitor.test | 3 + .../system_monitor/test/test_net_monitor.test | 6 + .../system_monitor/test/test_ntp_monitor.test | 6 + .../test/test_process_monitor.test | 3 + 490 files changed, 49322 insertions(+), 30316 deletions(-) create mode 100644 common/DISCLAIMER.md create mode 100644 common/libwaypoint_follower/include/libwaypoint_follower/pure_pursuit.h rename common/libwaypoint_follower/{test/src/test_libwaypoint_follower.hpp => include/libwaypoint_follower/test_libwaypoint_follower.h} (82%) create mode 100644 common/libwaypoint_follower/src/pure_pursuit.cpp create mode 100644 common/libwaypoint_follower/test/src/test_pure_pursuit.cpp create mode 100644 common/libwaypoint_follower/test/test_pure_pursuit.test create mode 100644 common/map_file/launch/points_map_loader.launch create mode 100644 common/map_file/launch/vector_map_loader.launch create mode 100644 common/op_planner/test/src/test_BuildPlanningSearchTreeV2.cpp create mode 100644 common/tvm_utility/.gitignore create mode 100644 common/tvm_utility/CMakeLists.txt create mode 100644 common/tvm_utility/README.md create mode 100644 common/tvm_utility/include/tvm_utility/pipeline.h create mode 100644 common/tvm_utility/package.xml create mode 100644 common/tvm_utility/test/yolo_v2_tiny/README.md create mode 100644 common/tvm_utility/test/yolo_v2_tiny/labels.txt create mode 100644 common/tvm_utility/test/yolo_v2_tiny/main.cpp create mode 100644 common/vehicle_sim_model/CMakeLists.txt create mode 100644 common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_constant_acceleration.h create mode 100644 common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_ideal.h create mode 100644 common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_interface.h create mode 100644 common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_time_delay.h create mode 100644 common/vehicle_sim_model/package.xml create mode 100644 common/vehicle_sim_model/scripts/README_fitParamDelayInputModel.md create mode 100644 common/vehicle_sim_model/scripts/fitParamDelayInputModel.py create mode 100644 common/vehicle_sim_model/src/vehicle_model_constant_acceleration.cpp create mode 100644 common/vehicle_sim_model/src/vehicle_model_ideal.cpp create mode 100644 common/vehicle_sim_model/src/vehicle_model_interface.cpp create mode 100644 common/vehicle_sim_model/src/vehicle_model_time_delay.cpp create mode 100644 common/vehicle_sim_model/test/src/test_vehicle_sim_model.cpp create mode 100644 common/vehicle_sim_model/test/test_vehicle_sim_model.test rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/CHANGELOG.rst (100%) create mode 100644 core_perception/imm_ukf_pda_track/CMakeLists.txt rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/README.md (100%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/include/imm_ukf_pda/imm_ukf_pda.h (100%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/include/imm_ukf_pda/ukf.h (100%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h (100%) create mode 100644 core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track.launch create mode 100644 core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch create mode 100644 core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/nodes/imm_ukf_pda/imm_ukf_pda.cpp (99%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/nodes/imm_ukf_pda/imm_ukf_pda_main.cpp (100%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/nodes/imm_ukf_pda/ukf.cpp (100%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp (98%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp (92%) rename core_perception/{lidar_imm_ukf_pda_track => imm_ukf_pda_track}/package.xml (100%) delete mode 100644 core_perception/lidar_imm_ukf_pda_track/CMakeLists.txt delete mode 100644 core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track.launch delete mode 100644 core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch create mode 100644 core_perception/lidar_point_pillars/include/point_pillars_pfe/pfe_tvm_pipeline.h create mode 100644 core_perception/lidar_point_pillars/include/point_pillars_rpn/rpn_tvm_pipeline.h create mode 100644 core_perception/lidar_point_pillars/nodes/pfe_tvm_pipeline.cpp create mode 100644 core_perception/lidar_point_pillars/nodes/rpn_tvm_pipeline.cpp rename core_perception/lidar_point_pillars/test/data/{ => data_onnx}/dummy.onnx (100%) create mode 100644 core_perception/lidar_point_pillars/test/data/data_tvm/deploy_graph.json create mode 100755 core_perception/lidar_point_pillars/test/data/data_tvm/deploy_lib.so create mode 100644 core_perception/lidar_point_pillars/test/data/data_tvm/deploy_param.params create mode 100644 core_perception/lidar_point_pillars/tvm_models/tvm_point_pillars_pfe/README.md create mode 100644 core_perception/lidar_point_pillars/tvm_models/tvm_point_pillars_rpn/README.md create mode 100644 core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/atan2_utils.h create mode 100644 core_perception/points_preprocessor/test/data/input_blob.bin create mode 100644 core_perception/points_preprocessor/test/data/input_structured.txt create mode 100644 core_perception/points_preprocessor/test/data/output_ground_blob.bin create mode 100644 core_perception/points_preprocessor/test/data/output_ground_structured.txt create mode 100644 core_perception/points_preprocessor/test/data/output_no_ground_blob.bin create mode 100644 core_perception/points_preprocessor/test/data/output_no_ground_structured.txt create mode 100644 core_perception/points_preprocessor/test/data/transformed_blob.bin create mode 100644 core_perception/points_preprocessor/test/data/transformed_structured.txt create mode 100644 core_perception/points_preprocessor/test/include/sensor_msg_comparison.h create mode 100644 core_perception/points_preprocessor/test/include/sensor_msg_serialization.h create mode 100644 core_perception/points_preprocessor/test/include/test_fast_atan2.h create mode 100644 core_perception/vel_pose_diff_checker/config/health_checker.yaml create mode 100644 core_planning/ll2_global_planner/CMakeLists.txt create mode 100644 core_planning/ll2_global_planner/LICENSE create mode 100644 core_planning/ll2_global_planner/README.md create mode 100644 core_planning/ll2_global_planner/config/params.yaml create mode 100644 core_planning/ll2_global_planner/include/ll2_global_planner/ll2_global_planner_nodelet.hpp create mode 100644 core_planning/ll2_global_planner/launch/ll2_global_planner_node.launch create mode 100644 core_planning/ll2_global_planner/nodelets.xml create mode 100644 core_planning/ll2_global_planner/package.xml create mode 100644 core_planning/ll2_global_planner/src/ll2_global_planner_node.cpp create mode 100644 core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp create mode 100644 documentation/.github/workflows/native-ci.yaml delete mode 100644 documentation/.gitlab-ci.yml delete mode 100644 documentation/.gitlab/issue_templates/bug_report.md delete mode 100644 documentation/.gitlab/issue_templates/feature_request.md delete mode 100644 documentation/.gitlab/issue_templates/other_issue.md delete mode 100644 documentation/.gitlab/merge_request_templates/bug_fix.md delete mode 100644 documentation/.gitlab/merge_request_templates/feature_implementation.md create mode 100644 documentation/DISCLAIMER.md create mode 100644 utilities/system_monitor/CHANGELOG.rst create mode 100644 utilities/system_monitor/CMakeLists.txt create mode 100644 utilities/system_monitor/README.md create mode 100644 utilities/system_monitor/cmake/FindNVML.cmake create mode 100644 utilities/system_monitor/config/system_monitor.yaml create mode 100644 utilities/system_monitor/docs/class_diagrams.md create mode 100644 utilities/system_monitor/docs/hdd_reader.md create mode 100644 utilities/system_monitor/docs/images/class_cpu_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_gpu_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_hdd_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_mem_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_net_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_ntp_monitor.png create mode 100644 utilities/system_monitor/docs/images/class_process_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_cpu_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_gpu_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_hdd_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_mem_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_net_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_ntp_monitor.png create mode 100644 utilities/system_monitor/docs/images/seq_process_monitor.png create mode 100644 utilities/system_monitor/docs/msr_reader.md create mode 100644 utilities/system_monitor/docs/ros_parameters.md create mode 100644 utilities/system_monitor/docs/seq_diagrams.md create mode 100644 utilities/system_monitor/docs/topics_cpu_monitor.md create mode 100644 utilities/system_monitor/docs/topics_gpu_monitor.md create mode 100644 utilities/system_monitor/docs/topics_hdd_monitor.md create mode 100644 utilities/system_monitor/docs/topics_mem_monitor.md create mode 100644 utilities/system_monitor/docs/topics_net_monitor.md create mode 100644 utilities/system_monitor/docs/topics_ntp_monitor.md create mode 100644 utilities/system_monitor/docs/topics_process_monitor.md create mode 100644 utilities/system_monitor/include/hdd_reader/hdd_reader.h create mode 100644 utilities/system_monitor/include/msr_reader/msr_reader.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.h create mode 100644 utilities/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/mem_monitor/mem_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/net_monitor/net_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/net_monitor/nl80211.h create mode 100644 utilities/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/process_monitor/diag_task.h create mode 100644 utilities/system_monitor/include/system_monitor/process_monitor/process_monitor.h create mode 100644 utilities/system_monitor/include/system_monitor/system_monitor_utility.h create mode 100644 utilities/system_monitor/launch/system_monitor.launch create mode 100644 utilities/system_monitor/package.xml create mode 100644 utilities/system_monitor/reader/hdd_reader/hdd_reader.cpp create mode 100644 utilities/system_monitor/reader/msr_reader/msr_reader.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/cpu_monitor_node.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp create mode 100644 utilities/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp create mode 100644 utilities/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp create mode 100644 utilities/system_monitor/src/gpu_monitor/gpu_monitor_node.cpp create mode 100644 utilities/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp create mode 100644 utilities/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp create mode 100644 utilities/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp create mode 100644 utilities/system_monitor/src/hdd_monitor/hdd_monitor.cpp create mode 100644 utilities/system_monitor/src/hdd_monitor/hdd_monitor_node.cpp create mode 100644 utilities/system_monitor/src/mem_monitor/mem_monitor.cpp create mode 100644 utilities/system_monitor/src/mem_monitor/mem_monitor_node.cpp create mode 100644 utilities/system_monitor/src/net_monitor/net_monitor.cpp create mode 100644 utilities/system_monitor/src/net_monitor/net_monitor_node.cpp create mode 100644 utilities/system_monitor/src/net_monitor/nl80211.cpp create mode 100644 utilities/system_monitor/src/ntp_monitor/ntp_monitor.cpp create mode 100644 utilities/system_monitor/src/ntp_monitor/ntp_monitor_node.cpp create mode 100644 utilities/system_monitor/src/process_monitor/process_monitor.cpp create mode 100644 utilities/system_monitor/src/process_monitor/process_monitor_node.cpp create mode 100644 utilities/system_monitor/test/config/test_hdd_monitor.yaml create mode 100644 utilities/system_monitor/test/config/test_net_monitor.yaml create mode 100644 utilities/system_monitor/test/config/test_ntp_monitor.yaml create mode 100644 utilities/system_monitor/test/src/cpu_monitor/mpstat1.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/mpstat2.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp create mode 100644 utilities/system_monitor/test/src/hdd_monitor/df1.cpp create mode 100644 utilities/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp create mode 100644 utilities/system_monitor/test/src/mem_monitor/free1.cpp create mode 100644 utilities/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp create mode 100644 utilities/system_monitor/test/src/net_monitor/test_net_monitor.cpp create mode 100644 utilities/system_monitor/test/src/ntp_monitor/ntpdate1.cpp create mode 100644 utilities/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/echo1.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/sed1.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/sort1.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/test_process_monitor.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/top1.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/top2.cpp create mode 100644 utilities/system_monitor/test/src/process_monitor/top3.cpp create mode 100644 utilities/system_monitor/test/test_cpu_monitor.test create mode 100644 utilities/system_monitor/test/test_gpu_monitor.test create mode 100644 utilities/system_monitor/test/test_hdd_monitor.test create mode 100644 utilities/system_monitor/test/test_mem_monitor.test create mode 100644 utilities/system_monitor/test/test_net_monitor.test create mode 100644 utilities/system_monitor/test/test_ntp_monitor.test create mode 100644 utilities/system_monitor/test/test_process_monitor.test diff --git a/common/CONTRIBUTING.md b/common/CONTRIBUTING.md index 3973501dc91..8b1dfbda427 100644 --- a/common/CONTRIBUTING.md +++ b/common/CONTRIBUTING.md @@ -7,7 +7,7 @@ we adhere to the [Contributor Covenant](https://www.contributor-covenant.org/), used [code of conduct](/CODE_OF_CONDUCT.md) adopted by many other communities such as Linux, Ruby on Rails and GitLab. -Everyone participating in the Autoware.Auto community is expected to follow the code of +Everyone participating in the Autoware.AI community is expected to follow the code of conduct. If someone in the community happens to be violating these terms, please let the project @@ -15,7 +15,7 @@ leads know, and we will address it as soon as possible. ## License -Autoware.Auto is licensed under Apache 2, and thus all contributions will be licensed as such +Autoware.AI is licensed under Apache 2, and thus all contributions will be licensed as such as per clause 5 of the Apache 2 License: ~~~ @@ -30,7 +30,7 @@ as per clause 5 of the Apache 2 License: ## Detailed contribution guidelines -For more detailed information on contributing to Autoware, including development processes, -please see the contributing guidelines on the Autoware Wiki: +For more detailed information on contributing to Autoware.AI, please see the contributing +guidelines on the Autoware Wiki: -https://github.com/autowarefoundation/autoware/wiki/Contributing-to-Autoware +https://github.com/Autoware-AI/autoware.ai/wiki/Contributing-to-Autoware diff --git a/common/DISCLAIMER.md b/common/DISCLAIMER.md new file mode 100644 index 00000000000..d0d6f97da09 --- /dev/null +++ b/common/DISCLAIMER.md @@ -0,0 +1,50 @@ +DISCLAIMER + +The open-source software for self-driving vehicles, Autoware.AI, Autoware.IO, +Autoware.Auto. (collectively, referred to as “Autoware”) will be provided by +The Autoware Foundation under the Apache 2.0 License. This “DISCLAIMER” will be +applied to all users of Autoware (a “User” or “Users”) with the Apache 2.0 +License and Users shall hereby approve and acknowledge all the contents +specified in this disclaimer below and will be deemed to consent to this +disclaimer without any objection upon utilizing or downloading Autoware. + + +Disclaimer and Waiver of Warranties + +1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) +including but not limited to any representation or warranty (i) of fitness or +suitability for a particular purpose contemplated by the Users, (ii) of the +expected functions, commercial value, accuracy, or usefulness of the Service, +(iii) that the use by the Users of the Service complies with the laws and +regulations applicable to the Users or any internal rules established by +industrial organizations, (iv) that the Service will be free of interruption or +defects, (v) of the non-infringement of any third party's right and (vi) the +accuracy of the content of the Services and the software itself. + +2. The Autoware Foundation shall not be liable for any damage incurred by the +User that are attributable to the Autoware Foundation for any reasons +whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR +INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. + +3. A User shall be entirely responsible for the content posted by the User and +its use of any content of the Service or the Website. If the User is held +responsible in a civil action such as a claim for damages or even in a criminal +case, the Autoware Foundation and member companies, governments and academic & +non-profit organizations and their directors, officers, employees and agents +(collectively, the “Indemnified Parties”) shall be completely discharged from +any rights or assertions the User may have against the Indemnified Parties, or +from any legal action, litigation or similar procedures. + + +Indemnity + +A User shall indemnify and hold the Indemnified Parties harmless from any of +their damages, losses, liabilities, costs or expenses (including attorneys' +fees or criminal compensation), or any claims or demands made against the +Indemnified Parties by any third party, due to or arising out of, or in +connection with utilizing Autoware (including the representations and +warranties), the violation of applicable Product Liability Law of each country +(including criminal case) or violation of any applicable laws by the Users, or +the content posted by the User or its use of any content of the Service or the +Website. diff --git a/common/README.md b/common/README.md index 121c4199a3c..cc7b0e24ed3 100644 --- a/common/README.md +++ b/common/README.md @@ -1,4 +1,7 @@ # common + +![Native CI workflow](https://github.com/Autoware-AI/common/workflows/Native%20CI%20workflow/badge.svg) ![CUDA CI workflow](https://github.com/Autoware-AI/common/workflows/CUDA%20CI%20workflow/badge.svg) ![Cross CI workflow](https://github.com/Autoware-AI/common/workflows/Cross%20CI%20workflow/badge.svg) + Autoware support packages used project-wide. www.autoware.org diff --git a/common/SUPPORT.md b/common/SUPPORT.md index 54c7aaa50d9..44606e1ff3c 100644 --- a/common/SUPPORT.md +++ b/common/SUPPORT.md @@ -1,5 +1,3 @@ # Support -To get support for Autoware, see the support guidelines on the Autoware wiki: - -https://github.com/autowarefoundation/Autoware/wiki/Support-guidelines +For detailed instructions on getting help, see the [support guidelines](https://github.com/Autoware-AI/autoware.ai/wiki/Support-guidelines). diff --git a/common/amathutils_lib/CMakeLists.txt b/common/amathutils_lib/CMakeLists.txt index 80bea996d9f..80160794267 100644 --- a/common/amathutils_lib/CMakeLists.txt +++ b/common/amathutils_lib/CMakeLists.txt @@ -4,9 +4,22 @@ project(amathutils_lib) # autoware math utility find_package(autoware_build_flags REQUIRED) find_package(Eigen3 REQUIRED) + +if (NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else () + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif () + find_package(catkin REQUIRED COMPONENTS - roscpp autoware_msgs + roscpp + roslint tf tf2 ) @@ -16,14 +29,16 @@ set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") catkin_package( INCLUDE_DIRS include LIBRARIES amathutils_lib - CATKIN_DEPENDS autoware_msgs - tf - tf2 + CATKIN_DEPENDS + autoware_msgs + tf + tf2 ) include_directories( include ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} ) add_library(amathutils_lib @@ -50,7 +65,15 @@ install(TARGETS amathutils_lib LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) - + +file(GLOB_RECURSE ROSLINT_FILES + LIST_DIRECTORIES false + *.cpp *.h *.hpp +) + +list(APPEND ROSLINT_CPP_OPTS "--extensions=cc,h,hpp,cpp,cu,cuh" "--filter=-build/c++11,-runtime/references") +roslint_cpp(${ROSLINT_FILES}) + if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) add_rostest_gtest(amathutils-test test/test_amathutils_lib.test test/src/test_amathutils_lib.cpp) @@ -59,13 +82,15 @@ if(CATKIN_ENABLE_TESTING) test/test_kalman_filter.test test/src/test_kalman_filter.cpp src/kalman_filter.cpp - src/time_delay_kalman_filter.cpp) + src/time_delay_kalman_filter.cpp + ) target_link_libraries(test-kalman_filter ${catkin_LIBRARIES}) add_rostest_gtest(test-butterworth_filter - test/test_butterworth_filter.test - test/src/test_butterworth_filter.cpp - src/butterworth_filter.cpp) + test/test_butterworth_filter.test + test/src/test_butterworth_filter.cpp + src/butterworth_filter.cpp + ) target_link_libraries(test-butterworth_filter ${catkin_LIBRARIES}) - + roslint_add_test() endif() diff --git a/common/amathutils_lib/include/amathutils_lib/amathutils.hpp b/common/amathutils_lib/include/amathutils_lib/amathutils.hpp index e35d6e5bf5d..ddebf53bd69 100644 --- a/common/amathutils_lib/include/amathutils_lib/amathutils.hpp +++ b/common/amathutils_lib/include/amathutils_lib/amathutils.hpp @@ -1,5 +1,21 @@ -#ifndef __AMATHUTILS_HPP -#define __AMATHUTILS_HPP +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef AMATHUTILS_LIB_AMATHUTILS_HPP +#define AMATHUTILS_LIB_AMATHUTILS_HPP #include #include @@ -13,6 +29,7 @@ namespace amathutils { + #define G_MPSS 9.80665 // m/s^2 inline double rad2deg(double _angle) @@ -49,8 +66,10 @@ inline double getTimefromAcceleration(double _v0, double _v, double _a) return (_v - _v0) / _a; } -bool getIntersect(double x1, double y1, double x2, double y2, double x3, double y3, double x4, double y4, double* intersect_x, double* intersect_y ); -bool getIntersect(geometry_msgs::Point p1, geometry_msgs::Point p2, geometry_msgs::Point p3, geometry_msgs::Point p4, geometry_msgs::Point* intersect); +bool getIntersect(double x1, double y1, double x2, double y2, double x3, + double y3, double x4, double y4, double* intersect_x, double* intersect_y); +bool getIntersect(geometry_msgs::Point p1, geometry_msgs::Point p2, geometry_msgs::Point p3, + geometry_msgs::Point p4, geometry_msgs::Point* intersect); geometry_msgs::Point getNearPtOnLine(const geometry_msgs::Point &_p, const geometry_msgs::Point &_a, const geometry_msgs::Point &_b); @@ -58,9 +77,9 @@ double find_distance(const geometry_msgs::Point &_from, const geometry_msgs::Poi double find_distance(const geometry_msgs::Pose &_from, const geometry_msgs::Pose &_to); double find_angle(const geometry_msgs::Point &_from, const geometry_msgs::Point &_to); bool isIntersectLine(const geometry_msgs::Point &_l1_p1, const geometry_msgs::Point &_l1_p2, - const geometry_msgs::Point &_l2_p1, const geometry_msgs::Point &_l2_p2); + const geometry_msgs::Point &_l2_p1, const geometry_msgs::Point &_l2_p2); int isPointLeftFromLine(const geometry_msgs::Point &_target, const geometry_msgs::Point &_line_p1, - const geometry_msgs::Point &_line_p2); + const geometry_msgs::Point &_line_p2); /** * @fn distanceFromSegment @@ -70,7 +89,8 @@ int isPointLeftFromLine(const geometry_msgs::Point &_target, const geometry_msgs * @param _p the point to find distance * @return distance between point _p and line segment(_l1,_l2) */ -double distanceFromSegment( const geometry_msgs::Point &_l1, const geometry_msgs::Point &_l2, const geometry_msgs::Point &_p); +double distanceFromSegment(const geometry_msgs::Point &_l1, const geometry_msgs::Point &_l2, + const geometry_msgs::Point &_p); double getPoseYawAngle(const geometry_msgs::Pose &_pose); /** @@ -90,5 +110,7 @@ double normalizeRadian(const double _angle); double calcPosesAngleDiffRaw(const geometry_msgs::Pose &p_from, const geometry_msgs::Pose &_p_to); double calcPosesAngleDiffDeg(const geometry_msgs::Pose &_p_from, const geometry_msgs::Pose &_p_to); double calcPosesAngleDiffRad(const geometry_msgs::Pose &_p_from, const geometry_msgs::Pose &_p_to); -} -#endif + +} // namespace amathutils + +#endif // AMATHUTILS_LIB_AMATHUTILS_HPP diff --git a/common/amathutils_lib/include/amathutils_lib/butterworth_filter.hpp b/common/amathutils_lib/include/amathutils_lib/butterworth_filter.hpp index 4e1cd46e124..405b099eece 100644 --- a/common/amathutils_lib/include/amathutils_lib/butterworth_filter.hpp +++ b/common/amathutils_lib/include/amathutils_lib/butterworth_filter.hpp @@ -16,27 +16,27 @@ * Authors: Ali Boyali, Simon Thompson */ -#ifndef BUTTERWORTH_FILTER_H -#define BUTTERWORTH_FILTER_H - -#pragma once +#ifndef AMATHUTILS_LIB_BUTTERWORTH_FILTER_HPP +#define AMATHUTILS_LIB_BUTTERWORTH_FILTER_HPP #include #include #include -struct Order_Cutoff { +struct Order_Cutoff +{ int N; double Wc; }; -struct DifferenceAnBn { +struct DifferenceAnBn +{ std::vector An; std::vector Bn; }; -class ButterworthFilter { - +class ButterworthFilter +{ public: // Prints the filter order and cutoff frequency @@ -53,7 +53,7 @@ class ButterworthFilter { // Setters and Getters void - setCuttoffFrequency(double Wc); // Wc is the cut-off frequency in [rad/sec] + setCuttoffFrequency(double Wc); // Wc is the cut-off frequency in [rad/sec] // fc is cut-off frequency in [Hz] and fs is the sampling frequency in [Hz] void setCuttoffFrequency(double fc, double fs); @@ -79,10 +79,8 @@ class ButterworthFilter { bool init_first_value = true); private: - // member variables - - int mOrder = 0; // filter order - double mCutoff_Frequency = 0.0; // filter cut-off frequency [rad/sec] + int mOrder = 0; // filter order + double mCutoff_Frequency = 0.0; // filter cut-off frequency [rad/sec] // Boolean parameter when a sampling frequency is defined. Default is false bool prewarp = false; @@ -140,4 +138,4 @@ class ButterworthFilter { std::vector u_filtered; }; -#endif +#endif // AMATHUTILS_LIB_BUTTERWORTH_FILTER_HPP diff --git a/common/amathutils_lib/include/amathutils_lib/kalman_filter.hpp b/common/amathutils_lib/include/amathutils_lib/kalman_filter.hpp index f8d76d77cef..a1ffa9afaef 100644 --- a/common/amathutils_lib/include/amathutils_lib/kalman_filter.hpp +++ b/common/amathutils_lib/include/amathutils_lib/kalman_filter.hpp @@ -14,7 +14,8 @@ * limitations under the License. */ -#pragma once +#ifndef AMATHUTILS_LIB_KALMAN_FILTER_HPP +#define AMATHUTILS_LIB_KALMAN_FILTER_HPP #include #include @@ -29,7 +30,6 @@ class KalmanFilter { public: - /** * @brief No initialization constructor. */ @@ -191,11 +191,13 @@ class KalmanFilter bool update(const Eigen::MatrixXd &y); protected: - Eigen::MatrixXd x_; //!< @brief current estimated state - Eigen::MatrixXd A_; //!< @brief coefficient matrix of x for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd B_; //!< @brief coefficient matrix of u for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd C_; //!< @brief coefficient matrix of x for measurement model y[k] = C * x[k] - Eigen::MatrixXd Q_; //!< @brief covariace matrix for process model x[k+1] = A*x[k] + B*u[k] - Eigen::MatrixXd R_; //!< @brief covariance matrix for measurement model y[k] = C * x[k] - Eigen::MatrixXd P_; //!< @brief covariance of estimated state -}; \ No newline at end of file + Eigen::MatrixXd x_; //!< @brief current estimated state + Eigen::MatrixXd A_; //!< @brief coefficient matrix of x for process model x[k+1] = A*x[k] + B*u[k] + Eigen::MatrixXd B_; //!< @brief coefficient matrix of u for process model x[k+1] = A*x[k] + B*u[k] + Eigen::MatrixXd C_; //!< @brief coefficient matrix of x for measurement model y[k] = C * x[k] + Eigen::MatrixXd Q_; //!< @brief covariace matrix for process model x[k+1] = A*x[k] + B*u[k] + Eigen::MatrixXd R_; //!< @brief covariance matrix for measurement model y[k] = C * x[k] + Eigen::MatrixXd P_; //!< @brief covariance of estimated state +}; + +#endif // AMATHUTILS_LIB_KALMAN_FILTER_HPP diff --git a/common/amathutils_lib/include/amathutils_lib/time_delay_kalman_filter.hpp b/common/amathutils_lib/include/amathutils_lib/time_delay_kalman_filter.hpp index a718633f03a..ba6235cf617 100644 --- a/common/amathutils_lib/include/amathutils_lib/time_delay_kalman_filter.hpp +++ b/common/amathutils_lib/include/amathutils_lib/time_delay_kalman_filter.hpp @@ -14,7 +14,8 @@ * limitations under the License. */ -#pragma once +#ifndef AMATHUTILS_LIB_TIME_DELAY_KALMAN_FILTER_HPP +#define AMATHUTILS_LIB_TIME_DELAY_KALMAN_FILTER_HPP #include #include @@ -31,13 +32,11 @@ class TimeDelayKalmanFilter : public KalmanFilter { public: - /** * @brief No initialization constructor. */ TimeDelayKalmanFilter(); - /** * @brief initialization of kalman filter * @param x initial state @@ -78,7 +77,9 @@ class TimeDelayKalmanFilter : public KalmanFilter const Eigen::MatrixXd &R, const int delay_step); private: - int max_delay_step_; //!< @brief maximum number of delay steps - int dim_x_; //!< @brief dimension of latest state - int dim_x_ex_; //!< @brief dimension of extended state with dime delay -}; \ No newline at end of file + int max_delay_step_; //!< @brief maximum number of delay steps + int dim_x_; //!< @brief dimension of latest state + int dim_x_ex_; //!< @brief dimension of extended state with dime delay +}; + +#endif // AMATHUTILS_LIB_TIME_DELAY_KALMAN_FILTER_HPP diff --git a/common/amathutils_lib/package.xml b/common/amathutils_lib/package.xml index 74aed22ff01..1266baba1a2 100644 --- a/common/amathutils_lib/package.xml +++ b/common/amathutils_lib/package.xml @@ -13,6 +13,8 @@ autoware_msgs roscpp + roslint tf2 tf + eigen diff --git a/common/amathutils_lib/src/Amathutils.cpp b/common/amathutils_lib/src/Amathutils.cpp index cc049a7e36e..a274f41af39 100644 --- a/common/amathutils_lib/src/Amathutils.cpp +++ b/common/amathutils_lib/src/Amathutils.cpp @@ -1,3 +1,19 @@ +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + #include namespace amathutils @@ -79,43 +95,44 @@ int isPointLeftFromLine(const geometry_msgs::Point &_target, const geometry_msgs } -//Following implementation comes from the website below: -//Author: Dan Sunday -//site: http://geomalgorithms.com/a02-_lines.html -//viewed: 2019/5/20 -double distanceFromSegment( const geometry_msgs::Point &_l1, const geometry_msgs::Point &_l2, const geometry_msgs::Point &_p) +// Following implementation comes from the website below: +// Author: Dan Sunday +// site: http://geomalgorithms.com/a02-_lines.html +// viewed: 2019/5/20 +double distanceFromSegment( + const geometry_msgs::Point &_l1, const geometry_msgs::Point &_l2, const geometry_msgs::Point &_p) { geometry_msgs::Point v, w; v.x = _l2.x - _l1.x; v.y = _l2.y - _l1.y; v.z = _l2.z - _l1.z; - + w.x = _p.x - _l1.x; w.y = _p.y - _l1.y; w.z = _p.z - _l1.z; - + double dot_vw = v.x * w.x + v.y * w.y + v.z * w.z; double dot_vv = v.x * v.x + v.y * v.y + v.z * v.z; - - if ( dot_vw <= 0 ) + + if (dot_vw <= 0) { - return find_distance(_p, _l1); + return find_distance(_p, _l1); } - if ( dot_vv <= dot_vw) + + if (dot_vv <= dot_vw) { - return find_distance(_p, _l2); + return find_distance(_p, _l2); } - + double b = dot_vw / dot_vv; geometry_msgs::Point pb; - pb.x = _l1.x + b * v.x; - pb.y = _l1.y + b * v.y; - pb.z = _l1.z + b * v.z; - + pb.x = _l1.x + b * v.x; + pb.y = _l1.y + b * v.y; + pb.z = _l1.z + b * v.z; + return find_distance(_p, pb); } - double getPoseYawAngle(const geometry_msgs::Pose &_pose) { double r, p, y; @@ -161,34 +178,41 @@ double calcPosesAngleDiffRad(const geometry_msgs::Pose &_p_from, const geometry_ return normalizeRadian(calcPosesAngleDiffRaw(_p_from, _p_to)); } -bool getIntersect(geometry_msgs::Point p1, geometry_msgs::Point p2, geometry_msgs::Point p3, geometry_msgs::Point p4, geometry_msgs::Point* intersect) +bool getIntersect(geometry_msgs::Point p1, geometry_msgs::Point p2, geometry_msgs::Point p3, + geometry_msgs::Point p4, geometry_msgs::Point* intersect) { return getIntersect(p1.x, p1.y, p2.x, p2.y, p3.x, p3.y, p4.x, p4.y, &intersect->x, &intersect->y); } -bool getIntersect(double x1, double y1, double x2, double y2, double x3, double y3, double x4, double y4, double* intersect_x, double* intersect_y ) +bool getIntersect(double x1, double y1, double x2, double y2, double x3, double y3, double x4, + double y4, double* intersect_x, double* intersect_y ) { - //let p1(x1, y1), p2(x2, y2), p3(x3, y3), p4(x4,y4) - //intersect of line segment p1 to p2 and p3 to p4 satisfies + // let p1(x1, y1), p2(x2, y2), p3(x3, y3), p4(x4,y4) + // intersect of line segment p1 to p2 and p3 to p4 satisfies // p1 + r(p2 - p1) = p3 + s(p4 - p3) // 0 <= r <= 1 // 0 <= s <= 1 double denominator = (y4 - y3) * (x2 - x1) - (x4 - x3) * (y2 - y1); - if(denominator == 0) { - //line is parallel - return false; + if (denominator == 0) + { + // line is parallel + return false; } double r = ( (y4 - y3) * (x3 - x1) - (x4 - x3) * (y3 - y1) ) / denominator; double s = ( (y2 - y1) * (x3 - x1) - (x2 - x1) * (y3 - y1) ) / denominator; - if( r >= 0 && r <= 1 && s >= 0 && s <= 1) { - *intersect_x = x1 + r * (x2 - x1); - *intersect_y = y1 + r * (y2 - y1); - return true; - }else{ - return false; + if (r >= 0 && r <= 1 && s >= 0 && s <= 1) + { + *intersect_x = x1 + r * (x2 - x1); + *intersect_y = y1 + r * (y2 - y1); + return true; + } + else + { + return false; } } -} + +} // namespace amathutils diff --git a/common/amathutils_lib/src/butterworth_filter.cpp b/common/amathutils_lib/src/butterworth_filter.cpp index b943a5292a6..5332f9c5616 100644 --- a/common/amathutils_lib/src/butterworth_filter.cpp +++ b/common/amathutils_lib/src/butterworth_filter.cpp @@ -22,10 +22,12 @@ #include #include #include +#include #include "amathutils_lib/butterworth_filter.hpp" -void ButterworthFilter::Buttord(double Wp, double Ws, double Ap, double As) { +void ButterworthFilter::Buttord(double Wp, double Ws, double Ap, double As) +{ /* * Inputs are double Wp, Ws, Ap, As; * Wp; passband frequency [rad/sc], @@ -58,26 +60,31 @@ void ButterworthFilter::Buttord(double Wp, double Ws, double Ap, double As) { setCuttoffFrequency(right_lim); } -void ButterworthFilter::initializeForFiltering() { +void ButterworthFilter::initializeForFiltering() +{ // record history of filtered and unfiltered signal for applying filter u_unfiltered.resize(mOrder + 1, 0.0); u_filtered.resize(mOrder + 1, 0.0); } -void ButterworthFilter::setOrder(int N) { +void ButterworthFilter::setOrder(int N) +{ mOrder = N; initializeForFiltering(); } -void ButterworthFilter::setCuttoffFrequency(double Wc) { +void ButterworthFilter::setCuttoffFrequency(double Wc) +{ mCutoff_Frequency = Wc; } -void ButterworthFilter::setCuttoffFrequency(double fc, double fs) { +void ButterworthFilter::setCuttoffFrequency(double fc, double fs) +{ /* * fc is the cut-off frequency in [Hz] * fs is the sampling frequency in [Hz] * */ - if (fc >= fs / 2) { + if (fc >= fs / 2) + { std::cout << "\n ERROR: Cut-off frequency fc must be less than fs/2 \n"; _Exit(0); } @@ -86,10 +93,10 @@ void ButterworthFilter::setCuttoffFrequency(double fc, double fs) { } std::vector> -ButterworthFilter::polynomialFromRoots(std::vector> &rts) { - +ButterworthFilter::polynomialFromRoots(std::vector> &rts) +{ std::vector> roots = rts; - std::vector> coefficients(roots.size() + 1, {0, 0}); + std::vector> coefficients(roots.size() + 1, {0, 0}); // NOLINT int n = roots.size(); @@ -97,9 +104,10 @@ ButterworthFilter::polynomialFromRoots(std::vector> &rts) { // Use Vieta's Formulas to calculate polynomial coefficients // relates sum and products of roots to coefficients - for (int i = 0; i < n; i++) { - - for (int j = i; j != -1; j--) { + for (int i = 0; i < n; i++) + { + for (int j = i; j != -1; j--) + { coefficients[j + 1] = coefficients[j + 1] - (roots[i] * coefficients[j]); } } @@ -107,54 +115,60 @@ ButterworthFilter::polynomialFromRoots(std::vector> &rts) { return coefficients; } -void ButterworthFilter::computePhaseAngles() { - +void ButterworthFilter::computePhaseAngles() +{ mPhaseAngles.resize(mOrder); int i = 1; - for (auto &&x : mPhaseAngles) { + for (auto &&x : mPhaseAngles) + { x = M_PI_2 + (M_PI * (2.0 * i - 1.0) / (2.0 * mOrder)); i++; } } -void ButterworthFilter::computeContinuousTimeRoots(bool use_sampling_freqency) { - +void ButterworthFilter::computeContinuousTimeRoots(bool use_sampling_freqency) +{ // First compute the phase angles of the roots computePhaseAngles(); - mContinuousTimeRoots.resize(mOrder, {0.0, 0.0}); + mContinuousTimeRoots.resize(mOrder, {0.0, 0.0}); // NOLINT int i = 0; - if (use_sampling_freqency) { + if (use_sampling_freqency) + { double Fc = (mSampling_Frequency / M_PI) * tan(mCutoff_Frequency / (mSampling_Frequency * 2.0)); - for (auto &&x : mContinuousTimeRoots) { - x = {cos(mPhaseAngles[i]) * Fc * 2.0 * M_PI, - sin(mPhaseAngles[i]) * Fc * 2.0 * M_PI}; + for (auto &&x : mContinuousTimeRoots) + { + x = {cos(mPhaseAngles[i]) * Fc * 2.0 * M_PI, // NOLINT + sin(mPhaseAngles[i]) * Fc * 2.0 * M_PI}; // NOLINT i++; } - - } else { - for (auto &&x : mContinuousTimeRoots) { - x = {mCutoff_Frequency * cos(mPhaseAngles[i]), - mCutoff_Frequency * sin(mPhaseAngles[i])}; + } + else + { + for (auto &&x : mContinuousTimeRoots) + { + x = {mCutoff_Frequency * cos(mPhaseAngles[i]), // NOLINT + mCutoff_Frequency * sin(mPhaseAngles[i])}; // NOLINT i++; } } } -void ButterworthFilter::computeContinuousTimeTF(bool use_sampling_freqency) { - +void ButterworthFilter::computeContinuousTimeTF(bool use_sampling_freqency) +{ computeContinuousTimeRoots(use_sampling_freqency); - mContinuousTimeDenominator.resize(mOrder + 1, {0.0, 0.0}); + mContinuousTimeDenominator.resize(mOrder + 1, {0.0, 0.0}); // NOLINT mContinuousTimeDenominator = polynomialFromRoots(mContinuousTimeRoots); mContinuousTimeNumerator = pow(mCutoff_Frequency, mOrder); } -void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) { +void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) +{ /* @brief * This method assumes the continous time transfer function of filter has * already been computed and stored in the @@ -165,8 +179,8 @@ void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) { // the values by Bilinear Transformation mDiscreteTimeZeros.resize( - mOrder, {-1.0, 0.0}); // Butter puts zeros at -1.0 for causality - mDiscreteTimeRoots.resize(mOrder, {0.0, 0.0}); + mOrder, {-1.0, 0.0}); // Butter puts zeros at -1.0 for causality // NOLINT + mDiscreteTimeRoots.resize(mOrder, {0.0, 0.0}); // NOLINT mAn.resize(mOrder + 1, 0.0); mBn.resize(mOrder + 1, 0.0); @@ -175,8 +189,10 @@ void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) { // Bi-linear Transformation of the Roots int i = 0; - if (use_sampling_freqency) { - for (auto &&dr : mDiscreteTimeRoots) { + if (use_sampling_freqency) + { + for (auto &&dr : mDiscreteTimeRoots) + { dr = (1.0 + mContinuousTimeRoots[i] / (mSampling_Frequency * 2.0)) / (1.0 - mContinuousTimeRoots[i] / (mSampling_Frequency * 2.0)); i++; @@ -192,29 +208,36 @@ void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) { std::complex sum_num{0.0, 0.0}; std::complex sum_den{0.0, 0.0}; - for (auto &n : mDiscreteTimeNumerator) { + for (auto &n : mDiscreteTimeNumerator) + { sum_num += n; } - for (auto &n : mDiscreteTimeDenominator) { + for (auto &n : mDiscreteTimeDenominator) + { sum_den += n; } mDiscreteTimeGain = (sum_den / sum_num); - for (auto &&dn : mDiscreteTimeNumerator) { + for (auto &&dn : mDiscreteTimeNumerator) + { dn = dn * mDiscreteTimeGain; mBn[i] = dn.real(); i++; } i = 0; - for (auto &&dd : mDiscreteTimeDenominator) { + for (auto &&dd : mDiscreteTimeDenominator) + { mAn[i] = dd.real(); i++; } - } else { - for (auto &&dr : mDiscreteTimeRoots) { + } + else + { + for (auto &&dr : mDiscreteTimeRoots) + { dr = (1.0 + 2.0 * mContinuousTimeRoots[i] / 2.0) / (1.0 - Td * mContinuousTimeRoots[i] / 2.0); @@ -228,29 +251,31 @@ void ButterworthFilter::computeDiscreteTimeTF(bool use_sampling_freqency) { i = 0; mDiscreteTimeNumerator = polynomialFromRoots(mDiscreteTimeZeros); - for (auto &&dn : mDiscreteTimeNumerator) { + for (auto &&dn : mDiscreteTimeNumerator) + { dn = dn * mDiscreteTimeGain; mBn[i] = dn.real(); i++; } i = 0; - for (auto &&dd : mDiscreteTimeDenominator) { + for (auto &&dd : mDiscreteTimeDenominator) + { mAn[i] = dd.real(); i++; } } } -Order_Cutoff ButterworthFilter::getOrderCutOff() { - +Order_Cutoff ButterworthFilter::getOrderCutOff() +{ Order_Cutoff NWc{mOrder, mCutoff_Frequency}; return NWc; } -DifferenceAnBn ButterworthFilter::getAnBn() { - +DifferenceAnBn ButterworthFilter::getAnBn() +{ // DifferenceAnBn AnBn; // AnBn.An.resize(mAn.size(), 0.0); // AnBn.Bn.resize(mBn.size(), 0.0); @@ -263,11 +288,18 @@ DifferenceAnBn ButterworthFilter::getAnBn() { return AnBn; } -std::vector ButterworthFilter::getAn() { return mAn; } +std::vector ButterworthFilter::getAn() +{ + return mAn; +} -std::vector ButterworthFilter::getBn() { return mBn; } +std::vector ButterworthFilter::getBn() +{ + return mBn; +} -void ButterworthFilter::PrintFilter_Specs() { +void ButterworthFilter::PrintFilter_Specs() +{ /* * Prints the order and cut-off angular frequency (rad/sec) of the filter * @@ -277,7 +309,8 @@ void ButterworthFilter::PrintFilter_Specs() { << std::endl; } -void ButterworthFilter::PrintFilter_ContinuousTimeRoots() { +void ButterworthFilter::PrintFilter_ContinuousTimeRoots() +{ /* * Prints the order and cut-off angular frequency (rad/sec) of the filter * */ @@ -285,14 +318,15 @@ void ButterworthFilter::PrintFilter_ContinuousTimeRoots() { "Denominator are : " << std::endl; - for (auto &&x : mContinuousTimeRoots) { + for (auto &&x : mContinuousTimeRoots) + { std::cout << std::real(x) << " + j " << std::imag(x) << std::endl; } std::cout << std::endl; } -void ButterworthFilter::PrintContinuousTimeTF() { - +void ButterworthFilter::PrintContinuousTimeTF() +{ int n = mOrder; std::cout << "\nThe Continuous Time Transfer Function of the Filter is ;\n" @@ -300,14 +334,15 @@ void ButterworthFilter::PrintContinuousTimeTF() { std::cout << " " << mContinuousTimeNumerator << std::endl; - for (int i = 0; i <= n; i++) { + for (int i = 0; i <= n; i++) + { std::cout << "--------"; } std::cout << "--------\n"; - for (int i = n; i > 0; i--) { - + for (int i = n; i > 0; i--) + { std::cout << mContinuousTimeDenominator[n - i].real() << " * "; std::cout << "z[-" << i << "] + "; } @@ -315,27 +350,29 @@ void ButterworthFilter::PrintContinuousTimeTF() { std::cout << mContinuousTimeDenominator[n].real() << std::endl; } -void ButterworthFilter::PrintDiscreteTimeTF() { - +void ButterworthFilter::PrintDiscreteTimeTF() +{ int n = mOrder; std::cout << "\nThe Discrete Time Transfer Function of the Filter is ;\n" << std::endl; - for (int i = n; i > 0; i--) { - + for (int i = n; i > 0; i--) + { std::cout << mDiscreteTimeNumerator[n - i].real() << " * "; std::cout << "z[-" << i << "] + "; } + std::cout << mDiscreteTimeNumerator[n].real() << std::endl; - for (int i = 0; i <= n; i++) { + for (int i = 0; i <= n; i++) + { std::cout << "--------"; } std::cout << "--------\n"; - for (int i = n; i > 0; i--) { - + for (int i = n; i > 0; i--) + { std::cout << mDiscreteTimeDenominator[n - i].real() << " * "; std::cout << "z[-" << i << "] + "; } @@ -344,20 +381,25 @@ void ButterworthFilter::PrintDiscreteTimeTF() { std::cout << std::endl; } -double ButterworthFilter::filter(const double &u) { - +double ButterworthFilter::filter(const double &u) +{ double u_f = 0.0; - for (int i = 0; i < mOrder + 1; i++) { + for (int i = 0; i < mOrder + 1; i++) + { if (i == 0) + { u_f += mBn[0] * u; - else { + } + else + { u_f += mBn[i] * u_unfiltered[i]; u_f -= mAn[i] * u_filtered[i]; } } - for (int i = mOrder; i >= 2; i--) { + for (int i = mOrder; i >= 2; i--) + { u_unfiltered[i] = u_unfiltered[i - 1]; u_filtered[i] = u_filtered[i - 1]; } @@ -369,12 +411,14 @@ double ButterworthFilter::filter(const double &u) { void ButterworthFilter::filtVector(const std::vector &t, std::vector &u, - bool init_first_value) { - + bool init_first_value) +{ // initialise trace values to 1st value - if (init_first_value) { - for (int i = 0; i < mOrder + 1; i++) { + if (init_first_value) + { + for (int i = 0; i < mOrder + 1; i++) + { u_unfiltered[i] = t[0]; u_filtered[i] = t[0]; } @@ -386,8 +430,8 @@ void ButterworthFilter::filtVector(const std::vector &t, void ButterworthFilter::filtFiltVector(const std::vector &t, std::vector &u, - bool init_first_value) { - + bool init_first_value) +{ std::vector u_rev(u); // forward filtering @@ -399,7 +443,8 @@ void ButterworthFilter::filtFiltVector(const std::vector &t, std::reverse(u_rev.begin(), u_rev.end()); // merge - for (unsigned int i = 0; i < u.size(); ++i) { + for (unsigned int i = 0; i < u.size(); ++i) + { u[i] = (u[i] + u_rev[i]) * 0.5; } } diff --git a/common/amathutils_lib/src/kalman_filter.cpp b/common/amathutils_lib/src/kalman_filter.cpp index 7a4977d9804..cee00b6b952 100644 --- a/common/amathutils_lib/src/kalman_filter.cpp +++ b/common/amathutils_lib/src/kalman_filter.cpp @@ -62,9 +62,9 @@ void KalmanFilter::setB(const Eigen::MatrixXd &B) { B_ = B; } void KalmanFilter::setC(const Eigen::MatrixXd &C) { C_ = C; } void KalmanFilter::setQ(const Eigen::MatrixXd &Q) { Q_ = Q; } void KalmanFilter::setR(const Eigen::MatrixXd &R) { R_ = R; } -void KalmanFilter::getX(Eigen::MatrixXd &x) { x = x_; }; -void KalmanFilter::getP(Eigen::MatrixXd &P) { P = P_; }; -double KalmanFilter::getXelement(unsigned int i) { return x_(i); }; +void KalmanFilter::getX(Eigen::MatrixXd &x) { x = x_; } +void KalmanFilter::getP(Eigen::MatrixXd &P) { P = P_; } +double KalmanFilter::getXelement(unsigned int i) { return x_(i); } bool KalmanFilter::predict(const Eigen::MatrixXd &x_next, const Eigen::MatrixXd &A, @@ -113,7 +113,7 @@ bool KalmanFilter::update(const Eigen::MatrixXd &y, if (isnan(K.array()).any() || isinf(K.array()).any()) { return false; - }; + } x_ = x_ + K * (y - y_pred); P_ = P_ - K * (C * P_); diff --git a/common/amathutils_lib/src/time_delay_kalman_filter.cpp b/common/amathutils_lib/src/time_delay_kalman_filter.cpp index 73dc8626601..2f629a41029 100644 --- a/common/amathutils_lib/src/time_delay_kalman_filter.cpp +++ b/common/amathutils_lib/src/time_delay_kalman_filter.cpp @@ -33,16 +33,14 @@ void TimeDelayKalmanFilter::init(const Eigen::MatrixXd &x, const Eigen::MatrixXd x_.block(i * dim_x_, 0, dim_x_, 1) = x; P_.block(i * dim_x_, i * dim_x_, dim_x_, dim_x_) = P0; } -}; +} -void TimeDelayKalmanFilter::getLatestX(Eigen::MatrixXd &x) { x = x_.block(0, 0, dim_x_, 1); }; -void TimeDelayKalmanFilter::getLatestP(Eigen::MatrixXd &P) { P = P_.block(0, 0, dim_x_, dim_x_); }; +void TimeDelayKalmanFilter::getLatestX(Eigen::MatrixXd &x) { x = x_.block(0, 0, dim_x_, 1); } +void TimeDelayKalmanFilter::getLatestP(Eigen::MatrixXd &P) { P = P_.block(0, 0, dim_x_, dim_x_); } bool TimeDelayKalmanFilter::predictWithDelay(const Eigen::MatrixXd &x_next, const Eigen::MatrixXd &A, const Eigen::MatrixXd &Q) { - - /* * time delay model: * @@ -57,7 +55,6 @@ bool TimeDelayKalmanFilter::predictWithDelay(const Eigen::MatrixXd &x_next, cons * [ P21*A' P21 P22] */ - const int d_dim_x = dim_x_ex_ - dim_x_; /* slide states in the time direction */ @@ -75,7 +72,7 @@ bool TimeDelayKalmanFilter::predictWithDelay(const Eigen::MatrixXd &x_next, cons P_ = P_tmp; return true; -}; +} bool TimeDelayKalmanFilter::updateWithDelay(const Eigen::MatrixXd &y, const Eigen::MatrixXd &C, const Eigen::MatrixXd &R, const int delay_step) @@ -97,4 +94,4 @@ bool TimeDelayKalmanFilter::updateWithDelay(const Eigen::MatrixXd &y, const Eige return false; return true; -}; \ No newline at end of file +} diff --git a/common/amathutils_lib/test/src/test_amathutils_lib.cpp b/common/amathutils_lib/test/src/test_amathutils_lib.cpp index 33b2d5e8f9a..2148507ee8c 100644 --- a/common/amathutils_lib/test/src/test_amathutils_lib.cpp +++ b/common/amathutils_lib/test/src/test_amathutils_lib.cpp @@ -1,3 +1,19 @@ +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + #include "amathutils_lib/amathutils.hpp" #include #include @@ -5,193 +21,205 @@ #include #include -class TestSuite: public ::testing::Test { +class TestSuite: + public ::testing::Test +{ public: - TestSuite(){} - ~TestSuite(){} + TestSuite() {} }; -TEST(TestSuite, Rad2Deg){ - double radAngle = 1; - ASSERT_EQ(amathutils::rad2deg(radAngle), radAngle*180/M_PI) << "Angle in degrees should be " << radAngle*180/M_PI; +TEST(TestSuite, Rad2Deg) +{ + double radAngle = 1; + ASSERT_EQ(amathutils::rad2deg(radAngle), radAngle*180/M_PI) << "Angle in degrees should be " << radAngle*180/M_PI; } -TEST(TestSuite, Deg2Rad){ - double degAngle = 10; - ASSERT_EQ(amathutils::deg2rad(degAngle), degAngle*M_PI/180) << "Angle in radians should be " << degAngle*M_PI/180; +TEST(TestSuite, Deg2Rad) +{ + double degAngle = 10; + ASSERT_EQ(amathutils::deg2rad(degAngle), degAngle*M_PI/180) << "Angle in radians should be " << degAngle*M_PI/180; } // Value from https://www.google.com/search?client=ubuntu&channel=fs&q=mps+to+kph&ie=utf-8&oe=utf-8 -TEST(TestSuite, Transform_mps2kph){ - double mpsValue = 1; - ASSERT_DOUBLE_EQ(amathutils::mps2kmph(mpsValue), mpsValue*3.6) << "Speed should be " << mpsValue*3.6 << "kmph"; +TEST(TestSuite, Transform_mps2kph) +{ + double mpsValue = 1; + ASSERT_DOUBLE_EQ(amathutils::mps2kmph(mpsValue), mpsValue*3.6) << "Speed should be " << mpsValue*3.6 << "kmph"; } // Value from https://www.google.com/search?client=ubuntu&channel=fs&q=kph+to+mps&ie=utf-8&oe=utf-8 -TEST(TestSuite, Transform_kmph2mps){ - double kmphValue = 1; - ASSERT_DOUBLE_EQ(amathutils::kmph2mps(kmphValue), kmphValue/3.6) << "Speed should be " << kmphValue/3.6 << "mps"; +TEST(TestSuite, Transform_kmph2mps) +{ + double kmphValue = 1; + ASSERT_DOUBLE_EQ(amathutils::kmph2mps(kmphValue), kmphValue/3.6) << "Speed should be " << kmphValue/3.6 << "mps"; } -TEST(TestSuite, GetGravityAcceleration){ - double accel = 10.8; - ASSERT_DOUBLE_EQ(amathutils::getGravityAcceleration(accel), accel/G_MPSS) << "Acceleration should be " << accel/G_MPSS << "g"; +TEST(TestSuite, GetGravityAcceleration) +{ + double accel = 10.8; + ASSERT_DOUBLE_EQ(amathutils::getGravityAcceleration(accel), accel/G_MPSS) + << "Acceleration should be " << accel/G_MPSS << "g"; } -TEST(TestSuite, GetAcceleration){ - double accel = 5.5; - double t = 2; - double v0 = 2.5; - double v = v0 + accel*t; - double x = v0*t + 0.5*accel*t*t; - ASSERT_DOUBLE_EQ(amathutils::getAcceleration(v0, v, x), accel) << "Acceleration should be " << accel; +TEST(TestSuite, GetAcceleration) +{ + double accel = 5.5; + double t = 2; + double v0 = 2.5; + double v = v0 + accel*t; + double x = v0*t + 0.5*accel*t*t; + ASSERT_DOUBLE_EQ(amathutils::getAcceleration(v0, v, x), accel) << "Acceleration should be " << accel; } -TEST(TestSuite, GetTimeFromAcceleration){ - double accel = 0.5; - double t = 2.8; - double v0 = 2; - double v = v0 + accel*t; - ASSERT_DOUBLE_EQ(amathutils::getTimefromAcceleration(v0, v, accel), t) << "Time should be " << t; +TEST(TestSuite, GetTimeFromAcceleration) +{ + double accel = 0.5; + double t = 2.8; + double v0 = 2; + double v = v0 + accel*t; + ASSERT_DOUBLE_EQ(amathutils::getTimefromAcceleration(v0, v, accel), t) << "Time should be " << t; } // Values taken from https://gerardnico.com/linear_algebra/closest_point_line - Example 5.4 -TEST(TestSuite, GetNearPointOnLine2D){ - geometry_msgs::Point a, b, p, nearPOut, nearP; - - a.x = 0; - a.y = 0; - a.z = 0; +TEST(TestSuite, GetNearPointOnLine2D) +{ + geometry_msgs::Point a, b, p, nearPOut, nearP; - b.x = 6; - b.y = 2; - b.z = 0; + a.x = 0; + a.y = 0; + a.z = 0; - p.x = 2; - p.y = 4; - p.z = 0; + b.x = 6; + b.y = 2; + b.z = 0; - nearP.x = 3; - nearP.y = 1; - nearP.z = 0; + p.x = 2; + p.y = 4; + p.z = 0; - nearPOut = amathutils::getNearPtOnLine(p, a, b); + nearP.x = 3; + nearP.y = 1; + nearP.z = 0; - ASSERT_DOUBLE_EQ(nearPOut.x, nearP.x) << "nearPoint coordinate X should be " << nearP.x; - ASSERT_DOUBLE_EQ(nearPOut.y, nearP.y) << "nearPoint coordinate X should be " << nearP.y; - ASSERT_DOUBLE_EQ(nearPOut.z, nearP.z) << "nearPoint coordinate X should be " << nearP.z; + nearPOut = amathutils::getNearPtOnLine(p, a, b); + ASSERT_DOUBLE_EQ(nearPOut.x, nearP.x) << "nearPoint coordinate X should be " << nearP.x; + ASSERT_DOUBLE_EQ(nearPOut.y, nearP.y) << "nearPoint coordinate X should be " << nearP.y; + ASSERT_DOUBLE_EQ(nearPOut.z, nearP.z) << "nearPoint coordinate X should be " << nearP.z; } // Values taken from https://math.stackexchange.com/questions/13176/how-to-find-a-point-on-a-line-closest-to-another-given-point -TEST(TestSuite, GetNearPointOnLine3D){ - geometry_msgs::Point a, b, p, nearPOut, nearP; - double threshold = 0.00000001; +TEST(TestSuite, GetNearPointOnLine3D) +{ + geometry_msgs::Point a, b, p, nearPOut, nearP; + double threshold = 0.00000001; - a.x = -2; - a.y = -4; - a.z = 5; + a.x = -2; + a.y = -4; + a.z = 5; - b.x = 0; - b.y = 0; - b.z = 1; + b.x = 0; + b.y = 0; + b.z = 1; - p.x = 1; - p.y = 1; - p.z = 1; + p.x = 1; + p.y = 1; + p.z = 1; - nearP.x = 1.0/3.0; - nearP.y = 2.0/3.0; - nearP.z = 1.0/3.0; + nearP.x = 1.0/3.0; + nearP.y = 2.0/3.0; + nearP.z = 1.0/3.0; - nearPOut = amathutils::getNearPtOnLine(p, a, b); + nearPOut = amathutils::getNearPtOnLine(p, a, b); - ASSERT_NEAR(nearPOut.x, nearP.x, threshold) << "nearPoint coordinate X should be " << nearP.x; - ASSERT_NEAR(nearPOut.y, nearP.y, threshold) << "nearPoint coordinate X should be " << nearP.y; - ASSERT_NEAR(nearPOut.z, nearP.z, threshold) << "nearPoint coordinate X should be " << nearP.z; + ASSERT_NEAR(nearPOut.x, nearP.x, threshold) << "nearPoint coordinate X should be " << nearP.x; + ASSERT_NEAR(nearPOut.y, nearP.y, threshold) << "nearPoint coordinate X should be " << nearP.y; + ASSERT_NEAR(nearPOut.z, nearP.z, threshold) << "nearPoint coordinate X should be " << nearP.z; } // Values from http://www.math.usm.edu/lambers/mat169/fall09/lecture17.pdf - The Distance Formula -TEST(TestSuite, GetDistance){ - - geometry_msgs::Point ptA, ptB; - geometry_msgs::Pose poseA, poseB; +TEST(TestSuite, GetDistance) +{ + geometry_msgs::Point ptA, ptB; + geometry_msgs::Pose poseA, poseB; - ptA.x = 2; - ptA.y = 3; - ptA.z = 1; + ptA.x = 2; + ptA.y = 3; + ptA.z = 1; - ptB.x = 8; - ptB.y = -5; - ptB.z = 0; + ptB.x = 8; + ptB.y = -5; + ptB.z = 0; - poseA.position.x = 2; - poseA.position.y = 3; - poseA.position.z = 1; + poseA.position.x = 2; + poseA.position.y = 3; + poseA.position.z = 1; - poseB.position.x = 8; - poseB.position.y = -5; - poseB.position.z = 0; + poseB.position.x = 8; + poseB.position.y = -5; + poseB.position.z = 0; - ASSERT_DOUBLE_EQ(amathutils::find_distance(ptA, ptB), sqrt(101)) << "Distance between points should be " << sqrt(101); - ASSERT_DOUBLE_EQ(amathutils::find_distance(poseA, poseB), sqrt(101)) << "Distance between poses should be " << sqrt(101); + ASSERT_DOUBLE_EQ(amathutils::find_distance(ptA, ptB), sqrt(101)) + << "Distance between points should be " << sqrt(101); + ASSERT_DOUBLE_EQ(amathutils::find_distance(poseA, poseB), sqrt(101)) + << "Distance between poses should be " << sqrt(101); } // Values from https://math.stackexchange.com/questions/707673/find-angle-in-degrees-from-one-point-to-another-in-2d-space -TEST(TestSuite, GetAngle){ - - geometry_msgs::Point ptA, ptB; +TEST(TestSuite, GetAngle) +{ + geometry_msgs::Point ptA, ptB; - ptA.x = 0; - ptA.y = 10; - ptA.z = 0; + ptA.x = 0; + ptA.y = 10; + ptA.z = 0; - ptB.x = 10; - ptB.y = 20; - ptB.z = 0; + ptB.x = 10; + ptB.y = 20; + ptB.z = 0; - ASSERT_DOUBLE_EQ(amathutils::find_angle(ptA, ptB), 45) << "Angle should be 45deg"; - ASSERT_DOUBLE_EQ(amathutils::find_angle(ptB, ptA), 225) << "Angle should be -45deg"; + ASSERT_DOUBLE_EQ(amathutils::find_angle(ptA, ptB), 45) << "Angle should be 45deg"; + ASSERT_DOUBLE_EQ(amathutils::find_angle(ptB, ptA), 225) << "Angle should be -45deg"; } // Values from https://www.mathopenref.com/coordintersection.html -TEST(TestSuite, LineIntersect){ - - geometry_msgs::Point l1_p1, l1_p2, l2_p1, l2_p2; - l1_p1.x = 29; - l1_p1.y = 5; - l1_p1.z = 0; - l1_p2.x = 51; - l1_p2.y = 15; - l1_p2.z = 0; - l2_p1.x = 15; - l2_p1.y = 10; - l2_p1.z = 0; - l2_p2.x = 58; - l2_p2.y = 10; - l2_p2.z = 0; - - ASSERT_TRUE(amathutils::isIntersectLine(l1_p1, l1_p2, l2_p1, l2_p2)) << "Lines intersect"; +TEST(TestSuite, LineIntersect) +{ + geometry_msgs::Point l1_p1, l1_p2, l2_p1, l2_p2; + l1_p1.x = 29; + l1_p1.y = 5; + l1_p1.z = 0; + l1_p2.x = 51; + l1_p2.y = 15; + l1_p2.z = 0; + l2_p1.x = 15; + l2_p1.y = 10; + l2_p1.z = 0; + l2_p2.x = 58; + l2_p2.y = 10; + l2_p2.z = 0; + + ASSERT_TRUE(amathutils::isIntersectLine(l1_p1, l1_p2, l2_p1, l2_p2)) << "Lines intersect"; } // Values from https://www.mathopenref.com/coordintersection.html -TEST(TestSuite, ParallelLines){ - - geometry_msgs::Point l1_p1, l1_p2, l2_p1, l2_p2; - l1_p1.x = 29; - l1_p1.y = 5; - l1_p1.z = 0; - l1_p2.x = 51; - l1_p2.y = 15; - l1_p2.z = 0; - l2_p1.x = 15; - l2_p1.y = 10; - l2_p1.z = 0; - l2_p2.x = 49; - l2_p2.y = 25; - l2_p2.z = 0; - - ASSERT_TRUE(!amathutils::isIntersectLine(l1_p1, l1_p2, l2_p1, l2_p2)) << "Parallel lines"; +TEST(TestSuite, ParallelLines) +{ + geometry_msgs::Point l1_p1, l1_p2, l2_p1, l2_p2; + l1_p1.x = 29; + l1_p1.y = 5; + l1_p1.z = 0; + l1_p2.x = 51; + l1_p2.y = 15; + l1_p2.z = 0; + l2_p1.x = 15; + l2_p1.y = 10; + l2_p1.z = 0; + l2_p2.x = 49; + l2_p2.y = 25; + l2_p2.z = 0; + + ASSERT_TRUE(!amathutils::isIntersectLine(l1_p1, l1_p2, l2_p1, l2_p2)) << "Parallel lines"; } #define LEFT 1 @@ -199,149 +227,153 @@ TEST(TestSuite, ParallelLines){ #define ONLINE 0 // 45degree angle line through the origin (0,0) -TEST(TestSuite, PointOnTheLeft){ - - geometry_msgs::Point p1, line_p1, line_p2; - p1.x = 1; - p1.y = 10; - p1.z = 0; - line_p1.x = 1; - line_p1.y = 1; - line_p1.z = 0; - line_p2.x = 10; - line_p2.y = 10; - line_p2.z = 0; - - ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), LEFT) << "Point is on the left"; +TEST(TestSuite, PointOnTheLeft) +{ + geometry_msgs::Point p1, line_p1, line_p2; + p1.x = 1; + p1.y = 10; + p1.z = 0; + line_p1.x = 1; + line_p1.y = 1; + line_p1.z = 0; + line_p2.x = 10; + line_p2.y = 10; + line_p2.z = 0; + + ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), LEFT) << "Point is on the left"; } // 45degree angle line through the origin (0,0) -TEST(TestSuite, PointOnTheRight){ - - geometry_msgs::Point p1, line_p1, line_p2; - p1.x = 10; - p1.y = 1; - p1.z = 0; - line_p1.x = 1; - line_p1.y = 1; - line_p1.z = 0; - line_p2.x = 10; - line_p2.y = 10; - line_p2.z = 0; - - ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), RIGHT) << "Point is on the right"; +TEST(TestSuite, PointOnTheRight) +{ + geometry_msgs::Point p1, line_p1, line_p2; + p1.x = 10; + p1.y = 1; + p1.z = 0; + line_p1.x = 1; + line_p1.y = 1; + line_p1.z = 0; + line_p2.x = 10; + line_p2.y = 10; + line_p2.z = 0; + + ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), RIGHT) << "Point is on the right"; } // 45degree angle line through the origin (0,0) -TEST(TestSuite, PointOnTheLine){ - - geometry_msgs::Point p1, line_p1, line_p2; - p1.x = -5; - p1.y = -5; - p1.z = 0; - line_p1.x = 1; - line_p1.y = 1; - line_p1.z = 0; - line_p2.x = 10; - line_p2.y = 10; - line_p2.z = 0; - - ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), ONLINE) << "Point is on the line "; +TEST(TestSuite, PointOnTheLine) +{ + geometry_msgs::Point p1, line_p1, line_p2; + p1.x = -5; + p1.y = -5; + p1.z = 0; + line_p1.x = 1; + line_p1.y = 1; + line_p1.z = 0; + line_p2.x = 10; + line_p2.y = 10; + line_p2.z = 0; + + ASSERT_EQ(amathutils::isPointLeftFromLine(p1, line_p1, line_p2), ONLINE) << "Point is on the line "; } // Point between p1, p2 -TEST(TestSuite, DistanceFromSegment1){ - geometry_msgs::Point p, line_p1, line_p2; - p.x = 1; - p.y = 1; - p.z = 0; - line_p1.x = 0; - line_p1.y = 0; - line_p1.z = 0; - line_p2.x = 2; - line_p2.y = 0; - line_p2.z = 0; - - ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment( line_p1, line_p2, p), 1.0) << "Point is 1m away from segment"; +TEST(TestSuite, DistanceFromSegment1) +{ + geometry_msgs::Point p, line_p1, line_p2; + p.x = 1; + p.y = 1; + p.z = 0; + line_p1.x = 0; + line_p1.y = 0; + line_p1.z = 0; + line_p2.x = 2; + line_p2.y = 0; + line_p2.z = 0; + + ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment(line_p1, line_p2, p), 1.0) << "Point is 1m away from segment"; } // Point 2m away from p1 -TEST(TestSuite, DistanceFromSegment2){ - geometry_msgs::Point p, line_p1, line_p2; - p.x = -2; - p.y = 0; - p.z = 0; - line_p1.x = 0; - line_p1.y = 0; - line_p1.z = 0; - line_p2.x = 2; - line_p2.y = 0; - line_p2.z = 0; - - ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment(line_p1, line_p2, p), 2.0) << "Point is 2m away from p1"; +TEST(TestSuite, DistanceFromSegment2) +{ + geometry_msgs::Point p, line_p1, line_p2; + p.x = -2; + p.y = 0; + p.z = 0; + line_p1.x = 0; + line_p1.y = 0; + line_p1.z = 0; + line_p2.x = 2; + line_p2.y = 0; + line_p2.z = 0; + + ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment(line_p1, line_p2, p), 2.0) << "Point is 2m away from p1"; } // Point 3m away from p2 -TEST(TestSuite, DistanceFromSegment3){ - geometry_msgs::Point p, line_p1, line_p2; - p.x = 5; - p.y = 0; - p.z = 0; - line_p1.x = 0; - line_p1.y = 0; - line_p1.z = 0; - line_p2.x = 2; - line_p2.y = 0; - line_p2.z = 0; - - ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment(line_p1, line_p2, p), 3.0) << "Point is 3m away from p1"; +TEST(TestSuite, DistanceFromSegment3) +{ + geometry_msgs::Point p, line_p1, line_p2; + p.x = 5; + p.y = 0; + p.z = 0; + line_p1.x = 0; + line_p1.y = 0; + line_p1.z = 0; + line_p2.x = 2; + line_p2.y = 0; + line_p2.z = 0; + + ASSERT_DOUBLE_EQ(amathutils::distanceFromSegment(line_p1, line_p2, p), 3.0) << "Point is 3m away from p1"; } -TEST(TestSuite, TestYawQuaternion){ - - geometry_msgs::Quaternion q; - q = amathutils::getQuaternionFromYaw(0.0); - ASSERT_DOUBLE_EQ(0.0, q.x); - ASSERT_DOUBLE_EQ(0.0, q.y); - ASSERT_DOUBLE_EQ(0.0, q.z); - ASSERT_DOUBLE_EQ(1.0, q.w); +TEST(TestSuite, TestYawQuaternion) +{ + geometry_msgs::Quaternion q; + q = amathutils::getQuaternionFromYaw(0.0); + ASSERT_DOUBLE_EQ(0.0, q.x); + ASSERT_DOUBLE_EQ(0.0, q.y); + ASSERT_DOUBLE_EQ(0.0, q.z); + ASSERT_DOUBLE_EQ(1.0, q.w); } - TEST(TestSuite, TestNormalizeRadian) { - ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(0.0)); - ASSERT_DOUBLE_EQ(0.5, amathutils::normalizeRadian(0.5)); - ASSERT_DOUBLE_EQ(-0.5, amathutils::normalizeRadian(-0.5)); - ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(2.0 * M_PI)); - ASSERT_DOUBLE_EQ(0.3, amathutils::normalizeRadian(2.0 * M_PI + 0.3)); - ASSERT_DOUBLE_EQ(M_PI, amathutils::normalizeRadian(3.0 * M_PI)); - ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(4.0 * M_PI)); - ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(-2.0 * M_PI)); - ASSERT_DOUBLE_EQ(0.3, amathutils::normalizeRadian(-2.0 * M_PI + 0.3)); - ASSERT_DOUBLE_EQ(-M_PI, amathutils::normalizeRadian(-3.0 * M_PI)); - ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(-4.0 * M_PI)); - ASSERT_DOUBLE_EQ(M_PI, amathutils::normalizeRadian(M_PI)); - ASSERT_DOUBLE_EQ(-M_PI, amathutils::normalizeRadian(-M_PI)); + ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(0.0)); + ASSERT_DOUBLE_EQ(0.5, amathutils::normalizeRadian(0.5)); + ASSERT_DOUBLE_EQ(-0.5, amathutils::normalizeRadian(-0.5)); + ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(2.0 * M_PI)); + ASSERT_DOUBLE_EQ(0.3, amathutils::normalizeRadian(2.0 * M_PI + 0.3)); + ASSERT_DOUBLE_EQ(M_PI, amathutils::normalizeRadian(3.0 * M_PI)); + ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(4.0 * M_PI)); + ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(-2.0 * M_PI)); + ASSERT_DOUBLE_EQ(0.3, amathutils::normalizeRadian(-2.0 * M_PI + 0.3)); + ASSERT_DOUBLE_EQ(-M_PI, amathutils::normalizeRadian(-3.0 * M_PI)); + ASSERT_DOUBLE_EQ(0.0, amathutils::normalizeRadian(-4.0 * M_PI)); + ASSERT_DOUBLE_EQ(M_PI, amathutils::normalizeRadian(M_PI)); + ASSERT_DOUBLE_EQ(-M_PI, amathutils::normalizeRadian(-M_PI)); } -TEST(TestSuite, TestGetIntersect){ - geometry_msgs::Point line1_p1, line1_p2, line2_p1, line2_p2, intersect_p; - line1_p1.x = 5; - line1_p1.y = 0; - line1_p2.x = 5; - line1_p2.y = 10; - line2_p1.x = 0; - line2_p1.y = 5; - line2_p2.x = 10; - line2_p2.y = 5; - - ASSERT_TRUE(amathutils::getIntersect(line1_p1, line1_p2, line2_p1, line2_p2, &intersect_p)); - ASSERT_DOUBLE_EQ(5, intersect_p.x); - ASSERT_DOUBLE_EQ(5, intersect_p.y); +TEST(TestSuite, TestGetIntersect) +{ + geometry_msgs::Point line1_p1, line1_p2, line2_p1, line2_p2, intersect_p; + line1_p1.x = 5; + line1_p1.y = 0; + line1_p2.x = 5; + line1_p2.y = 10; + line2_p1.x = 0; + line2_p1.y = 5; + line2_p2.x = 10; + line2_p2.y = 5; + + ASSERT_TRUE(amathutils::getIntersect(line1_p1, line1_p2, line2_p1, line2_p2, &intersect_p)); + ASSERT_DOUBLE_EQ(5, intersect_p.x); + ASSERT_DOUBLE_EQ(5, intersect_p.y); } -int main(int argc, char **argv) { - testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "TestNode"); - return RUN_ALL_TESTS(); +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "TestNode"); + return RUN_ALL_TESTS(); } diff --git a/common/amathutils_lib/test/src/test_butterworth_filter.cpp b/common/amathutils_lib/test/src/test_butterworth_filter.cpp index cf4b9c15e5d..55189b02b5b 100644 --- a/common/amathutils_lib/test/src/test_butterworth_filter.cpp +++ b/common/amathutils_lib/test/src/test_butterworth_filter.cpp @@ -16,156 +16,154 @@ * Authors: Ali Boyali, Simon Thompson */ - - -#include -#include #include -#include #include +#include +#include +#include + +#include #include #include "amathutils_lib/butterworth_filter.hpp" -class TestSuite : public ::testing::Test +class TestSuite : + public ::testing::Test { public: - TestSuite() - {} - - ~TestSuite() - {} + TestSuite() + {} }; TEST_F(TestSuite, OrderTest) { - - double Wp, Ws, Ap, As; - double err_lim = 0.0001; - Wp = 2.0; // passband frequency [rad/sec] - Ws = 3.0; // stopband frequency [rad/sec] - Ap = 6.0; // passband ripple mag or loss [dB] - As = 20.0; // stop band rippe attenuation [dB] - - ButterworthFilter bf; - - bf.Buttord(Wp, Ws, Ap, As); - Order_Cutoff NWn = bf.getOrderCutOff(); - - ASSERT_EQ(5, NWn.N); - ASSERT_NEAR(1.89478, NWn.Wc, 0.1); - - // test transfer functions - bf.computeContinuousTimeTF(); - bf.computeDiscreteTimeTF(); - - std::vector An = bf.getAn(); - std::vector Bn = bf.getBn(); - - /* - * Bd = [0.1913 0.9564 1.9128 1.9128 0.9564 0.1913] - * Ad = [1.0000 1.8849 1.8881 1.0137 0.2976 0.0365] - * - */ - - ASSERT_NEAR(1.8849, An[1], err_lim); - ASSERT_NEAR(1.8881, An[2], err_lim); - ASSERT_NEAR(1.0137, An[3], err_lim); - ASSERT_NEAR(0.29762, An[4], err_lim); - ASSERT_NEAR(0.0365, An[5], err_lim); - - ASSERT_NEAR(0.9564, Bn[1], err_lim); - ASSERT_NEAR(1.9128, Bn[2], err_lim); - ASSERT_NEAR(1.9128, Bn[3], err_lim); - ASSERT_NEAR(0.9564, Bn[4], err_lim); - ASSERT_NEAR(0.1913, Bn[5], err_lim); - - // Test with defined sampling frequency - bool use_sampling_frequency = true; - bf.setOrder(2); - bf.setCuttoffFrequency(10, 100); - bf.computeContinuousTimeTF(use_sampling_frequency); - bf.computeDiscreteTimeTF(use_sampling_frequency); - - An = bf.getAn(); - Bn = bf.getBn(); - - ASSERT_NEAR(1.0, An[0], err_lim); - ASSERT_NEAR(-1.14298, An[1], err_lim); - ASSERT_NEAR(0.4128, An[2], err_lim); - - ASSERT_NEAR(0.067455, Bn[0], err_lim); - ASSERT_NEAR(0.134911, Bn[1], err_lim); - - ASSERT_NEAR(0.067455, Bn[2], err_lim); - - //bool use_sampling_frequency = true; - // Test with order 5 - - bf.setOrder(5); - bf.setCuttoffFrequency(5, 100); - bf.computeContinuousTimeTF(use_sampling_frequency); - bf.computeDiscreteTimeTF(use_sampling_frequency); - - An = bf.getAn(); - Bn = bf.getBn(); - - ASSERT_NEAR(1.0, An[0], err_lim); - ASSERT_NEAR(-3.98454, An[1], err_lim); - ASSERT_NEAR(6.43487, An[2], err_lim); - ASSERT_NEAR(-5.25362, An[3], err_lim); - ASSERT_NEAR(2.16513, An[4], err_lim); - ASSERT_NEAR(-0.35993, An[5], err_lim); - - ASSERT_NEAR(5.9796e-05, Bn[0], err_lim); - ASSERT_NEAR(2.9898e-04, Bn[1], err_lim); - ASSERT_NEAR(5.9796e-04, Bn[2], err_lim); - ASSERT_NEAR(5.9796e-04, Bn[3], err_lim); - ASSERT_NEAR(2.9898e-04, Bn[4], err_lim); - ASSERT_NEAR(5.9796e-05, Bn[5], err_lim); - + double Wp, Ws, Ap, As; + double err_lim = 0.0001; + Wp = 2.0; // passband frequency [rad/sec] + Ws = 3.0; // stopband frequency [rad/sec] + Ap = 6.0; // passband ripple mag or loss [dB] + As = 20.0; // stop band rippe attenuation [dB] + + ButterworthFilter bf; + + bf.Buttord(Wp, Ws, Ap, As); + Order_Cutoff NWn = bf.getOrderCutOff(); + + ASSERT_EQ(5, NWn.N); + ASSERT_NEAR(1.89478, NWn.Wc, 0.1); + + // test transfer functions + bf.computeContinuousTimeTF(); + bf.computeDiscreteTimeTF(); + + std::vector An = bf.getAn(); + std::vector Bn = bf.getBn(); + + /* + * Bd = [0.1913 0.9564 1.9128 1.9128 0.9564 0.1913] + * Ad = [1.0000 1.8849 1.8881 1.0137 0.2976 0.0365] + * + */ + + ASSERT_NEAR(1.8849, An[1], err_lim); + ASSERT_NEAR(1.8881, An[2], err_lim); + ASSERT_NEAR(1.0137, An[3], err_lim); + ASSERT_NEAR(0.29762, An[4], err_lim); + ASSERT_NEAR(0.0365, An[5], err_lim); + + ASSERT_NEAR(0.9564, Bn[1], err_lim); + ASSERT_NEAR(1.9128, Bn[2], err_lim); + ASSERT_NEAR(1.9128, Bn[3], err_lim); + ASSERT_NEAR(0.9564, Bn[4], err_lim); + ASSERT_NEAR(0.1913, Bn[5], err_lim); + + // Test with defined sampling frequency + bool use_sampling_frequency = true; + bf.setOrder(2); + bf.setCuttoffFrequency(10, 100); + bf.computeContinuousTimeTF(use_sampling_frequency); + bf.computeDiscreteTimeTF(use_sampling_frequency); + + An = bf.getAn(); + Bn = bf.getBn(); + + ASSERT_NEAR(1.0, An[0], err_lim); + ASSERT_NEAR(-1.14298, An[1], err_lim); + ASSERT_NEAR(0.4128, An[2], err_lim); + + ASSERT_NEAR(0.067455, Bn[0], err_lim); + ASSERT_NEAR(0.134911, Bn[1], err_lim); + + ASSERT_NEAR(0.067455, Bn[2], err_lim); + + // bool use_sampling_frequency = true; + // Test with order 5 + + bf.setOrder(5); + bf.setCuttoffFrequency(5, 100); + bf.computeContinuousTimeTF(use_sampling_frequency); + bf.computeDiscreteTimeTF(use_sampling_frequency); + + An = bf.getAn(); + Bn = bf.getBn(); + + ASSERT_NEAR(1.0, An[0], err_lim); + ASSERT_NEAR(-3.98454, An[1], err_lim); + ASSERT_NEAR(6.43487, An[2], err_lim); + ASSERT_NEAR(-5.25362, An[3], err_lim); + ASSERT_NEAR(2.16513, An[4], err_lim); + ASSERT_NEAR(-0.35993, An[5], err_lim); + + ASSERT_NEAR(5.9796e-05, Bn[0], err_lim); + ASSERT_NEAR(2.9898e-04, Bn[1], err_lim); + ASSERT_NEAR(5.9796e-04, Bn[2], err_lim); + ASSERT_NEAR(5.9796e-04, Bn[3], err_lim); + ASSERT_NEAR(2.9898e-04, Bn[4], err_lim); + ASSERT_NEAR(5.9796e-05, Bn[5], err_lim); } + TEST_F(TestSuite, FilterTest) { + std::string noisy_data_str = "-0.1371005808542652 -0.3709432297059492 -0.3451507653422276 -0.9113837979184807 -0.6859465438088277 -1.130803977436368 -0.9436363618772066 -1.112200658662783 -0.7154709912539922 -0.628148023791735 -0.5282094726504378 -0.2157311690040078 -0.003056715799466224 0.3662332996766925 0.670284443627125 0.6487756443896476 0.8346368214115352 0.9149826841939783 1.036146653313645 0.9460126068389881 0.7943776776358672 0.6102342464348015 0.3066452312825719 0.198733461388589 -0.1602110234895633 -0.2406586131034821 -0.4268010870094675 -0.7987396363590219 -1.033385865255775 -1.055610786488985 -1.062757382508302 -0.9633911470286478 -0.6443418252958325 -0.7124675186143772 -0.4080025567122524 0.04252065686037088 0.2075318314404117 0.4818736896736595 0.6794600416480069 0.8109413436334337 1.03567284578397 1.117653438563471 1.133602854790763 1.006644229888911 0.6451847596770726 0.4783734780966611 0.1718252873280794 0.2035321575192375 -0.2365538970105183 -0.3692558251997717 -0.4739912900414277 -0.6888194604625204 -0.9201177390478115 -1.161989509610712 -1.100407991794637 -0.736905330798699 -0.6824755280897932 -0.358874554258565 -0.1665457916221496 0.1001605202302536 0.1309677172745332 0.3825332805692009 0.8384843843905719 0.9532211860170634 0.8295673423157065 0.8704830233348121 1.0421278614007 0.9415846857428267 0.863842804087283 0.5271023516302398 0.1688652968072815 -0.005546215398511188 -0.4405154046643793 -0.3871913100443919 -0.7596244593073413 -1.050314577452946 -0.8843182339793805 -1.06076262276747 -1.084844273909959 -0.9643608828084225 -0.5150342619911381 -0.5265395758832851 -0.3781195868538755 0.2413643475573005 0.3337588560449873 0.375111219372476 0.6167995986238088 0.7204879493487161 0.9678822689250257 1.120159661779572 0.7709765457767805 1.001621861423223 0.7307444509197082 0.343548426954505 0.1828021589239494 -0.2295619264720048 -0.2781911866431439 -0.625440539145193 -0.8980687231868024 -0.7827750682363231 -1.178552589390432 -0.9093329052735961 -1.049481023835633 -1.001182474987026 -0.4426052073400826 -0.4118661799194657 -0.2317011749950612 0.09025343576715453 0.2698007115302677 0.7871447555968187 0.6355329513622456 0.9822069903033573 0.9345692073092348 0.8435580999650101 1.010460052500257 0.5793227220658091 0.4635456634389983 0.2809137105835985 -0.1041131309548347 -0.01176984679462592 -0.3655803148733637 -0.4580925100515778 -0.6592065315050184 -0.9034769644872731 -1.179299107432306 -0.7880616600282311 -0.7996403172704826 -0.7205184085374469 -0.45547836487063 -0.2977559382835019 -0.1309826056646411 0.07310209133731735 0.288623133164537 0.8287661453922663 1.015004167620195 1.063978546693424 0.9805513672134679 0.9263897997506001 0.8847408431863337 0.8256807467446318 0.3253744736144354 0.3563941498176002 -0.01066801936638005 -0.4102939408412518 -0.485327520266525 -0.7449985451861397 -0.9199200901414391 -0.9814755267722944 -0.8009518999327396 -0.792624049994207 -0.9800529077936975 -0.5272848135843649 -0.4680895881951053 -0.1127915725315106 -0.03027587960489609 0.3550849408910264 0.7023980985453733 0.9042168830595656 0.9945419249758659 0.9863931844077523 0.8281983932715329 0.9179242332962795 0.8707669480297838 0.6443990907912504 0.4713737379704513 0.3588035177551953 -0.2272153402418235 -0.1908838988044834 -0.3875426194781867 -0.8558876185857398 -1.097109707983982 -0.8449136523770452 -1.046117772231036 -1.076479344504307 -0.6976332724079488 -0.5843110279114125 -0.5231146808120362 -0.2246522697555833 0.1696153682464069 0.4842383224939193 0.7105227314957293 0.736965032118687 0.8587363672056691 0.8395461915319591 1.083501485243421 0.767041134362224 0.7291711029664293 0.4675518718080606 0.3855626488805129 0.2888690887893905 -0.003416636133941719 -0.4560876334297616 -0.530516328785525 -0.8525529130915486 -1.016910752762844 -1.091599956796882 -0.8326843393435859 -0.9683306221348734 -0.6261013870933115 -0.6022311785378415 -0.2388903314658904"; // NOLINT + + std::string filtered_data_actual_str = "-0.002753441084361907 -0.01725484195781884 -0.04975400356783813 -0.1062174999431817 -0.1912128428226613 -0.2989301810510817 -0.4221489737151663 -0.5502127173606841 -0.6661400280543829 -0.7506670420039955 -0.7947828321038604 -0.7973932874802139 -0.7543449724231642 -0.6632369149529028 -0.523413931639269 -0.3443826622118596 -0.1456121498254898 0.05849731511868556 0.2590274344140979 0.4458228370014395 0.60457118703906 0.7209796179186816 0.784342915658452 0.7905358128713804 0.7419245233739661 0.6438690811394077 0.5078011913072592 0.3417225935293168 0.1463478417667104 -0.06946201422463558 -0.2867899189516319 -0.4863705217250148 -0.6482805909492491 -0.7595812255558665 -0.8196963772146335 -0.8222451909388749 -0.7601442845980215 -0.6403832719697302 -0.4749610839418473 -0.2774562751848083 -0.06147873542408955 0.1623098583288291 0.3812569463197684 0.5792474751661663 0.7358537002253744 0.8329187843517778 0.8638833859395074 0.8349404576919917 0.7561794615161928 0.6320895754695137 0.472624453952305 0.2920953008067464 0.09718159661786269 -0.1097621364424631 -0.3209205225779305 -0.5129026127976234 -0.6602327587304534 -0.7511041500705388 -0.7805118830466025 -0.7485568044784834 -0.6646196126778157 -0.542440509902709 -0.3856696578075186 -0.1936366297149061 0.01686742078700648 0.2204666257417112 0.4058888381799555 0.5704544914936845 0.7062710265327672 0.8008338936406366 0.8390604072810982 0.8134297825594364 0.7259674894726467 0.5859723762528095 0.409458048435324 0.2039755424657561 -0.01940064563244734 -0.2390224942835023 -0.4428305777449027 -0.6222150359794967 -0.7581450158487467 -0.8350490451452028 -0.8563760904909364 -0.8221736736224059 -0.7253859391011803 -0.5792513063359108 -0.40483696746661 -0.2136759654720214 -0.01314384172700706 0.1923667002891544 0.3886330086369225 0.5568685938319516 0.6904230507404202 0.7769814955364819 0.8022245814128699 0.7636005929583349 0.6663498742509556 0.5221024260862979 0.3389016480645037 0.1298262107779508 -0.08784109215811892 -0.3017076006043923 -0.4959053424457757 -0.6611403706593264 -0.7841827556495551 -0.8462568397616397 -0.8481710668722843 -0.7970279860950412 -0.6958089225309999 -0.546537059356502 -0.3570969274243752 -0.1458505557933878 0.07233428939792189 0.2806627093481237 0.4646735597863049 0.6145234788052054 0.7141356518059836 0.756548639516317 0.7414761032687529 0.6734673968754936 0.5658421592734542 0.4272399041674832 0.2650442264165674 0.08590478965820197 -0.1091006899631562 -0.306743696818966 -0.4802581847680378 -0.6153774683529787 -0.7067489025824831 -0.7473199791378606 -0.7370434929247721 -0.6810163455035136 -0.584272623054924 -0.4455836478769629 -0.2613699326045031 -0.04344534830134916 0.1826250457912295 0.3923035767621003 0.5699375158731055 0.7088028828591704 0.7983918947554687 0.8285216314543671 0.8019229259756029 0.7189315715271728 0.5815092502936023 0.4039624004503001 0.1994944992526493 -0.0192909803346456 -0.2320432377908689 -0.4176528986095191 -0.5707481244142196 -0.6889595439002087 -0.7596909965584708 -0.7756826311954292 -0.7381649439313006 -0.651153588662676 -0.5152782223190963 -0.3332362090505964 -0.1193135621708166 0.1053882391950277 0.3172618329346317 0.4991716717052922 0.6467305958453895 0.7557662032092406 0.8178211489893346 0.8310030064207594 0.7920153490899937 0.6976311135557269 0.5610409251188176 0.3917792224553188 0.1875549644576527 -0.03671664151195317 -0.2545846464822846 -0.4544701297089345 -0.6244168788783545 -0.7446268263279325 -0.8098918013260585 -0.8239466933370239 -0.7828933325922628 -0.6816449080671257 -0.5248237740714399 -0.3290201388219653 -0.1158923688533112 0.09626177345040375 0.2973226163264583 0.4781747353831783 0.6229651892897048 0.7198650213829796 0.7653502639768405 0.7637173276517409 0.7205956894058898 0.6315560675099344 0.4946725632822763 0.3195523443937227 0.1162461690715345 -0.103374129990069 -0.3169156411570013 -0.5032284339124055 -0.6504863504702056 -0.7493652339202174 -0.7941438568858976"; // NOLINT + + std::vector noisy_data; + std::vector filtered_data_actual; + + std::istringstream fda_iss(filtered_data_actual_str); + + for (std::string s; fda_iss >> s;) + filtered_data_actual.push_back(std::stod(s)); + + std::istringstream nd_iss(noisy_data_str); + + for (std::string s; nd_iss >> s;) + noisy_data.push_back(std::stod(s)); + + ButterworthFilter bf; + + double err_lim = 0.0001; + + bf.setOrder(2); + bf.setCuttoffFrequency(5, 100); + bf.computeContinuousTimeTF(true); + bf.computeDiscreteTimeTF(true); + + std::vector filtered_data; + filtered_data.resize(filtered_data_actual.size()); + + bf.initializeForFiltering(); + // set initial filter history to zero - same as in octave script + bf.filtVector(noisy_data, filtered_data, false); + + int N = filtered_data.size(); - std::string noisy_data_str = "-0.1371005808542652 -0.3709432297059492 -0.3451507653422276 -0.9113837979184807 -0.6859465438088277 -1.130803977436368 -0.9436363618772066 -1.112200658662783 -0.7154709912539922 -0.628148023791735 -0.5282094726504378 -0.2157311690040078 -0.003056715799466224 0.3662332996766925 0.670284443627125 0.6487756443896476 0.8346368214115352 0.9149826841939783 1.036146653313645 0.9460126068389881 0.7943776776358672 0.6102342464348015 0.3066452312825719 0.198733461388589 -0.1602110234895633 -0.2406586131034821 -0.4268010870094675 -0.7987396363590219 -1.033385865255775 -1.055610786488985 -1.062757382508302 -0.9633911470286478 -0.6443418252958325 -0.7124675186143772 -0.4080025567122524 0.04252065686037088 0.2075318314404117 0.4818736896736595 0.6794600416480069 0.8109413436334337 1.03567284578397 1.117653438563471 1.133602854790763 1.006644229888911 0.6451847596770726 0.4783734780966611 0.1718252873280794 0.2035321575192375 -0.2365538970105183 -0.3692558251997717 -0.4739912900414277 -0.6888194604625204 -0.9201177390478115 -1.161989509610712 -1.100407991794637 -0.736905330798699 -0.6824755280897932 -0.358874554258565 -0.1665457916221496 0.1001605202302536 0.1309677172745332 0.3825332805692009 0.8384843843905719 0.9532211860170634 0.8295673423157065 0.8704830233348121 1.0421278614007 0.9415846857428267 0.863842804087283 0.5271023516302398 0.1688652968072815 -0.005546215398511188 -0.4405154046643793 -0.3871913100443919 -0.7596244593073413 -1.050314577452946 -0.8843182339793805 -1.06076262276747 -1.084844273909959 -0.9643608828084225 -0.5150342619911381 -0.5265395758832851 -0.3781195868538755 0.2413643475573005 0.3337588560449873 0.375111219372476 0.6167995986238088 0.7204879493487161 0.9678822689250257 1.120159661779572 0.7709765457767805 1.001621861423223 0.7307444509197082 0.343548426954505 0.1828021589239494 -0.2295619264720048 -0.2781911866431439 -0.625440539145193 -0.8980687231868024 -0.7827750682363231 -1.178552589390432 -0.9093329052735961 -1.049481023835633 -1.001182474987026 -0.4426052073400826 -0.4118661799194657 -0.2317011749950612 0.09025343576715453 0.2698007115302677 0.7871447555968187 0.6355329513622456 0.9822069903033573 0.9345692073092348 0.8435580999650101 1.010460052500257 0.5793227220658091 0.4635456634389983 0.2809137105835985 -0.1041131309548347 -0.01176984679462592 -0.3655803148733637 -0.4580925100515778 -0.6592065315050184 -0.9034769644872731 -1.179299107432306 -0.7880616600282311 -0.7996403172704826 -0.7205184085374469 -0.45547836487063 -0.2977559382835019 -0.1309826056646411 0.07310209133731735 0.288623133164537 0.8287661453922663 1.015004167620195 1.063978546693424 0.9805513672134679 0.9263897997506001 0.8847408431863337 0.8256807467446318 0.3253744736144354 0.3563941498176002 -0.01066801936638005 -0.4102939408412518 -0.485327520266525 -0.7449985451861397 -0.9199200901414391 -0.9814755267722944 -0.8009518999327396 -0.792624049994207 -0.9800529077936975 -0.5272848135843649 -0.4680895881951053 -0.1127915725315106 -0.03027587960489609 0.3550849408910264 0.7023980985453733 0.9042168830595656 0.9945419249758659 0.9863931844077523 0.8281983932715329 0.9179242332962795 0.8707669480297838 0.6443990907912504 0.4713737379704513 0.3588035177551953 -0.2272153402418235 -0.1908838988044834 -0.3875426194781867 -0.8558876185857398 -1.097109707983982 -0.8449136523770452 -1.046117772231036 -1.076479344504307 -0.6976332724079488 -0.5843110279114125 -0.5231146808120362 -0.2246522697555833 0.1696153682464069 0.4842383224939193 0.7105227314957293 0.736965032118687 0.8587363672056691 0.8395461915319591 1.083501485243421 0.767041134362224 0.7291711029664293 0.4675518718080606 0.3855626488805129 0.2888690887893905 -0.003416636133941719 -0.4560876334297616 -0.530516328785525 -0.8525529130915486 -1.016910752762844 -1.091599956796882 -0.8326843393435859 -0.9683306221348734 -0.6261013870933115 -0.6022311785378415 -0.2388903314658904"; - - std::string filtered_data_actual_str = "-0.002753441084361907 -0.01725484195781884 -0.04975400356783813 -0.1062174999431817 -0.1912128428226613 -0.2989301810510817 -0.4221489737151663 -0.5502127173606841 -0.6661400280543829 -0.7506670420039955 -0.7947828321038604 -0.7973932874802139 -0.7543449724231642 -0.6632369149529028 -0.523413931639269 -0.3443826622118596 -0.1456121498254898 0.05849731511868556 0.2590274344140979 0.4458228370014395 0.60457118703906 0.7209796179186816 0.784342915658452 0.7905358128713804 0.7419245233739661 0.6438690811394077 0.5078011913072592 0.3417225935293168 0.1463478417667104 -0.06946201422463558 -0.2867899189516319 -0.4863705217250148 -0.6482805909492491 -0.7595812255558665 -0.8196963772146335 -0.8222451909388749 -0.7601442845980215 -0.6403832719697302 -0.4749610839418473 -0.2774562751848083 -0.06147873542408955 0.1623098583288291 0.3812569463197684 0.5792474751661663 0.7358537002253744 0.8329187843517778 0.8638833859395074 0.8349404576919917 0.7561794615161928 0.6320895754695137 0.472624453952305 0.2920953008067464 0.09718159661786269 -0.1097621364424631 -0.3209205225779305 -0.5129026127976234 -0.6602327587304534 -0.7511041500705388 -0.7805118830466025 -0.7485568044784834 -0.6646196126778157 -0.542440509902709 -0.3856696578075186 -0.1936366297149061 0.01686742078700648 0.2204666257417112 0.4058888381799555 0.5704544914936845 0.7062710265327672 0.8008338936406366 0.8390604072810982 0.8134297825594364 0.7259674894726467 0.5859723762528095 0.409458048435324 0.2039755424657561 -0.01940064563244734 -0.2390224942835023 -0.4428305777449027 -0.6222150359794967 -0.7581450158487467 -0.8350490451452028 -0.8563760904909364 -0.8221736736224059 -0.7253859391011803 -0.5792513063359108 -0.40483696746661 -0.2136759654720214 -0.01314384172700706 0.1923667002891544 0.3886330086369225 0.5568685938319516 0.6904230507404202 0.7769814955364819 0.8022245814128699 0.7636005929583349 0.6663498742509556 0.5221024260862979 0.3389016480645037 0.1298262107779508 -0.08784109215811892 -0.3017076006043923 -0.4959053424457757 -0.6611403706593264 -0.7841827556495551 -0.8462568397616397 -0.8481710668722843 -0.7970279860950412 -0.6958089225309999 -0.546537059356502 -0.3570969274243752 -0.1458505557933878 0.07233428939792189 0.2806627093481237 0.4646735597863049 0.6145234788052054 0.7141356518059836 0.756548639516317 0.7414761032687529 0.6734673968754936 0.5658421592734542 0.4272399041674832 0.2650442264165674 0.08590478965820197 -0.1091006899631562 -0.306743696818966 -0.4802581847680378 -0.6153774683529787 -0.7067489025824831 -0.7473199791378606 -0.7370434929247721 -0.6810163455035136 -0.584272623054924 -0.4455836478769629 -0.2613699326045031 -0.04344534830134916 0.1826250457912295 0.3923035767621003 0.5699375158731055 0.7088028828591704 0.7983918947554687 0.8285216314543671 0.8019229259756029 0.7189315715271728 0.5815092502936023 0.4039624004503001 0.1994944992526493 -0.0192909803346456 -0.2320432377908689 -0.4176528986095191 -0.5707481244142196 -0.6889595439002087 -0.7596909965584708 -0.7756826311954292 -0.7381649439313006 -0.651153588662676 -0.5152782223190963 -0.3332362090505964 -0.1193135621708166 0.1053882391950277 0.3172618329346317 0.4991716717052922 0.6467305958453895 0.7557662032092406 0.8178211489893346 0.8310030064207594 0.7920153490899937 0.6976311135557269 0.5610409251188176 0.3917792224553188 0.1875549644576527 -0.03671664151195317 -0.2545846464822846 -0.4544701297089345 -0.6244168788783545 -0.7446268263279325 -0.8098918013260585 -0.8239466933370239 -0.7828933325922628 -0.6816449080671257 -0.5248237740714399 -0.3290201388219653 -0.1158923688533112 0.09626177345040375 0.2973226163264583 0.4781747353831783 0.6229651892897048 0.7198650213829796 0.7653502639768405 0.7637173276517409 0.7205956894058898 0.6315560675099344 0.4946725632822763 0.3195523443937227 0.1162461690715345 -0.103374129990069 -0.3169156411570013 -0.5032284339124055 -0.6504863504702056 -0.7493652339202174 -0.7941438568858976"; - - std::vector noisy_data; - std::vector filtered_data_actual; - - std::istringstream fda_iss(filtered_data_actual_str); - for (std::string s; fda_iss >> s; ) - filtered_data_actual.push_back(std::stod(s)); - - std::istringstream nd_iss(noisy_data_str); - for (std::string s; nd_iss >> s; ) - noisy_data.push_back(std::stod(s)); - - ButterworthFilter bf; - - - double err_lim = 0.0001; - - bf.setOrder(2); - bf.setCuttoffFrequency(5, 100); - bf.computeContinuousTimeTF(true); - bf.computeDiscreteTimeTF(true); - - std::vector filtered_data; - filtered_data.resize(filtered_data_actual.size()); - - bf.initializeForFiltering(); - // set initial filter history to zero - same as in octave script - bf.filtVector(noisy_data, filtered_data, false); - - int N = filtered_data.size(); - for (int i = 0; i < N; i++) { - // std::cerr << "actual = " << filtered_data_actual[i] << "\t filtered = " << filtered_data[i] << "\n"; - ASSERT_NEAR(filtered_data_actual[i], filtered_data[i], err_lim); - } - + for (int i = 0; i < N; i++) + { + // std::cerr << "actual = " << filtered_data_actual[i] << "\t filtered = " << filtered_data[i] << "\n"; + ASSERT_NEAR(filtered_data_actual[i], filtered_data[i], err_lim); + } } int main(int argc, char **argv) diff --git a/common/amathutils_lib/test/src/test_kalman_filter.cpp b/common/amathutils_lib/test/src/test_kalman_filter.cpp index ecc947af043..d87cce566a4 100644 --- a/common/amathutils_lib/test/src/test_kalman_filter.cpp +++ b/common/amathutils_lib/test/src/test_kalman_filter.cpp @@ -21,144 +21,146 @@ #include "amathutils_lib/kalman_filter.hpp" #include "amathutils_lib/time_delay_kalman_filter.hpp" -class KalmanFilterTestSuite : public ::testing::Test +class KalmanFilterTestSuite : + public ::testing::Test { - public: - KalmanFilterTestSuite() {} - ~KalmanFilterTestSuite() {} +public: + KalmanFilterTestSuite() {} }; TEST_F(KalmanFilterTestSuite, updateCase) { - - KalmanFilter kf; - Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd y = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd A = Eigen::MatrixXd::Zero(3, 3); - Eigen::MatrixXd B = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd R = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd y_pred = y; - - ASSERT_EQ(false, kf.update(y)) << "uninitialized, false expected"; - ASSERT_EQ(false, kf.update(y, C, R)) << "uninitialized, false expected"; - ASSERT_EQ(false, kf.update(y, y_pred, C, R)) << "uninitialized, false expected"; - - kf.init(x, P); - Eigen::MatrixXd no_initialized; - ASSERT_EQ(false, kf.update(no_initialized)) << "inappropriate argument, false expected"; - - Eigen::MatrixXd R0 = Eigen::MatrixXd::Zero(3, 3); - Eigen::MatrixXd P0 = Eigen::MatrixXd::Zero(3, 3); - kf.init(x, P0); - ASSERT_EQ(false, kf.update(y, y_pred, C, R0)) << "R0 inverse problem, false expected"; - - kf.init(x, P); - Eigen::MatrixXd R_bad_dim = Eigen::MatrixXd::Identity(4, 4); - ASSERT_EQ(false, kf.update(y, y_pred, C, R_bad_dim)) << "R dimension problem, false expected"; - - Eigen::MatrixXd y_bad_dim = Eigen::MatrixXd::Identity(4, 1); - ASSERT_EQ(false, kf.update(y, y_bad_dim, C, R_bad_dim)) << "y_pred dimension problem, false expected"; - ASSERT_EQ(false, kf.update(y_bad_dim, y_pred, C, R_bad_dim)) << "y dimension problem, false expected"; - - Eigen::MatrixXd C_bad_dim = Eigen::MatrixXd::Identity(2, 2); - ASSERT_EQ(false, kf.update(y, y_pred, C_bad_dim, R_bad_dim)) << "C dimension problem, false expected"; - ASSERT_EQ(false, kf.update(y, y_pred, C_bad_dim)) << "C dimension problem, false expected"; - - kf.init(x, P); - ASSERT_EQ(true, kf.update(y, y_pred, C, R)) << "normal process, true expected"; - ASSERT_EQ(true, kf.update(y, C, R)) << "normal process, true expected"; - - kf.init(x, P); - y << 1.0, 1.0, 1.0; - y_pred << 0.0, 0.0, 0.0; - kf.update(y, y_pred, C, R); - Eigen::MatrixXd X_expected(3, 1); - X_expected << 0.5, 0.5, 0.5; - Eigen::MatrixXd X_actual; - kf.getX(X_actual); - ASSERT_TRUE((X_actual - X_expected).norm() < 1.0E-6) << "X_actual^T : " << X_actual.transpose() << ", X_expected^T : " << X_expected.transpose(); + KalmanFilter kf; + Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd y = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(3, 3); + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd R = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd y_pred = y; + + ASSERT_EQ(false, kf.update(y)) << "uninitialized, false expected"; + ASSERT_EQ(false, kf.update(y, C, R)) << "uninitialized, false expected"; + ASSERT_EQ(false, kf.update(y, y_pred, C, R)) << "uninitialized, false expected"; + + kf.init(x, P); + Eigen::MatrixXd no_initialized; + ASSERT_EQ(false, kf.update(no_initialized)) << "inappropriate argument, false expected"; + + Eigen::MatrixXd R0 = Eigen::MatrixXd::Zero(3, 3); + Eigen::MatrixXd P0 = Eigen::MatrixXd::Zero(3, 3); + kf.init(x, P0); + ASSERT_EQ(false, kf.update(y, y_pred, C, R0)) << "R0 inverse problem, false expected"; + + kf.init(x, P); + Eigen::MatrixXd R_bad_dim = Eigen::MatrixXd::Identity(4, 4); + ASSERT_EQ(false, kf.update(y, y_pred, C, R_bad_dim)) << "R dimension problem, false expected"; + + Eigen::MatrixXd y_bad_dim = Eigen::MatrixXd::Identity(4, 1); + ASSERT_EQ(false, kf.update(y, y_bad_dim, C, R_bad_dim)) << "y_pred dimension problem, false expected"; + ASSERT_EQ(false, kf.update(y_bad_dim, y_pred, C, R_bad_dim)) << "y dimension problem, false expected"; + + Eigen::MatrixXd C_bad_dim = Eigen::MatrixXd::Identity(2, 2); + ASSERT_EQ(false, kf.update(y, y_pred, C_bad_dim, R_bad_dim)) << "C dimension problem, false expected"; + ASSERT_EQ(false, kf.update(y, y_pred, C_bad_dim)) << "C dimension problem, false expected"; + + kf.init(x, P); + ASSERT_EQ(true, kf.update(y, y_pred, C, R)) << "normal process, true expected"; + ASSERT_EQ(true, kf.update(y, C, R)) << "normal process, true expected"; + + kf.init(x, P); + y << 1.0, 1.0, 1.0; + y_pred << 0.0, 0.0, 0.0; + kf.update(y, y_pred, C, R); + Eigen::MatrixXd X_expected(3, 1); + X_expected << 0.5, 0.5, 0.5; + Eigen::MatrixXd X_actual; + kf.getX(X_actual); + ASSERT_TRUE((X_actual - X_expected).norm() < 1.0E-6) << "X_actual^T : " + << X_actual.transpose() << ", X_expected^T : " << X_expected.transpose(); } TEST_F(KalmanFilterTestSuite, predictCase) { - KalmanFilter kf; - Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd x_next = x; - Eigen::MatrixXd u = Eigen::MatrixXd::Zero(2, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd A = Eigen::MatrixXd::Zero(3, 3); - Eigen::MatrixXd B = Eigen::MatrixXd::Zero(3, 2); - Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(3, 3); - - ASSERT_EQ(false, kf.predict(u)) << "uninitialized, false expected"; - ASSERT_EQ(false, kf.predict(x_next, A)) << "uninitialized, false expected"; - - kf.init(x, P); - Eigen::MatrixXd no_initialized; - ASSERT_EQ(false, kf.predict(no_initialized, A, Q)) << "inappropriate argument, false expected"; - ASSERT_EQ(false, kf.predict(x_next, no_initialized, Q)) << "inappropriate argument, false expected"; - ASSERT_EQ(false, kf.predict(x_next, A, no_initialized)) << "inappropriate argument, false expected"; - ASSERT_EQ(false, kf.predict(no_initialized, no_initialized, no_initialized)) << "inappropriate argument, false expected"; - ASSERT_EQ(false, kf.init(x, no_initialized)) << "inappropriate argument, false expected"; - - Eigen::MatrixXd A_bad_dim = Eigen::MatrixXd::Zero(4, 4); - ASSERT_EQ(false, kf.predict(x_next, A_bad_dim, Q)) << "A dimension problem, false expected"; - Eigen::MatrixXd Q_bad_dim = Eigen::MatrixXd::Zero(4, 4); - ASSERT_EQ(false, kf.predict(x_next, A, Q_bad_dim)) << "Q dimension problem, false expected"; - Eigen::MatrixXd x_bad_dim = Eigen::MatrixXd::Zero(4, 1); - ASSERT_EQ(false, kf.predict(x_bad_dim, A, Q)) << "x dimension problem, false expected"; - - ASSERT_EQ(true, kf.predict(x_next, A, Q)) << "normal process, true expected"; - ASSERT_EQ(true, kf.predict(u, A, B, Q)) << "normal process, true expected"; - - kf.init(x, P); - A = Eigen::MatrixXd::Identity(3, 3); - Q = Eigen::MatrixXd::Identity(3, 3); - kf.predict(x_next, A, Q); - Eigen::MatrixXd P_expected = Eigen::MatrixXd::Identity(3, 3) * 2.0; - Eigen::MatrixXd P_actual; - kf.getP(P_actual); - ASSERT_TRUE((P_actual - P_expected).norm() < 1.0E-6) << "P_actual : " << P_actual << ", P_expected : " << P_expected; + KalmanFilter kf; + Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd x_next = x; + Eigen::MatrixXd u = Eigen::MatrixXd::Zero(2, 1); + Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd A = Eigen::MatrixXd::Zero(3, 3); + Eigen::MatrixXd B = Eigen::MatrixXd::Zero(3, 2); + Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(3, 3); + + ASSERT_EQ(false, kf.predict(u)) << "uninitialized, false expected"; + ASSERT_EQ(false, kf.predict(x_next, A)) << "uninitialized, false expected"; + + kf.init(x, P); + Eigen::MatrixXd no_initialized; + ASSERT_EQ(false, kf.predict(no_initialized, A, Q)) << "inappropriate argument, false expected"; + ASSERT_EQ(false, kf.predict(x_next, no_initialized, Q)) << "inappropriate argument, false expected"; + ASSERT_EQ(false, kf.predict(x_next, A, no_initialized)) << "inappropriate argument, false expected"; + ASSERT_EQ(false, kf.predict(no_initialized, no_initialized, no_initialized)) + << "inappropriate argument, false expected"; + ASSERT_EQ(false, kf.init(x, no_initialized)) << "inappropriate argument, false expected"; + + Eigen::MatrixXd A_bad_dim = Eigen::MatrixXd::Zero(4, 4); + ASSERT_EQ(false, kf.predict(x_next, A_bad_dim, Q)) << "A dimension problem, false expected"; + Eigen::MatrixXd Q_bad_dim = Eigen::MatrixXd::Zero(4, 4); + ASSERT_EQ(false, kf.predict(x_next, A, Q_bad_dim)) << "Q dimension problem, false expected"; + Eigen::MatrixXd x_bad_dim = Eigen::MatrixXd::Zero(4, 1); + ASSERT_EQ(false, kf.predict(x_bad_dim, A, Q)) << "x dimension problem, false expected"; + + ASSERT_EQ(true, kf.predict(x_next, A, Q)) << "normal process, true expected"; + ASSERT_EQ(true, kf.predict(u, A, B, Q)) << "normal process, true expected"; + + kf.init(x, P); + A = Eigen::MatrixXd::Identity(3, 3); + Q = Eigen::MatrixXd::Identity(3, 3); + kf.predict(x_next, A, Q); + Eigen::MatrixXd P_expected = Eigen::MatrixXd::Identity(3, 3) * 2.0; + Eigen::MatrixXd P_actual; + kf.getP(P_actual); + ASSERT_TRUE((P_actual - P_expected).norm() < 1.0E-6) << "P_actual : " + << P_actual << ", P_expected : " << P_expected; } TEST_F(KalmanFilterTestSuite, delayedMeasurement) { - TimeDelayKalmanFilter tdkf; - Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd x_next = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd y = Eigen::MatrixXd::Zero(3, 1); - Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd A = Eigen::MatrixXd::Identity(3, 3) * 2.0; - Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); - Eigen::MatrixXd R = Eigen::MatrixXd::Identity(3, 3); - int max_delay_step = 5; - - tdkf.init(x, P, max_delay_step); - - x_next << 1.0, 2.0, 3.0; - tdkf.predictWithDelay(x_next, A, Q); - Eigen::MatrixXd x_curr; - tdkf.getLatestX(x_curr); - ASSERT_TRUE((x_next - x_curr).norm() < 1.0E-6); - - int delay_step = max_delay_step - 1; - ASSERT_EQ(true, tdkf.updateWithDelay(y, C, R, delay_step)); - - delay_step = max_delay_step; - ASSERT_EQ(false, tdkf.updateWithDelay(y, C, R, delay_step)); - - delay_step = max_delay_step + 1; - ASSERT_EQ(false, tdkf.updateWithDelay(y, C, R, delay_step)); + TimeDelayKalmanFilter tdkf; + Eigen::MatrixXd x = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd x_next = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd y = Eigen::MatrixXd::Zero(3, 1); + Eigen::MatrixXd P = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(3, 3) * 2.0; + Eigen::MatrixXd Q = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd C = Eigen::MatrixXd::Identity(3, 3); + Eigen::MatrixXd R = Eigen::MatrixXd::Identity(3, 3); + int max_delay_step = 5; + + tdkf.init(x, P, max_delay_step); + + x_next << 1.0, 2.0, 3.0; + tdkf.predictWithDelay(x_next, A, Q); + Eigen::MatrixXd x_curr; + tdkf.getLatestX(x_curr); + ASSERT_TRUE((x_next - x_curr).norm() < 1.0E-6); + + int delay_step = max_delay_step - 1; + ASSERT_EQ(true, tdkf.updateWithDelay(y, C, R, delay_step)); + + delay_step = max_delay_step; + ASSERT_EQ(false, tdkf.updateWithDelay(y, C, R, delay_step)); + + delay_step = max_delay_step + 1; + ASSERT_EQ(false, tdkf.updateWithDelay(y, C, R, delay_step)); } int main(int argc, char **argv) { - testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "KalmanFilterTestSuite"); - ros::NodeHandle nh; - return RUN_ALL_TESTS(); -} \ No newline at end of file + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "KalmanFilterTestSuite"); + ros::NodeHandle nh; + return RUN_ALL_TESTS(); +} diff --git a/common/amathutils_lib/test/test_butterworth_filter.test b/common/amathutils_lib/test/test_butterworth_filter.test index e440088dc7b..5a0cba73d31 100644 --- a/common/amathutils_lib/test/test_butterworth_filter.test +++ b/common/amathutils_lib/test/test_butterworth_filter.test @@ -1,4 +1,4 @@ - + diff --git a/common/build_depends.repos b/common/build_depends.repos index 229f656603f..5ec18083126 100644 --- a/common/build_depends.repos +++ b/common/build_depends.repos @@ -1,13 +1,5 @@ repositories: depends/autoware/messages: type: git - url: https://gitlab.com/autowarefoundation/autoware.ai/messages.git + url: https://github.com/Autoware-AI/messages.git version: master - depends/vendor/lanelet2: - type: git - url: https://github.com/fzi-forschungszentrum-informatik/Lanelet2.git - version: d13cf9c86b9f01821a7242ef6652c0daed5a7d84 - depends/vendor/mrt_cmake_modules: - type: git - url: https://github.com/KIT-MRT/mrt_cmake_modules.git - version: 67a93bcfee4f7e9e39e79f138ecadbba5c8392b7 diff --git a/common/gnss/CMakeLists.txt b/common/gnss/CMakeLists.txt index 2e826658114..211eb56bffa 100644 --- a/common/gnss/CMakeLists.txt +++ b/common/gnss/CMakeLists.txt @@ -1,43 +1,63 @@ cmake_minimum_required(VERSION 2.8.3) project(gnss) -find_package(catkin REQUIRED COMPONENTS roscpp) +find_package(catkin REQUIRED + COMPONENTS + roscpp + roslint +) catkin_package( - INCLUDE_DIRS include - LIBRARIES gnss + INCLUDE_DIRS include + LIBRARIES gnss ) include_directories( - include - ${catkin_INCLUDE_DIRS} + include + ${catkin_INCLUDE_DIRS} ) add_library(gnss - src/geo_pos_conv.cpp - ) + src/geo_pos_conv.cpp +) target_link_libraries(gnss - ${catkin_LIBRARIES} - ) + ${catkin_LIBRARIES} +) + +file(GLOB_RECURSE ROSLINT_FILES + LIST_DIRECTORIES false + *.cpp *.h *.hpp +) + +list(APPEND ROSLINT_CPP_OPTS + "--extensions=cc,h,hpp,cpp,cu,cuh" + "--filter=-build/c++14" +) + +roslint_cpp(${ROSLINT_FILES}) install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.hpp" - ) + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.hpp" +) + +install(TARGETS gnss + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) if(CATKIN_ENABLE_TESTING) + roslint_add_test() + find_package(rostest REQUIRED) find_package(rosunit REQUIRED) - add_rostest_gtest(test_gnss test/test_gnss.test test/test_gnss.cpp - src/geo_pos_conv.cpp) + add_rostest_gtest(test_gnss + test/test_gnss.test test/test_gnss.cpp + src/geo_pos_conv.cpp + ) target_link_libraries(test_gnss ${catkin_LIBRARIES}) add_dependencies(test_gnss ${catkin_EXPORTED_TARGETS}) endif() - -install(TARGETS gnss - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) diff --git a/common/gnss/include/gnss/geo_pos_conv.hpp b/common/gnss/include/gnss/geo_pos_conv.hpp index bff0bc90144..b9db5750085 100644 --- a/common/gnss/include/gnss/geo_pos_conv.hpp +++ b/common/gnss/include/gnss/geo_pos_conv.hpp @@ -1,20 +1,35 @@ -#ifndef __GEO_POS_CONV__ -#define __GEO_POS_CONV__ - -#include - -class geo_pos_conv { +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef GNSS_GEO_POS_CONV_HPP +#define GNSS_GEO_POS_CONV_HPP + +class geo_pos_conv +{ private: - double m_x; //m - double m_y; //m - double m_z; //m + double m_x; // m + double m_y; // m + double m_z; // m - double m_lat; //latitude - double m_lon; //longitude + double m_lat; // latitude + double m_lon; // longitude double m_h; - double m_PLato; //plane lat - double m_PLo; //plane lon + double m_PLato; // plane lat + double m_PLo; // plane lon public: geo_pos_conv(); @@ -26,10 +41,10 @@ class geo_pos_conv { void set_plane(int num); void set_xyz(double cx, double cy, double cz); - //set llh in radians + // set llh in radians void set_llh(double lat, double lon, double h); - //set llh in nmea degrees + // set llh in nmea degrees void set_llh_nmea_degrees(double latd, double lond, double h); void llh_to_xyz(double lat, double lon, double ele); @@ -38,4 +53,4 @@ class geo_pos_conv { void conv_xyz2llh(void); }; -#endif +#endif // GNSS_GEO_POSE_CONV_HPP diff --git a/common/gnss/package.xml b/common/gnss/package.xml index 74cf9e80f1d..daa3fb460f5 100644 --- a/common/gnss/package.xml +++ b/common/gnss/package.xml @@ -8,4 +8,5 @@ catkin roscpp + roslint diff --git a/common/gnss/src/geo_pos_conv.cpp b/common/gnss/src/geo_pos_conv.cpp index a8944d29f3c..21bf5ec23e9 100644 --- a/common/gnss/src/geo_pos_conv.cpp +++ b/common/gnss/src/geo_pos_conv.cpp @@ -16,6 +16,8 @@ #include +#include + geo_pos_conv::geo_pos_conv() : m_x(0) , m_y(0) @@ -51,8 +53,15 @@ void geo_pos_conv::set_plane(double lat, double lon) void geo_pos_conv::set_plane(int num) { - int lon_deg, lon_min, lat_deg, lat_min; // longitude and latitude of origin of each plane in Japan - if (num == 1) + int lon_deg, lon_min, lat_deg, lat_min; // longitude and latitude of origin of each plane in Japan + if (num == 0) + { + lon_deg = 0; + lon_min = 0; + lat_deg = 0; + lat_min = 0; + } + else if (num == 1) { lon_deg = 33; lon_min = 0; @@ -187,8 +196,8 @@ void geo_pos_conv::set_plane(int num) } // swap longitude and latitude - m_PLo = M_PI * ((double)lat_deg + (double)lat_min / 60.0) / 180.0; - m_PLato = M_PI * ((double)lon_deg + (double)lon_min / 60.0) / 180; + m_PLo = M_PI * (static_cast(lat_deg) + static_cast(lat_min) / 60.0) / 180.0; + m_PLato = M_PI * (static_cast(lon_deg) + static_cast(lon_min) / 60.0) / 180; } void geo_pos_conv::set_xyz(double cx, double cy, double cz) @@ -263,80 +272,80 @@ void geo_pos_conv::conv_llh2xyz(void) AW = 6378137.0; // Semimajor Axis FW = 1.0 / 298.257222101; // 298.257223563 //Geometrical flattening - Pe = (double)sqrt(2.0 * FW - pow(FW, 2)); - Pet = (double)sqrt(pow(Pe, 2) / (1.0 - pow(Pe, 2))); - - PA = (double)1.0 + 3.0 / 4.0 * pow(Pe, 2) + 45.0 / 64.0 * pow(Pe, 4) + 175.0 / 256.0 * pow(Pe, 6) + - 11025.0 / 16384.0 * pow(Pe, 8) + 43659.0 / 65536.0 * pow(Pe, 10) + 693693.0 / 1048576.0 * pow(Pe, 12) + - 19324305.0 / 29360128.0 * pow(Pe, 14) + 4927697775.0 / 7516192768.0 * pow(Pe, 16); - - PB = (double)3.0 / 4.0 * pow(Pe, 2) + 15.0 / 16.0 * pow(Pe, 4) + 525.0 / 512.0 * pow(Pe, 6) + - 2205.0 / 2048.0 * pow(Pe, 8) + 72765.0 / 65536.0 * pow(Pe, 10) + 297297.0 / 262144.0 * pow(Pe, 12) + - 135270135.0 / 117440512.0 * pow(Pe, 14) + 547521975.0 / 469762048.0 * pow(Pe, 16); - - PC = (double)15.0 / 64.0 * pow(Pe, 4) + 105.0 / 256.0 * pow(Pe, 6) + 2205.0 / 4096.0 * pow(Pe, 8) + - 10395.0 / 16384.0 * pow(Pe, 10) + 1486485.0 / 2097152.0 * pow(Pe, 12) + 45090045.0 / 58720256.0 * pow(Pe, 14) + - 766530765.0 / 939524096.0 * pow(Pe, 16); - - PD = (double)35.0 / 512.0 * pow(Pe, 6) + 315.0 / 2048.0 * pow(Pe, 8) + 31185.0 / 131072.0 * pow(Pe, 10) + - 165165.0 / 524288.0 * pow(Pe, 12) + 45090045.0 / 117440512.0 * pow(Pe, 14) + - 209053845.0 / 469762048.0 * pow(Pe, 16); - - PE = (double)315.0 / 16384.0 * pow(Pe, 8) + 3465.0 / 65536.0 * pow(Pe, 10) + 99099.0 / 1048576.0 * pow(Pe, 12) + - 4099095.0 / 29360128.0 * pow(Pe, 14) + 348423075.0 / 1879048192.0 * pow(Pe, 16); - - PF = (double)693.0 / 131072.0 * pow(Pe, 10) + 9009.0 / 524288.0 * pow(Pe, 12) + - 4099095.0 / 117440512.0 * pow(Pe, 14) + 26801775.0 / 469762048.0 * pow(Pe, 16); - - PG = (double)3003.0 / 2097152.0 * pow(Pe, 12) + 315315.0 / 58720256.0 * pow(Pe, 14) + - 11486475.0 / 939524096.0 * pow(Pe, 16); - - PH = (double)45045.0 / 117440512.0 * pow(Pe, 14) + 765765.0 / 469762048.0 * pow(Pe, 16); - - PI = (double)765765.0 / 7516192768.0 * pow(Pe, 16); - - PB1 = (double)AW * (1.0 - pow(Pe, 2)) * PA; - PB2 = (double)AW * (1.0 - pow(Pe, 2)) * PB / -2.0; - PB3 = (double)AW * (1.0 - pow(Pe, 2)) * PC / 4.0; - PB4 = (double)AW * (1.0 - pow(Pe, 2)) * PD / -6.0; - PB5 = (double)AW * (1.0 - pow(Pe, 2)) * PE / 8.0; - PB6 = (double)AW * (1.0 - pow(Pe, 2)) * PF / -10.0; - PB7 = (double)AW * (1.0 - pow(Pe, 2)) * PG / 12.0; - PB8 = (double)AW * (1.0 - pow(Pe, 2)) * PH / -14.0; - PB9 = (double)AW * (1.0 - pow(Pe, 2)) * PI / 16.0; - - PS = (double)PB1 * m_lat + PB2 * sin(2.0 * m_lat) + PB3 * sin(4.0 * m_lat) + PB4 * sin(6.0 * m_lat) + - PB5 * sin(8.0 * m_lat) + PB6 * sin(10.0 * m_lat) + PB7 * sin(12.0 * m_lat) + PB8 * sin(14.0 * m_lat) + - PB9 * sin(16.0 * m_lat); - - PSo = (double)PB1 * m_PLato + PB2 * sin(2.0 * m_PLato) + PB3 * sin(4.0 * m_PLato) + PB4 * sin(6.0 * m_PLato) + - PB5 * sin(8.0 * m_PLato) + PB6 * sin(10.0 * m_PLato) + PB7 * sin(12.0 * m_PLato) + PB8 * sin(14.0 * m_PLato) + - PB9 * sin(16.0 * m_PLato); - - PDL = (double)m_lon - m_PLo; - Pt = (double)tan(m_lat); - PW = (double)sqrt(1.0 - pow(Pe, 2) * pow(sin(m_lat), 2)); - PN = (double)AW / PW; - Pnn = (double)sqrt(pow(Pet, 2) * pow(cos(m_lat), 2)); - - m_x = (double)((PS - PSo) + (1.0 / 2.0) * PN * pow(cos(m_lat), 2.0) * Pt * pow(PDL, 2.0) + - (1.0 / 24.0) * PN * pow(cos(m_lat), 4) * Pt * - (5.0 - pow(Pt, 2) + 9.0 * pow(Pnn, 2) + 4.0 * pow(Pnn, 4)) * pow(PDL, 4) - - (1.0 / 720.0) * PN * pow(cos(m_lat), 6) * Pt * - (-61.0 + 58.0 * pow(Pt, 2) - pow(Pt, 4) - 270.0 * pow(Pnn, 2) + 330.0 * pow(Pt, 2) * pow(Pnn, 2)) * - pow(PDL, 6) - - (1.0 / 40320.0) * PN * pow(cos(m_lat), 8) * Pt * - (-1385.0 + 3111 * pow(Pt, 2) - 543 * pow(Pt, 4) + pow(Pt, 6)) * pow(PDL, 8)) * - Pmo; - - m_y = (double)(PN * cos(m_lat) * PDL - - 1.0 / 6.0 * PN * pow(cos(m_lat), 3) * (-1 + pow(Pt, 2) - pow(Pnn, 2)) * pow(PDL, 3) - - 1.0 / 120.0 * PN * pow(cos(m_lat), 5) * - (-5.0 + 18.0 * pow(Pt, 2) - pow(Pt, 4) - 14.0 * pow(Pnn, 2) + 58.0 * pow(Pt, 2) * pow(Pnn, 2)) * - pow(PDL, 5) - - 1.0 / 5040.0 * PN * pow(cos(m_lat), 7) * - (-61.0 + 479.0 * pow(Pt, 2) - 179.0 * pow(Pt, 4) + pow(Pt, 6)) * pow(PDL, 7)) * - Pmo; + Pe = static_cast(std::sqrt(2.0 * FW - std::pow(FW, 2))); + Pet = static_cast(std::sqrt(std::pow(Pe, 2) / (1.0 - std::pow(Pe, 2)))); + + PA = static_cast(1.0 + 3.0 / 4.0 * std::pow(Pe, 2) + 45.0 / 64.0 * std::pow(Pe, 4) + + 175.0 / 256.0 * std::pow(Pe, 6) + 11025.0 / 16384.0 * std::pow(Pe, 8) + 43659.0 / 65536.0 * + std::pow(Pe, 10) + 693693.0 / 1048576.0 * std::pow(Pe, 12) + 19324305.0 / 29360128.0 * std::pow(Pe, 14) + + 4927697775.0 / 7516192768.0 * std::pow(Pe, 16)); + + PB = static_cast(3.0 / 4.0 * std::pow(Pe, 2) + 15.0 / 16.0 * std::pow(Pe, 4) + 525.0 / 512.0 * + std::pow(Pe, 6) + 2205.0 / 2048.0 * std::pow(Pe, 8) + 72765.0 / 65536.0 * std::pow(Pe, 10) + 297297.0 / 262144.0 * + std::pow(Pe, 12) + 135270135.0 / 117440512.0 * std::pow(Pe, 14) + 547521975.0 / 469762048.0 * std::pow(Pe, 16)); + + PC = static_cast(15.0 / 64.0 * std::pow(Pe, 4) + 105.0 / 256.0 * std::pow(Pe, 6) + 2205.0 / 4096.0 * + std::pow(Pe, 8) + 10395.0 / 16384.0 * std::pow(Pe, 10) + 1486485.0 / 2097152.0 * std::pow(Pe, 12) + + 45090045.0 / 58720256.0 * std::pow(Pe, 14) + 766530765.0 / 939524096.0 * std::pow(Pe, 16)); + + PD = static_cast(35.0 / 512.0 * std::pow(Pe, 6) + 315.0 / 2048.0 * std::pow(Pe, 8) + 31185.0 / 131072.0 * + std::pow(Pe, 10) + 165165.0 / 524288.0 * std::pow(Pe, 12) + 45090045.0 / 117440512.0 * std::pow(Pe, 14) + + 209053845.0 / 469762048.0 * std::pow(Pe, 16)); + + PE = static_cast(315.0 / 16384.0 * std::pow(Pe, 8) + 3465.0 / 65536.0 * std::pow(Pe, 10) + + 99099.0 / 1048576.0 * std::pow(Pe, 12) + 4099095.0 / 29360128.0 * std::pow(Pe, 14) + 348423075.0 / 1879048192.0 * + std::pow(Pe, 16)); + + PF = static_cast(693.0 / 131072.0 * std::pow(Pe, 10) + 9009.0 / 524288.0 * std::pow(Pe, 12) + + 4099095.0 / 117440512.0 * std::pow(Pe, 14) + 26801775.0 / 469762048.0 * std::pow(Pe, 16)); + + PG = static_cast(3003.0 / 2097152.0 * std::pow(Pe, 12) + 315315.0 / 58720256.0 * std::pow(Pe, 14) + + 11486475.0 / 939524096.0 * std::pow(Pe, 16)); + + PH = static_cast(45045.0 / 117440512.0 * std::pow(Pe, 14) + 765765.0 / 469762048.0 * std::pow(Pe, 16)); + + PI = static_cast(765765.0 / 7516192768.0 * std::pow(Pe, 16)); + + PB1 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PA; + PB2 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PB / -2.0; + PB3 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PC / 4.0; + PB4 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PD / -6.0; + PB5 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PE / 8.0; + PB6 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PF / -10.0; + PB7 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PG / 12.0; + PB8 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PH / -14.0; + PB9 = static_cast(AW) * (1.0 - std::pow(Pe, 2)) * PI / 16.0; + + PS = static_cast(PB1) * m_lat + PB2 * std::sin(2.0 * m_lat) + PB3 * std::sin(4.0 * m_lat) + PB4 * + std::sin(6.0 * m_lat) + PB5 * std::sin(8.0 * m_lat) + PB6 * std::sin(10.0 * m_lat) + PB7 * std::sin(12.0 * m_lat) + + PB8 * std::sin(14.0 * m_lat) + PB9 * std::sin(16.0 * m_lat); + + PSo = static_cast(PB1) * m_PLato + PB2 * std::sin(2.0 * m_PLato) + PB3 * std::sin(4.0 * m_PLato) + PB4 * + std::sin(6.0 * m_PLato) + PB5 * std::sin(8.0 * m_PLato) + PB6 * std::sin(10.0 * m_PLato) + PB7 * + std::sin(12.0 * m_PLato) + PB8 * std::sin(14.0 * m_PLato) + PB9 * std::sin(16.0 * m_PLato); + + PDL = static_cast(m_lon) - m_PLo; + Pt = static_cast(std::tan(m_lat)); + PW = static_cast(std::sqrt(1.0 - std::pow(Pe, 2) * std::pow(std::sin(m_lat), 2))); + PN = static_cast(AW) / PW; + Pnn = static_cast(std::sqrt(std::pow(Pet, 2) * std::pow(std::cos(m_lat), 2))); + + m_x = static_cast(((PS - PSo) + (1.0 / 2.0) * PN * std::pow(std::cos(m_lat), 2.0) * Pt * std::pow(PDL, 2.0) + + (1.0 / 24.0) * PN * std::pow(std::cos(m_lat), 4) * Pt * + (5.0 - std::pow(Pt, 2) + 9.0 * std::pow(Pnn, 2) + 4.0 * std::pow(Pnn, 4)) * std::pow(PDL, 4) - + (1.0 / 720.0) * PN * std::pow(std::cos(m_lat), 6) * Pt * + (-61.0 + 58.0 * std::pow(Pt, 2) - std::pow(Pt, 4) - 270.0 * std::pow(Pnn, 2) + 330.0 * + std::pow(Pt, 2) * std::pow(Pnn, 2)) * + std::pow(PDL, 6) - (1.0 / 40320.0) * PN * std::pow(std::cos(m_lat), 8) * Pt * + (-1385.0 + 3111 * std::pow(Pt, 2) - 543 * std::pow(Pt, 4) + std::pow(Pt, 6)) * std::pow(PDL, 8)) * Pmo); + + m_y = static_cast((PN * std::cos(m_lat) * PDL - + 1.0 / 6.0 * PN * std::pow(std::cos(m_lat), 3) * (-1 + std::pow(Pt, 2) - std::pow(Pnn, 2)) * std::pow(PDL, 3) - + 1.0 / 120.0 * PN * std::pow(std::cos(m_lat), 5) * + (-5.0 + 18.0 * std::pow(Pt, 2) - std::pow(Pt, 4) - 14.0 * std::pow(Pnn, 2) + 58.0 * std::pow(Pt, 2) * + std::pow(Pnn, 2)) * std::pow(PDL, 5) - + 1.0 / 5040.0 * PN * std::pow(std::cos(m_lat), 7) * + (-61.0 + 479.0 * std::pow(Pt, 2) - 179.0 * std::pow(Pt, 4) + std::pow(Pt, 6)) * std::pow(PDL, 7)) * Pmo); m_z = m_h; } diff --git a/common/gnss/test/test_gnss.cpp b/common/gnss/test/test_gnss.cpp index 15f6c6a1629..863561776d9 100644 --- a/common/gnss/test/test_gnss.cpp +++ b/common/gnss/test/test_gnss.cpp @@ -1,49 +1,65 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + #include #include #include "gnss/geo_pos_conv.hpp" -TEST(TestSuite, llhNmeaDegreesTest) { - +TEST(TestSuite, llhNmeaDegreesTest) +{ geo_pos_conv geo_; - geo_.set_llh_nmea_degrees(0.000000,0.000000,10.124025); + geo_.set_llh_nmea_degrees(0.000000, 0.000000, 10.124025); ASSERT_FLOAT_EQ(0.000000, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(0.000000, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(1.000000,1.000000,10.124025); + geo_.set_llh_nmea_degrees(1.000000, 1.000000, 10.124025); ASSERT_FLOAT_EQ(1842.720386, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(1855.139262, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(-1.000000,-1.000000,10.124025); + geo_.set_llh_nmea_degrees(-1.000000, -1.000000, 10.124025); ASSERT_FLOAT_EQ(-1842.720386, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(-1855.139262, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(10.000000,10.000000,10.124025); + geo_.set_llh_nmea_degrees(10.000000, 10.000000, 10.124025); ASSERT_FLOAT_EQ(18427.282074, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(18551.341517, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(-10.000000,-10.000000,10.124025); + geo_.set_llh_nmea_degrees(-10.000000, -10.000000, 10.124025); ASSERT_FLOAT_EQ(-18427.282074, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(-18551.341517, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(100.000000,100.000000,10.124025); + geo_.set_llh_nmea_degrees(100.000000, 100.000000, 10.124025); ASSERT_FLOAT_EQ(110580.283099, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(111297.204780, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); - geo_.set_llh_nmea_degrees(-100.000000,-100.000000,10.124025); + geo_.set_llh_nmea_degrees(-100.000000, -100.000000, 10.124025); ASSERT_FLOAT_EQ(-110580.283099, geo_.geo_pos_conv::x()); ASSERT_FLOAT_EQ(-111297.204780, geo_.geo_pos_conv::y()); ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z()); } -int main(int argc, char ** argv) +int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "test_gnss"); diff --git a/common/lanelet2_extension/include/lanelet2_extension/utility/query.h b/common/lanelet2_extension/include/lanelet2_extension/utility/query.h index e75b496905e..9ef9231f68a 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/utility/query.h +++ b/common/lanelet2_extension/include/lanelet2_extension/utility/query.h @@ -124,28 +124,58 @@ std::vector trafficLights(const lanelet::ConstLan std::vector autowareTrafficLights(const lanelet::ConstLanelets lanelets); /** - * [stopLinesLanelets extracts stoplines that are associated to lanelets] + * [getTrafficLightStopLines extracts stoplines that are associated with + * traffic lights] * @param lanelets [input lanelets] * @return [stop lines that are associated with input lanelets] */ -std::vector stopLinesLanelets(const lanelet::ConstLanelets lanelets); +std::vector getTrafficLightStopLines(const lanelet::ConstLanelets lanelets); /** - * [stopLinesLanelet extracts stop lines that are associated with a given - * lanelet] + * [getTrafficLightStopLines extracts stoplines that are associated with + * traffic lights] * @param ll [input lanelet] * @return [stop lines that are associated with input lanelet] */ -std::vector stopLinesLanelet(const lanelet::ConstLanelet ll); +std::vector getTrafficLightStopLines(const lanelet::ConstLanelet ll); /** - * [stopSignes extracts stoplines that are associated with stopsignes] + * [getStopSignStopLines extracts stoplines that are associated with any stop + * signs, regardless of the type of regulatory element] * @param lanelets [input lanelets] * @param stop_sign_id [sign id of stop sign] * @return [array of stoplines] */ -std::vector stopSignStopLines(const lanelet::ConstLanelets lanelets, - const std::string& stop_sign_id = "stop_sign"); +std::vector getStopSignStopLines(const lanelet::ConstLanelets lanelets, + const std::string& stop_sign_id = "stop_sign"); + +/** + * [getTrafficSignStopLines extracts stoplines that are associated with + * traffic_sign regulatory elements ] + * @param lanelets [input lanelets] + * @param stop_sign_id [sign id of stop sign] + * @return [array of stoplines] + */ +std::vector getTrafficSignStopLines(const lanelet::ConstLanelets lanelets, + const std::string& stop_sign_id = "stop_sign"); + +/** + * [getRightOfWayStopLines extracts stoplines that are associated with + * right_of_way regulatory elements ] + * @param lanelets [input lanelets] + * @param stop_sign_id [sign id of stop sign] + * @return [array of stoplines] + */ +std::vector getRightOfWayStopLines(const lanelet::ConstLanelets lanelets); + +/** + * [getAllWayStopStopLines extracts stoplines that are associated with + * all_way_stop regulatory elements ] + * @param lanelets [input lanelets] + * @param stop_sign_id [sign id of stop sign] + * @return [array of stoplines] + */ +std::vector getAllWayStopStopLines(const lanelet::ConstLanelets lanelets); } // namespace query } // namespace utils diff --git a/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h b/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h index 938a72a35e5..97d109ae482 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h +++ b/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h @@ -35,6 +35,14 @@ namespace lanelet { namespace visualization { +/** + * [polygon2Triangle converts polygon into vector of triangles. Used for + * triangulation] + * @param polygon [input polygon] + * @param triangles [array of polygon message, each containing 3 vertices] + */ +void polygon2Triangle(const geometry_msgs::Polygon& polygon, + std::vector* triangles); /** * [lanelet2Triangle converts lanelet into vector of triangles. Used for * triangulation] diff --git a/common/lanelet2_extension/lib/query.cpp b/common/lanelet2_extension/lib/query.cpp index 8c699f3e1ff..74c01e6394b 100644 --- a/common/lanelet2_extension/lib/query.cpp +++ b/common/lanelet2_extension/lib/query.cpp @@ -294,81 +294,66 @@ std::vector query::autowareTrafficLights( } // return all stop lines and ref lines from a given set of lanelets -std::vector query::stopLinesLanelets(const lanelet::ConstLanelets lanelets) +std::vector query::getTrafficLightStopLines(const lanelet::ConstLanelets lanelets) { std::vector stoplines; for (auto lli = lanelets.begin(); lli != lanelets.end(); lli++) { std::vector ll_stoplines; - ll_stoplines = query::stopLinesLanelet(*lli); + ll_stoplines = query::getTrafficLightStopLines(*lli); stoplines.insert(stoplines.end(), ll_stoplines.begin(), ll_stoplines.end()); } return stoplines; } -// return all stop and ref lines from a given lanel -std::vector query::stopLinesLanelet(const lanelet::ConstLanelet ll) +// return all stop and ref lines from a given lanelet +std::vector query::getTrafficLightStopLines(const lanelet::ConstLanelet ll) { std::vector stoplines; - // find stop lines referened by right ofway reg. elems. - std::vector > right_of_way_reg_elems = - ll.regulatoryElementsAs(); - - if (right_of_way_reg_elems.size() > 0) - { - // lanelet has a right of way elem elemetn - for (auto j = right_of_way_reg_elems.begin(); j < right_of_way_reg_elems.end(); j++) - { - if ((*j)->getManeuver(ll) == lanelet::ManeuverType::Yield) - { - // lanelet has a yield reg. elem. - lanelet::Optional row_stopline_opt = (*j)->stopLine(); - if (!!row_stopline_opt) - stoplines.push_back(row_stopline_opt.get()); - } - } - } - // find stop lines referenced by traffic lights std::vector > traffic_light_reg_elems = ll.regulatoryElementsAs(); - if (traffic_light_reg_elems.size() > 0) + // lanelet has a traffic light elem element + for (const auto reg_elem : traffic_light_reg_elems) { - // lanelet has a traffic light elem elemetn - for (auto j = traffic_light_reg_elems.begin(); j < traffic_light_reg_elems.end(); j++) + lanelet::Optional traffic_light_stopline_opt = reg_elem->stopLine(); + if (!!traffic_light_stopline_opt) { - lanelet::Optional traffic_light_stopline_opt = (*j)->stopLine(); - if (!!traffic_light_stopline_opt) - stoplines.push_back(traffic_light_stopline_opt.get()); + stoplines.push_back(traffic_light_stopline_opt.get()); } } - // find stop lines referenced by traffic signs - std::vector > traffic_sign_reg_elems = - ll.regulatoryElementsAs(); - if (traffic_sign_reg_elems.size() > 0) - { - // lanelet has a traffic sign reg elem - can have multiple ref lines (but - // stop sign shod have 1 - for (auto j = traffic_sign_reg_elems.begin(); j < traffic_sign_reg_elems.end(); j++) - { - lanelet::ConstLineStrings3d traffic_sign_stoplines = (*j)->refLines(); - if (traffic_sign_stoplines.size() > 0) - stoplines.push_back(traffic_sign_stoplines.front()); - } - } return stoplines; } -std::vector query::stopSignStopLines(const lanelet::ConstLanelets lanelets, - const std::string& stop_sign_id) +std::vector query::getStopSignStopLines(const lanelet::ConstLanelets lanelets, + const std::string& stop_sign_id) { - std::vector stoplines; + std::vector all_stoplines; + std::vector traffic_sign_stoplines; + std::vector right_of_way_stoplines; + std::vector all_way_stop_stoplines; + + traffic_sign_stoplines = getTrafficSignStopLines(lanelets, stop_sign_id); + right_of_way_stoplines = getRightOfWayStopLines(lanelets); + all_way_stop_stoplines = getAllWayStopStopLines(lanelets); + + all_stoplines.reserve(traffic_sign_stoplines.size() + right_of_way_stoplines.size() + all_way_stop_stoplines.size()); + all_stoplines.insert(all_stoplines.end(), traffic_sign_stoplines.begin(), traffic_sign_stoplines.end()); + all_stoplines.insert(all_stoplines.end(), right_of_way_stoplines.begin(), right_of_way_stoplines.end()); + all_stoplines.insert(all_stoplines.end(), all_way_stop_stoplines.begin(), all_way_stop_stoplines.end()); + return all_stoplines; +} + +std::vector query::getTrafficSignStopLines(const lanelet::ConstLanelets lanelets, + const std::string& stop_sign_id) +{ + std::vector stoplines; std::set checklist; for (const auto& ll : lanelets) @@ -380,7 +365,7 @@ std::vector query::stopSignStopLines(const lanelet:: if (traffic_sign_reg_elems.size() > 0) { // lanelet has a traffic sign reg elem - can have multiple ref lines (but - // stop sign shod have 1 + // stop sign should have 1 for (const auto& ts : traffic_sign_reg_elems) { // skip if traffic sign is not stop sign @@ -407,5 +392,54 @@ std::vector query::stopSignStopLines(const lanelet:: return stoplines; } +std::vector query::getRightOfWayStopLines(const lanelet::ConstLanelets lanelets) +{ + std::vector stoplines; + + for (const auto& ll : lanelets) + { + // find stop lines referenced by RightOfWay reg. elems. + std::vector > right_of_way_reg_elems = + ll.regulatoryElementsAs(); + + for (const auto reg_elem : right_of_way_reg_elems) + { + if (reg_elem->getManeuver(ll) == lanelet::ManeuverType::Yield) + { + // lanelet has a yield reg. elem. + lanelet::Optional row_stopline_opt = reg_elem->stopLine(); + if (!!row_stopline_opt) + { + stoplines.push_back(row_stopline_opt.get()); + } + } + } + } + return stoplines; +} + +std::vector query::getAllWayStopStopLines(const lanelet::ConstLanelets lanelets) +{ + std::vector stoplines; + + for (const auto& ll : lanelets) + { + // Get every AllWayStop reg. elem. that this lanelet references. + std::vector> all_way_stop_reg_elems = + ll.regulatoryElementsAs(); + + for (const auto reg_elem : all_way_stop_reg_elems) + { + // Only get the stopline for this lanelet + lanelet::Optional stopline = reg_elem->getStopLine(ll); + if (!!stopline) + { + stoplines.push_back(stopline.get()); + } + } + } + return stoplines; +} + } // namespace utils } // namespace lanelet diff --git a/common/lanelet2_extension/lib/utilities.cpp b/common/lanelet2_extension/lib/utilities.cpp index c8566a48410..cc3c0f7b29a 100644 --- a/common/lanelet2_extension/lib/utilities.cpp +++ b/common/lanelet2_extension/lib/utilities.cpp @@ -69,6 +69,8 @@ void removeImpossibleCandidates(const lanelet::LaneletMapPtr lanelet_map, int prev_wp_gid; bool first_wp = true; + + // Loop over each waypoint for (const auto& wp : waypoints) { if (first_wp) @@ -78,39 +80,61 @@ void removeImpossibleCandidates(const lanelet::LaneletMapPtr lanelet_map, continue; } + // Pointer to vector of candidate lanelet ids for the current waypoint auto candidate_ids_ptr = &wp_candidate_lanelets->at(wp.gid); + + // Pointer to vector of candidate lanelet ids for the previous waypoint const auto prev_wp_candidate_ids_ptr = &wp_candidate_lanelets->at(prev_wp_gid); - // do not eliminate if previous waypoint do not have any candidate + // Do not remove candidates if previous waypoint does not have any candidates if (prev_wp_candidate_ids_ptr->empty()) + { + prev_wp_gid = wp.gid; + continue; + } + + // Skip if there is only one candidate lanelet for this waypoint + if (candidate_ids_ptr->size() == 1) + { + prev_wp_gid = wp.gid; continue; + } std::vector removing_ids; + + // Loop over each candidate lanelet id for (const auto candidate_id : *candidate_ids_ptr) { - // do not eliminate if the belonging lane exists in candidates of previous - // waypoint + // Do not remove candidate if the candidate lanelet id exists in the + // candidates of the previous waypoint + // This is to prevent removing a candidate that is the same lanelet as + // the previous waypoint's lanelet if (exists(*prev_wp_candidate_ids_ptr, candidate_id)) + { continue; + } + + auto candidate_lanelet = lanelet_map->laneletLayer.get(candidate_id); - auto lanelet = lanelet_map->laneletLayer.get(candidate_id); - // get available previous lanelet from routing graph + // Get previous connecting lanelets from routing graph lanelet::ConstLanelets previous_lanelets; if (reverse) { - previous_lanelets = routing_graph->following(lanelet); + previous_lanelets = routing_graph->following(candidate_lanelet); } else { - previous_lanelets = routing_graph->previous(lanelet); + previous_lanelets = routing_graph->previous(candidate_lanelet); } - // connection is impossible if none of predecessor lanelets match with - // lanelet candidates from previous waypoint + // Loop over all lanelets that connect (feed into) to the current lanelet + // candidate. bool connection_possible = false; - for (const auto& previous_lanelet : previous_lanelets) + for (const auto& connecting_lanelet : previous_lanelets) { - if (exists(*prev_wp_candidate_ids_ptr, previous_lanelet.id())) + // Remove candidate if previous waypoint's candidate lanelets don't + // connect to the current candidate lanelet. + if (exists(*prev_wp_candidate_ids_ptr, connecting_lanelet.id())) { connection_possible = true; break; @@ -125,9 +149,10 @@ void removeImpossibleCandidates(const lanelet::LaneletMapPtr lanelet_map, // declare function for remove_if separately, because roslint is not supporting lambda functions very well. auto remove_existing_func = [removing_ids](int id) { return exists(removing_ids, id); }; - auto result = std::remove_if(candidate_ids_ptr->begin(), candidate_ids_ptr->end(), remove_existing_func); + // Remove candidate lanelet ids + auto shortened_end = std::remove_if(candidate_ids_ptr->begin(), candidate_ids_ptr->end(), remove_existing_func); + candidate_ids_ptr->erase(shortened_end, candidate_ids_ptr->end()); - candidate_ids_ptr->erase(result, candidate_ids_ptr->end()); prev_wp_gid = wp.gid; } } @@ -305,23 +330,30 @@ std::vector resamplePoints(const lanelet::ConstLineString */ lanelet::LineString3d generateFineCenterline(const lanelet::ConstLanelet& lanelet_obj) { - if (lanelet_obj.rightBound2d().size() != lanelet_obj.leftBound2d().size()) { - throw std::invalid_argument("Left and right bound not the same size for centerline computation"); - } - - lanelet::ConstLineString3d left = lanelet_obj.leftBound3d(); - lanelet::ConstLineString3d right = lanelet_obj.rightBound3d(); - lanelet::LineString3d center; - double x, y, z; - for (int i = 0; i < lanelet_obj.rightBound3d().size(); i++) { - x = (left[i].x() + right[i].x())/2.0; - y = (left[i].y() + right[i].y())/2.0; - z = (left[i].z() + right[i].z())/2.0; - lanelet::Point3d point(lanelet::utils::getId(), x, y, z); - center.push_back(point); + // Parameter + constexpr double point_interval = 1.0; // [m] + + // Get length of longer border + const double left_length = lanelet::geometry::length(lanelet_obj.leftBound()); + const double right_length = lanelet::geometry::length(lanelet_obj.rightBound()); + const double longer_distance = (left_length > right_length) ? left_length : right_length; + const int num_segments = std::max(static_cast(ceil(longer_distance / point_interval)), 1); + + // Resample points + const auto left_points = resamplePoints(lanelet_obj.leftBound(), num_segments); + const auto right_points = resamplePoints(lanelet_obj.rightBound(), num_segments); + + // Create centerline + lanelet::LineString3d centerline(lanelet::utils::getId()); + for (int i = 0; i < num_segments + 1; i++) + { + // Add ID for the average point of left and right + const auto center_basic_point = (right_points.at(i) + left_points.at(i)) / 2; + const lanelet::Point3d center_point(lanelet::utils::getId(), center_basic_point.x(), center_basic_point.y(), + center_basic_point.z()); + centerline.push_back(center_point); } - - return center; + return centerline; } diff --git a/common/lanelet2_extension/lib/visualization.cpp b/common/lanelet2_extension/lib/visualization.cpp index 35511961aba..ecea92f5330 100644 --- a/common/lanelet2_extension/lib/visualization.cpp +++ b/common/lanelet2_extension/lib/visualization.cpp @@ -222,6 +222,24 @@ void laneletDirectionAsMarker(const lanelet::ConstLanelet ll, visualization_msgs ci = ci + 1; } } + +bool isReflexAngle(const geometry_msgs::Point32& a, const geometry_msgs::Point32& o, const geometry_msgs::Point32& b) +{ + // angle aob is reflex in counterclock wise direction if point b is on the right side of vector oa + // which can be found out by calculating cross product of oa and ob + return (a.x - o.x) * (b.y - o.y) - (a.y - o.y) * (b.x - o.x) < 0; +} + +bool isWithinTriangle(const geometry_msgs::Point32& a, const geometry_msgs::Point32& b, const geometry_msgs::Point32& c, + const geometry_msgs::Point32& p) +{ + // point p in within triangle if p is on the same side + const double side1 = (b.x - a.x) * (p.y - a.y) - (b.y - a.y) * (p.x - a.x); // a to b + const double side2 = (c.x - b.x) * (p.y - b.y) - (c.y - b.y) * (p.x - b.x); // b to c + const double side3 = (a.x - c.x) * (p.y - c.y) - (a.y - c.y) * (p.x - c.x); // c to a + return (side1 > 0.0 && side2 > 0.0 && side3 > 0.0) || (side1 < 0.0 && side2 < 0.0 && side3 < 0.0); +} + } // anonymous namespace namespace lanelet @@ -237,59 +255,96 @@ void visualization::lanelet2Triangle(const lanelet::ConstLanelet& ll, std::vecto triangles->clear(); geometry_msgs::Polygon ll_poly; lanelet2Polygon(ll, &ll_poly); + polygon2Triangle(ll_poly, triangles); +} +void visualization::polygon2Triangle(const geometry_msgs::Polygon& polygon, + std::vector* triangles) +{ + geometry_msgs::Polygon poly = polygon; // ear clipping: find smallest internal angle in polygon - int N = ll_poly.points.size(); + int N = poly.points.size(); + + // array of angles for each vertex + std::vector is_reflex_angle; + is_reflex_angle.assign(N, false); + for (int i = 0; i < N; i++) + { + geometry_msgs::Point32 p0, p1, p2; + + adjacentPoints(i, N, poly, &p0, &p1, &p2); + is_reflex_angle.at(i) = isReflexAngle(p0, p1, p2); + } + // start ear clipping while (N >= 3) { - double min_angle = 2 * M_PI; - int min_i = -1; + int clipped_vertex = -1; for (int i = 0; i < N; i++) { - geometry_msgs::Point32 p0, p1, p2; - - adjacentPoints(i, N, ll_poly, &p0, &p1, &p2); - - // angle at vertex i formed by p0, p1, p2 - double a = hypot(p0, p1); - double b = hypot(p1, p2); - double c = hypot(p0, p2); - double theta = acos((a * a + b * b - c * c) / (2.0 * a * b)); - - // get explementary angle for superior angles - geometry_msgs::Point p64_0, p64_1, p64_2; - utils::conversion::toGeomMsgPt(p0, &p64_0); - utils::conversion::toGeomMsgPt(p1, &p64_1); - utils::conversion::toGeomMsgPt(p2, &p64_2); - if (amathutils::isPointLeftFromLine(p64_2, p64_0, p64_1) > 0) + bool is_reflex = is_reflex_angle.at(i); + if (!is_reflex) { - theta = 2 * M_PI - theta; - } + geometry_msgs::Point32 p0, p1, p2; + adjacentPoints(i, N, poly, &p0, &p1, &p2); - if (theta < min_angle) - { - min_angle = theta; - min_i = i; + int j_begin = (i + 2) % N; + int j_end = (i - 1 + N) % N; + bool is_ear = true; + for (int j = j_begin; j != j_end; j = (j + 1) % N) + { + if (isWithinTriangle(p0, p1, p2, poly.points.at(j))) + { + is_ear = false; + break; + } + } + + if (is_ear) + { + clipped_vertex = i; + break; + } } } - if (min_i >= 0 && min_i < N) + if (clipped_vertex < 0 || clipped_vertex >= N) + { + ROS_ERROR("Could not find valid vertex for ear clipping triangulation. Triangulation result might be invalid"); + clipped_vertex = 0; + } + + // create triangle + geometry_msgs::Point32 p0, p1, p2; + adjacentPoints(clipped_vertex, N, poly, &p0, &p1, &p2); + geometry_msgs::Polygon triangle; + triangle.points.push_back(p0); + triangle.points.push_back(p1); + triangle.points.push_back(p2); + triangles->push_back(triangle); + + // remove vertex of center of angle + auto it = poly.points.begin(); + std::advance(it, clipped_vertex); + poly.points.erase(it); + + // remove from angle list + auto it_angle = is_reflex_angle.begin(); + std::advance(it_angle, clipped_vertex); + is_reflex_angle.erase(it_angle); + + // update angle list + N = poly.points.size(); + if (clipped_vertex == N) { - geometry_msgs::Point32 p0, p1, p2; - adjacentPoints(min_i, N, ll_poly, &p0, &p1, &p2); - geometry_msgs::Polygon triangle; - triangle.points.push_back(p0); - triangle.points.push_back(p1); - triangle.points.push_back(p2); - triangles->push_back(triangle); - - // remove vertex of center of angle - auto it = ll_poly.points.begin(); - std::advance(it, min_i); - ll_poly.points.erase(it); + clipped_vertex = 0; } - N = ll_poly.points.size(); + adjacentPoints(clipped_vertex, N, poly, &p0, &p1, &p2); + is_reflex_angle.at(clipped_vertex) = isReflexAngle(p0, p1, p2); + + int i_prev = (clipped_vertex == 0) ? N - 1 : clipped_vertex - 1; + adjacentPoints(i_prev, N, poly, &p0, &p1, &p2); + is_reflex_angle.at(i_prev) = isReflexAngle(p0, p1, p2); } } diff --git a/common/lanelet2_extension/test/src/test_query.cpp b/common/lanelet2_extension/test/src/test_query.cpp index 0d98bc12de1..e257aa370f4 100644 --- a/common/lanelet2_extension/test/src/test_query.cpp +++ b/common/lanelet2_extension/test/src/test_query.cpp @@ -239,10 +239,10 @@ TEST_F(TestSuite, QueryStopLine) lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(sample_map_ptr); lanelet::ConstLanelets road_lanelets = lanelet::utils::query::roadLanelets(all_lanelets); - auto stop_lines = lanelet::utils::query::stopLinesLanelets(all_lanelets); + auto stop_lines = lanelet::utils::query::getTrafficLightStopLines(all_lanelets); ASSERT_EQ(1, stop_lines.size()) << "failed to retrieve stop lines from all lanelets"; - auto stop_lines2 = lanelet::utils::query::stopLinesLanelet(road_lanelets.back()); + auto stop_lines2 = lanelet::utils::query::getTrafficLightStopLines(road_lanelets.front()); ASSERT_EQ(1, stop_lines2.size()) << "failed to retrieve stop lines from a lanelet"; } diff --git a/common/libvectormap/CMakeLists.txt b/common/libvectormap/CMakeLists.txt index 6905972800d..f2bfe7735d8 100644 --- a/common/libvectormap/CMakeLists.txt +++ b/common/libvectormap/CMakeLists.txt @@ -5,6 +5,7 @@ project(libvectormap) find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS + roslint vector_map vector_map_msgs ) @@ -65,3 +66,10 @@ install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} PATTERN ".svn" EXCLUDE ) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++14,-runtime/references") +roslint_cpp() + +if(CATKIN_ENABLE_TESTING) + roslint_add_test() +endif() diff --git a/common/libvectormap/include/libvectormap/Math.h b/common/libvectormap/include/libvectormap/Math.h index f3defcd0f69..dc477064b34 100644 --- a/common/libvectormap/include/libvectormap/Math.h +++ b/common/libvectormap/include/libvectormap/Math.h @@ -1,16 +1,27 @@ /* - * Math.h + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. * * Created on: Apr 8, 2015 * Author: sujiwo */ -#ifndef SRC_MATH_H_ -#define SRC_MATH_H_ +#ifndef LIBVECTORMAP_MATH_H +#define LIBVECTORMAP_MATH_H #include -#include - +#include typedef Eigen::Vector2f Point2; typedef Eigen::Vector3f Point3; @@ -22,57 +33,57 @@ typedef Eigen::Quaternionf Quaternion; typedef Eigen::Matrix4f Matrix4; typedef Eigen::Matrix2f Matrix2; - -template static F degreeToRadian (const F degree) -{ return degree * M_PI / 180; } - -template static F radianToDegree (const F radian) -{ return radian * 180 / M_PI; } - - -inline double distance (const Point2 &p1, const Point2 &p2) +template +static F degreeToRadian(const F degree) { - Vector2 p3 (p2.x()-p1.x(), p2.y()-p1.y()); - return sqrt (p3.squaredNorm()); + return degree * M_PI / 180; } - -inline double distance (const Point3 &p1, const Point3 &p2) +template +static F radianToDegree(const F radian) { - Vector3 p3 (p2.x()-p1.x(), p2.y()-p1.y(), p2.z()-p1.z()); - return sqrt(p3.squaredNorm()); + return radian * 180 / M_PI; } - -inline double distance (const Point4 &p1, const Point4 &p2) +inline double distance(const Point2 &p1, const Point2 &p2) { - Vector4 p3 (p2.x()-p1.x(), p2.y()-p1.y(), p2.z()-p1.z(), p2.w()-p1.w()); - return sqrt(p3.squaredNorm()); + Vector2 p3(p2.x()-p1.x(), p2.y()-p1.y()); + return sqrt (p3.squaredNorm()); } - -inline double distance (const double &x1, const double &y1, const double &x2, const double &y2) +inline double distance(const Point3 &p1, const Point3 &p2) { - Point2 p(x1, y1), q(x2, y2); - return distance (p, q); + Vector3 p3(p2.x()-p1.x(), p2.y()-p1.y(), p2.z()-p1.z()); + return sqrt(p3.squaredNorm()); } +inline double distance(const Point4 &p1, const Point4 &p2) +{ + Vector4 p3(p2.x() - p1.x(), p2.y() - p1.y(), p2.z() - p1.z(), p2.w() - p1.w()); + return std::sqrt(p3.squaredNorm()); +} -inline Vector2 perpendicular (const Vector2 &v) -{ return Vector2 (-v.y(), v.x()); } - +inline double distance(const double &x1, const double &y1, const double &x2, const double &y2) +{ + Point2 p(x1, y1), q(x2, y2); + return distance (p, q); +} -inline void rotate (Vector2 &v, const float angleInDegree) +inline Vector2 perpendicular(const Vector2 &v) { - Matrix2 rot; - double c = cos (degreeToRadian(angleInDegree)), - s = sin (degreeToRadian(angleInDegree)); - rot (0, 0) = c; - rot (0, 1) = -s; - rot (1, 0) = s; - rot (1, 1) = c; - v = rot * v; + return Vector2(-v.y(), v.x()); } +inline void rotate(Vector2 &v, const float angleInDegree) +{ + Matrix2 rot; + double c = std::cos(degreeToRadian(angleInDegree)), + s = std::sin(degreeToRadian(angleInDegree)); + rot(0, 0) = c; + rot(0, 1) = -s; + rot(1, 0) = s; + rot(1, 1) = c; + v = rot * v; +} -#endif /* SRC_MATH_H_ */ +#endif // LIBVECTORMAP_MATH_H diff --git a/common/libvectormap/include/libvectormap/vector_map.h b/common/libvectormap/include/libvectormap/vector_map.h index a84a7628e6f..57cb3a958b7 100644 --- a/common/libvectormap/include/libvectormap/vector_map.h +++ b/common/libvectormap/include/libvectormap/vector_map.h @@ -1,20 +1,35 @@ -#ifndef __VECTOR_MAP__ -#define __VECTOR_MAP__ - -//#include "ros/ros.h" -//#include "std_msgs/String.h" -#include -#include -#include +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef LIBVECTORMAP_VECTOR_MAP_H +#define LIBVECTORMAP_VECTOR_MAP_H + +#include +#include +#include #include #include #include + #include "Math.h" #include - -typedef struct{ +typedef struct +{ int pid; double bx; double ly; @@ -25,46 +40,57 @@ typedef struct{ int mcode1; int mcode2; int mcode3; -}Point; +} +Point; -typedef struct{ +typedef struct +{ int lid; int bpid; int fpid; int blid; int flid; -}Line; +} +Line; -typedef struct{ +typedef struct +{ int vid; int pid; double hang; double vang; -}Vector; - +} +Vector; -typedef struct{ +typedef struct +{ int id; int vid; int plid; int type; int linkid; -}Signal; +} +Signal; -typedef struct{ +typedef struct +{ int id; int lid; double width; char color; int type; int linkid; -}WhiteLine; +} +WhiteLine; -typedef struct{ +typedef struct +{ int lid; -}Mark; +} +Mark; -typedef struct{ +typedef struct +{ int did; double dist; int pid; @@ -75,9 +101,11 @@ typedef struct{ double cant; double lw; double rw; -}DTLane; +} +DTLane; -typedef struct{ +typedef struct +{ int lnid; int did; int blid; @@ -95,20 +123,20 @@ typedef struct{ double span; int lcnt; int lno; -}Lane; - +} +Lane; class VectorMap { - public: +public: bool loaded; - std::map points; - std::map lines; - std::map whitelines; - std::map lanes; - std::map dtlanes; - std::map vectors; - std::map signals; + std::map points; + std::map lines; + std::map whitelines; + std::map lanes; + std::map dtlanes; + std::map vectors; + std::map signals; void load_points(const vector_map::PointArray& msg); void load_lines(const vector_map::LineArray& msg); @@ -118,18 +146,18 @@ class VectorMap void load_whitelines(const vector_map::WhiteLineArray& msg); void load_dtlanes(const vector_map::DTLaneArray& msg); + VectorMap() : + loaded(false) {} - VectorMap () : - loaded(false) {} - - inline Point3 getPoint (const int idx) + inline Point3 getPoint(const int idx) { - Point3 p; - Point psrc = points[idx]; - p.x() = psrc.bx; p.y() = psrc.ly, p.z() = psrc.h; - return p; + Point3 p; + Point psrc = points[idx]; + p.x() = psrc.bx; + p.y() = psrc.ly; + p.z() = psrc.h; + return p; } - }; -#endif +#endif // LIBVECTORMAP_VECTOR_MAP_H diff --git a/common/libvectormap/package.xml b/common/libvectormap/package.xml index 968f90a511d..b4a1d9fcf21 100644 --- a/common/libvectormap/package.xml +++ b/common/libvectormap/package.xml @@ -11,6 +11,7 @@ cmake_modules eigen + roslint vector_map vector_map_msgs diff --git a/common/libvectormap/src/vector_map.cpp b/common/libvectormap/src/vector_map.cpp index 02202cd9e0b..9f6dfaa41c2 100644 --- a/common/libvectormap/src/vector_map.cpp +++ b/common/libvectormap/src/vector_map.cpp @@ -1,146 +1,163 @@ -#include -#include -#include +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + #include "libvectormap/vector_map.h" + +#include +#include +#include #include #include void VectorMap::load_points(const vector_map::PointArray& msg) { for (const auto& point : msg.data) - { - Point tmp; - tmp.pid = point.pid; - tmp.b = point.b; - tmp.l = point.l; - tmp.h = point.h; - tmp.bx = point.ly; - tmp.ly = point.bx; - tmp.ref = point.ref; - tmp.mcode1 = point.mcode1; - tmp.mcode2 = point.mcode2; - tmp.mcode3 = point.mcode3; - points.insert( std::map::value_type(tmp.pid, tmp) ); - } + { + Point tmp; + tmp.pid = point.pid; + tmp.b = point.b; + tmp.l = point.l; + tmp.h = point.h; + tmp.bx = point.ly; + tmp.ly = point.bx; + tmp.ref = point.ref; + tmp.mcode1 = point.mcode1; + tmp.mcode2 = point.mcode2; + tmp.mcode3 = point.mcode3; + points.insert(std::map::value_type(tmp.pid, tmp)); + } + std::cout << "load points complete. element num: " << points.size() << std::endl; } /* void VectorMap::load_points() */ - void VectorMap::load_lines(const vector_map::LineArray& msg) { for (const auto& line : msg.data) - { - Line tmp; - tmp.lid = line.lid; - tmp.bpid = line.bpid; - tmp.fpid = line.fpid; - tmp.blid = line.blid; - tmp.flid = line.flid; - - lines.insert( std::map::value_type(tmp.lid, tmp) ); - } + { + Line tmp; + tmp.lid = line.lid; + tmp.bpid = line.bpid; + tmp.fpid = line.fpid; + tmp.blid = line.blid; + tmp.flid = line.flid; + + lines.insert(std::map::value_type(tmp.lid, tmp)); + } + std::cout << "load lines complete." << std::endl; } /* void VectorMap::load_lines() */ - void VectorMap::load_lanes(const vector_map::LaneArray& msg) { for (const auto& lane : msg.data) - { - Lane tmp; - tmp.lnid = lane.lnid; - tmp.did = lane.did; - tmp.blid = lane.blid; - tmp.flid = lane.flid; - tmp.bnid = lane.bnid; - tmp.fnid = lane.fnid; - tmp.jct = lane.jct; - tmp.blid2 = lane.blid2; - tmp.blid3 = lane.blid3; - tmp.blid4 = lane.blid4; - tmp.flid2 = lane.flid2; - tmp.flid3 = lane.flid3; - tmp.flid4 = lane.flid4; - tmp.clossid = lane.clossid; - tmp.span = lane.span; - tmp.lcnt = lane.lcnt; - tmp.lno = lane.lno; - - lanes.insert( std::map::value_type(tmp.lnid, tmp) ); - } + { + Lane tmp; + tmp.lnid = lane.lnid; + tmp.did = lane.did; + tmp.blid = lane.blid; + tmp.flid = lane.flid; + tmp.bnid = lane.bnid; + tmp.fnid = lane.fnid; + tmp.jct = lane.jct; + tmp.blid2 = lane.blid2; + tmp.blid3 = lane.blid3; + tmp.blid4 = lane.blid4; + tmp.flid2 = lane.flid2; + tmp.flid3 = lane.flid3; + tmp.flid4 = lane.flid4; + tmp.clossid = lane.clossid; + tmp.span = lane.span; + tmp.lcnt = lane.lcnt; + tmp.lno = lane.lno; + + lanes.insert(std::map::value_type(tmp.lnid, tmp)); + } + std::cout << "load lanes complete." << std::endl; } /* void VectorMap::load_lanes() */ - void VectorMap::load_vectors(const vector_map::VectorArray& msg) { for (const auto& vector : msg.data) - { - Vector tmp; - tmp.vid = vector.vid; - tmp.pid = vector.pid; - tmp.hang = vector.hang; - tmp.vang = vector.vang; - - vectors.insert( std::map::value_type(tmp.vid, tmp) ); - } + { + Vector tmp; + tmp.vid = vector.vid; + tmp.pid = vector.pid; + tmp.hang = vector.hang; + tmp.vang = vector.vang; + + vectors.insert(std::map::value_type(tmp.vid, tmp)); + } + std::cout << "load vectors complete. element num: " << vectors.size() << std::endl; } /* void VectorMap::load_vectors() */ - void VectorMap::load_signals(const vector_map::SignalArray& msg) { for (const auto& signal : msg.data) - { - Signal tmp; - tmp.id = signal.id; - tmp.vid = signal.vid; - tmp.plid = signal.plid; - tmp.type = signal.type; - tmp.linkid = signal.linkid; - - signals.insert( std::map::value_type(tmp.id, tmp) ); - } + { + Signal tmp; + tmp.id = signal.id; + tmp.vid = signal.vid; + tmp.plid = signal.plid; + tmp.type = signal.type; + tmp.linkid = signal.linkid; + + signals.insert(std::map::value_type(tmp.id, tmp)); + } + std::cout << "load signals complete. element num: " << signals.size() << std::endl; } /* void VectorMap::load_signals() */ - void VectorMap::load_whitelines(const vector_map::WhiteLineArray& msg) { for (const auto& white_line : msg.data) - { - WhiteLine tmp; - tmp.id = white_line.id; - tmp.lid = white_line.lid; - tmp.width = white_line.width; - tmp.color = white_line.color; - tmp.type = white_line.type; - tmp.linkid = white_line.linkid; - - whitelines.insert( std::map::value_type(tmp.id, tmp) ); - } + { + WhiteLine tmp; + tmp.id = white_line.id; + tmp.lid = white_line.lid; + tmp.width = white_line.width; + tmp.color = white_line.color; + tmp.type = white_line.type; + tmp.linkid = white_line.linkid; + + whitelines.insert(std::map::value_type(tmp.id, tmp)); + } + std::cout << "load whitelines complete." << std::endl; } /* void VectorMap::load_whitelines() */ - void VectorMap::load_dtlanes(const vector_map::DTLaneArray& msg) { for (const auto& dtlane : msg.data) - { - DTLane tmp; - tmp.did = dtlane.did; - tmp.dist = dtlane.dist; - tmp.pid = dtlane.pid; - tmp.dir = dtlane.dir; - tmp.apara = dtlane.apara; - tmp.r = dtlane.r; - tmp.slope = dtlane.slope; - tmp.cant = dtlane.cant; - tmp.lw = dtlane.lw; - tmp.rw = dtlane.rw; - - dtlanes.insert( std::map::value_type(tmp.did, tmp) ); - } + { + DTLane tmp; + tmp.did = dtlane.did; + tmp.dist = dtlane.dist; + tmp.pid = dtlane.pid; + tmp.dir = dtlane.dir; + tmp.apara = dtlane.apara; + tmp.r = dtlane.r; + tmp.slope = dtlane.slope; + tmp.cant = dtlane.cant; + tmp.lw = dtlane.lw; + tmp.rw = dtlane.rw; + + dtlanes.insert(std::map::value_type(tmp.did, tmp)); + } + std::cout << "load dtlanes complete." << std::endl; } /* void VectorMap::load_dtlanes() */ - diff --git a/common/libwaypoint_follower/CMakeLists.txt b/common/libwaypoint_follower/CMakeLists.txt index 16b0d866976..89a6c1c0e24 100644 --- a/common/libwaypoint_follower/CMakeLists.txt +++ b/common/libwaypoint_follower/CMakeLists.txt @@ -4,64 +4,91 @@ project(libwaypoint_follower) find_package(autoware_build_flags) find_package(catkin REQUIRED COMPONENTS - roscpp - std_msgs - geometry_msgs - autoware_msgs - rosunit + amathutils_lib + autoware_msgs + geometry_msgs + roscpp + roslint + rosunit + std_msgs ) -################################################ -## Declare ROS messages, services and actions ## -################################################ +find_package(Eigen3 QUIET) + +if (NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else () + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif () -################################### -## catkin specific configuration ## -################################### catkin_package( - INCLUDE_DIRS include - LIBRARIES libwaypoint_follower - CATKIN_DEPENDS - std_msgs - geometry_msgs - autoware_msgs + INCLUDE_DIRS include + LIBRARIES libwaypoint_follower + CATKIN_DEPENDS + amathutils_lib + autoware_msgs + geometry_msgs + std_msgs ) -########### -## Build ## -########### - SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") include_directories(libwaypoint_follower - include - ${catkin_INCLUDE_DIRS} + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} ) -add_library(libwaypoint_follower src/libwaypoint_follower.cpp) +add_library(libwaypoint_follower src/libwaypoint_follower.cpp + src/pure_pursuit.cpp) add_dependencies(libwaypoint_follower ${catkin_EXPORTED_TARGETS}) target_link_libraries(libwaypoint_follower ${catkin_LIBRARIES}) - ## Install executables and/or libraries install(TARGETS libwaypoint_follower - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) ## Install project namespaced headers install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +file(GLOB_RECURSE ROSLINT_FILES + LIST_DIRECTORIES false + *.cpp *.h *.hpp +) +list(APPEND ROSLINT_CPP_OPTS "--extensions=cc,h,hpp,cpp,cu,cuh" "--filter=-build/c++11,-runtime/references") +roslint_cpp(${ROSLINT_FILES}) if (CATKIN_ENABLE_TESTING) - find_package(rostest REQUIRED) - add_rostest_gtest(test-libwaypoint_follower - test/test_libwaypoint_follower.test - test/src/test_libwaypoint_follower.cpp - src/libwaypoint_follower.cpp - ) - add_dependencies(test-libwaypoint_follower ${catkin_EXPORTED_TARGETS}) - target_link_libraries(test-libwaypoint_follower - ${catkin_LIBRARIES}) + find_package(rostest REQUIRED) + add_rostest_gtest(test-libwaypoint_follower + test/test_libwaypoint_follower.test + test/src/test_libwaypoint_follower.cpp + src/libwaypoint_follower.cpp + ) + add_dependencies(test-libwaypoint_follower ${catkin_EXPORTED_TARGETS}) + target_link_libraries(test-libwaypoint_follower + ${catkin_LIBRARIES} + ) + add_rostest_gtest(test-pure_pursuit + test/test_pure_pursuit.test + test/src/test_pure_pursuit.cpp + src/libwaypoint_follower.cpp + src/pure_pursuit.cpp + ) + add_dependencies(test-pure_pursuit ${catkin_EXPORTED_TARGETS}) + target_link_libraries(test-pure_pursuit + ${catkin_LIBRARIES} + ) + roslint_add_test() endif () diff --git a/common/libwaypoint_follower/include/libwaypoint_follower/libwaypoint_follower.h b/common/libwaypoint_follower/include/libwaypoint_follower/libwaypoint_follower.h index 0d7eaf5c54d..6950abdbbc5 100644 --- a/common/libwaypoint_follower/include/libwaypoint_follower/libwaypoint_follower.h +++ b/common/libwaypoint_follower/include/libwaypoint_follower/libwaypoint_follower.h @@ -14,18 +14,26 @@ * limitations under the License. */ -#ifndef _LIB_WAYPOINT_FOLLOWER_H_ -#define _LIB_WAYPOINT_FOLLOWER_H_ +#ifndef LIBWAYPOINT_FOLLOWER_LIBWAYPOINT_FOLLOWER_H +#define LIBWAYPOINT_FOLLOWER_LIBWAYPOINT_FOLLOWER_H + +#define EIGEN_MPL2_ONLY +#include +#include // C++ header #include #include #include +#include +#include // ROS header #include #include -#include "autoware_msgs/Lane.h" +#include + +constexpr double ERROR = 1e-6; enum class LaneDirection : int { @@ -70,10 +78,6 @@ inline double mps2kmph(double velocity_mps) { return (velocity_mps * 60 * 60) / 1000; } -inline double deg2rad(double deg) -{ - return deg * M_PI / 180; -} // convert degree to radian tf::Vector3 point2vector(geometry_msgs::Point point); // convert point to vector geometry_msgs::Point vector2point(tf::Vector3 vector); // convert vector to point @@ -96,4 +100,27 @@ int getClosestWaypoint(const autoware_msgs::Lane& current_path, geometry_msgs::P bool getLinearEquation(geometry_msgs::Point start, geometry_msgs::Point end, double* a, double* b, double* c); double getDistanceBetweenLineAndPoint(geometry_msgs::Point point, double sa, double b, double c); double getRelativeAngle(geometry_msgs::Pose waypoint_pose, geometry_msgs::Pose vehicle_pose); -#endif +double calcCurvature(const geometry_msgs::Point &target, const geometry_msgs::Pose &curr_pose); +double calcDistSquared2D(const geometry_msgs::Point &p, const geometry_msgs::Point &q); +double calcLateralError2D(const geometry_msgs::Point &a_start, const geometry_msgs::Point &a_end, + const geometry_msgs::Point &b); +double calcRadius(const geometry_msgs::Point &target, const geometry_msgs::Pose ¤t_pose); +std::vector extractPoses(const autoware_msgs::Lane &lane); +std::vector extractPoses(const std::vector &wps); +std::pair findClosestIdxWithDistAngThr(const std::vector &curr_ps, + const geometry_msgs::Pose &curr_pose, + double dist_thr = 3.0, + double angle_thr = M_PI_2); +geometry_msgs::Quaternion getQuaternionFromYaw(const double &_yaw); +bool isDirectionForward(const std::vector &poses); +double normalizeEulerAngle(double euler); +geometry_msgs::Point transformToAbsoluteCoordinate2D(const geometry_msgs::Point &point, + const geometry_msgs::Pose ¤t_pose); +geometry_msgs::Point transformToAbsoluteCoordinate3D(const geometry_msgs::Point &point, + const geometry_msgs::Pose &origin); +geometry_msgs::Point transformToRelativeCoordinate2D(const geometry_msgs::Point &point, + const geometry_msgs::Pose ¤t_pose); +geometry_msgs::Point transformToRelativeCoordinate3D(const geometry_msgs::Point &point, + const geometry_msgs::Pose ¤t_pose); + +#endif // LIBWAYPOINT_FOLLOWER_LIBWAYPOINT_FOLLOWER_H diff --git a/common/libwaypoint_follower/include/libwaypoint_follower/pure_pursuit.h b/common/libwaypoint_follower/include/libwaypoint_follower/pure_pursuit.h new file mode 100644 index 00000000000..1276c7319b5 --- /dev/null +++ b/common/libwaypoint_follower/include/libwaypoint_follower/pure_pursuit.h @@ -0,0 +1,65 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef LIBWAYPOINT_FOLLOWER_PURE_PURSUIT_H +#define LIBWAYPOINT_FOLLOWER_PURE_PURSUIT_H + +#define EIGEN_MPL2_ONLY + +// ROS includes +#include + +// C++ includes +#include +#include +#include + +class PurePursuit +{ +public: + PurePursuit() : use_lerp_(false), lookahead_distance_(0.0), clst_thr_dist_(3.0), clst_thr_ang_(M_PI/4) {} + + // setter + void setUseLerp(bool ul); + void setCurrentPose(const geometry_msgs::Pose &msg); + void setWaypoints(const std::vector &msg); + void setLookaheadDistance(double ld); + void setClosestThreshold(double clst_thr_dist, double clst_thr_ang); + + // getter + geometry_msgs::Point getLocationOfNextWaypoint(); + geometry_msgs::Point getLocationOfNextTarget(); + + bool isRequirementsSatisfied(); + std::pair run(); // calculate curvature + +private: + // variables for debug + geometry_msgs::Point loc_next_wp_; + geometry_msgs::Point loc_next_tgt_; + + // variables got from outside + bool use_lerp_; + double lookahead_distance_, clst_thr_dist_, clst_thr_ang_; + std::shared_ptr> curr_wps_ptr_; + std::shared_ptr curr_pose_ptr_; + + // functions + int32_t findNextPointIdx(int32_t search_start_idx); + std::pair lerpNextTarget(int32_t next_wp_idx); +}; + +#endif // LIBWAYPOINT_FOLLOWER_PURE_PURSUIT_H diff --git a/common/libwaypoint_follower/test/src/test_libwaypoint_follower.hpp b/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h similarity index 82% rename from common/libwaypoint_follower/test/src/test_libwaypoint_follower.hpp rename to common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h index 812b19bd22e..bd2e4be3f21 100644 --- a/common/libwaypoint_follower/test/src/test_libwaypoint_follower.hpp +++ b/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h @@ -14,6 +14,9 @@ * limitations under the License. */ +#ifndef LIBWAYPOINT_FOLLOWER_TEST_LIBWAYPOINT_FOLLOWER_H +#define LIBWAYPOINT_FOLLOWER_TEST_LIBWAYPOINT_FOLLOWER_H + #include #include "libwaypoint_follower/libwaypoint_follower.h" @@ -28,9 +31,10 @@ struct DirectionCheckDataSet { int idx; double vel; - DirectionCheckDataSet(int i, double v) : idx(i), vel(v){} - DirectionCheckDataSet(){} - ~DirectionCheckDataSet(){} + DirectionCheckDataSet(int i, double v) : + idx(i), vel(v) + {} + DirectionCheckDataSet() {} }; struct ClosestCheckDataSet @@ -41,12 +45,12 @@ struct ClosestCheckDataSet int num; geometry_msgs::PoseStamped pose; ClosestCheckDataSet(int d, double v, double o, int n, const geometry_msgs::PoseStamped& p) - : dir(d), vel(v), offset(o), num(n), pose(p){} - ClosestCheckDataSet(){} - ~ClosestCheckDataSet(){} + : dir(d), vel(v), offset(o), num(n), pose(p) {} + ClosestCheckDataSet() {} }; -class LibWaypointFollowerTestClass { +class LibWaypointFollowerTestClass +{ public: LibWaypointFollowerTestClass() {} autoware_msgs::Lane generateLane(int driving_direction, double velocity) @@ -62,7 +66,7 @@ class LibWaypointFollowerTestClass { static autoware_msgs::Waypoint wp; wp.gid = idx; wp.lid = idx; - wp.pose.pose.position.x = driving_direction * ((double)idx + offset); + wp.pose.pose.position.x = driving_direction * (static_cast(idx) + offset); wp.pose.pose.position.y = 0.0; wp.pose.pose.position.z = 0.0; wp.twist.twist.linear.x = velocity; @@ -75,6 +79,7 @@ class LibWaypointFollowerTestClass { } return std::move(lane); } + geometry_msgs::PoseStamped generateCurrentPose(double x, double y, double yaw) { geometry_msgs::PoseStamped pose; @@ -85,3 +90,5 @@ class LibWaypointFollowerTestClass { return std::move(pose); } }; + +#endif // LIBWAYPOINT_FOLLOWER_TEST_LIBWAYPOINT_FOLLOWER_H diff --git a/common/libwaypoint_follower/package.xml b/common/libwaypoint_follower/package.xml index 8c2609661b0..e826881f78a 100644 --- a/common/libwaypoint_follower/package.xml +++ b/common/libwaypoint_follower/package.xml @@ -14,6 +14,8 @@ autoware_msgs geometry_msgs roscpp + roslint rosunit std_msgs + eigen diff --git a/common/libwaypoint_follower/src/libwaypoint_follower.cpp b/common/libwaypoint_follower/src/libwaypoint_follower.cpp index c9e0d2e11cf..78483a14b29 100644 --- a/common/libwaypoint_follower/src/libwaypoint_follower.cpp +++ b/common/libwaypoint_follower/src/libwaypoint_follower.cpp @@ -14,8 +14,20 @@ * limitations under the License. */ +#include +#include +#include +#include + +#include +#include +#include +#include + #include "libwaypoint_follower/libwaypoint_follower.h" +using amathutils::deg2rad; + int WayPoints::getSize() const { if (current_waypoints_.waypoints.empty()) @@ -86,7 +98,7 @@ bool WayPoints::inDrivingDirection(int waypoint, geometry_msgs::Pose current_pos double DecelerateVelocity(double distance, double prev_velocity) { double decel_ms = 1.0; // m/s - double decel_velocity_ms = sqrt(2 * decel_ms * distance); + double decel_velocity_ms = std::sqrt(2 * decel_ms * distance); std::cout << "velocity/prev_velocity :" << decel_velocity_ms << "/" << prev_velocity << std::endl; if (decel_velocity_ms < prev_velocity) @@ -150,7 +162,6 @@ double getRelativeAngle(geometry_msgs::Pose waypoint_pose, geometry_msgs::Pose v relative_waypoint_v.normalize(); tf::Vector3 relative_pose_v(1, 0, 0); double angle = relative_pose_v.angle(relative_waypoint_v) * 180 / M_PI; - // ROS_INFO("angle : %lf",angle); return angle; } @@ -171,12 +182,12 @@ LaneDirection getLaneDirectionByPosition(const autoware_msgs::Lane& current_path return LaneDirection::Error; } LaneDirection positional_direction = LaneDirection::Error; - for (int i = 1; i < current_path.waypoints.size(); i++) + for (size_t i = 1; i < current_path.waypoints.size(); i++) { const geometry_msgs::Pose& prev_pose = current_path.waypoints[i - 1].pose.pose; const geometry_msgs::Pose& next_pose = current_path.waypoints[i].pose.pose; const double rlt_x = calcRelativeCoordinate(next_pose.position, prev_pose).x; - if (fabs(rlt_x) < 1e-3) + if (std::fabs(rlt_x) < 1e-3) { continue; } @@ -192,7 +203,7 @@ LaneDirection getLaneDirectionByVelocity(const autoware_msgs::Lane& current_path for (const auto waypoint : current_path.waypoints) { const double& vel = waypoint.twist.twist.linear.x; - if (fabs(vel) < 0.01) + if (std::fabs(vel) < 0.01) { continue; } @@ -208,7 +219,7 @@ class MinIDSearch double val_min_; int idx_min_; public: - MinIDSearch() : idx_min_(-1), val_min_(DBL_MAX){} + MinIDSearch() : val_min_(DBL_MAX), idx_min_(-1) {} void update(int index, double v) { if (v < val_min_) @@ -217,7 +228,7 @@ class MinIDSearch val_min_ = v; } } - const double result() const + const int result() const { return idx_min_; } @@ -231,7 +242,9 @@ class MinIDSearch int getClosestWaypoint(const autoware_msgs::Lane ¤t_path, geometry_msgs::Pose current_pose) { if (current_path.waypoints.size() < 2 || getLaneDirection(current_path) == LaneDirection::Error) + { return -1; + } WayPoints wp; wp.setPath(current_path); @@ -240,7 +253,7 @@ int getClosestWaypoint(const autoware_msgs::Lane ¤t_path, geometry_msgs::P double search_distance = 5.0; double angle_threshold = 90; MinIDSearch cand_idx, not_cand_idx; - for (int i = 1; i < wp.getSize(); i++) + for (int i = 0; i < wp.getSize(); i++) { if (!wp.inDrivingDirection(i, current_pose)) continue; @@ -252,10 +265,6 @@ int getClosestWaypoint(const autoware_msgs::Lane ¤t_path, geometry_msgs::P continue; cand_idx.update(i, distance); } - if (!cand_idx.isOK()) - { - ROS_INFO("no candidate. search closest waypoint from all waypoints..."); - } return (!cand_idx.isOK()) ? not_cand_idx.result() : cand_idx.result(); } @@ -263,14 +272,13 @@ int getClosestWaypoint(const autoware_msgs::Lane ¤t_path, geometry_msgs::P // if there are two points (x1,y1) , (x2,y2), a = "y2-y1, b = "(-1) * x2 - x1" ,c = "(-1) * (y2-y1)x1 + (x2-x1)y1" bool getLinearEquation(geometry_msgs::Point start, geometry_msgs::Point end, double *a, double *b, double *c) { - //(x1, y1) = (start.x, star.y), (x2, y2) = (end.x, end.y) - double sub_x = fabs(start.x - end.x); - double sub_y = fabs(start.y - end.y); - double error = pow(10, -5); // 0.00001 + // (x1, y1) = (start.x, star.y), (x2, y2) = (end.x, end.y) + double sub_x = std::fabs(start.x - end.x); + double sub_y = std::fabs(start.y - end.y); + double error = std::pow(10, -5); // 0.00001 if (sub_x < error && sub_y < error) { - ROS_INFO("two points are the same point!!"); return false; } @@ -282,7 +290,7 @@ bool getLinearEquation(geometry_msgs::Point start, geometry_msgs::Point end, dou } double getDistanceBetweenLineAndPoint(geometry_msgs::Point point, double a, double b, double c) { - double d = fabs(a * point.x + b * point.y + c) / sqrt(pow(a, 2) + pow(b, 2)); + double d = std::fabs(a * point.x + b * point.y + c) / std::sqrt(std::pow(a, 2) + std::pow(b, 2)); return d; } @@ -319,3 +327,191 @@ geometry_msgs::Point rotatePoint(geometry_msgs::Point point, double degree) return rotate; } + +double calcCurvature(const geometry_msgs::Point &target, const geometry_msgs::Pose &curr_pose) +{ + constexpr double KAPPA_MAX = 1e9; + const double radius = calcRadius(target, curr_pose); + + if (std::fabs(radius) > 0) + { + return 1.0 / radius; + } + else + { + return KAPPA_MAX; + } +} + +double calcDistSquared2D(const geometry_msgs::Point &p, const geometry_msgs::Point &q) +{ + const double dx = p.x - q.x; + const double dy = p.y - q.y; + return (dx * dx + dy * dy); +} + +double calcLateralError2D(const geometry_msgs::Point &line_s, const geometry_msgs::Point &line_e, + const geometry_msgs::Point &point) +{ + tf2::Vector3 a_vec((line_e.x - line_s.x), (line_e.y - line_s.y), 0.0); + tf2::Vector3 b_vec((point.x - line_s.x), (point.y - line_s.y), 0.0); + + double lat_err = (a_vec.length() > 0) ? a_vec.cross(b_vec).z() / a_vec.length() : 0.0; + return lat_err; +} + +double calcRadius(const geometry_msgs::Point &target, const geometry_msgs::Pose ¤t_pose) +{ + constexpr double RADIUS_MAX = 1e9; + const double denominator = 2.0 * transformToRelativeCoordinate2D(target, current_pose).y; + const double numerator = calcDistSquared2D(target, current_pose.position); + + if (std::fabs(denominator) > 0) + return numerator / denominator; + else + return RADIUS_MAX; +} + +std::vector extractPoses(const autoware_msgs::Lane &lane) +{ + std::vector poses; + + for (const auto &el : lane.waypoints) + poses.push_back(el.pose.pose); + + return poses; +} + +std::vector extractPoses(const std::vector &wps) +{ + std::vector poses; + + for (const auto &el : wps) + poses.push_back(el.pose.pose); + + return poses; +} + +std::pair findClosestIdxWithDistAngThr(const std::vector &curr_ps, + const geometry_msgs::Pose &curr_pose, + double dist_thr, + double angle_thr) +{ + double dist_squared_min = std::numeric_limits::max(); + int32_t idx_min = -1; + + for (int32_t i = 0; i < static_cast(curr_ps.size()); ++i) + { + const double ds = calcDistSquared2D(curr_ps.at(i).position, curr_pose.position); + if (ds > dist_thr * dist_thr) + continue; + + double yaw_pose = tf2::getYaw(curr_pose.orientation); + double yaw_ps = tf2::getYaw(curr_ps.at(i).orientation); + double yaw_diff = normalizeEulerAngle(yaw_pose - yaw_ps); + if (std::fabs(yaw_diff) > angle_thr) + continue; + + if (ds < dist_squared_min) + { + dist_squared_min = ds; + idx_min = i; + } + } + + return (idx_min >= 0) ? std::make_pair(true, idx_min) : std::make_pair(false, idx_min); +} + +geometry_msgs::Quaternion getQuaternionFromYaw(const double &_yaw) +{ + tf2::Quaternion q; + q.setRPY(0, 0, _yaw); + return tf2::toMsg(q); +} + +bool isDirectionForward(const std::vector &poses) +{ + geometry_msgs::Point rel_p = transformToRelativeCoordinate2D(poses.at(2).position, poses.at(1)); + bool is_forward = (rel_p.x > 0.0) ? true : false; + return is_forward; +} + +double normalizeEulerAngle(double euler) +{ + double res = euler; + while (res > M_PI) + { + res -= (2.0 * M_PI); + } + while (res < -M_PI) + { + res += 2.0 * M_PI; + } + + return res; +} + +geometry_msgs::Point transformToAbsoluteCoordinate2D(const geometry_msgs::Point &point, + const geometry_msgs::Pose &origin) +{ + // rotation + geometry_msgs::Point rot_p; + double yaw = tf2::getYaw(origin.orientation); + rot_p.x = (cos(yaw) * point.x) + ((-1.0) * sin(yaw) * point.y); + rot_p.y = (sin(yaw) * point.x) + (cos(yaw) * point.y); + + // translation + geometry_msgs::Point res; + res.x = rot_p.x + origin.position.x; + res.y = rot_p.y + origin.position.y; + res.z = origin.position.z; + + return res; +} + +geometry_msgs::Point transformToAbsoluteCoordinate3D(const geometry_msgs::Point &point, + const geometry_msgs::Pose &origin) +{ + Eigen::Translation3d trans(origin.position.x, origin.position.y, origin.position.z); + Eigen::Quaterniond rot(origin.orientation.w, origin.orientation.x, origin.orientation.y, origin.orientation.z); + + Eigen::Vector3d v(point.x, point.y, point.z); + Eigen::Vector3d transformed_v; + transformed_v = trans * rot.inverse() * v; + + geometry_msgs::Point transformed_p = tf2::toMsg(transformed_v); + return transformed_p; +} + +geometry_msgs::Point transformToRelativeCoordinate2D(const geometry_msgs::Point &point, + const geometry_msgs::Pose &origin) +{ + // translation + geometry_msgs::Point trans_p; + trans_p.x = point.x - origin.position.x; + trans_p.y = point.y - origin.position.y; + + // rotation (use inverse matrix of rotation) + double yaw = tf2::getYaw(origin.orientation); + + geometry_msgs::Point res; + res.x = (cos(yaw) * trans_p.x) + (sin(yaw) * trans_p.y); + res.y = ((-1.0) * sin(yaw) * trans_p.x) + (cos(yaw) * trans_p.y); + res.z = origin.position.z; + + return res; +} + +geometry_msgs::Point transformToRelativeCoordinate3D(const geometry_msgs::Point &point, + const geometry_msgs::Pose &origin) +{ + Eigen::Translation3d trans(-origin.position.x, -origin.position.y, -origin.position.z); + Eigen::Quaterniond rot(origin.orientation.w, origin.orientation.x, origin.orientation.y, origin.orientation.z); + + Eigen::Vector3d v(point.x, point.y, point.z); + Eigen::Vector3d transformed_v; + transformed_v = trans * rot * v; + + geometry_msgs::Point transformed_p = tf2::toMsg(transformed_v); + return transformed_p; +} diff --git a/common/libwaypoint_follower/src/pure_pursuit.cpp b/common/libwaypoint_follower/src/pure_pursuit.cpp new file mode 100644 index 00000000000..5edb0b721f8 --- /dev/null +++ b/common/libwaypoint_follower/src/pure_pursuit.cpp @@ -0,0 +1,196 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "libwaypoint_follower/pure_pursuit.h" +#include "libwaypoint_follower/libwaypoint_follower.h" + +#include +#include +#include +#include +#include + +void PurePursuit::setUseLerp(bool ul) { use_lerp_ = ul; } + +void PurePursuit::setLookaheadDistance(double ld) { lookahead_distance_ = ld; } + +void PurePursuit::setClosestThreshold(double clst_thr_dist, double clst_thr_ang) +{ + clst_thr_dist_ = clst_thr_dist; + clst_thr_ang_ = clst_thr_ang; +} + +geometry_msgs::Point PurePursuit::getLocationOfNextWaypoint() { return loc_next_wp_; } + +geometry_msgs::Point PurePursuit::getLocationOfNextTarget() { return loc_next_tgt_; } + +bool PurePursuit::isRequirementsSatisfied() +{ + return (curr_wps_ptr_ && curr_pose_ptr_) ? true : false; +} + +std::pair PurePursuit::run() +{ + std::pair error = std::make_pair(false, std::numeric_limits::quiet_NaN()); + if (!isRequirementsSatisfied()) + return error; + + auto clst_pair = findClosestIdxWithDistAngThr(*curr_wps_ptr_, *curr_pose_ptr_, clst_thr_dist_, clst_thr_ang_); + + if (!clst_pair.first) + { + ROS_WARN("cannot find, curr_bool: %d, clst_idx: %d", clst_pair.first, clst_pair.second); + return error; + } + + int32_t next_wp_idx = findNextPointIdx(clst_pair.second); + if (next_wp_idx == -1) + { + ROS_WARN("lost next waypoint"); + return error; + } + + loc_next_wp_ = curr_wps_ptr_->at(next_wp_idx).position; + + geometry_msgs::Point next_tgt_pos; + // if use_lerp_ is false or next waypoint is first + if (!use_lerp_ || next_wp_idx == 0) + { + next_tgt_pos = curr_wps_ptr_->at(next_wp_idx).position; + } + else + { + // linear interpolation + std::pair lerp_pair = lerpNextTarget(next_wp_idx); + + if (!lerp_pair.first) + { + ROS_WARN("lost target! "); + return error; + } + + next_tgt_pos = lerp_pair.second; + } + loc_next_tgt_ = next_tgt_pos; + + double kappa = calcCurvature(next_tgt_pos, *curr_pose_ptr_); + + return std::make_pair(true, kappa); +} + +// linear interpolation of next target +std::pair PurePursuit::lerpNextTarget(int32_t next_wp_idx) +{ + std::pair error = std::make_pair(false, geometry_msgs::Point()); + constexpr double ERROR2 = 1e-5; // 0.00001 + const geometry_msgs::Point &vec_end = curr_wps_ptr_->at(next_wp_idx).position; + const geometry_msgs::Point &vec_start = curr_wps_ptr_->at(next_wp_idx - 1).position; + const geometry_msgs::Pose &curr_pose = *curr_pose_ptr_; + + Eigen::Vector3d vec_a((vec_end.x - vec_start.x), + (vec_end.y - vec_start.y), + (vec_end.z - vec_start.z)); + + if (vec_a.norm() < ERROR2) + return error; + + double lateral_error = calcLateralError2D( + vec_start, vec_end, curr_pose.position); + + if (std::fabs(lateral_error) > lookahead_distance_) + return error; + + /* calculate the position of the foot of a perpendicular line */ + Eigen::Vector2d uva2d(vec_a.x(), vec_a.y()); + uva2d.normalize(); + Eigen::Rotation2Dd rot = (lateral_error > 0) ? Eigen::Rotation2Dd(-M_PI / 2.0) : Eigen::Rotation2Dd(M_PI / 2.0); + Eigen::Vector2d uva2d_rot = rot * uva2d; + + geometry_msgs::Point h; + h.x = curr_pose.position.x + fabs(lateral_error) * uva2d_rot.x(); + h.y = curr_pose.position.y + fabs(lateral_error) * uva2d_rot.y(); + h.z = curr_pose.position.z; + + // if there is a intersection + if (fabs(fabs(lateral_error) - lookahead_distance_) < ERROR2) + { + return std::make_pair(true, h); + } + else + { + // if there are two intersection + // get intersection in front of vehicle + double s = sqrt(pow(lookahead_distance_, 2) - pow(lateral_error, 2)); + geometry_msgs::Point res; + res.x = h.x + s * uva2d.x(); + res.y = h.y + s * uva2d.y(); + res.z = curr_pose.position.z; + return std::make_pair(true, res); + } +} + +int32_t PurePursuit::findNextPointIdx(int32_t search_start_idx) +{ + // if waypoints are not given, do nothing. + if (curr_wps_ptr_->size() < 3 || search_start_idx == -1) + return -1; + + // look for the next waypoint. + for (int32_t i = search_start_idx; i < static_cast(curr_wps_ptr_->size()); i++) + { + // if search waypoint is the last + if (i == static_cast(curr_wps_ptr_->size() - 1)) + { + return i; + } + + // if waypoint is not on the front + if (isDirectionForward(*curr_wps_ptr_)) + { + if (transformToRelativeCoordinate2D(curr_wps_ptr_->at(i).position, *curr_pose_ptr_).x < 0) + continue; + } + else + { + if (transformToRelativeCoordinate2D(curr_wps_ptr_->at(i).position, *curr_pose_ptr_).x > 0) + continue; + } + + const geometry_msgs::Point &curr_motion_point = curr_wps_ptr_->at(i).position; + const geometry_msgs::Point &curr_pose_point = curr_pose_ptr_->position; + // if there exists an effective waypoint + const double ds = calcDistSquared2D(curr_motion_point, curr_pose_point); + if (ds > std::pow(lookahead_distance_, 2)) + return i; + } + + // if this program reaches here , it means we lost the waypoint! + ROS_ERROR("lost waypoint!"); + return -1; +} + +void PurePursuit::setCurrentPose(const geometry_msgs::Pose &msg) +{ + curr_pose_ptr_ = std::make_shared(); + *curr_pose_ptr_ = msg; +} + +void PurePursuit::setWaypoints(const std::vector &msg) +{ + curr_wps_ptr_ = std::make_shared>(); + *curr_wps_ptr_ = msg; +} + diff --git a/common/libwaypoint_follower/test/src/test_libwaypoint_follower.cpp b/common/libwaypoint_follower/test/src/test_libwaypoint_follower.cpp index cf38bc38a62..2a26bea33ff 100644 --- a/common/libwaypoint_follower/test/src/test_libwaypoint_follower.cpp +++ b/common/libwaypoint_follower/test/src/test_libwaypoint_follower.cpp @@ -14,20 +14,27 @@ * limitations under the License. */ -#include "test_libwaypoint_follower.hpp" +#include +#include +#include +#include -class LibWaypointFollowerTestSuite : public ::testing::Test { +#include "libwaypoint_follower/test_libwaypoint_follower.h" + +class LibWaypointFollowerTestSuite : + public ::testing::Test +{ public: LibWaypointFollowerTestSuite() {} - ~LibWaypointFollowerTestSuite() {} LibWaypointFollowerTestClass test_obj_; protected: - virtual void SetUp(){} - virtual void TearDown(){} + virtual void SetUp() {} + virtual void TearDown() {} }; -TEST_F(LibWaypointFollowerTestSuite, calcRelativeCoordinate) { +TEST_F(LibWaypointFollowerTestSuite, calcRelativeCoordinate) +{ // The member variable x of calcRelativeCoordinate must return following: // - if target_point is in front of current_pose, return positive value // - else if target_point is behind from current_pose, return negative value @@ -56,7 +63,8 @@ TEST_F(LibWaypointFollowerTestSuite, calcRelativeCoordinate) { } } -TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByPosition) { +TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByPosition) +{ // getLaneDirectionByPosition must return following: // - if waypoint[i+1] is in front of waypoint[i], return Forward // - else if waypoint[i+1] is behind from waypoint[i], return Backward @@ -74,7 +82,8 @@ TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByPosition) { } } -TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByVelocity) { +TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByVelocity) +{ // getLaneDirectionByVelocity must return following: // - if waypoint[i+1] is in front of waypoint[i], return Forward // - else if waypoint[i+1] is behind from waypoint[i], return Backward @@ -90,7 +99,8 @@ TEST_F(LibWaypointFollowerTestSuite, getLaneDirectionByVelocity) { } } -TEST_F(LibWaypointFollowerTestSuite, getLaneDirection) { +TEST_F(LibWaypointFollowerTestSuite, getLaneDirection) +{ // getLaneDirection must return following: // Now, Rp means position identification result, // and Rv means velocity identification result. @@ -116,7 +126,8 @@ TEST_F(LibWaypointFollowerTestSuite, getLaneDirection) { } } -TEST_F(LibWaypointFollowerTestSuite, inDrivingDirection) { +TEST_F(LibWaypointFollowerTestSuite, inDrivingDirection) +{ // inDrivingDirection must return following: // Now, Rd means lane direction identification result, // and Rc means relative Coordinate result. @@ -151,7 +162,8 @@ TEST_F(LibWaypointFollowerTestSuite, inDrivingDirection) { } -TEST_F(LibWaypointFollowerTestSuite, getClosestWaypoint) { +TEST_F(LibWaypointFollowerTestSuite, getClosestWaypoint) +{ // // getClosestWaypoint must return following: // case) current_pose == (0,0,0) @@ -176,7 +188,7 @@ TEST_F(LibWaypointFollowerTestSuite, getClosestWaypoint) { dataset["(no_point_path)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, 0.0, 0, valid_pose), -1); dataset["(valid_forward)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, -0.5, 100, valid_pose), 1); dataset["(valid_backward)"] = std::make_pair(ClosestCheckDataSet(-1, -5.0, -1.5, 100, valid_pose), 2); - dataset["(over_distance)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, 6.0, 100, valid_pose), 1); + dataset["(over_distance)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, 6.0, 100, valid_pose), 0); dataset["(opposite_lane)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, -0.5, 100, invalid_pose), 1); dataset["(pass_endpoint)"] = std::make_pair(ClosestCheckDataSet(1, 5.0, -100.0, 100, valid_pose), -1); @@ -190,7 +202,302 @@ TEST_F(LibWaypointFollowerTestSuite, getClosestWaypoint) { } } -int main(int argc, char **argv) { +TEST_F(LibWaypointFollowerTestSuite, calcCurvature) +{ + geometry_msgs::Point target; + geometry_msgs::Pose curr_pose; + + target.x = 10.0; + target.y = 0.0; + ASSERT_NEAR(0.0, calcCurvature(target, curr_pose), ERROR); + + target.x = 10.0; + target.y = 10.0; + ASSERT_NEAR(0.1, calcCurvature(target, curr_pose), ERROR); + + target.x = 0.0; + target.y = 10.0; + ASSERT_NEAR(0.2, calcCurvature(target, curr_pose), ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, calcDistSquared2D) +{ + geometry_msgs::Point p; + geometry_msgs::Point q; + + // p.x = 0.0, p.y = 0.0, q.x = 0.0, q.y = 0.0, length2=0.0m + ASSERT_NEAR(0.000000, calcDistSquared2D(p, q), ERROR); + + // p.x = 0.0, p.y = 0.0, p.z = 10.0, q.x = 0.0, q.y = 0.0, length2=0.0m, z is invalid value + p.z = 10.0; + ASSERT_NEAR(0.000000, calcDistSquared2D(p, q), ERROR); + + // p.x = 1.0, p.y = 0.0, q.x = 0.0, q.y = 0.0, length2=0.0m + p.x = 1.0; + p.z = 0.0; + ASSERT_NEAR(1.000000, calcDistSquared2D(p, q), ERROR); + + // p.x = 2.0, p.y = 6.0, q.x = 6.0, q.y = 3.0, length2=25.0m + p.x = 2.0; + p.y = 6.0; + q.x = 6.0; + q.y = 3.0; + ASSERT_NEAR(25.000000, calcDistSquared2D(p, q), ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, calcLateralError) +{ + geometry_msgs::Point line_s; + geometry_msgs::Point line_e; + geometry_msgs::Point point; + + // target point is on right side of the line + line_s.x = 2.0; + line_s.y = 4.0; + + line_e.x = 7.0; + line_e.y = 3.0; + + point.x = 6.0; + point.y = -3.0; + ASSERT_NEAR(-6.079600, calcLateralError2D(line_s, line_e, point), ERROR); + + // target point is on left side of the line + point.x = 4.0; + point.y = 8.0; + ASSERT_NEAR(4.314555, calcLateralError2D(line_s, line_e, point), ERROR); + + // the length of line is zero + ASSERT_NEAR(0.0, calcLateralError2D(line_s, line_s, point), ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, calcRadius) +{ + geometry_msgs::Point target; + geometry_msgs::Pose curr_pose; + + ASSERT_NEAR(1e9, calcRadius(target, curr_pose), ERROR); + + target.x = 10.0; + target.y = 0.0; + ASSERT_NEAR(1e9, calcRadius(target, curr_pose), ERROR); + + target.x = 10.0; + target.y = 10.0; + ASSERT_NEAR(10.0, calcRadius(target, curr_pose), ERROR); + + target.x = 0.0; + target.y = 10.0; + ASSERT_NEAR(5.0, calcRadius(target, curr_pose), ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, extractPoses_Lane) +{ + autoware_msgs::Lane test; + test.waypoints.emplace_back(); + test.waypoints.emplace_back(); + test.waypoints.emplace_back(); + test.waypoints.at(0).pose.pose.position.x = 5.0; + test.waypoints.at(1).pose.pose.position.x = 100.0; + test.waypoints.at(2).pose.pose.position.x = -999.0; + std::vector poses = extractPoses(test); + ASSERT_NEAR(5.0, test.waypoints.at(0).pose.pose.position.x, ERROR); + ASSERT_NEAR(100.0, test.waypoints.at(1).pose.pose.position.x, ERROR); + ASSERT_NEAR(-999.0, test.waypoints.at(2).pose.pose.position.x, ERROR); +} +TEST_F(LibWaypointFollowerTestSuite, extractPoses_Waypoint) +{ + std::vector test; + test.emplace_back(); + test.emplace_back(); + test.emplace_back(); + test.at(0).pose.pose.position.x = 5.0; + test.at(1).pose.pose.position.x = 100.0; + test.at(2).pose.pose.position.x = -999.0; + std::vector poses = extractPoses(test); + ASSERT_NEAR(5.0, test.at(0).pose.pose.position.x, ERROR); + ASSERT_NEAR(100.0, test.at(1).pose.pose.position.x, ERROR); + ASSERT_NEAR(-999.0, test.at(2).pose.pose.position.x, ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, findClosestIdxWithDistAngThr) +{ + std::vector curr_ps; + geometry_msgs::Pose curr_pose; + + std::pair ans; + + ans = findClosestIdxWithDistAngThr(curr_ps, curr_pose); + ASSERT_EQ(false, ans.first); + ASSERT_EQ(-1, ans.second); + + tf2::Quaternion tf2_q; + tf2_q.setRPY(0, 0, 0); + tf2_q.normalize(); + for (uint32_t i = 0; i < 10; i++) + { + geometry_msgs::Pose tmp_pose; + tmp_pose.position.x = static_cast(i) * 1.0; + tmp_pose.orientation = tf2::toMsg(tf2_q); + curr_ps.push_back(tmp_pose); + } + + curr_pose.position.x = 0.0; + curr_pose.orientation = tf2::toMsg(tf2_q); + ans = findClosestIdxWithDistAngThr(curr_ps, curr_pose); + ASSERT_EQ(true, ans.first); + ASSERT_EQ(0, ans.second); + + tf2_q.setRPY(0, 0, 0.175); // yaw = 10deg + tf2_q.normalize(); + curr_pose.position.x = 3.0; + curr_pose.orientation = tf2::toMsg(tf2_q); + ans = findClosestIdxWithDistAngThr(curr_ps, curr_pose); + ASSERT_EQ(true, ans.first); + ASSERT_EQ(3, ans.second); +} + +TEST_F(LibWaypointFollowerTestSuite, isDirectionForward) +{ + std::vector poses; + poses.reserve(2); + geometry_msgs::Pose p0; + geometry_msgs::Pose p1; + geometry_msgs::Pose p2; + + // p1 and p2 is same pose + poses.push_back(p0); + poses.push_back(p1); + poses.push_back(p2); + ASSERT_EQ(false, isDirectionForward(poses)); + + // p2.position.x = 3.0 p1 is origin position + poses.clear(); + poses.push_back(p0); + poses.push_back(p1); + p2.position.x = 3.0; + poses.push_back(p2); + ASSERT_EQ(true, isDirectionForward(poses)); + + // p2.position.x = -3.0 p1 is origin position + poses.clear(); + poses.push_back(p0); + poses.push_back(p1); + p2.position.x = -3.0; + poses.push_back(p2); + ASSERT_EQ(false, isDirectionForward(poses)); +} + +TEST_F(LibWaypointFollowerTestSuite, normalizeEulerAngle) +{ + ASSERT_DOUBLE_EQ(M_PI, normalizeEulerAngle(3 * M_PI)); + ASSERT_DOUBLE_EQ(-M_PI, normalizeEulerAngle(-3 * M_PI)); + ASSERT_DOUBLE_EQ(-M_PI + 0.1, normalizeEulerAngle(M_PI + 0.1)); + ASSERT_DOUBLE_EQ(M_PI - 0.2, normalizeEulerAngle(-M_PI - 0.2)); +} + +TEST_F(LibWaypointFollowerTestSuite, transformToAbsoluteCoordinate2D) +{ + geometry_msgs::Point point; + geometry_msgs::Pose origin; + geometry_msgs::Point res; + + // no translation and rotation + res = transformToAbsoluteCoordinate2D(point, origin); + ASSERT_NEAR(0.0, res.x, ERROR); + ASSERT_NEAR(0.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // only translation + point.x = 2.0; + point.y = 2.0; + origin.position.x = 5.0; + origin.position.y = 3.0; + + res = transformToAbsoluteCoordinate2D(point, origin); + ASSERT_NEAR(7.0, res.x, ERROR); + ASSERT_NEAR(5.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // translation and rotation 90 deg + tf2::Quaternion tf_q; + point.x = 3.0; + point.y = 2.0; + origin.position.x = 4.0; + origin.position.y = 3.0; + tf_q.setRPY(0.0, 0.0, 90 * M_PI / 180); + origin.orientation = tf2::toMsg(tf_q); + + res = transformToAbsoluteCoordinate2D(point, origin); + ASSERT_NEAR(2.0, res.x, ERROR); + ASSERT_NEAR(6.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // translation and rotation -90 deg + point.x = 2.0; + point.y = -3.0; + origin.position.x = 5.0; + origin.position.y = -4.0; + tf_q.setRPY(0.0, 0.0, -90 * M_PI / 180); + origin.orientation = tf2::toMsg(tf_q); + + res = transformToAbsoluteCoordinate2D(point, origin); + ASSERT_NEAR(2.0, res.x, ERROR); + ASSERT_NEAR(-6.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); +} + +TEST_F(LibWaypointFollowerTestSuite, transformToRelativeCoordinate2D) +{ + geometry_msgs::Point point; + geometry_msgs::Pose origin; + geometry_msgs::Point res; + + // no translation and rotation + res = transformToRelativeCoordinate2D(point, origin); + ASSERT_NEAR(0.0, res.x, ERROR); + ASSERT_NEAR(0.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // only translation + point.x = 7.0; + point.y = 5.0; + origin.position.x = 5.0; + origin.position.y = 3.0; + res = transformToRelativeCoordinate2D(point, origin); + ASSERT_NEAR(2.0, res.x, ERROR); + ASSERT_NEAR(2.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // translation and rotation 90 deg + tf2::Quaternion tf_q; + + point.x = 2.0; + point.y = 6.0; + origin.position.x = 4.0; + origin.position.y = 3.0; + tf_q.setRPY(0.0, 0.0, 90 * M_PI / 180); + origin.orientation = tf2::toMsg(tf_q); + res = transformToRelativeCoordinate2D(point, origin); + ASSERT_NEAR(3.0, res.x, ERROR); + ASSERT_NEAR(2.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); + + // translation and rotation -90 deg + point.x = 2.0; + point.y = -6.0; + origin.position.x = 5.0; + origin.position.y = -4.0; + tf_q.setRPY(0.0, 0.0, -90 * M_PI / 180); + origin.orientation = tf2::toMsg(tf_q); + res = transformToRelativeCoordinate2D(point, origin); + ASSERT_NEAR(2.0, res.x, ERROR); + ASSERT_NEAR(-3.0, res.y, ERROR); + ASSERT_NEAR(0.0, res.z, ERROR); +} + +int main(int argc, char **argv) +{ testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "LibWaypointFollowerTestNode"); ros::NodeHandle n; diff --git a/common/libwaypoint_follower/test/src/test_pure_pursuit.cpp b/common/libwaypoint_follower/test/src/test_pure_pursuit.cpp new file mode 100644 index 00000000000..87ff0f9d986 --- /dev/null +++ b/common/libwaypoint_follower/test/src/test_pure_pursuit.cpp @@ -0,0 +1,62 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include "libwaypoint_follower/pure_pursuit.h" +#include "libwaypoint_follower/libwaypoint_follower.h" + +class TestSuite : public ::testing::Test +{ +public: + TestSuite() + { + } + ~TestSuite() + { + } +}; + +TEST_F(TestSuite, PurePursuit_is_requirements_safisfied) +{ + PurePursuit pp; + ASSERT_EQ(false, pp.isRequirementsSatisfied()); + + geometry_msgs::PoseStampedConstPtr pose_ptr(new geometry_msgs::PoseStamped()); + autoware_msgs::LaneConstPtr wps_ptr(new autoware_msgs::Lane()); + pp.setCurrentPose(pose_ptr->pose); + pp.setWaypoints(extractPoses(*wps_ptr)); + ASSERT_EQ(true, pp.isRequirementsSatisfied()); +} + +TEST_F(TestSuite, PurePursuit_run) +{ + PurePursuit pp; + auto res = pp.run(); + ASSERT_EQ(false, res.first); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "TestNode"); + return RUN_ALL_TESTS(); +} diff --git a/common/libwaypoint_follower/test/test_pure_pursuit.test b/common/libwaypoint_follower/test/test_pure_pursuit.test new file mode 100644 index 00000000000..74d6c83d1e5 --- /dev/null +++ b/common/libwaypoint_follower/test/test_pure_pursuit.test @@ -0,0 +1,5 @@ + + + + + \ No newline at end of file diff --git a/common/map_file/launch/lanelet2_map_loader.launch b/common/map_file/launch/lanelet2_map_loader.launch index 2b95eecf70b..75dcd94adef 100644 --- a/common/map_file/launch/lanelet2_map_loader.launch +++ b/common/map_file/launch/lanelet2_map_loader.launch @@ -1,5 +1,7 @@ - - - - \ No newline at end of file + + + + + + diff --git a/common/map_file/launch/points_map_loader.launch b/common/map_file/launch/points_map_loader.launch new file mode 100644 index 00000000000..fb26dce2a58 --- /dev/null +++ b/common/map_file/launch/points_map_loader.launch @@ -0,0 +1,15 @@ + + + + + + + + + area: $(arg scene_num) + arealist_path: $(arg path_area_list) + pcd_paths: [ $(arg path_pcd) ] + + + + diff --git a/common/map_file/launch/vector_map_loader.launch b/common/map_file/launch/vector_map_loader.launch new file mode 100644 index 00000000000..727e16e4a31 --- /dev/null +++ b/common/map_file/launch/vector_map_loader.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp index 716a7f9c830..86f5e7cdd13 100644 --- a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp +++ b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp @@ -53,37 +53,46 @@ void binMapCallback(autoware_lanelet2_msgs::MapBin msg) lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap); lanelet::utils::conversion::fromBinMsg(msg, viz_lanelet_map); - ROS_INFO("Map is loaded\n"); + ROS_INFO("Map loaded"); // get lanelets etc to visualize lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(viz_lanelet_map); lanelet::ConstLanelets road_lanelets = lanelet::utils::query::roadLanelets(all_lanelets); lanelet::ConstLanelets crosswalk_lanelets = lanelet::utils::query::crosswalkLanelets(all_lanelets); - std::vector stop_lines = lanelet::utils::query::stopLinesLanelets(road_lanelets); - // std::vector tl_reg_elems = lanelet::utils::query::trafficLights(all_lanelets); - // std::vector aw_tl_reg_elems = - // lanelet::utils::query::autowareTrafficLights(all_lanelets); - std_msgs::ColorRGBA cl_road, cl_cross, cl_ll_borders, cl_stoplines, cl_trafficlights; + std::vector tl_stop_lines = lanelet::utils::query::getTrafficLightStopLines(road_lanelets); + std::vector ss_stop_lines = lanelet::utils::query::getStopSignStopLines(road_lanelets); + std::vector tl_reg_elems = lanelet::utils::query::trafficLights(all_lanelets); + std::vector aw_tl_reg_elems = + lanelet::utils::query::autowareTrafficLights(all_lanelets); + + std_msgs::ColorRGBA cl_road, cl_cross, cl_ll_borders, cl_tl_stoplines, cl_ss_stoplines, cl_trafficlights; setColor(&cl_road, 0.2, 0.7, 0.7, 0.3); setColor(&cl_cross, 0.2, 0.7, 0.2, 0.3); setColor(&cl_ll_borders, 1.0, 1.0, 1.0, 1.0); - setColor(&cl_stoplines, 1.0, 0.0, 0.0, 0.5); + setColor(&cl_tl_stoplines, 1.0, 0.5, 0.0, 0.5); + setColor(&cl_ss_stoplines, 1.0, 0.0, 0.0, 0.5); setColor(&cl_trafficlights, 0.7, 0.7, 0.7, 0.8); visualization_msgs::MarkerArray map_marker_array; insertMarkerArray(&map_marker_array, lanelet::visualization::laneletsBoundaryAsMarkerArray( - road_lanelets, cl_ll_borders, g_viz_lanelets_centerline)); - // insertMarkerArray(&map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( - // "road_lanelets", road_lanelets, cl_road)); + road_lanelets, cl_ll_borders, g_viz_lanelets_centerline)); + insertMarkerArray(&map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( + "road_lanelets", road_lanelets, cl_road)); insertMarkerArray(&map_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray( - "crosswalk_lanelets", crosswalk_lanelets, cl_cross)); - insertMarkerArray(&map_marker_array, lanelet::visualization::laneletDirectionAsMarkerArray(road_lanelets)); - insertMarkerArray(&map_marker_array, lanelet::visualization::lineStringsAsMarkerArray(stop_lines, "stop_lines", - cl_stoplines, 0.5)); - // insertMarkerArray(&map_marker_array, lanelet::visualization::autowareTrafficLightsAsMarkerArray( - // aw_tl_reg_elems, cl_trafficlights)); + "crosswalk_lanelets", crosswalk_lanelets, cl_cross)); + insertMarkerArray(&map_marker_array, lanelet::visualization::laneletDirectionAsMarkerArray( + road_lanelets)); + insertMarkerArray(&map_marker_array, lanelet::visualization::lineStringsAsMarkerArray( + tl_stop_lines, "traffic_light_stop_lines", cl_tl_stoplines, 0.5)); + insertMarkerArray(&map_marker_array, lanelet::visualization::lineStringsAsMarkerArray( + ss_stop_lines, "stop_sign_stop_lines", cl_ss_stoplines, 0.5)); + insertMarkerArray(&map_marker_array, lanelet::visualization::autowareTrafficLightsAsMarkerArray( + aw_tl_reg_elems, cl_trafficlights)); + + ROS_INFO("Visualizing lanelet2 map with %lu lanelets, %lu stop lines, and %lu traffic lights", + all_lanelets.size(), tl_stop_lines.size() + ss_stop_lines.size(), aw_tl_reg_elems.size()); g_map_pub.publish(map_marker_array); } diff --git a/common/map_file/nodes/vector_map_loader/vector_map_loader.cpp b/common/map_file/nodes/vector_map_loader/vector_map_loader.cpp index 1801d494a9a..de430f49f60 100644 --- a/common/map_file/nodes/vector_map_loader/vector_map_loader.cpp +++ b/common/map_file/nodes/vector_map_loader/vector_map_loader.cpp @@ -99,6 +99,13 @@ using vector_map::createPoleMarker; namespace { + +enum class LoadMode { + FILE, + DIRECTORY, + DOWNLOAD +}; + void printUsage() { ROS_ERROR_STREAM("Usage:"); @@ -113,15 +120,24 @@ bool isDownloaded(const std::string& local_path) } template -U createObjectArray(const std::string& file_path) +vector_map::category_t registerVectormapPortion( + const std::string& file_path, ros::Publisher *publisher, + const std::string topic_name, const vector_map::category_t category, + ros::NodeHandle *nh) { U obj_array; - // NOTE: Autoware want to use map messages with or without /use_sim_time. - // Therefore we don't set obj_array.header.stamp. - // obj_array.header.stamp = ros::Time::now(); obj_array.header.frame_id = "map"; obj_array.data = vector_map::parse(file_path); - return obj_array; + if (!obj_array.data.empty()) + { + *publisher = nh->advertise(topic_name, 1, true); + publisher->publish(obj_array); + return category; + } + else + { + return Category::NONE; + } } visualization_msgs::Marker createLinkedLineMarker(const std::string& ns, int id, Color color, const VectorMap& vmap, @@ -916,52 +932,88 @@ int main(int argc, char **argv) { ros::init(argc, argv, "vector_map_loader"); ros::NodeHandle nh; + ros::NodeHandle pnh("~"); - if (argc < 2) + LoadMode load_mode = LoadMode::FILE; + if (pnh.hasParam("load_mode")) { - printUsage(); - return EXIT_FAILURE; + // Set mode based on rosparam + std::string load_mode_param; + pnh.getParam("load_mode", load_mode_param); + if (load_mode_param == "file") + { + load_mode = LoadMode::FILE; + } + else if (load_mode_param == "directory") + { + load_mode = LoadMode::DIRECTORY; + } + else if (load_mode_param == "download") + { + load_mode = LoadMode::DOWNLOAD; + } + else + { + printUsage(); + } } - - std::string mode(argv[1]); - if (mode == "download" && argc < 4) + else { - printUsage(); - return EXIT_FAILURE; + // Set mode based on args + if (argc < 2) + { + printUsage(); + ros::shutdown(); + } + + if (strcmp(argv[1], "download") == 0) + { + load_mode = LoadMode::DOWNLOAD; + if (argc < 4) + { + printUsage(); + ros::shutdown(); + } + } } - ros::Publisher point_pub = nh.advertise("vector_map_info/point", 1, true); - ros::Publisher vector_pub = nh.advertise("vector_map_info/vector", 1, true); - ros::Publisher line_pub = nh.advertise("vector_map_info/line", 1, true); - ros::Publisher area_pub = nh.advertise("vector_map_info/area", 1, true); - ros::Publisher pole_pub = nh.advertise("vector_map_info/pole", 1, true); - ros::Publisher box_pub = nh.advertise("vector_map_info/box", 1, true); - ros::Publisher dtlane_pub = nh.advertise("vector_map_info/dtlane", 1, true); - ros::Publisher node_pub = nh.advertise("vector_map_info/node", 1, true); - ros::Publisher lane_pub = nh.advertise("vector_map_info/lane", 1, true); - ros::Publisher way_area_pub = nh.advertise("vector_map_info/way_area", 1, true); - ros::Publisher road_edge_pub = nh.advertise("vector_map_info/road_edge", 1, true); - ros::Publisher gutter_pub = nh.advertise("vector_map_info/gutter", 1, true); - ros::Publisher curb_pub = nh.advertise("vector_map_info/curb", 1, true); - ros::Publisher white_line_pub = nh.advertise("vector_map_info/white_line", 1, true); - ros::Publisher stop_line_pub = nh.advertise("vector_map_info/stop_line", 1, true); - ros::Publisher zebra_zone_pub = nh.advertise("vector_map_info/zebra_zone", 1, true); - ros::Publisher cross_walk_pub = nh.advertise("vector_map_info/cross_walk", 1, true); - ros::Publisher road_mark_pub = nh.advertise("vector_map_info/road_mark", 1, true); - ros::Publisher road_pole_pub = nh.advertise("vector_map_info/road_pole", 1, true); - ros::Publisher road_sign_pub = nh.advertise("vector_map_info/road_sign", 1, true); - ros::Publisher signal_pub = nh.advertise("vector_map_info/signal", 1, true); - ros::Publisher street_light_pub = nh.advertise("vector_map_info/street_light", 1, true); - ros::Publisher utility_pole_pub = nh.advertise("vector_map_info/utility_pole", 1, true); - ros::Publisher guard_rail_pub = nh.advertise("vector_map_info/guard_rail", 1, true); - ros::Publisher side_walk_pub = nh.advertise("vector_map_info/side_walk", 1, true); - ros::Publisher drive_on_portion_pub = nh.advertise("vector_map_info/drive_on_portion", 1, true); - ros::Publisher cross_road_pub = nh.advertise("vector_map_info/cross_road", 1, true); - ros::Publisher side_strip_pub = nh.advertise("vector_map_info/side_strip", 1, true); - ros::Publisher curve_mirror_pub = nh.advertise("vector_map_info/curve_mirror", 1, true); - ros::Publisher wall_pub = nh.advertise("vector_map_info/wall", 1, true); - ros::Publisher fence_pub = nh.advertise("vector_map_info/fence", 1, true); - ros::Publisher rail_crossing_pub = nh.advertise("vector_map_info/rail_crossing", 1, true); + // Directory containing vector map csvs + std::string map_dir; + pnh.param("map_dir", map_dir, ""); + + // Vector map publishers will be initialized later as data is loaded. + ros::Publisher area_pub; + ros::Publisher box_pub; + ros::Publisher cross_road_pub; + ros::Publisher cross_walk_pub; + ros::Publisher curb_pub; + ros::Publisher curve_mirror_pub; + ros::Publisher drive_on_portion_pub; + ros::Publisher dtlane_pub; + ros::Publisher fence_pub; + ros::Publisher guard_rail_pub; + ros::Publisher gutter_pub; + ros::Publisher lane_pub; + ros::Publisher line_pub; + ros::Publisher node_pub; + ros::Publisher point_pub; + ros::Publisher pole_pub; + ros::Publisher rail_crossing_pub; + ros::Publisher road_edge_pub; + ros::Publisher road_mark_pub; + ros::Publisher road_pole_pub; + ros::Publisher road_sign_pub; + ros::Publisher side_strip_pub; + ros::Publisher side_walk_pub; + ros::Publisher signal_pub; + ros::Publisher stop_line_pub; + ros::Publisher street_light_pub; + ros::Publisher utility_pole_pub; + ros::Publisher vector_pub; + ros::Publisher wall_pub; + ros::Publisher way_area_pub; + ros::Publisher white_line_pub; + ros::Publisher zebra_zone_pub; ros::Publisher marker_array_pub = nh.advertise("vector_map", 1, true); ros::Publisher stat_pub = nh.advertise("vmap_stat", 1, true); @@ -971,16 +1023,54 @@ int main(int argc, char **argv) stat_pub.publish(stat); std::vector file_paths; - if (mode == "download") + std::vector file_names + { + "area.csv", + "box.csv", + "crosswalk.csv", + "curb.csv", + "curvemirror.csv", + "driveon_portion.csv", + "dtlane.csv", + "fence.csv", + "guardrail.csv", + "gutter.csv", + "idx.csv", + "intersection.csv", + "lane.csv", + "line.csv", + "node.csv", + "point.csv", + "pole.csv", + "poledata.csv", + "railroad_crossing.csv", + "road_surface_mark.csv", + "roadedge.csv", + "roadsign.csv", + "sidestrip.csv", + "sidewalk.csv", + "signaldata.csv", + "stopline.csv", + "streetlight.csv", + "utilitypole.csv", + "vector.csv", + "wall.csv", + "wayarea.csv", + "whiteline.csv", + "zebrazone.csv" + }; + + if (load_mode == LoadMode::DOWNLOAD) { + ROS_INFO("Load Mode: Download"); std::string host_name; - nh.param("vector_map_loader/host_name", host_name, HTTP_HOSTNAME); + pnh.param("host_name", host_name, HTTP_HOSTNAME); int port; - nh.param("vector_map_loader/port", port, HTTP_PORT); + pnh.param("port", port, HTTP_PORT); std::string user; - nh.param("vector_map_loader/user", user, HTTP_USER); + pnh.param("user", user, HTTP_USER); std::string password; - nh.param("vector_map_loader/password", password, HTTP_PASSWORD); + pnh.param("password", password, HTTP_PASSWORD); GetFile gf = GetFile(host_name, port, user, password); std::string remote_path = "/data/map"; @@ -1004,42 +1094,6 @@ int main(int argc, char **argv) } } - std::vector file_names - { - "idx.csv", - "point.csv", - "vector.csv", - "line.csv", - "area.csv", - "pole.csv", - "box.csv", - "dtlane.csv", - "node.csv", - "lane.csv", - "wayarea.csv", - "roadedge.csv", - "gutter.csv", - "curb.csv", - "whiteline.csv", - "stopline.csv", - "zebrazone.csv", - "crosswalk.csv", - "road_surface_mark.csv", - "poledata.csv", - "roadsign.csv", - "signaldata.csv", - "streetlight.csv", - "utilitypole.csv", - "guardrail.csv", - "sidewalk.csv", - "driveon_portion.csv", - "intersection.csv", - "sidestrip.csv", - "curvemirror.csv", - "wall.csv", - "fence.csv", - "railroad_crossing.csv" - }; for (const auto& file_name : file_names) { if (gf.GetHTTPFile(remote_path + "/" + file_name) == 0) @@ -1048,8 +1102,26 @@ int main(int argc, char **argv) ROS_ERROR_STREAM("download failure: " << remote_path + "/" + file_name); } } - else + else if (load_mode == LoadMode::DIRECTORY) { + ROS_INFO("Load Mode: Directory"); + // add slash if it doesn't exist + if (map_dir.back() != '/') + { + map_dir.append("/"); + } + + // Add all possible file paths for csv files. + for (auto file_name : file_names) + { + std::string file_path = map_dir; + file_path.append(file_name); + file_paths.push_back(file_path); + } + } + else if (load_mode == LoadMode::FILE) + { + ROS_INFO("Load Mode: File"); for (int i = 1; i < argc; ++i) { std::string file_path(argv[i]); @@ -1067,168 +1139,140 @@ int main(int argc, char **argv) } else if (file_name == "point.csv") { - point_pub.publish(createObjectArray(file_path)); - category |= Category::POINT; + category |= registerVectormapPortion(file_path, &point_pub, "vector_map_info/point", Category::POINT, &nh); } else if (file_name == "vector.csv") { - vector_pub.publish(createObjectArray(file_path)); - category |= Category::VECTOR; + category |= registerVectormapPortion(file_path, &vector_pub, "vector_map_info/vector", Category::VECTOR, &nh); } else if (file_name == "line.csv") { - line_pub.publish(createObjectArray(file_path)); - category |= Category::LINE; + category |= registerVectormapPortion(file_path, &line_pub, "vector_map_info/line", Category::LINE, &nh); } else if (file_name == "area.csv") { - area_pub.publish(createObjectArray(file_path)); - category |= Category::AREA; + category |= registerVectormapPortion(file_path, &area_pub, "vector_map_info/area", Category::AREA, &nh); } else if (file_name == "pole.csv") { - pole_pub.publish(createObjectArray(file_path)); - category |= Category::POLE; + category |= registerVectormapPortion(file_path, &pole_pub, "vector_map_info/pole", Category::POLE, &nh); } else if (file_name == "box.csv") { - box_pub.publish(createObjectArray(file_path)); - category |= Category::BOX; + category |= registerVectormapPortion(file_path, &box_pub, "vector_map_info/box", Category::BOX, &nh); } else if (file_name == "dtlane.csv") { - dtlane_pub.publish(createObjectArray(file_path)); - category |= Category::DTLANE; + category |= registerVectormapPortion(file_path, &dtlane_pub, "vector_map_info/dtlane", Category::DTLANE, &nh); } else if (file_name == "node.csv") { - node_pub.publish(createObjectArray(file_path)); - category |= Category::NODE; + category |= registerVectormapPortion(file_path, &node_pub, "vector_map_info/node", Category::NODE, &nh); } else if (file_name == "lane.csv") { - lane_pub.publish(createObjectArray(file_path)); - category |= Category::LANE; + category |= registerVectormapPortion(file_path, &lane_pub, "vector_map_info/lane", Category::LANE, &nh); } else if (file_name == "wayarea.csv") { - way_area_pub.publish(createObjectArray(file_path)); - category |= Category::WAY_AREA; + category |= registerVectormapPortion(file_path, &way_area_pub, "vector_map_info/way_area", Category::WAY_AREA, &nh); } else if (file_name == "roadedge.csv") { - road_edge_pub.publish(createObjectArray(file_path)); - category |= Category::ROAD_EDGE; + category |= registerVectormapPortion(file_path, &road_edge_pub, "vector_map_info/road_edge", Category::ROAD_EDGE, &nh); } else if (file_name == "gutter.csv") { - gutter_pub.publish(createObjectArray(file_path)); - category |= Category::GUTTER; + category |= registerVectormapPortion(file_path, &gutter_pub, "vector_map_info/gutter", Category::GUTTER, &nh); } else if (file_name == "curb.csv") { - curb_pub.publish(createObjectArray(file_path)); - category |= Category::CURB; + category |= registerVectormapPortion(file_path, &curb_pub, "vector_map_info/curb", Category::CURB, &nh); } else if (file_name == "whiteline.csv") { - white_line_pub.publish(createObjectArray(file_path)); - category |= Category::WHITE_LINE; + category |= registerVectormapPortion(file_path, &white_line_pub, "vector_map_info/white_line", Category::WHITE_LINE, &nh); } else if (file_name == "stopline.csv") { - stop_line_pub.publish(createObjectArray(file_path)); - category |= Category::STOP_LINE; + category |= registerVectormapPortion(file_path, &stop_line_pub, "vector_map_info/stop_line", Category::STOP_LINE, &nh); } else if (file_name == "zebrazone.csv") { - zebra_zone_pub.publish(createObjectArray(file_path)); - category |= Category::ZEBRA_ZONE; + category |= registerVectormapPortion(file_path, &zebra_zone_pub, "vector_map_info/zebra_zone", Category::ZEBRA_ZONE, &nh); } else if (file_name == "crosswalk.csv") { - cross_walk_pub.publish(createObjectArray(file_path)); - category |= Category::CROSS_WALK; + category |= registerVectormapPortion(file_path, &cross_walk_pub, "vector_map_info/cross_walk", Category::CROSS_WALK, &nh); } else if (file_name == "road_surface_mark.csv") { - road_mark_pub.publish(createObjectArray(file_path)); - category |= Category::ROAD_MARK; + category |= registerVectormapPortion(file_path, &road_mark_pub, "vector_map_info/road_mark", Category::ROAD_MARK, &nh); } else if (file_name == "poledata.csv") { - road_pole_pub.publish(createObjectArray(file_path)); - category |= Category::ROAD_POLE; + category |= registerVectormapPortion(file_path, &road_pole_pub, "vector_map_info/road_pole", Category::ROAD_POLE, &nh); } else if (file_name == "roadsign.csv") { - road_sign_pub.publish(createObjectArray(file_path)); - category |= Category::ROAD_SIGN; + category |= registerVectormapPortion(file_path, &road_sign_pub, "vector_map_info/road_sign", Category::ROAD_SIGN, &nh); } else if (file_name == "signaldata.csv") { - signal_pub.publish(createObjectArray(file_path)); - category |= Category::SIGNAL; + category |= registerVectormapPortion(file_path, &signal_pub, "vector_map_info/signal", Category::SIGNAL, &nh); } else if (file_name == "streetlight.csv") { - street_light_pub.publish(createObjectArray(file_path)); - category |= Category::STREET_LIGHT; + category |= registerVectormapPortion(file_path, &street_light_pub, "vector_map_info/street_light", Category::STREET_LIGHT, &nh); } else if (file_name == "utilitypole.csv") { - utility_pole_pub.publish(createObjectArray(file_path)); - category |= Category::UTILITY_POLE; + category |= registerVectormapPortion(file_path, &utility_pole_pub, "vector_map_info/utility_pole", Category::UTILITY_POLE, &nh); } else if (file_name == "guardrail.csv") { - guard_rail_pub.publish(createObjectArray(file_path)); - category |= Category::GUARD_RAIL; + category |= registerVectormapPortion(file_path, &guard_rail_pub, "vector_map_info/guard_rail", Category::GUARD_RAIL, &nh); } else if (file_name == "sidewalk.csv") { - side_walk_pub.publish(createObjectArray(file_path)); - category |= Category::SIDE_WALK; + category |= registerVectormapPortion(file_path, &side_walk_pub, "vector_map_info/side_walk", Category::SIDE_WALK, &nh); } else if (file_name == "driveon_portion.csv") { - drive_on_portion_pub.publish(createObjectArray(file_path)); - category |= Category::DRIVE_ON_PORTION; + category |= registerVectormapPortion(file_path, &drive_on_portion_pub, "vector_map_info/drive_on_portion", Category::DRIVE_ON_PORTION, &nh); } else if (file_name == "intersection.csv") { - cross_road_pub.publish(createObjectArray(file_path)); - category |= Category::CROSS_ROAD; + category |= registerVectormapPortion(file_path, &cross_road_pub, "vector_map_info/cross_road", Category::CROSS_ROAD, &nh); } else if (file_name == "sidestrip.csv") { - side_strip_pub.publish(createObjectArray(file_path)); - category |= Category::SIDE_STRIP; + category |= registerVectormapPortion(file_path, &side_strip_pub, "vector_map_info/side_strip", Category::SIDE_STRIP, &nh); } else if (file_name == "curvemirror.csv") { - curve_mirror_pub.publish(createObjectArray(file_path)); - category |= Category::CURVE_MIRROR; + category |= registerVectormapPortion(file_path, &curve_mirror_pub, "vector_map_info/curve_mirror", Category::CURVE_MIRROR, &nh); } else if (file_name == "wall.csv") { - wall_pub.publish(createObjectArray(file_path)); - category |= Category::WALL; + category |= registerVectormapPortion(file_path, &wall_pub, "vector_map_info/wall", Category::WALL, &nh); } else if (file_name == "fence.csv") { - fence_pub.publish(createObjectArray(file_path)); - category |= Category::FENCE; + category |= registerVectormapPortion(file_path, &fence_pub, "vector_map_info/fence", Category::FENCE, &nh); } else if (file_name == "railroad_crossing.csv") { - rail_crossing_pub.publish(createObjectArray(file_path)); - category |= Category::RAIL_CROSSING; + category |= registerVectormapPortion(file_path, &rail_crossing_pub, "vector_map_info/rail_crossing", Category::RAIL_CROSSING, &nh); } else + { ROS_ERROR_STREAM("unknown csv file: " << file_path); + } } + ROS_INFO("Published vector_map_info topics"); + VectorMap vmap; vmap.subscribe(nh, category); @@ -1257,6 +1301,7 @@ int main(int argc, char **argv) insertMarkerArray(marker_array, createFenceMarkerArray(vmap, Color::LIGHT_RED)); insertMarkerArray(marker_array, createRailCrossingMarkerArray(vmap, Color::LIGHT_MAGENTA)); marker_array_pub.publish(marker_array); + ROS_INFO("Published vector_map visualization"); stat.data = true; stat_pub.publish(stat); diff --git a/common/map_file/package.xml b/common/map_file/package.xml index c8127a2e446..33eccff3691 100644 --- a/common/map_file/package.xml +++ b/common/map_file/package.xml @@ -22,5 +22,6 @@ vector_map visualization_msgs lanelet2_extension + libboost-filesystem-dev diff --git a/common/op_planner/CMakeLists.txt b/common/op_planner/CMakeLists.txt index e6538881aeb..782f89bbdc1 100644 --- a/common/op_planner/CMakeLists.txt +++ b/common/op_planner/CMakeLists.txt @@ -3,16 +3,14 @@ cmake_minimum_required(VERSION 2.8.3) project(op_planner) find_package(autoware_build_flags REQUIRED) + find_package(catkin REQUIRED COMPONENTS - cmake_modules - op_utility + cmake_modules + op_utility ) find_package(TinyXML REQUIRED) -################################### -## catkin specific configuration ## -################################### catkin_package( INCLUDE_DIRS include LIBRARIES op_planner @@ -26,53 +24,59 @@ catkin_package( include_directories( include ${catkin_INCLUDE_DIRS} - ${TinyXML_INCLUDE_DIRS} + ${TinyXML_INCLUDE_DIRS} ) set(PLANNERH_SRC - src/BehaviorPrediction.cpp - src/BehaviorPrediction.cpp - src/BehaviorPrediction.cpp - src/BehaviorPrediction.cpp - src/BehaviorPrediction.cpp - src/BehaviorStateMachine.cpp - src/DecisionMaker.cpp - src/LocalPlannerH.cpp - src/MappingHelpers.cpp - src/MatrixOperations.cpp - src/PassiveDecisionMaker.cpp - src/PlannerH.cpp - src/PlannerH.cpp - src/PlannerH.cpp - src/PlannerH.cpp - src/PlannerH.cpp - src/PlanningHelpers.cpp - src/PlanningHelpers.cpp - src/PlanningHelpers.cpp - src/PlanningHelpers.cpp - src/PlanningHelpers.cpp - src/SimuDecisionMaker.cpp - src/TrajectoryCosts.cpp - src/TrajectoryDynamicCosts.cpp + src/BehaviorPrediction.cpp + src/BehaviorPrediction.cpp + src/BehaviorPrediction.cpp + src/BehaviorPrediction.cpp + src/BehaviorPrediction.cpp + src/BehaviorStateMachine.cpp + src/DecisionMaker.cpp + src/LocalPlannerH.cpp + src/MappingHelpers.cpp + src/MatrixOperations.cpp + src/PassiveDecisionMaker.cpp + src/PlannerH.cpp + src/PlannerH.cpp + src/PlannerH.cpp + src/PlannerH.cpp + src/PlannerH.cpp + src/PlanningHelpers.cpp + src/PlanningHelpers.cpp + src/PlanningHelpers.cpp + src/PlanningHelpers.cpp + src/PlanningHelpers.cpp + src/SimuDecisionMaker.cpp + src/TrajectoryCosts.cpp + src/TrajectoryDynamicCosts.cpp ) ## Declare a cpp library add_library(${PROJECT_NAME} - ${PLANNERH_SRC} + ${PLANNERH_SRC} ) target_link_libraries(${PROJECT_NAME} - ${catkin_LIBRARIES} - ${TinyXML_LIBRARIES} + ${catkin_LIBRARIES} + ${TinyXML_LIBRARIES} ) install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" ) install(TARGETS op_planner - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) + +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + catkin_add_gtest(test-op_planner test/src/test_BuildPlanningSearchTreeV2.cpp) + target_link_libraries(test-op_planner ${catkin_LIBRARIES} ${PROJECT_NAME}) +endif() diff --git a/common/op_planner/include/op_planner/BehaviorPrediction.h b/common/op_planner/include/op_planner/BehaviorPrediction.h index 302f20aab1d..12d1fd7b1c7 100644 --- a/common/op_planner/include/op_planner/BehaviorPrediction.h +++ b/common/op_planner/include/op_planner/BehaviorPrediction.h @@ -60,819 +60,819 @@ class TrajectoryTracker; class Particle { public: - bool bDeleted; - BEH_STATE_TYPE beh; //[Stop, Yielding, Forward, Branching] - double vel; //[0 -> Stop,1 -> moving] - double vel_prev_big; - double prev_time_diff; - int acc; //[-1 ->Slowing, 0, Stopping, 1 -> accelerating] - double acc_raw; - int indicator; //[0 -> No, 1 -> Left, 2 -> Right , 3 -> both] - WayPoint pose; - bool bStopLine; - double w; - double w_raw; - double pose_w; - double dir_w; - double vel_w; - double acl_w; - double ind_w; - TrajectoryTracker* pTraj; - int original_index; - - Particle() - { - prev_time_diff = 0; - vel_prev_big = 0; - original_index = 0; - bStopLine = false; - bDeleted = false; - pTraj = nullptr; - w = 0; - w_raw = 0; - pose_w = 0; - dir_w = 0; - vel_w = 0; - acl_w = 0; - ind_w = 0; - beh = BEH_STOPPING_STATE; - vel = 0; - acc = 0; - acc_raw = 0; - indicator = 0; - } + bool bDeleted; + BEH_STATE_TYPE beh; //[Stop, Yielding, Forward, Branching] + double vel; //[0 -> Stop,1 -> moving] + double vel_prev_big; + double prev_time_diff; + int acc; //[-1 ->Slowing, 0, Stopping, 1 -> accelerating] + double acc_raw; + int indicator; //[0 -> No, 1 -> Left, 2 -> Right , 3 -> both] + WayPoint pose; + bool bStopLine; + double w; + double w_raw; + double pose_w; + double dir_w; + double vel_w; + double acl_w; + double ind_w; + TrajectoryTracker* pTraj; + int original_index; + + Particle() + { + prev_time_diff = 0; + vel_prev_big = 0; + original_index = 0; + bStopLine = false; + bDeleted = false; + pTraj = nullptr; + w = 0; + w_raw = 0; + pose_w = 0; + dir_w = 0; + vel_w = 0; + acl_w = 0; + ind_w = 0; + beh = BEH_STOPPING_STATE; + vel = 0; + acc = 0; + acc_raw = 0; + indicator = 0; + } }; class TrajectoryTracker { public: - unsigned int index; - BEH_STATE_TYPE beh; - BEH_STATE_TYPE best_beh; - double best_p; - std::vector ids; - std::vector path_ids; - WayPoint path_last_pose; - double rms_error; - std::vector trajectory; - - std::vector m_ForwardPart; - std::vector m_StopPart; - std::vector m_YieldPart; - std::vector m_LeftPart; - std::vector m_RightPart; - BehaviorState m_CurrBehavior; - - int nAliveStop; - int nAliveYield; - int nAliveForward; - int nAliveLeft; - int nAliveRight; - - double pStop; - double pYield; - double pForward; - double pLeft; - double pRight; - - double w_avg_forward; - double w_avg_stop; - double w_avg_yield; - double w_avg_left; - double w_avg_right; - - PassiveDecisionMaker m_SinglePathDecisionMaker; - - TrajectoryTracker() - { - beh = BEH_STOPPING_STATE; - rms_error = 0; - index = 0; - nAliveStop = 0; - nAliveYield = 0; - nAliveForward = 0; - nAliveLeft = 0; - nAliveRight = 0; - - pStop = 0; - pYield = 0; - pForward = 0; - pLeft = 0; - pRight = 0; - best_beh = PlannerHNS::BEH_STOPPING_STATE; - best_p = 0; - - w_avg_forward = 0; - w_avg_stop = 0; - w_avg_yield = 0; - w_avg_left = 0; - w_avg_right = 0; - } - - virtual ~TrajectoryTracker() - { - } - - void InitDecision() - { - } - - TrajectoryTracker(const TrajectoryTracker& obj) - { - - rms_error = 0; - ids = obj.ids; - path_ids = obj.path_ids; - path_last_pose = obj.path_last_pose; - beh = obj.beh; - index = obj.index; - trajectory = obj.trajectory; - nAliveStop = obj.nAliveStop; - nAliveYield = obj.nAliveYield; - nAliveForward = obj.nAliveForward; - nAliveLeft = obj.nAliveLeft; - nAliveRight = obj.nAliveRight; - - pStop = obj.pStop; - pYield = obj.pYield; - pForward = obj.pForward; - pLeft = obj.pLeft; - pRight = obj.pRight; - best_beh = obj.best_beh; - best_p = obj.best_p; - m_SinglePathDecisionMaker = obj.m_SinglePathDecisionMaker; - - m_ForwardPart = obj.m_ForwardPart; - m_StopPart = obj.m_StopPart; - m_YieldPart = obj.m_YieldPart; - m_LeftPart = obj.m_LeftPart; - m_RightPart = obj.m_RightPart; - m_CurrBehavior = obj.m_CurrBehavior; - - w_avg_forward = obj.w_avg_forward; - w_avg_stop = obj.w_avg_stop; - w_avg_yield = obj.w_avg_yield; - w_avg_left = obj.w_avg_left; - w_avg_right = obj.w_avg_right; - } - - TrajectoryTracker(std::vector& path, const unsigned int& _index) - { - - if(path.size()>0) - { - beh = path.at(0).beh_state; - //std::cout << "New Path: Beh: " << beh << ", index: " << _index << ", LaneID_0: " << path.at(0).laneId << ", LaneID_1: "<< path.at(1).laneId << std::endl; - } - - index = _index; - trajectory = path; - int prev_id = -10; - int curr_id = -10; - ids.clear(); - path_ids.clear(); - for(unsigned int i = 0; i < path.size(); i++) - { - curr_id = path.at(i).laneId; - path_ids.push_back(curr_id); - - if(curr_id != prev_id) - { - ids.push_back(curr_id); - prev_id = curr_id; - } - } - - path_last_pose = path.at(path.size()-1); - - nAliveStop = 0; - nAliveYield = 0; - nAliveForward = 0; - nAliveLeft = 0; - nAliveRight = 0; - - pStop = 0; - pYield = 0; - pForward = 0; - pLeft = 0; - pRight = 0; - best_beh = PlannerHNS::BEH_STOPPING_STATE; - best_p = 0; - - InitDecision(); - } - - void UpdatePathAndIndex(std::vector& _path, const unsigned int& _index) - { - if(_path.size() == 0) return; - - beh = _path.at(0).beh_state; - index = _index; - trajectory = _path; - int prev_id = -10; - int curr_id = -10; - ids.clear(); - path_ids.clear(); - for(unsigned int i = 0; i < _path.size(); i++) - { - curr_id = _path.at(i).laneId; - path_ids.push_back(curr_id); - if(curr_id != prev_id) - { - ids.push_back(curr_id); - prev_id = curr_id; - } - } - - path_last_pose = _path.at(_path.size()-1); - } - - double CalcMatchingPercentage(const std::vector& _path) - { - if(_path.size() == 0) return 0; - - if(beh != _path.at(0).beh_state) return 0; - - int nCount = 0, nIds = 0; - int prev_id = -10; - int curr_id = -10; - std::vector _ids; - - for(unsigned int i = 0; i < _path.size(); i++) - { - curr_id = _path.at(i).laneId; - if(i < path_ids.size()) - { - nCount++; - if(curr_id == path_ids.at(i)) - nIds++; - } - - if(curr_id != prev_id) - { - _ids.push_back(curr_id); - prev_id = curr_id; - } - } - - int nEqualities = 0; - for(unsigned int i=0; i < _ids.size(); i++) - { - for(unsigned int j=0; j < ids.size(); j++) - { - if(_ids.at(i) == ids.at(j)) - { - nEqualities++; - break; - } - } - } - - double rms_val = 0; - for(unsigned int i=0; i < _path.size(); i++) - { - if(i < trajectory.size()) - { - rms_val += hypot(_path.at(i).pos.y - trajectory.at(i).pos.y, _path.at(i).pos.y - trajectory.at(i).pos.y); - } - } - - rms_error = rms_val; - - if(rms_error < 5.0) - return 1; - - if(_ids.size() == ids.size() && ids.size() == nEqualities && rms_error < 5.0) // perfect match - return 1; - - WayPoint curr_last_pose = _path.at(_path.size()-1); - double nMatch = (double)nIds/(double)nCount; - double _d = hypot(path_last_pose.pos.y-curr_last_pose.pos.y, path_last_pose.pos.x-curr_last_pose.pos.x); - - double dCost = _d/FIXED_PLANNING_DISTANCE; - if(dCost > 1.0) - dCost = 1.0; - double dMatch = 1.0 - dCost; - - double _a_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(path_last_pose.pos.a, curr_last_pose.pos.a); - double aCost = _a_diff/M_PI; - if(aCost > 1.0) - aCost = 1.0; - double aMatch = 1.0 - aCost; - - double totalMatch = (nMatch + dMatch + aMatch)/3.0; - - return totalMatch; - } - - void InsertNewParticle(const Particle& p) - { - if(p.beh == PlannerHNS::BEH_STOPPING_STATE && nAliveStop < BEH_PARTICLES_NUM) - { - m_StopPart.push_back(p); - m_StopPart.at(m_StopPart.size()-1).pTraj = this; - nAliveStop++; - } - else if(p.beh == PlannerHNS::BEH_YIELDING_STATE && nAliveYield < BEH_PARTICLES_NUM) - { - m_YieldPart.push_back(p); - m_YieldPart.at(m_YieldPart.size()-1).pTraj = this; - nAliveYield++; - } - else if(p.beh == PlannerHNS::BEH_FORWARD_STATE && nAliveForward < BEH_PARTICLES_NUM) - { - m_ForwardPart.push_back(p); - m_ForwardPart.at(m_ForwardPart.size()-1).pTraj = this; - nAliveForward++; - } - else if(p.beh == PlannerHNS::BEH_BRANCH_LEFT_STATE && nAliveLeft < BEH_PARTICLES_NUM) - { - m_LeftPart.push_back(p); - m_LeftPart.at(m_LeftPart.size()-1).pTraj = this; - nAliveLeft++; - } - else if(p.beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE && nAliveRight < BEH_PARTICLES_NUM) - { - m_RightPart.push_back(p); - m_RightPart.at(m_RightPart.size()-1).pTraj = this; - nAliveRight++; - } - } - - void DeleteParticle(const Particle& p, const int& _i) - { - if(p.beh == PlannerHNS::BEH_STOPPING_STATE && nAliveStop > BEH_MIN_PARTICLE_NUM) - { - m_StopPart.erase(m_StopPart.begin()+_i); - nAliveStop--; - } - else if(p.beh == PlannerHNS::BEH_YIELDING_STATE && nAliveYield > BEH_MIN_PARTICLE_NUM) - { - m_YieldPart.erase(m_YieldPart.begin()+_i); - nAliveYield--; - } - else if(p.beh == PlannerHNS::BEH_FORWARD_STATE && nAliveForward > BEH_MIN_PARTICLE_NUM) - { - m_ForwardPart.erase(m_ForwardPart.begin()+_i); - nAliveForward--; - } - else if(p.beh == PlannerHNS::BEH_BRANCH_LEFT_STATE && nAliveLeft > BEH_MIN_PARTICLE_NUM) - { - m_LeftPart.erase(m_LeftPart.begin()+_i); - nAliveLeft--; - } - else if(p.beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE && nAliveRight > BEH_MIN_PARTICLE_NUM) - { - m_RightPart.erase(m_RightPart.begin()+_i); - nAliveRight--; - } - } - - void CalcAverages() - { - w_avg_forward = 0; - double avg_sum = 0; - for(unsigned int i = 0; i < m_ForwardPart.size(); i++) - { - avg_sum += m_ForwardPart.at(i).w; - } - if(m_ForwardPart.size() > 0) - w_avg_forward = avg_sum/(double)m_ForwardPart.size(); - - w_avg_left = 0; - avg_sum = 0; - for(unsigned int i = 0; i < m_LeftPart.size(); i++) - { - avg_sum += m_LeftPart.at(i).w; - } - if(m_LeftPart.size() > 0) - w_avg_left = avg_sum/(double)m_LeftPart.size(); - - w_avg_right = 0; - avg_sum = 0; - for(unsigned int i = 0; i < m_RightPart.size(); i++) - { - avg_sum += m_RightPart.at(i).w; - } - if(m_RightPart.size() > 0) - w_avg_right = avg_sum/(double)m_RightPart.size(); - - w_avg_stop = 0; - avg_sum = 0; - for(unsigned int i = 0; i < m_StopPart.size(); i++) - { - avg_sum += m_StopPart.at(i).w; - } - if(m_StopPart.size() > 0) - w_avg_stop = avg_sum/(double)m_StopPart.size(); - - w_avg_yield = 0; - avg_sum = 0; - for(unsigned int i = 0; i < m_YieldPart.size(); i++) - { - avg_sum += m_YieldPart.at(i).w; - } - if(m_YieldPart.size() > 0) - w_avg_yield = avg_sum/(double)m_YieldPart.size(); - } - - void CalcProbabilities() - { - best_beh = PlannerHNS::BEH_STOPPING_STATE; - pStop = (double)nAliveStop/(double)BEH_PARTICLES_NUM; - best_p = pStop; - - pYield = (double)nAliveYield/(double)BEH_PARTICLES_NUM; - if(pYield > best_p) - { - best_p = pYield; - best_beh = PlannerHNS::BEH_YIELDING_STATE; - } - - pForward = (double)nAliveForward/(double)BEH_PARTICLES_NUM; - if(pForward > best_p) - { - best_p = pForward; - best_beh = PlannerHNS::BEH_FORWARD_STATE; - } - - pLeft = (double)nAliveLeft/(double)BEH_PARTICLES_NUM; - if(pLeft > best_p) - { - best_p = pLeft; - best_beh = PlannerHNS::BEH_BRANCH_LEFT_STATE; - } - - pRight = (double)nAliveRight/(double)BEH_PARTICLES_NUM; - if(pRight > best_p) - { - best_p = pRight; - best_beh = PlannerHNS::BEH_BRANCH_RIGHT_STATE; - } - } + unsigned int index; + BEH_STATE_TYPE beh; + BEH_STATE_TYPE best_beh; + double best_p; + std::vector ids; + std::vector path_ids; + WayPoint path_last_pose; + double rms_error; + std::vector trajectory; + + std::vector m_ForwardPart; + std::vector m_StopPart; + std::vector m_YieldPart; + std::vector m_LeftPart; + std::vector m_RightPart; + BehaviorState m_CurrBehavior; + + int nAliveStop; + int nAliveYield; + int nAliveForward; + int nAliveLeft; + int nAliveRight; + + double pStop; + double pYield; + double pForward; + double pLeft; + double pRight; + + double w_avg_forward; + double w_avg_stop; + double w_avg_yield; + double w_avg_left; + double w_avg_right; + + PassiveDecisionMaker m_SinglePathDecisionMaker; + + TrajectoryTracker() + { + beh = BEH_STOPPING_STATE; + rms_error = 0; + index = 0; + nAliveStop = 0; + nAliveYield = 0; + nAliveForward = 0; + nAliveLeft = 0; + nAliveRight = 0; + + pStop = 0; + pYield = 0; + pForward = 0; + pLeft = 0; + pRight = 0; + best_beh = PlannerHNS::BEH_STOPPING_STATE; + best_p = 0; + + w_avg_forward = 0; + w_avg_stop = 0; + w_avg_yield = 0; + w_avg_left = 0; + w_avg_right = 0; + } + + virtual ~TrajectoryTracker() + { + } + + void InitDecision() + { + } + + TrajectoryTracker(const TrajectoryTracker& obj) + { + + rms_error = 0; + ids = obj.ids; + path_ids = obj.path_ids; + path_last_pose = obj.path_last_pose; + beh = obj.beh; + index = obj.index; + trajectory = obj.trajectory; + nAliveStop = obj.nAliveStop; + nAliveYield = obj.nAliveYield; + nAliveForward = obj.nAliveForward; + nAliveLeft = obj.nAliveLeft; + nAliveRight = obj.nAliveRight; + + pStop = obj.pStop; + pYield = obj.pYield; + pForward = obj.pForward; + pLeft = obj.pLeft; + pRight = obj.pRight; + best_beh = obj.best_beh; + best_p = obj.best_p; + m_SinglePathDecisionMaker = obj.m_SinglePathDecisionMaker; + + m_ForwardPart = obj.m_ForwardPart; + m_StopPart = obj.m_StopPart; + m_YieldPart = obj.m_YieldPart; + m_LeftPart = obj.m_LeftPart; + m_RightPart = obj.m_RightPart; + m_CurrBehavior = obj.m_CurrBehavior; + + w_avg_forward = obj.w_avg_forward; + w_avg_stop = obj.w_avg_stop; + w_avg_yield = obj.w_avg_yield; + w_avg_left = obj.w_avg_left; + w_avg_right = obj.w_avg_right; + } + + TrajectoryTracker(std::vector& path, const unsigned int& _index) + { + + if(path.size()>0) + { + beh = path.at(0).beh_state; + //std::cout << "New Path: Beh: " << beh << ", index: " << _index << ", LaneID_0: " << path.at(0).laneId << ", LaneID_1: "<< path.at(1).laneId << std::endl; + } + + index = _index; + trajectory = path; + int prev_id = -10; + int curr_id = -10; + ids.clear(); + path_ids.clear(); + for(unsigned int i = 0; i < path.size(); i++) + { + curr_id = path.at(i).laneId; + path_ids.push_back(curr_id); + + if(curr_id != prev_id) + { + ids.push_back(curr_id); + prev_id = curr_id; + } + } + + path_last_pose = path.at(path.size()-1); + + nAliveStop = 0; + nAliveYield = 0; + nAliveForward = 0; + nAliveLeft = 0; + nAliveRight = 0; + + pStop = 0; + pYield = 0; + pForward = 0; + pLeft = 0; + pRight = 0; + best_beh = PlannerHNS::BEH_STOPPING_STATE; + best_p = 0; + + InitDecision(); + } + + void UpdatePathAndIndex(std::vector& _path, const unsigned int& _index) + { + if(_path.size() == 0) return; + + beh = _path.at(0).beh_state; + index = _index; + trajectory = _path; + int prev_id = -10; + int curr_id = -10; + ids.clear(); + path_ids.clear(); + for(unsigned int i = 0; i < _path.size(); i++) + { + curr_id = _path.at(i).laneId; + path_ids.push_back(curr_id); + if(curr_id != prev_id) + { + ids.push_back(curr_id); + prev_id = curr_id; + } + } + + path_last_pose = _path.at(_path.size()-1); + } + + double CalcMatchingPercentage(const std::vector& _path) + { + if(_path.size() == 0) return 0; + + if(beh != _path.at(0).beh_state) return 0; + + int nCount = 0, nIds = 0; + int prev_id = -10; + int curr_id = -10; + std::vector _ids; + + for(unsigned int i = 0; i < _path.size(); i++) + { + curr_id = _path.at(i).laneId; + if(i < path_ids.size()) + { + nCount++; + if(curr_id == path_ids.at(i)) + nIds++; + } + + if(curr_id != prev_id) + { + _ids.push_back(curr_id); + prev_id = curr_id; + } + } + + int nEqualities = 0; + for(unsigned int i=0; i < _ids.size(); i++) + { + for(unsigned int j=0; j < ids.size(); j++) + { + if(_ids.at(i) == ids.at(j)) + { + nEqualities++; + break; + } + } + } + + double rms_val = 0; + for(unsigned int i=0; i < _path.size(); i++) + { + if(i < trajectory.size()) + { + rms_val += hypot(_path.at(i).pos.y - trajectory.at(i).pos.y, _path.at(i).pos.y - trajectory.at(i).pos.y); + } + } + + rms_error = rms_val; + + if(rms_error < 5.0) + return 1; + + if(_ids.size() == ids.size() && ids.size() == nEqualities && rms_error < 5.0) // perfect match + return 1; + + WayPoint curr_last_pose = _path.at(_path.size()-1); + double nMatch = (double)nIds/(double)nCount; + double _d = hypot(path_last_pose.pos.y-curr_last_pose.pos.y, path_last_pose.pos.x-curr_last_pose.pos.x); + + double dCost = _d/FIXED_PLANNING_DISTANCE; + if(dCost > 1.0) + dCost = 1.0; + double dMatch = 1.0 - dCost; + + double _a_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(path_last_pose.pos.a, curr_last_pose.pos.a); + double aCost = _a_diff/M_PI; + if(aCost > 1.0) + aCost = 1.0; + double aMatch = 1.0 - aCost; + + double totalMatch = (nMatch + dMatch + aMatch)/3.0; + + return totalMatch; + } + + void InsertNewParticle(const Particle& p) + { + if(p.beh == PlannerHNS::BEH_STOPPING_STATE && nAliveStop < BEH_PARTICLES_NUM) + { + m_StopPart.push_back(p); + m_StopPart.at(m_StopPart.size()-1).pTraj = this; + nAliveStop++; + } + else if(p.beh == PlannerHNS::BEH_YIELDING_STATE && nAliveYield < BEH_PARTICLES_NUM) + { + m_YieldPart.push_back(p); + m_YieldPart.at(m_YieldPart.size()-1).pTraj = this; + nAliveYield++; + } + else if(p.beh == PlannerHNS::BEH_FORWARD_STATE && nAliveForward < BEH_PARTICLES_NUM) + { + m_ForwardPart.push_back(p); + m_ForwardPart.at(m_ForwardPart.size()-1).pTraj = this; + nAliveForward++; + } + else if(p.beh == PlannerHNS::BEH_BRANCH_LEFT_STATE && nAliveLeft < BEH_PARTICLES_NUM) + { + m_LeftPart.push_back(p); + m_LeftPart.at(m_LeftPart.size()-1).pTraj = this; + nAliveLeft++; + } + else if(p.beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE && nAliveRight < BEH_PARTICLES_NUM) + { + m_RightPart.push_back(p); + m_RightPart.at(m_RightPart.size()-1).pTraj = this; + nAliveRight++; + } + } + + void DeleteParticle(const Particle& p, const int& _i) + { + if(p.beh == PlannerHNS::BEH_STOPPING_STATE && nAliveStop > BEH_MIN_PARTICLE_NUM) + { + m_StopPart.erase(m_StopPart.begin()+_i); + nAliveStop--; + } + else if(p.beh == PlannerHNS::BEH_YIELDING_STATE && nAliveYield > BEH_MIN_PARTICLE_NUM) + { + m_YieldPart.erase(m_YieldPart.begin()+_i); + nAliveYield--; + } + else if(p.beh == PlannerHNS::BEH_FORWARD_STATE && nAliveForward > BEH_MIN_PARTICLE_NUM) + { + m_ForwardPart.erase(m_ForwardPart.begin()+_i); + nAliveForward--; + } + else if(p.beh == PlannerHNS::BEH_BRANCH_LEFT_STATE && nAliveLeft > BEH_MIN_PARTICLE_NUM) + { + m_LeftPart.erase(m_LeftPart.begin()+_i); + nAliveLeft--; + } + else if(p.beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE && nAliveRight > BEH_MIN_PARTICLE_NUM) + { + m_RightPart.erase(m_RightPart.begin()+_i); + nAliveRight--; + } + } + + void CalcAverages() + { + w_avg_forward = 0; + double avg_sum = 0; + for(unsigned int i = 0; i < m_ForwardPart.size(); i++) + { + avg_sum += m_ForwardPart.at(i).w; + } + if(m_ForwardPart.size() > 0) + w_avg_forward = avg_sum/(double)m_ForwardPart.size(); + + w_avg_left = 0; + avg_sum = 0; + for(unsigned int i = 0; i < m_LeftPart.size(); i++) + { + avg_sum += m_LeftPart.at(i).w; + } + if(m_LeftPart.size() > 0) + w_avg_left = avg_sum/(double)m_LeftPart.size(); + + w_avg_right = 0; + avg_sum = 0; + for(unsigned int i = 0; i < m_RightPart.size(); i++) + { + avg_sum += m_RightPart.at(i).w; + } + if(m_RightPart.size() > 0) + w_avg_right = avg_sum/(double)m_RightPart.size(); + + w_avg_stop = 0; + avg_sum = 0; + for(unsigned int i = 0; i < m_StopPart.size(); i++) + { + avg_sum += m_StopPart.at(i).w; + } + if(m_StopPart.size() > 0) + w_avg_stop = avg_sum/(double)m_StopPart.size(); + + w_avg_yield = 0; + avg_sum = 0; + for(unsigned int i = 0; i < m_YieldPart.size(); i++) + { + avg_sum += m_YieldPart.at(i).w; + } + if(m_YieldPart.size() > 0) + w_avg_yield = avg_sum/(double)m_YieldPart.size(); + } + + void CalcProbabilities() + { + best_beh = PlannerHNS::BEH_STOPPING_STATE; + pStop = (double)nAliveStop/(double)BEH_PARTICLES_NUM; + best_p = pStop; + + pYield = (double)nAliveYield/(double)BEH_PARTICLES_NUM; + if(pYield > best_p) + { + best_p = pYield; + best_beh = PlannerHNS::BEH_YIELDING_STATE; + } + + pForward = (double)nAliveForward/(double)BEH_PARTICLES_NUM; + if(pForward > best_p) + { + best_p = pForward; + best_beh = PlannerHNS::BEH_FORWARD_STATE; + } + + pLeft = (double)nAliveLeft/(double)BEH_PARTICLES_NUM; + if(pLeft > best_p) + { + best_p = pLeft; + best_beh = PlannerHNS::BEH_BRANCH_LEFT_STATE; + } + + pRight = (double)nAliveRight/(double)BEH_PARTICLES_NUM; + if(pRight > best_p) + { + best_p = pRight; + best_beh = PlannerHNS::BEH_BRANCH_RIGHT_STATE; + } + } }; class ObjParticles { public: - DetectedObject obj; - std::vector m_TrajectoryTracker; - std::vector m_TrajectoryTracker_temp; - - std::vector m_AllParticles; - - TrajectoryTracker* best_beh_track; - int i_best_track; - - PlannerHNS::BehaviorState m_beh; - double m_PredictionTime; - - double all_w; - double max_w; - double min_w; - double max_w_raw; - double min_w_raw; - double avg_w; - double pose_w_t; - double dir_w_t; - double vel_w_t; - double acl_w_t; - double ind_w_t; - - double pose_w_max; - double dir_w_max; - double vel_w_max; - double acl_w_max; - double ind_w_max; - - double pose_w_min; - double dir_w_min; - double vel_w_min; - double acl_w_min; - double ind_w_min; - - int n_stop; - int n_yield; - int n_left_branch; - int n_right_branch; - - double p_stop; - double p_yield; - double p_left_branch; - double p_right_branch; - - virtual ~ObjParticles() - { - DeleteTheRest(m_TrajectoryTracker); - m_TrajectoryTracker_temp.clear(); - } - - ObjParticles() - { - m_PredictionTime = 0; - best_beh_track = nullptr; - i_best_track = -1; - all_w = 0; - pose_w_t = 0; - dir_w_t = 0; - vel_w_t = 0; - acl_w_t = 0; - ind_w_t = 0; - max_w = DBL_MIN; - min_w = DBL_MAX; - max_w_raw = DBL_MIN; - min_w_raw = DBL_MAX; - avg_w = 0; - - pose_w_max = -999999; - dir_w_max=-999999; - vel_w_max=-999999; - acl_w_max=-999999; - ind_w_max=-999999; - - pose_w_min=999999; - dir_w_min=999999; - vel_w_min=999999; - acl_w_min=999999; - ind_w_min=999999; - - n_stop = 0; - n_yield = 0; - n_left_branch = 0; - n_right_branch = 0; - - p_stop = 0; - p_yield = 0; - p_left_branch = 0; - p_right_branch = 0; - } - -// void CalculateProbabilities() -// { -// for(unsigned int i = 0; i < m_TrajectoryTracker.size(); i++) -// { -// m_TrajectoryTracker.at(i)->CalcProbabilities(); -// } + DetectedObject obj; + std::vector m_TrajectoryTracker; + std::vector m_TrajectoryTracker_temp; + + std::vector m_AllParticles; + + TrajectoryTracker* best_beh_track; + int i_best_track; + + PlannerHNS::BehaviorState m_beh; + double m_PredictionTime; + + double all_w; + double max_w; + double min_w; + double max_w_raw; + double min_w_raw; + double avg_w; + double pose_w_t; + double dir_w_t; + double vel_w_t; + double acl_w_t; + double ind_w_t; + + double pose_w_max; + double dir_w_max; + double vel_w_max; + double acl_w_max; + double ind_w_max; + + double pose_w_min; + double dir_w_min; + double vel_w_min; + double acl_w_min; + double ind_w_min; + + int n_stop; + int n_yield; + int n_left_branch; + int n_right_branch; + + double p_stop; + double p_yield; + double p_left_branch; + double p_right_branch; + + virtual ~ObjParticles() + { + DeleteTheRest(m_TrajectoryTracker); + m_TrajectoryTracker_temp.clear(); + } + + ObjParticles() + { + m_PredictionTime = 0; + best_beh_track = nullptr; + i_best_track = -1; + all_w = 0; + pose_w_t = 0; + dir_w_t = 0; + vel_w_t = 0; + acl_w_t = 0; + ind_w_t = 0; + max_w = DBL_MIN; + min_w = DBL_MAX; + max_w_raw = DBL_MIN; + min_w_raw = DBL_MAX; + avg_w = 0; + + pose_w_max = -999999; + dir_w_max=-999999; + vel_w_max=-999999; + acl_w_max=-999999; + ind_w_max=-999999; + + pose_w_min=999999; + dir_w_min=999999; + vel_w_min=999999; + acl_w_min=999999; + ind_w_min=999999; + + n_stop = 0; + n_yield = 0; + n_left_branch = 0; + n_right_branch = 0; + + p_stop = 0; + p_yield = 0; + p_left_branch = 0; + p_right_branch = 0; + } + +// void CalculateProbabilities() +// { +// for(unsigned int i = 0; i < m_TrajectoryTracker.size(); i++) +// { +// m_TrajectoryTracker.at(i)->CalcProbabilities(); +// } // -// if(m_TrajectoryTracker.size() > 0) -// { -// best_beh_track = m_TrajectoryTracker.at(0); -// i_best_track = 0; -// } +// if(m_TrajectoryTracker.size() > 0) +// { +// best_beh_track = m_TrajectoryTracker.at(0); +// i_best_track = 0; +// } // -// for(unsigned int i = 1; i < m_TrajectoryTracker.size(); i++) -// { -// if(m_TrajectoryTracker.at(i)->best_p > best_beh_track->best_p) -// { -// best_beh_track = m_TrajectoryTracker.at(i); -// i_best_track = i; -// } -// } -// } - - class LLP - { - public: - int new_index; - double match_percent; - TrajectoryTracker* pTrack; - - LLP() - { - new_index = -1; - match_percent = -1; - pTrack = 0; - - } - }; - - void DeleteFromList(std::vector& delete_me_track, const TrajectoryTracker* track) - { - for(unsigned int k = 0; k < delete_me_track.size(); k++) - { - if(delete_me_track.at(k) == track) - { - delete_me_track.erase(delete_me_track.begin()+k); - return; - } - } - } - - void DeleteTheRest(std::vector& delete_me_track) - { - for(unsigned int k = 0; k < delete_me_track.size(); k++) - { - delete delete_me_track.at(k); - } - - delete_me_track.clear(); - } - - static bool IsBeggerPercentage(const LLP& p1, const LLP& p2) - { - return p1.match_percent > p2.match_percent; - } - - void MatchWithMax(std::vector& matching_list, std::vector& delete_me_track, std::vector& check_list) - { - if(matching_list.size() == 0 ) return; - - std::sort(matching_list.begin(), matching_list.end(), IsBeggerPercentage); - - while(matching_list.size()>0) - { - LLP f = matching_list.at(0); - f.pTrack->UpdatePathAndIndex(obj.predTrajectories.at(f.new_index), f.new_index); - - bool bFound = false; - for(unsigned int k=0; k < check_list.size(); k++) - { - if(check_list.at(k) == f.pTrack) - { - bFound = true; - break; - } - } - - if(!bFound) - check_list.push_back(f.pTrack); - - DeleteFromList(delete_me_track, f.pTrack); - for(int i=0; i < matching_list.size(); i++) - { - if(matching_list.at(i).new_index == f.new_index || matching_list.at(i).pTrack == f.pTrack) - { - matching_list.erase(matching_list.begin()+i); - i--; - } - } - } - } - - void MatchTrajectories() - { - m_TrajectoryTracker_temp.clear(); - std::vector matching_list; - std::vector delete_me_track = m_TrajectoryTracker; - for(unsigned int t = 0; t < obj.predTrajectories.size();t++) - { - bool bMatched = false; - LLP match_item; - match_item.new_index = t; - - for(int i = 0; i < m_TrajectoryTracker.size(); i++) - { - TrajectoryTracker* pTracker = m_TrajectoryTracker.at(i); - - double vMatch = pTracker->CalcMatchingPercentage(obj.predTrajectories.at(t)); - if(vMatch == 1.0) // perfect match - { - pTracker->UpdatePathAndIndex(obj.predTrajectories.at(t), t); - bool bFound = false; - for(unsigned int k=0; k < m_TrajectoryTracker_temp.size(); k++) - { - if(m_TrajectoryTracker_temp.at(k) == pTracker) - { - bFound = true; - break; - } - } - - if(!bFound) - m_TrajectoryTracker_temp.push_back(pTracker); - - DeleteFromList(delete_me_track, pTracker); - - for(unsigned int k=0; k < matching_list.size(); k++) - { - if(matching_list.at(k).pTrack == pTracker) - { - matching_list.erase(matching_list.begin()+k); - break; - } - } - - m_TrajectoryTracker.erase(m_TrajectoryTracker.begin()+i); - bMatched = true; - i--; - break; - } - else if(vMatch > 0.5) // any matching less than 50%, the trajectory will be considered new - { - bMatched = true; - match_item.match_percent = vMatch; - match_item.pTrack = pTracker; - matching_list.push_back(match_item); - } - } - - if(!bMatched) - { - m_TrajectoryTracker_temp.push_back(new TrajectoryTracker(obj.predTrajectories.at(t), t)); - } - } - - MatchWithMax(matching_list,delete_me_track, m_TrajectoryTracker_temp); - m_TrajectoryTracker.clear(); - DeleteTheRest(delete_me_track); - m_TrajectoryTracker = m_TrajectoryTracker_temp; - } +// for(unsigned int i = 1; i < m_TrajectoryTracker.size(); i++) +// { +// if(m_TrajectoryTracker.at(i)->best_p > best_beh_track->best_p) +// { +// best_beh_track = m_TrajectoryTracker.at(i); +// i_best_track = i; +// } +// } +// } + + class LLP + { + public: + int new_index; + double match_percent; + TrajectoryTracker* pTrack; + + LLP() + { + new_index = -1; + match_percent = -1; + pTrack = 0; + + } + }; + + void DeleteFromList(std::vector& delete_me_track, const TrajectoryTracker* track) + { + for(unsigned int k = 0; k < delete_me_track.size(); k++) + { + if(delete_me_track.at(k) == track) + { + delete_me_track.erase(delete_me_track.begin()+k); + return; + } + } + } + + void DeleteTheRest(std::vector& delete_me_track) + { + for(unsigned int k = 0; k < delete_me_track.size(); k++) + { + delete delete_me_track.at(k); + } + + delete_me_track.clear(); + } + + static bool IsBeggerPercentage(const LLP& p1, const LLP& p2) + { + return p1.match_percent > p2.match_percent; + } + + void MatchWithMax(std::vector& matching_list, std::vector& delete_me_track, std::vector& check_list) + { + if(matching_list.size() == 0 ) return; + + std::sort(matching_list.begin(), matching_list.end(), IsBeggerPercentage); + + while(matching_list.size()>0) + { + LLP f = matching_list.at(0); + f.pTrack->UpdatePathAndIndex(obj.predTrajectories.at(f.new_index), f.new_index); + + bool bFound = false; + for(unsigned int k=0; k < check_list.size(); k++) + { + if(check_list.at(k) == f.pTrack) + { + bFound = true; + break; + } + } + + if(!bFound) + check_list.push_back(f.pTrack); + + DeleteFromList(delete_me_track, f.pTrack); + for(int i=0; i < matching_list.size(); i++) + { + if(matching_list.at(i).new_index == f.new_index || matching_list.at(i).pTrack == f.pTrack) + { + matching_list.erase(matching_list.begin()+i); + i--; + } + } + } + } + + void MatchTrajectories() + { + m_TrajectoryTracker_temp.clear(); + std::vector matching_list; + std::vector delete_me_track = m_TrajectoryTracker; + for(unsigned int t = 0; t < obj.predTrajectories.size();t++) + { + bool bMatched = false; + LLP match_item; + match_item.new_index = t; + + for(int i = 0; i < m_TrajectoryTracker.size(); i++) + { + TrajectoryTracker* pTracker = m_TrajectoryTracker.at(i); + + double vMatch = pTracker->CalcMatchingPercentage(obj.predTrajectories.at(t)); + if(vMatch == 1.0) // perfect match + { + pTracker->UpdatePathAndIndex(obj.predTrajectories.at(t), t); + bool bFound = false; + for(unsigned int k=0; k < m_TrajectoryTracker_temp.size(); k++) + { + if(m_TrajectoryTracker_temp.at(k) == pTracker) + { + bFound = true; + break; + } + } + + if(!bFound) + m_TrajectoryTracker_temp.push_back(pTracker); + + DeleteFromList(delete_me_track, pTracker); + + for(unsigned int k=0; k < matching_list.size(); k++) + { + if(matching_list.at(k).pTrack == pTracker) + { + matching_list.erase(matching_list.begin()+k); + break; + } + } + + m_TrajectoryTracker.erase(m_TrajectoryTracker.begin()+i); + bMatched = true; + i--; + break; + } + else if(vMatch > 0.5) // any matching less than 50%, the trajectory will be considered new + { + bMatched = true; + match_item.match_percent = vMatch; + match_item.pTrack = pTracker; + matching_list.push_back(match_item); + } + } + + if(!bMatched) + { + m_TrajectoryTracker_temp.push_back(new TrajectoryTracker(obj.predTrajectories.at(t), t)); + } + } + + MatchWithMax(matching_list,delete_me_track, m_TrajectoryTracker_temp); + m_TrajectoryTracker.clear(); + DeleteTheRest(delete_me_track); + m_TrajectoryTracker = m_TrajectoryTracker_temp; + } }; class BehaviorPrediction { public: - BehaviorPrediction(); - virtual ~BehaviorPrediction(); - void DoOneStep(const std::vector& obj_list, const WayPoint& currPose, const double& minSpeed, const double& maxDeceleration, RoadNetwork& map); + BehaviorPrediction(); + virtual ~BehaviorPrediction(); + void DoOneStep(const std::vector& obj_list, const WayPoint& currPose, const double& minSpeed, const double& maxDeceleration, RoadNetwork& map); public: - std::vector m_d_makers; - double m_MaxLaneDetectionDistance; - double m_PredictionDistance; - bool m_bGenerateBranches; - bool m_bUseFixedPrediction; - bool m_bStepByStep; - bool m_bParticleFilter; - //std::vector m_PredictedObjects; - //std::vector m_PredictedObjectsII; + std::vector m_d_makers; + double m_MaxLaneDetectionDistance; + double m_PredictionDistance; + bool m_bGenerateBranches; + bool m_bUseFixedPrediction; + bool m_bStepByStep; + bool m_bParticleFilter; + //std::vector m_PredictedObjects; + //std::vector m_PredictedObjectsII; - std::vector m_temp_list; - std::vector m_ParticleInfo; + std::vector m_temp_list; + std::vector m_ParticleInfo; - std::vector m_temp_list_ii; - std::vector m_ParticleInfo_II; + std::vector m_temp_list_ii; + std::vector m_ParticleInfo_II; - struct timespec m_GenerationTimer; - timespec m_ResamplingTimer; + struct timespec m_GenerationTimer; + timespec m_ResamplingTimer; - bool m_bCanDecide; - bool m_bFirstMove; - bool m_bDebugOut; + bool m_bCanDecide; + bool m_bFirstMove; + bool m_bDebugOut; protected: - //int GetTrajectoryPredictedDirection(const std::vector& path, const PlannerHNS::WayPoint& pose, const double& pred_distance); - int FromIndicatorToNumber(const PlannerHNS::LIGHT_INDICATOR& ind); - PlannerHNS::LIGHT_INDICATOR FromNumbertoIndicator(const int& num); - double CalcIndicatorWeight(PlannerHNS::LIGHT_INDICATOR p_ind, PlannerHNS::LIGHT_INDICATOR obj_ind); - double CalcAccelerationWeight(int p_acl, int obj_acl); + //int GetTrajectoryPredictedDirection(const std::vector& path, const PlannerHNS::WayPoint& pose, const double& pred_distance); + int FromIndicatorToNumber(const PlannerHNS::LIGHT_INDICATOR& ind); + PlannerHNS::LIGHT_INDICATOR FromNumbertoIndicator(const int& num); + double CalcIndicatorWeight(PlannerHNS::LIGHT_INDICATOR p_ind, PlannerHNS::LIGHT_INDICATOR obj_ind); + double CalcAccelerationWeight(int p_acl, int obj_acl); - void CalPredictionTimeForObject(ObjParticles* pCarPart); - void PredictCurrentTrajectory(RoadNetwork& map, ObjParticles* pCarPart); - void FilterObservations(const std::vector& obj_list, RoadNetwork& map, std::vector& filtered_list); - void ExtractTrajectoriesFromMap(const std::vector& obj_list, RoadNetwork& map, std::vector& old_list); - void CalculateCollisionTimes(const double& minSpeed); + void CalPredictionTimeForObject(ObjParticles* pCarPart); + void PredictCurrentTrajectory(RoadNetwork& map, ObjParticles* pCarPart); + void FilterObservations(const std::vector& obj_list, RoadNetwork& map, std::vector& filtered_list); + void ExtractTrajectoriesFromMap(const std::vector& obj_list, RoadNetwork& map, std::vector& old_list); + void CalculateCollisionTimes(const double& minSpeed); - void ParticleFilterSteps(std::vector& part_info); + void ParticleFilterSteps(std::vector& part_info); - void SamplesFreshParticles(ObjParticles* pParts); - void MoveParticles(ObjParticles* parts); - void CalculateWeights(ObjParticles* pParts); + void SamplesFreshParticles(ObjParticles* pParts); + void MoveParticles(ObjParticles* parts); + void CalculateWeights(ObjParticles* pParts); - void CalOnePartWeight(ObjParticles* pParts,Particle& p); - void NormalizeOnePartWeight(ObjParticles* pParts,Particle& p); + void CalOnePartWeight(ObjParticles* pParts,Particle& p); + void NormalizeOnePartWeight(ObjParticles* pParts,Particle& p); - void CollectParticles(ObjParticles* pParts); + void CollectParticles(ObjParticles* pParts); - void RemoveWeakParticles(ObjParticles* pParts); - void FindBest(ObjParticles* pParts); - void CalculateAveragesAndProbabilities(ObjParticles* pParts); + void RemoveWeakParticles(ObjParticles* pParts); + void FindBest(ObjParticles* pParts); + void CalculateAveragesAndProbabilities(ObjParticles* pParts); - static bool sort_weights(const Particle* p1, const Particle* p2) - { - return p1->w > p2->w; - } + static bool sort_weights(const Particle* p1, const Particle* p2) + { + return p1->w > p2->w; + } - static bool sort_trajectories(const std::pair& p1, const std::pair& p2) - { - return p1.second > p2.second; - } + static bool sort_trajectories(const std::pair& p1, const std::pair& p2) + { + return p1.second > p2.second; + } public: - //move to CPP later - void DeleteFromList(std::vector& delete_me, const ObjParticles* pElement) - { - for(unsigned int k = 0; k < delete_me.size(); k++) - { - if(delete_me.at(k) == pElement) - { - delete_me.erase(delete_me.begin()+k); - return; - } - } - } - - void DeleteTheRest(std::vector& delete_me) - { - for(unsigned int k = 0; k < delete_me.size(); k++) - { - delete delete_me.at(k); - } - - delete_me.clear(); - } + //move to CPP later + void DeleteFromList(std::vector& delete_me, const ObjParticles* pElement) + { + for(unsigned int k = 0; k < delete_me.size(); k++) + { + if(delete_me.at(k) == pElement) + { + delete_me.erase(delete_me.begin()+k); + return; + } + } + } + + void DeleteTheRest(std::vector& delete_me) + { + for(unsigned int k = 0; k < delete_me.size(); k++) + { + delete delete_me.at(k); + } + + delete_me.clear(); + } }; diff --git a/common/op_planner/include/op_planner/BehaviorStateMachine.h b/common/op_planner/include/op_planner/BehaviorStateMachine.h index a9dc4bfd818..c520ed7d191 100755 --- a/common/op_planner/include/op_planner/BehaviorStateMachine.h +++ b/common/op_planner/include/op_planner/BehaviorStateMachine.h @@ -16,260 +16,260 @@ namespace PlannerHNS class BehaviorStateMachine { public: - virtual BehaviorStateMachine* GetNextState() = 0; - virtual void Init(); - virtual void ResetTimer(); - virtual void InsertNextState(BehaviorStateMachine* nextState); - BehaviorStateMachine(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* nextState); - virtual ~BehaviorStateMachine() ; - - STATE_TYPE m_Behavior; - int m_currentStopSignID ; - int m_currentTrafficLightID ; - double decisionMakingTime; - int decisionMakingCount; - double m_zero_velocity; - - PreCalculatedConditions* GetCalcParams() - { - if(!m_pCalculatedValues) - m_pCalculatedValues = new PreCalculatedConditions(); - - return m_pCalculatedValues; - } - - void SetBehaviorsParams(PlanningParams* pParams) - { - if(!pParams) - m_pParams = new PlanningParams; - else - m_pParams = pParams; - } - - - PreCalculatedConditions* m_pCalculatedValues; - PlanningParams* m_pParams; - timespec m_StateTimer; - std::vector pNextStates; - - BehaviorStateMachine* FindBehaviorState(const STATE_TYPE& behavior); - void UpdateLogCount(BehaviorStateMachine* pState); - BehaviorStateMachine* FindBestState(int nMinCount); + virtual BehaviorStateMachine* GetNextState() = 0; + virtual void Init(); + virtual void ResetTimer(); + virtual void InsertNextState(BehaviorStateMachine* nextState); + BehaviorStateMachine(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* nextState); + virtual ~BehaviorStateMachine() ; + + STATE_TYPE m_Behavior; + int m_currentStopSignID ; + int m_currentTrafficLightID ; + double decisionMakingTime; + int decisionMakingCount; + double m_zero_velocity; + + PreCalculatedConditions* GetCalcParams() + { + if(!m_pCalculatedValues) + m_pCalculatedValues = new PreCalculatedConditions(); + + return m_pCalculatedValues; + } + + void SetBehaviorsParams(PlanningParams* pParams) + { + if(!pParams) + m_pParams = new PlanningParams; + else + m_pParams = pParams; + } + + + PreCalculatedConditions* m_pCalculatedValues; + PlanningParams* m_pParams; + timespec m_StateTimer; + std::vector pNextStates; + + BehaviorStateMachine* FindBehaviorState(const STATE_TYPE& behavior); + void UpdateLogCount(BehaviorStateMachine* pState); + BehaviorStateMachine* FindBestState(int nMinCount); private: - std::vector > m_BehaviorsLog; + std::vector > m_BehaviorsLog; }; class ForwardState : public BehaviorStateMachine { public: - ForwardState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FORWARD_STATE;} - virtual ~ForwardState(){} - virtual BehaviorStateMachine* GetNextState(); + ForwardState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FORWARD_STATE;} + virtual ~ForwardState(){} + virtual BehaviorStateMachine* GetNextState(); }; class ForwardStateII : public BehaviorStateMachine { public: - ForwardStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FORWARD_STATE;} - virtual ~ForwardStateII(){} - virtual BehaviorStateMachine* GetNextState(); + ForwardStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FORWARD_STATE;} + virtual ~ForwardStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class MissionAccomplishedState : public BehaviorStateMachine { public: - MissionAccomplishedState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FINISH_STATE;} - virtual ~MissionAccomplishedState(){} - virtual BehaviorStateMachine* GetNextState(); + MissionAccomplishedState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FINISH_STATE;} + virtual ~MissionAccomplishedState(){} + virtual BehaviorStateMachine* GetNextState(); }; class MissionAccomplishedStateII : public BehaviorStateMachine { public: - MissionAccomplishedStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FINISH_STATE;} - virtual ~MissionAccomplishedStateII(){} - virtual BehaviorStateMachine* GetNextState(); + MissionAccomplishedStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FINISH_STATE;} + virtual ~MissionAccomplishedStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class FollowState : public BehaviorStateMachine { public: - FollowState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FOLLOW_STATE;} - virtual ~FollowState(){} - virtual BehaviorStateMachine* GetNextState(); + FollowState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FOLLOW_STATE;} + virtual ~FollowState(){} + virtual BehaviorStateMachine* GetNextState(); }; class FollowStateII : public BehaviorStateMachine { public: - FollowStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FOLLOW_STATE;} - virtual ~FollowStateII(){} - virtual BehaviorStateMachine* GetNextState(); + FollowStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = FOLLOW_STATE;} + virtual ~FollowStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class SwerveState : public BehaviorStateMachine { public: - SwerveState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = OBSTACLE_AVOIDANCE_STATE;} - virtual ~SwerveState(){} - virtual BehaviorStateMachine* GetNextState(); + SwerveState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = OBSTACLE_AVOIDANCE_STATE;} + virtual ~SwerveState(){} + virtual BehaviorStateMachine* GetNextState(); }; class SwerveStateII : public BehaviorStateMachine { public: - SwerveStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = OBSTACLE_AVOIDANCE_STATE;} - virtual ~SwerveStateII(){} - virtual BehaviorStateMachine* GetNextState(); + SwerveStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = OBSTACLE_AVOIDANCE_STATE;} + virtual ~SwerveStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class StopState : public BehaviorStateMachine { public: - StopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOPPING_STATE;} - virtual BehaviorStateMachine* GetNextState(); + StopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOPPING_STATE;} + virtual BehaviorStateMachine* GetNextState(); }; class TrafficLightStopState : public BehaviorStateMachine { public: - TrafficLightStopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_STOP_STATE;} - virtual ~TrafficLightStopState(){} - virtual BehaviorStateMachine* GetNextState(); + TrafficLightStopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_STOP_STATE;} + virtual ~TrafficLightStopState(){} + virtual BehaviorStateMachine* GetNextState(); }; class TrafficLightWaitState : public BehaviorStateMachine { public: - TrafficLightWaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_WAIT_STATE;} - virtual ~TrafficLightWaitState(){} - virtual BehaviorStateMachine* GetNextState(); + TrafficLightWaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_WAIT_STATE;} + virtual ~TrafficLightWaitState(){} + virtual BehaviorStateMachine* GetNextState(); }; class StopSignStopState : public BehaviorStateMachine { public: - StopSignStopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_STOP_STATE;} - virtual ~StopSignStopState(){} - virtual BehaviorStateMachine* GetNextState(); + StopSignStopState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_STOP_STATE;} + virtual ~StopSignStopState(){} + virtual BehaviorStateMachine* GetNextState(); }; class StopSignStopStateII : public BehaviorStateMachine { public: - StopSignStopStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_STOP_STATE;} - virtual ~StopSignStopStateII(){} - virtual BehaviorStateMachine* GetNextState(); + StopSignStopStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_STOP_STATE;} + virtual ~StopSignStopStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class StopSignWaitState : public BehaviorStateMachine { public: - StopSignWaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_WAIT_STATE;} - virtual ~StopSignWaitState(){} - virtual BehaviorStateMachine* GetNextState(); + StopSignWaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_WAIT_STATE;} + virtual ~StopSignWaitState(){} + virtual BehaviorStateMachine* GetNextState(); }; class StopSignWaitStateII : public BehaviorStateMachine { public: - StopSignWaitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_WAIT_STATE;} - virtual ~StopSignWaitStateII(){} - virtual BehaviorStateMachine* GetNextState(); + StopSignWaitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = STOP_SIGN_WAIT_STATE;} + virtual ~StopSignWaitStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class WaitState : public BehaviorStateMachine { public: - WaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = WAITING_STATE;} - virtual ~WaitState(){} - virtual BehaviorStateMachine* GetNextState(); + WaitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = WAITING_STATE;} + virtual ~WaitState(){} + virtual BehaviorStateMachine* GetNextState(); }; class InitState : public BehaviorStateMachine { public: - InitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = INITIAL_STATE;} - virtual ~InitState(){} - virtual BehaviorStateMachine* GetNextState(); + InitState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = INITIAL_STATE;} + virtual ~InitState(){} + virtual BehaviorStateMachine* GetNextState(); }; class InitStateII : public BehaviorStateMachine { public: - InitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = INITIAL_STATE;} - virtual ~InitStateII(){} - virtual BehaviorStateMachine* GetNextState(); + InitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = INITIAL_STATE;} + virtual ~InitStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class GoalState : public BehaviorStateMachine { public: - GoalState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = GOAL_STATE;} - virtual ~GoalState(){} - virtual BehaviorStateMachine* GetNextState(); + GoalState(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = GOAL_STATE;} + virtual ~GoalState(){} + virtual BehaviorStateMachine* GetNextState(); }; class GoalStateII : public BehaviorStateMachine { public: - GoalStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = GOAL_STATE;} - virtual ~GoalStateII(){} - virtual BehaviorStateMachine* GetNextState(); + GoalStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = GOAL_STATE;} + virtual ~GoalStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class TrafficLightStopStateII : public BehaviorStateMachine { public: - TrafficLightStopStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_STOP_STATE;} - virtual ~TrafficLightStopStateII(){} - virtual BehaviorStateMachine* GetNextState(); + TrafficLightStopStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_STOP_STATE;} + virtual ~TrafficLightStopStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; class TrafficLightWaitStateII : public BehaviorStateMachine { public: - TrafficLightWaitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) - : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_WAIT_STATE;} - virtual ~TrafficLightWaitStateII(){} - virtual BehaviorStateMachine* GetNextState(); + TrafficLightWaitStateII(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* pNextState) + : BehaviorStateMachine(pParams, pPreCalcVal, pNextState){m_Behavior = TRAFFIC_LIGHT_WAIT_STATE;} + virtual ~TrafficLightWaitStateII(){} + virtual BehaviorStateMachine* GetNextState(); }; } /* namespace PlannerHNS */ diff --git a/common/op_planner/include/op_planner/DecisionMaker.h b/common/op_planner/include/op_planner/DecisionMaker.h index 9a6fa0a0b0f..10e4db2166e 100755 --- a/common/op_planner/include/op_planner/DecisionMaker.h +++ b/common/op_planner/include/op_planner/DecisionMaker.h @@ -18,72 +18,72 @@ namespace PlannerHNS class DecisionMaker { public: - WayPoint state; - CAR_BASIC_INFO m_CarInfo; - ControllerParams m_ControlParams; - std::vector m_Path; - PlannerHNS::RoadNetwork m_Map; - - double m_MaxLaneSearchDistance; - int m_iCurrentTotalPathId; - std::vector > m_RollOuts; - Lane* pLane; - - BehaviorStateMachine* m_pCurrentBehaviorState; - StopState* m_pStopState; - WaitState* m_pWaitState; - SwerveStateII* m_pAvoidObstacleState; - TrafficLightStopStateII* m_pTrafficLightStopState; - TrafficLightWaitStateII* m_pTrafficLightWaitState; - - ForwardStateII * m_pGoToGoalState;; - InitStateII* m_pInitState; - MissionAccomplishedStateII* m_pMissionCompleteState; - GoalStateII* m_pGoalState; - FollowStateII* m_pFollowState; - StopSignStopStateII* m_pStopSignStopState; - StopSignWaitStateII* m_pStopSignWaitState; - - void InitBehaviorStates(); - - //For Simulation - UtilityHNS::PIDController m_pidVelocity; - UtilityHNS::PIDController m_pidStopping; - UtilityHNS::PIDController m_pidFollowing; + WayPoint state; + CAR_BASIC_INFO m_CarInfo; + ControllerParams m_ControlParams; + std::vector m_Path; + PlannerHNS::RoadNetwork m_Map; + + double m_MaxLaneSearchDistance; + int m_iCurrentTotalPathId; + std::vector > m_RollOuts; + Lane* pLane; + + BehaviorStateMachine* m_pCurrentBehaviorState; + StopState* m_pStopState; + WaitState* m_pWaitState; + SwerveStateII* m_pAvoidObstacleState; + TrafficLightStopStateII* m_pTrafficLightStopState; + TrafficLightWaitStateII* m_pTrafficLightWaitState; + + ForwardStateII * m_pGoToGoalState;; + InitStateII* m_pInitState; + MissionAccomplishedStateII* m_pMissionCompleteState; + GoalStateII* m_pGoalState; + FollowStateII* m_pFollowState; + StopSignStopStateII* m_pStopSignStopState; + StopSignWaitStateII* m_pStopSignWaitState; + + void InitBehaviorStates(); + + //For Simulation + UtilityHNS::PIDController m_pidVelocity; + UtilityHNS::PIDController m_pidStopping; + UtilityHNS::PIDController m_pidFollowing; public: - DecisionMaker(); - virtual ~DecisionMaker(); - void Init(const ControllerParams& ctrlParams, const PlanningParams& params, const CAR_BASIC_INFO& carInfo); - void CalculateImportantParameterForDecisionMaking(const VehicleState& car_state, - const int& goalID, const bool& bEmergencyStop, const std::vector& detectedLights, - const TrajectoryCost& bestTrajectory); - void SetNewGlobalPath(const std::vector >& globalPath); - - BehaviorState DoOneStep( - const double& dt, - const PlannerHNS::WayPoint currPose, - const PlannerHNS::VehicleState& vehicleState, - const int& goalID, - const std::vector& trafficLight, - const TrajectoryCost& tc, - const bool& bEmergencyStop); + DecisionMaker(); + virtual ~DecisionMaker(); + void Init(const ControllerParams& ctrlParams, const PlanningParams& params, const CAR_BASIC_INFO& carInfo); + void CalculateImportantParameterForDecisionMaking(const VehicleState& car_state, + const int& goalID, const bool& bEmergencyStop, const std::vector& detectedLights, + const TrajectoryCost& bestTrajectory); + void SetNewGlobalPath(const std::vector >& globalPath); + + BehaviorState DoOneStep( + const double& dt, + const PlannerHNS::WayPoint currPose, + const PlannerHNS::VehicleState& vehicleState, + const int& goalID, + const std::vector& trafficLight, + const TrajectoryCost& tc, + const bool& bEmergencyStop); protected: - bool GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, TrafficLight& trafficL); - void UpdateCurrentLane(const double& search_distance); - bool SelectSafeTrajectory(); - BehaviorState GenerateBehaviorState(const VehicleState& vehicleState); - double UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt); - bool ReachEndOfGlobalPath(const double& min_distance, const int& iGlobalPathIndex); + bool GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, TrafficLight& trafficL); + void UpdateCurrentLane(const double& search_distance); + bool SelectSafeTrajectory(); + BehaviorState GenerateBehaviorState(const VehicleState& vehicleState); + double UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt); + bool ReachEndOfGlobalPath(const double& min_distance, const int& iGlobalPathIndex); - std::vector t_centerTrajectorySmoothed; - std::vector > m_TotalOriginalPath; - std::vector > m_TotalPath; - PlannerHNS::PlanningParams m_params; + std::vector t_centerTrajectorySmoothed; + std::vector > m_TotalOriginalPath; + std::vector > m_TotalPath; + PlannerHNS::PlanningParams m_params; }; diff --git a/common/op_planner/include/op_planner/LocalPlannerH.h b/common/op_planner/include/op_planner/LocalPlannerH.h index 701c6c10111..f24d2d2d25c 100755 --- a/common/op_planner/include/op_planner/LocalPlannerH.h +++ b/common/op_planner/include/op_planner/LocalPlannerH.h @@ -20,147 +20,147 @@ namespace PlannerHNS class LocalPlannerH { public: - WayPoint state; - CAR_BASIC_INFO m_CarInfo; - ControllerParams m_ControlParams; - std::vector m_CarShapePolygon; - std::vector m_Path; - std::vector m_OriginalLocalPath; - std::vector > m_TotalPath; - std::vector > m_TotalOriginalPath; - std::vector m_PredictedTrajectoryObstacles; - int m_iCurrentTotalPathId; - int m_iSafeTrajectory; - double m_InitialFollowingDistance; -// int m_iGlobalPathPrevID; -// std::vector > m_PredictedPath; - std::vector > > m_RollOuts; - std::string carId; - Lane* pLane; - double m_SimulationSteeringDelayFactor; //second , time that every degree change in the steering wheel takes - timespec m_SteerDelayTimer; - double m_PredictionTime; - double m_CostCalculationTime; - double m_BehaviorGenTime; - double m_RollOutsGenerationTime; - int m_PrevBrakingWayPoint; - - BehaviorStateMachine* m_pCurrentBehaviorState; - ForwardState * m_pGoToGoalState; - StopState* m_pStopState; - WaitState* m_pWaitState; - InitState* m_pInitState; - MissionAccomplishedState* m_pMissionCompleteState; - GoalState* m_pGoalState; - FollowState* m_pFollowState; - SwerveState* m_pAvoidObstacleState; - TrafficLightStopState* m_pTrafficLightStopState; - TrafficLightWaitState* m_pTrafficLightWaitState; - StopSignStopState* m_pStopSignStopState; - StopSignWaitState* m_pStopSignWaitState; - - TrajectoryCosts m_TrajectoryCostsCalculatotor; - - //for debugging - - std::vector m_SampledPoints; - - void InitBehaviorStates(); - - void ReInitializePlanner(const WayPoint& start_pose); - - void SetSimulatedTargetOdometryReadings(const double& velocity_d, const double& steering_d, const SHIFT_POS& shift_d) - { - m_CurrentVelocityD = velocity_d; - m_CurrentSteeringD = steering_d; - m_CurrentShiftD = shift_d; - } - - double GetSimulatedVelocity() - { - return m_CurrentVelocity; - } - - double GetSimulatedSteering() - { - return m_CurrentSteering; - } - - double GetSimulatedShift() - { - return m_CurrentShift; - } - - - //For Simulation - WayPoint m_OdometryState; - double m_CurrentVelocity, m_CurrentVelocityD; //meter/second - double m_CurrentSteering, m_CurrentSteeringD; //radians - SHIFT_POS m_CurrentShift , m_CurrentShiftD; - - double m_CurrentAccSteerAngle; //degrees steer wheel range - double m_CurrentAccVelocity; // kilometer/hour - //std::vector m_TrafficLights; - - UtilityHNS::PIDController m_pidVelocity; - UtilityHNS::PIDController m_pidStopping; + WayPoint state; + CAR_BASIC_INFO m_CarInfo; + ControllerParams m_ControlParams; + std::vector m_CarShapePolygon; + std::vector m_Path; + std::vector m_OriginalLocalPath; + std::vector > m_TotalPath; + std::vector > m_TotalOriginalPath; + std::vector m_PredictedTrajectoryObstacles; + int m_iCurrentTotalPathId; + int m_iSafeTrajectory; + double m_InitialFollowingDistance; +// int m_iGlobalPathPrevID; +// std::vector > m_PredictedPath; + std::vector > > m_RollOuts; + std::string carId; + Lane* pLane; + double m_SimulationSteeringDelayFactor; //second , time that every degree change in the steering wheel takes + timespec m_SteerDelayTimer; + double m_PredictionTime; + double m_CostCalculationTime; + double m_BehaviorGenTime; + double m_RollOutsGenerationTime; + int m_PrevBrakingWayPoint; + + BehaviorStateMachine* m_pCurrentBehaviorState; + ForwardState * m_pGoToGoalState; + StopState* m_pStopState; + WaitState* m_pWaitState; + InitState* m_pInitState; + MissionAccomplishedState* m_pMissionCompleteState; + GoalState* m_pGoalState; + FollowState* m_pFollowState; + SwerveState* m_pAvoidObstacleState; + TrafficLightStopState* m_pTrafficLightStopState; + TrafficLightWaitState* m_pTrafficLightWaitState; + StopSignStopState* m_pStopSignStopState; + StopSignWaitState* m_pStopSignWaitState; + + TrajectoryCosts m_TrajectoryCostsCalculatotor; + + //for debugging + + std::vector m_SampledPoints; + + void InitBehaviorStates(); + + void ReInitializePlanner(const WayPoint& start_pose); + + void SetSimulatedTargetOdometryReadings(const double& velocity_d, const double& steering_d, const SHIFT_POS& shift_d) + { + m_CurrentVelocityD = velocity_d; + m_CurrentSteeringD = steering_d; + m_CurrentShiftD = shift_d; + } + + double GetSimulatedVelocity() + { + return m_CurrentVelocity; + } + + double GetSimulatedSteering() + { + return m_CurrentSteering; + } + + double GetSimulatedShift() + { + return m_CurrentShift; + } + + + //For Simulation + WayPoint m_OdometryState; + double m_CurrentVelocity, m_CurrentVelocityD; //meter/second + double m_CurrentSteering, m_CurrentSteeringD; //radians + SHIFT_POS m_CurrentShift , m_CurrentShiftD; + + double m_CurrentAccSteerAngle; //degrees steer wheel range + double m_CurrentAccVelocity; // kilometer/hour + //std::vector m_TrafficLights; + + UtilityHNS::PIDController m_pidVelocity; + UtilityHNS::PIDController m_pidStopping; public: - LocalPlannerH(); - virtual ~LocalPlannerH(); - void Init(const ControllerParams& ctrlParams, const PlanningParams& params, const CAR_BASIC_INFO& carInfo); - void InitPolygons(); - void FirstLocalizeMe(const WayPoint& initCarPos); - void LocalizeMe(const double& dt); // in seconds - void UpdateState(const VehicleState& state, const bool& bUseDelay = false); - void CalculateImportantParameterForDecisionMaking(const VehicleState& car_state, - const int& goalID, const bool& bEmergencyStop, const vector& detectedLights, - const TrajectoryCost& bestTrajectory); - - BehaviorState DoOneStep( - const double& dt, - const VehicleState& state, - const std::vector& obj_list, - const int& goalID, - RoadNetwork& map, - const bool& bEmergencyStop, - const std::vector& trafficLight, - const bool& bLive = false); - - void SimulateOdoPosition(const double& dt, const VehicleState& vehicleState); + LocalPlannerH(); + virtual ~LocalPlannerH(); + void Init(const ControllerParams& ctrlParams, const PlanningParams& params, const CAR_BASIC_INFO& carInfo); + void InitPolygons(); + void FirstLocalizeMe(const WayPoint& initCarPos); + void LocalizeMe(const double& dt); // in seconds + void UpdateState(const VehicleState& state, const bool& bUseDelay = false); + void CalculateImportantParameterForDecisionMaking(const VehicleState& car_state, + const int& goalID, const bool& bEmergencyStop, const vector& detectedLights, + const TrajectoryCost& bestTrajectory); + + BehaviorState DoOneStep( + const double& dt, + const VehicleState& state, + const std::vector& obj_list, + const int& goalID, + RoadNetwork& map, + const bool& bEmergencyStop, + const std::vector& trafficLight, + const bool& bLive = false); + + void SimulateOdoPosition(const double& dt, const VehicleState& vehicleState); private: - //Obstacle avoidance functionalities -// bool CalculateObstacleCosts(RoadNetwork& map, const VehicleState& vstatus, const std::vector& obj_list); + //Obstacle avoidance functionalities +// bool CalculateObstacleCosts(RoadNetwork& map, const VehicleState& vstatus, const std::vector& obj_list); // -// double PredictTimeCostForTrajectory(std::vector& path, -// const VehicleState& vstatus, -// const WayPoint& currState); +// double PredictTimeCostForTrajectory(std::vector& path, +// const VehicleState& vstatus, +// const WayPoint& currState); // -// void PredictObstacleTrajectory(RoadNetwork& map, -// const WayPoint& pos, -// const double& predTime, -// std::vector >& paths); +// void PredictObstacleTrajectory(RoadNetwork& map, +// const WayPoint& pos, +// const double& predTime, +// std::vector >& paths); // -// bool CalculateIntersectionVelocities(std::vector& path, -// std::vector >& predctedPath, -// const DetectedObject& obj); +// bool CalculateIntersectionVelocities(std::vector& path, +// std::vector >& predctedPath, +// const DetectedObject& obj); - bool GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, TrafficLight& trafficL); - void UpdateCurrentLane(RoadNetwork& map, const double& search_distance); - bool SelectSafeTrajectoryAndSpeedProfile(const VehicleState& vehicleState); - BehaviorState GenerateBehaviorState(const VehicleState& vehicleState); - void TransformPoint(const WayPoint& refPose, GPSPoint& p); - void AddAndTransformContourPoints(const DetectedObject& obj, std::vector& contourPoints); - double UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt); + bool GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, TrafficLight& trafficL); + void UpdateCurrentLane(RoadNetwork& map, const double& search_distance); + bool SelectSafeTrajectoryAndSpeedProfile(const VehicleState& vehicleState); + BehaviorState GenerateBehaviorState(const VehicleState& vehicleState); + void TransformPoint(const WayPoint& refPose, GPSPoint& p); + void AddAndTransformContourPoints(const DetectedObject& obj, std::vector& contourPoints); + double UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt); - void ExtractHorizonAndCalculateRecommendedSpeed(); + void ExtractHorizonAndCalculateRecommendedSpeed(); - bool NoWayTest(const double& min_distance, const int& iGlobalPathIndex); + bool NoWayTest(const double& min_distance, const int& iGlobalPathIndex); - PlannerHNS::PlanningParams m_params; + PlannerHNS::PlanningParams m_params; }; } /* namespace PlannerHNS */ diff --git a/common/op_planner/include/op_planner/MappingHelpers.h b/common/op_planner/include/op_planner/MappingHelpers.h index 9c0657f1187..76d51e4f58b 100755 --- a/common/op_planner/include/op_planner/MappingHelpers.h +++ b/common/op_planner/include/op_planner/MappingHelpers.h @@ -21,204 +21,204 @@ namespace PlannerHNS { class MappingHelpers { public: - MappingHelpers(); - virtual ~MappingHelpers(); - - static void ConstructRoadNetworkFromROSMessage(const std::vector& lanes_data, - const std::vector& points_data, - const std::vector& dt_data, - const std::vector& intersection_data, - const std::vector& area_data, - const std::vector& line_data, - const std::vector& stop_line_data, - const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& curb_data, - const std::vector& roadedge_data, - const std::vector& wayarea_data, - const std::vector& crosswalk_data, - const std::vector& nodes_data, - const std::vector& conn_data, - const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, - const bool& bFindLaneChangeLanes = false, - const bool& bFindCurbsAndWayArea = false); - - static void ConstructRoadNetworkFromROSMessageV2(const std::vector& lanes_data, - const std::vector& points_data, - const std::vector& dt_data, - const std::vector& intersection_data, - const std::vector& area_data, - const std::vector& line_data, - const std::vector& stop_line_data, - const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& curb_data, - const std::vector& roadedge_data, - const std::vector& wayarea_data, - const std::vector& crosswalk_data, - const std::vector& nodes_data, - const std::vector& conn_data, - UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, - UtilityHNS::AisanLinesFileReader* pLinedata, - const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, - const bool& bFindLaneChangeLanes = false, - const bool& bFindCurbsAndWayArea = false); - - static void ConstructRoadNetworkFromDataFiles(const std::string vectoMapPath, RoadNetwork& map, const bool& bZeroOrigin = false); - - static void UpdateMapWithOccupancyGrid(OccupancyToGridMap& map_info, const std::vector& data, RoadNetwork& map, std::vector& updated_list); - - static bool GetWayPoint(const int& id, const int& laneID,const double& refVel, const int& did, - const std::vector& dtpoints, - const std::vector& points, - const GPSPoint& origin, WayPoint& way_point); - - static void LoadKML(const std::string& kmlMap, RoadNetwork& map); - - static TiXmlElement* GetHeadElement(TiXmlElement* pMainElem); - static TiXmlElement* GetDataFolder(const std::string& folderName, TiXmlElement* pMainElem); - - - static Lane* GetClosestLaneFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0, const bool bDirectionBased = true); - static std::vector GetClosestLanesListFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); - static Lane* GetClosestLaneFromMapDirectionBased(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); - static std::vector GetClosestMultipleLanesFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); - static WayPoint* GetClosestWaypointFromMap(const WayPoint& pos, RoadNetwork& map, const bool bDirectionBased = true); - static std::vector GetClosestLanesFast(const WayPoint& pos, RoadNetwork& map, const double& distance = 10.0); - - static std::vector GetClosestWaypointsListFromMap(const WayPoint& center, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); - - static WayPoint* GetClosestBackWaypointFromMap(const WayPoint& pos, RoadNetwork& map); - static WayPoint GetFirstWaypoint(RoadNetwork& map); - static WayPoint* GetLastWaypoint(RoadNetwork& map); - static void FindAdjacentLanes(RoadNetwork& map); - static void FindAdjacentLanesV2(RoadNetwork& map); - static void ExtractSignalData(const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractSignalDataV2(const std::vector& signal_data, - const std::vector& vector_data, - UtilityHNS::AisanPointsFileReader* pPointsData, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractStopLinesData(const std::vector& stop_line_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractStopLinesDataV2(const std::vector& stop_line_data, - UtilityHNS::AisanLinesFileReader* pLineData, - UtilityHNS::AisanPointsFileReader* pPointData, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractCurbData(const std::vector& curb_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractCurbDataV2(const std::vector& curb_data, - UtilityHNS::AisanLinesFileReader* pLinedata, - UtilityHNS::AisanPointsFileReader* pPointsData, - const GPSPoint& origin, RoadNetwork& map); - - static void ExtractWayArea(const std::vector& area_data, - const std::vector& wayarea_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map); - - static void LinkMissingBranchingWayPoints(RoadNetwork& map); - static void LinkMissingBranchingWayPointsV2(RoadNetwork& map); - static void LinkTrafficLightsAndStopLinesConData(const std::vector& conn_data, - const std::vector >& id_replace_list, RoadNetwork& map); - - static void LinkTrafficLightsAndStopLines(RoadNetwork& map); - - static void LinkTrafficLightsAndStopLinesV2(RoadNetwork& map); - - static void GetUniqueNextLanes(const Lane* l, const std::vector& traversed_lanes, std::vector& lanes_list); - - static GPSPoint GetTransformationOrigin(const int& bToyotaCityMap = 0); - - static Lane* GetLaneFromPath(const WayPoint& currPos, const std::vector& currPath); - static Lane* GetLaneById(const int& id,RoadNetwork& map); - static int GetLaneIdByWaypointId(const int& id,std::vector& lanes); - - static WayPoint* FindWaypoint(const int& id, RoadNetwork& map); - static WayPoint* FindWaypointV2(const int& id, const int& l_id, RoadNetwork& map); - - static std::vector GetCurbsList(TiXmlElement* pElem); - static std::vector GetBoundariesList(TiXmlElement* pElem); - static std::vector GetMarkingsList(TiXmlElement* pElem); - static std::vector GetCrossingsList(TiXmlElement* pElem); - static std::vector GetTrafficSignsList(TiXmlElement* pElem); - static std::vector GetTrafficLightsList(TiXmlElement* pElem); - static std::vector GetStopLinesList(TiXmlElement* pElem); - static std::vector GetLanesList(TiXmlElement* pElem); - static std::vector GetRoadSegmentsList(TiXmlElement* pElem); - static std::vector GetIDsFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); - static std::vector GetDoubleFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); - static std::pair GetActionPairFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); - static std::vector GetCenterLaneData(TiXmlElement* pElem, const int& currLaneID); - static std::vector GetCenterLaneDataVer0(TiXmlElement* pElem, const int& currLaneID); - static std::vector GetPointsData(TiXmlElement* pElem); - static std::vector SplitString(const std::string& str, const std::string& token); - - //static void CreateKmlFromLocalizationPathFile(const std::string& pathFileName,const double& maxLaneDistance, const double& density,const std::vector& trafficLights, const std::vector& stopLines); - - static void AssignActionCostToLane(Lane* pL, ACTION_TYPE action, double cost); - - static int ReplaceMyID(int& id, const std::vector >& rep_list); - - static void GetLanesStartPoints(UtilityHNS::AisanLanesFileReader* pLaneData, - std::vector& m_LanesStartIds); - - static void GetLanePoints(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, int lnID, - PlannerHNS::Lane& out_lane); - - static void CreateLanes(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, - std::vector& out_lanes); - - static void ConnectLanes(UtilityHNS::AisanLanesFileReader* pLaneData, - std::vector& lanes); - - static bool GetPointFromDataList(UtilityHNS::AisanPointsFileReader* pPointsData,const int& pid, WayPoint& out_wp); - - static int GetBeginPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, const int& LnID); - static int GetEndPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID); - - static bool IsStartLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); - static bool IsEndLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); - - static void FixRedundantPointsLanes(std::vector& lanes); - static void FixTwoPointsLanes(std::vector& lanes); - static void FixTwoPointsLane(Lane& lanes); - static void FixUnconnectedLanes(std::vector& lanes); - static void InsertWayPointToBackOfLane(const WayPoint& wp, Lane& lane, int& global_id); - static void InsertWayPointToFrontOfLane(const WayPoint& wp, Lane& lane, int& global_id); + MappingHelpers(); + virtual ~MappingHelpers(); + + static void ConstructRoadNetworkFromROSMessage(const std::vector& lanes_data, + const std::vector& points_data, + const std::vector& dt_data, + const std::vector& intersection_data, + const std::vector& area_data, + const std::vector& line_data, + const std::vector& stop_line_data, + const std::vector& signal_data, + const std::vector& vector_data, + const std::vector& curb_data, + const std::vector& roadedge_data, + const std::vector& wayarea_data, + const std::vector& crosswalk_data, + const std::vector& nodes_data, + const std::vector& conn_data, + const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, + const bool& bFindLaneChangeLanes = false, + const bool& bFindCurbsAndWayArea = false); + + static void ConstructRoadNetworkFromROSMessageV2(const std::vector& lanes_data, + const std::vector& points_data, + const std::vector& dt_data, + const std::vector& intersection_data, + const std::vector& area_data, + const std::vector& line_data, + const std::vector& stop_line_data, + const std::vector& signal_data, + const std::vector& vector_data, + const std::vector& curb_data, + const std::vector& roadedge_data, + const std::vector& wayarea_data, + const std::vector& crosswalk_data, + const std::vector& nodes_data, + const std::vector& conn_data, + UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, + UtilityHNS::AisanLinesFileReader* pLinedata, + const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, + const bool& bFindLaneChangeLanes = false, + const bool& bFindCurbsAndWayArea = false); + + static void ConstructRoadNetworkFromDataFiles(const std::string vectoMapPath, RoadNetwork& map, const bool& bZeroOrigin = false); + + static void UpdateMapWithOccupancyGrid(OccupancyToGridMap& map_info, const std::vector& data, RoadNetwork& map, std::vector& updated_list); + + static bool GetWayPoint(const int& id, const int& laneID,const double& refVel, const int& did, + const std::vector& dtpoints, + const std::vector& points, + const GPSPoint& origin, WayPoint& way_point); + + static void LoadKML(const std::string& kmlMap, RoadNetwork& map); + + static TiXmlElement* GetHeadElement(TiXmlElement* pMainElem); + static TiXmlElement* GetDataFolder(const std::string& folderName, TiXmlElement* pMainElem); + + + static Lane* GetClosestLaneFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0, const bool bDirectionBased = true); + static std::vector GetClosestLanesListFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); + static Lane* GetClosestLaneFromMapDirectionBased(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); + static std::vector GetClosestMultipleLanesFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); + static WayPoint* GetClosestWaypointFromMap(const WayPoint& pos, RoadNetwork& map, const bool bDirectionBased = true); + static std::vector GetClosestLanesFast(const WayPoint& pos, RoadNetwork& map, const double& distance = 10.0); + + static std::vector GetClosestWaypointsListFromMap(const WayPoint& center, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); + + static WayPoint* GetClosestBackWaypointFromMap(const WayPoint& pos, RoadNetwork& map); + static WayPoint GetFirstWaypoint(RoadNetwork& map); + static WayPoint* GetLastWaypoint(RoadNetwork& map); + static void FindAdjacentLanes(RoadNetwork& map); + static void FindAdjacentLanesV2(RoadNetwork& map); + static void ExtractSignalData(const std::vector& signal_data, + const std::vector& vector_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractSignalDataV2(const std::vector& signal_data, + const std::vector& vector_data, + UtilityHNS::AisanPointsFileReader* pPointsData, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractStopLinesData(const std::vector& stop_line_data, + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractStopLinesDataV2(const std::vector& stop_line_data, + UtilityHNS::AisanLinesFileReader* pLineData, + UtilityHNS::AisanPointsFileReader* pPointData, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractCurbData(const std::vector& curb_data, + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractCurbDataV2(const std::vector& curb_data, + UtilityHNS::AisanLinesFileReader* pLinedata, + UtilityHNS::AisanPointsFileReader* pPointsData, + const GPSPoint& origin, RoadNetwork& map); + + static void ExtractWayArea(const std::vector& area_data, + const std::vector& wayarea_data, + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map); + + static void LinkMissingBranchingWayPoints(RoadNetwork& map); + static void LinkMissingBranchingWayPointsV2(RoadNetwork& map); + static void LinkTrafficLightsAndStopLinesConData(const std::vector& conn_data, + const std::vector >& id_replace_list, RoadNetwork& map); + + static void LinkTrafficLightsAndStopLines(RoadNetwork& map); + + static void LinkTrafficLightsAndStopLinesV2(RoadNetwork& map); + + static void GetUniqueNextLanes(const Lane* l, const std::vector& traversed_lanes, std::vector& lanes_list); + + static GPSPoint GetTransformationOrigin(const int& bToyotaCityMap = 0); + + static Lane* GetLaneFromPath(const WayPoint& currPos, const std::vector& currPath); + static Lane* GetLaneById(const int& id,RoadNetwork& map); + static int GetLaneIdByWaypointId(const int& id,std::vector& lanes); + + static WayPoint* FindWaypoint(const int& id, RoadNetwork& map); + static WayPoint* FindWaypointV2(const int& id, const int& l_id, RoadNetwork& map); + + static std::vector GetCurbsList(TiXmlElement* pElem); + static std::vector GetBoundariesList(TiXmlElement* pElem); + static std::vector GetMarkingsList(TiXmlElement* pElem); + static std::vector GetCrossingsList(TiXmlElement* pElem); + static std::vector GetTrafficSignsList(TiXmlElement* pElem); + static std::vector GetTrafficLightsList(TiXmlElement* pElem); + static std::vector GetStopLinesList(TiXmlElement* pElem); + static std::vector GetLanesList(TiXmlElement* pElem); + static std::vector GetRoadSegmentsList(TiXmlElement* pElem); + static std::vector GetIDsFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); + static std::vector GetDoubleFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); + static std::pair GetActionPairFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); + static std::vector GetCenterLaneData(TiXmlElement* pElem, const int& currLaneID); + static std::vector GetCenterLaneDataVer0(TiXmlElement* pElem, const int& currLaneID); + static std::vector GetPointsData(TiXmlElement* pElem); + static std::vector SplitString(const std::string& str, const std::string& token); + + //static void CreateKmlFromLocalizationPathFile(const std::string& pathFileName,const double& maxLaneDistance, const double& density,const std::vector& trafficLights, const std::vector& stopLines); + + static void AssignActionCostToLane(Lane* pL, ACTION_TYPE action, double cost); + + static int ReplaceMyID(int& id, const std::vector >& rep_list); + + static void GetLanesStartPoints(UtilityHNS::AisanLanesFileReader* pLaneData, + std::vector& m_LanesStartIds); + + static void GetLanePoints(UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, int lnID, + PlannerHNS::Lane& out_lane); + + static void CreateLanes(UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, + std::vector& out_lanes); + + static void ConnectLanes(UtilityHNS::AisanLanesFileReader* pLaneData, + std::vector& lanes); + + static bool GetPointFromDataList(UtilityHNS::AisanPointsFileReader* pPointsData,const int& pid, WayPoint& out_wp); + + static int GetBeginPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, const int& LnID); + static int GetEndPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID); + + static bool IsStartLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); + static bool IsEndLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); + + static void FixRedundantPointsLanes(std::vector& lanes); + static void FixTwoPointsLanes(std::vector& lanes); + static void FixTwoPointsLane(Lane& lanes); + static void FixUnconnectedLanes(std::vector& lanes); + static void InsertWayPointToBackOfLane(const WayPoint& wp, Lane& lane, int& global_id); + static void InsertWayPointToFrontOfLane(const WayPoint& wp, Lane& lane, int& global_id); - static void LinkLanesPointers(PlannerHNS::RoadNetwork& map); - - static void GetMapMaxIds(PlannerHNS::RoadNetwork& map); + static void LinkLanesPointers(PlannerHNS::RoadNetwork& map); + + static void GetMapMaxIds(PlannerHNS::RoadNetwork& map); - static double m_USING_VER_ZERO; + static double m_USING_VER_ZERO; - static int g_max_point_id; - static int g_max_lane_id; - static int g_max_stop_line_id; - static int g_max_traffic_light_id ; + static int g_max_point_id; + static int g_max_lane_id; + static int g_max_stop_line_id; + static int g_max_traffic_light_id ; }; diff --git a/common/op_planner/include/op_planner/MatrixOperations.h b/common/op_planner/include/op_planner/MatrixOperations.h index 248dff1c5c6..44b6d4a541c 100755 --- a/common/op_planner/include/op_planner/MatrixOperations.h +++ b/common/op_planner/include/op_planner/MatrixOperations.h @@ -17,61 +17,61 @@ namespace PlannerHNS { class Mat3 { - double m[3][3]; + double m[3][3]; public: - Mat3() - { - //initialize Identity by default - for(int i=0;i<3;i++) - for(int j=0;j<3;j++) - m[i][j] = 0; - - m[0][0] = m[1][1] = m[2][2] = 1; - } - - Mat3(double transX, double transY, bool mirrorX, bool mirrorY ) - { - m[0][0] = (mirrorX == true ) ? -1 : 1; m[0][1] = 0; m[0][2] = transX; - m[1][0] = 0; m[1][1] = (mirrorY==true) ? -1 : 1; m[1][2] = transY; - m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; - } - - Mat3(double transX, double transY) - { - m[0][0] = 1; m[0][1] = 0; m[0][2] = transX; - m[1][0] = 0; m[1][1] = 1; m[1][2] = transY; - m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; - } - - Mat3(double rotation_angle) - { - double c = cos(rotation_angle); - double s = sin(rotation_angle); - m[0][0] = c; m[0][1] = -s; m[0][2] = 0; - m[1][0] = s; m[1][1] = c; m[1][2] = 0; - m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; - } - - Mat3(GPSPoint rotationCenter) - { - double c = cos(rotationCenter.a); - double s = sin(rotationCenter.a); - double u = rotationCenter.x; - double v = rotationCenter.y; - m[0][0] = c; m[0][1] = -s; m[0][2] = -u*c + v*s + u; - m[1][0] = s; m[1][1] = c; m[1][2] = -u*s - v*c + v; - m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; - } - - - GPSPoint operator * (GPSPoint v) - { - GPSPoint _v = v; - v.x = m[0][0]*_v.x + m[0][1]*_v.y + m[0][2]*1; - v.y = m[1][0]*_v.x + m[1][1]*_v.y + m[1][2]*1; - return v; - } + Mat3() + { + //initialize Identity by default + for(int i=0;i<3;i++) + for(int j=0;j<3;j++) + m[i][j] = 0; + + m[0][0] = m[1][1] = m[2][2] = 1; + } + + Mat3(double transX, double transY, bool mirrorX, bool mirrorY ) + { + m[0][0] = (mirrorX == true ) ? -1 : 1; m[0][1] = 0; m[0][2] = transX; + m[1][0] = 0; m[1][1] = (mirrorY==true) ? -1 : 1; m[1][2] = transY; + m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; + } + + Mat3(double transX, double transY) + { + m[0][0] = 1; m[0][1] = 0; m[0][2] = transX; + m[1][0] = 0; m[1][1] = 1; m[1][2] = transY; + m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; + } + + Mat3(double rotation_angle) + { + double c = cos(rotation_angle); + double s = sin(rotation_angle); + m[0][0] = c; m[0][1] = -s; m[0][2] = 0; + m[1][0] = s; m[1][1] = c; m[1][2] = 0; + m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; + } + + Mat3(GPSPoint rotationCenter) + { + double c = cos(rotationCenter.a); + double s = sin(rotationCenter.a); + double u = rotationCenter.x; + double v = rotationCenter.y; + m[0][0] = c; m[0][1] = -s; m[0][2] = -u*c + v*s + u; + m[1][0] = s; m[1][1] = c; m[1][2] = -u*s - v*c + v; + m[2][0] = 0; m[2][1] = 0; m[2][2] = 1; + } + + + GPSPoint operator * (GPSPoint v) + { + GPSPoint _v = v; + v.x = m[0][0]*_v.x + m[0][1]*_v.y + m[0][2]*1; + v.y = m[1][0]*_v.x + m[1][1]*_v.y + m[1][2]*1; + return v; + } }; } /* namespace PlannerHNS */ diff --git a/common/op_planner/include/op_planner/PassiveDecisionMaker.h b/common/op_planner/include/op_planner/PassiveDecisionMaker.h index 0aa23242e42..66adf60aa13 100755 --- a/common/op_planner/include/op_planner/PassiveDecisionMaker.h +++ b/common/op_planner/include/op_planner/PassiveDecisionMaker.h @@ -18,17 +18,17 @@ namespace PlannerHNS class PassiveDecisionMaker { public: - PassiveDecisionMaker(); - PassiveDecisionMaker(const PassiveDecisionMaker& obj); - PassiveDecisionMaker& operator=(const PassiveDecisionMaker& obj); - virtual ~PassiveDecisionMaker(); - PlannerHNS::BehaviorState MoveStep(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); - PlannerHNS::ParticleInfo MoveStepSimple(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); + PassiveDecisionMaker(); + PassiveDecisionMaker(const PassiveDecisionMaker& obj); + PassiveDecisionMaker& operator=(const PassiveDecisionMaker& obj); + virtual ~PassiveDecisionMaker(); + PlannerHNS::BehaviorState MoveStep(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); + PlannerHNS::ParticleInfo MoveStepSimple(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); private: - double GetVelocity(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo, const RelativeInfo& info); - double GetSteerAngle(PlannerHNS::WayPoint& currPose, const std::vector& path, const RelativeInfo& info); - bool CheckForStopLine(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); + double GetVelocity(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo, const RelativeInfo& info); + double GetSteerAngle(PlannerHNS::WayPoint& currPose, const std::vector& path, const RelativeInfo& info); + bool CheckForStopLine(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo); }; diff --git a/common/op_planner/include/op_planner/PlannerCommonDef.h b/common/op_planner/include/op_planner/PlannerCommonDef.h index 8058b7302e6..83ee3d75f14 100755 --- a/common/op_planner/include/op_planner/PlannerCommonDef.h +++ b/common/op_planner/include/op_planner/PlannerCommonDef.h @@ -16,11 +16,11 @@ namespace PlannerHNS enum MAP_SOURCE_TYPE { - MAP_AUTOWARE, - MAP_FOLDER, - MAP_KML_FILE, - MAP_ONE_CSV_FILE, - MAP_LANES_CSV_FILES + MAP_AUTOWARE, + MAP_FOLDER, + MAP_KML_FILE, + MAP_ONE_CSV_FILE, + MAP_LANES_CSV_FILES }; enum CAR_TYPE @@ -35,51 +35,51 @@ enum CAR_TYPE class PID_CONST { public: - double kP; - double kI; - double kD; - - PID_CONST() - { - kP = kI = kD = 0; - } - - PID_CONST(const double& p, const double& i, const double& d) - { - kP = p; - kI = i; - kD = d; - } + double kP; + double kI; + double kD; + + PID_CONST() + { + kP = kI = kD = 0; + } + + PID_CONST(const double& p, const double& i, const double& d) + { + kP = p; + kI = i; + kD = d; + } }; class ControllerParams { public: - double SimulationSteeringDelay; - double SteeringDelay; - double minPursuiteDistance; - PID_CONST Steering_Gain; - PID_CONST Velocity_Gain; - double Acceleration; - double Deceleration; - double FollowDistance; - double LowpassSteerCutoff; - double maxAccel; - double maxDecel; - - - ControllerParams() - { - SimulationSteeringDelay = 0.0; - SteeringDelay = 0.8; - Acceleration = 0.5; - Deceleration = -0.8; - FollowDistance = 8.0; - LowpassSteerCutoff = 5.0; - maxAccel = 0.9; - minPursuiteDistance = 2.0; - maxDecel = -1.5; - } + double SimulationSteeringDelay; + double SteeringDelay; + double minPursuiteDistance; + PID_CONST Steering_Gain; + PID_CONST Velocity_Gain; + double Acceleration; + double Deceleration; + double FollowDistance; + double LowpassSteerCutoff; + double maxAccel; + double maxDecel; + + + ControllerParams() + { + SimulationSteeringDelay = 0.0; + SteeringDelay = 0.8; + Acceleration = 0.5; + Deceleration = -0.8; + FollowDistance = 8.0; + LowpassSteerCutoff = 5.0; + maxAccel = 0.9; + minPursuiteDistance = 2.0; + maxDecel = -1.5; + } }; class CAR_BASIC_INFO @@ -105,22 +105,22 @@ class CAR_BASIC_INFO CAR_BASIC_INFO() { - model = SimulationCar; - turning_radius = 5.2; - wheel_base = 2.7; - max_speed_forward = 3.0; - min_speed_forward = 0.0; - max_speed_backword = 1.0; - max_steer_value = 660; - min_steer_value = -660; - max_brake_value = 0; - min_brake_value = 0; - max_steer_angle = 0.42; - min_steer_angle = 0.42; - length = 4.3; - width = 1.82; - max_acceleration = 1.5; // m/s2 - max_deceleration = -1.5; // 1/3 G + model = SimulationCar; + turning_radius = 5.2; + wheel_base = 2.7; + max_speed_forward = 3.0; + min_speed_forward = 0.0; + max_speed_backword = 1.0; + max_steer_value = 660; + min_steer_value = -660; + max_brake_value = 0; + min_brake_value = 0; + max_steer_angle = 0.42; + min_steer_angle = 0.42; + length = 4.3; + width = 1.82; + max_acceleration = 1.5; // m/s2 + max_deceleration = -1.5; // 1/3 G } double CalcMaxSteeringAngle() @@ -130,31 +130,31 @@ class CAR_BASIC_INFO double BoundSpeed(double s) { - if(s > 0 && s > max_speed_forward) - return max_speed_forward; - if(s < 0 && s < max_speed_backword) - return max_speed_backword; - return s; + if(s > 0 && s > max_speed_forward) + return max_speed_forward; + if(s < 0 && s < max_speed_backword) + return max_speed_backword; + return s; } double BoundSteerAngle(double a) { - if(a > max_steer_angle) - return max_steer_angle; - if(a < min_steer_angle) - return min_steer_angle; + if(a > max_steer_angle) + return max_steer_angle; + if(a < min_steer_angle) + return min_steer_angle; - return a; + return a; } double BoundSteerValue(double v) { - if(v >= max_steer_value) - return max_steer_value; - if(v <= min_steer_value) - return min_steer_value; + if(v >= max_steer_value) + return max_steer_value; + if(v <= min_steer_value) + return min_steer_value; - return v; + return v; } }; diff --git a/common/op_planner/include/op_planner/PlannerH.h b/common/op_planner/include/op_planner/PlannerH.h index c1e446af0f1..0baa789836e 100755 --- a/common/op_planner/include/op_planner/PlannerH.h +++ b/common/op_planner/include/op_planner/PlannerH.h @@ -14,41 +14,42 @@ namespace PlannerHNS { -enum PLANDIRECTION {MOVE_FORWARD_ONLY, MOVE_BACKWARD_ONLY, MOVE_FREE}; +enum PLANDIRECTION {MOVE_FORWARD_ONLY, MOVE_BACKWARD_ONLY, MOVE_FREE}; enum HeuristicConstrains {EUCLIDEAN, NEIGBORHOOD,DIRECTION }; class PlannerH { public: - PlannerH(); - virtual ~PlannerH(); + PlannerH(); + virtual ~PlannerH(); - void GenerateRunoffTrajectory(const std::vector >& referencePaths, const WayPoint& carPos, const bool& bEnableLaneChange, const double& speed, const double& microPlanDistance, - const double& maxSpeed,const double& minSpeed, const double& carTipMargin, const double& rollInMargin, - const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, - const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, - const double& SmoothTolerance, const double& speedProfileFactor, const bool& bHeadingSmooth, - const int& iCurrGlobalPath, const int& iCurrLocalTraj, - std::vector > >& rollOutsPaths, - std::vector& sampledPoints); + void GenerateRunoffTrajectory(const std::vector >& referencePaths, const WayPoint& carPos, const bool& bEnableLaneChange, const double& speed, const double& microPlanDistance, + const double& maxSpeed,const double& minSpeed, const double& carTipMargin, const double& rollInMargin, + const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, + const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, + const double& SmoothTolerance, const double& speedProfileFactor, const bool& bHeadingSmooth, + const int& iCurrGlobalPath, const int& iCurrLocalTraj, + std::vector > >& rollOutsPaths, + std::vector& sampledPoints); - double PlanUsingDP(const WayPoint& carPos,const WayPoint& goalPos, - const double& maxPlanningDistance, const bool bEnableLaneChange, const std::vector& globalPath, - RoadNetwork& map, std::vector >& paths, std::vector* all_cell_to_delete = 0); + double PlanUsingDP(const WayPoint& carPos,const WayPoint& goalPos, + const double& maxPlanningDistance, const bool bEnableLaneChange, const std::vector& globalPath, + RoadNetwork& map, std::vector >& paths, std::vector* all_cell_to_delete = 0, + double fallback_min_goal_distance_th = 0.0); - double PlanUsingDPRandom(const WayPoint& start, - const double& maxPlanningDistance, - RoadNetwork& map, - std::vector >& paths); + double PlanUsingDPRandom(const WayPoint& start, + const double& maxPlanningDistance, + RoadNetwork& map, + std::vector >& paths); - double PredictPlanUsingDP(Lane* lane, const WayPoint& carPos, const double& maxPlanningDistance, - std::vector >& paths); + double PredictPlanUsingDP(Lane* lane, const WayPoint& carPos, const double& maxPlanningDistance, + std::vector >& paths); - double PredictPlanUsingDP(const WayPoint& startPose, WayPoint* closestWP, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches = true); + double PredictPlanUsingDP(const WayPoint& startPose, WayPoint* closestWP, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches = true); - double PredictTrajectoriesUsingDP(const WayPoint& startPose, std::vector closestWPs, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches = true, const bool bDirectionBased = false, const bool pathDensity = 1.0); + double PredictTrajectoriesUsingDP(const WayPoint& startPose, std::vector closestWPs, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches = true, const bool bDirectionBased = false, const bool pathDensity = 1.0); - void DeleteWaypoints(std::vector& wps); + void DeleteWaypoints(std::vector& wps); }; } diff --git a/common/op_planner/include/op_planner/PlanningHelpers.h b/common/op_planner/include/op_planner/PlanningHelpers.h index 8243ae1c9a5..ffa348be9ec 100755 --- a/common/op_planner/include/op_planner/PlanningHelpers.h +++ b/common/op_planner/include/op_planner/PlanningHelpers.h @@ -29,164 +29,167 @@ class PlanningHelpers { public: - static std::vector > m_TestingClosestPoint; + static std::vector > m_TestingClosestPoint; public: - PlanningHelpers(); - virtual ~PlanningHelpers(); + PlanningHelpers(); + virtual ~PlanningHelpers(); - static bool GetRelativeInfo(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex = 0); + static bool GetRelativeInfo(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex = 0); - static bool GetRelativeInfoRange(const std::vector >& trajectories, const WayPoint& p, const double& searchDistance, RelativeInfo& info); + static bool GetRelativeInfoRange(const std::vector >& trajectories, const WayPoint& p, const double& searchDistance, RelativeInfo& info); - static bool GetRelativeInfoLimited(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex = 0); + static bool GetRelativeInfoLimited(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex = 0); - static WayPoint GetFollowPointOnTrajectory(const std::vector& trajectory, const RelativeInfo& init_p, const double& distance, unsigned int& point_index); + static WayPoint GetFollowPointOnTrajectory(const std::vector& trajectory, const RelativeInfo& init_p, const double& distance, unsigned int& point_index); - static double GetExactDistanceOnTrajectory(const std::vector& trajectory, const RelativeInfo& p1,const RelativeInfo& p2); + static double GetExactDistanceOnTrajectory(const std::vector& trajectory, const RelativeInfo& p1,const RelativeInfo& p2); - static int GetClosestNextPointIndex_obsolete(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static int GetClosestNextPointIndex_obsolete(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static int GetClosestNextPointIndexFast(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static int GetClosestNextPointIndexFast(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static int GetClosestNextPointIndexFastV2(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static int GetClosestNextPointIndexFastV2(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static int GetClosestNextPointIndexDirectionFast(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static int GetClosestNextPointIndexDirectionFast(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static int GetClosestNextPointIndexDirectionFastV2(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static int GetClosestNextPointIndexDirectionFastV2(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static int GetClosestPointIndex_obsolete(const std::vector& trajectory, const WayPoint& p,const int& prevIndex = 0 ); + static int GetClosestPointIndex_obsolete(const std::vector& trajectory, const WayPoint& p,const int& prevIndex = 0 ); - static WayPoint GetPerpendicularOnTrajectory_obsolete(const std::vector& trajectory, const WayPoint& p, double& distance, const int& prevIndex = 0); static double GetPerpDistanceToTrajectorySimple_obsolete(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); + static WayPoint GetPerpendicularOnTrajectory_obsolete(const std::vector& trajectory, const WayPoint& p, double& distance, const int& prevIndex = 0); static double GetPerpDistanceToTrajectorySimple_obsolete(const std::vector& trajectory, const WayPoint& p, const int& prevIndex = 0); - static double GetPerpDistanceToVectorSimple_obsolete(const WayPoint& p1, const WayPoint& p2, const WayPoint& pose); + static double GetPerpDistanceToVectorSimple_obsolete(const WayPoint& p1, const WayPoint& p2, const WayPoint& pose); - static WayPoint GetNextPointOnTrajectory_obsolete(const std::vector& trajectory, const double& distance, const int& currIndex = 0); + static WayPoint GetNextPointOnTrajectory_obsolete(const std::vector& trajectory, const double& distance, const int& currIndex = 0); - static double GetDistanceOnTrajectory_obsolete(const std::vector& path, const int& start_index, const WayPoint& p); + static double GetDistanceOnTrajectory_obsolete(const std::vector& path, const int& start_index, const WayPoint& p); - static void CreateManualBranch(std::vector& path, const int& degree, const DIRECTION_TYPE& direction); + static void CreateManualBranch(std::vector& path, const int& degree, const DIRECTION_TYPE& direction); - static void CreateManualBranchFromTwoPoints(WayPoint& p1,WayPoint& p2 , const double& distance, const DIRECTION_TYPE& direction, std::vector& path); + static void CreateManualBranchFromTwoPoints(WayPoint& p1,WayPoint& p2 , const double& distance, const DIRECTION_TYPE& direction, std::vector& path); - static void FixPathDensity(std::vector& path, const double& distanceDensity); + static void FixPathDensity(std::vector& path, const double& distanceDensity); - static void SmoothPath(std::vector& path, double weight_data =0.25,double weight_smooth = 0.25,double tolerance = 0.01); + static void SmoothPath(std::vector& path, double weight_data =0.25,double weight_smooth = 0.25,double tolerance = 0.01); - static double CalcCircle(const GPSPoint& pt1, const GPSPoint& pt2, const GPSPoint& pt3, GPSPoint& center); + static double CalcCircle(const GPSPoint& pt1, const GPSPoint& pt2, const GPSPoint& pt3, GPSPoint& center); - static void FixAngleOnly(std::vector& path); + static void FixAngleOnly(std::vector& path); - static double CalcAngleAndCost(std::vector& path, const double& lastCost = 0, const bool& bSmooth = true ); + static double CalcAngleAndCost(std::vector& path, const double& lastCost = 0, const bool& bSmooth = true ); - //static double CalcAngleAndCostSimple(std::vector& path, const double& lastCost = 0); + //static double CalcAngleAndCostSimple(std::vector& path, const double& lastCost = 0); - static double CalcAngleAndCostAndCurvatureAnd2D(std::vector& path, const double& lastCost = 0); + static double CalcAngleAndCostAndCurvatureAnd2D(std::vector& path, const double& lastCost = 0); - static void PredictConstantTimeCostForTrajectory(std::vector& path, const PlannerHNS::WayPoint& currPose, const double& minVelocity, const double& minDist); + static void PredictConstantTimeCostForTrajectory(std::vector& path, const PlannerHNS::WayPoint& currPose, const double& minVelocity, const double& minDist); - static double GetAccurateDistanceOnTrajectory(std::vector& path, const int& start_index, const WayPoint& p); + static double GetAccurateDistanceOnTrajectory(std::vector& path, const int& start_index, const WayPoint& p); - static void ExtractPartFromPointToDistance(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, std::vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance); + static void ExtractPartFromPointToDistance(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, + const double& pathDensity, std::vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance); - static void ExtractPartFromPointToDistanceFast(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, std::vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance); + static void ExtractPartFromPointToDistanceFast(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, + const double& pathDensity, std::vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance); - static void ExtractPartFromPointToDistanceDirectionFast(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, std::vector& extractedPath); + static void ExtractPartFromPointToDistanceDirectionFast(const std::vector& originalPath, const WayPoint& pos, const double& minDistance, + const double& pathDensity, std::vector& extractedPath); - static void CalculateRollInTrajectories(const WayPoint& carPos, const double& speed, const std::vector& originalCenter, int& start_index, - int& end_index, std::vector& end_laterals , - std::vector >& rollInPaths, const double& max_roll_distance, - const double& maxSpeed, const double& carTipMargin, const double& rollInMargin, - const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, - const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, - const double& SmoothTolerance, const bool& bHeadingSmooth, - std::vector& sampledPoints); + static void CalculateRollInTrajectories(const WayPoint& carPos, const double& speed, const std::vector& originalCenter, int& start_index, + int& end_index, std::vector& end_laterals , + std::vector >& rollInPaths, const double& max_roll_distance, + const double& maxSpeed, const double& carTipMargin, const double& rollInMargin, + const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, + const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, + const double& SmoothTolerance, const bool& bHeadingSmooth, + std::vector& sampledPoints); - static void SmoothSpeedProfiles(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); + static void SmoothSpeedProfiles(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); - static void SmoothCurvatureProfiles(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); + static void SmoothCurvatureProfiles(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); - static void SmoothWayPointsDirections(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); + static void SmoothWayPointsDirections(std::vector& path_in, double weight_data, double weight_smooth, double tolerance = 0.1); - static void SmoothGlobalPathSpeed(std::vector& path); + static void SmoothGlobalPathSpeed(std::vector& path); - static void GenerateRecommendedSpeed(std::vector& path, const double& max_speed, const double& speedProfileFactor); + static void GenerateRecommendedSpeed(std::vector& path, const double& max_speed, const double& speedProfileFactor); -// static WayPoint* BuildPlanningSearchTree(Lane* l, const WayPoint& prevWayPointIndex, -// const WayPoint& startPos, const WayPoint& goalPos, -// const std::vector& globalPath, const double& DistanceLimit, -// int& nMaxLeftBranches, int& nMaxRightBranches, -// std::vector& all_cells_to_delete ); +// static WayPoint* BuildPlanningSearchTree(Lane* l, const WayPoint& prevWayPointIndex, +// const WayPoint& startPos, const WayPoint& goalPos, +// const std::vector& globalPath, const double& DistanceLimit, +// int& nMaxLeftBranches, int& nMaxRightBranches, +// std::vector& all_cells_to_delete ); - static WayPoint* BuildPlanningSearchTreeV2(WayPoint* pStart, - const WayPoint& goalPos, - const std::vector& globalPath, const double& DistanceLimit, - const bool& bEnableLaneChange, - std::vector& all_cells_to_delete ); + static WayPoint* BuildPlanningSearchTreeV2(WayPoint* pStart, + const WayPoint& goalPos, + const std::vector& globalPath, const double& DistanceLimit, + const bool& bEnableLaneChange, + std::vector& all_cells_to_delete, + double fallback_min_goal_distance_th = 0.0 ); - static WayPoint* BuildPlanningSearchTreeStraight(WayPoint* pStart, - const double& DistanceLimit, - std::vector& all_cells_to_delete ); + static WayPoint* BuildPlanningSearchTreeStraight(WayPoint* pStart, + const double& DistanceLimit, + std::vector& all_cells_to_delete ); - static int PredictiveDP(WayPoint* pStart, const double& DistanceLimit, - std::vector& all_cells_to_delete, std::vector& end_waypoints); + static int PredictiveDP(WayPoint* pStart, const double& DistanceLimit, + std::vector& all_cells_to_delete, std::vector& end_waypoints); - static int PredictiveIgnorIdsDP(WayPoint* pStart, const double& DistanceLimit, - std::vector& all_cells_to_delete, std::vector& end_waypoints, std::vector& lanes_ids); + static int PredictiveIgnorIdsDP(WayPoint* pStart, const double& DistanceLimit, + std::vector& all_cells_to_delete, std::vector& end_waypoints, std::vector& lanes_ids); - static bool CheckLaneIdExits(const std::vector& lanes, const Lane* pL); + static bool CheckLaneIdExits(const std::vector& lanes, const Lane* pL); - static WayPoint* CheckLaneExits(const std::vector& nodes, const Lane* pL); + static WayPoint* CheckLaneExits(const std::vector& nodes, const Lane* pL); - static WayPoint* CheckNodeExits(const std::vector& nodes, const WayPoint* pL); + static WayPoint* CheckNodeExits(const std::vector& nodes, const WayPoint* pL); - static WayPoint* CreateLaneHeadCell(Lane* pLane, WayPoint* pLeft, WayPoint* pRight, - WayPoint* pBack); + static int FindNodeIndex(const std::vector& nodes, const WayPoint* p); - static double GetLanePoints(Lane* l, const WayPoint& prevWayPointIndex, - const double& minDistance , const double& prevCost, std::vector& points); + static WayPoint* CreateLaneHeadCell(Lane* pLane, WayPoint* pLeft, WayPoint* pRight, + WayPoint* pBack); - static WayPoint* GetMinCostCell(const std::vector& cells, const std::vector& globalPathIds); + static double GetLanePoints(Lane* l, const WayPoint& prevWayPointIndex, + const double& minDistance , const double& prevCost, std::vector& points); - static void TraversePathTreeBackwards(WayPoint* pHead, WayPoint* pStartWP, const std::vector& globalPathIds, - std::vector& localPath, std::vector >& localPaths); + static WayPoint* GetMinCostCell(const std::vector& cells, const std::vector& globalPathIds); - static void ExtractPlanAlernatives(const std::vector& singlePath, std::vector >& allPaths); + static void TraversePathTreeBackwards(WayPoint* pHead, WayPoint* pStartWP, const std::vector& globalPathIds, + std::vector& localPath, std::vector >& localPaths); - static std::vector GetUniqueLeftRightIds(const std::vector& path); + static void ExtractPlanAlernatives(const std::vector& singlePath, std::vector >& allPaths); - static bool FindInList(const std::vector& list,const int& x); + static std::vector GetUniqueLeftRightIds(const std::vector& path); - static void RemoveWithValue(std::vector& list,const int& x); + static bool FindInList(const std::vector& list,const int& x); - static ACTION_TYPE GetBranchingDirection(WayPoint& currWP, WayPoint& nextWP); + static void RemoveWithValue(std::vector& list,const int& x); - static void CalcContourPointsForDetectedObjects(const WayPoint& currPose, std::vector& obj_list, const double& filterDistance = 100); + static ACTION_TYPE GetBranchingDirection(WayPoint& currWP, WayPoint& nextWP); - static double GetVelocityAhead(const std::vector& path, const RelativeInfo& info,int& prev_index, const double& reasonable_brake_distance); + static void CalcContourPointsForDetectedObjects(const WayPoint& currPose, std::vector& obj_list, const double& filterDistance = 100); - static bool CompareTrajectories(const std::vector& path1, const std::vector& path2); + static double GetVelocityAhead(const std::vector& path, const RelativeInfo& info,int& prev_index, const double& reasonable_brake_distance); - static double GetDistanceToClosestStopLineAndCheck(const std::vector& path, const WayPoint& p, const double& giveUpDistance, int& stopLineID,int& stopSignID, int& trafficLightID, const int& prevIndex = 0); + static bool CompareTrajectories(const std::vector& path1, const std::vector& path2); - static bool GetThreePointsInfo(const WayPoint& p0, const WayPoint& p1, const WayPoint& p2, WayPoint& perp_p, double& long_d, double lat_d); + static double GetDistanceToClosestStopLineAndCheck(const std::vector& path, const WayPoint& p, const double& giveUpDistance, int& stopLineID,int& stopSignID, int& trafficLightID, const int& prevIndex = 0); - static void WritePathToFile(const std::string& fileName, const std::vector& path); + static bool GetThreePointsInfo(const WayPoint& p0, const WayPoint& p1, const WayPoint& p2, WayPoint& perp_p, double& long_d, double lat_d); - static LIGHT_INDICATOR GetIndicatorsFromPath(const std::vector& path, const WayPoint& pose, const double& seachDistance); + static void WritePathToFile(const std::string& fileName, const std::vector& path); - static PlannerHNS::WayPoint GetRealCenter(const PlannerHNS::WayPoint& currState, const double& wheel_base); + static LIGHT_INDICATOR GetIndicatorsFromPath(const std::vector& path, const WayPoint& pose, const double& seachDistance); - static void TestQuadraticSpline(const std::vector& center_line, std::vector& path); + static PlannerHNS::WayPoint GetRealCenter(const PlannerHNS::WayPoint& currState, const double& wheel_base); - static double frunge ( double x ); + static void TestQuadraticSpline(const std::vector& center_line, std::vector& path); - static double fprunge ( double x ); + static double frunge ( double x ); - static double fpprunge ( double x ); + static double fprunge ( double x ); + + static double fpprunge ( double x ); }; diff --git a/common/op_planner/include/op_planner/RoadNetwork.h b/common/op_planner/include/op_planner/RoadNetwork.h index 506c9e91850..1b3ecb32a4b 100755 --- a/common/op_planner/include/op_planner/RoadNetwork.h +++ b/common/op_planner/include/op_planner/RoadNetwork.h @@ -19,8 +19,8 @@ namespace PlannerHNS { -enum DIRECTION_TYPE { FORWARD_DIR, FORWARD_LEFT_DIR, FORWARD_RIGHT_DIR, - BACKWARD_DIR, BACKWARD_LEFT_DIR, BACKWARD_RIGHT_DIR, STANDSTILL_DIR}; +enum DIRECTION_TYPE { FORWARD_DIR, FORWARD_LEFT_DIR, FORWARD_RIGHT_DIR, + BACKWARD_DIR, BACKWARD_LEFT_DIR, BACKWARD_RIGHT_DIR, STANDSTILL_DIR}; enum OBSTACLE_TYPE {SIDEWALK, TREE, CAR, TRUCK, HOUSE, PEDESTRIAN, CYCLIST, GENERAL_OBSTACLE}; @@ -29,15 +29,15 @@ enum DRIVABLE_TYPE {DIRT, TARMAC, PARKINGAREA, INDOOR, GENERAL_AREA}; enum GLOBAL_STATE_TYPE {G_WAITING_STATE, G_PLANING_STATE, G_FORWARD_STATE, G_BRANCHING_STATE, G_FINISH_STATE}; enum STATE_TYPE {INITIAL_STATE, WAITING_STATE, FORWARD_STATE, STOPPING_STATE, EMERGENCY_STATE, - TRAFFIC_LIGHT_STOP_STATE,TRAFFIC_LIGHT_WAIT_STATE, STOP_SIGN_STOP_STATE, STOP_SIGN_WAIT_STATE, FOLLOW_STATE, LANE_CHANGE_STATE, OBSTACLE_AVOIDANCE_STATE, GOAL_STATE, FINISH_STATE, YIELDING_STATE, BRANCH_LEFT_STATE, BRANCH_RIGHT_STATE}; + TRAFFIC_LIGHT_STOP_STATE,TRAFFIC_LIGHT_WAIT_STATE, STOP_SIGN_STOP_STATE, STOP_SIGN_WAIT_STATE, FOLLOW_STATE, LANE_CHANGE_STATE, OBSTACLE_AVOIDANCE_STATE, GOAL_STATE, FINISH_STATE, YIELDING_STATE, BRANCH_LEFT_STATE, BRANCH_RIGHT_STATE}; enum LIGHT_INDICATOR {INDICATOR_LEFT, INDICATOR_RIGHT, INDICATOR_BOTH , INDICATOR_NONE}; enum SHIFT_POS {SHIFT_POS_PP = 0x60, SHIFT_POS_RR = 0x40, SHIFT_POS_NN = 0x20, - SHIFT_POS_DD = 0x10, SHIFT_POS_BB = 0xA0, SHIFT_POS_SS = 0x0f, SHIFT_POS_UU = 0xff }; + SHIFT_POS_DD = 0x10, SHIFT_POS_BB = 0xA0, SHIFT_POS_SS = 0x0f, SHIFT_POS_UU = 0xff }; enum ACTION_TYPE {FORWARD_ACTION, BACKWARD_ACTION, STOP_ACTION, LEFT_TURN_ACTION, - RIGHT_TURN_ACTION, U_TURN_ACTION, SWERVE_ACTION, OVERTACK_ACTION, START_ACTION, SLOWDOWN_ACTION, CHANGE_DESTINATION, WAITING_ACTION, DESTINATION_REACHED, UNKOWN_ACTION}; + RIGHT_TURN_ACTION, U_TURN_ACTION, SWERVE_ACTION, OVERTACK_ACTION, START_ACTION, SLOWDOWN_ACTION, CHANGE_DESTINATION, WAITING_ACTION, DESTINATION_REACHED, UNKOWN_ACTION}; enum BEH_STATE_TYPE {BEH_FORWARD_STATE=0,BEH_STOPPING_STATE=1, BEH_BRANCH_LEFT_STATE=2, BEH_BRANCH_RIGHT_STATE=3, BEH_YIELDING_STATE=4, BEH_ACCELERATING_STATE=5, BEH_SLOWDOWN_STATE=6}; @@ -55,13 +55,13 @@ class RoadSegment; class ObjTimeStamp { public: - timespec tStamp; + timespec tStamp; - ObjTimeStamp() - { - tStamp.tv_nsec = 0; - tStamp.tv_sec = 0; - } + ObjTimeStamp() + { + tStamp.tv_nsec = 0; + tStamp.tv_sec = 0; + } }; //class POINT2D @@ -85,40 +85,40 @@ class ObjTimeStamp class GPSPoint { public: - double lat, x; - double lon, y; - double alt, z; - double dir, a; - - GPSPoint() - { - lat = x = 0; - lon = y = 0; - alt = z = 0; - dir = a = 0; - } - - GPSPoint(const double& x, const double& y, const double& z, const double& a) - { - this->x = x; - this->y = y; - this->z = z; - this->a = a; - - lat = 0; - lon = 0; - alt = 0; - dir = 0; - } - - std::string ToString() - { - std::stringstream str; - str.precision(12); - str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; - str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; - return str.str(); - } + double lat, x; + double lon, y; + double alt, z; + double dir, a; + + GPSPoint() + { + lat = x = 0; + lon = y = 0; + alt = z = 0; + dir = a = 0; + } + + GPSPoint(const double& x, const double& y, const double& z, const double& a) + { + this->x = x; + this->y = y; + this->z = z; + this->a = a; + + lat = 0; + lon = 0; + alt = 0; + dir = 0; + } + + std::string ToString() + { + std::stringstream str; + str.precision(12); + str << "X:" << x << ", Y:" << y << ", Z:" << z << ", A:" << a << std::endl; + str << "Lon:" << lon << ", Lat:" << lat << ", Alt:" << alt << ", Dir:" << dir << std::endl; + return str.str(); + } }; class RECTANGLE @@ -149,8 +149,8 @@ class RECTANGLE RECTANGLE() { - width=0; - length = 0; + width=0; + length = 0; bObstacle = true; } @@ -160,45 +160,45 @@ class RECTANGLE class PolygonShape { public: - std::vector points; - - inline int PointInsidePolygon(const PolygonShape& polygon,const GPSPoint& p) - { - int counter = 0; - int i; - double xinters; - GPSPoint p1,p2; - int N = polygon.points.size(); - if(N <=0 ) return -1; - - p1 = polygon.points.at(0); - for (i=1;i<=N;i++) - { - p2 = polygon.points.at(i % N); - - if (p.y > MIN(p1.y,p2.y)) - { - if (p.y <= MAX(p1.y,p2.y)) - { - if (p.x <= MAX(p1.x,p2.x)) - { - if (p1.y != p2.y) - { - xinters = (p.y-p1.y)*(p2.x-p1.x)/(p2.y-p1.y)+p1.x; - if (p1.x == p2.x || p.x <= xinters) - counter++; - } - } - } - } - p1 = p2; - } - - if (counter % 2 == 0) - return 0; - else - return 1; - } + std::vector points; + + inline int PointInsidePolygon(const PolygonShape& polygon,const GPSPoint& p) + { + int counter = 0; + int i; + double xinters; + GPSPoint p1,p2; + int N = polygon.points.size(); + if(N <=0 ) return -1; + + p1 = polygon.points.at(0); + for (i=1;i<=N;i++) + { + p2 = polygon.points.at(i % N); + + if (p.y > MIN(p1.y,p2.y)) + { + if (p.y <= MAX(p1.y,p2.y)) + { + if (p.x <= MAX(p1.x,p2.x)) + { + if (p1.y != p2.y) + { + xinters = (p.y-p1.y)*(p2.x-p1.x)/(p2.y-p1.y)+p1.x; + if (p1.x == p2.x || p.x <= xinters) + counter++; + } + } + } + } + p1 = p2; + } + + if (counter % 2 == 0) + return 0; + else + return 1; + } }; class MapItem @@ -352,270 +352,270 @@ class DrivableArea : public MapItem class Rotation { public: - double x; - double y; - double z; - double w; - - Rotation() - { - x = 0; - y = 0; - z = 0; - w = 0; - } + double x; + double y; + double z; + double w; + + Rotation() + { + x = 0; + y = 0; + z = 0; + w = 0; + } }; class WayPoint { public: - GPSPoint pos; - Rotation rot; - double v; - double cost; - double timeCost; - double totalReward; - double collisionCost; - double laneChangeCost; - int laneId; - int id; - int LeftPointId; - int RightPointId; - int LeftLnId; - int RightLnId; - int stopLineID; - DIRECTION_TYPE bDir; - STATE_TYPE state; - BEH_STATE_TYPE beh_state; - int iOriginalIndex; - - Lane* pLane; - WayPoint* pLeft; - WayPoint* pRight; - std::vector toIds; - std::vector fromIds; - std::vector pFronts; - std::vector pBacks; - std::vector > actionCost; - - int originalMapID; - int gid; - - WayPoint() - { - id = 0; - v = 0; - cost = 0; - laneId = -1; - pLane = 0; - pLeft = 0; - pRight = 0; - bDir = FORWARD_DIR; - LeftPointId = 0; - RightPointId = 0; - LeftLnId = 0; - RightLnId = 0; - timeCost = 0; - totalReward = 0; - collisionCost = 0; - laneChangeCost = 0; - stopLineID = -1; - state = INITIAL_STATE; - beh_state = BEH_STOPPING_STATE; - iOriginalIndex = 0; - - gid = 0; - originalMapID = -1; - } - - WayPoint(const double& x, const double& y, const double& z, const double& a) - { - pos.x = x; - pos.y = y; - pos.z = z; - pos.a = a; - - id = 0; - v = 0; - cost = 0; - laneId = -1; - pLane = 0; - pLeft = 0; - pRight = 0; - bDir = FORWARD_DIR; - LeftPointId = 0; - RightPointId = 0; - LeftLnId = 0; - RightLnId = 0; - timeCost = 0; - totalReward = 0; - collisionCost = 0; - laneChangeCost = 0; - stopLineID = -1; - iOriginalIndex = 0; - state = INITIAL_STATE; - beh_state = BEH_STOPPING_STATE; - - gid = 0; - originalMapID = -1; - } + GPSPoint pos; + Rotation rot; + double v; + double cost; + double timeCost; + double totalReward; + double collisionCost; + double laneChangeCost; + int laneId; + int id; + int LeftPointId; + int RightPointId; + int LeftLnId; + int RightLnId; + int stopLineID; + DIRECTION_TYPE bDir; + STATE_TYPE state; + BEH_STATE_TYPE beh_state; + int iOriginalIndex; + + Lane* pLane; + WayPoint* pLeft; + WayPoint* pRight; + std::vector toIds; + std::vector fromIds; + std::vector pFronts; + std::vector pBacks; + std::vector > actionCost; + + int originalMapID; + int gid; + + WayPoint() + { + id = 0; + v = 0; + cost = 0; + laneId = -1; + pLane = 0; + pLeft = 0; + pRight = 0; + bDir = FORWARD_DIR; + LeftPointId = 0; + RightPointId = 0; + LeftLnId = 0; + RightLnId = 0; + timeCost = 0; + totalReward = 0; + collisionCost = 0; + laneChangeCost = 0; + stopLineID = -1; + state = INITIAL_STATE; + beh_state = BEH_STOPPING_STATE; + iOriginalIndex = 0; + + gid = 0; + originalMapID = -1; + } + + WayPoint(const double& x, const double& y, const double& z, const double& a) + { + pos.x = x; + pos.y = y; + pos.z = z; + pos.a = a; + + id = 0; + v = 0; + cost = 0; + laneId = -1; + pLane = 0; + pLeft = 0; + pRight = 0; + bDir = FORWARD_DIR; + LeftPointId = 0; + RightPointId = 0; + LeftLnId = 0; + RightLnId = 0; + timeCost = 0; + totalReward = 0; + collisionCost = 0; + laneChangeCost = 0; + stopLineID = -1; + iOriginalIndex = 0; + state = INITIAL_STATE; + beh_state = BEH_STOPPING_STATE; + + gid = 0; + originalMapID = -1; + } }; class RelativeInfo { public: - double perp_distance; - double to_front_distance; //negative - double from_back_distance; - int iFront; - int iBack; - int iGlobalPath; - WayPoint perp_point; - double angle_diff; // degrees - bool bBefore; - bool bAfter; - double after_angle; - - RelativeInfo() - { - after_angle = 0; - bBefore = false; - bAfter = false; - perp_distance = 0; - to_front_distance = 0; - from_back_distance = 0; - iFront = 0; - iBack = 0; - iGlobalPath = 0; - angle_diff = 0; - } + double perp_distance; + double to_front_distance; //negative + double from_back_distance; + int iFront; + int iBack; + int iGlobalPath; + WayPoint perp_point; + double angle_diff; // degrees + bool bBefore; + bool bAfter; + double after_angle; + + RelativeInfo() + { + after_angle = 0; + bBefore = false; + bAfter = false; + perp_distance = 0; + to_front_distance = 0; + from_back_distance = 0; + iFront = 0; + iBack = 0; + iGlobalPath = 0; + angle_diff = 0; + } }; class Boundary //represent wayarea in vector map { public: - int id; - int roadId; - std::vector points; - RoadSegment* pSegment; - - Boundary() - { - id = 0; - roadId =0; - pSegment = nullptr; - } + int id; + int roadId; + std::vector points; + RoadSegment* pSegment; + + Boundary() + { + id = 0; + roadId =0; + pSegment = nullptr; + } }; class Curb { public: - int id; - int laneId; - int roadId; - std::vector points; - Lane* pLane; - - Curb() - { - id = 0; - laneId =0; - roadId =0; - pLane = 0; - } + int id; + int laneId; + int roadId; + std::vector points; + Lane* pLane; + + Curb() + { + id = 0; + laneId =0; + roadId =0; + pLane = 0; + } }; class Crossing { public: - int id; - int roadId; - std::vector points; - RoadSegment* pSegment; - - Crossing() - { - id = 0; - roadId =0; - pSegment = nullptr; - } + int id; + int roadId; + std::vector points; + RoadSegment* pSegment; + + Crossing() + { + id = 0; + roadId =0; + pSegment = nullptr; + } }; class StopLine { public: - int id; - int laneId; - int roadId; - int trafficLightID; - int stopSignID; - std::vector points; - Lane* pLane; - int linkID; - - StopLine() - { - id = 0; - laneId =0; - roadId =0; - pLane = 0; - trafficLightID = -1; - stopSignID = -1; - linkID = 0; - } + int id; + int laneId; + int roadId; + int trafficLightID; + int stopSignID; + std::vector points; + Lane* pLane; + int linkID; + + StopLine() + { + id = 0; + laneId =0; + roadId =0; + pLane = 0; + trafficLightID = -1; + stopSignID = -1; + linkID = 0; + } }; class WaitingLine { public: - int id; - int laneId; - int roadId; - std::vector points; - Lane* pLane; - - WaitingLine() - { - id = 0; - laneId =0; - roadId =0; - pLane = 0; - } + int id; + int laneId; + int roadId; + std::vector points; + Lane* pLane; + + WaitingLine() + { + id = 0; + laneId =0; + roadId =0; + pLane = 0; + } }; class TrafficSign { public: - int id; - int laneId; - int roadId; - - GPSPoint pos; - TrafficSignTypes signType; - double value; - double fromValue; - double toValue; - std::string strValue; - timespec timeValue; - timespec fromTimeValue; - timespec toTimeValue; - - Lane* pLane; - - TrafficSign() - { - id = 0; - laneId = 0; - roadId = 0; - signType = UNKNOWN_SIGN; - value = 0; - fromValue = 0; - toValue = 0; -// timeValue = 0; -// fromTimeValue = 0; -// toTimeValue = 0; - pLane = 0; - } + int id; + int laneId; + int roadId; + + GPSPoint pos; + TrafficSignTypes signType; + double value; + double fromValue; + double toValue; + std::string strValue; + timespec timeValue; + timespec fromTimeValue; + timespec toTimeValue; + + Lane* pLane; + + TrafficSign() + { + id = 0; + laneId = 0; + roadId = 0; + signType = UNKNOWN_SIGN; + value = 0; + fromValue = 0; + toValue = 0; +// timeValue = 0; +// fromTimeValue = 0; +// toTimeValue = 0; + pLane = 0; + } }; enum TrafficLightState {UNKNOWN_LIGHT, RED_LIGHT, GREEN_LIGHT, YELLOW_LIGHT, LEFT_GREEN, FORWARD_GREEN, RIGHT_GREEN, FLASH_YELLOW, FLASH_RED}; @@ -623,78 +623,78 @@ enum TrafficLightState {UNKNOWN_LIGHT, RED_LIGHT, GREEN_LIGHT, YELLOW_LIGHT, LEF class TrafficLight { public: - int id; - GPSPoint pos; - TrafficLightState lightState; - double stoppingDistance; - std::vector laneIds; - std::vector pLanes; - int linkID; - - TrafficLight() - { - stoppingDistance = 2; - id = 0; - lightState = GREEN_LIGHT; - linkID = 0; - } - - bool CheckLane(const int& laneId) - { - for(unsigned int i=0; i < laneIds.size(); i++) - { - if(laneId == laneIds.at(i)) - return true; - } - return false; - } + int id; + GPSPoint pos; + TrafficLightState lightState; + double stoppingDistance; + std::vector laneIds; + std::vector pLanes; + int linkID; + + TrafficLight() + { + stoppingDistance = 2; + id = 0; + lightState = GREEN_LIGHT; + linkID = 0; + } + + bool CheckLane(const int& laneId) + { + for(unsigned int i=0; i < laneIds.size(); i++) + { + if(laneId == laneIds.at(i)) + return true; + } + return false; + } }; class Marking { public: - int id; - int laneId; - int roadId; - MARKING_TYPE mark_type; - GPSPoint center; - std::vector points; - Lane* pLane; - - Marking() - { - id = 0; - laneId = 0; - roadId = 0; - mark_type = UNKNOWN_MARK; - pLane = nullptr; - } + int id; + int laneId; + int roadId; + MARKING_TYPE mark_type; + GPSPoint center; + std::vector points; + Lane* pLane; + + Marking() + { + id = 0; + laneId = 0; + roadId = 0; + mark_type = UNKNOWN_MARK; + pLane = nullptr; + } }; class RoadSegment { public: - int id; + int id; - SEGMENT_TYPE roadType; - Boundary boundary; - Crossing start_crossing; - Crossing finish_crossing; - double avgWidth; - std::vector fromIds; - std::vector toIds; - std::vector Lanes; + SEGMENT_TYPE roadType; + Boundary boundary; + Crossing start_crossing; + Crossing finish_crossing; + double avgWidth; + std::vector fromIds; + std::vector toIds; + std::vector Lanes; - std::vector fromLanes; - std::vector toLanes; + std::vector fromLanes; + std::vector toLanes; - RoadSegment() - { - id = 0; - avgWidth = 0; - roadType = NORMAL_ROAD_SEG; - } + RoadSegment() + { + id = 0; + avgWidth = 0; + roadType = NORMAL_ROAD_SEG; + } }; @@ -704,637 +704,637 @@ enum LaneType{NORMAL_LANE, MERGE_LANE, EXIT_LANE, BUS_LANE, BUS_STOP_LANE, EMERG class Lane { public: - int id; - int roadId; - int areaId; - int fromAreaId; - int toAreaId; - std::vector fromIds; - std::vector toIds; - int num; //lane number in the road segment from left to right - double speed; - double length; - double dir; - LaneType type; - double width; - std::vector points; - std::vector trafficlights; - std::vector stopLines; - WaitingLine waitingLine; - - std::vector fromLanes; - std::vector toLanes; - Lane* pLeftLane; - Lane* pRightLane; - - RoadSegment * pRoad; - - Lane() - { - id = 0; - num = 0; - speed = 0; - length = 0; - dir = 0; - type = NORMAL_LANE; - width = 0; - pLeftLane = 0; - pRightLane = 0; - pRoad = 0; - roadId = 0; - areaId = 0; - fromAreaId = 0; - toAreaId = 0; - } + int id; + int roadId; + int areaId; + int fromAreaId; + int toAreaId; + std::vector fromIds; + std::vector toIds; + int num; //lane number in the road segment from left to right + double speed; + double length; + double dir; + LaneType type; + double width; + std::vector points; + std::vector trafficlights; + std::vector stopLines; + WaitingLine waitingLine; + + std::vector fromLanes; + std::vector toLanes; + Lane* pLeftLane; + Lane* pRightLane; + + RoadSegment * pRoad; + + Lane() + { + id = 0; + num = 0; + speed = 0; + length = 0; + dir = 0; + type = NORMAL_LANE; + width = 0; + pLeftLane = 0; + pRightLane = 0; + pRoad = 0; + roadId = 0; + areaId = 0; + fromAreaId = 0; + toAreaId = 0; + } }; class RoadNetwork { public: - std::vector roadSegments; - std::vector trafficLights; - std::vector stopLines; - std::vector curbs; - std::vector boundaries; - std::vector crossings; - std::vector markings; - std::vector signs; + std::vector roadSegments; + std::vector trafficLights; + std::vector stopLines; + std::vector curbs; + std::vector boundaries; + std::vector crossings; + std::vector markings; + std::vector signs; }; class VehicleState : public ObjTimeStamp { public: - double speed; - double steer; - SHIFT_POS shift; + double speed; + double steer; + SHIFT_POS shift; - VehicleState() - { - speed = 0; - steer = 0; - shift = SHIFT_POS_NN; - } + VehicleState() + { + speed = 0; + steer = 0; + shift = SHIFT_POS_NN; + } }; class BehaviorState { public: - STATE_TYPE state; - double maxVelocity; - double minVelocity; - double stopDistance; - double followVelocity; - double followDistance; - LIGHT_INDICATOR indicator; - bool bNewPlan; - int iTrajectory; - - - BehaviorState() - { - state = INITIAL_STATE; - maxVelocity = 0; - minVelocity = 0; - stopDistance = 0; - followVelocity = 0; - followDistance = 0; - indicator = INDICATOR_NONE; - bNewPlan = false; - iTrajectory = -1; - - } + STATE_TYPE state; + double maxVelocity; + double minVelocity; + double stopDistance; + double followVelocity; + double followDistance; + LIGHT_INDICATOR indicator; + bool bNewPlan; + int iTrajectory; + + + BehaviorState() + { + state = INITIAL_STATE; + maxVelocity = 0; + minVelocity = 0; + stopDistance = 0; + followVelocity = 0; + followDistance = 0; + indicator = INDICATOR_NONE; + bNewPlan = false; + iTrajectory = -1; + + } }; class DetectedObject { public: - int id; - std::string label; - OBSTACLE_TYPE t; - WayPoint center; - WayPoint predicted_center; - WayPoint noisy_center; - STATE_TYPE predicted_behavior; - std::vector centers_list; - std::vector contour; - std::vector > predTrajectories; - std::vector pClosestWaypoints; - double w; - double l; - double h; - double distance_to_center; - - double actual_speed; - double actual_yaw; - - bool bDirection; - bool bVelocity; - int acceleration; - - int acceleration_desc; - double acceleration_raw; - - LIGHT_INDICATOR indicator_state; - - int originalID; - BEH_STATE_TYPE behavior_state; - - DetectedObject() - { - bDirection = false; - bVelocity = false; - acceleration = 0; - acceleration_desc = 0; - acceleration_raw = 0.0; - id = 0; - w = 0; - l = 0; - h = 0; - t = GENERAL_OBSTACLE; - distance_to_center = 0; - predicted_behavior = INITIAL_STATE; - actual_speed = 0; - actual_yaw = 0; - - acceleration_desc = 0; - acceleration_raw = 0.0; - indicator_state = INDICATOR_NONE; - - originalID = -1; - behavior_state = BEH_STOPPING_STATE; - } + int id; + std::string label; + OBSTACLE_TYPE t; + WayPoint center; + WayPoint predicted_center; + WayPoint noisy_center; + STATE_TYPE predicted_behavior; + std::vector centers_list; + std::vector contour; + std::vector > predTrajectories; + std::vector pClosestWaypoints; + double w; + double l; + double h; + double distance_to_center; + + double actual_speed; + double actual_yaw; + + bool bDirection; + bool bVelocity; + int acceleration; + + int acceleration_desc; + double acceleration_raw; + + LIGHT_INDICATOR indicator_state; + + int originalID; + BEH_STATE_TYPE behavior_state; + + DetectedObject() + { + bDirection = false; + bVelocity = false; + acceleration = 0; + acceleration_desc = 0; + acceleration_raw = 0.0; + id = 0; + w = 0; + l = 0; + h = 0; + t = GENERAL_OBSTACLE; + distance_to_center = 0; + predicted_behavior = INITIAL_STATE; + actual_speed = 0; + actual_yaw = 0; + + acceleration_desc = 0; + acceleration_raw = 0.0; + indicator_state = INDICATOR_NONE; + + originalID = -1; + behavior_state = BEH_STOPPING_STATE; + } }; class PlanningParams { public: - double maxSpeed; - double minSpeed; - double planningDistance; - double microPlanDistance; - double carTipMargin; - double rollInMargin; - double rollInSpeedFactor; - double pathDensity; - double rollOutDensity; - int rollOutNumber; - double horizonDistance; - double minFollowingDistance; //should be bigger than Distance to follow - double minDistanceToAvoid; // should be smaller than minFollowingDistance and larger than maxDistanceToAvoid - double maxDistanceToAvoid; // should be smaller than minDistanceToAvoid - double speedProfileFactor; - double smoothingDataWeight; - double smoothingSmoothWeight; - double smoothingToleranceError; - - double stopSignStopTime; - - double additionalBrakingDistance; - double verticalSafetyDistance; - double horizontalSafetyDistancel; - - double giveUpDistance; - - int nReliableCount; - - bool enableLaneChange; - bool enableSwerving; - bool enableFollowing; - bool enableHeadingSmoothing; - bool enableTrafficLightBehavior; - bool enableStopSignBehavior; - - bool enabTrajectoryVelocities; - double minIndicationDistance; - - PlanningParams() - { - maxSpeed = 3; - minSpeed = 0; - planningDistance = 10000; - microPlanDistance = 30; - carTipMargin = 4.0; - rollInMargin = 12.0; - rollInSpeedFactor = 0.25; - pathDensity = 0.25; - rollOutDensity = 0.5; - rollOutNumber = 4; - horizonDistance = 120; - minFollowingDistance = 35; - minDistanceToAvoid = 15; - maxDistanceToAvoid = 5; - speedProfileFactor = 1.0; - smoothingDataWeight = 0.47; - smoothingSmoothWeight = 0.2; - smoothingToleranceError = 0.05; - - stopSignStopTime = 2.0; - - additionalBrakingDistance = 10.0; - verticalSafetyDistance = 0.0; - horizontalSafetyDistancel = 0.0; - - giveUpDistance = -4; - nReliableCount = 2; - - enableHeadingSmoothing = false; - enableSwerving = false; - enableFollowing = false; - enableTrafficLightBehavior = false; - enableLaneChange = false; - enableStopSignBehavior = false; - enabTrajectoryVelocities = false; - minIndicationDistance = 15; - } + double maxSpeed; + double minSpeed; + double planningDistance; + double microPlanDistance; + double carTipMargin; + double rollInMargin; + double rollInSpeedFactor; + double pathDensity; + double rollOutDensity; + int rollOutNumber; + double horizonDistance; + double minFollowingDistance; //should be bigger than Distance to follow + double minDistanceToAvoid; // should be smaller than minFollowingDistance and larger than maxDistanceToAvoid + double maxDistanceToAvoid; // should be smaller than minDistanceToAvoid + double speedProfileFactor; + double smoothingDataWeight; + double smoothingSmoothWeight; + double smoothingToleranceError; + + double stopSignStopTime; + + double additionalBrakingDistance; + double verticalSafetyDistance; + double horizontalSafetyDistancel; + + double giveUpDistance; + + int nReliableCount; + + bool enableLaneChange; + bool enableSwerving; + bool enableFollowing; + bool enableHeadingSmoothing; + bool enableTrafficLightBehavior; + bool enableStopSignBehavior; + + bool enabTrajectoryVelocities; + double minIndicationDistance; + + PlanningParams() + { + maxSpeed = 3; + minSpeed = 0; + planningDistance = 10000; + microPlanDistance = 30; + carTipMargin = 4.0; + rollInMargin = 12.0; + rollInSpeedFactor = 0.25; + pathDensity = 0.25; + rollOutDensity = 0.5; + rollOutNumber = 4; + horizonDistance = 120; + minFollowingDistance = 35; + minDistanceToAvoid = 15; + maxDistanceToAvoid = 5; + speedProfileFactor = 1.0; + smoothingDataWeight = 0.47; + smoothingSmoothWeight = 0.2; + smoothingToleranceError = 0.05; + + stopSignStopTime = 2.0; + + additionalBrakingDistance = 10.0; + verticalSafetyDistance = 0.0; + horizontalSafetyDistancel = 0.0; + + giveUpDistance = -4; + nReliableCount = 2; + + enableHeadingSmoothing = false; + enableSwerving = false; + enableFollowing = false; + enableTrafficLightBehavior = false; + enableLaneChange = false; + enableStopSignBehavior = false; + enabTrajectoryVelocities = false; + minIndicationDistance = 15; + } }; class HMIPreCalculatedConditions { public: - HMIPreCalculatedConditions() - { + HMIPreCalculatedConditions() + { - } + } }; class PreCalculatedConditions { public: - //-------------------------------------------// - //Global Goals - int currentGoalID; - int prevGoalID; - //-------------------------------------------// - //Following - double distanceToNext; - double velocityOfNext; - //-------------------------------------------// - //For Lane Change - int iPrevSafeLane; - int iCurrSafeLane; - double distanceToGoBack; - double timeToGoBack; - double distanceToChangeLane; - double timeToChangeLane; - int currentLaneID; - int originalLaneID; - int targetLaneID; - bool bUpcomingLeft; - bool bUpcomingRight; - bool bCanChangeLane; - bool bTargetLaneSafe; - //-------------------------------------------// - //Traffic Lights & Stop Sign - int currentStopSignID; - int prevStopSignID; - int currentTrafficLightID; - int prevTrafficLightID; - bool bTrafficIsRed; //On , off status - //-------------------------------------------// - //Swerving - int iPrevSafeTrajectory; - int iCurrSafeTrajectory; - int iCentralTrajectory; - bool bFullyBlock; - LIGHT_INDICATOR indicator; - - //-------------------------------------------// - //General - bool bNewGlobalPath; - bool bRePlan; - double currentVelocity; - double minStoppingDistance; //comfortably - int bOutsideControl; // 0 waiting, 1 start, 2 Green Traffic Light, 3 Red Traffic Light, 5 Emergency Stop - bool bGreenOutsideControl; - std::vector stoppingDistances; - - - double distanceToStop() - { - if(stoppingDistances.size()==0) return 0; - double minS = stoppingDistances.at(0); - for(unsigned int i=0; i< stoppingDistances.size(); i++) - { - if(stoppingDistances.at(i) < minS) - minS = stoppingDistances.at(i); - } - return minS; - } - - PreCalculatedConditions() - { - currentGoalID = 0; - prevGoalID = -1; - currentVelocity = 0; - minStoppingDistance = 1; - bOutsideControl = 0; - bGreenOutsideControl = false; - //distance to stop - distanceToNext = -1; - velocityOfNext = 0; - currentStopSignID = -1; - prevStopSignID = -1; - currentTrafficLightID = -1; - prevTrafficLightID = -1; - bTrafficIsRed = false; - iCurrSafeTrajectory = -1; - bFullyBlock = false; - - iPrevSafeTrajectory = -1; - iCentralTrajectory = -1; - bRePlan = false; - bNewGlobalPath = false; - - bCanChangeLane = false; - distanceToGoBack = 0; - timeToGoBack = 0; - distanceToChangeLane = 0; - timeToChangeLane = 0; - bTargetLaneSafe = true; - bUpcomingLeft = false; - bUpcomingRight = false; - targetLaneID = -1; - currentLaneID = -1; - originalLaneID = -1; - iCurrSafeLane = -1; - iPrevSafeLane = -1; - - indicator = INDICATOR_NONE; - } - - virtual ~PreCalculatedConditions(){} - - std::string ToStringHeader() - { - return "Time:General>>:currentVelocity:distanceToStop:minStoppingDistance:bStartBehaviorGenerator:bGoalReached:" - "Following>>:velocityOfNext:distanceToNext:" - "TrafficLight>>:currentTrafficLightID:bTrafficIsRed:" - "Swerving>>:iSafeTrajectory:bFullyBlock:"; - } - - std::string ToString(STATE_TYPE beh) - { - std::string str = "Unknown"; - switch(beh) - { - case PlannerHNS::INITIAL_STATE: - str = "Init"; - break; - case PlannerHNS::WAITING_STATE: - str = "Waiting"; - break; - case PlannerHNS::FORWARD_STATE: - str = "Forward"; - break; - case PlannerHNS::STOPPING_STATE: - str = "Stop"; - break; - case PlannerHNS::FINISH_STATE: - str = "End"; - break; - case PlannerHNS::FOLLOW_STATE: - str = "Follow"; - break; - case PlannerHNS::OBSTACLE_AVOIDANCE_STATE: - str = "Swerving"; - break; - case PlannerHNS::TRAFFIC_LIGHT_STOP_STATE: - str = "Light Stop"; - break; - case PlannerHNS::TRAFFIC_LIGHT_WAIT_STATE: - str = "Light Wait"; - break; - case PlannerHNS::STOP_SIGN_STOP_STATE: - str = "Sign Stop"; - break; - case PlannerHNS::STOP_SIGN_WAIT_STATE: - str = "Sign Wait"; - break; - default: - str = "Unknown"; - break; - } - - return str; - } + //-------------------------------------------// + //Global Goals + int currentGoalID; + int prevGoalID; + //-------------------------------------------// + //Following + double distanceToNext; + double velocityOfNext; + //-------------------------------------------// + //For Lane Change + int iPrevSafeLane; + int iCurrSafeLane; + double distanceToGoBack; + double timeToGoBack; + double distanceToChangeLane; + double timeToChangeLane; + int currentLaneID; + int originalLaneID; + int targetLaneID; + bool bUpcomingLeft; + bool bUpcomingRight; + bool bCanChangeLane; + bool bTargetLaneSafe; + //-------------------------------------------// + //Traffic Lights & Stop Sign + int currentStopSignID; + int prevStopSignID; + int currentTrafficLightID; + int prevTrafficLightID; + bool bTrafficIsRed; //On , off status + //-------------------------------------------// + //Swerving + int iPrevSafeTrajectory; + int iCurrSafeTrajectory; + int iCentralTrajectory; + bool bFullyBlock; + LIGHT_INDICATOR indicator; + + //-------------------------------------------// + //General + bool bNewGlobalPath; + bool bRePlan; + double currentVelocity; + double minStoppingDistance; //comfortably + int bOutsideControl; // 0 waiting, 1 start, 2 Green Traffic Light, 3 Red Traffic Light, 5 Emergency Stop + bool bGreenOutsideControl; + std::vector stoppingDistances; + + + double distanceToStop() + { + if(stoppingDistances.size()==0) return 0; + double minS = stoppingDistances.at(0); + for(unsigned int i=0; i< stoppingDistances.size(); i++) + { + if(stoppingDistances.at(i) < minS) + minS = stoppingDistances.at(i); + } + return minS; + } + + PreCalculatedConditions() + { + currentGoalID = 0; + prevGoalID = -1; + currentVelocity = 0; + minStoppingDistance = 1; + bOutsideControl = 0; + bGreenOutsideControl = false; + //distance to stop + distanceToNext = -1; + velocityOfNext = 0; + currentStopSignID = -1; + prevStopSignID = -1; + currentTrafficLightID = -1; + prevTrafficLightID = -1; + bTrafficIsRed = false; + iCurrSafeTrajectory = -1; + bFullyBlock = false; + + iPrevSafeTrajectory = -1; + iCentralTrajectory = -1; + bRePlan = false; + bNewGlobalPath = false; + + bCanChangeLane = false; + distanceToGoBack = 0; + timeToGoBack = 0; + distanceToChangeLane = 0; + timeToChangeLane = 0; + bTargetLaneSafe = true; + bUpcomingLeft = false; + bUpcomingRight = false; + targetLaneID = -1; + currentLaneID = -1; + originalLaneID = -1; + iCurrSafeLane = -1; + iPrevSafeLane = -1; + + indicator = INDICATOR_NONE; + } + + virtual ~PreCalculatedConditions(){} + + std::string ToStringHeader() + { + return "Time:General>>:currentVelocity:distanceToStop:minStoppingDistance:bStartBehaviorGenerator:bGoalReached:" + "Following>>:velocityOfNext:distanceToNext:" + "TrafficLight>>:currentTrafficLightID:bTrafficIsRed:" + "Swerving>>:iSafeTrajectory:bFullyBlock:"; + } + + std::string ToString(STATE_TYPE beh) + { + std::string str = "Unknown"; + switch(beh) + { + case PlannerHNS::INITIAL_STATE: + str = "Init"; + break; + case PlannerHNS::WAITING_STATE: + str = "Waiting"; + break; + case PlannerHNS::FORWARD_STATE: + str = "Forward"; + break; + case PlannerHNS::STOPPING_STATE: + str = "Stop"; + break; + case PlannerHNS::FINISH_STATE: + str = "End"; + break; + case PlannerHNS::FOLLOW_STATE: + str = "Follow"; + break; + case PlannerHNS::OBSTACLE_AVOIDANCE_STATE: + str = "Swerving"; + break; + case PlannerHNS::TRAFFIC_LIGHT_STOP_STATE: + str = "Light Stop"; + break; + case PlannerHNS::TRAFFIC_LIGHT_WAIT_STATE: + str = "Light Wait"; + break; + case PlannerHNS::STOP_SIGN_STOP_STATE: + str = "Sign Stop"; + break; + case PlannerHNS::STOP_SIGN_WAIT_STATE: + str = "Sign Wait"; + break; + default: + str = "Unknown"; + break; + } + + return str; + } }; class TrajectoryCost { public: - int index; - int relative_index; - double closest_obj_velocity; - double distance_from_center; - double priority_cost; //0 to 1 - double transition_cost; // 0 to 1 - double closest_obj_cost; // 0 to 1 - double cost; - double closest_obj_distance; - - int lane_index; - double lane_change_cost; - double lateral_cost; - double longitudinal_cost; - bool bBlocked; - std::vector > lateral_costs; - - - TrajectoryCost() - { - lane_index = -1; - index = -1; - relative_index = -100; - closest_obj_velocity = 0; - priority_cost = 0; - transition_cost = 0; - closest_obj_cost = 0; - distance_from_center = 0; - cost = 0; - closest_obj_distance = -1; - lane_change_cost = 0; - lateral_cost = 0; - longitudinal_cost = 0; - bBlocked = false; - } - - std::string ToString() - { - std::ostringstream str; - str.precision(4); - str << "LI : " << lane_index; - str << ", In : " << relative_index; - str << ", Co : " << cost; - str << ", Pr : " << priority_cost; - str << ", Tr : " << transition_cost; - str << ", La : " << lateral_cost; - str << ", Lo : " << longitudinal_cost; - str << ", Ln : " << lane_change_cost; - str << ", Bl : " << bBlocked; - str << "\n"; - for (unsigned int i=0; i > lateral_costs; + + + TrajectoryCost() + { + lane_index = -1; + index = -1; + relative_index = -100; + closest_obj_velocity = 0; + priority_cost = 0; + transition_cost = 0; + closest_obj_cost = 0; + distance_from_center = 0; + cost = 0; + closest_obj_distance = -1; + lane_change_cost = 0; + lateral_cost = 0; + longitudinal_cost = 0; + bBlocked = false; + } + + std::string ToString() + { + std::ostringstream str; + str.precision(4); + str << "LI : " << lane_index; + str << ", In : " << relative_index; + str << ", Co : " << cost; + str << ", Pr : " << priority_cost; + str << ", Tr : " << transition_cost; + str << ", La : " << lateral_cost; + str << ", Lo : " << longitudinal_cost; + str << ", Ln : " << lane_change_cost; + str << ", Bl : " << bBlocked; + str << "\n"; + for (unsigned int i=0; i& data, int& _cell) - { - int col = floor(p.x / res); - int row = floor(p.y / res); - - int index = -1; - if(row >= 0 && row < length && col >=0 && col < width) - { - index = get2dIndex(row,col); - - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - //printf("Cell Info: P(%f,%f) , D(%f,%f), G(%d,%d), index = %d \n", p.x, p.y, p.x-center.pos.x, p.y-center.pos.y, col, row , index); - return true; - } - } - - if(row+1 >= 0 && row+1 < length && col >=0 && col < width) - { - index = get2dIndex(row+1,col); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row >= 0 && row < length && col+1 >=0 && col+1 < width) - { - index = get2dIndex(row,col+1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row-1 >= 0 && row-1 < length && col >=0 && col < width) - { - index = get2dIndex(row-1,col); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row >= 0 && row < length && col-1 >=0 && col-1 < width) - { - index = get2dIndex(row,col-1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row+1 >= 0 && row+1 < length && col+1 >=0 && col+1 < width) - { - index = get2dIndex(row+1,col+1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row-1 >= 0 && row-1 < length && col-1 >=0 && col-1 < width) - { - index = get2dIndex(row-1,col-1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row-1 >= 0 && row-1 < length && col+1 >=0 && col+1 < width) - { - index = get2dIndex(row-1,col+1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - if(row+1 >= 0 && row+1 < length && col-1 >=0 && col-1 < width) - { - index = get2dIndex(row+1,col-1); - if(index >= 0 && index < (int)data.size()) - { - _cell = data.at((unsigned int)index); - return true; - } - } - - //printf("Error Getting Cell with Info: P(%f,%f) , C(%d,%d), index = %d \n", p.x, p.y, row, col, index); - return false; - } + int width; + int length; + double res; + WayPoint center; + + OccupancyToGridMap(const int& _width, const int& _length, const double& _res, const WayPoint& _center) + { + width = _width; + length = _length; + res = _res; + center = _center; + } + + OccupancyToGridMap() + { + width = 0; + length = 0; + res = 0.0; + } + + bool GetCellIndexFromPoint(const GPSPoint& p, const std::vector& data, int& _cell) + { + int col = floor(p.x / res); + int row = floor(p.y / res); + + int index = -1; + if(row >= 0 && row < length && col >=0 && col < width) + { + index = get2dIndex(row,col); + + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + //printf("Cell Info: P(%f,%f) , D(%f,%f), G(%d,%d), index = %d \n", p.x, p.y, p.x-center.pos.x, p.y-center.pos.y, col, row , index); + return true; + } + } + + if(row+1 >= 0 && row+1 < length && col >=0 && col < width) + { + index = get2dIndex(row+1,col); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row >= 0 && row < length && col+1 >=0 && col+1 < width) + { + index = get2dIndex(row,col+1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row-1 >= 0 && row-1 < length && col >=0 && col < width) + { + index = get2dIndex(row-1,col); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row >= 0 && row < length && col-1 >=0 && col-1 < width) + { + index = get2dIndex(row,col-1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row+1 >= 0 && row+1 < length && col+1 >=0 && col+1 < width) + { + index = get2dIndex(row+1,col+1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row-1 >= 0 && row-1 < length && col-1 >=0 && col-1 < width) + { + index = get2dIndex(row-1,col-1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row-1 >= 0 && row-1 < length && col+1 >=0 && col+1 < width) + { + index = get2dIndex(row-1,col+1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + if(row+1 >= 0 && row+1 < length && col-1 >=0 && col-1 < width) + { + index = get2dIndex(row+1,col-1); + if(index >= 0 && index < (int)data.size()) + { + _cell = data.at((unsigned int)index); + return true; + } + } + + //printf("Error Getting Cell with Info: P(%f,%f) , C(%d,%d), index = %d \n", p.x, p.y, row, col, index); + return false; + } private: - int get2dIndex(const int& r,const int& c) - { - return ((r*width) + c); - } + int get2dIndex(const int& r,const int& c) + { + return ((r*width) + c); + } }; class ParticleInfo { public: - double vel; - int acl; //slow down -1 braking , 0 cruising , 1 accelerating - PlannerHNS::LIGHT_INDICATOR indicator; - PlannerHNS::STATE_TYPE state; - - ParticleInfo() - { - vel = 0; - acl = 0; - indicator = PlannerHNS::INDICATOR_NONE; - state = PlannerHNS::FORWARD_STATE; - } + double vel; + int acl; //slow down -1 braking , 0 cruising , 1 accelerating + PlannerHNS::LIGHT_INDICATOR indicator; + PlannerHNS::STATE_TYPE state; + + ParticleInfo() + { + vel = 0; + acl = 0; + indicator = PlannerHNS::INDICATOR_NONE; + state = PlannerHNS::FORWARD_STATE; + } }; } diff --git a/common/op_planner/include/op_planner/SimuDecisionMaker.h b/common/op_planner/include/op_planner/SimuDecisionMaker.h index fa1605ae0d9..bfa9915ca2c 100644 --- a/common/op_planner/include/op_planner/SimuDecisionMaker.h +++ b/common/op_planner/include/op_planner/SimuDecisionMaker.h @@ -17,39 +17,39 @@ namespace PlannerHNS class SimuDecisionMaker: public PlannerHNS::DecisionMaker { public: - SimuDecisionMaker(); - virtual ~SimuDecisionMaker(); - - //For Simulation - std::vector m_CarShapePolygon; - PlannerHNS::WayPoint m_OdometryState; - double m_CurrentVelocity, m_CurrentVelocityD; //meter/second - double m_CurrentSteering, m_CurrentSteeringD; //radians - PlannerHNS::SHIFT_POS m_CurrentShift , m_CurrentShiftD; - - double m_CurrentAccSteerAngle; //degrees steer wheel range - double m_CurrentAccVelocity; // kilometer/hour - double m_SimulationSteeringDelayFactor; //second , time that every degree change in the steering wheel takes - timespec m_SteerDelayTimer; - PlannerHNS::TrajectoryDynamicCosts m_TrajectoryCostsCalculator; - - void ReInitializePlanner(const WayPoint& start_pose); - void InitPolygons(); - void SetSimulatedTargetOdometryReadings(const double& velocity_d, const double& steering_d, const SHIFT_POS& shift_d); - void FirstLocalizeMe(const PlannerHNS::WayPoint& initCarPos); - void LocalizeMe(const double& dt); // in seconds - void UpdateState(const PlannerHNS::VehicleState& state, const bool& bUseDelay = false); - void GenerateLocalRollOuts(); - - bool SelectSafeTrajectory(); - PlannerHNS::VehicleState LocalizeStep(const double& dt, const PlannerHNS::VehicleState& desiredStatus); - - PlannerHNS::BehaviorState DoOneStep(const double& dt, - const PlannerHNS::VehicleState& vehicleState, - const int& goalID, - const std::vector& trafficLight, - const std::vector& objects, - const bool& bEmergencyStop); + SimuDecisionMaker(); + virtual ~SimuDecisionMaker(); + + //For Simulation + std::vector m_CarShapePolygon; + PlannerHNS::WayPoint m_OdometryState; + double m_CurrentVelocity, m_CurrentVelocityD; //meter/second + double m_CurrentSteering, m_CurrentSteeringD; //radians + PlannerHNS::SHIFT_POS m_CurrentShift , m_CurrentShiftD; + + double m_CurrentAccSteerAngle; //degrees steer wheel range + double m_CurrentAccVelocity; // kilometer/hour + double m_SimulationSteeringDelayFactor; //second , time that every degree change in the steering wheel takes + timespec m_SteerDelayTimer; + PlannerHNS::TrajectoryDynamicCosts m_TrajectoryCostsCalculator; + + void ReInitializePlanner(const WayPoint& start_pose); + void InitPolygons(); + void SetSimulatedTargetOdometryReadings(const double& velocity_d, const double& steering_d, const SHIFT_POS& shift_d); + void FirstLocalizeMe(const PlannerHNS::WayPoint& initCarPos); + void LocalizeMe(const double& dt); // in seconds + void UpdateState(const PlannerHNS::VehicleState& state, const bool& bUseDelay = false); + void GenerateLocalRollOuts(); + + bool SelectSafeTrajectory(); + PlannerHNS::VehicleState LocalizeStep(const double& dt, const PlannerHNS::VehicleState& desiredStatus); + + PlannerHNS::BehaviorState DoOneStep(const double& dt, + const PlannerHNS::VehicleState& vehicleState, + const int& goalID, + const std::vector& trafficLight, + const std::vector& objects, + const bool& bEmergencyStop); }; } diff --git a/common/op_planner/include/op_planner/TrajectoryCosts.h b/common/op_planner/include/op_planner/TrajectoryCosts.h index a9b07d92cfc..840dfbfe77c 100755 --- a/common/op_planner/include/op_planner/TrajectoryCosts.h +++ b/common/op_planner/include/op_planner/TrajectoryCosts.h @@ -20,35 +20,35 @@ namespace PlannerHNS class TrajectoryCosts { public: - TrajectoryCosts(); - virtual ~TrajectoryCosts(); + TrajectoryCosts(); + virtual ~TrajectoryCosts(); - TrajectoryCost DoOneStep(const vector > >& rollOuts, const vector >& totalPaths, - const WayPoint& currState, const int& currTrajectoryIndex, const int& currLaneIndex, const PlanningParams& params, - const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const std::vector& obj_list); + TrajectoryCost DoOneStep(const vector > >& rollOuts, const vector >& totalPaths, + const WayPoint& currState, const int& currTrajectoryIndex, const int& currLaneIndex, const PlanningParams& params, + const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const std::vector& obj_list); public: - int m_PrevCostIndex; - vector m_TrajectoryCosts; - PlanningParams m_Params; - PolygonShape m_SafetyBorder; - vector m_AllContourPoints; - vector m_CollisionPoints; - double m_WeightPriority; - double m_WeightTransition; - double m_WeightLong; - double m_WeightLat; - double m_WeightLaneChange; - double m_LateralSkipDistance; + int m_PrevCostIndex; + vector m_TrajectoryCosts; + PlanningParams m_Params; + PolygonShape m_SafetyBorder; + vector m_AllContourPoints; + vector m_CollisionPoints; + double m_WeightPriority; + double m_WeightTransition; + double m_WeightLong; + double m_WeightLat; + double m_WeightLaneChange; + double m_LateralSkipDistance; private: - bool ValidateRollOutsInput(const vector > >& rollOuts); - vector CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, const int& lane_index, const PlanningParams& params); - void NormalizeCosts(vector& trajectoryCosts); - void CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, const vector > >& rollOuts, const vector >& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); - void CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params); + bool ValidateRollOutsInput(const vector > >& rollOuts); + vector CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, const int& lane_index, const PlanningParams& params); + void NormalizeCosts(vector& trajectoryCosts); + void CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, const vector > >& rollOuts, const vector >& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); + void CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params); }; } diff --git a/common/op_planner/include/op_planner/TrajectoryDynamicCosts.h b/common/op_planner/include/op_planner/TrajectoryDynamicCosts.h index 46606a22007..5496ff25cb4 100755 --- a/common/op_planner/include/op_planner/TrajectoryDynamicCosts.h +++ b/common/op_planner/include/op_planner/TrajectoryDynamicCosts.h @@ -20,54 +20,54 @@ namespace PlannerHNS class TrajectoryDynamicCosts { public: - TrajectoryDynamicCosts(); - virtual ~TrajectoryDynamicCosts(); + TrajectoryDynamicCosts(); + virtual ~TrajectoryDynamicCosts(); - TrajectoryCost DoOneStep(const vector > >& rollOuts, const vector >& totalPaths, - const WayPoint& currState, const int& currTrajectoryIndex, const int& currLaneIndex, const PlanningParams& params, - const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const std::vector& obj_list); + TrajectoryCost DoOneStep(const vector > >& rollOuts, const vector >& totalPaths, + const WayPoint& currState, const int& currTrajectoryIndex, const int& currLaneIndex, const PlanningParams& params, + const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const std::vector& obj_list); - TrajectoryCost DoOneStepStatic(const vector >& rollOuts, const vector& totalPaths, - const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list, const int& iCurrentIndex = -1); + TrajectoryCost DoOneStepStatic(const vector >& rollOuts, const vector& totalPaths, + const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list, const int& iCurrentIndex = -1); - TrajectoryCost DoOneStepDynamic(const vector >& rollOuts, const vector& totalPaths, - const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list, const int& iCurrentIndex = -1); + TrajectoryCost DoOneStepDynamic(const vector >& rollOuts, const vector& totalPaths, + const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list, const int& iCurrentIndex = -1); public: - int m_PrevCostIndex; - int m_PrevIndex; - vector m_TrajectoryCosts; - PlanningParams m_Params; - PolygonShape m_SafetyBorder; - vector m_AllContourPoints; - vector m_CollisionPoints; - double m_WeightPriority; - double m_WeightTransition; - double m_WeightLong; - double m_WeightLat; - double m_WeightLaneChange; - double m_LateralSkipDistance; - double m_CollisionTimeDiff; + int m_PrevCostIndex; + int m_PrevIndex; + vector m_TrajectoryCosts; + PlanningParams m_Params; + PolygonShape m_SafetyBorder; + vector m_AllContourPoints; + vector m_CollisionPoints; + double m_WeightPriority; + double m_WeightTransition; + double m_WeightLong; + double m_WeightLat; + double m_WeightLaneChange; + double m_LateralSkipDistance; + double m_CollisionTimeDiff; private: - bool ValidateRollOutsInput(const vector > >& rollOuts); - vector CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, const int& lane_index, const PlanningParams& params); - void NormalizeCosts(vector& trajectoryCosts); - void CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, const vector > >& rollOuts, const vector >& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); - void CalculateLateralAndLongitudinalCostsStatic(vector& trajectoryCosts, const vector >& rollOuts, const vector& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); - void CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params); - - void CalculateIntersectionVelocities(const std::vector& path, const DetectedObject& obj, const WayPoint& currPose, const CAR_BASIC_INFO& carInfo, const double& c_lateral_d, WayPoint& collisionPoint, TrajectoryCost& trajectoryCosts); - int GetCurrentRollOutIndex(const std::vector& path, const WayPoint& currState, const PlanningParams& params); - void InitializeCosts(const vector >& rollOuts, const PlanningParams& params); - void InitializeSafetyPolygon(const WayPoint& currState, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d); - void CalculateLateralAndLongitudinalCostsDynamic(const std::vector& obj_list, const vector >& rollOuts, const vector& totalPaths, - const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, - const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d ); + bool ValidateRollOutsInput(const vector > >& rollOuts); + vector CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, const int& lane_index, const PlanningParams& params); + void NormalizeCosts(vector& trajectoryCosts); + void CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, const vector > >& rollOuts, const vector >& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); + void CalculateLateralAndLongitudinalCostsStatic(vector& trajectoryCosts, const vector >& rollOuts, const vector& totalPaths, const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState); + void CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params); + + void CalculateIntersectionVelocities(const std::vector& path, const DetectedObject& obj, const WayPoint& currPose, const CAR_BASIC_INFO& carInfo, const double& c_lateral_d, WayPoint& collisionPoint, TrajectoryCost& trajectoryCosts); + int GetCurrentRollOutIndex(const std::vector& path, const WayPoint& currState, const PlanningParams& params); + void InitializeCosts(const vector >& rollOuts, const PlanningParams& params); + void InitializeSafetyPolygon(const WayPoint& currState, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d); + void CalculateLateralAndLongitudinalCostsDynamic(const std::vector& obj_list, const vector >& rollOuts, const vector& totalPaths, + const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, + const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d ); }; diff --git a/common/op_planner/src/BehaviorPrediction.cpp b/common/op_planner/src/BehaviorPrediction.cpp index 9c41c566162..04697f40377 100644 --- a/common/op_planner/src/BehaviorPrediction.cpp +++ b/common/op_planner/src/BehaviorPrediction.cpp @@ -17,17 +17,17 @@ namespace PlannerHNS BehaviorPrediction::BehaviorPrediction() { - m_MaxLaneDetectionDistance = 0.5; - m_PredictionDistance = 20.0; - m_bGenerateBranches = false; - m_bUseFixedPrediction = true; - m_bStepByStep = false; - m_bCanDecide = true; - m_bParticleFilter = false; - UtilityHNS::UtilityH::GetTickCount(m_GenerationTimer); - UtilityHNS::UtilityH::GetTickCount(m_ResamplingTimer); - m_bFirstMove = true; - m_bDebugOut = false; + m_MaxLaneDetectionDistance = 0.5; + m_PredictionDistance = 20.0; + m_bGenerateBranches = false; + m_bUseFixedPrediction = true; + m_bStepByStep = false; + m_bCanDecide = true; + m_bParticleFilter = false; + UtilityHNS::UtilityH::GetTickCount(m_GenerationTimer); + UtilityHNS::UtilityH::GetTickCount(m_ResamplingTimer); + m_bFirstMove = true; + m_bDebugOut = false; } BehaviorPrediction::~BehaviorPrediction() @@ -36,727 +36,727 @@ BehaviorPrediction::~BehaviorPrediction() void BehaviorPrediction::FilterObservations(const std::vector& obj_list, RoadNetwork& map, std::vector& filtered_list) { - for(unsigned int i=0; i < obj_list.size(); i++) - { - if(obj_list.at(i).t == SIDEWALK || obj_list.at(i).center.v < 1.0) - continue; - - bool bFound = false; - int found_index = 0; - for(unsigned int ip=0; ip < filtered_list.size(); ip++) - { - if(filtered_list.at(ip).id == obj_list.at(i).id) - { - found_index = ip; - bFound = true; - break; - } - } - - if(bFound) - filtered_list.at(found_index) = obj_list.at(i); - else - filtered_list.push_back(obj_list.at(i)); - } - - for(int ip=0; ip < (int)filtered_list.size(); ip++) - { - //check for cleaning - bool bRevFound = false; - for(unsigned int ic=0; ic < obj_list.size(); ic++) - { - if(filtered_list.at(ip).id == obj_list.at(ic).id) - { - bRevFound = true; - break; - } - } - - if(!bRevFound) - { - filtered_list.erase(filtered_list.begin()+ip); - ip--; - } - } + for(unsigned int i=0; i < obj_list.size(); i++) + { + if(obj_list.at(i).t == SIDEWALK || obj_list.at(i).center.v < 1.0) + continue; + + bool bFound = false; + int found_index = 0; + for(unsigned int ip=0; ip < filtered_list.size(); ip++) + { + if(filtered_list.at(ip).id == obj_list.at(i).id) + { + found_index = ip; + bFound = true; + break; + } + } + + if(bFound) + filtered_list.at(found_index) = obj_list.at(i); + else + filtered_list.push_back(obj_list.at(i)); + } + + for(int ip=0; ip < (int)filtered_list.size(); ip++) + { + //check for cleaning + bool bRevFound = false; + for(unsigned int ic=0; ic < obj_list.size(); ic++) + { + if(filtered_list.at(ip).id == obj_list.at(ic).id) + { + bRevFound = true; + break; + } + } + + if(!bRevFound) + { + filtered_list.erase(filtered_list.begin()+ip); + ip--; + } + } } void BehaviorPrediction::DoOneStep(const std::vector& obj_list, const WayPoint& currPose, const double& minSpeed, const double& maxDeceleration, RoadNetwork& map) { - if(!m_bUseFixedPrediction && maxDeceleration !=0) - m_PredictionDistance = -pow(currPose.v, 2)/(maxDeceleration); + if(!m_bUseFixedPrediction && maxDeceleration !=0) + m_PredictionDistance = -pow(currPose.v, 2)/(maxDeceleration); - ExtractTrajectoriesFromMap(obj_list, map, m_ParticleInfo_II); - CalculateCollisionTimes(minSpeed); + ExtractTrajectoriesFromMap(obj_list, map, m_ParticleInfo_II); + CalculateCollisionTimes(minSpeed); - if(m_bParticleFilter) - { - ParticleFilterSteps(m_ParticleInfo_II); - } + if(m_bParticleFilter) + { + ParticleFilterSteps(m_ParticleInfo_II); + } } void BehaviorPrediction::CalculateCollisionTimes(const double& minSpeed) { - for(unsigned int i=0; i < m_ParticleInfo_II.size(); i++) - { - for(unsigned int j=0; j < m_ParticleInfo_II.at(i)->obj.predTrajectories.size(); j++) - { - PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(m_ParticleInfo_II.at(i)->obj.predTrajectories.at(j), m_ParticleInfo_II.at(i)->obj.center, minSpeed, m_PredictionDistance); -// PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_PredictedObjects.at(i).predTrajectories.at(j)); - } - } + for(unsigned int i=0; i < m_ParticleInfo_II.size(); i++) + { + for(unsigned int j=0; j < m_ParticleInfo_II.at(i)->obj.predTrajectories.size(); j++) + { + PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(m_ParticleInfo_II.at(i)->obj.predTrajectories.at(j), m_ParticleInfo_II.at(i)->obj.center, minSpeed, m_PredictionDistance); +// PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_PredictedObjects.at(i).predTrajectories.at(j)); + } + } } void BehaviorPrediction::ExtractTrajectoriesFromMap(const std::vector& curr_obj_list,RoadNetwork& map, std::vector& old_obj_list) { - PlannerH planner; - m_temp_list_ii.clear(); - - std::vector delete_me_list = old_obj_list; - - for(unsigned int i=0; i < curr_obj_list.size(); i++) - { - bool bMatch = false; - for(unsigned int ip=0; ip < old_obj_list.size(); ip++) - { - if(old_obj_list.at(ip)->obj.id == curr_obj_list.at(i).id) - { - bool bFound = false; - for(unsigned int k=0; k < m_temp_list_ii.size(); k++) - { - if(m_temp_list_ii.at(k) == old_obj_list.at(ip)) - { - bFound = true; - break; - } - } - - if(!bFound) - { - old_obj_list.at(ip)->obj = curr_obj_list.at(i); - m_temp_list_ii.push_back(old_obj_list.at(ip)); - } - - DeleteFromList(delete_me_list, old_obj_list.at(ip)); - - old_obj_list.erase(old_obj_list.begin()+ip); - bMatch = true; - break; - } - } - - if(!bMatch) - { - ObjParticles* pNewObj = new ObjParticles(); - pNewObj->obj = curr_obj_list.at(i); - m_temp_list_ii.push_back(pNewObj); - } - } - - DeleteTheRest(delete_me_list); - old_obj_list.clear(); - old_obj_list = m_temp_list_ii; - - //m_PredictedObjects.clear(); - for(unsigned int ip=0; ip < old_obj_list.size(); ip++) - { - PredictCurrentTrajectory(map, old_obj_list.at(ip)); - //m_PredictedObjects.push_back(old_obj_list.at(ip)->obj); - old_obj_list.at(ip)->MatchTrajectories(); - } + PlannerH planner; + m_temp_list_ii.clear(); + + std::vector delete_me_list = old_obj_list; + + for(unsigned int i=0; i < curr_obj_list.size(); i++) + { + bool bMatch = false; + for(unsigned int ip=0; ip < old_obj_list.size(); ip++) + { + if(old_obj_list.at(ip)->obj.id == curr_obj_list.at(i).id) + { + bool bFound = false; + for(unsigned int k=0; k < m_temp_list_ii.size(); k++) + { + if(m_temp_list_ii.at(k) == old_obj_list.at(ip)) + { + bFound = true; + break; + } + } + + if(!bFound) + { + old_obj_list.at(ip)->obj = curr_obj_list.at(i); + m_temp_list_ii.push_back(old_obj_list.at(ip)); + } + + DeleteFromList(delete_me_list, old_obj_list.at(ip)); + + old_obj_list.erase(old_obj_list.begin()+ip); + bMatch = true; + break; + } + } + + if(!bMatch) + { + ObjParticles* pNewObj = new ObjParticles(); + pNewObj->obj = curr_obj_list.at(i); + m_temp_list_ii.push_back(pNewObj); + } + } + + DeleteTheRest(delete_me_list); + old_obj_list.clear(); + old_obj_list = m_temp_list_ii; + + //m_PredictedObjects.clear(); + for(unsigned int ip=0; ip < old_obj_list.size(); ip++) + { + PredictCurrentTrajectory(map, old_obj_list.at(ip)); + //m_PredictedObjects.push_back(old_obj_list.at(ip)->obj); + old_obj_list.at(ip)->MatchTrajectories(); + } } void BehaviorPrediction::CalPredictionTimeForObject(ObjParticles* pCarPart) { - if(pCarPart->obj.center.v > 0 ) - pCarPart->m_PredictionTime = (MIN_PREDICTION_TIME + 1.5*pCarPart->obj.center.v) / pCarPart->obj.center.v; - else - pCarPart->m_PredictionTime = MIN_PREDICTION_TIME; + if(pCarPart->obj.center.v > 0 ) + pCarPart->m_PredictionTime = (MIN_PREDICTION_TIME + 1.5*pCarPart->obj.center.v) / pCarPart->obj.center.v; + else + pCarPart->m_PredictionTime = MIN_PREDICTION_TIME; } void BehaviorPrediction::PredictCurrentTrajectory(RoadNetwork& map, ObjParticles* pCarPart) { - pCarPart->obj.predTrajectories.clear(); - PlannerH planner; - if(pCarPart->obj.bDirection && pCarPart->obj.bVelocity) - { - PlannerHNS::WayPoint fake_pose = pCarPart->obj.center; - pCarPart->obj.pClosestWaypoints = MappingHelpers::GetClosestWaypointsListFromMap(fake_pose, map, m_MaxLaneDetectionDistance, pCarPart->obj.bDirection); - planner.PredictTrajectoriesUsingDP(fake_pose, pCarPart->obj.pClosestWaypoints, m_PredictionDistance, pCarPart->obj.predTrajectories, m_bGenerateBranches, pCarPart->obj.bDirection); - } - else - { - bool bLocalDirectionSearch = false; - pCarPart->obj.pClosestWaypoints = MappingHelpers::GetClosestWaypointsListFromMap(pCarPart->obj.center, map, m_MaxLaneDetectionDistance, pCarPart->obj.bDirection); - if(pCarPart->obj.pClosestWaypoints.size()>0) - { - pCarPart->obj.center.pos.a = pCarPart->obj.pClosestWaypoints.at(0)->pos.a; - bLocalDirectionSearch = true; - } - planner.PredictTrajectoriesUsingDP(pCarPart->obj.center, pCarPart->obj.pClosestWaypoints, m_PredictionDistance, pCarPart->obj.predTrajectories, m_bGenerateBranches, pCarPart->obj.bDirection); - } - - - for(unsigned int t = 0; t < pCarPart->obj.predTrajectories.size(); t ++) - { -// std::ostringstream path_name; -// path_name << "/home/hatem/autoware_openplanner_logs/TempPredLog/"; -// path_name << t ; -// path_name << "_"; -// PlanningHelpers::GenerateRecommendedSpeed(pCarPart->obj.predTrajectories.at(t), 10, 1.0); -// PlannerHNS::PlanningHelpers::WritePathToFile(path_name.str(), pCarPart->obj.predTrajectories.at(t)); - if(pCarPart->obj.predTrajectories.at(t).size() > 0) - pCarPart->obj.predTrajectories.at(t).at(0).collisionCost = 0; - } + pCarPart->obj.predTrajectories.clear(); + PlannerH planner; + if(pCarPart->obj.bDirection && pCarPart->obj.bVelocity) + { + PlannerHNS::WayPoint fake_pose = pCarPart->obj.center; + pCarPart->obj.pClosestWaypoints = MappingHelpers::GetClosestWaypointsListFromMap(fake_pose, map, m_MaxLaneDetectionDistance, pCarPart->obj.bDirection); + planner.PredictTrajectoriesUsingDP(fake_pose, pCarPart->obj.pClosestWaypoints, m_PredictionDistance, pCarPart->obj.predTrajectories, m_bGenerateBranches, pCarPart->obj.bDirection); + } + else + { + bool bLocalDirectionSearch = false; + pCarPart->obj.pClosestWaypoints = MappingHelpers::GetClosestWaypointsListFromMap(pCarPart->obj.center, map, m_MaxLaneDetectionDistance, pCarPart->obj.bDirection); + if(pCarPart->obj.pClosestWaypoints.size()>0) + { + pCarPart->obj.center.pos.a = pCarPart->obj.pClosestWaypoints.at(0)->pos.a; + bLocalDirectionSearch = true; + } + planner.PredictTrajectoriesUsingDP(pCarPart->obj.center, pCarPart->obj.pClosestWaypoints, m_PredictionDistance, pCarPart->obj.predTrajectories, m_bGenerateBranches, pCarPart->obj.bDirection); + } + + + for(unsigned int t = 0; t < pCarPart->obj.predTrajectories.size(); t ++) + { +// std::ostringstream path_name; +// path_name << "/home/hatem/autoware_openplanner_logs/TempPredLog/"; +// path_name << t ; +// path_name << "_"; +// PlanningHelpers::GenerateRecommendedSpeed(pCarPart->obj.predTrajectories.at(t), 10, 1.0); +// PlannerHNS::PlanningHelpers::WritePathToFile(path_name.str(), pCarPart->obj.predTrajectories.at(t)); + if(pCarPart->obj.predTrajectories.at(t).size() > 0) + pCarPart->obj.predTrajectories.at(t).at(0).collisionCost = 0; + } } void BehaviorPrediction::ParticleFilterSteps(std::vector& part_info) { - for(unsigned int i=0; i < part_info.size(); i++) - { - SamplesFreshParticles(part_info.at(i)); - CollectParticles(part_info.at(i)); - MoveParticles(part_info.at(i)); - CalculateWeights(part_info.at(i)); - RemoveWeakParticles(part_info.at(i)); - CalculateAveragesAndProbabilities(part_info.at(i)); - FindBest(part_info.at(i)); - } + for(unsigned int i=0; i < part_info.size(); i++) + { + SamplesFreshParticles(part_info.at(i)); + CollectParticles(part_info.at(i)); + MoveParticles(part_info.at(i)); + CalculateWeights(part_info.at(i)); + RemoveWeakParticles(part_info.at(i)); + CalculateAveragesAndProbabilities(part_info.at(i)); + FindBest(part_info.at(i)); + } } int BehaviorPrediction::FromIndicatorToNumber(const PlannerHNS::LIGHT_INDICATOR& indi) { - if(indi == PlannerHNS::INDICATOR_NONE) - return 0; - else if(indi == PlannerHNS::INDICATOR_LEFT) - { - return 1; - } - else if(indi == PlannerHNS::INDICATOR_RIGHT) - return 2; - else if(indi == PlannerHNS::INDICATOR_BOTH) - return 3; - else - return 0; + if(indi == PlannerHNS::INDICATOR_NONE) + return 0; + else if(indi == PlannerHNS::INDICATOR_LEFT) + { + return 1; + } + else if(indi == PlannerHNS::INDICATOR_RIGHT) + return 2; + else if(indi == PlannerHNS::INDICATOR_BOTH) + return 3; + else + return 0; } PlannerHNS::LIGHT_INDICATOR BehaviorPrediction::FromNumbertoIndicator(const int& num) { - if(num == 0) - return PlannerHNS::INDICATOR_NONE; - else if(num == 1) - return PlannerHNS::INDICATOR_LEFT; - else if(num == 2) - return PlannerHNS::INDICATOR_RIGHT; - else if(num == 3) - return PlannerHNS::INDICATOR_BOTH; - else - return PlannerHNS::INDICATOR_NONE; + if(num == 0) + return PlannerHNS::INDICATOR_NONE; + else if(num == 1) + return PlannerHNS::INDICATOR_LEFT; + else if(num == 2) + return PlannerHNS::INDICATOR_RIGHT; + else if(num == 3) + return PlannerHNS::INDICATOR_BOTH; + else + return PlannerHNS::INDICATOR_NONE; } double BehaviorPrediction::CalcIndicatorWeight(PlannerHNS::LIGHT_INDICATOR p_ind, PlannerHNS::LIGHT_INDICATOR obj_ind) { - if((obj_ind == PlannerHNS::INDICATOR_LEFT || obj_ind == PlannerHNS::INDICATOR_RIGHT || obj_ind == PlannerHNS::INDICATOR_NONE) && p_ind == obj_ind) - return 0.99; - else - return 0.01; + if((obj_ind == PlannerHNS::INDICATOR_LEFT || obj_ind == PlannerHNS::INDICATOR_RIGHT || obj_ind == PlannerHNS::INDICATOR_NONE) && p_ind == obj_ind) + return 0.99; + else + return 0.01; } double BehaviorPrediction::CalcAccelerationWeight(int p_acl, int obj_acl) { - if((p_acl > 0 && obj_acl > 0) || (p_acl < 0 && obj_acl < 0)) - return 0.99; - else - return 0.01; + if((p_acl > 0 && obj_acl > 0) || (p_acl < 0 && obj_acl < 0)) + return 0.99; + else + return 0.01; } void BehaviorPrediction::CalOnePartWeight(ObjParticles* pParts,Particle& p) { - if(p.bDeleted) return; - - //p.pose_w = exp(-(0.5*pow((p.pose.pos.x - pParts->obj.center.pos.x),2)/(2*MEASURE_POSE_ERROR*MEASURE_POSE_ERROR)+ pow((p.pose.pos.y - pParts->obj.center.pos.y),2)/(2*MEASURE_POSE_ERROR*MEASURE_POSE_ERROR))); - p.pose_w = 1.0/hypot(0.5*(p.pose.pos.y - pParts->obj.center.pos.y), 0.5*(p.pose.pos.x - pParts->obj.center.pos.x)); - //p.dir_w = exp(-(pow(fabs(UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(p.pose.pos.a, pParts->obj.center.pos.a)),2)/(2*MEASURE_ANGLE_ERROR*MEASURE_ANGLE_ERROR))); - p.dir_w = M_PI_2 - fabs(UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(p.pose.pos.a, pParts->obj.center.pos.a)); - p.vel_w = exp(-(pow((p.vel - pParts->obj.center.v),2)/(2*MEASURE_VEL_ERROR*MEASURE_VEL_ERROR))); - //p.vel_w = fabs(p.vel - pParts->obj.center.v); - p.ind_w = CalcIndicatorWeight(FromNumbertoIndicator(p.indicator), pParts->obj.indicator_state); - p.ind_w -= p.ind_w*MEASURE_IND_ERROR; - p.acl_w = CalcAccelerationWeight(p.acc, pParts->obj.acceleration_desc); - - //std::cout << p.beh << "|" << p.vel_w <<"|" <obj.center.v; - - pParts->pose_w_t += p.pose_w; - pParts->dir_w_t += p.dir_w; - pParts->vel_w_t += p.vel_w; - pParts->ind_w_t += p.ind_w; - pParts->acl_w_t += p.acl_w; - - if(p.pose_w > pParts->pose_w_max) - pParts->pose_w_max = p.pose_w; - if(p.dir_w > pParts->dir_w_max) - pParts->dir_w_max = p.dir_w; - if(p.vel_w > pParts->vel_w_max) - pParts->vel_w_max = p.vel_w; - if(p.ind_w > pParts->ind_w_max) - pParts->ind_w_max = p.ind_w; - if(p.acl_w > pParts->acl_w_max) - pParts->acl_w_max = p.acl_w; - - if(p.pose_w < pParts->pose_w_min) - pParts->pose_w_min = p.pose_w; - if(p.dir_w < pParts->dir_w_min) - pParts->dir_w_min = p.dir_w; - if(p.vel_w < pParts->vel_w_min) - pParts->vel_w_min = p.vel_w; - if(p.ind_w < pParts->ind_w_min) - pParts->ind_w_min = p.ind_w; - if(p.acl_w < pParts->acl_w_min) - pParts->acl_w_min = p.acl_w; - - p.w_raw = p.pose_w*POSE_FACTOR + p.dir_w*DIRECTION_FACTOR + p.vel_w*VELOCITY_FACTOR + p.ind_w*INDICATOR_FACTOR + p.acl_w*ACCELERATE_FACTOR; - - if(p.w_raw >= pParts->max_w_raw) - pParts->max_w_raw = p.w_raw; - - if(p.w_raw <= pParts->min_w_raw) - pParts->min_w_raw = p.w_raw; + if(p.bDeleted) return; + + //p.pose_w = exp(-(0.5*pow((p.pose.pos.x - pParts->obj.center.pos.x),2)/(2*MEASURE_POSE_ERROR*MEASURE_POSE_ERROR)+ pow((p.pose.pos.y - pParts->obj.center.pos.y),2)/(2*MEASURE_POSE_ERROR*MEASURE_POSE_ERROR))); + p.pose_w = 1.0/hypot(0.5*(p.pose.pos.y - pParts->obj.center.pos.y), 0.5*(p.pose.pos.x - pParts->obj.center.pos.x)); + //p.dir_w = exp(-(pow(fabs(UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(p.pose.pos.a, pParts->obj.center.pos.a)),2)/(2*MEASURE_ANGLE_ERROR*MEASURE_ANGLE_ERROR))); + p.dir_w = M_PI_2 - fabs(UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(p.pose.pos.a, pParts->obj.center.pos.a)); + p.vel_w = exp(-(pow((p.vel - pParts->obj.center.v),2)/(2*MEASURE_VEL_ERROR*MEASURE_VEL_ERROR))); + //p.vel_w = fabs(p.vel - pParts->obj.center.v); + p.ind_w = CalcIndicatorWeight(FromNumbertoIndicator(p.indicator), pParts->obj.indicator_state); + p.ind_w -= p.ind_w*MEASURE_IND_ERROR; + p.acl_w = CalcAccelerationWeight(p.acc, pParts->obj.acceleration_desc); + + //std::cout << p.beh << "|" << p.vel_w <<"|" <obj.center.v; + + pParts->pose_w_t += p.pose_w; + pParts->dir_w_t += p.dir_w; + pParts->vel_w_t += p.vel_w; + pParts->ind_w_t += p.ind_w; + pParts->acl_w_t += p.acl_w; + + if(p.pose_w > pParts->pose_w_max) + pParts->pose_w_max = p.pose_w; + if(p.dir_w > pParts->dir_w_max) + pParts->dir_w_max = p.dir_w; + if(p.vel_w > pParts->vel_w_max) + pParts->vel_w_max = p.vel_w; + if(p.ind_w > pParts->ind_w_max) + pParts->ind_w_max = p.ind_w; + if(p.acl_w > pParts->acl_w_max) + pParts->acl_w_max = p.acl_w; + + if(p.pose_w < pParts->pose_w_min) + pParts->pose_w_min = p.pose_w; + if(p.dir_w < pParts->dir_w_min) + pParts->dir_w_min = p.dir_w; + if(p.vel_w < pParts->vel_w_min) + pParts->vel_w_min = p.vel_w; + if(p.ind_w < pParts->ind_w_min) + pParts->ind_w_min = p.ind_w; + if(p.acl_w < pParts->acl_w_min) + pParts->acl_w_min = p.acl_w; + + p.w_raw = p.pose_w*POSE_FACTOR + p.dir_w*DIRECTION_FACTOR + p.vel_w*VELOCITY_FACTOR + p.ind_w*INDICATOR_FACTOR + p.acl_w*ACCELERATE_FACTOR; + + if(p.w_raw >= pParts->max_w_raw) + pParts->max_w_raw = p.w_raw; + + if(p.w_raw <= pParts->min_w_raw) + pParts->min_w_raw = p.w_raw; } void BehaviorPrediction::NormalizeOnePartWeight(ObjParticles* pParts,Particle& p) { - if(p.bDeleted) return; + if(p.bDeleted) return; - double pose_diff = pParts->pose_w_max-pParts->pose_w_min; - double dir_diff = pParts->dir_w_max-pParts->dir_w_min; - double vel_diff = pParts->vel_w_max-pParts->vel_w_min; - double ind_diff = pParts->ind_w_max-pParts->ind_w_min; - double acl_diff = pParts->acl_w_max-pParts->acl_w_min; + double pose_diff = pParts->pose_w_max-pParts->pose_w_min; + double dir_diff = pParts->dir_w_max-pParts->dir_w_min; + double vel_diff = pParts->vel_w_max-pParts->vel_w_min; + double ind_diff = pParts->ind_w_max-pParts->ind_w_min; + double acl_diff = pParts->acl_w_max-pParts->acl_w_min; - double epsilon = 0.05; + double epsilon = 0.05; - if(fabs(pose_diff) > epsilon) - p.pose_w = p.pose_w/pose_diff; - else - p.pose_w = 0; + if(fabs(pose_diff) > epsilon) + p.pose_w = p.pose_w/pose_diff; + else + p.pose_w = 0; - if(p.pose_w > 1.0 ) p.pose_w = 1.0; + if(p.pose_w > 1.0 ) p.pose_w = 1.0; - if(fabs(dir_diff) > epsilon) - p.dir_w = (p.dir_w - pParts->dir_w_min)/dir_diff; - else - p.dir_w = 0; + if(fabs(dir_diff) > epsilon) + p.dir_w = (p.dir_w - pParts->dir_w_min)/dir_diff; + else + p.dir_w = 0; - if(p.dir_w > 1.0 ) p.dir_w = 1.0; + if(p.dir_w > 1.0 ) p.dir_w = 1.0; - if(fabs(vel_diff) > epsilon) - p.vel_w = (p.vel_w-pParts->vel_w_min)/vel_diff; - else - p.vel_w = 0; + if(fabs(vel_diff) > epsilon) + p.vel_w = (p.vel_w-pParts->vel_w_min)/vel_diff; + else + p.vel_w = 0; - if(p.vel_w > 1.0) p.vel_w = 1.0; + if(p.vel_w > 1.0) p.vel_w = 1.0; - if(fabs(ind_diff) > epsilon) - p.ind_w = (p.ind_w - pParts->ind_w_min)/ind_diff; - else - p.ind_w = 0; + if(fabs(ind_diff) > epsilon) + p.ind_w = (p.ind_w - pParts->ind_w_min)/ind_diff; + else + p.ind_w = 0; - if(p.ind_w > 1.0) p.ind_w = 1.0; + if(p.ind_w > 1.0) p.ind_w = 1.0; - if(fabs(acl_diff) > epsilon) - p.acl_w = (p.acl_w - pParts->acl_w_min)/acl_diff; - else - p.acl_w = 0; + if(fabs(acl_diff) > epsilon) + p.acl_w = (p.acl_w - pParts->acl_w_min)/acl_diff; + else + p.acl_w = 0; - if(p.acl_w > 1.0) p.acl_w = 1.0; + if(p.acl_w > 1.0) p.acl_w = 1.0; - p.w = p.pose_w*POSE_FACTOR + p.dir_w*DIRECTION_FACTOR + p.vel_w*VELOCITY_FACTOR + p.ind_w*INDICATOR_FACTOR + p.acl_w*ACCELERATE_FACTOR; - //p.w = p.pose_w*0.1 + p.vel_w*0.2 + p.dir_w * 0.2 + p.ind_w + 0.5; + p.w = p.pose_w*POSE_FACTOR + p.dir_w*DIRECTION_FACTOR + p.vel_w*VELOCITY_FACTOR + p.ind_w*INDICATOR_FACTOR + p.acl_w*ACCELERATE_FACTOR; + //p.w = p.pose_w*0.1 + p.vel_w*0.2 + p.dir_w * 0.2 + p.ind_w + 0.5; - if(p.w >= pParts->max_w) - pParts->max_w = p.w; + if(p.w >= pParts->max_w) + pParts->max_w = p.w; - if(p.w <= pParts->min_w) - pParts->min_w = p.w; + if(p.w <= pParts->min_w) + pParts->min_w = p.w; - pParts->all_w += p.w; + pParts->all_w += p.w; } void BehaviorPrediction::CalculateWeights(ObjParticles* pParts) { - pParts->all_w = 0; - pParts->pose_w_t = 0; - pParts->dir_w_t = 0; - pParts->vel_w_t = 0; - pParts->acl_w_t = 0; - - pParts->pose_w_max = -99999999; - pParts->dir_w_max = -99999999; - pParts->vel_w_max = -99999999; - pParts->acl_w_max = -99999999; - - pParts->pose_w_min = 99999999; - pParts->dir_w_min = 99999999; - pParts->vel_w_min = 99999999; - pParts->acl_w_min = 99999999; - - pParts->max_w_raw = DBL_MIN; - pParts->min_w_raw = DBL_MAX; - - //std::cout << "Acceleration Diff: "; - for(unsigned int i = 0 ; i < pParts->m_AllParticles.size(); i++) - { - // std::cout << "(" << pParts->m_AllParticles.at(i)->pTraj->index <<","; - CalOnePartWeight(pParts, *pParts->m_AllParticles.at(i)); - //std::cout << ")"; - } - - //std::cout << "Befor Normalize: Max: " << pParts->acl_w_max << ", Min: " << pParts->acl_w_min << std::endl; - //std::cout << std::endl; - - //if((pParts->m_TrajectoryTracker.size() > 1 && pParts->min_w_raw < 0.5) || pParts->max_w_raw == 0 || fabs(pParts->max_w_raw - pParts->min_w_raw) < 0.1 ) - if((pParts->max_w_raw == 0 || fabs(pParts->max_w_raw - pParts->min_w_raw) < 0.1 || pParts->min_w_raw > 0.5) && pParts->m_TrajectoryTracker.size() > 1) - m_bCanDecide = false; - else - m_bCanDecide = true; - - //Normalize - pParts->max_w = -9999999; - pParts->min_w = 9999999; - pParts->all_w = 0; - - for(unsigned int i = 0 ; i < pParts->m_AllParticles.size(); i++) - { - NormalizeOnePartWeight(pParts, *pParts->m_AllParticles.at(i)); - } + pParts->all_w = 0; + pParts->pose_w_t = 0; + pParts->dir_w_t = 0; + pParts->vel_w_t = 0; + pParts->acl_w_t = 0; + + pParts->pose_w_max = -99999999; + pParts->dir_w_max = -99999999; + pParts->vel_w_max = -99999999; + pParts->acl_w_max = -99999999; + + pParts->pose_w_min = 99999999; + pParts->dir_w_min = 99999999; + pParts->vel_w_min = 99999999; + pParts->acl_w_min = 99999999; + + pParts->max_w_raw = DBL_MIN; + pParts->min_w_raw = DBL_MAX; + + //std::cout << "Acceleration Diff: "; + for(unsigned int i = 0 ; i < pParts->m_AllParticles.size(); i++) + { + // std::cout << "(" << pParts->m_AllParticles.at(i)->pTraj->index <<","; + CalOnePartWeight(pParts, *pParts->m_AllParticles.at(i)); + //std::cout << ")"; + } + + //std::cout << "Befor Normalize: Max: " << pParts->acl_w_max << ", Min: " << pParts->acl_w_min << std::endl; + //std::cout << std::endl; + + //if((pParts->m_TrajectoryTracker.size() > 1 && pParts->min_w_raw < 0.5) || pParts->max_w_raw == 0 || fabs(pParts->max_w_raw - pParts->min_w_raw) < 0.1 ) + if((pParts->max_w_raw == 0 || fabs(pParts->max_w_raw - pParts->min_w_raw) < 0.1 || pParts->min_w_raw > 0.5) && pParts->m_TrajectoryTracker.size() > 1) + m_bCanDecide = false; + else + m_bCanDecide = true; + + //Normalize + pParts->max_w = -9999999; + pParts->min_w = 9999999; + pParts->all_w = 0; + + for(unsigned int i = 0 ; i < pParts->m_AllParticles.size(); i++) + { + NormalizeOnePartWeight(pParts, *pParts->m_AllParticles.at(i)); + } } void BehaviorPrediction::CalculateAveragesAndProbabilities(ObjParticles* pParts) { - for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) - { - pParts->m_TrajectoryTracker.at(t)->CalcAverages(); - pParts->m_TrajectoryTracker.at(t)->CalcProbabilities(); - } + for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) + { + pParts->m_TrajectoryTracker.at(t)->CalcAverages(); + pParts->m_TrajectoryTracker.at(t)->CalcProbabilities(); + } } void BehaviorPrediction::RemoveWeakParticles(ObjParticles* pParts) { - double critical_val = pParts->min_w + (pParts->max_w - pParts->min_w)*KEEP_PERCENTAGE; -// std::cout << "Behavior Weights ------------------------------------------------ " << std::endl; -// std::cout << "Max Raw: " << pParts->max_w_raw << ", Min Raw: " << pParts->min_w_raw << std::endl; -// std::cout << "Keep Percent Value: " << critical_val << std::endl; + double critical_val = pParts->min_w + (pParts->max_w - pParts->min_w)*KEEP_PERCENTAGE; +// std::cout << "Behavior Weights ------------------------------------------------ " << std::endl; +// std::cout << "Max Raw: " << pParts->max_w_raw << ", Min Raw: " << pParts->min_w_raw << std::endl; +// std::cout << "Keep Percent Value: " << critical_val << std::endl; // -// if(pParts->obj.acceleration > 0 ) -// std::cout << "Accelerate vrooom vroom : " << std::endl; -// else if(pParts->obj.acceleration < 0 ) -// std::cout << "Brake Eeeeee Eeeeeeee: " << std::endl; - - for(int i =0 ; i < pParts->m_AllParticles.size(); i++) - { - //also delete far particle - double d = hypot(pParts->obj.center.pos.y - pParts->m_AllParticles.at(i)->pose.pos.y, pParts->obj.center.pos.x - pParts->m_AllParticles.at(i)->pose.pos.x); - - if(pParts->m_AllParticles.at(i)->w < critical_val || d > m_PredictionDistance) - { - pParts->m_AllParticles.at(i)->pTraj->DeleteParticle(*(pParts->m_AllParticles.at(i)), pParts->m_AllParticles.at(i)->original_index); - pParts->m_AllParticles.erase(pParts->m_AllParticles.begin()+i); - i--; - } - } +// if(pParts->obj.acceleration > 0 ) +// std::cout << "Accelerate vrooom vroom : " << std::endl; +// else if(pParts->obj.acceleration < 0 ) +// std::cout << "Brake Eeeeee Eeeeeeee: " << std::endl; + + for(int i =0 ; i < pParts->m_AllParticles.size(); i++) + { + //also delete far particle + double d = hypot(pParts->obj.center.pos.y - pParts->m_AllParticles.at(i)->pose.pos.y, pParts->obj.center.pos.x - pParts->m_AllParticles.at(i)->pose.pos.x); + + if(pParts->m_AllParticles.at(i)->w < critical_val || d > m_PredictionDistance) + { + pParts->m_AllParticles.at(i)->pTraj->DeleteParticle(*(pParts->m_AllParticles.at(i)), pParts->m_AllParticles.at(i)->original_index); + pParts->m_AllParticles.erase(pParts->m_AllParticles.begin()+i); + i--; + } + } } void BehaviorPrediction::FindBest(ObjParticles* pParts) { - if(pParts->m_TrajectoryTracker.size() > 0) - { - pParts->best_beh_track = pParts->m_TrajectoryTracker.at(0); - pParts->i_best_track = 0; - } - - for(unsigned int t = 1; t < pParts->m_TrajectoryTracker.size(); t++) - { - if(pParts->m_TrajectoryTracker.at(t)->best_p > pParts->best_beh_track->best_p) - { - pParts->best_beh_track = pParts->m_TrajectoryTracker.at(t); - pParts->i_best_track = t; - } - } - - - if(m_bDebugOut ) - { - std::cout << "Behavior Prob ------------------------------------------------ : " << pParts->m_TrajectoryTracker.size() << std::endl; - std::cout << "Raw Weights: Max: " << pParts->max_w_raw << ", Min: " << pParts->min_w_raw << std::endl; - std::cout << "Norm Weights: Max: " << pParts->max_w << ", Min: " << pParts->min_w << std::endl; - } - - for(unsigned int t=0; t < pParts->obj.predTrajectories.size() ; t++) - { - if(pParts->obj.predTrajectories.at(t).size()>0) - { - pParts->obj.predTrajectories.at(t).at(0).collisionCost = 0.25; - } - } - - if(m_bCanDecide && pParts->best_beh_track != nullptr) - { - std::string str_beh = "Unknown"; - if(pParts->best_beh_track->best_beh == BEH_STOPPING_STATE) - str_beh = "Stopping"; - else if(pParts->best_beh_track->best_beh == BEH_FORWARD_STATE) - str_beh = "Forward"; - - if(m_bDebugOut ) - std::cout << "Trajectory (" << pParts->i_best_track << "), P: " << pParts->best_beh_track->best_p << " , Beh (" << pParts->best_beh_track->best_beh << ", " << str_beh << ")" << std::endl; - - if(pParts->best_beh_track->index < pParts->obj.predTrajectories.size()) - pParts->obj.predTrajectories.at(pParts->best_beh_track->index).at(0).collisionCost = 1; - - } - else - { - if(m_bDebugOut ) - std::cout << "Trajectory (" << -1 << "), P: " << 0 << " , Beh (" << -1 << ", " << "Can't Decide" << ")" << std::endl; - } - - if(m_bDebugOut ) - { - for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size() ; t++) - { - if(pParts->m_TrajectoryTracker.at(t)->nAliveForward > 0) - std::cout << t << ", Forward Particles:" << pParts->m_TrajectoryTracker.at(t)->nAliveForward << std::endl; - if(pParts->m_TrajectoryTracker.at(t)->nAliveStop > 0) - std::cout << t << ", Stoping Particles:" << pParts->m_TrajectoryTracker.at(t)->nAliveStop << std::endl; - } - - std::cout << "------------------------------------------------ --------------" << std::endl<< std::endl; - } + if(pParts->m_TrajectoryTracker.size() > 0) + { + pParts->best_beh_track = pParts->m_TrajectoryTracker.at(0); + pParts->i_best_track = 0; + } + + for(unsigned int t = 1; t < pParts->m_TrajectoryTracker.size(); t++) + { + if(pParts->m_TrajectoryTracker.at(t)->best_p > pParts->best_beh_track->best_p) + { + pParts->best_beh_track = pParts->m_TrajectoryTracker.at(t); + pParts->i_best_track = t; + } + } + + + if(m_bDebugOut ) + { + std::cout << "Behavior Prob ------------------------------------------------ : " << pParts->m_TrajectoryTracker.size() << std::endl; + std::cout << "Raw Weights: Max: " << pParts->max_w_raw << ", Min: " << pParts->min_w_raw << std::endl; + std::cout << "Norm Weights: Max: " << pParts->max_w << ", Min: " << pParts->min_w << std::endl; + } + + for(unsigned int t=0; t < pParts->obj.predTrajectories.size() ; t++) + { + if(pParts->obj.predTrajectories.at(t).size()>0) + { + pParts->obj.predTrajectories.at(t).at(0).collisionCost = 0.25; + } + } + + if(m_bCanDecide && pParts->best_beh_track != nullptr) + { + std::string str_beh = "Unknown"; + if(pParts->best_beh_track->best_beh == BEH_STOPPING_STATE) + str_beh = "Stopping"; + else if(pParts->best_beh_track->best_beh == BEH_FORWARD_STATE) + str_beh = "Forward"; + + if(m_bDebugOut ) + std::cout << "Trajectory (" << pParts->i_best_track << "), P: " << pParts->best_beh_track->best_p << " , Beh (" << pParts->best_beh_track->best_beh << ", " << str_beh << ")" << std::endl; + + if(pParts->best_beh_track->index < pParts->obj.predTrajectories.size()) + pParts->obj.predTrajectories.at(pParts->best_beh_track->index).at(0).collisionCost = 1; + + } + else + { + if(m_bDebugOut ) + std::cout << "Trajectory (" << -1 << "), P: " << 0 << " , Beh (" << -1 << ", " << "Can't Decide" << ")" << std::endl; + } + + if(m_bDebugOut ) + { + for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size() ; t++) + { + if(pParts->m_TrajectoryTracker.at(t)->nAliveForward > 0) + std::cout << t << ", Forward Particles:" << pParts->m_TrajectoryTracker.at(t)->nAliveForward << std::endl; + if(pParts->m_TrajectoryTracker.at(t)->nAliveStop > 0) + std::cout << t << ", Stoping Particles:" << pParts->m_TrajectoryTracker.at(t)->nAliveStop << std::endl; + } + + std::cout << "------------------------------------------------ --------------" << std::endl<< std::endl; + } } void BehaviorPrediction::SamplesFreshParticles(ObjParticles* pParts) { - timespec _time; - UtilityHNS::UtilityH::GetTickCount(_time); - srand(_time.tv_nsec); - - ENG eng(_time.tv_nsec); - NormalDIST dist_x(0, MOTION_POSE_ERROR); - VariatGEN gen_x(eng, dist_x); - NormalDIST vel(MOTION_VEL_ERROR, MOTION_VEL_ERROR); - VariatGEN gen_v(eng, vel); - NormalDIST ang(0, MOTION_ANGLE_ERROR); - VariatGEN gen_a(eng, ang); -// NormalDIST acl(0, MEASURE_ACL_ERROR); -// VariatGEN gen_acl(eng, acl); - - Particle p; - p.pose = pParts->obj.center; - p.vel = 0; - p.acc = 0; - p.indicator = 0; - bool bRegenerate = true; - - if(UtilityHNS::UtilityH::GetTimeDiffNow(m_GenerationTimer) > 2) - { - UtilityHNS::UtilityH::GetTickCount(m_GenerationTimer); - bRegenerate = true; - } - -// for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) -// { -// PlanningHelpers::FixPathDensity(pParts->m_TrajectoryTracker.at(t)->trajectory, 0.5); -// PlanningHelpers::CalcAngleAndCost(pParts->m_TrajectoryTracker.at(t)->trajectory); -// } - - for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) - { - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(pParts->m_TrajectoryTracker.at(t)->trajectory, pParts->obj.center, info); - unsigned int point_index = 0; - p.pose = PlanningHelpers::GetFollowPointOnTrajectory(pParts->m_TrajectoryTracker.at(t)->trajectory, info, PREDICTION_DISTANCE_PERCENTAGE*m_PredictionDistance, point_index); - - if(pParts->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_FORWARD_STATE && pParts->m_TrajectoryTracker.at(t)->nAliveForward < BEH_PARTICLES_NUM) - { - p.beh = PlannerHNS::BEH_FORWARD_STATE; - int nPs = BEH_PARTICLES_NUM - pParts->m_TrajectoryTracker.at(t)->nAliveForward; - - for(unsigned int i=0; i < nPs; i++) - { - Particle p_new = p; - p_new.pose.pos.x += gen_x(); - p_new.pose.pos.y += gen_x(); - p_new.pose.pos.a += gen_a(); - p_new.vel = pParts->obj.center.v + fabs(gen_v()); - p_new.pose.v = p_new.vel; - pParts->m_TrajectoryTracker.at(t)->InsertNewParticle(p_new); - } - } - - if(ENABLE_STOP_BEHAVIOR_GEN == 1 && pParts->m_TrajectoryTracker.at(t)->nAliveStop < BEH_PARTICLES_NUM) - { - p.beh = PlannerHNS::BEH_STOPPING_STATE; - int nPs = BEH_PARTICLES_NUM - pParts->m_TrajectoryTracker.at(t)->nAliveStop; - - for(unsigned int i=0; i < nPs; i++) - { - Particle p_new = p; - p_new.pose.pos.x += gen_x(); - p_new.pose.pos.y += gen_x(); - p_new.pose.pos.a += gen_a(); - p_new.vel = 0; - p_new.pose.v = pParts->obj.center.v + fabs(gen_v()); - pParts->m_TrajectoryTracker.at(t)->InsertNewParticle(p_new); - } - } - } + timespec _time; + UtilityHNS::UtilityH::GetTickCount(_time); + srand(_time.tv_nsec); + + ENG eng(_time.tv_nsec); + NormalDIST dist_x(0, MOTION_POSE_ERROR); + VariatGEN gen_x(eng, dist_x); + NormalDIST vel(MOTION_VEL_ERROR, MOTION_VEL_ERROR); + VariatGEN gen_v(eng, vel); + NormalDIST ang(0, MOTION_ANGLE_ERROR); + VariatGEN gen_a(eng, ang); +// NormalDIST acl(0, MEASURE_ACL_ERROR); +// VariatGEN gen_acl(eng, acl); + + Particle p; + p.pose = pParts->obj.center; + p.vel = 0; + p.acc = 0; + p.indicator = 0; + bool bRegenerate = true; + + if(UtilityHNS::UtilityH::GetTimeDiffNow(m_GenerationTimer) > 2) + { + UtilityHNS::UtilityH::GetTickCount(m_GenerationTimer); + bRegenerate = true; + } + +// for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) +// { +// PlanningHelpers::FixPathDensity(pParts->m_TrajectoryTracker.at(t)->trajectory, 0.5); +// PlanningHelpers::CalcAngleAndCost(pParts->m_TrajectoryTracker.at(t)->trajectory); +// } + + for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) + { + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(pParts->m_TrajectoryTracker.at(t)->trajectory, pParts->obj.center, info); + unsigned int point_index = 0; + p.pose = PlanningHelpers::GetFollowPointOnTrajectory(pParts->m_TrajectoryTracker.at(t)->trajectory, info, PREDICTION_DISTANCE_PERCENTAGE*m_PredictionDistance, point_index); + + if(pParts->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_FORWARD_STATE && pParts->m_TrajectoryTracker.at(t)->nAliveForward < BEH_PARTICLES_NUM) + { + p.beh = PlannerHNS::BEH_FORWARD_STATE; + int nPs = BEH_PARTICLES_NUM - pParts->m_TrajectoryTracker.at(t)->nAliveForward; + + for(unsigned int i=0; i < nPs; i++) + { + Particle p_new = p; + p_new.pose.pos.x += gen_x(); + p_new.pose.pos.y += gen_x(); + p_new.pose.pos.a += gen_a(); + p_new.vel = pParts->obj.center.v + fabs(gen_v()); + p_new.pose.v = p_new.vel; + pParts->m_TrajectoryTracker.at(t)->InsertNewParticle(p_new); + } + } + + if(ENABLE_STOP_BEHAVIOR_GEN == 1 && pParts->m_TrajectoryTracker.at(t)->nAliveStop < BEH_PARTICLES_NUM) + { + p.beh = PlannerHNS::BEH_STOPPING_STATE; + int nPs = BEH_PARTICLES_NUM - pParts->m_TrajectoryTracker.at(t)->nAliveStop; + + for(unsigned int i=0; i < nPs; i++) + { + Particle p_new = p; + p_new.pose.pos.x += gen_x(); + p_new.pose.pos.y += gen_x(); + p_new.pose.pos.a += gen_a(); + p_new.vel = 0; + p_new.pose.v = pParts->obj.center.v + fabs(gen_v()); + pParts->m_TrajectoryTracker.at(t)->InsertNewParticle(p_new); + } + } + } } void BehaviorPrediction::CollectParticles(ObjParticles* pParts) { - pParts->m_AllParticles.clear(); - for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) - { - for(unsigned int i=0; i < pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.size(); i++) - { - pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.at(i).original_index = i; - pParts->m_AllParticles.push_back(&pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.at(i)); - } - - for(unsigned int i=0; i < pParts->m_TrajectoryTracker.at(t)->m_StopPart.size(); i++) - { - pParts->m_TrajectoryTracker.at(t)->m_StopPart.at(i).original_index = i; - pParts->m_AllParticles.push_back(&pParts->m_TrajectoryTracker.at(t)->m_StopPart.at(i)); - } - } + pParts->m_AllParticles.clear(); + for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) + { + for(unsigned int i=0; i < pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.size(); i++) + { + pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.at(i).original_index = i; + pParts->m_AllParticles.push_back(&pParts->m_TrajectoryTracker.at(t)->m_ForwardPart.at(i)); + } + + for(unsigned int i=0; i < pParts->m_TrajectoryTracker.at(t)->m_StopPart.size(); i++) + { + pParts->m_TrajectoryTracker.at(t)->m_StopPart.at(i).original_index = i; + pParts->m_AllParticles.push_back(&pParts->m_TrajectoryTracker.at(t)->m_StopPart.at(i)); + } + } } void BehaviorPrediction::MoveParticles(ObjParticles* pParts) { - double dt = 0.01; - if(m_bStepByStep) - { - dt = 0.08; - } - else - { - dt = UtilityHNS::UtilityH::GetTimeDiffNow(m_ResamplingTimer); - UtilityHNS::UtilityH::GetTickCount(m_ResamplingTimer); - if(m_bFirstMove) - { - m_bFirstMove = false; - return; - } - } - - PlannerHNS::BehaviorState curr_behavior; - PlannerHNS::ParticleInfo curr_part_info; - PlannerHNS::VehicleState control_u; - PassiveDecisionMaker decision_make; - PlannerHNS::CAR_BASIC_INFO carInfo; - carInfo.width = pParts->obj.w; - carInfo.length = pParts->obj.l; - carInfo.max_acceleration = 3.0; - carInfo.max_deceleration = -3; - carInfo.max_speed_forward = MAX_PREDICTION_SPEED; - carInfo.min_speed_forward = 0; - carInfo.max_steer_angle = 0.4; - carInfo.min_steer_angle = -0.4; - carInfo.turning_radius = 7.2; - carInfo.wheel_base = carInfo.length*0.75; - - for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) - { - PlanningHelpers::GenerateRecommendedSpeed(pParts->m_TrajectoryTracker.at(t)->trajectory, carInfo.max_speed_forward, 1.0); - } - -// std::cout << "Motion Status------ " << std::endl; -// if(pParts->obj.acceleration_desc == 1) -// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Accelerate: " << pParts->obj.acceleration_desc << std::endl; -// else if(pParts->obj.acceleration_desc == -1) -// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Braking : " << pParts->obj.acceleration_desc << std::endl; -// else -// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Cruising : " << pParts->obj.acceleration_desc << std::endl; - - for(unsigned int i=0; i < pParts->m_AllParticles.size(); i++) - { - Particle* p = pParts->m_AllParticles.at(i); - - if(USE_OPEN_PLANNER_MOVE == 0) - { - p->pose.v = pParts->obj.center.v; - curr_part_info = decision_make.MoveStepSimple(dt, p->pose, p->pTraj->trajectory,carInfo); - if(p->prev_time_diff > ACCELERATION_CALC_TIME) - { - p->acc_raw = (curr_part_info.vel - p->vel_prev_big)/p->prev_time_diff; - p->vel_prev_big = curr_part_info.vel; - p->prev_time_diff = 0; - } - else - { - p->prev_time_diff += dt; - } - - if(fabs(p->acc_raw) < ACCELERATION_DECISION_VALUE) - p->acc = 0; - else if(p->acc_raw > ACCELERATION_DECISION_VALUE) - p->acc = 1; - else if(p->acc_raw < -ACCELERATION_DECISION_VALUE) - p->acc = -1; - - p->indicator = FromIndicatorToNumber(curr_part_info.indicator); - -// if(curr_behavior.state == PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_YIELDING_STATE) -// p->vel += 1; -// else if(p->beh == PlannerHNS::BEH_YIELDING_STATE) -// p->vel = p->vel/2.0; -// else if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) -// p->vel += 1; -// else if(p->beh == PlannerHNS::BEH_STOPPING_STATE) -// p->vel = 0; - -// if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) -// p->vel += 1; - if(p->beh == PlannerHNS::BEH_STOPPING_STATE) - { - p->vel = 0; - if(p->acc == 0) - p->acc = -1; - else if(p->acc == 1) - p->acc = 0; - } - - } - else - { - curr_behavior = decision_make.MoveStep(dt, p->pose, p->pTraj->trajectory,carInfo); - p->acc = UtilityHNS::UtilityH::GetSign(curr_behavior.maxVelocity - p->vel_prev_big); - p->vel = curr_behavior.maxVelocity; - if(fabs(p->vel - p->vel_prev_big) > 0.5) - p->vel_prev_big = p->vel; - p->indicator = FromIndicatorToNumber(curr_behavior.indicator); -// if(p->indicator == 0) -// std::cout << ", Off"; -// else if(p->indicator == 1) -// std::cout << ", Left"; -// else if(p->indicator == 2) -// std::cout << ", Right"; - - if(curr_behavior.state == PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_YIELDING_STATE) - p->vel += 1; - else if(p->beh == PlannerHNS::BEH_YIELDING_STATE) - p->vel = p->vel/2.0; - else if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) - p->vel += 1; - else if(p->beh == PlannerHNS::BEH_STOPPING_STATE) - { - p->vel = 0; - } - - } - } - //std::cout << "End Motion Status ------ " << std::endl; + double dt = 0.01; + if(m_bStepByStep) + { + dt = 0.08; + } + else + { + dt = UtilityHNS::UtilityH::GetTimeDiffNow(m_ResamplingTimer); + UtilityHNS::UtilityH::GetTickCount(m_ResamplingTimer); + if(m_bFirstMove) + { + m_bFirstMove = false; + return; + } + } + + PlannerHNS::BehaviorState curr_behavior; + PlannerHNS::ParticleInfo curr_part_info; + PlannerHNS::VehicleState control_u; + PassiveDecisionMaker decision_make; + PlannerHNS::CAR_BASIC_INFO carInfo; + carInfo.width = pParts->obj.w; + carInfo.length = pParts->obj.l; + carInfo.max_acceleration = 3.0; + carInfo.max_deceleration = -3; + carInfo.max_speed_forward = MAX_PREDICTION_SPEED; + carInfo.min_speed_forward = 0; + carInfo.max_steer_angle = 0.4; + carInfo.min_steer_angle = -0.4; + carInfo.turning_radius = 7.2; + carInfo.wheel_base = carInfo.length*0.75; + + for(unsigned int t=0; t < pParts->m_TrajectoryTracker.size(); t++) + { + PlanningHelpers::GenerateRecommendedSpeed(pParts->m_TrajectoryTracker.at(t)->trajectory, carInfo.max_speed_forward, 1.0); + } + +// std::cout << "Motion Status------ " << std::endl; +// if(pParts->obj.acceleration_desc == 1) +// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Accelerate: " << pParts->obj.acceleration_desc << std::endl; +// else if(pParts->obj.acceleration_desc == -1) +// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Braking : " << pParts->obj.acceleration_desc << std::endl; +// else +// std::cout << "Acceleration: " << pParts->obj.acceleration_raw << ", Cruising : " << pParts->obj.acceleration_desc << std::endl; + + for(unsigned int i=0; i < pParts->m_AllParticles.size(); i++) + { + Particle* p = pParts->m_AllParticles.at(i); + + if(USE_OPEN_PLANNER_MOVE == 0) + { + p->pose.v = pParts->obj.center.v; + curr_part_info = decision_make.MoveStepSimple(dt, p->pose, p->pTraj->trajectory,carInfo); + if(p->prev_time_diff > ACCELERATION_CALC_TIME) + { + p->acc_raw = (curr_part_info.vel - p->vel_prev_big)/p->prev_time_diff; + p->vel_prev_big = curr_part_info.vel; + p->prev_time_diff = 0; + } + else + { + p->prev_time_diff += dt; + } + + if(fabs(p->acc_raw) < ACCELERATION_DECISION_VALUE) + p->acc = 0; + else if(p->acc_raw > ACCELERATION_DECISION_VALUE) + p->acc = 1; + else if(p->acc_raw < -ACCELERATION_DECISION_VALUE) + p->acc = -1; + + p->indicator = FromIndicatorToNumber(curr_part_info.indicator); + +// if(curr_behavior.state == PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_YIELDING_STATE) +// p->vel += 1; +// else if(p->beh == PlannerHNS::BEH_YIELDING_STATE) +// p->vel = p->vel/2.0; +// else if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) +// p->vel += 1; +// else if(p->beh == PlannerHNS::BEH_STOPPING_STATE) +// p->vel = 0; + +// if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) +// p->vel += 1; + if(p->beh == PlannerHNS::BEH_STOPPING_STATE) + { + p->vel = 0; + if(p->acc == 0) + p->acc = -1; + else if(p->acc == 1) + p->acc = 0; + } + + } + else + { + curr_behavior = decision_make.MoveStep(dt, p->pose, p->pTraj->trajectory,carInfo); + p->acc = UtilityHNS::UtilityH::GetSign(curr_behavior.maxVelocity - p->vel_prev_big); + p->vel = curr_behavior.maxVelocity; + if(fabs(p->vel - p->vel_prev_big) > 0.5) + p->vel_prev_big = p->vel; + p->indicator = FromIndicatorToNumber(curr_behavior.indicator); +// if(p->indicator == 0) +// std::cout << ", Off"; +// else if(p->indicator == 1) +// std::cout << ", Left"; +// else if(p->indicator == 2) +// std::cout << ", Right"; + + if(curr_behavior.state == PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_YIELDING_STATE) + p->vel += 1; + else if(p->beh == PlannerHNS::BEH_YIELDING_STATE) + p->vel = p->vel/2.0; + else if(curr_behavior.state != PlannerHNS::STOPPING_STATE && p->beh == PlannerHNS::BEH_STOPPING_STATE) + p->vel += 1; + else if(p->beh == PlannerHNS::BEH_STOPPING_STATE) + { + p->vel = 0; + } + + } + } + //std::cout << "End Motion Status ------ " << std::endl; } } /* namespace PlannerHNS */ diff --git a/common/op_planner/src/BehaviorStateMachine.cpp b/common/op_planner/src/BehaviorStateMachine.cpp index 97939de1a94..9b5b2d774b1 100755 --- a/common/op_planner/src/BehaviorStateMachine.cpp +++ b/common/op_planner/src/BehaviorStateMachine.cpp @@ -16,102 +16,102 @@ namespace PlannerHNS BehaviorStateMachine::BehaviorStateMachine(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* nextState) { - m_Behavior = INITIAL_STATE; + m_Behavior = INITIAL_STATE; - m_currentStopSignID = -1; - m_currentTrafficLightID = -1; - decisionMakingTime = 0.0; - decisionMakingCount = 1; - m_zero_velocity = 0.1; + m_currentStopSignID = -1; + m_currentTrafficLightID = -1; + decisionMakingTime = 0.0; + decisionMakingCount = 1; + m_zero_velocity = 0.1; - if(!pPreCalcVal) - m_pCalculatedValues = new PreCalculatedConditions(); - else - m_pCalculatedValues = pPreCalcVal; + if(!pPreCalcVal) + m_pCalculatedValues = new PreCalculatedConditions(); + else + m_pCalculatedValues = pPreCalcVal; - if(!pParams) - m_pParams = new PlanningParams; - else - m_pParams = pParams; + if(!pParams) + m_pParams = new PlanningParams; + else + m_pParams = pParams; - if(nextState) - pNextStates.push_back(nextState); + if(nextState) + pNextStates.push_back(nextState); - pNextStates.push_back(this); + pNextStates.push_back(this); - Init(); + Init(); } void BehaviorStateMachine::InsertNextState(BehaviorStateMachine* nextState) { - if(nextState) - pNextStates.push_back(nextState); + if(nextState) + pNextStates.push_back(nextState); } void BehaviorStateMachine::UpdateLogCount(BehaviorStateMachine* pState) { - if(!pState) return; - - bool bFound = false; - for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++) - { - if(m_BehaviorsLog.at(i).first->m_Behavior == pState->m_Behavior) - { - m_BehaviorsLog.at(i).second++; - bFound = true; - break; - } - } - - if(!bFound) - { - m_BehaviorsLog.push_back(std::make_pair(pState, 1)); - } + if(!pState) return; + + bool bFound = false; + for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++) + { + if(m_BehaviorsLog.at(i).first->m_Behavior == pState->m_Behavior) + { + m_BehaviorsLog.at(i).second++; + bFound = true; + break; + } + } + + if(!bFound) + { + m_BehaviorsLog.push_back(std::make_pair(pState, 1)); + } } BehaviorStateMachine* BehaviorStateMachine::FindBestState(int nMinCount) { - for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++) - { - if(m_BehaviorsLog.at(i).second >= nMinCount) - { - //std::cout << "Found Next Beh: " << m_BehaviorsLog.at(i).first->m_Behavior << ", Count: " << m_BehaviorsLog.at(i).second << ", LogSize: " << m_BehaviorsLog.size() << std::endl; - return m_BehaviorsLog.at(i).first; - } - } - - return nullptr; + for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++) + { + if(m_BehaviorsLog.at(i).second >= nMinCount) + { + //std::cout << "Found Next Beh: " << m_BehaviorsLog.at(i).first->m_Behavior << ", Count: " << m_BehaviorsLog.at(i).second << ", LogSize: " << m_BehaviorsLog.size() << std::endl; + return m_BehaviorsLog.at(i).first; + } + } + + return nullptr; } BehaviorStateMachine* BehaviorStateMachine::FindBehaviorState(const STATE_TYPE& behavior) { - for(unsigned int i = 0 ; i < pNextStates.size(); i++) - { - BehaviorStateMachine* pState = pNextStates.at(i); - if(pState && behavior == pState->m_Behavior ) - { - //UpdateLogCount(pState); - //pState = FindBestState(decisionMakingCount); - - if(pState == 0) return this; - - m_BehaviorsLog.clear(); - pState->ResetTimer(); - return pState; - } - } - - return nullptr; + for(unsigned int i = 0 ; i < pNextStates.size(); i++) + { + BehaviorStateMachine* pState = pNextStates.at(i); + if(pState && behavior == pState->m_Behavior ) + { + //UpdateLogCount(pState); + //pState = FindBestState(decisionMakingCount); + + if(pState == 0) return this; + + m_BehaviorsLog.clear(); + pState->ResetTimer(); + return pState; + } + } + + return nullptr; } void BehaviorStateMachine::Init() { - UtilityH::GetTickCount(m_StateTimer); + UtilityH::GetTickCount(m_StateTimer); } void BehaviorStateMachine::ResetTimer() { - UtilityH::GetTickCount(m_StateTimer); + UtilityH::GetTickCount(m_StateTimer); } BehaviorStateMachine::~BehaviorStateMachine() @@ -120,398 +120,398 @@ BehaviorStateMachine::~BehaviorStateMachine() BehaviorStateMachine* ForwardState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; //return this behavior only , without reset - - PreCalculatedConditions* pCParams = GetCalcParams(); - - if(pCParams->currentGoalID != pCParams->prevGoalID) - return FindBehaviorState(GOAL_STATE); - - else if(m_pParams->enableSwerving - && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid - && !pCParams->bFullyBlock - && (pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory || pCParams->iCurrSafeLane != pCParams->iPrevSafeLane) - ) - return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); - - else if(m_pParams->enableTrafficLightBehavior - && pCParams->currentTrafficLightID > 0 - && pCParams->bTrafficIsRed - && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) - return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - - else if(m_pParams->enableStopSignBehavior - && pCParams->currentStopSignID > 0 - && pCParams->currentStopSignID != pCParams->prevStopSignID) - return FindBehaviorState(STOP_SIGN_STOP_STATE); - - else if(m_pParams->enableFollowing - && pCParams->bFullyBlock) - return FindBehaviorState(FOLLOW_STATE); - -// else if(pCParams->distanceToNext <= m_pParams->maxDistanceToAvoid) -// return FindBehaviorState(STOPPING_STATE); - - else - { - if(pCParams->iCurrSafeTrajectory == pCParams->iCentralTrajectory - && pCParams->iPrevSafeTrajectory != pCParams->iCurrSafeTrajectory) - pCParams->bRePlan = true; - - return FindBehaviorState(this->m_Behavior); // return and reset - } + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; //return this behavior only , without reset + + PreCalculatedConditions* pCParams = GetCalcParams(); + + if(pCParams->currentGoalID != pCParams->prevGoalID) + return FindBehaviorState(GOAL_STATE); + + else if(m_pParams->enableSwerving + && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid + && !pCParams->bFullyBlock + && (pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory || pCParams->iCurrSafeLane != pCParams->iPrevSafeLane) + ) + return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); + + else if(m_pParams->enableTrafficLightBehavior + && pCParams->currentTrafficLightID > 0 + && pCParams->bTrafficIsRed + && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) + return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); + + else if(m_pParams->enableStopSignBehavior + && pCParams->currentStopSignID > 0 + && pCParams->currentStopSignID != pCParams->prevStopSignID) + return FindBehaviorState(STOP_SIGN_STOP_STATE); + + else if(m_pParams->enableFollowing + && pCParams->bFullyBlock) + return FindBehaviorState(FOLLOW_STATE); + +// else if(pCParams->distanceToNext <= m_pParams->maxDistanceToAvoid) +// return FindBehaviorState(STOPPING_STATE); + + else + { + if(pCParams->iCurrSafeTrajectory == pCParams->iCentralTrajectory + && pCParams->iPrevSafeTrajectory != pCParams->iCurrSafeTrajectory) + pCParams->bRePlan = true; + + return FindBehaviorState(this->m_Behavior); // return and reset + } } BehaviorStateMachine* MissionAccomplishedState::GetNextState() { - return FindBehaviorState(this->m_Behavior); // return and reset + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* StopState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->distanceToNext > m_pParams->maxDistanceToAvoid) - return FindBehaviorState(FORWARD_STATE); + if(pCParams->distanceToNext > m_pParams->maxDistanceToAvoid) + return FindBehaviorState(FORWARD_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* TrafficLightStopState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(!pCParams->bTrafficIsRed) - { - pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; - return FindBehaviorState(FORWARD_STATE); - } + if(!pCParams->bTrafficIsRed) + { + pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; + return FindBehaviorState(FORWARD_STATE); + } - else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity) - return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity) + return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE); + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* TrafficLightWaitState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(!pCParams->bTrafficIsRed) - { - pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; - return FindBehaviorState(FORWARD_STATE); - } + if(!pCParams->bTrafficIsRed) + { + pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; + return FindBehaviorState(FORWARD_STATE); + } - else if(pCParams->currentVelocity > m_zero_velocity) - return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); + else if(pCParams->currentVelocity > m_zero_velocity) + return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* StopSignStopState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - //std::cout << "From Stop Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl; + //std::cout << "From Stop Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl; - if(pCParams->currentVelocity < m_zero_velocity) - return FindBehaviorState(STOP_SIGN_WAIT_STATE); + if(pCParams->currentVelocity < m_zero_velocity) + return FindBehaviorState(STOP_SIGN_WAIT_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* StopSignWaitState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - //std::cout << "From Wait Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl; + //std::cout << "From Wait Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl; - pCParams->prevStopSignID = pCParams->currentStopSignID; + pCParams->prevStopSignID = pCParams->currentStopSignID; - return FindBehaviorState(FORWARD_STATE); + return FindBehaviorState(FORWARD_STATE); } BehaviorStateMachine* WaitState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - //PreCalculatedConditions* pCParams = GetCalcParams(); + //PreCalculatedConditions* pCParams = GetCalcParams(); - return FindBehaviorState(FORWARD_STATE); + return FindBehaviorState(FORWARD_STATE); } BehaviorStateMachine* InitState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->bOutsideControl == 1) - { - pCParams->prevGoalID = pCParams->currentGoalID; - return FindBehaviorState(FORWARD_STATE); - } + if(pCParams->bOutsideControl == 1) + { + pCParams->prevGoalID = pCParams->currentGoalID; + return FindBehaviorState(FORWARD_STATE); + } - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* FollowState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - //std::cout << "Following State >> followDistance: " << pCParams->distanceToNext << ", followSpeed: " << pCParams->velocityOfNext << std::endl; + //std::cout << "Following State >> followDistance: " << pCParams->distanceToNext << ", followSpeed: " << pCParams->velocityOfNext << std::endl; - if(m_pParams->enableTrafficLightBehavior - && pCParams->currentTrafficLightID > 0 - && pCParams->bTrafficIsRed - && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) - return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); + if(m_pParams->enableTrafficLightBehavior + && pCParams->currentTrafficLightID > 0 + && pCParams->bTrafficIsRed + && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) + return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - else if(m_pParams->enableStopSignBehavior - && pCParams->currentStopSignID > 0 - && pCParams->currentStopSignID != pCParams->prevStopSignID) - return FindBehaviorState(STOP_SIGN_STOP_STATE); + else if(m_pParams->enableStopSignBehavior + && pCParams->currentStopSignID > 0 + && pCParams->currentStopSignID != pCParams->prevStopSignID) + return FindBehaviorState(STOP_SIGN_STOP_STATE); - else if(pCParams->currentGoalID != pCParams->prevGoalID - || !pCParams->bFullyBlock) - return FindBehaviorState(FORWARD_STATE); + else if(pCParams->currentGoalID != pCParams->prevGoalID + || !pCParams->bFullyBlock) + return FindBehaviorState(FORWARD_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* SwerveState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->distanceToNext > 0 - && pCParams->distanceToNext < m_pParams->minDistanceToAvoid - && !pCParams->bFullyBlock - && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) - return FindBehaviorState(this->m_Behavior); + if(pCParams->distanceToNext > 0 + && pCParams->distanceToNext < m_pParams->minDistanceToAvoid + && !pCParams->bFullyBlock + && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) + return FindBehaviorState(this->m_Behavior); - else - return FindBehaviorState(FORWARD_STATE); + else + return FindBehaviorState(FORWARD_STATE); } BehaviorStateMachine* GoalState::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID == -1) - return FindBehaviorState(FINISH_STATE); + if(pCParams->currentGoalID == -1) + return FindBehaviorState(FINISH_STATE); - else if(pCParams->currentGoalID != pCParams->prevGoalID) - { - pCParams->prevGoalID = pCParams->currentGoalID; - return FindBehaviorState(FORWARD_STATE); - } + else if(pCParams->currentGoalID != pCParams->prevGoalID) + { + pCParams->prevGoalID = pCParams->currentGoalID; + return FindBehaviorState(FORWARD_STATE); + } - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* ForwardStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID != pCParams->prevGoalID) - return FindBehaviorState(GOAL_STATE); + if(pCParams->currentGoalID != pCParams->prevGoalID) + return FindBehaviorState(GOAL_STATE); - else if(m_pParams->enableTrafficLightBehavior - && pCParams->currentTrafficLightID > 0 - && pCParams->bTrafficIsRed - && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) - return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); + else if(m_pParams->enableTrafficLightBehavior + && pCParams->currentTrafficLightID > 0 + && pCParams->bTrafficIsRed + && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) + return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - else if(m_pParams->enableStopSignBehavior - && pCParams->currentStopSignID > 0 - && pCParams->currentStopSignID != pCParams->prevStopSignID) - return FindBehaviorState(STOP_SIGN_STOP_STATE); + else if(m_pParams->enableStopSignBehavior + && pCParams->currentStopSignID > 0 + && pCParams->currentStopSignID != pCParams->prevStopSignID) + return FindBehaviorState(STOP_SIGN_STOP_STATE); - else if(m_pParams->enableFollowing && pCParams->bFullyBlock) - return FindBehaviorState(FOLLOW_STATE); + else if(m_pParams->enableFollowing && pCParams->bFullyBlock) + return FindBehaviorState(FOLLOW_STATE); - else if(m_pParams->enableSwerving - && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid - && !pCParams->bFullyBlock - && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) - return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); + else if(m_pParams->enableSwerving + && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid + && !pCParams->bFullyBlock + && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) + return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); - else - return FindBehaviorState(this->m_Behavior); + else + return FindBehaviorState(this->m_Behavior); } BehaviorStateMachine* FollowStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID != pCParams->prevGoalID) - return FindBehaviorState(GOAL_STATE); + if(pCParams->currentGoalID != pCParams->prevGoalID) + return FindBehaviorState(GOAL_STATE); - else if(m_pParams->enableTrafficLightBehavior - && pCParams->currentTrafficLightID > 0 - && pCParams->bTrafficIsRed - && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) - return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); + else if(m_pParams->enableTrafficLightBehavior + && pCParams->currentTrafficLightID > 0 + && pCParams->bTrafficIsRed + && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID) + return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - else if(m_pParams->enableStopSignBehavior - && pCParams->currentStopSignID > 0 - && pCParams->currentStopSignID != pCParams->prevStopSignID) - return FindBehaviorState(STOP_SIGN_STOP_STATE); + else if(m_pParams->enableStopSignBehavior + && pCParams->currentStopSignID > 0 + && pCParams->currentStopSignID != pCParams->prevStopSignID) + return FindBehaviorState(STOP_SIGN_STOP_STATE); - else if(m_pParams->enableSwerving - && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid - && !pCParams->bFullyBlock - && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) - return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); + else if(m_pParams->enableSwerving + && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid + && !pCParams->bFullyBlock + && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory) + return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE); - else if(!pCParams->bFullyBlock) - return FindBehaviorState(FORWARD_STATE); + else if(!pCParams->bFullyBlock) + return FindBehaviorState(FORWARD_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* SwerveStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - pCParams->iPrevSafeTrajectory = pCParams->iCurrSafeTrajectory; - pCParams->bRePlan = true; + pCParams->iPrevSafeTrajectory = pCParams->iCurrSafeTrajectory; + pCParams->bRePlan = true; - return FindBehaviorState(FORWARD_STATE); + return FindBehaviorState(FORWARD_STATE); } BehaviorStateMachine* InitStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID > 0) - return FindBehaviorState(FORWARD_STATE); - else - return FindBehaviorState(this->m_Behavior); + if(pCParams->currentGoalID > 0) + return FindBehaviorState(FORWARD_STATE); + else + return FindBehaviorState(this->m_Behavior); } BehaviorStateMachine* GoalStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID == -1) - return FindBehaviorState(FINISH_STATE); + if(pCParams->currentGoalID == -1) + return FindBehaviorState(FINISH_STATE); - else - { - pCParams->prevGoalID = pCParams->currentGoalID; - return FindBehaviorState(FORWARD_STATE); - } + else + { + pCParams->prevGoalID = pCParams->currentGoalID; + return FindBehaviorState(FORWARD_STATE); + } } BehaviorStateMachine* MissionAccomplishedStateII::GetNextState() { - return FindBehaviorState(this->m_Behavior); + return FindBehaviorState(this->m_Behavior); } BehaviorStateMachine* StopSignStopStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - if(pCParams->currentGoalID != pCParams->prevGoalID) - return FindBehaviorState(GOAL_STATE); + if(pCParams->currentGoalID != pCParams->prevGoalID) + return FindBehaviorState(GOAL_STATE); - else if(pCParams->currentVelocity < m_zero_velocity) - return FindBehaviorState(STOP_SIGN_WAIT_STATE); + else if(pCParams->currentVelocity < m_zero_velocity) + return FindBehaviorState(STOP_SIGN_WAIT_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } BehaviorStateMachine* StopSignWaitStateII::GetNextState() { - if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) - return this; + if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime) + return this; - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - pCParams->prevStopSignID = pCParams->currentStopSignID; + pCParams->prevStopSignID = pCParams->currentStopSignID; - return FindBehaviorState(FORWARD_STATE); + return FindBehaviorState(FORWARD_STATE); } BehaviorStateMachine* TrafficLightStopStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); - - //std::cout << "Stopping for trafficLight " << std::endl; - if(!pCParams->bTrafficIsRed) - { - //std::cout << "Color Changed Stopping for trafficLight " << std::endl; - pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; - return FindBehaviorState(FORWARD_STATE); - } - - else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity) - { - //std::cout << "Velocity Changed Stopping for trafficLight (" <currentVelocity << ", " << m_zero_velocity << ")" << std::endl; - return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE); - } - - else - { - return FindBehaviorState(this->m_Behavior); // return and reset - } + PreCalculatedConditions* pCParams = GetCalcParams(); + + //std::cout << "Stopping for trafficLight " << std::endl; + if(!pCParams->bTrafficIsRed) + { + //std::cout << "Color Changed Stopping for trafficLight " << std::endl; + pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; + return FindBehaviorState(FORWARD_STATE); + } + + else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity) + { + //std::cout << "Velocity Changed Stopping for trafficLight (" <currentVelocity << ", " << m_zero_velocity << ")" << std::endl; + return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE); + } + + else + { + return FindBehaviorState(this->m_Behavior); // return and reset + } } BehaviorStateMachine* TrafficLightWaitStateII::GetNextState() { - PreCalculatedConditions* pCParams = GetCalcParams(); + PreCalculatedConditions* pCParams = GetCalcParams(); - //std::cout << "Wait for trafficLight " << std::endl; + //std::cout << "Wait for trafficLight " << std::endl; - if(!pCParams->bTrafficIsRed) - { - pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; - return FindBehaviorState(FORWARD_STATE); - } + if(!pCParams->bTrafficIsRed) + { + pCParams->prevTrafficLightID = pCParams->currentTrafficLightID; + return FindBehaviorState(FORWARD_STATE); + } -// else if(pCParams->currentVelocity > m_zero_velocity) -// return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); +// else if(pCParams->currentVelocity > m_zero_velocity) +// return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE); - else - return FindBehaviorState(this->m_Behavior); // return and reset + else + return FindBehaviorState(this->m_Behavior); // return and reset } diff --git a/common/op_planner/src/DecisionMaker.cpp b/common/op_planner/src/DecisionMaker.cpp index b94d015eb75..1f936374474 100755 --- a/common/op_planner/src/DecisionMaker.cpp +++ b/common/op_planner/src/DecisionMaker.cpp @@ -17,473 +17,473 @@ namespace PlannerHNS DecisionMaker::DecisionMaker() { - m_iCurrentTotalPathId = 0; - pLane = 0; - m_pCurrentBehaviorState = 0; - m_pGoToGoalState = 0; - m_pStopState= 0; - m_pWaitState= 0; - m_pMissionCompleteState= 0; - m_pAvoidObstacleState = 0; - m_pTrafficLightStopState = 0; - m_pTrafficLightWaitState = 0; - m_pStopSignStopState = 0; - m_pStopSignWaitState = 0; - m_pFollowState = 0; - m_MaxLaneSearchDistance = 3.0; - m_pStopState = 0; - m_pMissionCompleteState = 0; - m_pGoalState = 0; - m_pGoToGoalState = 0; - m_pWaitState = 0; - m_pInitState = 0; - m_pFollowState = 0; - m_pAvoidObstacleState = 0; + m_iCurrentTotalPathId = 0; + pLane = 0; + m_pCurrentBehaviorState = 0; + m_pGoToGoalState = 0; + m_pStopState= 0; + m_pWaitState= 0; + m_pMissionCompleteState= 0; + m_pAvoidObstacleState = 0; + m_pTrafficLightStopState = 0; + m_pTrafficLightWaitState = 0; + m_pStopSignStopState = 0; + m_pStopSignWaitState = 0; + m_pFollowState = 0; + m_MaxLaneSearchDistance = 3.0; + m_pStopState = 0; + m_pMissionCompleteState = 0; + m_pGoalState = 0; + m_pGoToGoalState = 0; + m_pWaitState = 0; + m_pInitState = 0; + m_pFollowState = 0; + m_pAvoidObstacleState = 0; } DecisionMaker::~DecisionMaker() { - delete m_pStopState; - delete m_pMissionCompleteState; - delete m_pGoalState; - delete m_pGoToGoalState; - delete m_pWaitState; - delete m_pInitState; - delete m_pFollowState; - delete m_pAvoidObstacleState; - delete m_pTrafficLightStopState; - delete m_pTrafficLightWaitState; - delete m_pStopSignWaitState; - delete m_pStopSignStopState; + delete m_pStopState; + delete m_pMissionCompleteState; + delete m_pGoalState; + delete m_pGoToGoalState; + delete m_pWaitState; + delete m_pInitState; + delete m_pFollowState; + delete m_pAvoidObstacleState; + delete m_pTrafficLightStopState; + delete m_pTrafficLightWaitState; + delete m_pStopSignWaitState; + delete m_pStopSignStopState; } void DecisionMaker::Init(const ControllerParams& ctrlParams, const PlannerHNS::PlanningParams& params,const CAR_BASIC_INFO& carInfo) - { - m_CarInfo = carInfo; - m_ControlParams = ctrlParams; - m_params = params; + { + m_CarInfo = carInfo; + m_ControlParams = ctrlParams; + m_params = params; - m_pidVelocity.Init(0.01, 0.004, 0.01); - m_pidVelocity.Setlimit(m_params.maxSpeed, 0); + m_pidVelocity.Init(0.01, 0.004, 0.01); + m_pidVelocity.Setlimit(m_params.maxSpeed, 0); - m_pidStopping.Init(0.05, 0.05, 0.1); - m_pidStopping.Setlimit(m_params.horizonDistance, 0); + m_pidStopping.Init(0.05, 0.05, 0.1); + m_pidStopping.Setlimit(m_params.horizonDistance, 0); - m_pidFollowing.Init(0.05, 0.05, 0.01); - m_pidFollowing.Setlimit(m_params.minFollowingDistance, 0); + m_pidFollowing.Init(0.05, 0.05, 0.01); + m_pidFollowing.Setlimit(m_params.minFollowingDistance, 0); - InitBehaviorStates(); + InitBehaviorStates(); - if(m_pCurrentBehaviorState) - m_pCurrentBehaviorState->SetBehaviorsParams(&m_params); - } + if(m_pCurrentBehaviorState) + m_pCurrentBehaviorState->SetBehaviorsParams(&m_params); + } void DecisionMaker::InitBehaviorStates() { - m_pStopState = new StopState(&m_params, 0, 0); - m_pMissionCompleteState = new MissionAccomplishedStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), 0); - m_pGoalState = new GoalStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pMissionCompleteState); - m_pGoToGoalState = new ForwardStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoalState); - m_pInitState = new InitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pStopState = new StopState(&m_params, 0, 0); + m_pMissionCompleteState = new MissionAccomplishedStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), 0); + m_pGoalState = new GoalStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pMissionCompleteState); + m_pGoToGoalState = new ForwardStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoalState); + m_pInitState = new InitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pFollowState = new FollowStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pAvoidObstacleState = new SwerveStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pStopSignWaitState = new StopSignWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pStopSignStopState = new StopSignStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pStopSignWaitState); + m_pFollowState = new FollowStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pAvoidObstacleState = new SwerveStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pStopSignWaitState = new StopSignWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pStopSignStopState = new StopSignStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pStopSignWaitState); - m_pTrafficLightWaitState = new TrafficLightWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pTrafficLightStopState = new TrafficLightStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pTrafficLightWaitState = new TrafficLightWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pTrafficLightStopState = new TrafficLightStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pGoToGoalState->InsertNextState(m_pAvoidObstacleState); - m_pGoToGoalState->InsertNextState(m_pStopSignStopState); - m_pGoToGoalState->InsertNextState(m_pTrafficLightStopState); - m_pGoToGoalState->InsertNextState(m_pFollowState); - m_pGoToGoalState->decisionMakingCount = 0;//m_params.nReliableCount; + m_pGoToGoalState->InsertNextState(m_pAvoidObstacleState); + m_pGoToGoalState->InsertNextState(m_pStopSignStopState); + m_pGoToGoalState->InsertNextState(m_pTrafficLightStopState); + m_pGoToGoalState->InsertNextState(m_pFollowState); + m_pGoToGoalState->decisionMakingCount = 0;//m_params.nReliableCount; - m_pGoalState->InsertNextState(m_pGoToGoalState); + m_pGoalState->InsertNextState(m_pGoToGoalState); - m_pStopSignWaitState->decisionMakingTime = m_params.stopSignStopTime; - m_pStopSignWaitState->InsertNextState(m_pStopSignStopState); - m_pStopSignWaitState->InsertNextState(m_pGoalState); + m_pStopSignWaitState->decisionMakingTime = m_params.stopSignStopTime; + m_pStopSignWaitState->InsertNextState(m_pStopSignStopState); + m_pStopSignWaitState->InsertNextState(m_pGoalState); - m_pTrafficLightStopState->InsertNextState(m_pTrafficLightWaitState); + m_pTrafficLightStopState->InsertNextState(m_pTrafficLightWaitState); - m_pTrafficLightWaitState->InsertNextState(m_pTrafficLightStopState); - m_pTrafficLightWaitState->InsertNextState(m_pGoalState); + m_pTrafficLightWaitState->InsertNextState(m_pTrafficLightStopState); + m_pTrafficLightWaitState->InsertNextState(m_pGoalState); - m_pFollowState->InsertNextState(m_pAvoidObstacleState); - m_pFollowState->InsertNextState(m_pStopSignStopState); - m_pFollowState->InsertNextState(m_pTrafficLightStopState); - m_pFollowState->InsertNextState(m_pGoalState); - m_pFollowState->decisionMakingCount = 0;//m_params.nReliableCount; + m_pFollowState->InsertNextState(m_pAvoidObstacleState); + m_pFollowState->InsertNextState(m_pStopSignStopState); + m_pFollowState->InsertNextState(m_pTrafficLightStopState); + m_pFollowState->InsertNextState(m_pGoalState); + m_pFollowState->decisionMakingCount = 0;//m_params.nReliableCount; - m_pInitState->decisionMakingCount = 0;//m_params.nReliableCount; + m_pInitState->decisionMakingCount = 0;//m_params.nReliableCount; - m_pCurrentBehaviorState = m_pInitState; + m_pCurrentBehaviorState = m_pInitState; } bool DecisionMaker::GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, PlannerHNS::TrafficLight& trafficL) { - for(unsigned int i = 0; i < trafficLights.size(); i++) - { - double d = hypot(trafficLights.at(i).pos.y - state.pos.y, trafficLights.at(i).pos.x - state.pos.x); - if(d <= trafficLights.at(i).stoppingDistance) - { - double a_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(UtilityHNS::UtilityH::FixNegativeAngle(trafficLights.at(i).pos.a) , UtilityHNS::UtilityH::FixNegativeAngle(state.pos.a)); - - if(a_diff < M_PI_2 && trafficLights.at(i).id != prevTrafficLightId) - { - //std::cout << "Detected Light, ID = " << trafficLights.at(i).id << ", Distance = " << d << ", Angle = " << trafficLights.at(i).pos.a*RAD2DEG << ", Car Heading = " << state.pos.a*RAD2DEG << ", Diff = " << a_diff*RAD2DEG << std::endl; - trafficL = trafficLights.at(i); - return true; - } - } - } - - return false; + for(unsigned int i = 0; i < trafficLights.size(); i++) + { + double d = hypot(trafficLights.at(i).pos.y - state.pos.y, trafficLights.at(i).pos.x - state.pos.x); + if(d <= trafficLights.at(i).stoppingDistance) + { + double a_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(UtilityHNS::UtilityH::FixNegativeAngle(trafficLights.at(i).pos.a) , UtilityHNS::UtilityH::FixNegativeAngle(state.pos.a)); + + if(a_diff < M_PI_2 && trafficLights.at(i).id != prevTrafficLightId) + { + //std::cout << "Detected Light, ID = " << trafficLights.at(i).id << ", Distance = " << d << ", Angle = " << trafficLights.at(i).pos.a*RAD2DEG << ", Car Heading = " << state.pos.a*RAD2DEG << ", Diff = " << a_diff*RAD2DEG << std::endl; + trafficL = trafficLights.at(i); + return true; + } + } + } + + return false; } void DecisionMaker::CalculateImportantParameterForDecisionMaking(const PlannerHNS::VehicleState& car_state, - const int& goalID, const bool& bEmergencyStop, const std::vector& detectedLights, - const TrajectoryCost& bestTrajectory) + const int& goalID, const bool& bEmergencyStop, const std::vector& detectedLights, + const TrajectoryCost& bestTrajectory) { - if(m_TotalPath.size() == 0) return; + if(m_TotalPath.size() == 0) return; - PreCalculatedConditions* pValues = m_pCurrentBehaviorState->GetCalcParams(); + PreCalculatedConditions* pValues = m_pCurrentBehaviorState->GetCalcParams(); - if(m_CarInfo.max_deceleration != 0) - pValues->minStoppingDistance = -pow(car_state.speed, 2)/(m_CarInfo.max_deceleration); + if(m_CarInfo.max_deceleration != 0) + pValues->minStoppingDistance = -pow(car_state.speed, 2)/(m_CarInfo.max_deceleration); - pValues->iCentralTrajectory = m_pCurrentBehaviorState->m_pParams->rollOutNumber/2; + pValues->iCentralTrajectory = m_pCurrentBehaviorState->m_pParams->rollOutNumber/2; - if(pValues->iPrevSafeTrajectory < 0) - pValues->iPrevSafeTrajectory = pValues->iCentralTrajectory; + if(pValues->iPrevSafeTrajectory < 0) + pValues->iPrevSafeTrajectory = pValues->iCentralTrajectory; - pValues->stoppingDistances.clear(); - pValues->currentVelocity = car_state.speed; - pValues->bTrafficIsRed = false; - pValues->currentTrafficLightID = -1; - pValues->bFullyBlock = false; + pValues->stoppingDistances.clear(); + pValues->currentVelocity = car_state.speed; + pValues->bTrafficIsRed = false; + pValues->currentTrafficLightID = -1; + pValues->bFullyBlock = false; - pValues->distanceToNext = bestTrajectory.closest_obj_distance; - pValues->velocityOfNext = bestTrajectory.closest_obj_velocity; + pValues->distanceToNext = bestTrajectory.closest_obj_distance; + pValues->velocityOfNext = bestTrajectory.closest_obj_velocity; - if(bestTrajectory.index >=0 && bestTrajectory.index < (int)m_RollOuts.size()) - pValues->iCurrSafeTrajectory = bestTrajectory.index; - else - pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; + if(bestTrajectory.index >=0 && bestTrajectory.index < (int)m_RollOuts.size()) + pValues->iCurrSafeTrajectory = bestTrajectory.index; + else + pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; - pValues->bFullyBlock = bestTrajectory.bBlocked; + pValues->bFullyBlock = bestTrajectory.bBlocked; - if(bestTrajectory.lane_index >=0) - pValues->iCurrSafeLane = bestTrajectory.lane_index; - else - { - PlannerHNS::RelativeInfo info; - PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_TotalPath, state, m_params.rollOutDensity*m_params.rollOutNumber/2.0 + 0.1, info); - pValues->iCurrSafeLane = info.iGlobalPath; - } + if(bestTrajectory.lane_index >=0) + pValues->iCurrSafeLane = bestTrajectory.lane_index; + else + { + PlannerHNS::RelativeInfo info; + PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_TotalPath, state, m_params.rollOutDensity*m_params.rollOutNumber/2.0 + 0.1, info); + pValues->iCurrSafeLane = info.iGlobalPath; + } - double critical_long_front_distance = m_CarInfo.wheel_base/2.0 + m_CarInfo.length/2.0 + m_params.verticalSafetyDistance; + double critical_long_front_distance = m_CarInfo.wheel_base/2.0 + m_CarInfo.length/2.0 + m_params.verticalSafetyDistance; - if(ReachEndOfGlobalPath(pValues->minStoppingDistance + critical_long_front_distance, pValues->iCurrSafeLane)) - pValues->currentGoalID = -1; - else - pValues->currentGoalID = goalID; + if(ReachEndOfGlobalPath(pValues->minStoppingDistance + critical_long_front_distance, pValues->iCurrSafeLane)) + pValues->currentGoalID = -1; + else + pValues->currentGoalID = goalID; - m_iCurrentTotalPathId = pValues->iCurrSafeLane; + m_iCurrentTotalPathId = pValues->iCurrSafeLane; - int stopLineID = -1; - int stopSignID = -1; - int trafficLightID = -1; - double distanceToClosestStopLine = 0; - bool bGreenTrafficLight = true; + int stopLineID = -1; + int stopSignID = -1; + int trafficLightID = -1; + double distanceToClosestStopLine = 0; + bool bGreenTrafficLight = true; - distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_TotalPath.at(pValues->iCurrSafeLane), state, m_params.giveUpDistance, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; + distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_TotalPath.at(pValues->iCurrSafeLane), state, m_params.giveUpDistance, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; - //std::cout << "StopLineID" << stopLineID << ", StopSignID: " << stopSignID << ", TrafficLightID: " << trafficLightID << ", Distance: " << distanceToClosestStopLine << ", MinStopDistance: " << pValues->minStoppingDistance << std::endl; + //std::cout << "StopLineID" << stopLineID << ", StopSignID: " << stopSignID << ", TrafficLightID: " << trafficLightID << ", Distance: " << distanceToClosestStopLine << ", MinStopDistance: " << pValues->minStoppingDistance << std::endl; - if(distanceToClosestStopLine > m_params.giveUpDistance && distanceToClosestStopLine < (pValues->minStoppingDistance + 1.0)) - { - if(m_pCurrentBehaviorState->m_pParams->enableTrafficLightBehavior) - { - pValues->currentTrafficLightID = trafficLightID; - //std::cout << "Detected Traffic Light: " << trafficLightID << std::endl; - for(unsigned int i=0; i< detectedLights.size(); i++) - { - if(detectedLights.at(i).id == trafficLightID) - bGreenTrafficLight = (detectedLights.at(i).lightState == GREEN_LIGHT); - } - } + if(distanceToClosestStopLine > m_params.giveUpDistance && distanceToClosestStopLine < (pValues->minStoppingDistance + 1.0)) + { + if(m_pCurrentBehaviorState->m_pParams->enableTrafficLightBehavior) + { + pValues->currentTrafficLightID = trafficLightID; + //std::cout << "Detected Traffic Light: " << trafficLightID << std::endl; + for(unsigned int i=0; i< detectedLights.size(); i++) + { + if(detectedLights.at(i).id == trafficLightID) + bGreenTrafficLight = (detectedLights.at(i).lightState == GREEN_LIGHT); + } + } - if(m_pCurrentBehaviorState->m_pParams->enableStopSignBehavior) - pValues->currentStopSignID = stopSignID; + if(m_pCurrentBehaviorState->m_pParams->enableStopSignBehavior) + pValues->currentStopSignID = stopSignID; - pValues->stoppingDistances.push_back(distanceToClosestStopLine); - //std::cout << "LP => D: " << pValues->distanceToStop() << ", PrevSignID: " << pValues->prevTrafficLightID << ", CurrSignID: " << pValues->currentTrafficLightID << ", Green: " << bGreenTrafficLight << endl; - } + pValues->stoppingDistances.push_back(distanceToClosestStopLine); + //std::cout << "LP => D: " << pValues->distanceToStop() << ", PrevSignID: " << pValues->prevTrafficLightID << ", CurrSignID: " << pValues->currentTrafficLightID << ", Green: " << bGreenTrafficLight << endl; + } - //std::cout << "Distance To Closest: " << distanceToClosestStopLine << ", Stop LineID: " << stopLineID << ", Stop SignID: " << stopSignID << ", TFID: " << trafficLightID << std::endl; + //std::cout << "Distance To Closest: " << distanceToClosestStopLine << ", Stop LineID: " << stopLineID << ", Stop SignID: " << stopSignID << ", TFID: " << trafficLightID << std::endl; - pValues->bTrafficIsRed = !bGreenTrafficLight; + pValues->bTrafficIsRed = !bGreenTrafficLight; - if(bEmergencyStop) - { - pValues->bFullyBlock = true; - pValues->distanceToNext = 1; - pValues->velocityOfNext = 0; - } - //cout << "Distances: " << pValues->stoppingDistances.size() << ", Distance To Stop : " << pValues->distanceToStop << endl; + if(bEmergencyStop) + { + pValues->bFullyBlock = true; + pValues->distanceToNext = 1; + pValues->velocityOfNext = 0; + } + //cout << "Distances: " << pValues->stoppingDistances.size() << ", Distance To Stop : " << pValues->distanceToStop << endl; } void DecisionMaker::UpdateCurrentLane(const double& search_distance) { - PlannerHNS::Lane* pMapLane = 0; - PlannerHNS::Lane* pPathLane = 0; - pPathLane = MappingHelpers::GetLaneFromPath(state, m_TotalPath.at(m_iCurrentTotalPathId)); - if(!pPathLane) - { - std::cout << "Performance Alert: Can't Find Lane Information in Global Path, Searching the Map :( " << std::endl; - pMapLane = MappingHelpers::GetClosestLaneFromMap(state, m_Map, search_distance); - } - - if(pPathLane) - pLane = pPathLane; - else if(pMapLane) - pLane = pMapLane; - else - pLane = 0; + PlannerHNS::Lane* pMapLane = 0; + PlannerHNS::Lane* pPathLane = 0; + pPathLane = MappingHelpers::GetLaneFromPath(state, m_TotalPath.at(m_iCurrentTotalPathId)); + if(!pPathLane) + { + std::cout << "Performance Alert: Can't Find Lane Information in Global Path, Searching the Map :( " << std::endl; + pMapLane = MappingHelpers::GetClosestLaneFromMap(state, m_Map, search_distance); + } + + if(pPathLane) + pLane = pPathLane; + else if(pMapLane) + pLane = pMapLane; + else + pLane = 0; } bool DecisionMaker::ReachEndOfGlobalPath(const double& min_distance, const int& iGlobalPathIndex) { - if(m_TotalPath.size()==0) return false; + if(m_TotalPath.size()==0) return false; - PlannerHNS::RelativeInfo info; - PlanningHelpers::GetRelativeInfo(m_TotalPath.at(iGlobalPathIndex), state, info); + PlannerHNS::RelativeInfo info; + PlanningHelpers::GetRelativeInfo(m_TotalPath.at(iGlobalPathIndex), state, info); - double d = 0; - for(unsigned int i = info.iFront; i < m_TotalPath.at(iGlobalPathIndex).size()-1; i++) - { - d+= hypot(m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.y - m_TotalPath.at(iGlobalPathIndex).at(i).pos.y, m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.x - m_TotalPath.at(iGlobalPathIndex).at(i).pos.x); - if(d > min_distance) - return false; - } + double d = 0; + for(unsigned int i = info.iFront; i < m_TotalPath.at(iGlobalPathIndex).size()-1; i++) + { + d+= hypot(m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.y - m_TotalPath.at(iGlobalPathIndex).at(i).pos.y, m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.x - m_TotalPath.at(iGlobalPathIndex).at(i).pos.x); + if(d > min_distance) + return false; + } - return true; + return true; } void DecisionMaker::SetNewGlobalPath(const std::vector >& globalPath) { - if(m_pCurrentBehaviorState) - { - m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath = true; - m_TotalOriginalPath = globalPath; - } + if(m_pCurrentBehaviorState) + { + m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath = true; + m_TotalOriginalPath = globalPath; + } } bool DecisionMaker::SelectSafeTrajectory() { - bool bNewTrajectory = false; - PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); - - if(!preCalcPrams || m_RollOuts.size() == 0) return bNewTrajectory; - - int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); - int index_limit = 0; - if(index_limit<=0) - index_limit = m_Path.size()/2.0; - if(currIndex > index_limit - || preCalcPrams->bRePlan - || preCalcPrams->bNewGlobalPath) - { - std::cout << "New Local Plan !! " << currIndex << ", "<< preCalcPrams->bRePlan << ", " << preCalcPrams->bNewGlobalPath << ", " << m_TotalOriginalPath.at(0).size() << ", PrevLocal: " << m_Path.size(); - m_Path = m_RollOuts.at(preCalcPrams->iCurrSafeTrajectory); - std::cout << ", NewLocal: " << m_Path.size() << std::endl; - - preCalcPrams->bNewGlobalPath = false; - preCalcPrams->bRePlan = false; - bNewTrajectory = true; - } - - return bNewTrajectory; + bool bNewTrajectory = false; + PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); + + if(!preCalcPrams || m_RollOuts.size() == 0) return bNewTrajectory; + + int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); + int index_limit = 0; + if(index_limit<=0) + index_limit = m_Path.size()/2.0; + if(currIndex > index_limit + || preCalcPrams->bRePlan + || preCalcPrams->bNewGlobalPath) + { + std::cout << "New Local Plan !! " << currIndex << ", "<< preCalcPrams->bRePlan << ", " << preCalcPrams->bNewGlobalPath << ", " << m_TotalOriginalPath.at(0).size() << ", PrevLocal: " << m_Path.size(); + m_Path = m_RollOuts.at(preCalcPrams->iCurrSafeTrajectory); + std::cout << ", NewLocal: " << m_Path.size() << std::endl; + + preCalcPrams->bNewGlobalPath = false; + preCalcPrams->bRePlan = false; + bNewTrajectory = true; + } + + return bNewTrajectory; } PlannerHNS::BehaviorState DecisionMaker::GenerateBehaviorState(const PlannerHNS::VehicleState& vehicleState) { - PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); + PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); - m_pCurrentBehaviorState = m_pCurrentBehaviorState->GetNextState(); - if(m_pCurrentBehaviorState==0) - m_pCurrentBehaviorState = m_pInitState; + m_pCurrentBehaviorState = m_pCurrentBehaviorState->GetNextState(); + if(m_pCurrentBehaviorState==0) + m_pCurrentBehaviorState = m_pInitState; - PlannerHNS::BehaviorState currentBehavior; + PlannerHNS::BehaviorState currentBehavior; - currentBehavior.state = m_pCurrentBehaviorState->m_Behavior; - currentBehavior.followDistance = preCalcPrams->distanceToNext; + currentBehavior.state = m_pCurrentBehaviorState->m_Behavior; + currentBehavior.followDistance = preCalcPrams->distanceToNext; - currentBehavior.minVelocity = 0; - currentBehavior.stopDistance = preCalcPrams->distanceToStop(); - currentBehavior.followVelocity = preCalcPrams->velocityOfNext; - if(preCalcPrams->iPrevSafeTrajectory<0 || preCalcPrams->iPrevSafeTrajectory >= m_RollOuts.size()) - currentBehavior.iTrajectory = preCalcPrams->iCurrSafeTrajectory; - else - currentBehavior.iTrajectory = preCalcPrams->iPrevSafeTrajectory; + currentBehavior.minVelocity = 0; + currentBehavior.stopDistance = preCalcPrams->distanceToStop(); + currentBehavior.followVelocity = preCalcPrams->velocityOfNext; + if(preCalcPrams->iPrevSafeTrajectory<0 || preCalcPrams->iPrevSafeTrajectory >= m_RollOuts.size()) + currentBehavior.iTrajectory = preCalcPrams->iCurrSafeTrajectory; + else + currentBehavior.iTrajectory = preCalcPrams->iPrevSafeTrajectory; - double average_braking_distance = -pow(vehicleState.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; + double average_braking_distance = -pow(vehicleState.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; - if(average_braking_distance < m_params.minIndicationDistance) - average_braking_distance = m_params.minIndicationDistance; + if(average_braking_distance < m_params.minIndicationDistance) + average_braking_distance = m_params.minIndicationDistance; - currentBehavior.indicator = PlanningHelpers::GetIndicatorsFromPath(m_Path, state, average_braking_distance ); + currentBehavior.indicator = PlanningHelpers::GetIndicatorsFromPath(m_Path, state, average_braking_distance ); - return currentBehavior; + return currentBehavior; } double DecisionMaker::UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt) { - if(m_TotalOriginalPath.size() ==0 ) return 0; + if(m_TotalOriginalPath.size() ==0 ) return 0; - RelativeInfo info, total_info; - PlanningHelpers::GetRelativeInfo(m_TotalOriginalPath.at(m_iCurrentTotalPathId), state, total_info); - PlanningHelpers::GetRelativeInfo(m_Path, state, info); - double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; - double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalOriginalPath.at(m_iCurrentTotalPathId), total_info, total_info.iBack, average_braking_distance); + RelativeInfo info, total_info; + PlanningHelpers::GetRelativeInfo(m_TotalOriginalPath.at(m_iCurrentTotalPathId), state, total_info); + PlanningHelpers::GetRelativeInfo(m_Path, state, info); + double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; + double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalOriginalPath.at(m_iCurrentTotalPathId), total_info, total_info.iBack, average_braking_distance); - unsigned int point_index = 0; - double critical_long_front_distance = m_CarInfo.length/2.0; + unsigned int point_index = 0; + double critical_long_front_distance = m_CarInfo.length/2.0; - if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE) - { - PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); + if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE) + { + PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); - double e = -beh.stopDistance; - double desiredVelocity = m_pidStopping.getPID(e); + double e = -beh.stopDistance; + double desiredVelocity = m_pidStopping.getPID(e); -// std::cout << "Stopping : e=" << e << ", desiredPID=" << desiredVelocity << ", PID: " << m_pidStopping.ToString() << std::endl; +// std::cout << "Stopping : e=" << e << ", desiredPID=" << desiredVelocity << ", PID: " << m_pidStopping.ToString() << std::endl; - if(desiredVelocity > max_velocity) - desiredVelocity = max_velocity; - else if(desiredVelocity < m_params.minSpeed) - desiredVelocity = 0; + if(desiredVelocity > max_velocity) + desiredVelocity = max_velocity; + else if(desiredVelocity < m_params.minSpeed) + desiredVelocity = 0; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = desiredVelocity; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = desiredVelocity; - return desiredVelocity; - } - else if(beh.state == FOLLOW_STATE) - { + return desiredVelocity; + } + else if(beh.state == FOLLOW_STATE) + { - double deceleration_critical = 0; - double inv_time = 2.0*((beh.followDistance- (critical_long_front_distance+m_params.additionalBrakingDistance))-CurrStatus.speed); - if(inv_time <= 0) - deceleration_critical = m_CarInfo.max_deceleration; - else - deceleration_critical = CurrStatus.speed*CurrStatus.speed/inv_time; + double deceleration_critical = 0; + double inv_time = 2.0*((beh.followDistance- (critical_long_front_distance+m_params.additionalBrakingDistance))-CurrStatus.speed); + if(inv_time <= 0) + deceleration_critical = m_CarInfo.max_deceleration; + else + deceleration_critical = CurrStatus.speed*CurrStatus.speed/inv_time; - if(deceleration_critical > 0) deceleration_critical = -deceleration_critical; - if(deceleration_critical < - m_CarInfo.max_acceleration) deceleration_critical = - m_CarInfo.max_acceleration; + if(deceleration_critical > 0) deceleration_critical = -deceleration_critical; + if(deceleration_critical < - m_CarInfo.max_acceleration) deceleration_critical = - m_CarInfo.max_acceleration; - double desiredVelocity = (deceleration_critical * dt) + CurrStatus.speed; + double desiredVelocity = (deceleration_critical * dt) + CurrStatus.speed; - if(desiredVelocity > m_params.maxSpeed) - desiredVelocity = m_params.maxSpeed; + if(desiredVelocity > m_params.maxSpeed) + desiredVelocity = m_params.maxSpeed; - if((desiredVelocity < 0.1 && desiredVelocity > -0.1) || beh.followDistance <= 0) //use only effective velocities - desiredVelocity = 0; + if((desiredVelocity < 0.1 && desiredVelocity > -0.1) || beh.followDistance <= 0) //use only effective velocities + desiredVelocity = 0; - //std::cout << "Acc: V: " << desiredVelocity << ", Accel: " << deceleration_critical<< std::endl; + //std::cout << "Acc: V: " << desiredVelocity << ", Accel: " << deceleration_critical<< std::endl; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = desiredVelocity; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = desiredVelocity; - return desiredVelocity; + return desiredVelocity; - } - else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) - { - double target_velocity = max_velocity; - bool bSlowBecauseChange=false; - if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory != m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) - { - target_velocity*=0.5; - bSlowBecauseChange = true; - } + } + else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) + { + double target_velocity = max_velocity; + bool bSlowBecauseChange=false; + if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory != m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) + { + target_velocity*=0.5; + bSlowBecauseChange = true; + } - double e = target_velocity - CurrStatus.speed; - double desiredVelocity = m_pidVelocity.getPID(e); + double e = target_velocity - CurrStatus.speed; + double desiredVelocity = m_pidVelocity.getPID(e); - if(desiredVelocity>max_velocity) - desiredVelocity = max_velocity; - else if(desiredVelocity < m_params.minSpeed) - desiredVelocity = 0; + if(desiredVelocity>max_velocity) + desiredVelocity = max_velocity; + else if(desiredVelocity < m_params.minSpeed) + desiredVelocity = 0; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = desiredVelocity; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = desiredVelocity; - //std::cout << "Target Velocity: " << desiredVelocity << ", Change Slowdown: " << bSlowBecauseChange << std::endl; + //std::cout << "Target Velocity: " << desiredVelocity << ", Change Slowdown: " << bSlowBecauseChange << std::endl; - return desiredVelocity; - } - else if(beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) - { - double target_velocity = 0; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = target_velocity; + return desiredVelocity; + } + else if(beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) + { + double target_velocity = 0; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = target_velocity; - return target_velocity; - } - else - { - double target_velocity = 0; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = target_velocity; + return target_velocity; + } + else + { + double target_velocity = 0; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = target_velocity; - return target_velocity; - } + return target_velocity; + } - return max_velocity; + return max_velocity; } PlannerHNS::BehaviorState DecisionMaker::DoOneStep( - const double& dt, - const PlannerHNS::WayPoint currPose, - const PlannerHNS::VehicleState& vehicleState, - const int& goalID, - const std::vector& trafficLight, - const TrajectoryCost& tc, - const bool& bEmergencyStop) + const double& dt, + const PlannerHNS::WayPoint currPose, + const PlannerHNS::VehicleState& vehicleState, + const int& goalID, + const std::vector& trafficLight, + const TrajectoryCost& tc, + const bool& bEmergencyStop) { - PlannerHNS::BehaviorState beh; - state = currPose; - m_TotalPath.clear(); - for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) - { - t_centerTrajectorySmoothed.clear(); - PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_TotalOriginalPath.at(i), state, m_params.horizonDistance , m_params.pathDensity , t_centerTrajectorySmoothed); - m_TotalPath.push_back(t_centerTrajectorySmoothed); - } + PlannerHNS::BehaviorState beh; + state = currPose; + m_TotalPath.clear(); + for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) + { + t_centerTrajectorySmoothed.clear(); + PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_TotalOriginalPath.at(i), state, m_params.horizonDistance , m_params.pathDensity , t_centerTrajectorySmoothed); + m_TotalPath.push_back(t_centerTrajectorySmoothed); + } - if(m_TotalPath.size()==0) return beh; + if(m_TotalPath.size()==0) return beh; - UpdateCurrentLane(m_MaxLaneSearchDistance); + UpdateCurrentLane(m_MaxLaneSearchDistance); - CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); + CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); - beh = GenerateBehaviorState(vehicleState); + beh = GenerateBehaviorState(vehicleState); - beh.bNewPlan = SelectSafeTrajectory(); + beh.bNewPlan = SelectSafeTrajectory(); - beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); + beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); - //std::cout << "Eval_i: " << tc.index << ", Curr_i: " << m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << ", Prev_i: " << m_pCurrentBehaviorState->GetCalcParams()->iPrevSafeTrajectory << std::endl; + //std::cout << "Eval_i: " << tc.index << ", Curr_i: " << m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << ", Prev_i: " << m_pCurrentBehaviorState->GetCalcParams()->iPrevSafeTrajectory << std::endl; - return beh; + return beh; } } /* namespace PlannerHNS */ diff --git a/common/op_planner/src/LocalPlannerH.cpp b/common/op_planner/src/LocalPlannerH.cpp index f09b72418f3..bb6e0afc83c 100755 --- a/common/op_planner/src/LocalPlannerH.cpp +++ b/common/op_planner/src/LocalPlannerH.cpp @@ -18,780 +18,780 @@ namespace PlannerHNS LocalPlannerH::LocalPlannerH() { - m_PrevBrakingWayPoint = 0; - m_iSafeTrajectory = 0; - m_iCurrentTotalPathId = 0; - pLane = 0; - m_CurrentVelocity = m_CurrentVelocityD =0; - m_CurrentSteering = m_CurrentSteeringD =0; - m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; - m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; - m_pCurrentBehaviorState = 0; - m_pGoToGoalState = 0; - m_pStopState= 0; - m_pWaitState= 0; - m_pMissionCompleteState= 0; - m_pAvoidObstacleState = 0; - m_pTrafficLightStopState = 0; - m_pTrafficLightWaitState = 0; - m_pStopSignStopState = 0; - m_pStopSignWaitState = 0; - m_pFollowState = 0; - m_SimulationSteeringDelayFactor = 0.1; - UtilityH::GetTickCount(m_SteerDelayTimer); - m_PredictionTime = 0; - - InitBehaviorStates(); + m_PrevBrakingWayPoint = 0; + m_iSafeTrajectory = 0; + m_iCurrentTotalPathId = 0; + pLane = 0; + m_CurrentVelocity = m_CurrentVelocityD =0; + m_CurrentSteering = m_CurrentSteeringD =0; + m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; + m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; + m_pCurrentBehaviorState = 0; + m_pGoToGoalState = 0; + m_pStopState= 0; + m_pWaitState= 0; + m_pMissionCompleteState= 0; + m_pAvoidObstacleState = 0; + m_pTrafficLightStopState = 0; + m_pTrafficLightWaitState = 0; + m_pStopSignStopState = 0; + m_pStopSignWaitState = 0; + m_pFollowState = 0; + m_SimulationSteeringDelayFactor = 0.1; + UtilityH::GetTickCount(m_SteerDelayTimer); + m_PredictionTime = 0; + + InitBehaviorStates(); } LocalPlannerH::~LocalPlannerH() { - delete m_pStopState; - delete m_pMissionCompleteState ; - delete m_pGoalState ; - delete m_pGoToGoalState ; - delete m_pWaitState ; - delete m_pInitState ; - delete m_pFollowState ; - delete m_pAvoidObstacleState ; - delete m_pTrafficLightStopState; - delete m_pTrafficLightWaitState; - delete m_pStopSignWaitState ; - delete m_pStopSignStopState; + delete m_pStopState; + delete m_pMissionCompleteState ; + delete m_pGoalState ; + delete m_pGoToGoalState ; + delete m_pWaitState ; + delete m_pInitState ; + delete m_pFollowState ; + delete m_pAvoidObstacleState ; + delete m_pTrafficLightStopState; + delete m_pTrafficLightWaitState; + delete m_pStopSignWaitState ; + delete m_pStopSignStopState; } void LocalPlannerH::Init(const ControllerParams& ctrlParams, const PlannerHNS::PlanningParams& params,const CAR_BASIC_INFO& carInfo) - { + { - m_CarInfo = carInfo; - m_ControlParams = ctrlParams; - m_CurrentVelocity = m_CurrentVelocityD =0; - m_CurrentSteering = m_CurrentSteeringD =0; - m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; - m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; - m_params = params; - m_InitialFollowingDistance = m_params.minFollowingDistance; + m_CarInfo = carInfo; + m_ControlParams = ctrlParams; + m_CurrentVelocity = m_CurrentVelocityD =0; + m_CurrentSteering = m_CurrentSteeringD =0; + m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; + m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; + m_params = params; + m_InitialFollowingDistance = m_params.minFollowingDistance; - m_pidVelocity.Init(0.005, 0.005, 0.05); - m_pidVelocity.Setlimit(m_params.maxSpeed, 0); + m_pidVelocity.Init(0.005, 0.005, 0.05); + m_pidVelocity.Setlimit(m_params.maxSpeed, 0); - m_pidStopping.Init(0.1, 0.05, 0.1); - m_pidStopping.Setlimit(m_params.horizonDistance, 0); + m_pidStopping.Init(0.1, 0.05, 0.1); + m_pidStopping.Setlimit(m_params.horizonDistance, 0); - if(m_pCurrentBehaviorState) - m_pCurrentBehaviorState->SetBehaviorsParams(&m_params); + if(m_pCurrentBehaviorState) + m_pCurrentBehaviorState->SetBehaviorsParams(&m_params); - } + } void LocalPlannerH::InitBehaviorStates() { - m_pStopState = new StopState(&m_params, 0, 0); - m_pMissionCompleteState = new MissionAccomplishedState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), 0); - m_pGoalState = new GoalState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pMissionCompleteState); - m_pGoToGoalState = new ForwardState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoalState); - m_pWaitState = new WaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pInitState = new InitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pFollowState = new FollowState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pAvoidObstacleState = new SwerveState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pTrafficLightStopState = new TrafficLightStopState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pTrafficLightWaitState = new TrafficLightWaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pStopSignWaitState = new StopSignWaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); - m_pStopSignStopState = new StopSignStopState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pStopSignWaitState); - - m_pGoToGoalState->InsertNextState(m_pStopState); - m_pGoToGoalState->InsertNextState(m_pWaitState); - m_pGoToGoalState->InsertNextState(m_pFollowState); - m_pGoToGoalState->InsertNextState(m_pAvoidObstacleState); - m_pGoToGoalState->InsertNextState(m_pTrafficLightStopState); - m_pGoToGoalState->InsertNextState(m_pStopSignStopState); - - m_pStopState->InsertNextState(m_pGoToGoalState); - - m_pTrafficLightStopState->InsertNextState(m_pTrafficLightWaitState); - m_pTrafficLightWaitState->InsertNextState(m_pTrafficLightStopState); - - m_pStopSignWaitState->decisionMakingTime = 5.0; - m_pStopSignWaitState->InsertNextState(m_pStopSignStopState); - - m_pFollowState->InsertNextState(m_pStopState); - m_pFollowState->InsertNextState(m_pTrafficLightStopState); - m_pFollowState->InsertNextState(m_pStopSignStopState); - - m_pAvoidObstacleState->decisionMakingTime = 0.1; - - m_pCurrentBehaviorState = m_pInitState; + m_pStopState = new StopState(&m_params, 0, 0); + m_pMissionCompleteState = new MissionAccomplishedState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), 0); + m_pGoalState = new GoalState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pMissionCompleteState); + m_pGoToGoalState = new ForwardState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoalState); + m_pWaitState = new WaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pInitState = new InitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pFollowState = new FollowState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pAvoidObstacleState = new SwerveState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pTrafficLightStopState = new TrafficLightStopState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pTrafficLightWaitState = new TrafficLightWaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pStopSignWaitState = new StopSignWaitState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState); + m_pStopSignStopState = new StopSignStopState(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pStopSignWaitState); + + m_pGoToGoalState->InsertNextState(m_pStopState); + m_pGoToGoalState->InsertNextState(m_pWaitState); + m_pGoToGoalState->InsertNextState(m_pFollowState); + m_pGoToGoalState->InsertNextState(m_pAvoidObstacleState); + m_pGoToGoalState->InsertNextState(m_pTrafficLightStopState); + m_pGoToGoalState->InsertNextState(m_pStopSignStopState); + + m_pStopState->InsertNextState(m_pGoToGoalState); + + m_pTrafficLightStopState->InsertNextState(m_pTrafficLightWaitState); + m_pTrafficLightWaitState->InsertNextState(m_pTrafficLightStopState); + + m_pStopSignWaitState->decisionMakingTime = 5.0; + m_pStopSignWaitState->InsertNextState(m_pStopSignStopState); + + m_pFollowState->InsertNextState(m_pStopState); + m_pFollowState->InsertNextState(m_pTrafficLightStopState); + m_pFollowState->InsertNextState(m_pStopSignStopState); + + m_pAvoidObstacleState->decisionMakingTime = 0.1; + + m_pCurrentBehaviorState = m_pInitState; } void LocalPlannerH::InitPolygons() { - double l2 = m_CarInfo.length/2.0; - double w2 = m_CarInfo.width/2.0; + double l2 = m_CarInfo.length/2.0; + double w2 = m_CarInfo.width/2.0; - m_CarShapePolygon.push_back(GPSPoint(-w2, -l2, 0,0)); - m_CarShapePolygon.push_back(GPSPoint(w2, -l2, 0,0)); - m_CarShapePolygon.push_back(GPSPoint(w2, l2, 0,0)); - m_CarShapePolygon.push_back(GPSPoint(-w2, l2, 0,0)); + m_CarShapePolygon.push_back(GPSPoint(-w2, -l2, 0,0)); + m_CarShapePolygon.push_back(GPSPoint(w2, -l2, 0,0)); + m_CarShapePolygon.push_back(GPSPoint(w2, l2, 0,0)); + m_CarShapePolygon.push_back(GPSPoint(-w2, l2, 0,0)); } void LocalPlannerH::ReInitializePlanner(const WayPoint& start_pose) { - m_pidVelocity.Init(0.005, 0.005, 0.05); - m_pidVelocity.Setlimit(m_params.maxSpeed, 0); - - m_pidStopping.Init(0.1, 0.05, 0.1); - m_pidStopping.Setlimit(m_params.horizonDistance, 0); - - m_PrevBrakingWayPoint = 0; - m_iSafeTrajectory = 0; - m_iCurrentTotalPathId = 0; - m_CurrentVelocity = m_CurrentVelocityD =0; - m_CurrentSteering = m_CurrentSteeringD =0; - m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; - m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; - - m_pCurrentBehaviorState = m_pFollowState; - m_TotalPath.clear(); - m_OriginalLocalPath.clear(); - m_TotalOriginalPath.clear(); - m_Path.clear(); - m_RollOuts.clear(); - m_pCurrentBehaviorState->m_Behavior = PlannerHNS::FORWARD_STATE; - m_pCurrentBehaviorState->GetCalcParams()->bOutsideControl = 1; - FirstLocalizeMe(start_pose); - LocalizeMe(0); + m_pidVelocity.Init(0.005, 0.005, 0.05); + m_pidVelocity.Setlimit(m_params.maxSpeed, 0); + + m_pidStopping.Init(0.1, 0.05, 0.1); + m_pidStopping.Setlimit(m_params.horizonDistance, 0); + + m_PrevBrakingWayPoint = 0; + m_iSafeTrajectory = 0; + m_iCurrentTotalPathId = 0; + m_CurrentVelocity = m_CurrentVelocityD =0; + m_CurrentSteering = m_CurrentSteeringD =0; + m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; + m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; + + m_pCurrentBehaviorState = m_pFollowState; + m_TotalPath.clear(); + m_OriginalLocalPath.clear(); + m_TotalOriginalPath.clear(); + m_Path.clear(); + m_RollOuts.clear(); + m_pCurrentBehaviorState->m_Behavior = PlannerHNS::FORWARD_STATE; + m_pCurrentBehaviorState->GetCalcParams()->bOutsideControl = 1; + FirstLocalizeMe(start_pose); + LocalizeMe(0); } void LocalPlannerH::FirstLocalizeMe(const WayPoint& initCarPos) { - pLane = initCarPos.pLane; - state = initCarPos; - m_OdometryState.pos.a = initCarPos.pos.a; - m_OdometryState.pos.x = initCarPos.pos.x + (m_CarInfo.wheel_base/2.0 * cos(initCarPos.pos.a)); - m_OdometryState.pos.y = initCarPos.pos.y + (m_CarInfo.wheel_base/2.0 * sin(initCarPos.pos.a)); + pLane = initCarPos.pLane; + state = initCarPos; + m_OdometryState.pos.a = initCarPos.pos.a; + m_OdometryState.pos.x = initCarPos.pos.x + (m_CarInfo.wheel_base/2.0 * cos(initCarPos.pos.a)); + m_OdometryState.pos.y = initCarPos.pos.y + (m_CarInfo.wheel_base/2.0 * sin(initCarPos.pos.a)); } void LocalPlannerH::LocalizeMe(const double& dt) { - //calculate the new x, y , - WayPoint currPose = state; - - if(m_CurrentShift == SHIFT_POS_DD) - { - m_OdometryState.pos.x += m_CurrentVelocity * dt * cos(currPose.pos.a); - m_OdometryState.pos.y += m_CurrentVelocity * dt * sin(currPose.pos.a); - m_OdometryState.pos.a += m_CurrentVelocity * dt * tan(m_CurrentSteering) / m_CarInfo.wheel_base; - - } - else if(m_CurrentShift == SHIFT_POS_RR ) - { - m_OdometryState.pos.x += -m_CurrentVelocity * dt * cos(currPose.pos.a); - m_OdometryState.pos.y += -m_CurrentVelocity * dt * sin(currPose.pos.a); - m_OdometryState.pos.a += -m_CurrentVelocity * dt * tan(m_CurrentSteering); - } - - m_OdometryState.pos.a = atan2(sin(m_OdometryState.pos.a), cos(m_OdometryState.pos.a)); - m_OdometryState.pos.a = UtilityH::FixNegativeAngle(m_OdometryState.pos.a); - - state.pos.a = m_OdometryState.pos.a; - state.pos.x = m_OdometryState.pos.x - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base) * cos (m_OdometryState.pos.a)); - state.pos.y = m_OdometryState.pos.y - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base/2.0) * sin (m_OdometryState.pos.a)); + //calculate the new x, y , + WayPoint currPose = state; + + if(m_CurrentShift == SHIFT_POS_DD) + { + m_OdometryState.pos.x += m_CurrentVelocity * dt * cos(currPose.pos.a); + m_OdometryState.pos.y += m_CurrentVelocity * dt * sin(currPose.pos.a); + m_OdometryState.pos.a += m_CurrentVelocity * dt * tan(m_CurrentSteering) / m_CarInfo.wheel_base; + + } + else if(m_CurrentShift == SHIFT_POS_RR ) + { + m_OdometryState.pos.x += -m_CurrentVelocity * dt * cos(currPose.pos.a); + m_OdometryState.pos.y += -m_CurrentVelocity * dt * sin(currPose.pos.a); + m_OdometryState.pos.a += -m_CurrentVelocity * dt * tan(m_CurrentSteering); + } + + m_OdometryState.pos.a = atan2(sin(m_OdometryState.pos.a), cos(m_OdometryState.pos.a)); + m_OdometryState.pos.a = UtilityH::FixNegativeAngle(m_OdometryState.pos.a); + + state.pos.a = m_OdometryState.pos.a; + state.pos.x = m_OdometryState.pos.x - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base) * cos (m_OdometryState.pos.a)); + state.pos.y = m_OdometryState.pos.y - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base/2.0) * sin (m_OdometryState.pos.a)); } void LocalPlannerH::UpdateState(const PlannerHNS::VehicleState& state, const bool& bUseDelay) { - if(!bUseDelay) - { - m_CurrentSteering = m_CurrentSteeringD; - // std::cout << " No Delay " << std::endl; - } - else - { - double currSteerDeg = RAD2DEG * m_CurrentSteering; - double desiredSteerDeg = RAD2DEG * m_CurrentSteeringD; - - double mFact = UtilityH::GetMomentumScaleFactor(state.speed); - double diff = desiredSteerDeg - currSteerDeg; - double diffSign = UtilityH::GetSign(diff); - double inc = 1.0*diffSign; - if(fabs(diff) < 1.0 ) - inc = diff; - -// std::cout << "Delay: " << m_SimulationSteeringDelayFactor -// << ", Fact: " << mFact -// << ", Diff: " << diff -// << ", inc: " << inc << std::endl; - if(UtilityH::GetTimeDiffNow(m_SteerDelayTimer) > m_SimulationSteeringDelayFactor*mFact) - { - UtilityH::GetTickCount(m_SteerDelayTimer); - currSteerDeg += inc; - } - - m_CurrentSteering = DEG2RAD * currSteerDeg; - } - - m_CurrentShift = m_CurrentShiftD; - m_CurrentVelocity = m_CurrentVelocityD; + if(!bUseDelay) + { + m_CurrentSteering = m_CurrentSteeringD; + // std::cout << " No Delay " << std::endl; + } + else + { + double currSteerDeg = RAD2DEG * m_CurrentSteering; + double desiredSteerDeg = RAD2DEG * m_CurrentSteeringD; + + double mFact = UtilityH::GetMomentumScaleFactor(state.speed); + double diff = desiredSteerDeg - currSteerDeg; + double diffSign = UtilityH::GetSign(diff); + double inc = 1.0*diffSign; + if(fabs(diff) < 1.0 ) + inc = diff; + +// std::cout << "Delay: " << m_SimulationSteeringDelayFactor +// << ", Fact: " << mFact +// << ", Diff: " << diff +// << ", inc: " << inc << std::endl; + if(UtilityH::GetTimeDiffNow(m_SteerDelayTimer) > m_SimulationSteeringDelayFactor*mFact) + { + UtilityH::GetTickCount(m_SteerDelayTimer); + currSteerDeg += inc; + } + + m_CurrentSteering = DEG2RAD * currSteerDeg; + } + + m_CurrentShift = m_CurrentShiftD; + m_CurrentVelocity = m_CurrentVelocityD; } void LocalPlannerH::AddAndTransformContourPoints(const PlannerHNS::DetectedObject& obj, std::vector& contourPoints) { - contourPoints.clear(); - WayPoint p, p_center = obj.center; - p_center.pos.a += M_PI_2; - for(unsigned int i=0; i< obj.contour.size(); i++) - { - p.pos = obj.contour.at(i); - //TransformPoint(p_center, p.pos); - contourPoints.push_back(p); - } - - contourPoints.push_back(obj.center); + contourPoints.clear(); + WayPoint p, p_center = obj.center; + p_center.pos.a += M_PI_2; + for(unsigned int i=0; i< obj.contour.size(); i++) + { + p.pos = obj.contour.at(i); + //TransformPoint(p_center, p.pos); + contourPoints.push_back(p); + } + + contourPoints.push_back(obj.center); } void LocalPlannerH::TransformPoint(const PlannerHNS::WayPoint& refPose, PlannerHNS::GPSPoint& p) { - PlannerHNS::Mat3 rotationMat(refPose.pos.a); - PlannerHNS::Mat3 translationMat(refPose.pos.x, refPose.pos.y); - p = rotationMat*p; - p = translationMat*p; + PlannerHNS::Mat3 rotationMat(refPose.pos.a); + PlannerHNS::Mat3 translationMat(refPose.pos.x, refPose.pos.y); + p = rotationMat*p; + p = translationMat*p; } bool LocalPlannerH::GetNextTrafficLight(const int& prevTrafficLightId, const std::vector& trafficLights, PlannerHNS::TrafficLight& trafficL) { - for(unsigned int i = 0; i < trafficLights.size(); i++) - { - double d = hypot(trafficLights.at(i).pos.y - state.pos.y, trafficLights.at(i).pos.x - state.pos.x); - if(d <= trafficLights.at(i).stoppingDistance) - { - double a_diff = UtilityH::AngleBetweenTwoAnglesPositive(UtilityH::FixNegativeAngle(trafficLights.at(i).pos.a) , UtilityH::FixNegativeAngle(state.pos.a)); - - if(a_diff < M_PI_2 && trafficLights.at(i).id != prevTrafficLightId) - { - //std::cout << "Detected Light, ID = " << trafficLights.at(i).id << ", Distance = " << d << ", Angle = " << trafficLights.at(i).pos.a*RAD2DEG << ", Car Heading = " << state.pos.a*RAD2DEG << ", Diff = " << a_diff*RAD2DEG << std::endl; - trafficL = trafficLights.at(i); - return true; - } - } - } - - return false; + for(unsigned int i = 0; i < trafficLights.size(); i++) + { + double d = hypot(trafficLights.at(i).pos.y - state.pos.y, trafficLights.at(i).pos.x - state.pos.x); + if(d <= trafficLights.at(i).stoppingDistance) + { + double a_diff = UtilityH::AngleBetweenTwoAnglesPositive(UtilityH::FixNegativeAngle(trafficLights.at(i).pos.a) , UtilityH::FixNegativeAngle(state.pos.a)); + + if(a_diff < M_PI_2 && trafficLights.at(i).id != prevTrafficLightId) + { + //std::cout << "Detected Light, ID = " << trafficLights.at(i).id << ", Distance = " << d << ", Angle = " << trafficLights.at(i).pos.a*RAD2DEG << ", Car Heading = " << state.pos.a*RAD2DEG << ", Diff = " << a_diff*RAD2DEG << std::endl; + trafficL = trafficLights.at(i); + return true; + } + } + } + + return false; } void LocalPlannerH::CalculateImportantParameterForDecisionMaking(const PlannerHNS::VehicleState& car_state, - const int& goalID, const bool& bEmergencyStop, const vector& detectedLights, - const TrajectoryCost& bestTrajectory) + const int& goalID, const bool& bEmergencyStop, const vector& detectedLights, + const TrajectoryCost& bestTrajectory) { - PreCalculatedConditions* pValues = m_pCurrentBehaviorState->GetCalcParams(); + PreCalculatedConditions* pValues = m_pCurrentBehaviorState->GetCalcParams(); - double critical_long_front_distance = m_CarInfo.wheel_base/2.0 + m_CarInfo.length/2.0 + m_params.verticalSafetyDistance; + double critical_long_front_distance = m_CarInfo.wheel_base/2.0 + m_CarInfo.length/2.0 + m_params.verticalSafetyDistance; - pValues->minStoppingDistance = -pow(car_state.speed, 2)/(m_CarInfo.max_deceleration); + pValues->minStoppingDistance = -pow(car_state.speed, 2)/(m_CarInfo.max_deceleration); - pValues->iCentralTrajectory = m_pCurrentBehaviorState->m_pParams->rollOutNumber/2; + pValues->iCentralTrajectory = m_pCurrentBehaviorState->m_pParams->rollOutNumber/2; - if(pValues->iCurrSafeTrajectory < 0) - pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; + if(pValues->iCurrSafeTrajectory < 0) + pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; - if(pValues->iPrevSafeTrajectory < 0) - pValues->iPrevSafeTrajectory = pValues->iCentralTrajectory; + if(pValues->iPrevSafeTrajectory < 0) + pValues->iPrevSafeTrajectory = pValues->iCentralTrajectory; - pValues->stoppingDistances.clear(); - pValues->currentVelocity = car_state.speed; - pValues->bTrafficIsRed = false; - pValues->currentTrafficLightID = -1; - pValues->bRePlan = false; - pValues->bFullyBlock = false; + pValues->stoppingDistances.clear(); + pValues->currentVelocity = car_state.speed; + pValues->bTrafficIsRed = false; + pValues->currentTrafficLightID = -1; + pValues->bRePlan = false; + pValues->bFullyBlock = false; - pValues->distanceToNext = bestTrajectory.closest_obj_distance; - pValues->velocityOfNext = bestTrajectory.closest_obj_velocity; + pValues->distanceToNext = bestTrajectory.closest_obj_distance; + pValues->velocityOfNext = bestTrajectory.closest_obj_velocity; - if(pValues->distanceToNext > m_params.minDistanceToAvoid) - pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; - else if(bestTrajectory.index>=0) - pValues->iCurrSafeTrajectory = bestTrajectory.index; + if(pValues->distanceToNext > m_params.minDistanceToAvoid) + pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory; + else if(bestTrajectory.index>=0) + pValues->iCurrSafeTrajectory = bestTrajectory.index; - pValues->bFullyBlock = bestTrajectory.bBlocked; + pValues->bFullyBlock = bestTrajectory.bBlocked; - if(bestTrajectory.lane_index >=0) - pValues->iCurrSafeLane = bestTrajectory.lane_index; - else - { - PlannerHNS::RelativeInfo info; - PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_TotalPath, state, m_params.rollOutDensity*m_params.rollOutNumber/2.0 + 0.1, info); - pValues->iCurrSafeLane = info.iGlobalPath; - } + if(bestTrajectory.lane_index >=0) + pValues->iCurrSafeLane = bestTrajectory.lane_index; + else + { + PlannerHNS::RelativeInfo info; + PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_TotalPath, state, m_params.rollOutDensity*m_params.rollOutNumber/2.0 + 0.1, info); + pValues->iCurrSafeLane = info.iGlobalPath; + } - if(NoWayTest(pValues->minStoppingDistance, pValues->iCurrSafeLane)) - pValues->currentGoalID = -1; - else - pValues->currentGoalID = goalID; + if(NoWayTest(pValues->minStoppingDistance, pValues->iCurrSafeLane)) + pValues->currentGoalID = -1; + else + pValues->currentGoalID = goalID; - m_iSafeTrajectory = pValues->iCurrSafeTrajectory; - m_iCurrentTotalPathId = pValues->iCurrSafeLane; + m_iSafeTrajectory = pValues->iCurrSafeTrajectory; + m_iCurrentTotalPathId = pValues->iCurrSafeLane; - int stopLineID = -1; - int stopSignID = -1; - int trafficLightID = -1; - double distanceToClosestStopLine = 0; - bool bGreenTrafficLight = true; + int stopLineID = -1; + int stopSignID = -1; + int trafficLightID = -1; + double distanceToClosestStopLine = 0; + bool bGreenTrafficLight = true; - if(m_TotalPath.size()>0) - distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_TotalPath.at(pValues->iCurrSafeLane), state, 0, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; + if(m_TotalPath.size()>0) + distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_TotalPath.at(pValues->iCurrSafeLane), state, 0, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; - if(distanceToClosestStopLine > 0 && distanceToClosestStopLine < pValues->minStoppingDistance) - { - if(m_pCurrentBehaviorState->m_pParams->enableTrafficLightBehavior) - { - pValues->currentTrafficLightID = trafficLightID; - //cout << "Detected Traffic Light: " << trafficLightID << endl; - for(unsigned int i=0; i< detectedLights.size(); i++) - { - if(detectedLights.at(i).id == trafficLightID) - bGreenTrafficLight = (detectedLights.at(i).lightState == GREEN_LIGHT); - } - } + if(distanceToClosestStopLine > 0 && distanceToClosestStopLine < pValues->minStoppingDistance) + { + if(m_pCurrentBehaviorState->m_pParams->enableTrafficLightBehavior) + { + pValues->currentTrafficLightID = trafficLightID; + //cout << "Detected Traffic Light: " << trafficLightID << endl; + for(unsigned int i=0; i< detectedLights.size(); i++) + { + if(detectedLights.at(i).id == trafficLightID) + bGreenTrafficLight = (detectedLights.at(i).lightState == GREEN_LIGHT); + } + } - if(m_pCurrentBehaviorState->m_pParams->enableStopSignBehavior) - pValues->currentStopSignID = stopSignID; + if(m_pCurrentBehaviorState->m_pParams->enableStopSignBehavior) + pValues->currentStopSignID = stopSignID; - pValues->stoppingDistances.push_back(distanceToClosestStopLine); - //std::cout << "LP => D: " << pValues->distanceToStop() << ", PrevSignID: " << pValues->prevTrafficLightID << ", CurrSignID: " << pValues->currentTrafficLightID << ", Green: " << bGreenTrafficLight << endl; - } + pValues->stoppingDistances.push_back(distanceToClosestStopLine); + //std::cout << "LP => D: " << pValues->distanceToStop() << ", PrevSignID: " << pValues->prevTrafficLightID << ", CurrSignID: " << pValues->currentTrafficLightID << ", Green: " << bGreenTrafficLight << endl; + } -// cout << "Distance To Closest: " << distanceToClosestStopLine << ", Stop LineID: " << stopLineID << ", Stop SignID: " << stopSignID << ", TFID: " << trafficLightID << endl; +// cout << "Distance To Closest: " << distanceToClosestStopLine << ", Stop LineID: " << stopLineID << ", Stop SignID: " << stopSignID << ", TFID: " << trafficLightID << endl; - pValues->bTrafficIsRed = !bGreenTrafficLight; + pValues->bTrafficIsRed = !bGreenTrafficLight; - if(bEmergencyStop) - { - pValues->bFullyBlock = true; - pValues->distanceToNext = 1; - pValues->velocityOfNext = 0; - } - //cout << "Distances: " << pValues->stoppingDistances.size() << ", Distance To Stop : " << pValues->distanceToStop << endl; + if(bEmergencyStop) + { + pValues->bFullyBlock = true; + pValues->distanceToNext = 1; + pValues->velocityOfNext = 0; + } + //cout << "Distances: " << pValues->stoppingDistances.size() << ", Distance To Stop : " << pValues->distanceToStop << endl; } void LocalPlannerH::UpdateCurrentLane(PlannerHNS::RoadNetwork& map, const double& search_distance) { - PlannerHNS::Lane* pMapLane = 0; - PlannerHNS::Lane* pPathLane = 0; - pPathLane = MappingHelpers::GetLaneFromPath(state, m_Path); - if(!pPathLane) - { - cout << "Performance Alert: Can't Find Lane Information in Global Path, Searching the Map :( " << endl; - pMapLane = MappingHelpers::GetClosestLaneFromMap(state, map, search_distance); - - } - - if(pPathLane) - pLane = pPathLane; - else if(pMapLane) - pLane = pMapLane; - else - pLane = 0; + PlannerHNS::Lane* pMapLane = 0; + PlannerHNS::Lane* pPathLane = 0; + pPathLane = MappingHelpers::GetLaneFromPath(state, m_Path); + if(!pPathLane) + { + cout << "Performance Alert: Can't Find Lane Information in Global Path, Searching the Map :( " << endl; + pMapLane = MappingHelpers::GetClosestLaneFromMap(state, map, search_distance); + + } + + if(pPathLane) + pLane = pPathLane; + else if(pMapLane) + pLane = pMapLane; + else + pLane = 0; } void LocalPlannerH::SimulateOdoPosition(const double& dt, const PlannerHNS::VehicleState& vehicleState) { - SetSimulatedTargetOdometryReadings(vehicleState.speed, vehicleState.steer, vehicleState.shift); - UpdateState(vehicleState, false); - LocalizeMe(dt); + SetSimulatedTargetOdometryReadings(vehicleState.speed, vehicleState.steer, vehicleState.shift); + UpdateState(vehicleState, false); + LocalizeMe(dt); } bool LocalPlannerH::NoWayTest(const double& min_distance, const int& iGlobalPathIndex) { - if(m_TotalPath.size()==0) return false; + if(m_TotalPath.size()==0) return false; - PlannerHNS::RelativeInfo info; - PlanningHelpers::GetRelativeInfo(m_TotalPath.at(iGlobalPathIndex), state, info); + PlannerHNS::RelativeInfo info; + PlanningHelpers::GetRelativeInfo(m_TotalPath.at(iGlobalPathIndex), state, info); - double d = 0; - for(unsigned int i = info.iFront; i < m_TotalPath.at(iGlobalPathIndex).size()-1; i++) - { - d+= hypot(m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.y - m_TotalPath.at(iGlobalPathIndex).at(i).pos.y, m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.x - m_TotalPath.at(iGlobalPathIndex).at(i).pos.x); - if(d > min_distance) - return false; - } + double d = 0; + for(unsigned int i = info.iFront; i < m_TotalPath.at(iGlobalPathIndex).size()-1; i++) + { + d+= hypot(m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.y - m_TotalPath.at(iGlobalPathIndex).at(i).pos.y, m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.x - m_TotalPath.at(iGlobalPathIndex).at(i).pos.x); + if(d > min_distance) + return false; + } - return true; + return true; } bool LocalPlannerH::SelectSafeTrajectoryAndSpeedProfile(const PlannerHNS::VehicleState& vehicleState) { - PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); - - bool bNewTrajectory = false; - - if(m_TotalPath.size()>0) - { - int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); - int index_limit = 0;//m_Path.size() - 20; - if(index_limit<=0) - index_limit = m_Path.size()/2.0; - if(m_RollOuts.size() == 0 - || currIndex > index_limit - || m_pCurrentBehaviorState->GetCalcParams()->bRePlan - || m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath - || m_pCurrentBehaviorState->m_Behavior == OBSTACLE_AVOIDANCE_STATE) - { - PlannerHNS::PlannerH planner; - planner.GenerateRunoffTrajectory(m_TotalPath, state, - m_pCurrentBehaviorState->m_pParams->enableLaneChange, - vehicleState.speed, - m_pCurrentBehaviorState->m_pParams->microPlanDistance, - m_pCurrentBehaviorState->m_pParams->maxSpeed, - m_pCurrentBehaviorState->m_pParams->minSpeed, - m_pCurrentBehaviorState->m_pParams->carTipMargin, - m_pCurrentBehaviorState->m_pParams->rollInMargin, - m_pCurrentBehaviorState->m_pParams->rollInSpeedFactor, - m_pCurrentBehaviorState->m_pParams->pathDensity, - m_pCurrentBehaviorState->m_pParams->rollOutDensity, - m_pCurrentBehaviorState->m_pParams->rollOutNumber, - m_pCurrentBehaviorState->m_pParams->smoothingDataWeight, - m_pCurrentBehaviorState->m_pParams->smoothingSmoothWeight, - m_pCurrentBehaviorState->m_pParams->smoothingToleranceError, - m_pCurrentBehaviorState->m_pParams->speedProfileFactor, - m_pCurrentBehaviorState->m_pParams->enableHeadingSmoothing, - preCalcPrams->iCurrSafeLane , preCalcPrams->iCurrSafeTrajectory, - m_RollOuts, m_SampledPoints); - - m_pCurrentBehaviorState->GetCalcParams()->bRePlan = false; - m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath = false; - - if(m_pCurrentBehaviorState->m_Behavior == OBSTACLE_AVOIDANCE_STATE) - preCalcPrams->iPrevSafeTrajectory = preCalcPrams->iCurrSafeTrajectory; - else - preCalcPrams->iPrevSafeTrajectory = preCalcPrams->iCentralTrajectory; - - preCalcPrams->iPrevSafeLane = preCalcPrams->iCurrSafeLane; - - if(preCalcPrams->iPrevSafeLane >= 0 - && preCalcPrams->iPrevSafeLane < (int)m_RollOuts.size() - && preCalcPrams->iPrevSafeTrajectory >= 0 - && preCalcPrams->iPrevSafeTrajectory < (int)m_RollOuts.at(preCalcPrams->iPrevSafeLane).size()) - { - m_Path = m_RollOuts.at(preCalcPrams->iPrevSafeLane).at(preCalcPrams->iPrevSafeTrajectory); - m_OriginalLocalPath = m_TotalPath.at(m_iCurrentTotalPathId); - bNewTrajectory = true; - } - } - } - - return bNewTrajectory; + PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); + + bool bNewTrajectory = false; + + if(m_TotalPath.size()>0) + { + int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); + int index_limit = 0;//m_Path.size() - 20; + if(index_limit<=0) + index_limit = m_Path.size()/2.0; + if(m_RollOuts.size() == 0 + || currIndex > index_limit + || m_pCurrentBehaviorState->GetCalcParams()->bRePlan + || m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath + || m_pCurrentBehaviorState->m_Behavior == OBSTACLE_AVOIDANCE_STATE) + { + PlannerHNS::PlannerH planner; + planner.GenerateRunoffTrajectory(m_TotalPath, state, + m_pCurrentBehaviorState->m_pParams->enableLaneChange, + vehicleState.speed, + m_pCurrentBehaviorState->m_pParams->microPlanDistance, + m_pCurrentBehaviorState->m_pParams->maxSpeed, + m_pCurrentBehaviorState->m_pParams->minSpeed, + m_pCurrentBehaviorState->m_pParams->carTipMargin, + m_pCurrentBehaviorState->m_pParams->rollInMargin, + m_pCurrentBehaviorState->m_pParams->rollInSpeedFactor, + m_pCurrentBehaviorState->m_pParams->pathDensity, + m_pCurrentBehaviorState->m_pParams->rollOutDensity, + m_pCurrentBehaviorState->m_pParams->rollOutNumber, + m_pCurrentBehaviorState->m_pParams->smoothingDataWeight, + m_pCurrentBehaviorState->m_pParams->smoothingSmoothWeight, + m_pCurrentBehaviorState->m_pParams->smoothingToleranceError, + m_pCurrentBehaviorState->m_pParams->speedProfileFactor, + m_pCurrentBehaviorState->m_pParams->enableHeadingSmoothing, + preCalcPrams->iCurrSafeLane , preCalcPrams->iCurrSafeTrajectory, + m_RollOuts, m_SampledPoints); + + m_pCurrentBehaviorState->GetCalcParams()->bRePlan = false; + m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath = false; + + if(m_pCurrentBehaviorState->m_Behavior == OBSTACLE_AVOIDANCE_STATE) + preCalcPrams->iPrevSafeTrajectory = preCalcPrams->iCurrSafeTrajectory; + else + preCalcPrams->iPrevSafeTrajectory = preCalcPrams->iCentralTrajectory; + + preCalcPrams->iPrevSafeLane = preCalcPrams->iCurrSafeLane; + + if(preCalcPrams->iPrevSafeLane >= 0 + && preCalcPrams->iPrevSafeLane < (int)m_RollOuts.size() + && preCalcPrams->iPrevSafeTrajectory >= 0 + && preCalcPrams->iPrevSafeTrajectory < (int)m_RollOuts.at(preCalcPrams->iPrevSafeLane).size()) + { + m_Path = m_RollOuts.at(preCalcPrams->iPrevSafeLane).at(preCalcPrams->iPrevSafeTrajectory); + m_OriginalLocalPath = m_TotalPath.at(m_iCurrentTotalPathId); + bNewTrajectory = true; + } + } + } + + return bNewTrajectory; } PlannerHNS::BehaviorState LocalPlannerH::GenerateBehaviorState(const PlannerHNS::VehicleState& vehicleState) { - PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); + PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); - m_pCurrentBehaviorState = m_pCurrentBehaviorState->GetNextState(); - if(m_pCurrentBehaviorState==0) - m_pCurrentBehaviorState = m_pInitState; + m_pCurrentBehaviorState = m_pCurrentBehaviorState->GetNextState(); + if(m_pCurrentBehaviorState==0) + m_pCurrentBehaviorState = m_pInitState; - PlannerHNS::BehaviorState currentBehavior; + PlannerHNS::BehaviorState currentBehavior; - currentBehavior.state = m_pCurrentBehaviorState->m_Behavior; - currentBehavior.followDistance = preCalcPrams->distanceToNext; + currentBehavior.state = m_pCurrentBehaviorState->m_Behavior; + currentBehavior.followDistance = preCalcPrams->distanceToNext; - currentBehavior.minVelocity = 0; - currentBehavior.stopDistance = preCalcPrams->distanceToStop(); - currentBehavior.followVelocity = preCalcPrams->velocityOfNext; + currentBehavior.minVelocity = 0; + currentBehavior.stopDistance = preCalcPrams->distanceToStop(); + currentBehavior.followVelocity = preCalcPrams->velocityOfNext; - double average_braking_distance = -pow(vehicleState.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; + double average_braking_distance = -pow(vehicleState.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; - if(average_braking_distance < 15) - average_braking_distance = 15; + if(average_braking_distance < 15) + average_braking_distance = 15; - currentBehavior.indicator = PlanningHelpers::GetIndicatorsFromPath(m_Path, state, average_braking_distance ); + currentBehavior.indicator = PlanningHelpers::GetIndicatorsFromPath(m_Path, state, average_braking_distance ); - return currentBehavior; + return currentBehavior; } // double LocalPlannerH::UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt) // { -// RelativeInfo info, total_info; -// PlanningHelpers::GetRelativeInfo(m_TotalPath.at(m_iCurrentTotalPathId), state, total_info); -// PlanningHelpers::GetRelativeInfo(m_Path, state, info); -// double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration); -// double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalPath.at(m_iCurrentTotalPathId), total_info, average_braking_distance); +// RelativeInfo info, total_info; +// PlanningHelpers::GetRelativeInfo(m_TotalPath.at(m_iCurrentTotalPathId), state, total_info); +// PlanningHelpers::GetRelativeInfo(m_Path, state, info); +// double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration); +// double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalPath.at(m_iCurrentTotalPathId), total_info, average_braking_distance); // -// unsigned int point_index = 0; -// double critical_long_front_distance = 2.0; +// unsigned int point_index = 0; +// double critical_long_front_distance = 2.0; // -// if(m_Path.size() <= 5) -// { -// double target_velocity = 0; -// for(unsigned int i = 0; i < m_Path.size(); i++) -// m_Path.at(i).v = target_velocity; -// } -// else if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE || beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) -// { -// PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); +// if(m_Path.size() <= 5) +// { +// double target_velocity = 0; +// for(unsigned int i = 0; i < m_Path.size(); i++) +// m_Path.at(i).v = target_velocity; +// } +// else if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE || beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) +// { +// PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); // -// double inc = CurrStatus.speed; -// int iRange = point_index - info.iBack; -// if(iRange > 0) -// inc = inc / (double)iRange; -// else -// inc = 0; +// double inc = CurrStatus.speed; +// int iRange = point_index - info.iBack; +// if(iRange > 0) +// inc = inc / (double)iRange; +// else +// inc = 0; // -// double target_velocity = CurrStatus.speed - inc; -// for(unsigned int i = info.iBack; i < point_index; i++) -// { -// if(i < m_Path.size() && i >= 0) -// m_Path.at(i).v = target_velocity; -// target_velocity -= inc; -// } -// } -// else if(beh.state == FOLLOW_STATE) -// { -// double targe_acceleration = -pow(CurrStatus.speed, 2)/(2.0*(beh.followDistance - critical_long_front_distance)); -// if(targe_acceleration <= 0 && targe_acceleration > m_CarInfo.max_deceleration/2.0) -// { -// double target_velocity = (targe_acceleration * dt) + CurrStatus.speed; -// for(unsigned int i = 0; i < m_Path.size(); i++) -// { -// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) -// m_Path.at(i).v = target_velocity; -// else -// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; -// } +// double target_velocity = CurrStatus.speed - inc; +// for(unsigned int i = info.iBack; i < point_index; i++) +// { +// if(i < m_Path.size() && i >= 0) +// m_Path.at(i).v = target_velocity; +// target_velocity -= inc; +// } +// } +// else if(beh.state == FOLLOW_STATE) +// { +// double targe_acceleration = -pow(CurrStatus.speed, 2)/(2.0*(beh.followDistance - critical_long_front_distance)); +// if(targe_acceleration <= 0 && targe_acceleration > m_CarInfo.max_deceleration/2.0) +// { +// double target_velocity = (targe_acceleration * dt) + CurrStatus.speed; +// for(unsigned int i = 0; i < m_Path.size(); i++) +// { +// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) +// m_Path.at(i).v = target_velocity; +// else +// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; +// } // -// //cout << "Accelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Acceleration: " << targe_acceleration << endl; -// } -// else -// { -// WayPoint pursuite_point = PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.followDistance - critical_long_front_distance, point_index); -// double inc = CurrStatus.speed; -// int iRange = point_index - info.iBack; +// //cout << "Accelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Acceleration: " << targe_acceleration << endl; +// } +// else +// { +// WayPoint pursuite_point = PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.followDistance - critical_long_front_distance, point_index); +// double inc = CurrStatus.speed; +// int iRange = point_index - info.iBack; // -// if(iRange > 0) -// inc = inc / (double)iRange; -// else -// inc = 0; +// if(iRange > 0) +// inc = inc / (double)iRange; +// else +// inc = 0; // -// double target_velocity = CurrStatus.speed - inc; -// for(unsigned int i = info.iBack; i < point_index; i++) -// { -// if(i < m_Path.size() && i >= 0) -// { -// target_velocity = target_velocity < 0 ? 0 : target_velocity; -// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) -// m_Path.at(i).v = target_velocity; -// else -// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; -// } +// double target_velocity = CurrStatus.speed - inc; +// for(unsigned int i = info.iBack; i < point_index; i++) +// { +// if(i < m_Path.size() && i >= 0) +// { +// target_velocity = target_velocity < 0 ? 0 : target_velocity; +// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) +// m_Path.at(i).v = target_velocity; +// else +// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; +// } // -// target_velocity -= inc; -// } +// target_velocity -= inc; +// } // -// //cout << "Decelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Start I" << info.iBack << endl; -// } +// //cout << "Decelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Start I" << info.iBack << endl; +// } // -// } -// else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) -// { -// double target_velocity = max_velocity; +// } +// else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) +// { +// double target_velocity = max_velocity; // -// for(unsigned int i = 0; i < m_Path.size(); i++) -// { -// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) -// m_Path.at(i).v = target_velocity; -// else -// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; -// } -// } -// else -// { -// double target_velocity = 0; -// for(unsigned int i = 0; i < m_Path.size(); i++) -// m_Path.at(i).v = target_velocity; -// } +// for(unsigned int i = 0; i < m_Path.size(); i++) +// { +// if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory == m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) +// m_Path.at(i).v = target_velocity; +// else +// m_Path.at(i).v = target_velocity*AVOIDANCE_SPEED_FACTOR; +// } +// } +// else +// { +// double target_velocity = 0; +// for(unsigned int i = 0; i < m_Path.size(); i++) +// m_Path.at(i).v = target_velocity; +// } // -// return max_velocity; +// return max_velocity; // } double LocalPlannerH::UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt) { - if(m_TotalOriginalPath.size() ==0 ) return 0; - - RelativeInfo info, total_info; - PlanningHelpers::GetRelativeInfo(m_TotalOriginalPath.at(m_iCurrentTotalPathId), state, total_info); - PlanningHelpers::GetRelativeInfo(m_Path, state, info); - double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; - double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalOriginalPath.at(m_iCurrentTotalPathId), total_info, m_PrevBrakingWayPoint, average_braking_distance); - - unsigned int point_index = 0; - double critical_long_front_distance = 2.0; - - if(m_Path.size() <= 5) - { - double target_velocity = 0; - for(unsigned int i = 0; i < m_Path.size(); i++) - m_Path.at(i).v = target_velocity; - } - else if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE || beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) - { - PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); - - double e = -beh.stopDistance; - double desiredVelocity = m_pidStopping.getPID(e); - - for(unsigned int i = info.iBack; i < point_index; i++) - { - if(i < m_Path.size() && i >= 0) - m_Path.at(i).v = desiredVelocity; - } - - return desiredVelocity; - } - else if(beh.state == FOLLOW_STATE) - { - double targe_acceleration = -pow(CurrStatus.speed, 2)/(2.0*(beh.followDistance - critical_long_front_distance)); - if(targe_acceleration <= 0 && targe_acceleration > m_CarInfo.max_deceleration/2.0) - { - double target_velocity = (targe_acceleration * dt) + CurrStatus.speed; - - double e = target_velocity - CurrStatus.speed; - double desiredVelocity = m_pidVelocity.getPID(e); - - for(unsigned int i = info.iBack; i < m_Path.size(); i++) - { - if(i < m_Path.size() && i >= 0) - m_Path.at(i).v = desiredVelocity; - } - - return desiredVelocity; - //cout << "Accelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Acceleration: " << targe_acceleration << endl; - } - else - { - WayPoint pursuite_point = PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.followDistance - critical_long_front_distance, point_index); - - double e = beh.followDistance - m_params.minFollowingDistance; - double desiredVelocity = m_pidStopping.getPID(e); - - for(unsigned int i = info.iBack; i < point_index; i++) - { - if(i < m_Path.size() && i >= 0) - m_Path.at(i).v = desiredVelocity; - } - - return desiredVelocity; - //cout << "Decelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Start I" << info.iBack << endl; - } - - } - else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) - { - double target_velocity = max_velocity; - if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory != m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) - target_velocity*=AVOIDANCE_SPEED_FACTOR; - - double e = target_velocity - CurrStatus.speed; - double desiredVelocity = m_pidVelocity.getPID(e); - - for(unsigned int i = info.iBack; i < m_Path.size(); i++) - { - m_Path.at(i).v = desiredVelocity; - } - - return desiredVelocity; - } - else - { - double target_velocity = 0; - for(unsigned int i = info.iBack; i < m_Path.size(); i++) - m_Path.at(i).v = target_velocity; - - return target_velocity; - } - - return max_velocity; + if(m_TotalOriginalPath.size() ==0 ) return 0; + + RelativeInfo info, total_info; + PlanningHelpers::GetRelativeInfo(m_TotalOriginalPath.at(m_iCurrentTotalPathId), state, total_info); + PlanningHelpers::GetRelativeInfo(m_Path, state, info); + double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance; + double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalOriginalPath.at(m_iCurrentTotalPathId), total_info, m_PrevBrakingWayPoint, average_braking_distance); + + unsigned int point_index = 0; + double critical_long_front_distance = 2.0; + + if(m_Path.size() <= 5) + { + double target_velocity = 0; + for(unsigned int i = 0; i < m_Path.size(); i++) + m_Path.at(i).v = target_velocity; + } + else if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE || beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE) + { + PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index); + + double e = -beh.stopDistance; + double desiredVelocity = m_pidStopping.getPID(e); + + for(unsigned int i = info.iBack; i < point_index; i++) + { + if(i < m_Path.size() && i >= 0) + m_Path.at(i).v = desiredVelocity; + } + + return desiredVelocity; + } + else if(beh.state == FOLLOW_STATE) + { + double targe_acceleration = -pow(CurrStatus.speed, 2)/(2.0*(beh.followDistance - critical_long_front_distance)); + if(targe_acceleration <= 0 && targe_acceleration > m_CarInfo.max_deceleration/2.0) + { + double target_velocity = (targe_acceleration * dt) + CurrStatus.speed; + + double e = target_velocity - CurrStatus.speed; + double desiredVelocity = m_pidVelocity.getPID(e); + + for(unsigned int i = info.iBack; i < m_Path.size(); i++) + { + if(i < m_Path.size() && i >= 0) + m_Path.at(i).v = desiredVelocity; + } + + return desiredVelocity; + //cout << "Accelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Acceleration: " << targe_acceleration << endl; + } + else + { + WayPoint pursuite_point = PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.followDistance - critical_long_front_distance, point_index); + + double e = beh.followDistance - m_params.minFollowingDistance; + double desiredVelocity = m_pidStopping.getPID(e); + + for(unsigned int i = info.iBack; i < point_index; i++) + { + if(i < m_Path.size() && i >= 0) + m_Path.at(i).v = desiredVelocity; + } + + return desiredVelocity; + //cout << "Decelerate -> Target V: " << target_velocity << ", Brake D: " << average_braking_distance << ", Start I" << info.iBack << endl; + } + + } + else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE ) + { + double target_velocity = max_velocity; + if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory != m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) + target_velocity*=AVOIDANCE_SPEED_FACTOR; + + double e = target_velocity - CurrStatus.speed; + double desiredVelocity = m_pidVelocity.getPID(e); + + for(unsigned int i = info.iBack; i < m_Path.size(); i++) + { + m_Path.at(i).v = desiredVelocity; + } + + return desiredVelocity; + } + else + { + double target_velocity = 0; + for(unsigned int i = info.iBack; i < m_Path.size(); i++) + m_Path.at(i).v = target_velocity; + + return target_velocity; + } + + return max_velocity; } void LocalPlannerH::ExtractHorizonAndCalculateRecommendedSpeed() { - if(m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath && m_TotalOriginalPath.size() > 0) - { - m_PrevBrakingWayPoint = 0; - PlanningHelpers::FixPathDensity(m_TotalOriginalPath.at(m_iCurrentTotalPathId), m_pCurrentBehaviorState->m_pParams->pathDensity); - PlanningHelpers::SmoothPath(m_TotalOriginalPath.at(m_iCurrentTotalPathId), 0.49, 0.25, 0.05); - - PlanningHelpers::GenerateRecommendedSpeed(m_TotalOriginalPath.at(m_iCurrentTotalPathId), m_CarInfo.max_speed_forward, m_pCurrentBehaviorState->m_pParams->speedProfileFactor); - m_TotalOriginalPath.at(m_iCurrentTotalPathId).at(m_TotalOriginalPath.at(m_iCurrentTotalPathId).size()-1).v = 0; - - } - - m_TotalPath.clear(); - - for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) - { - vector centerTrajectorySmoothed; - PlanningHelpers::ExtractPartFromPointToDistanceFast(m_TotalOriginalPath.at(i), state, - m_pCurrentBehaviorState->m_pParams->horizonDistance , - m_pCurrentBehaviorState->m_pParams->pathDensity , - centerTrajectorySmoothed, - m_pCurrentBehaviorState->m_pParams->smoothingDataWeight, - m_pCurrentBehaviorState->m_pParams->smoothingSmoothWeight, - m_pCurrentBehaviorState->m_pParams->smoothingToleranceError); - - m_TotalPath.push_back(centerTrajectorySmoothed); - } + if(m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath && m_TotalOriginalPath.size() > 0) + { + m_PrevBrakingWayPoint = 0; + PlanningHelpers::FixPathDensity(m_TotalOriginalPath.at(m_iCurrentTotalPathId), m_pCurrentBehaviorState->m_pParams->pathDensity); + PlanningHelpers::SmoothPath(m_TotalOriginalPath.at(m_iCurrentTotalPathId), 0.49, 0.25, 0.05); + + PlanningHelpers::GenerateRecommendedSpeed(m_TotalOriginalPath.at(m_iCurrentTotalPathId), m_CarInfo.max_speed_forward, m_pCurrentBehaviorState->m_pParams->speedProfileFactor); + m_TotalOriginalPath.at(m_iCurrentTotalPathId).at(m_TotalOriginalPath.at(m_iCurrentTotalPathId).size()-1).v = 0; + + } + + m_TotalPath.clear(); + + for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) + { + vector centerTrajectorySmoothed; + PlanningHelpers::ExtractPartFromPointToDistanceFast(m_TotalOriginalPath.at(i), state, + m_pCurrentBehaviorState->m_pParams->horizonDistance , + m_pCurrentBehaviorState->m_pParams->pathDensity , + centerTrajectorySmoothed, + m_pCurrentBehaviorState->m_pParams->smoothingDataWeight, + m_pCurrentBehaviorState->m_pParams->smoothingSmoothWeight, + m_pCurrentBehaviorState->m_pParams->smoothingToleranceError); + + m_TotalPath.push_back(centerTrajectorySmoothed); + } } PlannerHNS::BehaviorState LocalPlannerH::DoOneStep( - const double& dt, - const PlannerHNS::VehicleState& vehicleState, - const std::vector& obj_list, - const int& goalID, PlannerHNS::RoadNetwork& map , - const bool& bEmergencyStop, - const std::vector& trafficLight, - const bool& bLive) + const double& dt, + const PlannerHNS::VehicleState& vehicleState, + const std::vector& obj_list, + const int& goalID, PlannerHNS::RoadNetwork& map , + const bool& bEmergencyStop, + const std::vector& trafficLight, + const bool& bLive) { - PlannerHNS::BehaviorState beh; + PlannerHNS::BehaviorState beh; - m_params.minFollowingDistance = m_InitialFollowingDistance + vehicleState.speed*1.5; + m_params.minFollowingDistance = m_InitialFollowingDistance + vehicleState.speed*1.5; - if(!bLive) - SimulateOdoPosition(dt, vehicleState); + if(!bLive) + SimulateOdoPosition(dt, vehicleState); - UpdateCurrentLane(map, 3.0); + UpdateCurrentLane(map, 3.0); - ExtractHorizonAndCalculateRecommendedSpeed(); + ExtractHorizonAndCalculateRecommendedSpeed(); - m_PredictedTrajectoryObstacles = obj_list; + m_PredictedTrajectoryObstacles = obj_list; - timespec t; - UtilityH::GetTickCount(t); - TrajectoryCost tc = m_TrajectoryCostsCalculatotor.DoOneStep(m_RollOuts, m_TotalPath, state, - m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory, m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeLane, *m_pCurrentBehaviorState->m_pParams, - m_CarInfo,vehicleState, m_PredictedTrajectoryObstacles); - m_CostCalculationTime = UtilityH::GetTimeDiffNow(t); + timespec t; + UtilityH::GetTickCount(t); + TrajectoryCost tc = m_TrajectoryCostsCalculatotor.DoOneStep(m_RollOuts, m_TotalPath, state, + m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory, m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeLane, *m_pCurrentBehaviorState->m_pParams, + m_CarInfo,vehicleState, m_PredictedTrajectoryObstacles); + m_CostCalculationTime = UtilityH::GetTimeDiffNow(t); - UtilityH::GetTickCount(t); - CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); + UtilityH::GetTickCount(t); + CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); - beh = GenerateBehaviorState(vehicleState); - m_BehaviorGenTime = UtilityH::GetTimeDiffNow(t); + beh = GenerateBehaviorState(vehicleState); + m_BehaviorGenTime = UtilityH::GetTimeDiffNow(t); - UtilityH::GetTickCount(t); - beh.bNewPlan = SelectSafeTrajectoryAndSpeedProfile(vehicleState); + UtilityH::GetTickCount(t); + beh.bNewPlan = SelectSafeTrajectoryAndSpeedProfile(vehicleState); - m_RollOutsGenerationTime = UtilityH::GetTimeDiffNow(t); + m_RollOutsGenerationTime = UtilityH::GetTimeDiffNow(t); - beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); + beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); - return beh; + return beh; } } /* namespace PlannerHNS */ diff --git a/common/op_planner/src/MappingHelpers.cpp b/common/op_planner/src/MappingHelpers.cpp index 9ad6de01bb3..6588136c072 100755 --- a/common/op_planner/src/MappingHelpers.cpp +++ b/common/op_planner/src/MappingHelpers.cpp @@ -38,436 +38,436 @@ MappingHelpers::~MappingHelpers() { GPSPoint MappingHelpers::GetTransformationOrigin(const int& bToyotaCityMap) { -// if(bToyotaCityMap == 1) -// return GPSPoint(-3700, 99427, -88,0); //toyota city -// else if(bToyotaCityMap == 2) -// return GPSPoint(14805.945, 84680.211, -39.59, 0); // for moriyama map -// else - return GPSPoint(); - //return GPSPoint(18221.1, 93546.1, -36.19, 0); +// if(bToyotaCityMap == 1) +// return GPSPoint(-3700, 99427, -88,0); //toyota city +// else if(bToyotaCityMap == 2) +// return GPSPoint(14805.945, 84680.211, -39.59, 0); // for moriyama map +// else + return GPSPoint(); + //return GPSPoint(18221.1, 93546.1, -36.19, 0); } Lane* MappingHelpers::GetLaneById(const int& id,RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - if(map.roadSegments.at(rs).Lanes.at(i).id == id) - return &map.roadSegments.at(rs).Lanes.at(i); - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + if(map.roadSegments.at(rs).Lanes.at(i).id == id) + return &map.roadSegments.at(rs).Lanes.at(i); + } + } - return nullptr; + return nullptr; } int MappingHelpers::GetLaneIdByWaypointId(const int& id,std::vector& lanes) { - for(unsigned int in_l= 0; in_l < lanes.size(); in_l++) - { - for(unsigned int in_p = 0; in_p >& rep_list) { - for(unsigned int i=0; i < rep_list.size(); i++) - { - if(rep_list.at(i).first == id) - { - id = rep_list.at(i).second; - return id; - } - } + for(unsigned int i=0; i < rep_list.size(); i++) + { + if(rep_list.at(i).first == id) + { + id = rep_list.at(i).second; + return id; + } + } - return -1; + return -1; } void MappingHelpers::ConstructRoadNetworkFromROSMessage(const std::vector& lanes_data, - const std::vector& points_data, - const std::vector& dt_data, - const std::vector& intersection_data, - const std::vector& area_data, - const std::vector& line_data, - const std::vector& stop_line_data, - const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& curb_data, - const std::vector& roadedge_data, - const std::vector& wayarea_data, - const std::vector& crosswalk_data, - const std::vector& nodes_data, - const std::vector& conn_data, - const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag, - const bool& bFindLaneChangeLanes, const bool& bFindCurbsAndWayArea) -{ - vector roadLanes; - Lane lane_obj; - int laneIDSeq = 0; - WayPoint prevWayPoint; - UtilityHNS::AisanLanesFileReader::AisanLane prev_lane_point; - UtilityHNS::AisanLanesFileReader::AisanLane curr_lane_point; - UtilityHNS::AisanLanesFileReader::AisanLane next_lane_point; - vector > id_replace_list; - - for(unsigned int l= 0; l < lanes_data.size(); l++) - { - curr_lane_point = lanes_data.at(l); - curr_lane_point.originalMapID = -1; - - if(l+1 < lanes_data.size()) - { - next_lane_point = lanes_data.at(l+1); - if(curr_lane_point.FLID == next_lane_point.LnID && curr_lane_point.DID == next_lane_point.DID) - { - next_lane_point.BLID = curr_lane_point.BLID; - if(next_lane_point.LaneDir == 'F') - next_lane_point.LaneDir = curr_lane_point.LaneDir; - - if(curr_lane_point.BLID2 != 0) - { - if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID2; - else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID2; - else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID2; - } - - if(curr_lane_point.BLID3 != 0) - { - if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID3; - else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID3; - else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID3; - } - - if(curr_lane_point.BLID3 != 0) - { - if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID4; - else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID4; - else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID4; - } - - if(curr_lane_point.FLID2 != 0) - { - if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID2; - else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID2; - else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID2; - } - - if(curr_lane_point.FLID3 != 0) - { - if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID3; - else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID3; - else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID3; - } - - if(curr_lane_point.FLID3 != 0) - { - if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID4; - else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID4; - else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID4; - } - - if(prev_lane_point.FLID == curr_lane_point.LnID) - prev_lane_point.FLID = next_lane_point.LnID; - - id_replace_list.push_back(make_pair(curr_lane_point.LnID, next_lane_point.LnID)); - int originalMapID = curr_lane_point.LnID; - curr_lane_point = next_lane_point; - curr_lane_point.originalMapID = originalMapID; - l++; - } - } - - if(curr_lane_point.LnID != prev_lane_point.FLID) - { - if(laneIDSeq != 0) //first lane - { - lane_obj.toIds.push_back(prev_lane_point.FLID); - roadLanes.push_back(lane_obj); -// if(lane_obj.points.size() <= 1) -// prev_FLID = 0; - } - - laneIDSeq++; - lane_obj = Lane(); - lane_obj.speed = curr_lane_point.LimitVel; - lane_obj.id = curr_lane_point.LnID; - lane_obj.fromIds.push_back(curr_lane_point.BLID); - lane_obj.roadId = laneIDSeq; - } - - WayPoint wp; - bool bFound = GetWayPoint(curr_lane_point.LnID, lane_obj.id, curr_lane_point.RefVel,curr_lane_point.DID, - dt_data, points_data,origin, wp); - - wp.originalMapID = curr_lane_point.originalMapID; - - if(curr_lane_point.LaneDir == 'L') - { - wp.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); - //std::cout << " Left Lane : " << curr_lane_point.LnID << std::endl ; - } - else if(curr_lane_point.LaneDir == 'R') - { - wp.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); - //std::cout << " Right Lane : " << curr_lane_point.LnID << std::endl ; - } - else - { - wp.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); - } - - wp.fromIds.push_back(curr_lane_point.BLID); - wp.toIds.push_back(curr_lane_point.FLID); - - //if(curr_lane_point.JCT > 0) - if(curr_lane_point.FLID2 > 0) - { - lane_obj.toIds.push_back(curr_lane_point.FLID2); - wp.toIds.push_back(curr_lane_point.FLID2); - } - if(curr_lane_point.FLID3 > 0) - { - lane_obj.toIds.push_back(curr_lane_point.FLID3); - wp.toIds.push_back(curr_lane_point.FLID3); - } - if(curr_lane_point.FLID4 > 0) - { - lane_obj.toIds.push_back(curr_lane_point.FLID4); - wp.toIds.push_back(curr_lane_point.FLID4); - } - - if(curr_lane_point.BLID2 > 0) - { - lane_obj.fromIds.push_back(curr_lane_point.BLID2); - wp.fromIds.push_back(curr_lane_point.BLID2); - } - if(curr_lane_point.BLID3 > 0) - { - lane_obj.fromIds.push_back(curr_lane_point.BLID3); - wp.fromIds.push_back(curr_lane_point.BLID3); - } - if(curr_lane_point.BLID4 > 0) - { - lane_obj.fromIds.push_back(curr_lane_point.BLID4); - wp.fromIds.push_back(curr_lane_point.BLID4); - } - - //if(prev_lane_point.DID == curr_lane_point.DID && curr_lane_point.LnID == prev_lane_point.FLID) -// if(prevWayPoint.pos.x == wp.pos.x && prevWayPoint.pos.y == wp.pos.y) -// { -// //if((prev_lane_point.FLID2 != 0 && curr_lane_point.FLID2 != 0) || (prev_lane_point.FLID3 != 0 && curr_lane_point.FLID3 != 0) || (prev_lane_point.FLID4 != 0 && curr_lane_point.FLID4 != 0)) -// { -// cout << "Prev WP, LnID: " << prev_lane_point.LnID << ",BLID: " << prev_lane_point.BLID << ",FLID: " << prev_lane_point.FLID << ",DID: " << prev_lane_point.DID -// << ", Begin: " << prev_lane_point.BLID2 << "," << prev_lane_point.BLID3 << "," << prev_lane_point.BLID4 -// << ", End: " << prev_lane_point.FLID2 << "," << prev_lane_point.FLID3 << "," << prev_lane_point.FLID4 << ": " << prev_lane_point.LaneDir << endl; -// cout << "Curr WP, LnID: " << curr_lane_point.LnID << ",BLID: " << curr_lane_point.BLID << ",FLID: " << curr_lane_point.FLID << ",DID: " << curr_lane_point.DID -// << ", Begin: " << curr_lane_point.BLID2 << "," << curr_lane_point.BLID3 << "," << curr_lane_point.BLID4 -// << ", End: " << curr_lane_point.FLID2 << "," < 0) - roadLanes.erase(roadLanes.begin()+0); - if(roadLanes.size() > 0) - roadLanes.erase(roadLanes.begin()+0); - } - - roadLanes.push_back(lane_obj); - - for(unsigned int i =0; i < roadLanes.size(); i++) - { - Lane* pL = &roadLanes.at(i); - ReplaceMyID(pL->id, id_replace_list); - - for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) - { - int id = ReplaceMyID(pL->fromIds.at(j), id_replace_list); - if(id != -1) - pL->fromIds.at(j) = id; - } - - for(unsigned int j = 0 ; j < pL->toIds.size(); j++) - { - int id = ReplaceMyID(pL->toIds.at(j), id_replace_list); - if(id != -1) - pL->toIds.at(j) = id; - } - - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - ReplaceMyID(pL->points.at(j).id, id_replace_list); - ReplaceMyID(pL->points.at(j).laneId, id_replace_list); - - for(unsigned int jj = 0 ; jj < pL->points.at(j).fromIds.size(); jj++) - { - int id = ReplaceMyID(pL->points.at(j).fromIds.at(jj), id_replace_list); - if(id != -1) - pL->points.at(j).fromIds.at(jj) = id; - } - - for(unsigned int jj = 0 ; jj < pL->points.at(j).toIds.size(); jj++) - { - int id = ReplaceMyID(pL->points.at(j).toIds.at(jj), id_replace_list); - if(id != -1) - pL->points.at(j).toIds.at(jj) = id; - } - } - } - - //Link Lanes and lane's waypoints by pointers - //For each lane, the previous code set the fromId as the id of the last waypoint of the previos lane. - //here we fix that by finding from each fromID the corresponding point and replace the fromId by the LaneID associated with that point. - for(unsigned int l= 0; l < roadLanes.size(); l++) - { - for(unsigned int fp = 0; fp< roadLanes.at(l).fromIds.size(); fp++) - { - roadLanes.at(l).fromIds.at(fp) = GetLaneIdByWaypointId(roadLanes.at(l).fromIds.at(fp), roadLanes); - } - - for(unsigned int tp = 0; tp< roadLanes.at(l).toIds.size(); tp++) - { - roadLanes.at(l).toIds.at(tp) = GetLaneIdByWaypointId(roadLanes.at(l).toIds.at(tp), roadLanes); - } - - double sum_a = 0; - for(unsigned int j = 0 ; j < roadLanes.at(l).points.size(); j++) - { - sum_a += roadLanes.at(l).points.at(j).pos.a; - } - roadLanes.at(l).dir = sum_a/(double)roadLanes.at(l).points.size(); - } - - //map has one road segment - RoadSegment roadSegment1; - roadSegment1.id = 1; - roadSegment1.Lanes = roadLanes; - map.roadSegments.push_back(roadSegment1); - - //Link Lanes and lane's waypoints by pointers - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - //Link Lanes - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) - { - pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->toIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) - { - pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - pL->points.at(j).pLane = pL; - } - } - } - - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - if(pL->points.at(j).actionCost.size() > 0) - { - if(pL->points.at(j).actionCost.at(0).first == LEFT_TURN_ACTION) - { - AssignActionCostToLane(pL, LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST); - break; - } - else if(pL->points.at(j).actionCost.at(0).first == RIGHT_TURN_ACTION) - { - AssignActionCostToLane(pL, RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST); - break; - - } - } - } - } - } - - if(bFindLaneChangeLanes) - { - cout << " >> Extract Lane Change Information... " << endl; - FindAdjacentLanes(map); - } - - //Extract Signals and StopLines - // Signals - ExtractSignalData(signal_data, vector_data, points_data, origin, map); - - - //Stop Lines - ExtractStopLinesData(stop_line_data, line_data, points_data, origin, map); - - - //Link waypoints - LinkMissingBranchingWayPoints(map); - - //Link StopLines and Traffic Lights - LinkTrafficLightsAndStopLines(map); - //LinkTrafficLightsAndStopLinesConData(conn_data, id_replace_list, map); - - if(bFindCurbsAndWayArea) - { - //Curbs - ExtractCurbData(curb_data, line_data, points_data, origin, map); - - //Wayarea - ExtractWayArea(area_data, wayarea_data, line_data, points_data, origin, map); - } - - //Fix angle for lanes - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - PlannerHNS::PlanningHelpers::FixAngleOnly(pL->points); - } - } - - cout << "Map loaded from data with " << roadLanes.size() << " lanes" << endl; + const std::vector& points_data, + const std::vector& dt_data, + const std::vector& intersection_data, + const std::vector& area_data, + const std::vector& line_data, + const std::vector& stop_line_data, + const std::vector& signal_data, + const std::vector& vector_data, + const std::vector& curb_data, + const std::vector& roadedge_data, + const std::vector& wayarea_data, + const std::vector& crosswalk_data, + const std::vector& nodes_data, + const std::vector& conn_data, + const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag, + const bool& bFindLaneChangeLanes, const bool& bFindCurbsAndWayArea) +{ + vector roadLanes; + Lane lane_obj; + int laneIDSeq = 0; + WayPoint prevWayPoint; + UtilityHNS::AisanLanesFileReader::AisanLane prev_lane_point; + UtilityHNS::AisanLanesFileReader::AisanLane curr_lane_point; + UtilityHNS::AisanLanesFileReader::AisanLane next_lane_point; + vector > id_replace_list; + + for(unsigned int l= 0; l < lanes_data.size(); l++) + { + curr_lane_point = lanes_data.at(l); + curr_lane_point.originalMapID = -1; + + if(l+1 < lanes_data.size()) + { + next_lane_point = lanes_data.at(l+1); + if(curr_lane_point.FLID == next_lane_point.LnID && curr_lane_point.DID == next_lane_point.DID) + { + next_lane_point.BLID = curr_lane_point.BLID; + if(next_lane_point.LaneDir == 'F') + next_lane_point.LaneDir = curr_lane_point.LaneDir; + + if(curr_lane_point.BLID2 != 0) + { + if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID2; + else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID2; + else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID2; + } + + if(curr_lane_point.BLID3 != 0) + { + if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID3; + else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID3; + else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID3; + } + + if(curr_lane_point.BLID3 != 0) + { + if(next_lane_point.BLID2 == 0) next_lane_point.BLID2 = curr_lane_point.BLID4; + else if(next_lane_point.BLID3 == 0) next_lane_point.BLID3 = curr_lane_point.BLID4; + else if(next_lane_point.BLID4 == 0) next_lane_point.BLID4 = curr_lane_point.BLID4; + } + + if(curr_lane_point.FLID2 != 0) + { + if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID2; + else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID2; + else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID2; + } + + if(curr_lane_point.FLID3 != 0) + { + if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID3; + else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID3; + else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID3; + } + + if(curr_lane_point.FLID3 != 0) + { + if(next_lane_point.FLID2 == 0) next_lane_point.FLID2 = curr_lane_point.FLID4; + else if(next_lane_point.FLID3 == 0) next_lane_point.FLID3 = curr_lane_point.FLID4; + else if(next_lane_point.FLID4 == 0) next_lane_point.FLID4 = curr_lane_point.FLID4; + } + + if(prev_lane_point.FLID == curr_lane_point.LnID) + prev_lane_point.FLID = next_lane_point.LnID; + + id_replace_list.push_back(make_pair(curr_lane_point.LnID, next_lane_point.LnID)); + int originalMapID = curr_lane_point.LnID; + curr_lane_point = next_lane_point; + curr_lane_point.originalMapID = originalMapID; + l++; + } + } + + if(curr_lane_point.LnID != prev_lane_point.FLID) + { + if(laneIDSeq != 0) //first lane + { + lane_obj.toIds.push_back(prev_lane_point.FLID); + roadLanes.push_back(lane_obj); +// if(lane_obj.points.size() <= 1) +// prev_FLID = 0; + } + + laneIDSeq++; + lane_obj = Lane(); + lane_obj.speed = curr_lane_point.LimitVel; + lane_obj.id = curr_lane_point.LnID; + lane_obj.fromIds.push_back(curr_lane_point.BLID); + lane_obj.roadId = laneIDSeq; + } + + WayPoint wp; + bool bFound = GetWayPoint(curr_lane_point.LnID, lane_obj.id, curr_lane_point.RefVel,curr_lane_point.DID, + dt_data, points_data,origin, wp); + + wp.originalMapID = curr_lane_point.originalMapID; + + if(curr_lane_point.LaneDir == 'L') + { + wp.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); + //std::cout << " Left Lane : " << curr_lane_point.LnID << std::endl ; + } + else if(curr_lane_point.LaneDir == 'R') + { + wp.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); + //std::cout << " Right Lane : " << curr_lane_point.LnID << std::endl ; + } + else + { + wp.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); + } + + wp.fromIds.push_back(curr_lane_point.BLID); + wp.toIds.push_back(curr_lane_point.FLID); + + //if(curr_lane_point.JCT > 0) + if(curr_lane_point.FLID2 > 0) + { + lane_obj.toIds.push_back(curr_lane_point.FLID2); + wp.toIds.push_back(curr_lane_point.FLID2); + } + if(curr_lane_point.FLID3 > 0) + { + lane_obj.toIds.push_back(curr_lane_point.FLID3); + wp.toIds.push_back(curr_lane_point.FLID3); + } + if(curr_lane_point.FLID4 > 0) + { + lane_obj.toIds.push_back(curr_lane_point.FLID4); + wp.toIds.push_back(curr_lane_point.FLID4); + } + + if(curr_lane_point.BLID2 > 0) + { + lane_obj.fromIds.push_back(curr_lane_point.BLID2); + wp.fromIds.push_back(curr_lane_point.BLID2); + } + if(curr_lane_point.BLID3 > 0) + { + lane_obj.fromIds.push_back(curr_lane_point.BLID3); + wp.fromIds.push_back(curr_lane_point.BLID3); + } + if(curr_lane_point.BLID4 > 0) + { + lane_obj.fromIds.push_back(curr_lane_point.BLID4); + wp.fromIds.push_back(curr_lane_point.BLID4); + } + + //if(prev_lane_point.DID == curr_lane_point.DID && curr_lane_point.LnID == prev_lane_point.FLID) +// if(prevWayPoint.pos.x == wp.pos.x && prevWayPoint.pos.y == wp.pos.y) +// { +// //if((prev_lane_point.FLID2 != 0 && curr_lane_point.FLID2 != 0) || (prev_lane_point.FLID3 != 0 && curr_lane_point.FLID3 != 0) || (prev_lane_point.FLID4 != 0 && curr_lane_point.FLID4 != 0)) +// { +// cout << "Prev WP, LnID: " << prev_lane_point.LnID << ",BLID: " << prev_lane_point.BLID << ",FLID: " << prev_lane_point.FLID << ",DID: " << prev_lane_point.DID +// << ", Begin: " << prev_lane_point.BLID2 << "," << prev_lane_point.BLID3 << "," << prev_lane_point.BLID4 +// << ", End: " << prev_lane_point.FLID2 << "," << prev_lane_point.FLID3 << "," << prev_lane_point.FLID4 << ": " << prev_lane_point.LaneDir << endl; +// cout << "Curr WP, LnID: " << curr_lane_point.LnID << ",BLID: " << curr_lane_point.BLID << ",FLID: " << curr_lane_point.FLID << ",DID: " << curr_lane_point.DID +// << ", Begin: " << curr_lane_point.BLID2 << "," << curr_lane_point.BLID3 << "," << curr_lane_point.BLID4 +// << ", End: " << curr_lane_point.FLID2 << "," < 0) + roadLanes.erase(roadLanes.begin()+0); + if(roadLanes.size() > 0) + roadLanes.erase(roadLanes.begin()+0); + } + + roadLanes.push_back(lane_obj); + + for(unsigned int i =0; i < roadLanes.size(); i++) + { + Lane* pL = &roadLanes.at(i); + ReplaceMyID(pL->id, id_replace_list); + + for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) + { + int id = ReplaceMyID(pL->fromIds.at(j), id_replace_list); + if(id != -1) + pL->fromIds.at(j) = id; + } + + for(unsigned int j = 0 ; j < pL->toIds.size(); j++) + { + int id = ReplaceMyID(pL->toIds.at(j), id_replace_list); + if(id != -1) + pL->toIds.at(j) = id; + } + + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + ReplaceMyID(pL->points.at(j).id, id_replace_list); + ReplaceMyID(pL->points.at(j).laneId, id_replace_list); + + for(unsigned int jj = 0 ; jj < pL->points.at(j).fromIds.size(); jj++) + { + int id = ReplaceMyID(pL->points.at(j).fromIds.at(jj), id_replace_list); + if(id != -1) + pL->points.at(j).fromIds.at(jj) = id; + } + + for(unsigned int jj = 0 ; jj < pL->points.at(j).toIds.size(); jj++) + { + int id = ReplaceMyID(pL->points.at(j).toIds.at(jj), id_replace_list); + if(id != -1) + pL->points.at(j).toIds.at(jj) = id; + } + } + } + + //Link Lanes and lane's waypoints by pointers + //For each lane, the previous code set the fromId as the id of the last waypoint of the previos lane. + //here we fix that by finding from each fromID the corresponding point and replace the fromId by the LaneID associated with that point. + for(unsigned int l= 0; l < roadLanes.size(); l++) + { + for(unsigned int fp = 0; fp< roadLanes.at(l).fromIds.size(); fp++) + { + roadLanes.at(l).fromIds.at(fp) = GetLaneIdByWaypointId(roadLanes.at(l).fromIds.at(fp), roadLanes); + } + + for(unsigned int tp = 0; tp< roadLanes.at(l).toIds.size(); tp++) + { + roadLanes.at(l).toIds.at(tp) = GetLaneIdByWaypointId(roadLanes.at(l).toIds.at(tp), roadLanes); + } + + double sum_a = 0; + for(unsigned int j = 0 ; j < roadLanes.at(l).points.size(); j++) + { + sum_a += roadLanes.at(l).points.at(j).pos.a; + } + roadLanes.at(l).dir = sum_a/(double)roadLanes.at(l).points.size(); + } + + //map has one road segment + RoadSegment roadSegment1; + roadSegment1.id = 1; + roadSegment1.Lanes = roadLanes; + map.roadSegments.push_back(roadSegment1); + + //Link Lanes and lane's waypoints by pointers + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + //Link Lanes + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) + { + pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->toIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) + { + pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + pL->points.at(j).pLane = pL; + } + } + } + + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + if(pL->points.at(j).actionCost.size() > 0) + { + if(pL->points.at(j).actionCost.at(0).first == LEFT_TURN_ACTION) + { + AssignActionCostToLane(pL, LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST); + break; + } + else if(pL->points.at(j).actionCost.at(0).first == RIGHT_TURN_ACTION) + { + AssignActionCostToLane(pL, RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST); + break; + + } + } + } + } + } + + if(bFindLaneChangeLanes) + { + cout << " >> Extract Lane Change Information... " << endl; + FindAdjacentLanes(map); + } + + //Extract Signals and StopLines + // Signals + ExtractSignalData(signal_data, vector_data, points_data, origin, map); + + + //Stop Lines + ExtractStopLinesData(stop_line_data, line_data, points_data, origin, map); + + + //Link waypoints + LinkMissingBranchingWayPoints(map); + + //Link StopLines and Traffic Lights + LinkTrafficLightsAndStopLines(map); + //LinkTrafficLightsAndStopLinesConData(conn_data, id_replace_list, map); + + if(bFindCurbsAndWayArea) + { + //Curbs + ExtractCurbData(curb_data, line_data, points_data, origin, map); + + //Wayarea + ExtractWayArea(area_data, wayarea_data, line_data, points_data, origin, map); + } + + //Fix angle for lanes + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + PlannerHNS::PlanningHelpers::FixAngleOnly(pL->points); + } + } + + cout << "Map loaded from data with " << roadLanes.size() << " lanes" << endl; } void MappingHelpers::AssignActionCostToLane(Lane* pL, ACTION_TYPE action, double cost) @@ -481,2962 +481,2962 @@ void MappingHelpers::AssignActionCostToLane(Lane* pL, ACTION_TYPE action, double WayPoint* MappingHelpers::FindWaypoint(const int& id, RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - if(map.roadSegments.at(rs).Lanes.at(i).points.at(p).id == id) - return &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + if(map.roadSegments.at(rs).Lanes.at(i).points.at(p).id == id) + return &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + } + } + } - return nullptr; + return nullptr; } WayPoint* MappingHelpers::FindWaypointV2(const int& id, const int& l_id, RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pLane = &map.roadSegments.at(rs).Lanes.at(i); - if(pLane ->id != l_id) - { - for(unsigned int p= 0; p < pLane->points.size(); p++) - { - if(pLane->points.at(p).id == id) - return &pLane->points.at(p); - } - } - } - } - - return nullptr; + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pLane = &map.roadSegments.at(rs).Lanes.at(i); + if(pLane ->id != l_id) + { + for(unsigned int p= 0; p < pLane->points.size(); p++) + { + if(pLane->points.at(p).id == id) + return &pLane->points.at(p); + } + } + } + } + + return nullptr; } void MappingHelpers::ConstructRoadNetworkFromDataFiles(const std::string vectoMapPath, RoadNetwork& map, const bool& bZeroOrigin) { - /** - * Exporting the center lines - */ - string laneLinesDetails = vectoMapPath + "point.csv"; - string center_lines_info = vectoMapPath + "dtlane.csv"; - string lane_info = vectoMapPath + "lane.csv"; - string node_info = vectoMapPath + "node.csv"; - string area_info = vectoMapPath + "area.csv"; - string line_info = vectoMapPath + "line.csv"; - string signal_info = vectoMapPath + "signaldata.csv"; - string stop_line_info = vectoMapPath + "stopline.csv"; - string vector_info = vectoMapPath + "vector.csv"; - string curb_info = vectoMapPath + "curb.csv"; - string roadedge_info = vectoMapPath + "roadedge.csv"; - string wayarea_info = vectoMapPath + "wayarea.csv"; - string crosswalk_info = vectoMapPath + "crosswalk.csv"; - string conn_info = vectoMapPath + "dataconnection.csv"; - string intersection_info = vectoMapPath + "intersection.csv"; - - cout << " >> Loading vector map data files ... " << endl; - AisanCenterLinesFileReader center_lanes(center_lines_info); - AisanLanesFileReader lanes(lane_info); - AisanPointsFileReader points(laneLinesDetails); - AisanNodesFileReader nodes(node_info); - AisanLinesFileReader lines(line_info); - AisanStopLineFileReader stop_line(stop_line_info); - AisanSignalFileReader signal(signal_info); - AisanVectorFileReader vec(vector_info); - AisanCurbFileReader curb(curb_info); - AisanRoadEdgeFileReader roadedge(roadedge_info); - AisanDataConnFileReader conn(conn_info); - AisanAreasFileReader areas(area_info); - AisanWayareaFileReader way_area(wayarea_info); - AisanCrossWalkFileReader cross_walk(crosswalk_info); - - - vector intersection_data; - vector nodes_data; - vector lanes_data; - vector points_data; - vector dt_data; - vector line_data; - vector stop_line_data; - vector signal_data; - vector vector_data; - vector curb_data; - vector roadedge_data; - vector area_data; - vector way_area_data; - vector crosswalk_data; - vector conn_data; - - - nodes.ReadAllData(nodes_data); - lanes.ReadAllData(lanes_data); - points.ReadAllData(points_data); - center_lanes.ReadAllData(dt_data); - lines.ReadAllData(line_data); - stop_line.ReadAllData(stop_line_data); - signal.ReadAllData(signal_data); - vec.ReadAllData(vector_data); - curb.ReadAllData(curb_data); - roadedge.ReadAllData(roadedge_data); - areas.ReadAllData(area_data); - way_area.ReadAllData(way_area_data); - cross_walk.ReadAllData(crosswalk_data); - conn.ReadAllData(conn_data); - - if(points_data.size() == 0) - { - std::cout << std::endl << "## Alert Can't Read Points Data from vector map files in path: " << vectoMapPath << std::endl; - return; - } - - //Special Condtion to be able to pars old data structures - int bSpecialMap = 0; - - // use this to transform data to origin (0,0,0) - if(nodes_data.size() > 0 && bSpecialMap == 0) - { - ConstructRoadNetworkFromROSMessageV2(lanes_data, points_data, dt_data, intersection_data, area_data, - line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data, - way_area_data, crosswalk_data, nodes_data, conn_data, &lanes, &points, &nodes, &lines, - GetTransformationOrigin(0), map, false); - } - else - { - ConstructRoadNetworkFromROSMessage(lanes_data, points_data, dt_data, intersection_data, area_data, - line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data, - way_area_data, crosswalk_data, nodes_data, conn_data, - GetTransformationOrigin(0), map, bSpecialMap == 1); - } - - WayPoint origin = GetFirstWaypoint(map); - cout << origin.pos.ToString() ; -} + /** + * Exporting the center lines + */ + string laneLinesDetails = vectoMapPath + "point.csv"; + string center_lines_info = vectoMapPath + "dtlane.csv"; + string lane_info = vectoMapPath + "lane.csv"; + string node_info = vectoMapPath + "node.csv"; + string area_info = vectoMapPath + "area.csv"; + string line_info = vectoMapPath + "line.csv"; + string signal_info = vectoMapPath + "signaldata.csv"; + string stop_line_info = vectoMapPath + "stopline.csv"; + string vector_info = vectoMapPath + "vector.csv"; + string curb_info = vectoMapPath + "curb.csv"; + string roadedge_info = vectoMapPath + "roadedge.csv"; + string wayarea_info = vectoMapPath + "wayarea.csv"; + string crosswalk_info = vectoMapPath + "crosswalk.csv"; + string conn_info = vectoMapPath + "dataconnection.csv"; + string intersection_info = vectoMapPath + "intersection.csv"; + + cout << " >> Loading vector map data files ... " << endl; + AisanCenterLinesFileReader center_lanes(center_lines_info); + AisanLanesFileReader lanes(lane_info); + AisanPointsFileReader points(laneLinesDetails); + AisanNodesFileReader nodes(node_info); + AisanLinesFileReader lines(line_info); + AisanStopLineFileReader stop_line(stop_line_info); + AisanSignalFileReader signal(signal_info); + AisanVectorFileReader vec(vector_info); + AisanCurbFileReader curb(curb_info); + AisanRoadEdgeFileReader roadedge(roadedge_info); + AisanDataConnFileReader conn(conn_info); + AisanAreasFileReader areas(area_info); + AisanWayareaFileReader way_area(wayarea_info); + AisanCrossWalkFileReader cross_walk(crosswalk_info); + + + vector intersection_data; + vector nodes_data; + vector lanes_data; + vector points_data; + vector dt_data; + vector line_data; + vector stop_line_data; + vector signal_data; + vector vector_data; + vector curb_data; + vector roadedge_data; + vector area_data; + vector way_area_data; + vector crosswalk_data; + vector conn_data; + + + nodes.ReadAllData(nodes_data); + lanes.ReadAllData(lanes_data); + points.ReadAllData(points_data); + center_lanes.ReadAllData(dt_data); + lines.ReadAllData(line_data); + stop_line.ReadAllData(stop_line_data); + signal.ReadAllData(signal_data); + vec.ReadAllData(vector_data); + curb.ReadAllData(curb_data); + roadedge.ReadAllData(roadedge_data); + areas.ReadAllData(area_data); + way_area.ReadAllData(way_area_data); + cross_walk.ReadAllData(crosswalk_data); + conn.ReadAllData(conn_data); + + if(points_data.size() == 0) + { + std::cout << std::endl << "## Alert Can't Read Points Data from vector map files in path: " << vectoMapPath << std::endl; + return; + } -bool MappingHelpers::GetWayPoint(const int& id, const int& laneID,const double& refVel, const int& did, - const std::vector& dtpoints, - const std::vector& points, - const GPSPoint& origin, WayPoint& way_point) -{ - - for(unsigned int dtp =0; dtp < dtpoints.size(); dtp++) - { - if(dtpoints.at(dtp).DID == did) - { - for(unsigned int p =0; p < points.size(); p++) - { - if(dtpoints.at(dtp).PID == points.at(p).PID) - { - WayPoint wp; - wp.id = id; - wp.laneId = laneID; - wp.v = refVel; -// double integ_part = points.at(p).L; -// double deg = trunc(points.at(p).L); -// double min = trunc((points.at(p).L - deg) * 100.0) / 60.0; -// double sec = modf((points.at(p).L - deg) * 100.0, &integ_part)/36.0; -// double L = deg + min + sec; -// -// deg = trunc(points.at(p).B); -// min = trunc((points.at(p).B - deg) * 100.0) / 60.0; -// sec = modf((points.at(p).B - deg) * 100.0, &integ_part)/36.0; -// double B = deg + min + sec; + //Special Condtion to be able to pars old data structures + int bSpecialMap = 0; + + // use this to transform data to origin (0,0,0) + if(nodes_data.size() > 0 && bSpecialMap == 0) + { + ConstructRoadNetworkFromROSMessageV2(lanes_data, points_data, dt_data, intersection_data, area_data, + line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data, + way_area_data, crosswalk_data, nodes_data, conn_data, &lanes, &points, &nodes, &lines, + GetTransformationOrigin(0), map, false); + } + else + { + ConstructRoadNetworkFromROSMessage(lanes_data, points_data, dt_data, intersection_data, area_data, + line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data, + way_area_data, crosswalk_data, nodes_data, conn_data, + GetTransformationOrigin(0), map, bSpecialMap == 1); + } - wp.pos = GPSPoint(points.at(p).Ly + origin.x, points.at(p).Bx + origin.y, points.at(p).H + origin.z, dtpoints.at(dtp).Dir); + WayPoint origin = GetFirstWaypoint(map); + cout << origin.pos.ToString() ; +} - wp.pos.lat = points.at(p).L; - wp.pos.lon = points.at(p).B; - wp.pos.alt = points.at(p).H; - wp.pos.dir = dtpoints.at(dtp).Dir; - wp.iOriginalIndex = p; +bool MappingHelpers::GetWayPoint(const int& id, const int& laneID,const double& refVel, const int& did, + const std::vector& dtpoints, + const std::vector& points, + const GPSPoint& origin, WayPoint& way_point) +{ - way_point = wp; - return 1; - } - } - } - } + for(unsigned int dtp =0; dtp < dtpoints.size(); dtp++) + { + if(dtpoints.at(dtp).DID == did) + { + for(unsigned int p =0; p < points.size(); p++) + { + if(dtpoints.at(dtp).PID == points.at(p).PID) + { + WayPoint wp; + wp.id = id; + wp.laneId = laneID; + wp.v = refVel; +// double integ_part = points.at(p).L; +// double deg = trunc(points.at(p).L); +// double min = trunc((points.at(p).L - deg) * 100.0) / 60.0; +// double sec = modf((points.at(p).L - deg) * 100.0, &integ_part)/36.0; +// double L = deg + min + sec; +// +// deg = trunc(points.at(p).B); +// min = trunc((points.at(p).B - deg) * 100.0) / 60.0; +// sec = modf((points.at(p).B - deg) * 100.0, &integ_part)/36.0; +// double B = deg + min + sec; + + wp.pos = GPSPoint(points.at(p).Ly + origin.x, points.at(p).Bx + origin.y, points.at(p).H + origin.z, dtpoints.at(dtp).Dir); + + wp.pos.lat = points.at(p).L; + wp.pos.lon = points.at(p).B; + wp.pos.alt = points.at(p).H; + wp.pos.dir = dtpoints.at(dtp).Dir; + wp.iOriginalIndex = p; + + way_point = wp; + return 1; + } + } + } + } - return false; + return false; } void MappingHelpers::LoadKML(const std::string& kmlFile, RoadNetwork& map) { - //First, Get the main element - TiXmlElement* pHeadElem = 0; - TiXmlElement* pElem = 0; - - ifstream f(kmlFile.c_str()); - if(!f.good()) - { - cout << "Can't Open KML Map File: (" << kmlFile << ")" << endl; - return; - } - - std::cout << " >> Loading KML Map file ... " << std::endl; - - TiXmlDocument doc(kmlFile); - try - { - doc.LoadFile(); - } - catch(exception& e) - { - cout << "KML Custom Reader Error, Can't Load .kml File, path is: "<< kmlFile << endl; - cout << e.what() << endl; - return; - } - - - std::cout << " >> Reading Data from KML map file ... " << std::endl; - - pElem = doc.FirstChildElement(); - pHeadElem = GetHeadElement(pElem); - - std::cout << " >> Load Lanes from KML file .. " << std::endl; - vector laneLinksList = GetLanesList(pHeadElem); - - map.roadSegments.clear(); - map.roadSegments = GetRoadSegmentsList(pHeadElem); - - std::cout << " >> Load Traffic lights from KML file .. " << std::endl; - vector trafficLights = GetTrafficLightsList(pHeadElem); - - std::cout << " >> Load Stop lines from KML file .. " << std::endl; - vector stopLines = GetStopLinesList(pHeadElem); - - std::cout << " >> Load Signes from KML file .. " << std::endl; - vector signs = GetTrafficSignsList(pHeadElem); - - std::cout << " >> Load Crossings from KML file .. " << std::endl; - vector crossings = GetCrossingsList(pHeadElem); - - std::cout << " >> Load Markings from KML file .. " << std::endl; - vector markings = GetMarkingsList(pHeadElem); - - std::cout << " >> Load Road boundaries from KML file .. " << std::endl; - vector boundaries = GetBoundariesList(pHeadElem); - - std::cout << " >> Load Curbs from KML file .. " << std::endl; - vector curbs = GetCurbsList(pHeadElem); - - map.signs.clear(); - map.signs = signs; - - map.crossings.clear(); - map.crossings = crossings; - - map.markings.clear(); - map.markings = markings; - - map.boundaries.clear(); - map.boundaries = boundaries; - - map.curbs.clear(); - map.curbs = curbs; - - //Fill the relations - for(unsigned int i= 0; i> Link lanes and waypoints with pointers ... " << endl; - //Link Lanes and lane's waypoints by pointers - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - //Link Lanes - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) - { - pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->toIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) - { - pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - pL->points.at(j).pLane = pL; - } - } - } - - //Link waypoints - cout << " >> Link missing branches and waypoints... " << endl; - LinkMissingBranchingWayPointsV2(map); - - cout << " >> Link Lane change semantics ... " << endl; - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - if(pWP->pLeft == 0 && pWP->LeftPointId > 0) - { - pWP->pLeft = FindWaypointV2(pWP->LeftPointId, pWP->laneId, map); - - if(pWP->pLeft != nullptr) - { - pWP->LeftLnId = pWP->pLeft->laneId; - pWP->pLane->pLeftLane = pWP->pLeft->pLane; - - if(pWP->pLeft->RightPointId == pWP->id) - { - pWP->pLeft->pRight = pWP; - pWP->pLeft->RightLnId = pWP->laneId; - pWP->pLeft->pLane->pRightLane = pWP->pLane; - } - } - } - - if(pWP->pRight == 0 && pWP->RightPointId > 0) - { - pWP->pRight = FindWaypointV2(pWP->RightPointId, pWP->laneId, map); - - if(pWP->pRight != nullptr) - { - pWP->RightLnId = pWP->pRight->laneId; - pWP->pLane->pRightLane = pWP->pRight->pLane; - - if(pWP->pRight->LeftPointId == pWP->id) - { - pWP->pRight->pLeft = pWP; - pWP->pRight->LeftLnId = pWP->laneId; - pWP->pRight->pLane->pLeftLane = pWP->pLane; - } - } - } - } - } - } - - map.stopLines = stopLines; - map.trafficLights = trafficLights; - - //Link waypoints && StopLines - cout << " >> Link Stop lines and Traffic lights ... " << endl; - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - if(map.trafficLights.at(itl).CheckLane(map.roadSegments.at(rs).Lanes.at(i).id)) - { - map.trafficLights.at(itl).pLanes.push_back(&map.roadSegments.at(rs).Lanes.at(i)); - map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); - } - } - - for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) - { - if(map.stopLines.at(isl).laneId == map.roadSegments.at(rs).Lanes.at(i).id) - { - map.stopLines.at(isl).pLane = &map.roadSegments.at(rs).Lanes.at(i); - map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); - WayPoint wp((map.stopLines.at(isl).points.at(0).x+map.stopLines.at(isl).points.at(1).x)/2.0, (map.stopLines.at(isl).points.at(0).y+map.stopLines.at(isl).points.at(1).y)/2.0, (map.stopLines.at(isl).points.at(0).z+map.stopLines.at(isl).points.at(1).z)/2.0, (map.stopLines.at(isl).points.at(0).a+map.stopLines.at(isl).points.at(1).a)/2.0); - map.roadSegments.at(rs).Lanes.at(i).points.at(PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs).Lanes.at(i).points, wp)).stopLineID = map.stopLines.at(isl).id; - } - } - } - } - - cout << " >> Find Max IDs ... " << endl; - GetMapMaxIds(map); - - cout << "Map loaded from kml file with (" << laneLinksList.size() << ") lanes, First Point ( " << GetFirstWaypoint(map).pos.ToString() << ")"<< endl; + //First, Get the main element + TiXmlElement* pHeadElem = 0; + TiXmlElement* pElem = 0; + + ifstream f(kmlFile.c_str()); + if(!f.good()) + { + cout << "Can't Open KML Map File: (" << kmlFile << ")" << endl; + return; + } + + std::cout << " >> Loading KML Map file ... " << std::endl; + + TiXmlDocument doc(kmlFile); + try + { + doc.LoadFile(); + } + catch(exception& e) + { + cout << "KML Custom Reader Error, Can't Load .kml File, path is: "<< kmlFile << endl; + cout << e.what() << endl; + return; + } + + + std::cout << " >> Reading Data from KML map file ... " << std::endl; + + pElem = doc.FirstChildElement(); + pHeadElem = GetHeadElement(pElem); + + std::cout << " >> Load Lanes from KML file .. " << std::endl; + vector laneLinksList = GetLanesList(pHeadElem); + + map.roadSegments.clear(); + map.roadSegments = GetRoadSegmentsList(pHeadElem); + + std::cout << " >> Load Traffic lights from KML file .. " << std::endl; + vector trafficLights = GetTrafficLightsList(pHeadElem); + + std::cout << " >> Load Stop lines from KML file .. " << std::endl; + vector stopLines = GetStopLinesList(pHeadElem); + + std::cout << " >> Load Signes from KML file .. " << std::endl; + vector signs = GetTrafficSignsList(pHeadElem); + + std::cout << " >> Load Crossings from KML file .. " << std::endl; + vector crossings = GetCrossingsList(pHeadElem); + + std::cout << " >> Load Markings from KML file .. " << std::endl; + vector markings = GetMarkingsList(pHeadElem); + + std::cout << " >> Load Road boundaries from KML file .. " << std::endl; + vector boundaries = GetBoundariesList(pHeadElem); + + std::cout << " >> Load Curbs from KML file .. " << std::endl; + vector curbs = GetCurbsList(pHeadElem); + + map.signs.clear(); + map.signs = signs; + + map.crossings.clear(); + map.crossings = crossings; + + map.markings.clear(); + map.markings = markings; + + map.boundaries.clear(); + map.boundaries = boundaries; + + map.curbs.clear(); + map.curbs = curbs; + + //Fill the relations + for(unsigned int i= 0; i> Link lanes and waypoints with pointers ... " << endl; + //Link Lanes and lane's waypoints by pointers + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + //Link Lanes + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) + { + pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->toIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) + { + pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + pL->points.at(j).pLane = pL; + } + } + } + + //Link waypoints + cout << " >> Link missing branches and waypoints... " << endl; + LinkMissingBranchingWayPointsV2(map); + + cout << " >> Link Lane change semantics ... " << endl; + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + if(pWP->pLeft == 0 && pWP->LeftPointId > 0) + { + pWP->pLeft = FindWaypointV2(pWP->LeftPointId, pWP->laneId, map); + + if(pWP->pLeft != nullptr) + { + pWP->LeftLnId = pWP->pLeft->laneId; + pWP->pLane->pLeftLane = pWP->pLeft->pLane; + + if(pWP->pLeft->RightPointId == pWP->id) + { + pWP->pLeft->pRight = pWP; + pWP->pLeft->RightLnId = pWP->laneId; + pWP->pLeft->pLane->pRightLane = pWP->pLane; + } + } + } + + if(pWP->pRight == 0 && pWP->RightPointId > 0) + { + pWP->pRight = FindWaypointV2(pWP->RightPointId, pWP->laneId, map); + + if(pWP->pRight != nullptr) + { + pWP->RightLnId = pWP->pRight->laneId; + pWP->pLane->pRightLane = pWP->pRight->pLane; + + if(pWP->pRight->LeftPointId == pWP->id) + { + pWP->pRight->pLeft = pWP; + pWP->pRight->LeftLnId = pWP->laneId; + pWP->pRight->pLane->pLeftLane = pWP->pLane; + } + } + } + } + } + } + + map.stopLines = stopLines; + map.trafficLights = trafficLights; + + //Link waypoints && StopLines + cout << " >> Link Stop lines and Traffic lights ... " << endl; + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + if(map.trafficLights.at(itl).CheckLane(map.roadSegments.at(rs).Lanes.at(i).id)) + { + map.trafficLights.at(itl).pLanes.push_back(&map.roadSegments.at(rs).Lanes.at(i)); + map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); + } + } + + for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) + { + if(map.stopLines.at(isl).laneId == map.roadSegments.at(rs).Lanes.at(i).id) + { + map.stopLines.at(isl).pLane = &map.roadSegments.at(rs).Lanes.at(i); + map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); + WayPoint wp((map.stopLines.at(isl).points.at(0).x+map.stopLines.at(isl).points.at(1).x)/2.0, (map.stopLines.at(isl).points.at(0).y+map.stopLines.at(isl).points.at(1).y)/2.0, (map.stopLines.at(isl).points.at(0).z+map.stopLines.at(isl).points.at(1).z)/2.0, (map.stopLines.at(isl).points.at(0).a+map.stopLines.at(isl).points.at(1).a)/2.0); + map.roadSegments.at(rs).Lanes.at(i).points.at(PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs).Lanes.at(i).points, wp)).stopLineID = map.stopLines.at(isl).id; + } + } + } + } + + cout << " >> Find Max IDs ... " << endl; + GetMapMaxIds(map); + + cout << "Map loaded from kml file with (" << laneLinksList.size() << ") lanes, First Point ( " << GetFirstWaypoint(map).pos.ToString() << ")"<< endl; } TiXmlElement* MappingHelpers::GetHeadElement(TiXmlElement* pMainElem) { - TiXmlElement* pElem = pMainElem; - if(pElem) - pElem = pElem->FirstChildElement("Folder"); - if(pElem && pElem->FirstChildElement("Folder")) - pElem = pElem->FirstChildElement("Folder"); - if(pElem && pElem->FirstChildElement("Document")) - pElem = pElem->FirstChildElement("Document"); + TiXmlElement* pElem = pMainElem; + if(pElem) + pElem = pElem->FirstChildElement("Folder"); + if(pElem && pElem->FirstChildElement("Folder")) + pElem = pElem->FirstChildElement("Folder"); + if(pElem && pElem->FirstChildElement("Document")) + pElem = pElem->FirstChildElement("Document"); - if(!pElem) - { - return nullptr; - } - return pElem; + if(!pElem) + { + return nullptr; + } + return pElem; } TiXmlElement* MappingHelpers::GetDataFolder(const string& folderName, TiXmlElement* pMainElem) { - if(!pMainElem) return nullptr; + if(!pMainElem) return nullptr; - TiXmlElement* pElem = pMainElem->FirstChildElement("Folder"); + TiXmlElement* pElem = pMainElem->FirstChildElement("Folder"); - string folderID=""; - for(; pElem; pElem=pElem->NextSiblingElement()) - { - folderID=""; - if(pElem->FirstChildElement("name")->GetText()) //Map Name - folderID = pElem->FirstChildElement("name")->GetText(); - if(folderID.compare(folderName)==0) - return pElem; - } - return nullptr; + string folderID=""; + for(; pElem; pElem=pElem->NextSiblingElement()) + { + folderID=""; + if(pElem->FirstChildElement("name")->GetText()) //Map Name + folderID = pElem->FirstChildElement("name")->GetText(); + if(folderID.compare(folderName)==0) + return pElem; + } + return nullptr; } WayPoint* MappingHelpers::GetClosestWaypointFromMap(const WayPoint& pos, RoadNetwork& map, const bool bDirectionBased) { - double distance_to_nearest_lane = 1; - Lane* pLane = 0; - while(distance_to_nearest_lane < 100 && pLane == 0) - { - pLane = GetClosestLaneFromMap(pos, map, distance_to_nearest_lane, bDirectionBased); - distance_to_nearest_lane += 1; - } + double distance_to_nearest_lane = 1; + Lane* pLane = 0; + while(distance_to_nearest_lane < 100 && pLane == 0) + { + pLane = GetClosestLaneFromMap(pos, map, distance_to_nearest_lane, bDirectionBased); + distance_to_nearest_lane += 1; + } - if(!pLane) return nullptr; + if(!pLane) return nullptr; - int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLane->points, pos); + int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLane->points, pos); - return &pLane->points.at(closest_index); + return &pLane->points.at(closest_index); } vector MappingHelpers::GetClosestWaypointsListFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance, const bool bDirectionBased) { - vector pLanes = GetClosestLanesListFromMap(pos, map, distance, bDirectionBased); + vector pLanes = GetClosestLanesListFromMap(pos, map, distance, bDirectionBased); - vector waypoints_list; + vector waypoints_list; - if(pLanes.size() == 0) return waypoints_list; + if(pLanes.size() == 0) return waypoints_list; - for(unsigned int i = 0; i < pLanes.size(); i++) - { - if(pLanes.at(i)) - { - int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLanes.at(i)->points, pos); - waypoints_list.push_back(&pLanes.at(i)->points.at(closest_index)); - } - } + for(unsigned int i = 0; i < pLanes.size(); i++) + { + if(pLanes.at(i)) + { + int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLanes.at(i)->points, pos); + waypoints_list.push_back(&pLanes.at(i)->points.at(closest_index)); + } + } - return waypoints_list; + return waypoints_list; } WayPoint* MappingHelpers::GetClosestBackWaypointFromMap(const WayPoint& pos, RoadNetwork& map) { - double distance_to_nearest_lane = 1; - Lane* pLane = 0; - while(distance_to_nearest_lane < 100 && pLane == 0) - { - pLane = GetClosestLaneFromMap(pos, map, distance_to_nearest_lane); - distance_to_nearest_lane += 1; - } + double distance_to_nearest_lane = 1; + Lane* pLane = 0; + while(distance_to_nearest_lane < 100 && pLane == 0) + { + pLane = GetClosestLaneFromMap(pos, map, distance_to_nearest_lane); + distance_to_nearest_lane += 1; + } - if(!pLane) return nullptr; + if(!pLane) return nullptr; - int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLane->points, pos); + int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(pLane->points, pos); - if(closest_index>2) - return &pLane->points.at(closest_index-3); - else if(closest_index>1) - return &pLane->points.at(closest_index-2); - else if(closest_index>0) - return &pLane->points.at(closest_index-1); - else - return &pLane->points.at(closest_index); + if(closest_index>2) + return &pLane->points.at(closest_index-3); + else if(closest_index>1) + return &pLane->points.at(closest_index-2); + else if(closest_index>0) + return &pLane->points.at(closest_index-1); + else + return &pLane->points.at(closest_index); } std::vector MappingHelpers::GetClosestLanesFast(const WayPoint& center, RoadNetwork& map, const double& distance) { - vector lanesList; - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - Lane* pL = &map.roadSegments.at(j).Lanes.at(k); - int index = PlanningHelpers::GetClosestNextPointIndexFast(pL->points, center); + vector lanesList; + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + Lane* pL = &map.roadSegments.at(j).Lanes.at(k); + int index = PlanningHelpers::GetClosestNextPointIndexFast(pL->points, center); - if(index < 0 || index >= pL->points.size()) continue; + if(index < 0 || index >= pL->points.size()) continue; - double d = hypot(pL->points.at(index).pos.y - center.pos.y, pL->points.at(index).pos.x - center.pos.x); - if(d <= distance) - lanesList.push_back(pL); - } - } + double d = hypot(pL->points.at(index).pos.y - center.pos.y, pL->points.at(index).pos.x - center.pos.x); + if(d <= distance) + lanesList.push_back(pL); + } + } - return lanesList; + return lanesList; } Lane* MappingHelpers::GetClosestLaneFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance, const bool bDirectionBased) { - vector > laneLinksList; - double d = 0; - double min_d = DBL_MAX; - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - //Lane* pLane = &pEdge->lanes.at(k); - d = 0; - min_d = DBL_MAX; - for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) - { - - d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); - if(d < min_d) - min_d = d; - } - - if(min_d < distance) - laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k))); - } - } - - if(laneLinksList.size() == 0) return nullptr; - - min_d = DBL_MAX; - Lane* closest_lane = 0; - for(unsigned int i = 0; i < laneLinksList.size(); i++) - { - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->points, pos, info); - - if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) - continue; - - if(bDirectionBased && fabs(info.perp_distance) < min_d && fabs(info.angle_diff) < 45) - { - min_d = fabs(info.perp_distance); - closest_lane = laneLinksList.at(i).second; - } - else if(!bDirectionBased && fabs(info.perp_distance) < min_d) - { - min_d = fabs(info.perp_distance); - closest_lane = laneLinksList.at(i).second; - } - } - - return closest_lane; + vector > laneLinksList; + double d = 0; + double min_d = DBL_MAX; + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + //Lane* pLane = &pEdge->lanes.at(k); + d = 0; + min_d = DBL_MAX; + for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) + { + + d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); + if(d < min_d) + min_d = d; + } + + if(min_d < distance) + laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k))); + } + } + + if(laneLinksList.size() == 0) return nullptr; + + min_d = DBL_MAX; + Lane* closest_lane = 0; + for(unsigned int i = 0; i < laneLinksList.size(); i++) + { + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->points, pos, info); + + if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) + continue; + + if(bDirectionBased && fabs(info.perp_distance) < min_d && fabs(info.angle_diff) < 45) + { + min_d = fabs(info.perp_distance); + closest_lane = laneLinksList.at(i).second; + } + else if(!bDirectionBased && fabs(info.perp_distance) < min_d) + { + min_d = fabs(info.perp_distance); + closest_lane = laneLinksList.at(i).second; + } + } + + return closest_lane; } vector MappingHelpers::GetClosestLanesListFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance, const bool bDirectionBased) { - vector > laneLinksList; - double d = 0; - double min_d = DBL_MAX; - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - //Lane* pLane = &pEdge->lanes.at(k); - d = 0; - min_d = DBL_MAX; - for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) - { - - d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); - if(d < min_d) - min_d = d; - } - - if(min_d < distance) - laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k))); - } - } - - vector closest_lanes; - if(laneLinksList.size() == 0) return closest_lanes; - - - for(unsigned int i = 0; i < laneLinksList.size(); i++) - { - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->points, pos, info); - - if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) - continue; - - if(bDirectionBased && fabs(info.perp_distance) < distance && fabs(info.angle_diff) < 30) - { - closest_lanes.push_back(laneLinksList.at(i).second); - } - else if(!bDirectionBased && fabs(info.perp_distance) < distance) - { - closest_lanes.push_back(laneLinksList.at(i).second); - } - } - - return closest_lanes; + vector > laneLinksList; + double d = 0; + double min_d = DBL_MAX; + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + //Lane* pLane = &pEdge->lanes.at(k); + d = 0; + min_d = DBL_MAX; + for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) + { + + d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); + if(d < min_d) + min_d = d; + } + + if(min_d < distance) + laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k))); + } + } + + vector closest_lanes; + if(laneLinksList.size() == 0) return closest_lanes; + + + for(unsigned int i = 0; i < laneLinksList.size(); i++) + { + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->points, pos, info); + + if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) + continue; + + if(bDirectionBased && fabs(info.perp_distance) < distance && fabs(info.angle_diff) < 30) + { + closest_lanes.push_back(laneLinksList.at(i).second); + } + else if(!bDirectionBased && fabs(info.perp_distance) < distance) + { + closest_lanes.push_back(laneLinksList.at(i).second); + } + } + + return closest_lanes; } Lane* MappingHelpers::GetClosestLaneFromMapDirectionBased(const WayPoint& pos, RoadNetwork& map, const double& distance) { - vector > laneLinksList; - double d = 0; - double min_d = DBL_MAX; - int min_i = 0; - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - //Lane* pLane = &pEdge->lanes.at(k); - d = 0; - min_d = DBL_MAX; - for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) - { - - d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); - if(d < min_d) - { - min_d = d; - min_i = pindex; - } - } - - if(min_d < distance) - laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k).points.at(min_i))); - } - } - - if(laneLinksList.size() == 0) return nullptr; - - min_d = DBL_MAX; - Lane* closest_lane = 0; - double a_diff = 0; - for(unsigned int i = 0; i < laneLinksList.size(); i++) - { - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->pLane->points, pos, info); - if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) - continue; - - a_diff = UtilityH::AngleBetweenTwoAnglesPositive(laneLinksList.at(i).second->pos.a, pos.pos.a); - - if(fabs(info.perp_distance)pLane; - } - } - - return closest_lane; + vector > laneLinksList; + double d = 0; + double min_d = DBL_MAX; + int min_i = 0; + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + //Lane* pLane = &pEdge->lanes.at(k); + d = 0; + min_d = DBL_MAX; + for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) + { + + d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); + if(d < min_d) + { + min_d = d; + min_i = pindex; + } + } + + if(min_d < distance) + laneLinksList.push_back(make_pair(min_d, &map.roadSegments.at(j).Lanes.at(k).points.at(min_i))); + } + } + + if(laneLinksList.size() == 0) return nullptr; + + min_d = DBL_MAX; + Lane* closest_lane = 0; + double a_diff = 0; + for(unsigned int i = 0; i < laneLinksList.size(); i++) + { + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(laneLinksList.at(i).second->pLane->points, pos, info); + if(info.perp_distance == 0 && laneLinksList.at(i).first != 0) + continue; + + a_diff = UtilityH::AngleBetweenTwoAnglesPositive(laneLinksList.at(i).second->pos.a, pos.pos.a); + + if(fabs(info.perp_distance)pLane; + } + } + + return closest_lane; } std::vector MappingHelpers::GetClosestMultipleLanesFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance) { - vector lanesList; - double d = 0; - double a_diff = 0; - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) - { - d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); - a_diff = UtilityH::AngleBetweenTwoAnglesPositive(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos.a, pos.pos.a); - - if(d <= distance && a_diff <= M_PI_4) - { - bool bLaneExist = false; - for(unsigned int il = 0; il < lanesList.size(); il++) - { - if(lanesList.at(il)->id == map.roadSegments.at(j).Lanes.at(k).id) - { - bLaneExist = true; - break; - } - } - - if(!bLaneExist) - lanesList.push_back(&map.roadSegments.at(j).Lanes.at(k)); - - break; - } - } - } - } - - return lanesList; + vector lanesList; + double d = 0; + double a_diff = 0; + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) + { + d = distance2points(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos, pos.pos); + a_diff = UtilityH::AngleBetweenTwoAnglesPositive(map.roadSegments.at(j).Lanes.at(k).points.at(pindex).pos.a, pos.pos.a); + + if(d <= distance && a_diff <= M_PI_4) + { + bool bLaneExist = false; + for(unsigned int il = 0; il < lanesList.size(); il++) + { + if(lanesList.at(il)->id == map.roadSegments.at(j).Lanes.at(k).id) + { + bLaneExist = true; + break; + } + } + + if(!bLaneExist) + lanesList.push_back(&map.roadSegments.at(j).Lanes.at(k)); + + break; + } + } + } + } + + return lanesList; } WayPoint MappingHelpers::GetFirstWaypoint(RoadNetwork& map) { - for(unsigned int j=0; j< map.roadSegments.size(); j ++) - { - for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) - { - for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) - { - WayPoint fp = map.roadSegments.at(j).Lanes.at(k).points.at(pindex); - return fp; - } - } - } + for(unsigned int j=0; j< map.roadSegments.size(); j ++) + { + for(unsigned int k=0; k< map.roadSegments.at(j).Lanes.size(); k ++) + { + for(unsigned int pindex=0; pindex< map.roadSegments.at(j).Lanes.at(k).points.size(); pindex ++) + { + WayPoint fp = map.roadSegments.at(j).Lanes.at(k).points.at(pindex); + return fp; + } + } + } - return WayPoint(); + return WayPoint(); } WayPoint* MappingHelpers::GetLastWaypoint(RoadNetwork& map) { - if(map.roadSegments.size() > 0 && map.roadSegments.at(map.roadSegments.size()-1).Lanes.size() > 0) - { - std::vector* lanes = &map.roadSegments.at(map.roadSegments.size()-1).Lanes; - if(lanes->at(lanes->size()-1).points.size() > 0) - return &lanes->at(lanes->size()-1).points.at(lanes->at(lanes->size()-1).points.size()-1); - } + if(map.roadSegments.size() > 0 && map.roadSegments.at(map.roadSegments.size()-1).Lanes.size() > 0) + { + std::vector* lanes = &map.roadSegments.at(map.roadSegments.size()-1).Lanes; + if(lanes->at(lanes->size()-1).points.size() > 0) + return &lanes->at(lanes->size()-1).points.at(lanes->at(lanes->size()-1).points.size()-1); + } - return nullptr; + return nullptr; } void MappingHelpers::GetUniqueNextLanes(const Lane* l, const vector& traversed_lanes, vector& lanes_list) { - if(!l) return; + if(!l) return; - for(unsigned int i=0; i< l->toLanes.size(); i++) - { - bool bFound = false; - for(unsigned int j = 0; j < traversed_lanes.size(); j++) - if(l->toLanes.at(i)->id == traversed_lanes.at(j)->id) - { - bFound = true; - break; - } - - if(!bFound) - lanes_list.push_back(l->toLanes.at(i)); - } + for(unsigned int i=0; i< l->toLanes.size(); i++) + { + bool bFound = false; + for(unsigned int j = 0; j < traversed_lanes.size(); j++) + if(l->toLanes.at(i)->id == traversed_lanes.at(j)->id) + { + bFound = true; + break; + } + + if(!bFound) + lanes_list.push_back(l->toLanes.at(i)); + } } Lane* MappingHelpers::GetLaneFromPath(const WayPoint& currPos, const std::vector& currPath) { - if(currPath.size() < 1) return nullptr; + if(currPath.size() < 1) return nullptr; - int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(currPath, currPos); + int closest_index = PlanningHelpers::GetClosestNextPointIndexFast(currPath, currPos); - return currPath.at(closest_index).pLane; + return currPath.at(closest_index).pLane; } std::vector MappingHelpers::GetCurbsList(TiXmlElement* pElem) { - vector cList; - TiXmlElement* pCurbs = GetDataFolder("CurbsLines", pElem); - if(!pCurbs) - return cList; - - TiXmlElement* pE = pCurbs->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml = pE->FirstChildElement("name"); - - if(pNameXml) - { - tfID = pNameXml->GetText(); - Curb c; - c.id = GetIDsFromPrefix(tfID, "BID", "LnID").at(0); - c.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); - c.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); + vector cList; + TiXmlElement* pCurbs = GetDataFolder("CurbsLines", pElem); + if(!pCurbs) + return cList; - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - c.points = GetPointsData(pPoints); - - cList.push_back(c); - } - } + TiXmlElement* pE = pCurbs->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml = pE->FirstChildElement("name"); + + if(pNameXml) + { + tfID = pNameXml->GetText(); + Curb c; + c.id = GetIDsFromPrefix(tfID, "BID", "LnID").at(0); + c.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); + c.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); + + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + c.points = GetPointsData(pPoints); + + cList.push_back(c); + } + } - return cList; + return cList; } std::vector MappingHelpers::GetBoundariesList(TiXmlElement* pElem) { - vector bList; - TiXmlElement* pBoundaries = GetDataFolder("Boundaries", pElem); - if(!pBoundaries) - return bList; + vector bList; + TiXmlElement* pBoundaries = GetDataFolder("Boundaries", pElem); + if(!pBoundaries) + return bList; - TiXmlElement* pE = pBoundaries->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml = pE->FirstChildElement("name"); + TiXmlElement* pE = pBoundaries->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml = pE->FirstChildElement("name"); - if(pNameXml) - { - tfID = pNameXml->GetText(); - Boundary b; - b.id = GetIDsFromPrefix(tfID, "BID", "RdID").at(0); - b.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); + if(pNameXml) + { + tfID = pNameXml->GetText(); + Boundary b; + b.id = GetIDsFromPrefix(tfID, "BID", "RdID").at(0); + b.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - b.points = GetPointsData(pPoints); + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + b.points = GetPointsData(pPoints); - bList.push_back(b); - } - } + bList.push_back(b); + } + } - return bList; + return bList; } std::vector MappingHelpers::GetMarkingsList(TiXmlElement* pElem) { - vector mList; - TiXmlElement* pMarkings= GetDataFolder("Markings", pElem); - if(!pMarkings) - return mList; - - TiXmlElement* pE = pMarkings->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("name"); - - if(pNameXml) - { - tfID = pNameXml->GetText(); - Marking m; - m.id = GetIDsFromPrefix(tfID, "MID", "LnID").at(0); - m.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); - m.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); - - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - - m.points = GetPointsData(pPoints); - - if(m.points.size() > 0) - { - //first item is the center of the marking - m.center = m.points.at(0); - m.points.erase(m.points.begin()+0); - } + vector mList; + TiXmlElement* pMarkings= GetDataFolder("Markings", pElem); + if(!pMarkings) + return mList; - mList.push_back(m); - } - } + TiXmlElement* pE = pMarkings->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("name"); + + if(pNameXml) + { + tfID = pNameXml->GetText(); + Marking m; + m.id = GetIDsFromPrefix(tfID, "MID", "LnID").at(0); + m.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); + m.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); + + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + + m.points = GetPointsData(pPoints); + + if(m.points.size() > 0) + { + //first item is the center of the marking + m.center = m.points.at(0); + m.points.erase(m.points.begin()+0); + } + + mList.push_back(m); + } + } - return mList; + return mList; } std::vector MappingHelpers::GetCrossingsList(TiXmlElement* pElem) { - vector crossList; - TiXmlElement* pCrossings= GetDataFolder("Crossings", pElem); + vector crossList; + TiXmlElement* pCrossings= GetDataFolder("Crossings", pElem); - if(!pCrossings) - return crossList; + if(!pCrossings) + return crossList; - TiXmlElement* pE = pCrossings->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("name"); + TiXmlElement* pE = pCrossings->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("name"); - if(pNameXml) - { - tfID = pNameXml->GetText(); - Crossing cross; - cross.id = GetIDsFromPrefix(tfID, "CRID", "RdID").at(0); - cross.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); + if(pNameXml) + { + tfID = pNameXml->GetText(); + Crossing cross; + cross.id = GetIDsFromPrefix(tfID, "CRID", "RdID").at(0); + cross.roadId = GetIDsFromPrefix(tfID, "RdID", "").at(0); - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - cross.points = GetPointsData(pPoints); + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + cross.points = GetPointsData(pPoints); - crossList.push_back(cross); - } - } + crossList.push_back(cross); + } + } - return crossList; + return crossList; } std::vector MappingHelpers::GetTrafficSignsList(TiXmlElement* pElem) { - vector tsList; - TiXmlElement* pSigns = GetDataFolder("TrafficSigns", pElem); - - if(!pSigns) - return tsList; - - TiXmlElement* pE = pSigns->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("name"); - - if(pNameXml) - { - tfID = pNameXml->GetText(); - - TrafficSign ts; - ts.id = GetIDsFromPrefix(tfID, "TSID", "LnID").at(0); - ts.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); - ts.roadId = GetIDsFromPrefix(tfID, "RdID", "Type").at(0); - int iType = GetIDsFromPrefix(tfID, "Type", "").at(0); - switch(iType) - { - case 0: - ts.signType = UNKNOWN_SIGN; - break; - case 1: - ts.signType = STOP_SIGN; - break; - case 2: - ts.signType = MAX_SPEED_SIGN; - break; - case 3: - ts.signType = MIN_SPEED_SIGN; - break; - default: - ts.signType = STOP_SIGN; - break; - } - - - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - ts.pos = GetPointsData(pPoints).at(0); - - tsList.push_back(ts); - } - } - - return tsList; + vector tsList; + TiXmlElement* pSigns = GetDataFolder("TrafficSigns", pElem); + + if(!pSigns) + return tsList; + + TiXmlElement* pE = pSigns->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("name"); + + if(pNameXml) + { + tfID = pNameXml->GetText(); + + TrafficSign ts; + ts.id = GetIDsFromPrefix(tfID, "TSID", "LnID").at(0); + ts.laneId = GetIDsFromPrefix(tfID, "LnID", "RdID").at(0); + ts.roadId = GetIDsFromPrefix(tfID, "RdID", "Type").at(0); + int iType = GetIDsFromPrefix(tfID, "Type", "").at(0); + switch(iType) + { + case 0: + ts.signType = UNKNOWN_SIGN; + break; + case 1: + ts.signType = STOP_SIGN; + break; + case 2: + ts.signType = MAX_SPEED_SIGN; + break; + case 3: + ts.signType = MIN_SPEED_SIGN; + break; + default: + ts.signType = STOP_SIGN; + break; + } + + + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + ts.pos = GetPointsData(pPoints).at(0); + + tsList.push_back(ts); + } + } + + return tsList; } std::vector MappingHelpers::GetStopLinesList(TiXmlElement* pElem) { - vector slList; - TiXmlElement* pStopLines = GetDataFolder("StopLines", pElem); + vector slList; + TiXmlElement* pStopLines = GetDataFolder("StopLines", pElem); - if(!pStopLines) - return slList; + if(!pStopLines) + return slList; - TiXmlElement* pE = pStopLines->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("name"); + TiXmlElement* pE = pStopLines->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("name"); - if(pNameXml) - { - tfID = pNameXml->GetText(); + if(pNameXml) + { + tfID = pNameXml->GetText(); - StopLine sl; - sl.id = GetIDsFromPrefix(tfID, "SLID", "LnID").at(0); - sl.laneId = GetIDsFromPrefix(tfID, "LnID", "TSID").at(0); - sl.stopSignID = GetIDsFromPrefix(tfID, "TSID", "TLID").at(0); - sl.trafficLightID = GetIDsFromPrefix(tfID, "TLID", "").at(0); + StopLine sl; + sl.id = GetIDsFromPrefix(tfID, "SLID", "LnID").at(0); + sl.laneId = GetIDsFromPrefix(tfID, "LnID", "TSID").at(0); + sl.stopSignID = GetIDsFromPrefix(tfID, "TSID", "TLID").at(0); + sl.trafficLightID = GetIDsFromPrefix(tfID, "TLID", "").at(0); - TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); - sl.points = GetPointsData(pPoints); + TiXmlElement* pPoints = pE->FirstChildElement("LineString")->FirstChildElement("coordinates"); + sl.points = GetPointsData(pPoints); - slList.push_back(sl); - } - } + slList.push_back(sl); + } + } - return slList; + return slList; } std::vector MappingHelpers::GetTrafficLightsList(TiXmlElement* pElem) { - vector tlList; - TiXmlElement* pLightsLines = GetDataFolder("TrafficLights", pElem); + vector tlList; + TiXmlElement* pLightsLines = GetDataFolder("TrafficLights", pElem); - if(!pLightsLines) - return tlList; + if(!pLightsLines) + return tlList; - TiXmlElement* pE = pLightsLines->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("name"); + TiXmlElement* pE = pLightsLines->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("name"); - if(pNameXml) - { - tfID = pNameXml->GetText(); + if(pNameXml) + { + tfID = pNameXml->GetText(); - TrafficLight tl; - tl.id = GetIDsFromPrefix(tfID, "TLID", "LnID").at(0); - tl.laneIds = GetIDsFromPrefix(tfID, "LnID", ""); + TrafficLight tl; + tl.id = GetIDsFromPrefix(tfID, "TLID", "LnID").at(0); + tl.laneIds = GetIDsFromPrefix(tfID, "LnID", ""); - TiXmlElement* pPoints = pE->FirstChildElement("Point")->FirstChildElement("coordinates"); - tl.pos = GetPointsData(pPoints).at(0); + TiXmlElement* pPoints = pE->FirstChildElement("Point")->FirstChildElement("coordinates"); + tl.pos = GetPointsData(pPoints).at(0); - tlList.push_back(tl); - } - } + tlList.push_back(tl); + } + } - return tlList; + return tlList; } vector MappingHelpers::GetLanesList(TiXmlElement* pElem) { - vector llList; - TiXmlElement* pLaneLinks = GetDataFolder("Lanes", pElem); - - if(!pLaneLinks) - return llList; + vector llList; + TiXmlElement* pLaneLinks = GetDataFolder("Lanes", pElem); - TiXmlElement* pE = pLaneLinks->FirstChildElement("Folder"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("description"); - if(pNameXml) - { - tfID = pNameXml->GetText(); + if(!pLaneLinks) + return llList; - Lane ll; - ll.id = GetIDsFromPrefix(tfID, "LID", "RSID").at(0); - ll.roadId = GetIDsFromPrefix(tfID, "RSID", "NUM").at(0); - ll.num = GetIDsFromPrefix(tfID, "NUM", "From").at(0); - ll.fromIds = GetIDsFromPrefix(tfID, "From", "To"); - ll.toIds = GetIDsFromPrefix(tfID, "To", "Vel"); - ll.speed = GetIDsFromPrefix(tfID, "Vel", "").at(0); - if(m_USING_VER_ZERO == 1) - ll.points = GetCenterLaneDataVer0(pE, ll.id); - else - ll.points = GetCenterLaneData(pE, ll.id); - - llList.push_back(ll); - } - } + TiXmlElement* pE = pLaneLinks->FirstChildElement("Folder"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("description"); + if(pNameXml) + { + tfID = pNameXml->GetText(); + + Lane ll; + ll.id = GetIDsFromPrefix(tfID, "LID", "RSID").at(0); + ll.roadId = GetIDsFromPrefix(tfID, "RSID", "NUM").at(0); + ll.num = GetIDsFromPrefix(tfID, "NUM", "From").at(0); + ll.fromIds = GetIDsFromPrefix(tfID, "From", "To"); + ll.toIds = GetIDsFromPrefix(tfID, "To", "Vel"); + ll.speed = GetIDsFromPrefix(tfID, "Vel", "").at(0); + if(m_USING_VER_ZERO == 1) + ll.points = GetCenterLaneDataVer0(pE, ll.id); + else + ll.points = GetCenterLaneData(pE, ll.id); + + llList.push_back(ll); + } + } - return llList; + return llList; } vector MappingHelpers::GetRoadSegmentsList(TiXmlElement* pElem) { - vector rlList; - TiXmlElement* pRoadLinks = GetDataFolder("RoadSegments", pElem); - - if(!pRoadLinks) - return rlList; + vector rlList; + TiXmlElement* pRoadLinks = GetDataFolder("RoadSegments", pElem); - TiXmlElement* pE = pRoadLinks->FirstChildElement("Placemark"); - for( ; pE; pE=pE->NextSiblingElement()) - { - string tfID; - TiXmlElement* pNameXml =pE->FirstChildElement("description"); - if(pNameXml) - tfID = pNameXml->GetText(); + if(!pRoadLinks) + return rlList; - RoadSegment rl; - rl.id = GetIDsFromPrefix(tfID, "RSID", "").at(0); - rlList.push_back(rl); - } + TiXmlElement* pE = pRoadLinks->FirstChildElement("Placemark"); + for( ; pE; pE=pE->NextSiblingElement()) + { + string tfID; + TiXmlElement* pNameXml =pE->FirstChildElement("description"); + if(pNameXml) + tfID = pNameXml->GetText(); + + RoadSegment rl; + rl.id = GetIDsFromPrefix(tfID, "RSID", "").at(0); + rlList.push_back(rl); + } - return rlList; + return rlList; } std::vector MappingHelpers::GetPointsData(TiXmlElement* pElem) { - std::vector points; - if(pElem) - { - string coordinate_list; - if(!pElem->NoChildren()) - coordinate_list = pElem->GetText(); + std::vector points; + if(pElem) + { + string coordinate_list; + if(!pElem->NoChildren()) + coordinate_list = pElem->GetText(); - istringstream str_stream(coordinate_list); - string token, temp; + istringstream str_stream(coordinate_list); + string token, temp; - while(getline(str_stream, token, ' ')) - { - string lat, lon, alt; - double numLat=0, numLon=0, numAlt=0; + while(getline(str_stream, token, ' ')) + { + string lat, lon, alt; + double numLat=0, numLon=0, numAlt=0; - istringstream ss(token); + istringstream ss(token); - getline(ss, lat, ','); - getline(ss, lon, ','); - getline(ss, alt, ','); + getline(ss, lat, ','); + getline(ss, lon, ','); + getline(ss, alt, ','); - numLat = atof(lat.c_str()); - numLon = atof(lon.c_str()); - numAlt = atof(alt.c_str()); + numLat = atof(lat.c_str()); + numLon = atof(lon.c_str()); + numAlt = atof(alt.c_str()); - GPSPoint p; + GPSPoint p; - p.x = p.lat = numLat; - p.y = p.lon = numLon; - p.z = p.alt = numAlt; - points.push_back(p); - } - } + p.x = p.lat = numLat; + p.y = p.lon = numLon; + p.z = p.alt = numAlt; + points.push_back(p); + } + } - return points; + return points; } vector MappingHelpers::GetCenterLaneData(TiXmlElement* pElem, const int& currLaneID) { - vector gps_points; - - TiXmlElement* pV = pElem->FirstChildElement("Placemark"); - - if(pV) - pV = pV->FirstChildElement("LineString"); - - if(pV) - pV = pV->FirstChildElement("coordinates"); - - if(pV) - { - string coordinate_list; - if(!pV->NoChildren()) - coordinate_list = pV->GetText(); - - istringstream str_stream(coordinate_list); - string token, temp; - - - while(getline(str_stream, token, ' ')) - { - string lat, lon, alt; - double numLat=0, numLon=0, numAlt=0; - - istringstream ss(token); - - getline(ss, lat, ','); - getline(ss, lon, ','); - getline(ss, alt, ','); + vector gps_points; - numLat = atof(lat.c_str()); - numLon = atof(lon.c_str()); - numAlt = atof(alt.c_str()); + TiXmlElement* pV = pElem->FirstChildElement("Placemark"); - WayPoint wp; + if(pV) + pV = pV->FirstChildElement("LineString"); - wp.pos.x = wp.pos.lat = numLat; - wp.pos.y = wp.pos.lon = numLon; - wp.pos.z = wp.pos.alt = numAlt; + if(pV) + pV = pV->FirstChildElement("coordinates"); - wp.laneId = currLaneID; - gps_points.push_back(wp); - } - - TiXmlElement* pInfoEl =pElem->FirstChildElement("Folder")->FirstChildElement("description"); - string additional_info; - if(pInfoEl) - additional_info = pInfoEl->GetText(); - additional_info.insert(additional_info.begin(), ','); - additional_info.erase(additional_info.end()-1); - vector add_info_list = SplitString(additional_info, ","); - if(gps_points.size() == add_info_list.size()) - { - for(unsigned int i=0; i< gps_points.size(); i++) - { - gps_points.at(i).id = GetIDsFromPrefix(add_info_list.at(i), "WPID", "AC").at(0); - gps_points.at(i).actionCost.push_back(GetActionPairFromPrefix(add_info_list.at(i), "AC", "From")); - gps_points.at(i).fromIds = GetIDsFromPrefix(add_info_list.at(i), "From", "To"); - gps_points.at(i).toIds = GetIDsFromPrefix(add_info_list.at(i), "To", "Lid"); + if(pV) + { + string coordinate_list; + if(!pV->NoChildren()) + coordinate_list = pV->GetText(); + + istringstream str_stream(coordinate_list); + string token, temp; + + + while(getline(str_stream, token, ' ')) + { + string lat, lon, alt; + double numLat=0, numLon=0, numAlt=0; + + istringstream ss(token); + + getline(ss, lat, ','); + getline(ss, lon, ','); + getline(ss, alt, ','); + + numLat = atof(lat.c_str()); + numLon = atof(lon.c_str()); + numAlt = atof(alt.c_str()); + + WayPoint wp; + + wp.pos.x = wp.pos.lat = numLat; + wp.pos.y = wp.pos.lon = numLon; + wp.pos.z = wp.pos.alt = numAlt; + + wp.laneId = currLaneID; + gps_points.push_back(wp); + } + + TiXmlElement* pInfoEl =pElem->FirstChildElement("Folder")->FirstChildElement("description"); + string additional_info; + if(pInfoEl) + additional_info = pInfoEl->GetText(); + additional_info.insert(additional_info.begin(), ','); + additional_info.erase(additional_info.end()-1); + vector add_info_list = SplitString(additional_info, ","); + if(gps_points.size() == add_info_list.size()) + { + for(unsigned int i=0; i< gps_points.size(); i++) + { + gps_points.at(i).id = GetIDsFromPrefix(add_info_list.at(i), "WPID", "AC").at(0); + gps_points.at(i).actionCost.push_back(GetActionPairFromPrefix(add_info_list.at(i), "AC", "From")); + gps_points.at(i).fromIds = GetIDsFromPrefix(add_info_list.at(i), "From", "To"); + gps_points.at(i).toIds = GetIDsFromPrefix(add_info_list.at(i), "To", "Lid"); + + vector ids = GetIDsFromPrefix(add_info_list.at(i), "Lid", "Rid"); + if(ids.size() > 0) + gps_points.at(i).LeftPointId = ids.at(0); + + ids = GetIDsFromPrefix(add_info_list.at(i), "Rid", "Vel"); + if(ids.size() > 0) + gps_points.at(i).RightPointId = ids.at(0); + + vector dnums = GetDoubleFromPrefix(add_info_list.at(i), "Vel", "Dir"); + if(dnums.size() > 0) + gps_points.at(i).v = dnums.at(0); + + dnums = GetDoubleFromPrefix(add_info_list.at(i), "Dir", ""); + if(dnums.size() > 0) + gps_points.at(i).pos.a = gps_points.at(i).pos.dir = dnums.at(0); + } + } + } - vector ids = GetIDsFromPrefix(add_info_list.at(i), "Lid", "Rid"); - if(ids.size() > 0) - gps_points.at(i).LeftPointId = ids.at(0); + return gps_points; +} - ids = GetIDsFromPrefix(add_info_list.at(i), "Rid", "Vel"); - if(ids.size() > 0) - gps_points.at(i).RightPointId = ids.at(0); +vector MappingHelpers::GetCenterLaneDataVer0(TiXmlElement* pElem, const int& currLaneID) +{ + vector gps_points; - vector dnums = GetDoubleFromPrefix(add_info_list.at(i), "Vel", "Dir"); - if(dnums.size() > 0) - gps_points.at(i).v = dnums.at(0); + TiXmlElement* pV = pElem->FirstChildElement("Placemark"); - dnums = GetDoubleFromPrefix(add_info_list.at(i), "Dir", ""); - if(dnums.size() > 0) - gps_points.at(i).pos.a = gps_points.at(i).pos.dir = dnums.at(0); - } - } - } + if(pV) + pV = pV->FirstChildElement("LineString"); - return gps_points; -} + if(pV) + pV = pV->FirstChildElement("coordinates"); -vector MappingHelpers::GetCenterLaneDataVer0(TiXmlElement* pElem, const int& currLaneID) -{ - vector gps_points; - - TiXmlElement* pV = pElem->FirstChildElement("Placemark"); - - if(pV) - pV = pV->FirstChildElement("LineString"); - - if(pV) - pV = pV->FirstChildElement("coordinates"); - - if(pV) - { - string coordinate_list; - if(!pV->NoChildren()) - coordinate_list = pV->GetText(); - - istringstream str_stream(coordinate_list); - string token, temp; - - - while(getline(str_stream, token, ' ')) - { - string lat, lon, alt; - double numLat=0, numLon=0, numAlt=0; - - istringstream ss(token); - - getline(ss, lat, ','); - getline(ss, lon, ','); - getline(ss, alt, ','); - - numLat = atof(lat.c_str()); - numLon = atof(lon.c_str()); - numAlt = atof(alt.c_str()); - - WayPoint wp; - - wp.pos.x = wp.pos.lat = numLat; - wp.pos.y = wp.pos.lon = numLon; - wp.pos.z = wp.pos.alt = numAlt; - - wp.laneId = currLaneID; - gps_points.push_back(wp); - } - - TiXmlElement* pInfoEl =pElem->FirstChildElement("Folder")->FirstChildElement("description"); - string additional_info; - if(pInfoEl) - additional_info = pInfoEl->GetText(); - additional_info.insert(additional_info.begin(), ','); - additional_info.erase(additional_info.end()-1); - vector add_info_list = SplitString(additional_info, ","); - if(gps_points.size() == add_info_list.size()) - { - for(unsigned int i=0; i< gps_points.size(); i++) - { - gps_points.at(i).id = GetIDsFromPrefix(add_info_list.at(i), "WPID", "C").at(0); - gps_points.at(i).fromIds = GetIDsFromPrefix(add_info_list.at(i), "From", "To"); - gps_points.at(i).toIds = GetIDsFromPrefix(add_info_list.at(i), "To", "Vel"); - gps_points.at(i).v = GetDoubleFromPrefix(add_info_list.at(i), "Vel", "Dir").at(0); - gps_points.at(i).pos.a = gps_points.at(i).pos.dir = GetDoubleFromPrefix(add_info_list.at(i), "Dir", "").at(0); -// if(currLaneID == 11115) -// { + if(pV) + { + string coordinate_list; + if(!pV->NoChildren()) + coordinate_list = pV->GetText(); + + istringstream str_stream(coordinate_list); + string token, temp; + + + while(getline(str_stream, token, ' ')) + { + string lat, lon, alt; + double numLat=0, numLon=0, numAlt=0; + + istringstream ss(token); + + getline(ss, lat, ','); + getline(ss, lon, ','); + getline(ss, alt, ','); + + numLat = atof(lat.c_str()); + numLon = atof(lon.c_str()); + numAlt = atof(alt.c_str()); + + WayPoint wp; + + wp.pos.x = wp.pos.lat = numLat; + wp.pos.y = wp.pos.lon = numLon; + wp.pos.z = wp.pos.alt = numAlt; + + wp.laneId = currLaneID; + gps_points.push_back(wp); + } + + TiXmlElement* pInfoEl =pElem->FirstChildElement("Folder")->FirstChildElement("description"); + string additional_info; + if(pInfoEl) + additional_info = pInfoEl->GetText(); + additional_info.insert(additional_info.begin(), ','); + additional_info.erase(additional_info.end()-1); + vector add_info_list = SplitString(additional_info, ","); + if(gps_points.size() == add_info_list.size()) + { + for(unsigned int i=0; i< gps_points.size(); i++) + { + gps_points.at(i).id = GetIDsFromPrefix(add_info_list.at(i), "WPID", "C").at(0); + gps_points.at(i).fromIds = GetIDsFromPrefix(add_info_list.at(i), "From", "To"); + gps_points.at(i).toIds = GetIDsFromPrefix(add_info_list.at(i), "To", "Vel"); + gps_points.at(i).v = GetDoubleFromPrefix(add_info_list.at(i), "Vel", "Dir").at(0); + gps_points.at(i).pos.a = gps_points.at(i).pos.dir = GetDoubleFromPrefix(add_info_list.at(i), "Dir", "").at(0); +// if(currLaneID == 11115) +// { // -// pair act_cost; -// act_cost.first = FORWARD_ACTION; -// act_cost.second = 100; -// gps_points.at(i).actionCost.push_back(act_cost); -// } - } - } - } +// pair act_cost; +// act_cost.first = FORWARD_ACTION; +// act_cost.second = 100; +// gps_points.at(i).actionCost.push_back(act_cost); +// } + } + } + } - return gps_points; + return gps_points; } vector MappingHelpers::GetIDsFromPrefix(const string& str, const string& prefix, const string& postfix) { - int index1 = str.find(prefix)+prefix.size(); - int index2 = str.find(postfix, index1); - if(index2 < 0 || postfix.size() ==0) - index2 = str.size(); + int index1 = str.find(prefix)+prefix.size(); + int index2 = str.find(postfix, index1); + if(index2 < 0 || postfix.size() ==0) + index2 = str.size(); - string str_ids = str.substr(index1, index2-index1); + string str_ids = str.substr(index1, index2-index1); - vector ids; - vector idstr = SplitString(str_ids, "_"); + vector ids; + vector idstr = SplitString(str_ids, "_"); - for(unsigned int i=0; i< idstr.size(); i++ ) - { - if(idstr.at(i).size()>0) - { - int num = atoi(idstr.at(i).c_str()); - //if(num>-1) - ids.push_back(num); - } - } + for(unsigned int i=0; i< idstr.size(); i++ ) + { + if(idstr.at(i).size()>0) + { + int num = atoi(idstr.at(i).c_str()); + //if(num>-1) + ids.push_back(num); + } + } - return ids; + return ids; } vector MappingHelpers::GetDoubleFromPrefix(const string& str, const string& prefix, const string& postfix) { - int index1 = str.find(prefix)+prefix.size(); - int index2 = str.find(postfix, index1); - if(index2 < 0 || postfix.size() ==0) - index2 = str.size(); + int index1 = str.find(prefix)+prefix.size(); + int index2 = str.find(postfix, index1); + if(index2 < 0 || postfix.size() ==0) + index2 = str.size(); - string str_ids = str.substr(index1, index2-index1); + string str_ids = str.substr(index1, index2-index1); - vector ids; - vector idstr = SplitString(str_ids, "_"); + vector ids; + vector idstr = SplitString(str_ids, "_"); - for(unsigned int i=0; i< idstr.size(); i++ ) - { - if(idstr.at(i).size()>0) - { - double num = atof(idstr.at(i).c_str()); - //if(num>-1) - ids.push_back(num); - } - } + for(unsigned int i=0; i< idstr.size(); i++ ) + { + if(idstr.at(i).size()>0) + { + double num = atof(idstr.at(i).c_str()); + //if(num>-1) + ids.push_back(num); + } + } - return ids; + return ids; } pair MappingHelpers::GetActionPairFromPrefix(const string& str, const string& prefix, const string& postfix) { - int index1 = str.find(prefix)+prefix.size(); - int index2 = str.find(postfix, index1); - if(index2<0 || postfix.size() ==0) - index2 = str.size(); + int index1 = str.find(prefix)+prefix.size(); + int index2 = str.find(postfix, index1); + if(index2<0 || postfix.size() ==0) + index2 = str.size(); - string str_ids = str.substr(index1, index2-index1); + string str_ids = str.substr(index1, index2-index1); - pair act_cost; - act_cost.first = FORWARD_ACTION; - act_cost.second = 0; + pair act_cost; + act_cost.first = FORWARD_ACTION; + act_cost.second = 0; - vector idstr = SplitString(str_ids, "_"); + vector idstr = SplitString(str_ids, "_"); - if(idstr.size() >= 2) - { - if(idstr.at(0).size() > 0 && idstr.at(0).at(0) == 'L') - act_cost.first = LEFT_TURN_ACTION; - else if(idstr.at(0).size() > 0 && idstr.at(0).at(0) == 'R') - act_cost.first = RIGHT_TURN_ACTION; - if(idstr.at(1).size() > 0) - act_cost.second = atof(idstr.at(1).c_str()); - } + if(idstr.size() >= 2) + { + if(idstr.at(0).size() > 0 && idstr.at(0).at(0) == 'L') + act_cost.first = LEFT_TURN_ACTION; + else if(idstr.at(0).size() > 0 && idstr.at(0).at(0) == 'R') + act_cost.first = RIGHT_TURN_ACTION; + if(idstr.at(1).size() > 0) + act_cost.second = atof(idstr.at(1).c_str()); + } - return act_cost; + return act_cost; } vector MappingHelpers::SplitString(const string& str, const string& token) { - vector str_parts; - int iFirstPart = str.find(token); - - while(iFirstPart >= 0) - { - iFirstPart++; - int iSecondPart = str.find(token, iFirstPart); - if(iSecondPart>0) - { - str_parts.push_back(str.substr(iFirstPart,iSecondPart - iFirstPart)); - } - else - { - str_parts.push_back(str.substr(iFirstPart,str.size() - iFirstPart)); - } + vector str_parts; + int iFirstPart = str.find(token); - iFirstPart = iSecondPart; - } + while(iFirstPart >= 0) + { + iFirstPart++; + int iSecondPart = str.find(token, iFirstPart); + if(iSecondPart>0) + { + str_parts.push_back(str.substr(iFirstPart,iSecondPart - iFirstPart)); + } + else + { + str_parts.push_back(str.substr(iFirstPart,str.size() - iFirstPart)); + } + + iFirstPart = iSecondPart; + } - return str_parts; + return str_parts; } void MappingHelpers::FindAdjacentLanes(RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - //Link Lanes - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - //Link left and right lanes - for(unsigned int rs_2 = 0; rs_2 < map.roadSegments.size(); rs_2++) - { - for(unsigned int i2 =0; i2 < map.roadSegments.at(rs_2).Lanes.size(); i2++) - { - int iCenter1 = pL->points.size()/2; - WayPoint wp_1 = pL->points.at(iCenter1); - int iCenter2 = PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs_2).Lanes.at(i2).points, wp_1 ); - WayPoint closest_p = map.roadSegments.at(rs_2).Lanes.at(i2).points.at(iCenter2); - double mid_a1 = wp_1.pos.a; - double mid_a2 = closest_p.pos.a; - double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(mid_a1, mid_a2); - double distance = distance2points(wp_1.pos, closest_p.pos); - - if(pL->id != map.roadSegments.at(rs_2).Lanes.at(i2).id && angle_diff < 0.05 && distance < 3.5 && distance > 2.5) - { - double perp_distance = DBL_MAX; - if(pL->points.size() > 2 && map.roadSegments.at(rs_2).Lanes.at(i2).points.size()>2) - { - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(pL->points, closest_p, info); - perp_distance = info.perp_distance; - //perp_distance = PlanningHelpers::GetPerpDistanceToVectorSimple(pL->points.at(iCenter1-1), pL->points.at(iCenter1+1), closest_p); - } - - if(perp_distance > 1.0 && perp_distance < 10.0) - { - pL->pRightLane = &map.roadSegments.at(rs_2).Lanes.at(i2); - for(unsigned int i_internal = 0; i_internal< pL->points.size(); i_internal++) - { - if(i_internalpoints.at(i_internal).RightPointId = map.roadSegments.at(rs_2).Lanes.at(i2).id; - pL->points.at(i_internal).pRight = &map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal); -// map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal).pLeft = &pL->points.at(i_internal); - } - } - } - else if(perp_distance < -1.0 && perp_distance > -10.0) - { - pL->pLeftLane = &map.roadSegments.at(rs_2).Lanes.at(i2); - for(unsigned int i_internal = 0; i_internal< pL->points.size(); i_internal++) - { - if(i_internalpoints.at(i_internal).LeftPointId = map.roadSegments.at(rs_2).Lanes.at(i2).id; - pL->points.at(i_internal).pLeft = &map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal); -// map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal).pRight = &pL->points.at(i_internal); - } - } - } - } - } - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + //Link Lanes + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + //Link left and right lanes + for(unsigned int rs_2 = 0; rs_2 < map.roadSegments.size(); rs_2++) + { + for(unsigned int i2 =0; i2 < map.roadSegments.at(rs_2).Lanes.size(); i2++) + { + int iCenter1 = pL->points.size()/2; + WayPoint wp_1 = pL->points.at(iCenter1); + int iCenter2 = PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs_2).Lanes.at(i2).points, wp_1 ); + WayPoint closest_p = map.roadSegments.at(rs_2).Lanes.at(i2).points.at(iCenter2); + double mid_a1 = wp_1.pos.a; + double mid_a2 = closest_p.pos.a; + double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(mid_a1, mid_a2); + double distance = distance2points(wp_1.pos, closest_p.pos); + + if(pL->id != map.roadSegments.at(rs_2).Lanes.at(i2).id && angle_diff < 0.05 && distance < 3.5 && distance > 2.5) + { + double perp_distance = DBL_MAX; + if(pL->points.size() > 2 && map.roadSegments.at(rs_2).Lanes.at(i2).points.size()>2) + { + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(pL->points, closest_p, info); + perp_distance = info.perp_distance; + //perp_distance = PlanningHelpers::GetPerpDistanceToVectorSimple(pL->points.at(iCenter1-1), pL->points.at(iCenter1+1), closest_p); + } + + if(perp_distance > 1.0 && perp_distance < 10.0) + { + pL->pRightLane = &map.roadSegments.at(rs_2).Lanes.at(i2); + for(unsigned int i_internal = 0; i_internal< pL->points.size(); i_internal++) + { + if(i_internalpoints.at(i_internal).RightPointId = map.roadSegments.at(rs_2).Lanes.at(i2).id; + pL->points.at(i_internal).pRight = &map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal); +// map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal).pLeft = &pL->points.at(i_internal); + } + } + } + else if(perp_distance < -1.0 && perp_distance > -10.0) + { + pL->pLeftLane = &map.roadSegments.at(rs_2).Lanes.at(i2); + for(unsigned int i_internal = 0; i_internal< pL->points.size(); i_internal++) + { + if(i_internalpoints.at(i_internal).LeftPointId = map.roadSegments.at(rs_2).Lanes.at(i2).id; + pL->points.at(i_internal).pLeft = &map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal); +// map.roadSegments.at(rs_2).Lanes.at(i2).points.at(i_internal).pRight = &pL->points.at(i_internal); + } + } + } + } + } + } + } + } } void MappingHelpers::ExtractSignalData(const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int is=0; is< signal_data.size(); is++) - { - if(signal_data.at(is).Type == 2) - { - TrafficLight tl; - tl.id = signal_data.at(is).ID; - tl.linkID = signal_data.at(is).LinkID; - tl.stoppingDistance = 0; - - for(unsigned int iv = 0; iv < vector_data.size(); iv++) - { - if(signal_data.at(is).VID == vector_data.at(iv).VID) - { - for(unsigned int ip = 0; ip < points_data.size(); ip++) - { - if(vector_data.at(iv).PID == points_data.at(ip).PID) - { - tl.pos = GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, vector_data.at(iv).Hang*DEG2RAD); - break; - } - } - } - } - map.trafficLights.push_back(tl); - if(tl.id > g_max_traffic_light_id) - g_max_traffic_light_id = tl.id; - } - } + const std::vector& vector_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int is=0; is< signal_data.size(); is++) + { + if(signal_data.at(is).Type == 2) + { + TrafficLight tl; + tl.id = signal_data.at(is).ID; + tl.linkID = signal_data.at(is).LinkID; + tl.stoppingDistance = 0; + + for(unsigned int iv = 0; iv < vector_data.size(); iv++) + { + if(signal_data.at(is).VID == vector_data.at(iv).VID) + { + for(unsigned int ip = 0; ip < points_data.size(); ip++) + { + if(vector_data.at(iv).PID == points_data.at(ip).PID) + { + tl.pos = GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, vector_data.at(iv).Hang*DEG2RAD); + break; + } + } + } + } + map.trafficLights.push_back(tl); + if(tl.id > g_max_traffic_light_id) + g_max_traffic_light_id = tl.id; + } + } } void MappingHelpers::ExtractStopLinesData(const std::vector& stop_line_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int ist=0; ist < stop_line_data.size(); ist++) - { - StopLine sl; - sl.linkID = stop_line_data.at(ist).LinkID; - sl.id = stop_line_data.at(ist).ID; - if(stop_line_data.at(ist).TLID>0) - sl.trafficLightID = stop_line_data.at(ist).TLID; - else - sl.stopSignID = 100+ist; - - for(unsigned int il=0; il < line_data.size(); il++) - { - if(stop_line_data.at(ist).LID == line_data.at(il).LID) - { - int s_id = line_data.at(il).BPID; - int e_id = line_data.at(il).FPID; - for(unsigned int ip = 0; ip < points_data.size(); ip++) - { - if(points_data.at(ip).PID == s_id || points_data.at(ip).PID == e_id) - { - sl.points.push_back(GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0)); - } - } - } - } - map.stopLines.push_back(sl); - if(sl.id > g_max_stop_line_id) - g_max_stop_line_id = sl.id; - } + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int ist=0; ist < stop_line_data.size(); ist++) + { + StopLine sl; + sl.linkID = stop_line_data.at(ist).LinkID; + sl.id = stop_line_data.at(ist).ID; + if(stop_line_data.at(ist).TLID>0) + sl.trafficLightID = stop_line_data.at(ist).TLID; + else + sl.stopSignID = 100+ist; + + for(unsigned int il=0; il < line_data.size(); il++) + { + if(stop_line_data.at(ist).LID == line_data.at(il).LID) + { + int s_id = line_data.at(il).BPID; + int e_id = line_data.at(il).FPID; + for(unsigned int ip = 0; ip < points_data.size(); ip++) + { + if(points_data.at(ip).PID == s_id || points_data.at(ip).PID == e_id) + { + sl.points.push_back(GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0)); + } + } + } + } + map.stopLines.push_back(sl); + if(sl.id > g_max_stop_line_id) + g_max_stop_line_id = sl.id; + } } void MappingHelpers::ExtractCurbData(const std::vector& curb_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int ic=0; ic < curb_data.size(); ic++) - { - Curb c; - c.id = curb_data.at(ic).ID; - - for(unsigned int il=0; il < line_data.size(); il++) - { - if(curb_data.at(ic).LID == line_data.at(il).LID) - { - int s_id = line_data.at(il).BPID; - //int e_id = line_data.at(il).FPID; - for(unsigned int ip = 0; ip < points_data.size(); ip++) - { - if(points_data.at(ip).PID == s_id) - { - c.points.push_back(GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0)); - WayPoint wp; - wp.pos = c.points.at(0); - Lane* pLane = GetClosestLaneFromMap(wp, map, 5); - if(pLane) - { - c.laneId = pLane->id; - c.pLane = pLane; - } - } - } - } - } - map.curbs.push_back(c); - } + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int ic=0; ic < curb_data.size(); ic++) + { + Curb c; + c.id = curb_data.at(ic).ID; + + for(unsigned int il=0; il < line_data.size(); il++) + { + if(curb_data.at(ic).LID == line_data.at(il).LID) + { + int s_id = line_data.at(il).BPID; + //int e_id = line_data.at(il).FPID; + for(unsigned int ip = 0; ip < points_data.size(); ip++) + { + if(points_data.at(ip).PID == s_id) + { + c.points.push_back(GPSPoint(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0)); + WayPoint wp; + wp.pos = c.points.at(0); + Lane* pLane = GetClosestLaneFromMap(wp, map, 5); + if(pLane) + { + c.laneId = pLane->id; + c.pLane = pLane; + } + } + } + } + } + map.curbs.push_back(c); + } } void MappingHelpers::ExtractWayArea(const std::vector& area_data, - const std::vector& wayarea_data, - const std::vector& line_data, - const std::vector& points_data, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int iw=0; iw < wayarea_data.size(); iw ++) - { - Boundary bound; - bound.id = wayarea_data.at(iw).ID; - - for(unsigned int ia=0; ia < area_data.size(); ia ++) - { - if(wayarea_data.at(iw).AID == area_data.at(ia).AID) - { - int s_id = area_data.at(ia).SLID; - int e_id = area_data.at(ia).ELID; - - for(unsigned int il=0; il< line_data.size(); il++) - { - if(line_data.at(il).LID >= s_id && line_data.at(il).LID <= e_id) - { - for(unsigned int ip=0; ip < points_data.size(); ip++) - { - if(points_data.at(ip).PID == line_data.at(il).BPID) - { - GPSPoint p(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0); - bound.points.push_back(p); - } - } - } - } - } - } - - map.boundaries.push_back(bound); - } + const std::vector& wayarea_data, + const std::vector& line_data, + const std::vector& points_data, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int iw=0; iw < wayarea_data.size(); iw ++) + { + Boundary bound; + bound.id = wayarea_data.at(iw).ID; + + for(unsigned int ia=0; ia < area_data.size(); ia ++) + { + if(wayarea_data.at(iw).AID == area_data.at(ia).AID) + { + int s_id = area_data.at(ia).SLID; + int e_id = area_data.at(ia).ELID; + + for(unsigned int il=0; il< line_data.size(); il++) + { + if(line_data.at(il).LID >= s_id && line_data.at(il).LID <= e_id) + { + for(unsigned int ip=0; ip < points_data.size(); ip++) + { + if(points_data.at(ip).PID == line_data.at(il).BPID) + { + GPSPoint p(points_data.at(ip).Ly + origin.x, points_data.at(ip).Bx + origin.y, points_data.at(ip).H + origin.z, 0); + bound.points.push_back(p); + } + } + } + } + } + } + + map.boundaries.push_back(bound); + } } void MappingHelpers::LinkMissingBranchingWayPoints(RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - for(unsigned int j = 0 ; j < pWP->toIds.size(); j++) - { - pWP->pFronts.push_back(FindWaypoint(pWP->toIds.at(j), map)); - } - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + for(unsigned int j = 0 ; j < pWP->toIds.size(); j++) + { + pWP->pFronts.push_back(FindWaypoint(pWP->toIds.at(j), map)); + } + } + } + } } void MappingHelpers::LinkMissingBranchingWayPointsV2(RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pLane = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int p= 0; p < pLane->points.size(); p++) - { - WayPoint* pWP = &pLane->points.at(p); - - if(p+1 == pLane->points.size()) // Last Point in Lane - { - for(unsigned int j = 0 ; j < pLane->toLanes.size(); j++) - { - //cout << "Link, Next Lane: " << pWP->laneId << ", WP: " << pWP->id << " To WP: " << pWP->toIds.at(j) << endl; - pWP->pFronts.push_back(&pLane->toLanes.at(j)->points.at(0)); - } - } - else - { - if(pWP->toIds.size() > 1) - { - cout << "Error Error Erro ! Lane: " << pWP->laneId << ", Point: " << pWP->originalMapID << endl; - } - else - { - // cout << "Link, Same Lane: " << pWP->laneId << ", WP: " << pWP->id << " To WP: " << map.roadSegments.at(rs).Lanes.at(i).points.at(p+1).id << endl; - pWP->pFronts.push_back(&pLane->points.at(p+1)); - } - } - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pLane = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int p= 0; p < pLane->points.size(); p++) + { + WayPoint* pWP = &pLane->points.at(p); + + if(p+1 == pLane->points.size()) // Last Point in Lane + { + for(unsigned int j = 0 ; j < pLane->toLanes.size(); j++) + { + //cout << "Link, Next Lane: " << pWP->laneId << ", WP: " << pWP->id << " To WP: " << pWP->toIds.at(j) << endl; + pWP->pFronts.push_back(&pLane->toLanes.at(j)->points.at(0)); + } + } + else + { + if(pWP->toIds.size() > 1) + { + cout << "Error Error Erro ! Lane: " << pWP->laneId << ", Point: " << pWP->originalMapID << endl; + } + else + { + // cout << "Link, Same Lane: " << pWP->laneId << ", WP: " << pWP->id << " To WP: " << map.roadSegments.at(rs).Lanes.at(i).points.at(p+1).id << endl; + pWP->pFronts.push_back(&pLane->points.at(p+1)); + } + } + } + } + } } void MappingHelpers::LinkTrafficLightsAndStopLines(RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - - if(map.stopLines.at(isl).linkID == pWP->id) - { - map.stopLines.at(isl).laneId = pWP->laneId; - map.stopLines.at(isl).pLane = pWP->pLane; - map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); - - pWP->stopLineID = map.stopLines.at(isl).id; - - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - if(map.trafficLights.at(itl).id == map.stopLines.at(isl).trafficLightID) - { - map.trafficLights.at(itl).laneIds.push_back(pWP->laneId); - map.trafficLights.at(itl).pLanes.push_back(pWP->pLane); - } - } - break; - } - } - } - } - } - - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - if(map.trafficLights.at(itl).linkID == pWP->id) - { - map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); - break; - } - } - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + + if(map.stopLines.at(isl).linkID == pWP->id) + { + map.stopLines.at(isl).laneId = pWP->laneId; + map.stopLines.at(isl).pLane = pWP->pLane; + map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); + + pWP->stopLineID = map.stopLines.at(isl).id; + + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + if(map.trafficLights.at(itl).id == map.stopLines.at(isl).trafficLightID) + { + map.trafficLights.at(itl).laneIds.push_back(pWP->laneId); + map.trafficLights.at(itl).pLanes.push_back(pWP->pLane); + } + } + break; + } + } + } + } + } + + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + if(map.trafficLights.at(itl).linkID == pWP->id) + { + map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); + break; + } + } + } + } + } } void MappingHelpers::LinkTrafficLightsAndStopLinesConData(const std::vector& conn_data, - const std::vector >& id_replace_list, RoadNetwork& map) -{ - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - - for(unsigned int ic = 0; ic < conn_data.size(); ic++) - { - UtilityHNS::AisanDataConnFileReader::DataConn data_conn = conn_data.at(ic); - ReplaceMyID(data_conn.LID , id_replace_list); - - if(map.roadSegments.at(rs).Lanes.at(i).id == data_conn.LID) - { - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - if(map.trafficLights.at(itl).id == data_conn.SID) - { - map.trafficLights.at(itl).laneIds.push_back(map.roadSegments.at(rs).Lanes.at(i).id); - map.trafficLights.at(itl).pLanes.push_back(&map.roadSegments.at(rs).Lanes.at(i)); - map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); - } - } - - for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) - { - if(map.stopLines.at(isl).id == data_conn.SLID) - { - map.stopLines.at(isl).laneId = map.roadSegments.at(rs).Lanes.at(i).id; - map.stopLines.at(isl).pLane = &map.roadSegments.at(rs).Lanes.at(i); - map.stopLines.at(isl).trafficLightID = data_conn.SID; - map.stopLines.at(isl).stopSignID = data_conn.SSID; - map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); - WayPoint wp((map.stopLines.at(isl).points.at(0).x+map.stopLines.at(isl).points.at(1).x)/2.0, (map.stopLines.at(isl).points.at(0).y+map.stopLines.at(isl).points.at(1).y)/2.0, (map.stopLines.at(isl).points.at(0).z+map.stopLines.at(isl).points.at(1).z)/2.0, (map.stopLines.at(isl).points.at(0).a+map.stopLines.at(isl).points.at(1).a)/2.0); - map.roadSegments.at(rs).Lanes.at(i).points.at(PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs).Lanes.at(i).points, wp)).stopLineID = map.stopLines.at(isl).id; - } - } - } - } - - } - } + const std::vector >& id_replace_list, RoadNetwork& map) +{ + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + + for(unsigned int ic = 0; ic < conn_data.size(); ic++) + { + UtilityHNS::AisanDataConnFileReader::DataConn data_conn = conn_data.at(ic); + ReplaceMyID(data_conn.LID , id_replace_list); + + if(map.roadSegments.at(rs).Lanes.at(i).id == data_conn.LID) + { + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + if(map.trafficLights.at(itl).id == data_conn.SID) + { + map.trafficLights.at(itl).laneIds.push_back(map.roadSegments.at(rs).Lanes.at(i).id); + map.trafficLights.at(itl).pLanes.push_back(&map.roadSegments.at(rs).Lanes.at(i)); + map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); + } + } + + for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) + { + if(map.stopLines.at(isl).id == data_conn.SLID) + { + map.stopLines.at(isl).laneId = map.roadSegments.at(rs).Lanes.at(i).id; + map.stopLines.at(isl).pLane = &map.roadSegments.at(rs).Lanes.at(i); + map.stopLines.at(isl).trafficLightID = data_conn.SID; + map.stopLines.at(isl).stopSignID = data_conn.SSID; + map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); + WayPoint wp((map.stopLines.at(isl).points.at(0).x+map.stopLines.at(isl).points.at(1).x)/2.0, (map.stopLines.at(isl).points.at(0).y+map.stopLines.at(isl).points.at(1).y)/2.0, (map.stopLines.at(isl).points.at(0).z+map.stopLines.at(isl).points.at(1).z)/2.0, (map.stopLines.at(isl).points.at(0).a+map.stopLines.at(isl).points.at(1).a)/2.0); + map.roadSegments.at(rs).Lanes.at(i).points.at(PlanningHelpers::GetClosestNextPointIndexFast(map.roadSegments.at(rs).Lanes.at(i).points, wp)).stopLineID = map.stopLines.at(isl).id; + } + } + } + } + + } + } } void MappingHelpers::UpdateMapWithOccupancyGrid(OccupancyToGridMap& map_info, const std::vector& data, RoadNetwork& map, std::vector& updated_list) { - PlannerHNS::Mat3 rotationMat(- map_info.center.pos.a); - PlannerHNS::Mat3 translationMat(-map_info.center.pos.x, -map_info.center.pos.y); - updated_list.clear(); - - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - - GPSPoint relative_point = pWP->pos; - relative_point = translationMat * relative_point; - relative_point = rotationMat *relative_point; - - int cell_value = 0; - if(map_info.GetCellIndexFromPoint(relative_point, data, cell_value) == true) - { - if(cell_value == 0) - { - bool bFound = false; - for(unsigned int i_action=0; i_action < pWP->actionCost.size(); i_action++) - { - if(pWP->actionCost.at(i_action).first == FORWARD_ACTION) - { - pWP->actionCost.at(i_action).second = 100; - bFound = true; - } - } - - if(!bFound) - pWP->actionCost.push_back(make_pair(FORWARD_ACTION, 100)); - - updated_list.push_back(pWP); - } - } - } - } - } + PlannerHNS::Mat3 rotationMat(- map_info.center.pos.a); + PlannerHNS::Mat3 translationMat(-map_info.center.pos.x, -map_info.center.pos.y); + updated_list.clear(); + + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + + GPSPoint relative_point = pWP->pos; + relative_point = translationMat * relative_point; + relative_point = rotationMat *relative_point; + + int cell_value = 0; + if(map_info.GetCellIndexFromPoint(relative_point, data, cell_value) == true) + { + if(cell_value == 0) + { + bool bFound = false; + for(unsigned int i_action=0; i_action < pWP->actionCost.size(); i_action++) + { + if(pWP->actionCost.at(i_action).first == FORWARD_ACTION) + { + pWP->actionCost.at(i_action).second = 100; + bFound = true; + } + } + + if(!bFound) + pWP->actionCost.push_back(make_pair(FORWARD_ACTION, 100)); + + updated_list.push_back(pWP); + } + } + } + } + } } void MappingHelpers::ConstructRoadNetworkFromROSMessageV2(const std::vector& lanes_data, - const std::vector& points_data, - const std::vector& dt_data, - const std::vector& intersection_data, - const std::vector& area_data, - const std::vector& line_data, - const std::vector& stop_line_data, - const std::vector& signal_data, - const std::vector& vector_data, - const std::vector& curb_data, - const std::vector& roadedge_data, - const std::vector& wayarea_data, - const std::vector& crosswalk_data, - const std::vector& nodes_data, - const std::vector& conn_data, - UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, - UtilityHNS::AisanLinesFileReader* pLinedata, - const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag, - const bool& bFindLaneChangeLanes, const bool& bFindCurbsAndWayArea) -{ - vector roadLanes; - - for(unsigned int i=0; i< pLaneData->m_data_list.size(); i++) - { - if(pLaneData->m_data_list.at(i).LnID > g_max_lane_id) - g_max_lane_id = pLaneData->m_data_list.at(i).LnID; - } - - cout << " >> Extracting Lanes ... " << endl; - CreateLanes(pLaneData, pPointsData, pNodesData, roadLanes); - - cout << " >> Fix Waypoints errors ... " << endl; - FixTwoPointsLanes(roadLanes); - FixRedundantPointsLanes(roadLanes); - - ConnectLanes(pLaneData, roadLanes); - - cout << " >> Create Missing lane connections ... " << endl; - FixUnconnectedLanes(roadLanes); - ////FixTwoPointsLanes(roadLanes); - - //map has one road segment - RoadSegment roadSegment1; - roadSegment1.id = 1; - roadSegment1.Lanes = roadLanes; - map.roadSegments.push_back(roadSegment1); - - //Fix angle for lanes - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - PlannerHNS::PlanningHelpers::FixAngleOnly(pL->points); - } - } - - //Link Lanes and lane's waypoints by pointers - cout << " >> Link lanes and waypoints with pointers ... " << endl; - LinkLanesPointers(map); - - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - if(pL->points.at(j).actionCost.size() > 0) - { - if(pL->points.at(j).actionCost.at(0).first == LEFT_TURN_ACTION) - { - AssignActionCostToLane(pL, LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST); - break; - } - else if(pL->points.at(j).actionCost.at(0).first == RIGHT_TURN_ACTION) - { - AssignActionCostToLane(pL, RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST); - break; - - } - } - } - } - } - - if(bFindLaneChangeLanes) - { - cout << " >> Extract Lane Change Information... " << endl; - FindAdjacentLanesV2(map); - } - - //Extract Signals and StopLines - cout << " >> Extract Signal data ... " << endl; - ExtractSignalDataV2(signal_data, vector_data, pPointsData, origin, map); - - //Stop Lines - cout << " >> Extract Stop lines data ... " << endl; - ExtractStopLinesDataV2(stop_line_data, pLinedata, pPointsData, origin, map); - - if(bFindCurbsAndWayArea) - { - //Curbs - cout << " >> Extract curbs data ... " << endl; - ExtractCurbDataV2(curb_data, pLinedata, pPointsData, origin, map); - - //Wayarea - cout << " >> Extract wayarea data ... " << endl; - ExtractWayArea(area_data, wayarea_data, line_data, points_data, origin, map); - } - - //Link waypoints - cout << " >> Link missing branches and waypoints... " << endl; - LinkMissingBranchingWayPointsV2(map); - - //Link StopLines and Traffic Lights - cout << " >> Link StopLines and Traffic Lights ... " << endl; - LinkTrafficLightsAndStopLinesV2(map); -// //LinkTrafficLightsAndStopLinesConData(conn_data, id_replace_list, map); - - cout << " >> Map loaded from data with " << roadLanes.size() << " lanes" << endl; + const std::vector& points_data, + const std::vector& dt_data, + const std::vector& intersection_data, + const std::vector& area_data, + const std::vector& line_data, + const std::vector& stop_line_data, + const std::vector& signal_data, + const std::vector& vector_data, + const std::vector& curb_data, + const std::vector& roadedge_data, + const std::vector& wayarea_data, + const std::vector& crosswalk_data, + const std::vector& nodes_data, + const std::vector& conn_data, + UtilityHNS::AisanLanesFileReader* pLaneData, + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, + UtilityHNS::AisanLinesFileReader* pLinedata, + const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag, + const bool& bFindLaneChangeLanes, const bool& bFindCurbsAndWayArea) +{ + vector roadLanes; + + for(unsigned int i=0; i< pLaneData->m_data_list.size(); i++) + { + if(pLaneData->m_data_list.at(i).LnID > g_max_lane_id) + g_max_lane_id = pLaneData->m_data_list.at(i).LnID; + } + + cout << " >> Extracting Lanes ... " << endl; + CreateLanes(pLaneData, pPointsData, pNodesData, roadLanes); + + cout << " >> Fix Waypoints errors ... " << endl; + FixTwoPointsLanes(roadLanes); + FixRedundantPointsLanes(roadLanes); + + ConnectLanes(pLaneData, roadLanes); + + cout << " >> Create Missing lane connections ... " << endl; + FixUnconnectedLanes(roadLanes); + ////FixTwoPointsLanes(roadLanes); + + //map has one road segment + RoadSegment roadSegment1; + roadSegment1.id = 1; + roadSegment1.Lanes = roadLanes; + map.roadSegments.push_back(roadSegment1); + + //Fix angle for lanes + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + PlannerHNS::PlanningHelpers::FixAngleOnly(pL->points); + } + } + + //Link Lanes and lane's waypoints by pointers + cout << " >> Link lanes and waypoints with pointers ... " << endl; + LinkLanesPointers(map); + + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + if(pL->points.at(j).actionCost.size() > 0) + { + if(pL->points.at(j).actionCost.at(0).first == LEFT_TURN_ACTION) + { + AssignActionCostToLane(pL, LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST); + break; + } + else if(pL->points.at(j).actionCost.at(0).first == RIGHT_TURN_ACTION) + { + AssignActionCostToLane(pL, RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST); + break; + + } + } + } + } + } + + if(bFindLaneChangeLanes) + { + cout << " >> Extract Lane Change Information... " << endl; + FindAdjacentLanesV2(map); + } + + //Extract Signals and StopLines + cout << " >> Extract Signal data ... " << endl; + ExtractSignalDataV2(signal_data, vector_data, pPointsData, origin, map); + + //Stop Lines + cout << " >> Extract Stop lines data ... " << endl; + ExtractStopLinesDataV2(stop_line_data, pLinedata, pPointsData, origin, map); + + if(bFindCurbsAndWayArea) + { + //Curbs + cout << " >> Extract curbs data ... " << endl; + ExtractCurbDataV2(curb_data, pLinedata, pPointsData, origin, map); + + //Wayarea + cout << " >> Extract wayarea data ... " << endl; + ExtractWayArea(area_data, wayarea_data, line_data, points_data, origin, map); + } + + //Link waypoints + cout << " >> Link missing branches and waypoints... " << endl; + LinkMissingBranchingWayPointsV2(map); + + //Link StopLines and Traffic Lights + cout << " >> Link StopLines and Traffic Lights ... " << endl; + LinkTrafficLightsAndStopLinesV2(map); +// //LinkTrafficLightsAndStopLinesConData(conn_data, id_replace_list, map); + + cout << " >> Map loaded from data with " << roadLanes.size() << " lanes" << endl; } bool MappingHelpers::GetPointFromDataList(UtilityHNS::AisanPointsFileReader* pPointsData,const int& pid, WayPoint& out_wp) { - if(pPointsData == nullptr) return false; + if(pPointsData == nullptr) return false; - AisanPointsFileReader::AisanPoints* pP = pPointsData->GetDataRowById(pid); + AisanPointsFileReader::AisanPoints* pP = pPointsData->GetDataRowById(pid); - if(pP!=nullptr) - { - out_wp.id = pP->PID; - out_wp.pos.x = pP->Ly; - out_wp.pos.y = pP->Bx; - out_wp.pos.z = pP->H; - return true; - } + if(pP!=nullptr) + { + out_wp.id = pP->PID; + out_wp.pos.x = pP->Ly; + out_wp.pos.y = pP->Bx; + out_wp.pos.z = pP->H; + return true; + } - return false; + return false; } int MappingHelpers::GetBeginPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID) + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID) { - if(pLaneData == nullptr) return false; - UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; - UtilityHNS::AisanPointsFileReader::AisanPoints* pP = nullptr; - UtilityHNS::AisanNodesFileReader::AisanNode* pN = nullptr; + if(pLaneData == nullptr) return false; + UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; + UtilityHNS::AisanPointsFileReader::AisanPoints* pP = nullptr; + UtilityHNS::AisanNodesFileReader::AisanNode* pN = nullptr; - pL = pLaneData->GetDataRowById(LnID); - if(pL!=nullptr) - { - return pL->FNID; - } + pL = pLaneData->GetDataRowById(LnID); + if(pL!=nullptr) + { + return pL->FNID; + } - return 0; + return 0; } int MappingHelpers::GetEndPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID) + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID) { - UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; - UtilityHNS::AisanPointsFileReader::AisanPoints* pP = nullptr; - UtilityHNS::AisanNodesFileReader::AisanNode* pN = nullptr; + UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; + UtilityHNS::AisanPointsFileReader::AisanPoints* pP = nullptr; + UtilityHNS::AisanNodesFileReader::AisanNode* pN = nullptr; - pL = pLaneData->GetDataRowById(LnID); - if(pL!=nullptr) - { - return pL->BNID; - } + pL = pLaneData->GetDataRowById(LnID); + if(pL!=nullptr) + { + return pL->BNID; + } - return 0; + return 0; } bool MappingHelpers::IsStartLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL) { - if(pL->JCT > 0 || pL->BLID == 0) - return true; + if(pL->JCT > 0 || pL->BLID == 0) + return true; - if(pL->BLID2 != 0 || pL->BLID3 != 0 || pL->BLID4 != 0) - return true; + if(pL->BLID2 != 0 || pL->BLID3 != 0 || pL->BLID4 != 0) + return true; - UtilityHNS::AisanLanesFileReader::AisanLane* pPrevL = pLaneData->GetDataRowById(pL->BLID); - if(pPrevL == nullptr || pPrevL->FLID2 > 0 || pPrevL->FLID3 > 0 || pPrevL->FLID4 > 0 || pPrevL->JCT > 0) - return true; + UtilityHNS::AisanLanesFileReader::AisanLane* pPrevL = pLaneData->GetDataRowById(pL->BLID); + if(pPrevL == nullptr || pPrevL->FLID2 > 0 || pPrevL->FLID3 > 0 || pPrevL->FLID4 > 0 || pPrevL->JCT > 0) + return true; - return false; + return false; } bool MappingHelpers::IsEndLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL) { - if(pL->FLID2 > 0 || pL->FLID3 > 0 || pL->FLID4 > 0) - return true; + if(pL->FLID2 > 0 || pL->FLID3 > 0 || pL->FLID4 > 0) + return true; - UtilityHNS::AisanLanesFileReader::AisanLane* pNextL = pLaneData->GetDataRowById(pL->FLID); + UtilityHNS::AisanLanesFileReader::AisanLane* pNextL = pLaneData->GetDataRowById(pL->FLID); - return IsStartLanePoint(pLaneData, pNextL); + return IsStartLanePoint(pLaneData, pNextL); } void MappingHelpers::GetLanesStartPoints(UtilityHNS::AisanLanesFileReader* pLaneData, - std::vector& m_LanesStartIds) + std::vector& m_LanesStartIds) { - m_LanesStartIds.clear(); - UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; - UtilityHNS::AisanLanesFileReader::AisanLane* pPrevL = nullptr; - for(unsigned int il=0; il < pLaneData->m_data_list.size(); il++) - { - pL = &pLaneData->m_data_list.at(il); - - if(IsStartLanePoint(pLaneData, pL) == true) - { - m_LanesStartIds.push_back(pL->LnID); - } - - if(DEBUG_MAP_PARSING) - { - if(IsStartLanePoint(pLaneData, pL) && IsEndLanePoint(pLaneData, pL)) - cout << " :( :( :( Start And End in the same time !! " << pL->LnID << endl; - } - } + m_LanesStartIds.clear(); + UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; + UtilityHNS::AisanLanesFileReader::AisanLane* pPrevL = nullptr; + for(unsigned int il=0; il < pLaneData->m_data_list.size(); il++) + { + pL = &pLaneData->m_data_list.at(il); + + if(IsStartLanePoint(pLaneData, pL) == true) + { + m_LanesStartIds.push_back(pL->LnID); + } + + if(DEBUG_MAP_PARSING) + { + if(IsStartLanePoint(pLaneData, pL) && IsEndLanePoint(pLaneData, pL)) + cout << " :( :( :( Start And End in the same time !! " << pL->LnID << endl; + } + } } void MappingHelpers::ConnectLanes(UtilityHNS::AisanLanesFileReader* pLaneData, std::vector& lanes) { - for(unsigned int il = 0; il < lanes.size(); il++) - { - WayPoint fp = lanes.at(il).points.at(0); - UtilityHNS::AisanLanesFileReader::AisanLane* pFirstL = pLaneData->GetDataRowById(fp.originalMapID); - if(pFirstL!=nullptr) - { - if(pFirstL->BLID > 0) - lanes.at(il).fromIds.push_back(pFirstL->BLID); - if(pFirstL->BLID2 > 0) - lanes.at(il).fromIds.push_back(pFirstL->BLID2); - if(pFirstL->BLID3 > 0) - lanes.at(il).fromIds.push_back(pFirstL->BLID3); - if(pFirstL->BLID4 > 0) - lanes.at(il).fromIds.push_back(pFirstL->BLID4); - } - - WayPoint ep = lanes.at(il).points.at(lanes.at(il).points.size()-1); - UtilityHNS::AisanLanesFileReader::AisanLane* pEndL = pLaneData->GetDataRowById(ep.originalMapID); - if(pEndL!=nullptr) - { - if(pEndL->FLID > 0) - lanes.at(il).toIds.push_back(pEndL->FLID); - if(pEndL->FLID2 > 0) - lanes.at(il).toIds.push_back(pEndL->FLID2); - if(pEndL->FLID3 > 0) - lanes.at(il).toIds.push_back(pEndL->FLID3); - if(pEndL->FLID4 > 0) - lanes.at(il).toIds.push_back(pEndL->FLID4); - } - } + for(unsigned int il = 0; il < lanes.size(); il++) + { + WayPoint fp = lanes.at(il).points.at(0); + UtilityHNS::AisanLanesFileReader::AisanLane* pFirstL = pLaneData->GetDataRowById(fp.originalMapID); + if(pFirstL!=nullptr) + { + if(pFirstL->BLID > 0) + lanes.at(il).fromIds.push_back(pFirstL->BLID); + if(pFirstL->BLID2 > 0) + lanes.at(il).fromIds.push_back(pFirstL->BLID2); + if(pFirstL->BLID3 > 0) + lanes.at(il).fromIds.push_back(pFirstL->BLID3); + if(pFirstL->BLID4 > 0) + lanes.at(il).fromIds.push_back(pFirstL->BLID4); + } + + WayPoint ep = lanes.at(il).points.at(lanes.at(il).points.size()-1); + UtilityHNS::AisanLanesFileReader::AisanLane* pEndL = pLaneData->GetDataRowById(ep.originalMapID); + if(pEndL!=nullptr) + { + if(pEndL->FLID > 0) + lanes.at(il).toIds.push_back(pEndL->FLID); + if(pEndL->FLID2 > 0) + lanes.at(il).toIds.push_back(pEndL->FLID2); + if(pEndL->FLID3 > 0) + lanes.at(il).toIds.push_back(pEndL->FLID3); + if(pEndL->FLID4 > 0) + lanes.at(il).toIds.push_back(pEndL->FLID4); + } + } } void MappingHelpers::CreateLanes(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, - std::vector& out_lanes) + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, + std::vector& out_lanes) { - out_lanes.clear(); - std::vector start_lines; - GetLanesStartPoints(pLaneData, start_lines); - for(unsigned int l =0; l < start_lines.size(); l++) - { - Lane _lane; - GetLanePoints(pLaneData, pPointsData, pNodesData, start_lines.at(l), _lane); - out_lanes.push_back(_lane); - } + out_lanes.clear(); + std::vector start_lines; + GetLanesStartPoints(pLaneData, start_lines); + for(unsigned int l =0; l < start_lines.size(); l++) + { + Lane _lane; + GetLanePoints(pLaneData, pPointsData, pNodesData, start_lines.at(l), _lane); + out_lanes.push_back(_lane); + } } void MappingHelpers::GetLanePoints(UtilityHNS::AisanLanesFileReader* pLaneData, - UtilityHNS::AisanPointsFileReader* pPointsData, - UtilityHNS::AisanNodesFileReader* pNodesData, int lnID, - PlannerHNS::Lane& out_lane) -{ - int next_lnid = lnID; - bool bStart = false; - bool bLast = false; - int _rID = 0; - out_lane.points.clear(); - UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; - out_lane.id = lnID; - out_lane.speed = 0; - - while(!bStart) - { - pL = pLaneData->GetDataRowById(next_lnid); - if(pL == nullptr) - { - cout << "## Error, Can't find lane from ID: " << next_lnid <FLID; - if(next_lnid == 0) - bStart = true; - else - bStart = IsStartLanePoint(pLaneData, pLaneData->GetDataRowById(next_lnid)); - -// if(_lnid == 1267 ) //|| _lnid == 1268 || _lnid == 1269 || _lnid == 958) -// out_lane.id = lnID; - - if(out_lane.points.size() == 0) - { - WayPoint wp1, wp2; - GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->BNID)->PID, wp1); - wp1.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; - - wp1.id = pL->BNID; - - if(pL->BLID != 0) - { - _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID); - if(_rID > 0) - wp1.fromIds.push_back(_rID); - } - if(pL->BLID2 != 0) - { - _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID2); - if(_rID > 0) - wp1.fromIds.push_back(_rID); - } - if(pL->BLID3 != 0) - { - _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID3); - if(_rID > 0) - wp1.fromIds.push_back(_rID); - } - if(pL->BLID4 != 0) - { - _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID4); - if(_rID > 0) - wp1.fromIds.push_back(_rID); - } - - GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->FNID)->PID, wp2); - wp2.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; - wp2.id = pL->FNID; - - if(bStart && pL->FLID != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID); - if(_rID > 0) - wp2.toIds.push_back(_rID); - } - if(pL->FLID2 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID2); - if(_rID > 0) - wp2.toIds.push_back(_rID); - } - if(pL->FLID3 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID3); - if(_rID > 0) - wp2.toIds.push_back(_rID); - } - if(pL->FLID4 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID4); - if(_rID > 0) - wp2.toIds.push_back(_rID); - } - - if(pL->LaneDir == 'L') - { - wp1.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); - wp2.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); - } - else if(pL->LaneDir == 'R') - { - wp1.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); - wp2.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); - } - else - { - wp1.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); - wp2.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); - } - - wp1.originalMapID = pL->LnID; - wp2.originalMapID = pL->LnID; - - wp1.laneId = lnID; - wp2.laneId = lnID; - - wp1.toIds.push_back(wp2.id); - wp2.fromIds.push_back(wp1.id); - out_lane.points.push_back(wp1); - out_lane.points.push_back(wp2); - out_lane.speed = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; - } - else - { - WayPoint wp; - GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->FNID)->PID, wp); - wp.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; - wp.id = pL->FNID; - - out_lane.points.at(out_lane.points.size()-1).toIds.push_back(wp.id); - wp.fromIds.push_back(out_lane.points.at(out_lane.points.size()-1).id); - - if(bStart && pL->FLID != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID); - if(_rID > 0) - wp.toIds.push_back(_rID); - } - if(pL->FLID2 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID2); - if(_rID > 0) - wp.toIds.push_back(_rID); - } - if(pL->FLID3 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID3); - if(_rID > 0) - wp.toIds.push_back(_rID); - } - if(pL->FLID4 != 0) - { - _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID4); - if(_rID > 0) - wp.toIds.push_back(_rID); - } - - if(pL->LaneDir == 'L') - { - wp.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); - } - else if(pL->LaneDir == 'R') - { - wp.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); - } - else - { - wp.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); - } - - wp.originalMapID = pL->LnID; - wp.laneId = lnID; - - out_lane.points.push_back(wp); - } - -// if(next_lnid == 0) -// break; - } + UtilityHNS::AisanPointsFileReader* pPointsData, + UtilityHNS::AisanNodesFileReader* pNodesData, int lnID, + PlannerHNS::Lane& out_lane) +{ + int next_lnid = lnID; + bool bStart = false; + bool bLast = false; + int _rID = 0; + out_lane.points.clear(); + UtilityHNS::AisanLanesFileReader::AisanLane* pL = nullptr; + out_lane.id = lnID; + out_lane.speed = 0; + + while(!bStart) + { + pL = pLaneData->GetDataRowById(next_lnid); + if(pL == nullptr) + { + cout << "## Error, Can't find lane from ID: " << next_lnid <FLID; + if(next_lnid == 0) + bStart = true; + else + bStart = IsStartLanePoint(pLaneData, pLaneData->GetDataRowById(next_lnid)); + +// if(_lnid == 1267 ) //|| _lnid == 1268 || _lnid == 1269 || _lnid == 958) +// out_lane.id = lnID; + + if(out_lane.points.size() == 0) + { + WayPoint wp1, wp2; + GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->BNID)->PID, wp1); + wp1.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; + + wp1.id = pL->BNID; + + if(pL->BLID != 0) + { + _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID); + if(_rID > 0) + wp1.fromIds.push_back(_rID); + } + if(pL->BLID2 != 0) + { + _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID2); + if(_rID > 0) + wp1.fromIds.push_back(_rID); + } + if(pL->BLID3 != 0) + { + _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID3); + if(_rID > 0) + wp1.fromIds.push_back(_rID); + } + if(pL->BLID4 != 0) + { + _rID = GetBeginPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->BLID4); + if(_rID > 0) + wp1.fromIds.push_back(_rID); + } + + GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->FNID)->PID, wp2); + wp2.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; + wp2.id = pL->FNID; + + if(bStart && pL->FLID != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID); + if(_rID > 0) + wp2.toIds.push_back(_rID); + } + if(pL->FLID2 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID2); + if(_rID > 0) + wp2.toIds.push_back(_rID); + } + if(pL->FLID3 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID3); + if(_rID > 0) + wp2.toIds.push_back(_rID); + } + if(pL->FLID4 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID4); + if(_rID > 0) + wp2.toIds.push_back(_rID); + } + + if(pL->LaneDir == 'L') + { + wp1.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); + wp2.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); + } + else if(pL->LaneDir == 'R') + { + wp1.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); + wp2.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); + } + else + { + wp1.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); + wp2.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); + } + + wp1.originalMapID = pL->LnID; + wp2.originalMapID = pL->LnID; + + wp1.laneId = lnID; + wp2.laneId = lnID; + + wp1.toIds.push_back(wp2.id); + wp2.fromIds.push_back(wp1.id); + out_lane.points.push_back(wp1); + out_lane.points.push_back(wp2); + out_lane.speed = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; + } + else + { + WayPoint wp; + GetPointFromDataList(pPointsData, pNodesData->GetDataRowById(pL->FNID)->PID, wp); + wp.v = pL->RefVel == 0 ? DEFAULT_REF_VELOCITY : pL->RefVel; + wp.id = pL->FNID; + + out_lane.points.at(out_lane.points.size()-1).toIds.push_back(wp.id); + wp.fromIds.push_back(out_lane.points.at(out_lane.points.size()-1).id); + + if(bStart && pL->FLID != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID); + if(_rID > 0) + wp.toIds.push_back(_rID); + } + if(pL->FLID2 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID2); + if(_rID > 0) + wp.toIds.push_back(_rID); + } + if(pL->FLID3 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID3); + if(_rID > 0) + wp.toIds.push_back(_rID); + } + if(pL->FLID4 != 0) + { + _rID = GetEndPointIdFromLaneNo(pLaneData, pPointsData, pNodesData, pL->FLID4); + if(_rID > 0) + wp.toIds.push_back(_rID); + } + + if(pL->LaneDir == 'L') + { + wp.actionCost.push_back(make_pair(LEFT_TURN_ACTION, LEFT_INITIAL_TURNS_COST)); + } + else if(pL->LaneDir == 'R') + { + wp.actionCost.push_back(make_pair(RIGHT_TURN_ACTION, RIGHT_INITIAL_TURNS_COST)); + } + else + { + wp.actionCost.push_back(make_pair(FORWARD_ACTION, 0)); + } + + wp.originalMapID = pL->LnID; + wp.laneId = lnID; + + out_lane.points.push_back(wp); + } + +// if(next_lnid == 0) +// break; + } } void MappingHelpers::FixRedundantPointsLanes(std::vector& lanes) { - //Fix Redundant point for two points in a row - for(unsigned int il=0; il < lanes.size(); il ++) - { - for(int ip = 1; ip < lanes.at(il).points.size(); ip++) - { - WayPoint* p1 = &lanes.at(il).points.at(ip-1); - WayPoint* p2 = &lanes.at(il).points.at(ip); - WayPoint* p3 = nullptr; - if(ip+1 < lanes.at(il).points.size()) - p3 = &lanes.at(il).points.at(ip+1); - - double d = hypot(p2->pos.y-p1->pos.y, p2->pos.x-p1->pos.x); - if(d == 0) - { - p1->toIds = p2->toIds; - p1->originalMapID = p2->originalMapID; - if(p3 != nullptr) - p3->fromIds = p2->fromIds; - - lanes.at(il).points.erase(lanes.at(il).points.begin()+ip); - ip--; - - if(DEBUG_MAP_PARSING) - cout << "Fixed Redundant Points for Lane:" << lanes.at(il).id << ", Current: " << ip << ", Size: " << lanes.at(il).points.size() << endl; - } - } - } + //Fix Redundant point for two points in a row + for(unsigned int il=0; il < lanes.size(); il ++) + { + for(int ip = 1; ip < lanes.at(il).points.size(); ip++) + { + WayPoint* p1 = &lanes.at(il).points.at(ip-1); + WayPoint* p2 = &lanes.at(il).points.at(ip); + WayPoint* p3 = nullptr; + if(ip+1 < lanes.at(il).points.size()) + p3 = &lanes.at(il).points.at(ip+1); + + double d = hypot(p2->pos.y-p1->pos.y, p2->pos.x-p1->pos.x); + if(d == 0) + { + p1->toIds = p2->toIds; + p1->originalMapID = p2->originalMapID; + if(p3 != nullptr) + p3->fromIds = p2->fromIds; + + lanes.at(il).points.erase(lanes.at(il).points.begin()+ip); + ip--; + + if(DEBUG_MAP_PARSING) + cout << "Fixed Redundant Points for Lane:" << lanes.at(il).id << ", Current: " << ip << ", Size: " << lanes.at(il).points.size() << endl; + } + } + } } void MappingHelpers::FixTwoPointsLane(Lane& l) { - if(l.points.size() == 2) - { - g_max_point_id++; - WayPoint wp = l.points.at(0); - wp.id = g_max_point_id; - wp.fromIds.clear(); - wp.fromIds.push_back(l.points.at(0).id); - wp.toIds.clear(); - wp.toIds.push_back(l.points.at(1).id); + if(l.points.size() == 2) + { + g_max_point_id++; + WayPoint wp = l.points.at(0); + wp.id = g_max_point_id; + wp.fromIds.clear(); + wp.fromIds.push_back(l.points.at(0).id); + wp.toIds.clear(); + wp.toIds.push_back(l.points.at(1).id); - l.points.at(0).toIds.clear(); - l.points.at(0).toIds.push_back(wp.id); + l.points.at(0).toIds.clear(); + l.points.at(0).toIds.push_back(wp.id); - l.points.at(1).fromIds.clear(); - l.points.at(1).fromIds.push_back(wp.id); + l.points.at(1).fromIds.clear(); + l.points.at(1).fromIds.push_back(wp.id); - wp.pos.x = (l.points.at(0).pos.x + l.points.at(1).pos.x)/2.0; - wp.pos.y = (l.points.at(0).pos.y + l.points.at(1).pos.y)/2.0; - wp.pos.z = (l.points.at(0).pos.z + l.points.at(1).pos.z)/2.0; + wp.pos.x = (l.points.at(0).pos.x + l.points.at(1).pos.x)/2.0; + wp.pos.y = (l.points.at(0).pos.y + l.points.at(1).pos.y)/2.0; + wp.pos.z = (l.points.at(0).pos.z + l.points.at(1).pos.z)/2.0; - l.points.insert(l.points.begin()+1, wp); - } - else if(l.points.size() < 2) - { - cout << "## WOW Lane " << l.id << " With Size (" << l.points.size() << ") " << endl; - } + l.points.insert(l.points.begin()+1, wp); + } + else if(l.points.size() < 2) + { + cout << "## WOW Lane " << l.id << " With Size (" << l.points.size() << ") " << endl; + } } void MappingHelpers::FixTwoPointsLanes(std::vector& lanes) { - for(unsigned int il=0; il < lanes.size(); il ++) - { - for(unsigned int ip = 0; ip < lanes.at(il).points.size(); ip++) - { - if(lanes.at(il).points.at(ip).id > g_max_point_id) - { - g_max_point_id = lanes.at(il).points.at(ip).id; - } - } - } + for(unsigned int il=0; il < lanes.size(); il ++) + { + for(unsigned int ip = 0; ip < lanes.at(il).points.size(); ip++) + { + if(lanes.at(il).points.at(ip).id > g_max_point_id) + { + g_max_point_id = lanes.at(il).points.at(ip).id; + } + } + } - for(unsigned int il=0; il < lanes.size(); il ++) - { - FixTwoPointsLane(lanes.at(il)); - PlannerHNS::PlanningHelpers::CalcAngleAndCost(lanes.at(il).points); - } + for(unsigned int il=0; il < lanes.size(); il ++) + { + FixTwoPointsLane(lanes.at(il)); + PlannerHNS::PlanningHelpers::CalcAngleAndCost(lanes.at(il).points); + } } void MappingHelpers::InsertWayPointToBackOfLane(const WayPoint& wp, Lane& lane, int& global_id) { - WayPoint* pFirst = &lane.points.at(0); - pFirst->pos = wp.pos; + WayPoint* pFirst = &lane.points.at(0); + pFirst->pos = wp.pos; -// WayPoint f_wp = *pFirst; -// f_wp.pos = wp.pos; +// WayPoint f_wp = *pFirst; +// f_wp.pos = wp.pos; // -// //Give old first new ID -// global_id++; -// pFirst->id = global_id; +// //Give old first new ID +// global_id++; +// pFirst->id = global_id; // -// //link ids -// f_wp.toIds.clear(); //only see front -// f_wp.toIds.push_back(pFirst->id); +// //link ids +// f_wp.toIds.clear(); //only see front +// f_wp.toIds.push_back(pFirst->id); // -// pFirst->fromIds.clear(); -// pFirst->fromIds.push_back(f_wp.id); +// pFirst->fromIds.clear(); +// pFirst->fromIds.push_back(f_wp.id); // -// if(lane.points.size() > 1) -// { -// lane.points.at(1).fromIds.clear(); -// lane.points.at(1).fromIds.push_back(pFirst->id); -// } +// if(lane.points.size() > 1) +// { +// lane.points.at(1).fromIds.clear(); +// lane.points.at(1).fromIds.push_back(pFirst->id); +// } // -// lane.points.insert(lane.points.begin(), f_wp); +// lane.points.insert(lane.points.begin(), f_wp); } void MappingHelpers::InsertWayPointToFrontOfLane(const WayPoint& wp, Lane& lane, int& global_id) { - WayPoint* pLast = &lane.points.at(lane.points.size()-1); - pLast->pos = wp.pos; + WayPoint* pLast = &lane.points.at(lane.points.size()-1); + pLast->pos = wp.pos; -// WayPoint l_wp = *pLast; -// l_wp.pos = wp.pos; +// WayPoint l_wp = *pLast; +// l_wp.pos = wp.pos; // -// //Give old first new ID -// global_id++; -// pLast->id = global_id; +// //Give old first new ID +// global_id++; +// pLast->id = global_id; // -// //link ids -// l_wp.fromIds.clear(); //only see front -// l_wp.fromIds.push_back(pLast->id); +// //link ids +// l_wp.fromIds.clear(); //only see front +// l_wp.fromIds.push_back(pLast->id); // -// pLast->toIds.clear(); -// pLast->toIds.push_back(l_wp.id); +// pLast->toIds.clear(); +// pLast->toIds.push_back(l_wp.id); // -// if(lane.points.size() > 1) -// { -// lane.points.at(lane.points.size()-2).toIds.clear(); -// lane.points.at(lane.points.size()-2).toIds.push_back(pLast->id); -// } +// if(lane.points.size() > 1) +// { +// lane.points.at(lane.points.size()-2).toIds.clear(); +// lane.points.at(lane.points.size()-2).toIds.push_back(pLast->id); +// } // -// lane.points.push_back(l_wp); +// lane.points.push_back(l_wp); } void MappingHelpers::FixUnconnectedLanes(std::vector& lanes) { - std::vector sp_lanes = lanes; - bool bAtleastOneChange = false; - //Find before lanes - for(unsigned int il=0; il < lanes.size(); il ++) - { - if(lanes.at(il).fromIds.size() == 0) - { - double closest_d = DBL_MAX; - Lane* pL = nullptr; - Lane* pFL = nullptr; - for(int l=0; l < sp_lanes.size(); l ++) - { - if(lanes.at(il).id == sp_lanes.at(l).id) - { - pFL = &sp_lanes.at(l); - break; - } - } - - PlannerHNS::RelativeInfo closest_info; - int closest_index = -1; - for(int l=0; l < sp_lanes.size(); l ++) - { - if(pFL->id != sp_lanes.at(l).id ) - { - PlannerHNS::RelativeInfo info; - WayPoint lastofother = sp_lanes.at(l).points.at(sp_lanes.at(l).points.size()-1); - PlanningHelpers::GetRelativeInfoLimited(sp_lanes.at(l).points, pFL->points.at(0), info, 0); - double back_distance = hypot(lastofother.pos.y - pFL->points.at(0).pos.y, lastofother.pos.x - pFL->points.at(0).pos.x); - bool bCloseFromBack = false; - if((info.bAfter == true && back_distance < 15.0) || info.bAfter == false) - bCloseFromBack = true; - - - if(fabs(info.perp_distance) < 2 && fabs(info.perp_distance) < closest_d && info.bBefore == false && bCloseFromBack) - { - closest_d = fabs(info.perp_distance); - pL = &sp_lanes.at(l); - closest_info = info; - closest_info.angle_diff = back_distance; - closest_index = l; - } - } - } - - if(pL != nullptr && pFL != nullptr) - { - if(closest_info.iFront == pL->points.size()-1) - { - pL->toIds.push_back(pFL->id); - pL->points.at(closest_info.iFront).toIds.push_back(pFL->points.at(0).id); - - pFL->points.at(0).fromIds.push_back(pL->points.at(closest_info.iFront).id); - pFL->fromIds.push_back(pL->id); - bAtleastOneChange = true; - if(DEBUG_MAP_PARSING) - { - cout << "Closest Next Lane For: " << pFL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; - cout << "Don't Split , Perfect !" << endl; - } - } - else - { - // split from previous point - if(DEBUG_MAP_PARSING) - cout << "Closest Next Lane For: " << pFL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; - - Lane front_half, back_half; - front_half.points.insert(front_half.points.begin(), pL->points.begin()+closest_info.iFront, pL->points.end()); - front_half.toIds = pL->toIds; - front_half.fromIds.push_back(pL->id); - front_half.id = front_half.points.at(0).originalMapID; - front_half.areaId = pL->areaId; - front_half.dir = pL->dir; - front_half.num = pL->num; - front_half.roadId = pL->roadId; - front_half.speed = pL->speed; - front_half.type = pL->type; - front_half.width = pL->width; - - back_half.points.insert(back_half.points.begin(), pL->points.begin(), pL->points.begin()+closest_info.iFront); - back_half.toIds.clear(); - back_half.toIds.push_back(front_half.id); - back_half.toIds.push_back(pFL->id); - back_half.fromIds = pL->fromIds; - back_half.id = pL->id; - back_half.areaId = pL->areaId; - back_half.dir = pL->dir; - back_half.num = pL->num; - back_half.roadId = pL->roadId; - back_half.speed = pL->speed; - back_half.type = pL->type; - back_half.width = pL->width; - - WayPoint* last_from_back = &back_half.points.at(back_half.points.size()-1); - WayPoint* first_from_front = &pFL->points.at(0); - - last_from_back->toIds.push_back(first_from_front->id); - first_from_front->fromIds.push_back(last_from_back->id); - - if(front_half.points.size() > 1 && back_half.points.size() > 1) - { - if(DEBUG_MAP_PARSING) - cout << "Split this one Nicely! first_half_size: " << front_half.points.size() << ", second_hald_size: " << back_half.points.size() << endl; - - pFL->fromIds.push_back(back_half.id); - - if(closest_index >= 0) - sp_lanes.erase(sp_lanes.begin()+closest_index); - else - cout << "## Alert Alert Alert !!!! " << endl; - - // add perp point to lane points - InsertWayPointToBackOfLane(closest_info.perp_point, front_half, g_max_point_id); - InsertWayPointToFrontOfLane(closest_info.perp_point, back_half, g_max_point_id); - - sp_lanes.push_back(front_half); - sp_lanes.push_back(back_half); - bAtleastOneChange = true; - } - else - { - if(DEBUG_MAP_PARSING) - cout << "=> Can't Split this one :( !" << endl; - } - } - } - else - { - if(DEBUG_MAP_PARSING) - cout << "=> Can't find Before Lanes For: " << lanes.at(il).id << endl; - } - } - } - - lanes = sp_lanes; - - //Find to lanes - - for(unsigned int il=0; il < lanes.size(); il ++) - { - if(lanes.at(il).toIds.size() == 0) - { - double closest_d = DBL_MAX; - Lane* pL = nullptr; - Lane* pBL = nullptr; - for(int l=0; l < sp_lanes.size(); l ++) - { - if(lanes.at(il).id == sp_lanes.at(l).id) - { - pBL = &sp_lanes.at(l); - break; - } - } - - PlannerHNS::RelativeInfo closest_info; - int closest_index = -1; - for(int l=0; l < sp_lanes.size(); l ++) - { - if(pBL->id != sp_lanes.at(l).id ) - { - PlannerHNS::RelativeInfo info; - WayPoint firstofother = sp_lanes.at(l).points.at(0); - WayPoint last_point = pBL->points.at(pBL->points.size()-1); - PlanningHelpers::GetRelativeInfoLimited(sp_lanes.at(l).points, last_point, info, 0); - double front_distance = hypot(firstofother.pos.y - last_point.pos.y, firstofother.pos.x - last_point.pos.x); - bool bCloseFromFront = false; - if((info.bBefore == true && front_distance < 15.0) || info.bBefore == false) - bCloseFromFront = true; - - if(fabs(info.perp_distance) < 2 && fabs(info.perp_distance) < closest_d && info.bAfter == false && bCloseFromFront) - { - closest_d = fabs(info.perp_distance); - pL = &sp_lanes.at(l); - closest_info = info; - closest_info.angle_diff = front_distance; - closest_index = l; - } - } - } - - if(pL != nullptr && pBL != nullptr) - { - if(closest_info.iFront == 0) - { - pL->fromIds.push_back(pBL->id); - pL->points.at(closest_info.iFront).fromIds.push_back(pBL->points.at(pBL->points.size()-1).id); - - pBL->points.at(pBL->points.size()-1).toIds.push_back(pL->points.at(closest_info.iFront).id); - pBL->toIds.push_back(pL->id); - - bAtleastOneChange = true; - if(DEBUG_MAP_PARSING) - { - cout << "Closest Back Lane For: " << pBL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; - cout << "Don't Split , Perfect !" << endl; - } - } - else - { - // split from previous point - if(DEBUG_MAP_PARSING) - cout << "Closest Back Lane For: " << pBL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; - - Lane front_half, back_half; - front_half.points.insert(front_half.points.begin(), pL->points.begin()+closest_info.iFront, pL->points.end()); - front_half.toIds = pL->toIds; - front_half.fromIds.push_back(pL->id); - front_half.fromIds.push_back(pBL->id); - front_half.id = front_half.points.at(0).originalMapID; - front_half.areaId = pL->areaId; - front_half.dir = pL->dir; - front_half.num = pL->num; - front_half.roadId = pL->roadId; - front_half.speed = pL->speed; - front_half.type = pL->type; - front_half.width = pL->width; - - back_half.points.insert(back_half.points.begin(), pL->points.begin(), pL->points.begin()+closest_info.iFront); - back_half.toIds.push_back(front_half.id); - back_half.fromIds = pL->fromIds; - back_half.id = pL->id; - back_half.areaId = pL->areaId; - back_half.dir = pL->dir; - back_half.num = pL->num; - back_half.roadId = pL->roadId; - back_half.speed = pL->speed; - back_half.type = pL->type; - back_half.width = pL->width; - - WayPoint* first_from_next = &front_half.points.at(0); - WayPoint* last_from_front = &pBL->points.at(pBL->points.size()-1); - - first_from_next->fromIds.push_back(last_from_front->id); - last_from_front->toIds.push_back(first_from_next->id); - - if(front_half.points.size() > 1 && back_half.points.size() > 1) - { - if(DEBUG_MAP_PARSING) - cout << "Split this one Nicely! first_half_size: " << front_half.points.size() << ", second_hald_size: " << back_half.points.size() << endl; - - pBL->toIds.push_back(front_half.id); - - if(closest_index >= 0) - sp_lanes.erase(sp_lanes.begin()+closest_index); - else - cout << "## Alert Alert Alert !!!! " << endl; - - // add perp point to lane points - InsertWayPointToBackOfLane(closest_info.perp_point, front_half, g_max_point_id); - InsertWayPointToFrontOfLane(closest_info.perp_point, back_half, g_max_point_id); - - sp_lanes.push_back(front_half); - sp_lanes.push_back(back_half); - bAtleastOneChange = true; - } - else - { - if(DEBUG_MAP_PARSING) - cout << "=> Can't Split this one :( !" << endl; - } - } - } - else - { - if(DEBUG_MAP_PARSING) - cout << "=> Can't find After Lanes For: " << lanes.at(il).id << endl; - } - } - } - - lanes = sp_lanes; + std::vector sp_lanes = lanes; + bool bAtleastOneChange = false; + //Find before lanes + for(unsigned int il=0; il < lanes.size(); il ++) + { + if(lanes.at(il).fromIds.size() == 0) + { + double closest_d = DBL_MAX; + Lane* pL = nullptr; + Lane* pFL = nullptr; + for(int l=0; l < sp_lanes.size(); l ++) + { + if(lanes.at(il).id == sp_lanes.at(l).id) + { + pFL = &sp_lanes.at(l); + break; + } + } + + PlannerHNS::RelativeInfo closest_info; + int closest_index = -1; + for(int l=0; l < sp_lanes.size(); l ++) + { + if(pFL->id != sp_lanes.at(l).id ) + { + PlannerHNS::RelativeInfo info; + WayPoint lastofother = sp_lanes.at(l).points.at(sp_lanes.at(l).points.size()-1); + PlanningHelpers::GetRelativeInfoLimited(sp_lanes.at(l).points, pFL->points.at(0), info, 0); + double back_distance = hypot(lastofother.pos.y - pFL->points.at(0).pos.y, lastofother.pos.x - pFL->points.at(0).pos.x); + bool bCloseFromBack = false; + if((info.bAfter == true && back_distance < 15.0) || info.bAfter == false) + bCloseFromBack = true; + + + if(fabs(info.perp_distance) < 2 && fabs(info.perp_distance) < closest_d && info.bBefore == false && bCloseFromBack) + { + closest_d = fabs(info.perp_distance); + pL = &sp_lanes.at(l); + closest_info = info; + closest_info.angle_diff = back_distance; + closest_index = l; + } + } + } + + if(pL != nullptr && pFL != nullptr) + { + if(closest_info.iFront == pL->points.size()-1) + { + pL->toIds.push_back(pFL->id); + pL->points.at(closest_info.iFront).toIds.push_back(pFL->points.at(0).id); + + pFL->points.at(0).fromIds.push_back(pL->points.at(closest_info.iFront).id); + pFL->fromIds.push_back(pL->id); + bAtleastOneChange = true; + if(DEBUG_MAP_PARSING) + { + cout << "Closest Next Lane For: " << pFL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; + cout << "Don't Split , Perfect !" << endl; + } + } + else + { + // split from previous point + if(DEBUG_MAP_PARSING) + cout << "Closest Next Lane For: " << pFL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; + + Lane front_half, back_half; + front_half.points.insert(front_half.points.begin(), pL->points.begin()+closest_info.iFront, pL->points.end()); + front_half.toIds = pL->toIds; + front_half.fromIds.push_back(pL->id); + front_half.id = front_half.points.at(0).originalMapID; + front_half.areaId = pL->areaId; + front_half.dir = pL->dir; + front_half.num = pL->num; + front_half.roadId = pL->roadId; + front_half.speed = pL->speed; + front_half.type = pL->type; + front_half.width = pL->width; + + back_half.points.insert(back_half.points.begin(), pL->points.begin(), pL->points.begin()+closest_info.iFront); + back_half.toIds.clear(); + back_half.toIds.push_back(front_half.id); + back_half.toIds.push_back(pFL->id); + back_half.fromIds = pL->fromIds; + back_half.id = pL->id; + back_half.areaId = pL->areaId; + back_half.dir = pL->dir; + back_half.num = pL->num; + back_half.roadId = pL->roadId; + back_half.speed = pL->speed; + back_half.type = pL->type; + back_half.width = pL->width; + + WayPoint* last_from_back = &back_half.points.at(back_half.points.size()-1); + WayPoint* first_from_front = &pFL->points.at(0); + + last_from_back->toIds.push_back(first_from_front->id); + first_from_front->fromIds.push_back(last_from_back->id); + + if(front_half.points.size() > 1 && back_half.points.size() > 1) + { + if(DEBUG_MAP_PARSING) + cout << "Split this one Nicely! first_half_size: " << front_half.points.size() << ", second_hald_size: " << back_half.points.size() << endl; + + pFL->fromIds.push_back(back_half.id); + + if(closest_index >= 0) + sp_lanes.erase(sp_lanes.begin()+closest_index); + else + cout << "## Alert Alert Alert !!!! " << endl; + + // add perp point to lane points + InsertWayPointToBackOfLane(closest_info.perp_point, front_half, g_max_point_id); + InsertWayPointToFrontOfLane(closest_info.perp_point, back_half, g_max_point_id); + + sp_lanes.push_back(front_half); + sp_lanes.push_back(back_half); + bAtleastOneChange = true; + } + else + { + if(DEBUG_MAP_PARSING) + cout << "=> Can't Split this one :( !" << endl; + } + } + } + else + { + if(DEBUG_MAP_PARSING) + cout << "=> Can't find Before Lanes For: " << lanes.at(il).id << endl; + } + } + } + + lanes = sp_lanes; + + //Find to lanes + + for(unsigned int il=0; il < lanes.size(); il ++) + { + if(lanes.at(il).toIds.size() == 0) + { + double closest_d = DBL_MAX; + Lane* pL = nullptr; + Lane* pBL = nullptr; + for(int l=0; l < sp_lanes.size(); l ++) + { + if(lanes.at(il).id == sp_lanes.at(l).id) + { + pBL = &sp_lanes.at(l); + break; + } + } + + PlannerHNS::RelativeInfo closest_info; + int closest_index = -1; + for(int l=0; l < sp_lanes.size(); l ++) + { + if(pBL->id != sp_lanes.at(l).id ) + { + PlannerHNS::RelativeInfo info; + WayPoint firstofother = sp_lanes.at(l).points.at(0); + WayPoint last_point = pBL->points.at(pBL->points.size()-1); + PlanningHelpers::GetRelativeInfoLimited(sp_lanes.at(l).points, last_point, info, 0); + double front_distance = hypot(firstofother.pos.y - last_point.pos.y, firstofother.pos.x - last_point.pos.x); + bool bCloseFromFront = false; + if((info.bBefore == true && front_distance < 15.0) || info.bBefore == false) + bCloseFromFront = true; + + if(fabs(info.perp_distance) < 2 && fabs(info.perp_distance) < closest_d && info.bAfter == false && bCloseFromFront) + { + closest_d = fabs(info.perp_distance); + pL = &sp_lanes.at(l); + closest_info = info; + closest_info.angle_diff = front_distance; + closest_index = l; + } + } + } + + if(pL != nullptr && pBL != nullptr) + { + if(closest_info.iFront == 0) + { + pL->fromIds.push_back(pBL->id); + pL->points.at(closest_info.iFront).fromIds.push_back(pBL->points.at(pBL->points.size()-1).id); + + pBL->points.at(pBL->points.size()-1).toIds.push_back(pL->points.at(closest_info.iFront).id); + pBL->toIds.push_back(pL->id); + + bAtleastOneChange = true; + if(DEBUG_MAP_PARSING) + { + cout << "Closest Back Lane For: " << pBL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; + cout << "Don't Split , Perfect !" << endl; + } + } + else + { + // split from previous point + if(DEBUG_MAP_PARSING) + cout << "Closest Back Lane For: " << pBL->id << " , Is:" << pL->id << ", Distance=" << fabs(closest_info.perp_distance) << ", Size: " << pL->points.size() << ", back_index: " << closest_info.iBack <<", front_index: " << closest_info.iFront << ", Direct: " << closest_info.angle_diff << endl; + + Lane front_half, back_half; + front_half.points.insert(front_half.points.begin(), pL->points.begin()+closest_info.iFront, pL->points.end()); + front_half.toIds = pL->toIds; + front_half.fromIds.push_back(pL->id); + front_half.fromIds.push_back(pBL->id); + front_half.id = front_half.points.at(0).originalMapID; + front_half.areaId = pL->areaId; + front_half.dir = pL->dir; + front_half.num = pL->num; + front_half.roadId = pL->roadId; + front_half.speed = pL->speed; + front_half.type = pL->type; + front_half.width = pL->width; + + back_half.points.insert(back_half.points.begin(), pL->points.begin(), pL->points.begin()+closest_info.iFront); + back_half.toIds.push_back(front_half.id); + back_half.fromIds = pL->fromIds; + back_half.id = pL->id; + back_half.areaId = pL->areaId; + back_half.dir = pL->dir; + back_half.num = pL->num; + back_half.roadId = pL->roadId; + back_half.speed = pL->speed; + back_half.type = pL->type; + back_half.width = pL->width; + + WayPoint* first_from_next = &front_half.points.at(0); + WayPoint* last_from_front = &pBL->points.at(pBL->points.size()-1); + + first_from_next->fromIds.push_back(last_from_front->id); + last_from_front->toIds.push_back(first_from_next->id); + + if(front_half.points.size() > 1 && back_half.points.size() > 1) + { + if(DEBUG_MAP_PARSING) + cout << "Split this one Nicely! first_half_size: " << front_half.points.size() << ", second_hald_size: " << back_half.points.size() << endl; + + pBL->toIds.push_back(front_half.id); + + if(closest_index >= 0) + sp_lanes.erase(sp_lanes.begin()+closest_index); + else + cout << "## Alert Alert Alert !!!! " << endl; + + // add perp point to lane points + InsertWayPointToBackOfLane(closest_info.perp_point, front_half, g_max_point_id); + InsertWayPointToFrontOfLane(closest_info.perp_point, back_half, g_max_point_id); + + sp_lanes.push_back(front_half); + sp_lanes.push_back(back_half); + bAtleastOneChange = true; + } + else + { + if(DEBUG_MAP_PARSING) + cout << "=> Can't Split this one :( !" << endl; + } + } + } + else + { + if(DEBUG_MAP_PARSING) + cout << "=> Can't find After Lanes For: " << lanes.at(il).id << endl; + } + } + } + + lanes = sp_lanes; } void MappingHelpers::LinkLanesPointers(PlannerHNS::RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - //Link Lanes - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) - { - pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->toIds.size(); j++) - { - for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) - { - if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) - { - pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); - } - } - } - - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - pL->points.at(j).pLane = pL; - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + //Link Lanes + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int j = 0 ; j < pL->fromIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->fromIds.at(j)) + { + pL->fromLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->toIds.size(); j++) + { + for(unsigned int l= 0; l < map.roadSegments.at(rs).Lanes.size(); l++) + { + if(map.roadSegments.at(rs).Lanes.at(l).id == pL->toIds.at(j)) + { + pL->toLanes.push_back(&map.roadSegments.at(rs).Lanes.at(l)); + } + } + } + + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + pL->points.at(j).pLane = pL; + } + } + } } void MappingHelpers::ExtractCurbDataV2(const std::vector& curb_data, - UtilityHNS::AisanLinesFileReader* pLinedata, - UtilityHNS::AisanPointsFileReader* pPointsData, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int ic=0; ic < curb_data.size(); ic++) - { - Curb c; - c.id = curb_data.at(ic).ID; - - for(unsigned int il=0; il < pLinedata->m_data_list.size() ; il++) - { - if(curb_data.at(ic).LID == pLinedata->m_data_list.at(il).LID) - { - int s_id = pLinedata->m_data_list.at(il).BPID; - if(s_id == 0) - s_id = pLinedata->m_data_list.at(il).FPID; - - AisanPointsFileReader::AisanPoints* pP = pPointsData->GetDataRowById(s_id); - if(pP != nullptr) - { - c.points.push_back(GPSPoint(pP->Ly + origin.x, pP->Bx + origin.y, pP->H + origin.z, 0)); - WayPoint wp; - wp.pos = c.points.at(0); - Lane* pLane = GetClosestLaneFromMap(wp, map, 5); - if(pLane != nullptr) - { - c.laneId = pLane->id; - c.pLane = pLane; - } - } - } - } - map.curbs.push_back(c); - } + UtilityHNS::AisanLinesFileReader* pLinedata, + UtilityHNS::AisanPointsFileReader* pPointsData, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int ic=0; ic < curb_data.size(); ic++) + { + Curb c; + c.id = curb_data.at(ic).ID; + + for(unsigned int il=0; il < pLinedata->m_data_list.size() ; il++) + { + if(curb_data.at(ic).LID == pLinedata->m_data_list.at(il).LID) + { + int s_id = pLinedata->m_data_list.at(il).BPID; + if(s_id == 0) + s_id = pLinedata->m_data_list.at(il).FPID; + + AisanPointsFileReader::AisanPoints* pP = pPointsData->GetDataRowById(s_id); + if(pP != nullptr) + { + c.points.push_back(GPSPoint(pP->Ly + origin.x, pP->Bx + origin.y, pP->H + origin.z, 0)); + WayPoint wp; + wp.pos = c.points.at(0); + Lane* pLane = GetClosestLaneFromMap(wp, map, 5); + if(pLane != nullptr) + { + c.laneId = pLane->id; + c.pLane = pLane; + } + } + } + } + map.curbs.push_back(c); + } } void MappingHelpers::ExtractSignalDataV2(const std::vector& signal_data, - const std::vector& vector_data, - UtilityHNS::AisanPointsFileReader* pPointData, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int is=0; is< signal_data.size(); is++) - { - //if(signal_data.at(is).Type == 2) - { - TrafficLight tl; - tl.id = signal_data.at(is).ID; - tl.linkID = signal_data.at(is).LinkID; - tl.stoppingDistance = 0; - - for(unsigned int iv = 0; iv < vector_data.size(); iv++) - { - if(signal_data.at(is).VID == vector_data.at(iv).VID) - { - AisanPointsFileReader::AisanPoints* pP = pPointData->GetDataRowById(vector_data.at(iv).PID); - if(pP != nullptr) - { - tl.pos = GPSPoint(pP->Ly + origin.x, pP->Bx + origin.y, pP->H + origin.z, vector_data.at(iv).Hang*DEG2RAD); - } - } - } - map.trafficLights.push_back(tl); - if(tl.id > g_max_traffic_light_id) - g_max_traffic_light_id = tl.id; - } - } + const std::vector& vector_data, + UtilityHNS::AisanPointsFileReader* pPointData, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int is=0; is< signal_data.size(); is++) + { + //if(signal_data.at(is).Type == 2) + { + TrafficLight tl; + tl.id = signal_data.at(is).ID; + tl.linkID = signal_data.at(is).LinkID; + tl.stoppingDistance = 0; + + for(unsigned int iv = 0; iv < vector_data.size(); iv++) + { + if(signal_data.at(is).VID == vector_data.at(iv).VID) + { + AisanPointsFileReader::AisanPoints* pP = pPointData->GetDataRowById(vector_data.at(iv).PID); + if(pP != nullptr) + { + tl.pos = GPSPoint(pP->Ly + origin.x, pP->Bx + origin.y, pP->H + origin.z, vector_data.at(iv).Hang*DEG2RAD); + } + } + } + map.trafficLights.push_back(tl); + if(tl.id > g_max_traffic_light_id) + g_max_traffic_light_id = tl.id; + } + } } void MappingHelpers::ExtractStopLinesDataV2(const std::vector& stop_line_data, - UtilityHNS::AisanLinesFileReader* pLineData, - UtilityHNS::AisanPointsFileReader* pPointData, - const GPSPoint& origin, RoadNetwork& map) -{ - for(unsigned int ist=0; ist < stop_line_data.size(); ist++) - { - StopLine sl; - sl.linkID = stop_line_data.at(ist).LinkID; - sl.id = stop_line_data.at(ist).ID; - if(stop_line_data.at(ist).TLID>0) - sl.trafficLightID = stop_line_data.at(ist).TLID; - else - sl.stopSignID = 100+ist; - - AisanLinesFileReader::AisanLine* pLine = pLineData->GetDataRowById(stop_line_data.at(ist).LID); - if(pLine != nullptr) - { - UtilityHNS::AisanPointsFileReader::AisanPoints* pStart = pPointData->GetDataRowById(pLine->BPID); - UtilityHNS::AisanPointsFileReader::AisanPoints* pEnd = pPointData->GetDataRowById(pLine->FPID); - if(pStart != nullptr) - sl.points.push_back(GPSPoint(pStart->Ly + origin.x, pStart->Bx + origin.y, pStart->H + origin.z, 0)); - - if(pEnd != nullptr) - sl.points.push_back(GPSPoint(pEnd->Ly + origin.x, pEnd->Bx + origin.y, pEnd->H + origin.z, 0)); - } - - map.stopLines.push_back(sl); - if(sl.id > g_max_stop_line_id) - g_max_stop_line_id = sl.id; - } + UtilityHNS::AisanLinesFileReader* pLineData, + UtilityHNS::AisanPointsFileReader* pPointData, + const GPSPoint& origin, RoadNetwork& map) +{ + for(unsigned int ist=0; ist < stop_line_data.size(); ist++) + { + StopLine sl; + sl.linkID = stop_line_data.at(ist).LinkID; + sl.id = stop_line_data.at(ist).ID; + if(stop_line_data.at(ist).TLID>0) + sl.trafficLightID = stop_line_data.at(ist).TLID; + else + sl.stopSignID = 100+ist; + + AisanLinesFileReader::AisanLine* pLine = pLineData->GetDataRowById(stop_line_data.at(ist).LID); + if(pLine != nullptr) + { + UtilityHNS::AisanPointsFileReader::AisanPoints* pStart = pPointData->GetDataRowById(pLine->BPID); + UtilityHNS::AisanPointsFileReader::AisanPoints* pEnd = pPointData->GetDataRowById(pLine->FPID); + if(pStart != nullptr) + sl.points.push_back(GPSPoint(pStart->Ly + origin.x, pStart->Bx + origin.y, pStart->H + origin.z, 0)); + + if(pEnd != nullptr) + sl.points.push_back(GPSPoint(pEnd->Ly + origin.x, pEnd->Bx + origin.y, pEnd->H + origin.z, 0)); + } + + map.stopLines.push_back(sl); + if(sl.id > g_max_stop_line_id) + g_max_stop_line_id = sl.id; + } } void MappingHelpers::LinkTrafficLightsAndStopLinesV2(RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - - for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) - { - if(map.stopLines.at(isl).linkID == pWP->originalMapID) - { - map.stopLines.at(isl).laneId = pWP->laneId; - map.stopLines.at(isl).pLane = pWP->pLane; - map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); - - pWP->stopLineID = map.stopLines.at(isl).id; - - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - if(map.trafficLights.at(itl).id == map.stopLines.at(isl).trafficLightID) - { - map.trafficLights.at(itl).laneIds.push_back(pWP->laneId); - map.trafficLights.at(itl).pLanes.push_back(pWP->pLane); - } - } - break; - } - } - } - } - } - - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) - { - for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) - { - WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); - if(map.trafficLights.at(itl).linkID == pWP->originalMapID) - { - map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); - break; - } - } - } - } - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + + for(unsigned int isl = 0; isl < map.stopLines.size(); isl++) + { + if(map.stopLines.at(isl).linkID == pWP->originalMapID) + { + map.stopLines.at(isl).laneId = pWP->laneId; + map.stopLines.at(isl).pLane = pWP->pLane; + map.roadSegments.at(rs).Lanes.at(i).stopLines.push_back(map.stopLines.at(isl)); + + pWP->stopLineID = map.stopLines.at(isl).id; + + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + if(map.trafficLights.at(itl).id == map.stopLines.at(isl).trafficLightID) + { + map.trafficLights.at(itl).laneIds.push_back(pWP->laneId); + map.trafficLights.at(itl).pLanes.push_back(pWP->pLane); + } + } + break; + } + } + } + } + } + + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + for(unsigned int itl = 0; itl < map.trafficLights.size(); itl++) + { + for(unsigned int p= 0; p < map.roadSegments.at(rs).Lanes.at(i).points.size(); p++) + { + WayPoint* pWP = &map.roadSegments.at(rs).Lanes.at(i).points.at(p); + if(map.trafficLights.at(itl).linkID == pWP->originalMapID) + { + map.roadSegments.at(rs).Lanes.at(i).trafficlights.push_back(map.trafficLights.at(itl)); + break; + } + } + } + } + } } void MappingHelpers::FindAdjacentLanesV2(RoadNetwork& map) { - bool bTestDebug = false; - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - for(unsigned int i2 =0; i2 < map.roadSegments.at(rs).Lanes.size(); i2++) - { - Lane* pL2 = &map.roadSegments.at(rs).Lanes.at(i2); - - if(pL->id == pL2->id) continue; - - - if(pL->id == 1683) - bTestDebug = true; - - for(unsigned int p=0; p < pL->points.size(); p++) - { - WayPoint* pWP = &pL->points.at(p); - RelativeInfo info; - PlanningHelpers::GetRelativeInfoLimited(pL2->points, *pWP, info); - - if(!info.bAfter && !info.bBefore && fabs(info.perp_distance) > 1.2 && fabs(info.perp_distance) < 3.5 && UtilityH::AngleBetweenTwoAnglesPositive(info.perp_point.pos.a, pWP->pos.a) < 0.06) - { - WayPoint* pWP2 = &pL2->points.at(info.iFront); - if(info.perp_distance < 0) - { - if(pWP->pRight == 0) - { - pWP->pRight = pWP2; - pWP->RightPointId = pWP2->id; - pWP->RightLnId = pL2->id; - pL->pRightLane = pL2; - - } - - if(pWP2->pLeft == 0) - { - pWP2->pLeft = pWP; - pWP2->LeftPointId = pWP->id; - pWP2->LeftLnId = pL->id; - pL2->pLeftLane = pL; - } - } - else - { - if(pWP->pLeft == 0) - { - pWP->pLeft = pWP2; - pWP->LeftPointId = pWP2->id; - pWP->LeftLnId = pL2->id; - pL->pLeftLane = pL2; - } - - if(pWP2->pRight == 0) - { - pWP2->pRight = pWP->pLeft; - pWP2->RightPointId = pWP->id; - pWP2->RightLnId = pL->id; - pL2->pRightLane = pL; - } - } - } - } - } - } - } + bool bTestDebug = false; + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + for(unsigned int i2 =0; i2 < map.roadSegments.at(rs).Lanes.size(); i2++) + { + Lane* pL2 = &map.roadSegments.at(rs).Lanes.at(i2); + + if(pL->id == pL2->id) continue; + + + if(pL->id == 1683) + bTestDebug = true; + + for(unsigned int p=0; p < pL->points.size(); p++) + { + WayPoint* pWP = &pL->points.at(p); + RelativeInfo info; + PlanningHelpers::GetRelativeInfoLimited(pL2->points, *pWP, info); + + if(!info.bAfter && !info.bBefore && fabs(info.perp_distance) > 1.2 && fabs(info.perp_distance) < 3.5 && UtilityH::AngleBetweenTwoAnglesPositive(info.perp_point.pos.a, pWP->pos.a) < 0.06) + { + WayPoint* pWP2 = &pL2->points.at(info.iFront); + if(info.perp_distance < 0) + { + if(pWP->pRight == 0) + { + pWP->pRight = pWP2; + pWP->RightPointId = pWP2->id; + pWP->RightLnId = pL2->id; + pL->pRightLane = pL2; + + } + + if(pWP2->pLeft == 0) + { + pWP2->pLeft = pWP; + pWP2->LeftPointId = pWP->id; + pWP2->LeftLnId = pL->id; + pL2->pLeftLane = pL; + } + } + else + { + if(pWP->pLeft == 0) + { + pWP->pLeft = pWP2; + pWP->LeftPointId = pWP2->id; + pWP->LeftLnId = pL2->id; + pL->pLeftLane = pL2; + } + + if(pWP2->pRight == 0) + { + pWP2->pRight = pWP->pLeft; + pWP2->RightPointId = pWP->id; + pWP2->RightLnId = pL->id; + pL2->pRightLane = pL; + } + } + } + } + } + } + } } void MappingHelpers::GetMapMaxIds(PlannerHNS::RoadNetwork& map) { - for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) - { - for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) - { - Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); - if(pL->id > g_max_lane_id) - g_max_lane_id = pL->id; - - for(unsigned int j = 0 ; j < pL->points.size(); j++) - { - if(pL->points.at(j).id > g_max_point_id) - { - g_max_point_id = pL->points.at(j).id; - } - } - } - } - - for(unsigned int i=0; i < map.stopLines.size(); i++) - { - if(map.stopLines.at(i).id > g_max_stop_line_id) - g_max_stop_line_id = map.stopLines.at(i).id; - } - - for(unsigned int i=0; i < map.trafficLights.size(); i++) - { - if(map.trafficLights.at(i).id > g_max_traffic_light_id) - g_max_traffic_light_id = map.trafficLights.at(i).id; - } + for(unsigned int rs = 0; rs < map.roadSegments.size(); rs++) + { + for(unsigned int i =0; i < map.roadSegments.at(rs).Lanes.size(); i++) + { + Lane* pL = &map.roadSegments.at(rs).Lanes.at(i); + if(pL->id > g_max_lane_id) + g_max_lane_id = pL->id; + + for(unsigned int j = 0 ; j < pL->points.size(); j++) + { + if(pL->points.at(j).id > g_max_point_id) + { + g_max_point_id = pL->points.at(j).id; + } + } + } + } + + for(unsigned int i=0; i < map.stopLines.size(); i++) + { + if(map.stopLines.at(i).id > g_max_stop_line_id) + g_max_stop_line_id = map.stopLines.at(i).id; + } + + for(unsigned int i=0; i < map.trafficLights.size(); i++) + { + if(map.trafficLights.at(i).id > g_max_traffic_light_id) + g_max_traffic_light_id = map.trafficLights.at(i).id; + } } diff --git a/common/op_planner/src/PassiveDecisionMaker.cpp b/common/op_planner/src/PassiveDecisionMaker.cpp index 3a5480c00a0..8a02ec2a87c 100755 --- a/common/op_planner/src/PassiveDecisionMaker.cpp +++ b/common/op_planner/src/PassiveDecisionMaker.cpp @@ -20,7 +20,7 @@ PassiveDecisionMaker::PassiveDecisionMaker() PassiveDecisionMaker& PassiveDecisionMaker::operator=(const PassiveDecisionMaker& obj) { - return *this; + return *this; } PassiveDecisionMaker::PassiveDecisionMaker(const PassiveDecisionMaker& obj) @@ -33,15 +33,15 @@ PassiveDecisionMaker::~PassiveDecisionMaker() double PassiveDecisionMaker::GetVelocity(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo, const RelativeInfo& info) { - double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 1.0; - int prev_index = 0; - double velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(path, info, prev_index, average_braking_distance); - if(velocity > carInfo.max_speed_forward) - velocity = carInfo.max_speed_forward; - else if(velocity < carInfo.min_speed_forward) - velocity = carInfo.min_speed_forward; - - return velocity; + double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 1.0; + int prev_index = 0; + double velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(path, info, prev_index, average_braking_distance); + if(velocity > carInfo.max_speed_forward) + velocity = carInfo.max_speed_forward; + else if(velocity < carInfo.min_speed_forward) + velocity = carInfo.min_speed_forward; + + return velocity; } double PassiveDecisionMaker::GetSteerAngle(PlannerHNS::WayPoint& currPose, const std::vector& path, const RelativeInfo& info) @@ -60,93 +60,93 @@ PassiveDecisionMaker::~PassiveDecisionMaker() bool PassiveDecisionMaker::CheckForStopLine(PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo) { - double minStoppingDistance = -pow(currPose.v, 2)/(carInfo.max_deceleration); - double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0; + double minStoppingDistance = -pow(currPose.v, 2)/(carInfo.max_deceleration); + double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0; - int stopLineID = -1; - int stopSignID = -1; - int trafficLightID = -1; - double distanceToClosestStopLine = 0; + int stopLineID = -1; + int stopSignID = -1; + int trafficLightID = -1; + double distanceToClosestStopLine = 0; - distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(path, currPose, 0, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; + distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(path, currPose, 0, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance; - if(distanceToClosestStopLine > -2 && distanceToClosestStopLine < minStoppingDistance) - { - return true; - } + if(distanceToClosestStopLine > -2 && distanceToClosestStopLine < minStoppingDistance) + { + return true; + } - return false; + return false; } PlannerHNS::BehaviorState PassiveDecisionMaker::MoveStep(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo) { - PlannerHNS::BehaviorState beh; - if(path.size() == 0) return beh; + PlannerHNS::BehaviorState beh; + if(path.size() == 0) return beh; - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(path, currPose, info); + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(path, currPose, info); - bool bStopLine = CheckForStopLine(currPose, path, carInfo); - if(bStopLine) - beh.state = PlannerHNS::STOPPING_STATE; - else - beh.state = PlannerHNS::FORWARD_STATE; + bool bStopLine = CheckForStopLine(currPose, path, carInfo); + if(bStopLine) + beh.state = PlannerHNS::STOPPING_STATE; + else + beh.state = PlannerHNS::FORWARD_STATE; - double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 1.0; + double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 1.0; - if(average_braking_distance < 10) - average_braking_distance = 10; + if(average_braking_distance < 10) + average_braking_distance = 10; - beh.indicator = PlanningHelpers::GetIndicatorsFromPath(path, currPose, average_braking_distance); + beh.indicator = PlanningHelpers::GetIndicatorsFromPath(path, currPose, average_braking_distance); - currPose.v = beh.maxVelocity = GetVelocity(currPose, path, carInfo, info); + currPose.v = beh.maxVelocity = GetVelocity(currPose, path, carInfo, info); - double steer = GetSteerAngle(currPose, path, info); + double steer = GetSteerAngle(currPose, path, info); - currPose.pos.x += currPose.v * dt * cos(currPose.pos.a); - currPose.pos.y += currPose.v * dt * sin(currPose.pos.a); - currPose.pos.a += currPose.v * dt * tan(steer) / carInfo.wheel_base; + currPose.pos.x += currPose.v * dt * cos(currPose.pos.a); + currPose.pos.y += currPose.v * dt * sin(currPose.pos.a); + currPose.pos.a += currPose.v * dt * tan(steer) / carInfo.wheel_base; - return beh; + return beh; } PlannerHNS::ParticleInfo PassiveDecisionMaker::MoveStepSimple(const double& dt, PlannerHNS::WayPoint& currPose, const std::vector& path, const CAR_BASIC_INFO& carInfo) { - PlannerHNS::ParticleInfo beh; - if(path.size() == 0) return beh; + PlannerHNS::ParticleInfo beh; + if(path.size() == 0) return beh; - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(path, currPose, info); + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(path, currPose, info); - bool bStopLine = CheckForStopLine(currPose, path, carInfo); - if(bStopLine) - beh.state = PlannerHNS::STOPPING_STATE; - else - beh.state = PlannerHNS::FORWARD_STATE; + bool bStopLine = CheckForStopLine(currPose, path, carInfo); + if(bStopLine) + beh.state = PlannerHNS::STOPPING_STATE; + else + beh.state = PlannerHNS::FORWARD_STATE; - double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 15.0; + double average_braking_distance = -pow(currPose.v, 2)/(carInfo.max_deceleration) + 15.0; - PlannerHNS::WayPoint startPose = path.at(0); - beh.indicator = PlanningHelpers::GetIndicatorsFromPath(path, startPose, average_braking_distance); + PlannerHNS::WayPoint startPose = path.at(0); + beh.indicator = PlanningHelpers::GetIndicatorsFromPath(path, startPose, average_braking_distance); - double speed = 0; - if(info.iFront < path.size()) - { - beh.vel = path.at(info.iFront).v; - } - else - beh.vel = 0; + double speed = 0; + if(info.iFront < path.size()) + { + beh.vel = path.at(info.iFront).v; + } + else + beh.vel = 0; - double steer = GetSteerAngle(currPose, path, info); + double steer = GetSteerAngle(currPose, path, info); - currPose.pos.x += currPose.v * dt * cos(currPose.pos.a); - currPose.pos.y += currPose.v * dt * sin(currPose.pos.a); - currPose.pos.a += currPose.v * dt * tan(steer) / carInfo.wheel_base; + currPose.pos.x += currPose.v * dt * cos(currPose.pos.a); + currPose.pos.y += currPose.v * dt * sin(currPose.pos.a); + currPose.pos.a += currPose.v * dt * tan(steer) / carInfo.wheel_base; - return beh; + return beh; } diff --git a/common/op_planner/src/PlannerH.cpp b/common/op_planner/src/PlannerH.cpp index 46da2460358..ed2899461af 100755 --- a/common/op_planner/src/PlannerH.cpp +++ b/common/op_planner/src/PlannerH.cpp @@ -15,7 +15,7 @@ namespace PlannerHNS { PlannerH::PlannerH() { - //m_Params = params; + //m_Params = params; } PlannerH::~PlannerH() @@ -23,470 +23,489 @@ PlannerH::~PlannerH() } void PlannerH::GenerateRunoffTrajectory(const std::vector >& referencePaths,const WayPoint& carPos, const bool& bEnableLaneChange, const double& speed, const double& microPlanDistance, - const double& maxSpeed,const double& minSpeed, const double& carTipMargin, const double& rollInMargin, - const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, - const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, - const double& SmoothTolerance, const double& speedProfileFactor, const bool& bHeadingSmooth, - const int& iCurrGlobalPath, const int& iCurrLocalTraj, - std::vector > >& rollOutsPaths, - std::vector& sampledPoints_debug) + const double& maxSpeed,const double& minSpeed, const double& carTipMargin, const double& rollInMargin, + const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, + const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, + const double& SmoothTolerance, const double& speedProfileFactor, const bool& bHeadingSmooth, + const int& iCurrGlobalPath, const int& iCurrLocalTraj, + std::vector > >& rollOutsPaths, + std::vector& sampledPoints_debug) { - if(referencePaths.size()==0) return; - if(microPlanDistance <=0 ) return; - rollOutsPaths.clear(); - - sampledPoints_debug.clear(); //for visualization only - - for(unsigned int i = 0; i < referencePaths.size(); i++) - { - std::vector > local_rollOutPaths; - int s_index = 0, e_index = 0; - vector e_distances; - if(referencePaths.at(i).size()>0) - { - PlanningHelpers::CalculateRollInTrajectories(carPos, speed, referencePaths.at(i), s_index, e_index, e_distances, - local_rollOutPaths, microPlanDistance, maxSpeed, carTipMargin, rollInMargin, - rollInSpeedFactor, pathDensity, rollOutDensity,rollOutNumber, - SmoothDataWeight, SmoothWeight, SmoothTolerance, bHeadingSmooth, sampledPoints_debug); - } - else - { - for(int j=0; j< rollOutNumber+1; j++) - { - local_rollOutPaths.push_back(vector()); - } - } - - rollOutsPaths.push_back(local_rollOutPaths); - } + if(referencePaths.size()==0) return; + if(microPlanDistance <=0 ) return; + rollOutsPaths.clear(); + + sampledPoints_debug.clear(); //for visualization only + + for(unsigned int i = 0; i < referencePaths.size(); i++) + { + std::vector > local_rollOutPaths; + int s_index = 0, e_index = 0; + vector e_distances; + if(referencePaths.at(i).size()>0) + { + PlanningHelpers::CalculateRollInTrajectories(carPos, speed, referencePaths.at(i), s_index, e_index, e_distances, + local_rollOutPaths, microPlanDistance, maxSpeed, carTipMargin, rollInMargin, + rollInSpeedFactor, pathDensity, rollOutDensity,rollOutNumber, + SmoothDataWeight, SmoothWeight, SmoothTolerance, bHeadingSmooth, sampledPoints_debug); + } + else + { + for(int j=0; j< rollOutNumber+1; j++) + { + local_rollOutPaths.push_back(vector()); + } + } + + rollOutsPaths.push_back(local_rollOutPaths); + } } double PlannerH::PlanUsingDPRandom(const WayPoint& start, - const double& maxPlanningDistance, - RoadNetwork& map, - std::vector >& paths) + const double& maxPlanningDistance, + RoadNetwork& map, + std::vector >& paths) { - PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestBackWaypointFromMap(start, map); - - if(!pStart) - { - GPSPoint sp = start.pos; - cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ")" << endl; - return 0; - } - - if(!pStart->pLane) - { - cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ")" << endl; - return 0; - } - - RelativeInfo start_info; - PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info); - - if(start_info.perp_distance > START_POINT_MAX_DISTANCE) - { - GPSPoint sp = start.pos; - cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance - << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString() - << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl; - return 0; - } - - vector local_cell_to_delete; - WayPoint* pLaneCell = 0; - pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, maxPlanningDistance, local_cell_to_delete); - - if(!pLaneCell) - { - cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl; - return 0; - } - - - vector path; - vector > tempCurrentForwardPathss; - const std::vector globalPath; - PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss); - cout << endl <<"Info: PlannerH -> Plan (B) Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl; - - //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_RIGHT_DIR); - //cout << "Right Branch Created with Size: " << path.size() << endl; - //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_LEFT_DIR); - paths.push_back(path); - - if(path.size()<2) - { - cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl; - if(pLaneCell) - DeleteWaypoints(local_cell_to_delete); - return 0 ; - } - - if(pLaneCell) - DeleteWaypoints(local_cell_to_delete); - - double totalPlanningDistance = path.at(path.size()-1).cost; - return totalPlanningDistance; + PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestBackWaypointFromMap(start, map); + + if(!pStart) + { + GPSPoint sp = start.pos; + cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ")" << endl; + return 0; + } + + if(!pStart->pLane) + { + cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ")" << endl; + return 0; + } + + RelativeInfo start_info; + if(!PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info)) + { + cout << endl << "Error: PlannerH -> GetRelativeInfo for start failed"; + return 0; + } + + if(start_info.perp_distance > START_POINT_MAX_DISTANCE) + { + GPSPoint sp = start.pos; + cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance + << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString() + << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl; + return 0; + } + + vector local_cell_to_delete; + WayPoint* pLaneCell = 0; + pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, maxPlanningDistance, local_cell_to_delete); + + if(!pLaneCell) + { + cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl; + return 0; + } + + + vector path; + vector > tempCurrentForwardPathss; + const std::vector globalPath; + PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss); + cout << endl <<"Info: PlannerH -> Plan (B) Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl; + + //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_RIGHT_DIR); + //cout << "Right Branch Created with Size: " << path.size() << endl; + //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_LEFT_DIR); + paths.push_back(path); + + if(path.size()<2) + { + cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl; + if(pLaneCell) + DeleteWaypoints(local_cell_to_delete); + return 0 ; + } + + if(pLaneCell) + DeleteWaypoints(local_cell_to_delete); + + double totalPlanningDistance = path.at(path.size()-1).cost; + return totalPlanningDistance; } double PlannerH::PlanUsingDP(const WayPoint& start, - const WayPoint& goalPos, - const double& maxPlanningDistance, - const bool bEnableLaneChange, - const std::vector& globalPath, - RoadNetwork& map, - std::vector >& paths, vector* all_cell_to_delete) + const WayPoint& goalPos, + const double& maxPlanningDistance, + const bool bEnableLaneChange, + const std::vector& globalPath, + RoadNetwork& map, + std::vector >& paths, + vector* all_cell_to_delete, + double fallback_min_goal_distance_th) { - PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(start, map); - PlannerHNS::WayPoint* pGoal = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(goalPos, map); - bool bEnableGoalBranching = false; - - if(!pStart || !pGoal) - { - GPSPoint sp = start.pos; - GPSPoint gp = goalPos.pos; - cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ") and Goal (" << gp.ToString() << ")" << endl; - return 0; - } - - if(!pStart->pLane || !pGoal->pLane) - { - cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ") and Goal (" << pGoal->pLane << ")" << endl; - return 0; - } - - RelativeInfo start_info, goal_info; - PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info); - PlanningHelpers::GetRelativeInfo(pGoal->pLane->points, goalPos, goal_info); - - vector start_path, goal_path; - - if(fabs(start_info.perp_distance) > START_POINT_MAX_DISTANCE) - { - GPSPoint sp = start.pos; - cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance - << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString() - << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl; - return 0; - } - - if(fabs(goal_info.perp_distance) > GOAL_POINT_MAX_DISTANCE) - { - if(fabs(start_info.perp_distance) > 20) - { - GPSPoint gp = goalPos.pos; - cout << endl << "Error: PlannerH -> Goal Distance to Lane is: " << goal_info.perp_distance - << ", Pose: " << gp.ToString() << ", LanePose:" << goal_info.perp_point.pos.ToString() - << ", LaneID: " << pGoal->pLane->id << " -> Check origin and vector map. " << endl; - return 0; - } - else - { - WayPoint wp = *pGoal; - wp.pos.x = (goalPos.pos.x+pGoal->pos.x)/2.0; - wp.pos.y = (goalPos.pos.y+pGoal->pos.y)/2.0; - goal_path.push_back(wp); - goal_path.push_back(goalPos); - } - } - - vector local_cell_to_delete; - WayPoint* pLaneCell = 0; - char bPlan = 'A'; - - if(all_cell_to_delete) - pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, *pGoal, globalPath, maxPlanningDistance,bEnableLaneChange, *all_cell_to_delete); - else - pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, *pGoal, globalPath, maxPlanningDistance,bEnableLaneChange, local_cell_to_delete); - - if(!pLaneCell) - { - bPlan = 'B'; - cout << endl << "PlannerH -> Plan (A) Failed, Trying Plan (B)." << endl; - - if(all_cell_to_delete) - pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, *all_cell_to_delete); - else - pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, local_cell_to_delete); - - if(!pLaneCell) - { - bPlan = 'Z'; - cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl; - return 0; - } - } - - vector path; - vector > tempCurrentForwardPathss; - PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss); - if(path.size()==0) return 0; - - paths.clear(); - - if(bPlan == 'A') - { - PlanningHelpers::ExtractPlanAlernatives(path, paths); - } - else if (bPlan == 'B') - { - paths.push_back(path); - } - - //attach start path to beginning of all paths, but goal path to only the path connected to the goal path. - for(unsigned int i=0; i< paths.size(); i++ ) - { - paths.at(i).insert(paths.at(i).begin(), start_path.begin(), start_path.end()); - if(paths.at(i).size() > 0) - { - //if(hypot(paths.at(i).at(paths.at(i).size()-1).pos.y-goal_info.perp_point.pos.y, paths.at(i).at(paths.at(i).size()-1).pos.x-goal_info.perp_point.pos.x) < 1.5) - { - - if(paths.at(i).size() > 0 && goal_path.size() > 0) - { - goal_path.insert(goal_path.begin(), paths.at(i).end()-5, paths.at(i).end()); - PlanningHelpers::SmoothPath(goal_path, 0.25, 0.25); - PlanningHelpers::FixPathDensity(goal_path, 0.75); - PlanningHelpers::SmoothPath(goal_path, 0.25, 0.35); - paths.at(i).erase(paths.at(i).end()-5, paths.at(i).end()); - paths.at(i).insert(paths.at(i).end(), goal_path.begin(), goal_path.end()); - } - } - } - } - - cout << endl <<"Info: PlannerH -> Plan (" << bPlan << ") Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl; - - - if(path.size()<2) - { - cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl; - if(pLaneCell && !all_cell_to_delete) - DeleteWaypoints(local_cell_to_delete); - return 0 ; - } - - if(pLaneCell && !all_cell_to_delete) - DeleteWaypoints(local_cell_to_delete); - - double totalPlanningDistance = path.at(path.size()-1).cost; - return totalPlanningDistance; + PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(start, map); + PlannerHNS::WayPoint* pGoal = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(goalPos, map); + bool bEnableGoalBranching = false; + + if(!pStart || !pGoal) + { + GPSPoint sp = start.pos; + GPSPoint gp = goalPos.pos; + cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ") and Goal (" << gp.ToString() << ")" << endl; + return 0; + } + + if(!pStart->pLane || !pGoal->pLane) + { + cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ") and Goal (" << pGoal->pLane << ")" << endl; + return 0; + } + + RelativeInfo start_info, goal_info; + if(!PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info)) + { + cout << endl << "Error: PlannerH -> GetRelativeInfo for start failed"; + return 0; + } + if(!PlanningHelpers::GetRelativeInfo(pGoal->pLane->points, goalPos, goal_info)) { + cout << endl << "Error: PlannerH -> GetRelativeInfo for goal failed"; + return 0; + } + + vector start_path, goal_path; + + if(fabs(start_info.perp_distance) > START_POINT_MAX_DISTANCE) + { + GPSPoint sp = start.pos; + cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance + << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString() + << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl; + return 0; + } + + if(fabs(goal_info.perp_distance) > GOAL_POINT_MAX_DISTANCE) + { + if(fabs(start_info.perp_distance) > 20) + { + GPSPoint gp = goalPos.pos; + cout << endl << "Error: PlannerH -> Goal Distance to Lane is: " << goal_info.perp_distance + << ", Pose: " << gp.ToString() << ", LanePose:" << goal_info.perp_point.pos.ToString() + << ", LaneID: " << pGoal->pLane->id << " -> Check origin and vector map. " << endl; + return 0; + } + else + { + WayPoint wp = *pGoal; + wp.pos.x = (goalPos.pos.x+pGoal->pos.x)/2.0; + wp.pos.y = (goalPos.pos.y+pGoal->pos.y)/2.0; + goal_path.push_back(wp); + goal_path.push_back(goalPos); + } + } + + vector local_cell_to_delete; + WayPoint* pLaneCell = 0; + char bPlan = 'A'; + + if(all_cell_to_delete) + pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, + *pGoal, globalPath, maxPlanningDistance, + bEnableLaneChange, *all_cell_to_delete, + fallback_min_goal_distance_th); + else + pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, + *pGoal, globalPath, maxPlanningDistance, + bEnableLaneChange, local_cell_to_delete, + fallback_min_goal_distance_th); + + if(!pLaneCell) + { + bPlan = 'B'; + cout << endl << "PlannerH -> Plan (A) Failed, Trying Plan (B)." << endl; + + if(all_cell_to_delete) + pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, *all_cell_to_delete); + else + pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, local_cell_to_delete); + + if(!pLaneCell) + { + bPlan = 'Z'; + cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl; + return 0; + } + } + + vector path; + vector > tempCurrentForwardPathss; + PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss); + if(path.size()==0) return 0; + + paths.clear(); + + if(bPlan == 'A') + { + PlanningHelpers::ExtractPlanAlernatives(path, paths); + } + else if (bPlan == 'B') + { + paths.push_back(path); + } + + //attach start path to beginning of all paths, but goal path to only the path connected to the goal path. + for(unsigned int i=0; i< paths.size(); i++ ) + { + paths.at(i).insert(paths.at(i).begin(), start_path.begin(), start_path.end()); + if(paths.at(i).size() > 0) + { + //if(hypot(paths.at(i).at(paths.at(i).size()-1).pos.y-goal_info.perp_point.pos.y, paths.at(i).at(paths.at(i).size()-1).pos.x-goal_info.perp_point.pos.x) < 1.5) + { + + if(paths.at(i).size() > 0 && goal_path.size() > 0) + { + goal_path.insert(goal_path.begin(), paths.at(i).end()-5, paths.at(i).end()); + PlanningHelpers::SmoothPath(goal_path, 0.25, 0.25); + PlanningHelpers::FixPathDensity(goal_path, 0.75); + PlanningHelpers::SmoothPath(goal_path, 0.25, 0.35); + paths.at(i).erase(paths.at(i).end()-5, paths.at(i).end()); + paths.at(i).insert(paths.at(i).end(), goal_path.begin(), goal_path.end()); + } + } + } + } + + cout << endl <<"Info: PlannerH -> Plan (" << bPlan << ") Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl; + + + if(path.size()<2) + { + cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl; + if(pLaneCell && !all_cell_to_delete) + DeleteWaypoints(local_cell_to_delete); + return 0 ; + } + + if(pLaneCell && !all_cell_to_delete) + DeleteWaypoints(local_cell_to_delete); + + double totalPlanningDistance = path.at(path.size()-1).cost; + return totalPlanningDistance; } double PlannerH::PredictPlanUsingDP(PlannerHNS::Lane* l, const WayPoint& start, const double& maxPlanningDistance, std::vector >& paths) { - if(!l) - { - cout < Null Lane !!" << endl; - return 0; - } - - WayPoint carPos = start; - vector > tempCurrentForwardPathss; - vector all_cell_to_delete; - vector globalPath; - - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(l->points, carPos, info); - WayPoint closest_p = l->points.at(info.iBack); - WayPoint* pStartWP = &l->points.at(info.iBack); - - if(distance2points(closest_p.pos, carPos.pos) > 8) - { - cout < Distance to Lane is: " << distance2points(closest_p.pos, carPos.pos) - << ", Pose: " << carPos.pos.ToString() << ", LanePose:" << closest_p.pos.ToString() - << ", LaneID: " << l->id << " -> Check origin and vector map. " << endl; - return 0; - } - - vector pLaneCells; - int nPaths = PlanningHelpers::PredictiveDP(pStartWP, maxPlanningDistance, all_cell_to_delete, pLaneCells); - - if(nPaths==0) - { - cout < Null Tree Head." << endl; - return 0; - } - - double totalPlanDistance = 0; - for(unsigned int i = 0; i< pLaneCells.size(); i++) - { - std::vector path; - PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), pStartWP, globalPath, path, tempCurrentForwardPathss); - if(path.size()>0) - totalPlanDistance+= path.at(path.size()-1).cost; - - PlanningHelpers::FixPathDensity(path, 0.5); - PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1); - PlanningHelpers::CalcAngleAndCost(path); - - paths.push_back(path); - } - - DeleteWaypoints(all_cell_to_delete); - - return totalPlanDistance; + if(!l) + { + cout < Null Lane !!" << endl; + return 0; + } + + WayPoint carPos = start; + vector > tempCurrentForwardPathss; + vector all_cell_to_delete; + vector globalPath; + + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(l->points, carPos, info); + WayPoint closest_p = l->points.at(info.iBack); + WayPoint* pStartWP = &l->points.at(info.iBack); + + if(distance2points(closest_p.pos, carPos.pos) > 8) + { + cout < Distance to Lane is: " << distance2points(closest_p.pos, carPos.pos) + << ", Pose: " << carPos.pos.ToString() << ", LanePose:" << closest_p.pos.ToString() + << ", LaneID: " << l->id << " -> Check origin and vector map. " << endl; + return 0; + } + + vector pLaneCells; + int nPaths = PlanningHelpers::PredictiveDP(pStartWP, maxPlanningDistance, all_cell_to_delete, pLaneCells); + + if(nPaths==0) + { + cout < Null Tree Head." << endl; + return 0; + } + + double totalPlanDistance = 0; + for(unsigned int i = 0; i< pLaneCells.size(); i++) + { + std::vector path; + PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), pStartWP, globalPath, path, tempCurrentForwardPathss); + if(path.size()>0) + totalPlanDistance+= path.at(path.size()-1).cost; + + PlanningHelpers::FixPathDensity(path, 0.5); + PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1); + PlanningHelpers::CalcAngleAndCost(path); + + paths.push_back(path); + } + + DeleteWaypoints(all_cell_to_delete); + + return totalPlanDistance; } double PlannerH::PredictTrajectoriesUsingDP(const WayPoint& startPose, std::vector closestWPs, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches , const bool bDirectionBased, const bool pathDensity) { - vector > tempCurrentForwardPathss; - vector all_cell_to_delete; - vector globalPath; - - vector pLaneCells; - vector unique_lanes; - std::vector path; - for(unsigned int j = 0 ; j < closestWPs.size(); j++) - { - pLaneCells.clear(); - int nPaths = PlanningHelpers::PredictiveIgnorIdsDP(closestWPs.at(j), maxPlanningDistance, all_cell_to_delete, pLaneCells, unique_lanes); - for(unsigned int i = 0; i< pLaneCells.size(); i++) - { - path.clear(); - PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWPs.at(j), globalPath, path, tempCurrentForwardPathss); - - for(unsigned int k = 0; k< path.size(); k++) - { - bool bFoundLaneID = false; - for(unsigned int l_id = 0 ; l_id < unique_lanes.size(); l_id++) - { - if(path.at(k).laneId == unique_lanes.at(l_id)) - { - bFoundLaneID = true; - break; - } - } - - if(!bFoundLaneID) - unique_lanes.push_back(path.at(k).laneId); - } - - if(path.size()>0) - { - path.insert(path.begin(), startPose); - if(!bDirectionBased) - path.at(0).pos.a = path.at(1).pos.a; - - path.at(0).beh_state = path.at(1).beh_state = PlannerHNS::BEH_FORWARD_STATE; - path.at(0).laneId = path.at(1).laneId; - - PlanningHelpers::FixPathDensity(path, pathDensity); - PlanningHelpers::SmoothPath(path,0.4,0.3,0.1); - PlanningHelpers::CalcAngleAndCost(path); - paths.push_back(path); - } - } - } - - if(bDirectionBased && bFindBranches) - { - WayPoint p1, p2; - if(paths.size()> 0 && paths.at(0).size() > 0) - p2 = p1 = paths.at(0).at(0); - else - p2 = p1 = startPose; - - double branch_length = maxPlanningDistance*0.5; - - p2.pos.y = p1.pos.y + branch_length*0.4*sin(p1.pos.a); - p2.pos.x = p1.pos.x + branch_length*0.4*cos(p1.pos.a); - - vector l_branch; - vector r_branch; - - PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_RIGHT_DIR,r_branch); - PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_LEFT_DIR, l_branch); - - PlanningHelpers::FixPathDensity(l_branch, pathDensity); - PlanningHelpers::SmoothPath(l_branch,0.4,0.3,0.1); - PlanningHelpers::CalcAngleAndCost(l_branch); - - PlanningHelpers::FixPathDensity(r_branch, pathDensity); - PlanningHelpers::SmoothPath(r_branch,0.4,0.3,0.1); - PlanningHelpers::CalcAngleAndCost(r_branch); - - paths.push_back(l_branch); - paths.push_back(r_branch); - } - - DeleteWaypoints(all_cell_to_delete); - - return paths.size(); + vector > tempCurrentForwardPathss; + vector all_cell_to_delete; + vector globalPath; + + vector pLaneCells; + vector unique_lanes; + std::vector path; + for(unsigned int j = 0 ; j < closestWPs.size(); j++) + { + pLaneCells.clear(); + int nPaths = PlanningHelpers::PredictiveIgnorIdsDP(closestWPs.at(j), maxPlanningDistance, all_cell_to_delete, pLaneCells, unique_lanes); + for(unsigned int i = 0; i< pLaneCells.size(); i++) + { + path.clear(); + PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWPs.at(j), globalPath, path, tempCurrentForwardPathss); + + for(unsigned int k = 0; k< path.size(); k++) + { + bool bFoundLaneID = false; + for(unsigned int l_id = 0 ; l_id < unique_lanes.size(); l_id++) + { + if(path.at(k).laneId == unique_lanes.at(l_id)) + { + bFoundLaneID = true; + break; + } + } + + if(!bFoundLaneID) + unique_lanes.push_back(path.at(k).laneId); + } + + if(path.size()>0) + { + path.insert(path.begin(), startPose); + if(!bDirectionBased) + path.at(0).pos.a = path.at(1).pos.a; + + path.at(0).beh_state = path.at(1).beh_state = PlannerHNS::BEH_FORWARD_STATE; + path.at(0).laneId = path.at(1).laneId; + + PlanningHelpers::FixPathDensity(path, pathDensity); + PlanningHelpers::SmoothPath(path,0.4,0.3,0.1); + PlanningHelpers::CalcAngleAndCost(path); + paths.push_back(path); + } + } + } + + if(bDirectionBased && bFindBranches) + { + WayPoint p1, p2; + if(paths.size()> 0 && paths.at(0).size() > 0) + p2 = p1 = paths.at(0).at(0); + else + p2 = p1 = startPose; + + double branch_length = maxPlanningDistance*0.5; + + p2.pos.y = p1.pos.y + branch_length*0.4*sin(p1.pos.a); + p2.pos.x = p1.pos.x + branch_length*0.4*cos(p1.pos.a); + + vector l_branch; + vector r_branch; + + PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_RIGHT_DIR,r_branch); + PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_LEFT_DIR, l_branch); + + PlanningHelpers::FixPathDensity(l_branch, pathDensity); + PlanningHelpers::SmoothPath(l_branch,0.4,0.3,0.1); + PlanningHelpers::CalcAngleAndCost(l_branch); + + PlanningHelpers::FixPathDensity(r_branch, pathDensity); + PlanningHelpers::SmoothPath(r_branch,0.4,0.3,0.1); + PlanningHelpers::CalcAngleAndCost(r_branch); + + paths.push_back(l_branch); + paths.push_back(r_branch); + } + + DeleteWaypoints(all_cell_to_delete); + + return paths.size(); } double PlannerH::PredictPlanUsingDP(const WayPoint& startPose, WayPoint* closestWP, const double& maxPlanningDistance, std::vector >& paths, const bool& bFindBranches) { - if(!closestWP || !closestWP->pLane) - { - cout < Null Lane !!" << endl; - return 0; - } - - vector > tempCurrentForwardPathss; - vector all_cell_to_delete; - vector globalPath; - - vector pLaneCells; - int nPaths = PlanningHelpers::PredictiveDP(closestWP, maxPlanningDistance, all_cell_to_delete, pLaneCells); - - if(nPaths==0) - { - cout < Null Tree Head." << endl; - return 0; - } - - double totalPlanDistance = 0; - for(unsigned int i = 0; i< pLaneCells.size(); i++) - { - std::vector path; - PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWP, globalPath, path, tempCurrentForwardPathss); - if(path.size()>0) - { - totalPlanDistance+= path.at(path.size()-1).cost; - path.insert(path.begin(), startPose); - //path.at(0).pos.a = path.at(1).pos.a;; - } - - - PlanningHelpers::FixPathDensity(path, 0.5); - PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1); - paths.push_back(path); - - if(bFindBranches) - { - int max_branch_index = path.size() > 5 ? 5 : path.size(); - vector l_branch; - vector r_branch; - l_branch.insert(l_branch.begin(), path.begin(), path.begin()+5); - r_branch.insert(r_branch.begin(), path.begin(), path.begin()+5); - - PlanningHelpers::CreateManualBranch(r_branch, 0, FORWARD_RIGHT_DIR); - PlanningHelpers::CreateManualBranch(l_branch, 0, FORWARD_LEFT_DIR); - - paths.push_back(l_branch); - paths.push_back(r_branch); - } - } - - DeleteWaypoints(all_cell_to_delete); - - return totalPlanDistance; + if(!closestWP || !closestWP->pLane) + { + cout < Null Lane !!" << endl; + return 0; + } + + vector > tempCurrentForwardPathss; + vector all_cell_to_delete; + vector globalPath; + + vector pLaneCells; + int nPaths = PlanningHelpers::PredictiveDP(closestWP, maxPlanningDistance, all_cell_to_delete, pLaneCells); + + if(nPaths==0) + { + cout < Null Tree Head." << endl; + return 0; + } + + double totalPlanDistance = 0; + for(unsigned int i = 0; i< pLaneCells.size(); i++) + { + std::vector path; + PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWP, globalPath, path, tempCurrentForwardPathss); + if(path.size()>0) + { + totalPlanDistance+= path.at(path.size()-1).cost; + path.insert(path.begin(), startPose); + //path.at(0).pos.a = path.at(1).pos.a;; + } + + + PlanningHelpers::FixPathDensity(path, 0.5); + PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1); + paths.push_back(path); + + if(bFindBranches) + { + int max_branch_index = path.size() > 5 ? 5 : path.size(); + vector l_branch; + vector r_branch; + l_branch.insert(l_branch.begin(), path.begin(), path.begin()+5); + r_branch.insert(r_branch.begin(), path.begin(), path.begin()+5); + + PlanningHelpers::CreateManualBranch(r_branch, 0, FORWARD_RIGHT_DIR); + PlanningHelpers::CreateManualBranch(l_branch, 0, FORWARD_LEFT_DIR); + + paths.push_back(l_branch); + paths.push_back(r_branch); + } + } + + DeleteWaypoints(all_cell_to_delete); + + return totalPlanDistance; } void PlannerH::DeleteWaypoints(vector& wps) { - for(unsigned int i=0; i >& trajectories, const WayPoint& p,const double& searchDistance, RelativeInfo& info) { - if(trajectories.size() == 0) return false; - - vector infos; - for(unsigned int i=0; i < trajectories.size(); i++) - { - RelativeInfo info_item; - GetRelativeInfo(trajectories.at(i), p, info_item); - double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(info_item.perp_point.pos.a, p.pos.a)*RAD2DEG; - if(angle_diff < 75) - { - info_item.iGlobalPath = i; - infos.push_back(info_item); - } - } - - if(infos.size() == 0) - return false; - else if(infos.size() == 1) - { - info = infos.at(0); - return true; - } - - double minCost = DBL_MAX; - int min_index = 0; - - for(unsigned int i=0 ; i< infos.size(); i++) - { - if(searchDistance > 0) - { - double laneChangeCost = trajectories.at(infos.at(i).iGlobalPath).at(infos.at(i).iFront).laneChangeCost; - if(fabs(infos.at(i).perp_distance) < searchDistance && laneChangeCost < minCost) - { - min_index = i; - minCost = laneChangeCost; - } - } - else - { - if(fabs(infos.at(i).perp_distance) < minCost) - { - min_index = i; - minCost = infos.at(i).perp_distance; - } - } - } - - info = infos.at(min_index); - - return true; + if(trajectories.size() == 0) return false; + + vector infos; + for(unsigned int i=0; i < trajectories.size(); i++) + { + RelativeInfo info_item; + GetRelativeInfo(trajectories.at(i), p, info_item); + double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(info_item.perp_point.pos.a, p.pos.a)*RAD2DEG; + if(angle_diff < 75) + { + info_item.iGlobalPath = i; + infos.push_back(info_item); + } + } + + if(infos.size() == 0) + return false; + else if(infos.size() == 1) + { + info = infos.at(0); + return true; + } + + double minCost = DBL_MAX; + int min_index = 0; + + for(unsigned int i=0 ; i< infos.size(); i++) + { + if(searchDistance > 0) + { + double laneChangeCost = trajectories.at(infos.at(i).iGlobalPath).at(infos.at(i).iFront).laneChangeCost; + if(fabs(infos.at(i).perp_distance) < searchDistance && laneChangeCost < minCost) + { + min_index = i; + minCost = laneChangeCost; + } + } + else + { + if(fabs(infos.at(i).perp_distance) < minCost) + { + min_index = i; + minCost = infos.at(i).perp_distance; + } + } + } + + info = infos.at(min_index); + + return true; } bool PlanningHelpers::GetRelativeInfo(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex ) { - if(trajectory.size() < 2) return false; - - WayPoint p0, p1; - if(trajectory.size()==2) - { - p0 = trajectory.at(0); - p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, - (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, - (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); - info.iFront = 1; - info.iBack = 0; - } - else - { - info.iFront = GetClosestNextPointIndexFast(trajectory, p, prevIndex); -// WayPoint p2 = p; -// int old_index = GetClosestNextPointIndex(trajectory, p2, prevIndex); -// if(old_index != info.iFront) -// cout << " Alert Alert !!!! fast: " << info.iFront << ", slow: " << old_index << endl; - - if(info.iFront > 0) - info.iBack = info.iFront -1; - else - info.iBack = 0; - - if(info.iFront == 0) - { - p0 = trajectory.at(info.iFront); - p1 = trajectory.at(info.iFront+1); - } - else if(info.iFront > 0 && info.iFront < trajectory.size()-1) - { - p0 = trajectory.at(info.iFront-1); - p1 = trajectory.at(info.iFront); - } - else - { - p0 = trajectory.at(info.iFront-1); - p1 = WayPoint((p0.pos.x+trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); - } - } - - WayPoint prevWP = p0; - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-p.pos.x, -p.pos.y); - Mat3 invRotationMat(p1.pos.a); - Mat3 invTranslationMat(p.pos.x, p.pos.y); - - p0.pos = translationMat*p0.pos; - p0.pos = rotationMat*p0.pos; - - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; - - double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); - info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 - - if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; - - info.to_front_distance = fabs(p1.pos.x); // distance on the x axes - - - info.perp_point = p1; - info.perp_point.pos.x = 0; // on the same y axis of the car - info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the trajectory - - info.perp_point.pos = invRotationMat * info.perp_point.pos; - info.perp_point.pos = invTranslationMat * info.perp_point.pos; - - info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); - - info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; - - return true; + if(trajectory.size() < 2) return false; + + WayPoint p0, p1; + if(trajectory.size()==2) + { + p0 = trajectory.at(0); + p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, + (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, + (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); + info.iFront = 1; + info.iBack = 0; + } + else + { + info.iFront = GetClosestNextPointIndexFast(trajectory, p, prevIndex); +// WayPoint p2 = p; +// int old_index = GetClosestNextPointIndex(trajectory, p2, prevIndex); +// if(old_index != info.iFront) +// cout << " Alert Alert !!!! fast: " << info.iFront << ", slow: " << old_index << endl; + + if(info.iFront > 0) + info.iBack = info.iFront -1; + else + info.iBack = 0; + + if(info.iFront == 0) + { + p0 = trajectory.at(info.iFront); + p1 = trajectory.at(info.iFront+1); + } + else if(info.iFront > 0 && info.iFront < trajectory.size()-1) + { + p0 = trajectory.at(info.iFront-1); + p1 = trajectory.at(info.iFront); + } + else + { + p0 = trajectory.at(info.iFront-1); + p1 = WayPoint((p0.pos.x+trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); + } + } + + WayPoint prevWP = p0; + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-p.pos.x, -p.pos.y); + Mat3 invRotationMat(p1.pos.a); + Mat3 invTranslationMat(p.pos.x, p.pos.y); + + p0.pos = translationMat*p0.pos; + p0.pos = rotationMat*p0.pos; + + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; + + double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); + info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 + + if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; + + info.to_front_distance = fabs(p1.pos.x); // distance on the x axes + + + info.perp_point = p1; + info.perp_point.pos.x = 0; // on the same y axis of the car + info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the trajectory + + info.perp_point.pos = invRotationMat * info.perp_point.pos; + info.perp_point.pos = invTranslationMat * info.perp_point.pos; + + info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); + + info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; + + return true; } bool PlanningHelpers::GetRelativeInfoLimited(const std::vector& trajectory, const WayPoint& p, RelativeInfo& info, const int& prevIndex ) { - if(trajectory.size() < 2) return false; - - WayPoint p0, p1; - - if(trajectory.size()==2) - { - vector _trajectory; - p0 = trajectory.at(0); - p1 = p0; - p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, - (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, - (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); - _trajectory.push_back(p0); - _trajectory.push_back(p1); - _trajectory.push_back(trajectory.at(1)); - - info.iFront = GetClosestNextPointIndexFast(_trajectory, p, prevIndex); - if(info.iFront > 0) - info.iBack = info.iFront -1; - else - info.iBack = 0; - - if(info.iFront == 0) - { - p0 = _trajectory.at(info.iFront); - p1 = _trajectory.at(info.iFront+1); - } - else if(info.iFront > 0 && info.iFront < _trajectory.size()-1) - { - p0 = _trajectory.at(info.iFront-1); - p1 = _trajectory.at(info.iFront); - } - else - { - p0 = _trajectory.at(info.iFront-1); - p1 = WayPoint((p0.pos.x+_trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+_trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+_trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); - } - - WayPoint prevWP = p0; - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-p.pos.x, -p.pos.y); - Mat3 invRotationMat(p1.pos.a); - Mat3 invTranslationMat(p.pos.x, p.pos.y); - - p0.pos = translationMat*p0.pos; - p0.pos = rotationMat*p0.pos; - - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; - - double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); - info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 - - if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; - - info.to_front_distance = fabs(p1.pos.x); // distance on the x axes - - info.perp_point = p1; - info.perp_point.pos.x = 0; // on the same y axis of the car - info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the _trajectory - - info.perp_point.pos = invRotationMat * info.perp_point.pos; - info.perp_point.pos = invTranslationMat * info.perp_point.pos; - - info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); - - info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; - - info.bAfter = false; - info.bBefore = false; - - if(info.iFront == 0) - { - info.bBefore = true; - } - else if(info.iFront == _trajectory.size()-1) - { - int s = _trajectory.size(); - double angle_befor_last = UtilityH::FixNegativeAngle(atan2(_trajectory.at(s-2).pos.y - _trajectory.at(s-1).pos.y, _trajectory.at(s-2).pos.x - _trajectory.at(s-1).pos.x)); - double angle_from_perp = UtilityH::FixNegativeAngle(atan2(info.perp_point.pos.y - _trajectory.at(s-1).pos.y, info.perp_point.pos.x - _trajectory.at(s-1).pos.x)); - double diff_last_perp = UtilityH::AngleBetweenTwoAnglesPositive(angle_befor_last, angle_from_perp); - info.after_angle = diff_last_perp; - if(diff_last_perp > M_PI_2) - { - info.bAfter = true; - } - - } - } - else - { - info.iFront = GetClosestNextPointIndexFast(trajectory, p, prevIndex); - if(info.iFront > 0) - info.iBack = info.iFront -1; - else - info.iBack = 0; - - if(info.iFront == 0) - { - p0 = trajectory.at(info.iFront); - p1 = trajectory.at(info.iFront+1); - } - else if(info.iFront > 0 && info.iFront < trajectory.size()-1) - { - p0 = trajectory.at(info.iFront-1); - p1 = trajectory.at(info.iFront); - } - else - { - p0 = trajectory.at(info.iFront-1); - p1 = WayPoint((p0.pos.x+trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); - } - - WayPoint prevWP = p0; - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-p.pos.x, -p.pos.y); - Mat3 invRotationMat(p1.pos.a); - Mat3 invTranslationMat(p.pos.x, p.pos.y); - - p0.pos = translationMat*p0.pos; - p0.pos = rotationMat*p0.pos; - - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; - - double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); - info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 - - if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; - - info.to_front_distance = fabs(p1.pos.x); // distance on the x axes - - info.perp_point = p1; - info.perp_point.pos.x = 0; // on the same y axis of the car - info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the trajectory - - info.perp_point.pos = invRotationMat * info.perp_point.pos; - info.perp_point.pos = invTranslationMat * info.perp_point.pos; - - info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); - - info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; - - info.bAfter = false; - info.bBefore = false; - - if(info.iFront == 0) - { - info.bBefore = true; - } - else if(info.iFront == trajectory.size()-1) - { - int s = trajectory.size(); - double angle_befor_last = UtilityH::FixNegativeAngle(atan2(trajectory.at(s-2).pos.y - trajectory.at(s-1).pos.y, trajectory.at(s-2).pos.x - trajectory.at(s-1).pos.x)); - double angle_from_perp = UtilityH::FixNegativeAngle(atan2(info.perp_point.pos.y - trajectory.at(s-1).pos.y, info.perp_point.pos.x - trajectory.at(s-1).pos.x)); - double diff_last_perp = UtilityH::AngleBetweenTwoAnglesPositive(angle_befor_last, angle_from_perp); - info.after_angle = diff_last_perp; - if(diff_last_perp > M_PI_2) - { - info.bAfter = true; - } - - } - } - - return true; + if(trajectory.size() < 2) return false; + + WayPoint p0, p1; + + if(trajectory.size()==2) + { + vector _trajectory; + p0 = trajectory.at(0); + p1 = p0; + p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, + (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, + (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); + _trajectory.push_back(p0); + _trajectory.push_back(p1); + _trajectory.push_back(trajectory.at(1)); + + info.iFront = GetClosestNextPointIndexFast(_trajectory, p, prevIndex); + if(info.iFront > 0) + info.iBack = info.iFront -1; + else + info.iBack = 0; + + if(info.iFront == 0) + { + p0 = _trajectory.at(info.iFront); + p1 = _trajectory.at(info.iFront+1); + } + else if(info.iFront > 0 && info.iFront < _trajectory.size()-1) + { + p0 = _trajectory.at(info.iFront-1); + p1 = _trajectory.at(info.iFront); + } + else + { + p0 = _trajectory.at(info.iFront-1); + p1 = WayPoint((p0.pos.x+_trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+_trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+_trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); + } + + WayPoint prevWP = p0; + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-p.pos.x, -p.pos.y); + Mat3 invRotationMat(p1.pos.a); + Mat3 invTranslationMat(p.pos.x, p.pos.y); + + p0.pos = translationMat*p0.pos; + p0.pos = rotationMat*p0.pos; + + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; + + double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); + info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 + + if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; + + info.to_front_distance = fabs(p1.pos.x); // distance on the x axes + + info.perp_point = p1; + info.perp_point.pos.x = 0; // on the same y axis of the car + info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the _trajectory + + info.perp_point.pos = invRotationMat * info.perp_point.pos; + info.perp_point.pos = invTranslationMat * info.perp_point.pos; + + info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); + + info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; + + info.bAfter = false; + info.bBefore = false; + + if(info.iFront == 0) + { + info.bBefore = true; + } + else if(info.iFront == _trajectory.size()-1) + { + int s = _trajectory.size(); + double angle_befor_last = UtilityH::FixNegativeAngle(atan2(_trajectory.at(s-2).pos.y - _trajectory.at(s-1).pos.y, _trajectory.at(s-2).pos.x - _trajectory.at(s-1).pos.x)); + double angle_from_perp = UtilityH::FixNegativeAngle(atan2(info.perp_point.pos.y - _trajectory.at(s-1).pos.y, info.perp_point.pos.x - _trajectory.at(s-1).pos.x)); + double diff_last_perp = UtilityH::AngleBetweenTwoAnglesPositive(angle_befor_last, angle_from_perp); + info.after_angle = diff_last_perp; + if(diff_last_perp > M_PI_2) + { + info.bAfter = true; + } + + } + } + else + { + info.iFront = GetClosestNextPointIndexFast(trajectory, p, prevIndex); + if(info.iFront > 0) + info.iBack = info.iFront -1; + else + info.iBack = 0; + + if(info.iFront == 0) + { + p0 = trajectory.at(info.iFront); + p1 = trajectory.at(info.iFront+1); + } + else if(info.iFront > 0 && info.iFront < trajectory.size()-1) + { + p0 = trajectory.at(info.iFront-1); + p1 = trajectory.at(info.iFront); + } + else + { + p0 = trajectory.at(info.iFront-1); + p1 = WayPoint((p0.pos.x+trajectory.at(info.iFront).pos.x)/2.0, (p0.pos.y+trajectory.at(info.iFront).pos.y)/2.0, (p0.pos.z+trajectory.at(info.iFront).pos.z)/2.0, p0.pos.a); + } + + WayPoint prevWP = p0; + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-p.pos.x, -p.pos.y); + Mat3 invRotationMat(p1.pos.a); + Mat3 invTranslationMat(p.pos.x, p.pos.y); + + p0.pos = translationMat*p0.pos; + p0.pos = rotationMat*p0.pos; + + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; + + double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); + info.perp_distance = p1.pos.y - m*p1.pos.x; // solve for x = 0 + + if(std::isnan(info.perp_distance) || std::isinf(info.perp_distance)) info.perp_distance = 0; + + info.to_front_distance = fabs(p1.pos.x); // distance on the x axes + + info.perp_point = p1; + info.perp_point.pos.x = 0; // on the same y axis of the car + info.perp_point.pos.y = info.perp_distance; //perp distance between the car and the trajectory + + info.perp_point.pos = invRotationMat * info.perp_point.pos; + info.perp_point.pos = invTranslationMat * info.perp_point.pos; + + info.from_back_distance = hypot(info.perp_point.pos.y - prevWP.pos.y, info.perp_point.pos.x - prevWP.pos.x); + + info.angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(p1.pos.a, p.pos.a)*RAD2DEG; + + info.bAfter = false; + info.bBefore = false; + + if(info.iFront == 0) + { + info.bBefore = true; + } + else if(info.iFront == trajectory.size()-1) + { + int s = trajectory.size(); + double angle_befor_last = UtilityH::FixNegativeAngle(atan2(trajectory.at(s-2).pos.y - trajectory.at(s-1).pos.y, trajectory.at(s-2).pos.x - trajectory.at(s-1).pos.x)); + double angle_from_perp = UtilityH::FixNegativeAngle(atan2(info.perp_point.pos.y - trajectory.at(s-1).pos.y, info.perp_point.pos.x - trajectory.at(s-1).pos.x)); + double diff_last_perp = UtilityH::AngleBetweenTwoAnglesPositive(angle_befor_last, angle_from_perp); + info.after_angle = diff_last_perp; + if(diff_last_perp > M_PI_2) + { + info.bAfter = true; + } + + } + } + + return true; } bool PlanningHelpers::GetThreePointsInfo(const WayPoint& p0, const WayPoint& p1, const WayPoint& p2, WayPoint& perp_p, double& long_d, double lat_d) { - if(p0.pos.x == p1.pos.x && p0.pos.y == p1.pos.y) return false; - if(p0.pos.x == p2.pos.x && p0.pos.y == p2.pos.y) return false; - if(p1.pos.x == p2.pos.x && p1.pos.y == p2.pos.y) return false; + if(p0.pos.x == p1.pos.x && p0.pos.y == p1.pos.y) return false; + if(p0.pos.x == p2.pos.x && p0.pos.y == p2.pos.y) return false; + if(p1.pos.x == p2.pos.x && p1.pos.y == p2.pos.y) return false; - perp_p = p1; - WayPoint first_p = p0; - double angle_x = atan2(p1.pos.y-p0.pos.y, p1.pos.x-p0.pos.x); + perp_p = p1; + WayPoint first_p = p0; + double angle_x = atan2(p1.pos.y-p0.pos.y, p1.pos.x-p0.pos.x); - Mat3 rotationMat(-angle_x); - Mat3 translationMat(-p2.pos.x, -p2.pos.y); - Mat3 invRotationMat(angle_x); - Mat3 invTranslationMat(p2.pos.x, p2.pos.y); + Mat3 rotationMat(-angle_x); + Mat3 translationMat(-p2.pos.x, -p2.pos.y); + Mat3 invRotationMat(angle_x); + Mat3 invTranslationMat(p2.pos.x, p2.pos.y); - first_p.pos = translationMat*first_p.pos; - first_p.pos = rotationMat*first_p.pos; + first_p.pos = translationMat*first_p.pos; + first_p.pos = rotationMat*first_p.pos; - perp_p.pos = translationMat*perp_p.pos; - perp_p.pos = rotationMat*perp_p.pos; + perp_p.pos = translationMat*perp_p.pos; + perp_p.pos = rotationMat*perp_p.pos; - if(perp_p.pos.x-first_p.pos.x == 0) return false; + if(perp_p.pos.x-first_p.pos.x == 0) return false; - double m = (perp_p.pos.y-first_p.pos.y)/(perp_p.pos.x-first_p.pos.x); - lat_d = perp_p.pos.y - m*perp_p.pos.x; // solve for x = 0 + double m = (perp_p.pos.y-first_p.pos.y)/(perp_p.pos.x-first_p.pos.x); + lat_d = perp_p.pos.y - m*perp_p.pos.x; // solve for x = 0 - if(std::isnan(lat_d) || std::isinf(lat_d)) return false; + if(std::isnan(lat_d) || std::isinf(lat_d)) return false; - if(perp_p.pos.x < 0) - return false; + if(perp_p.pos.x < 0) + return false; - perp_p.pos.x = 0; // on the same y axis of the car - perp_p.pos.y = lat_d; //perp distance between the car and the trajectory + perp_p.pos.x = 0; // on the same y axis of the car + perp_p.pos.y = lat_d; //perp distance between the car and the trajectory - perp_p.pos = invRotationMat * perp_p.pos; - perp_p.pos = invTranslationMat * perp_p.pos; + perp_p.pos = invRotationMat * perp_p.pos; + perp_p.pos = invTranslationMat * perp_p.pos; - long_d = hypot(perp_p.pos.y - first_p.pos.y, perp_p.pos.x - first_p.pos.x); + long_d = hypot(perp_p.pos.y - first_p.pos.y, perp_p.pos.x - first_p.pos.x); - return true; + return true; } WayPoint PlanningHelpers::GetFollowPointOnTrajectory(const std::vector& trajectory, const RelativeInfo& init_p, const double& distance, unsigned int& point_index) { - WayPoint follow_point; - - if(trajectory.size()==0) return follow_point; - - //condition 1, if far behind the first point on the trajectory - int local_i = init_p.iFront; - - if(init_p.iBack == 0 && init_p.iBack == init_p.iFront && init_p.from_back_distance > distance) - { - follow_point = trajectory.at(init_p.iFront); - follow_point.pos.x = init_p.perp_point.pos.x + distance * cos(follow_point.pos.a); - follow_point.pos.y = init_p.perp_point.pos.y + distance * sin(follow_point.pos.a); - } - //condition 2, if far after the last point on the trajectory - else if(init_p.iFront == (int)trajectory.size() - 1) - { - follow_point = trajectory.at(init_p.iFront); - follow_point.pos.x = init_p.perp_point.pos.x + distance * cos(follow_point.pos.a); - follow_point.pos.y = init_p.perp_point.pos.y + distance * sin(follow_point.pos.a); - } - else - { - double d = init_p.to_front_distance; - while(local_i < (int)trajectory.size()-1 && d < distance) - { - local_i++; - d += hypot(trajectory.at(local_i).pos.y - trajectory.at(local_i-1).pos.y, trajectory.at(local_i).pos.x - trajectory.at(local_i-1).pos.x); - } - - double d_part = distance - d; - - follow_point = trajectory.at(local_i); - follow_point.pos.x = follow_point.pos.x + d_part * cos(follow_point.pos.a); - follow_point.pos.y = follow_point.pos.y + d_part * sin(follow_point.pos.a); - } - - point_index = local_i; - - return follow_point; + WayPoint follow_point; + + if(trajectory.size()==0) return follow_point; + + //condition 1, if far behind the first point on the trajectory + int local_i = init_p.iFront; + + if(init_p.iBack == 0 && init_p.iBack == init_p.iFront && init_p.from_back_distance > distance) + { + follow_point = trajectory.at(init_p.iFront); + follow_point.pos.x = init_p.perp_point.pos.x + distance * cos(follow_point.pos.a); + follow_point.pos.y = init_p.perp_point.pos.y + distance * sin(follow_point.pos.a); + } + //condition 2, if far after the last point on the trajectory + else if(init_p.iFront == (int)trajectory.size() - 1) + { + follow_point = trajectory.at(init_p.iFront); + follow_point.pos.x = init_p.perp_point.pos.x + distance * cos(follow_point.pos.a); + follow_point.pos.y = init_p.perp_point.pos.y + distance * sin(follow_point.pos.a); + } + else + { + double d = init_p.to_front_distance; + while(local_i < (int)trajectory.size()-1 && d < distance) + { + local_i++; + d += hypot(trajectory.at(local_i).pos.y - trajectory.at(local_i-1).pos.y, trajectory.at(local_i).pos.x - trajectory.at(local_i-1).pos.x); + } + + double d_part = distance - d; + + follow_point = trajectory.at(local_i); + follow_point.pos.x = follow_point.pos.x + d_part * cos(follow_point.pos.a); + follow_point.pos.y = follow_point.pos.y + d_part * sin(follow_point.pos.a); + } + + point_index = local_i; + + return follow_point; } double PlanningHelpers::GetExactDistanceOnTrajectory(const std::vector& trajectory, const RelativeInfo& p1,const RelativeInfo& p2) { - if(trajectory.size() == 0) return 0; - - if(p2.iFront == p1.iFront && p2.iBack == p1.iBack) - { - return p2.to_front_distance - p1.to_front_distance; - } - else if(p2.iBack >= p1.iFront) - { - double d_on_path = p1.to_front_distance + p2.from_back_distance; - for(int i = p1.iFront; i < p2.iBack; i++) - d_on_path += hypot(trajectory.at(i+1).pos.y - trajectory.at(i).pos.y, trajectory.at(i+1).pos.x - trajectory.at(i).pos.x); - - return d_on_path; - } - else if(p2.iFront <= p1.iBack) - { - double d_on_path = p1.from_back_distance + p2.to_front_distance; - for(int i = p2.iFront; i < p1.iBack; i++) - d_on_path += hypot(trajectory.at(i+1).pos.y - trajectory.at(i).pos.y, trajectory.at(i+1).pos.x - trajectory.at(i).pos.x); - - return -d_on_path; - } - else - { - return 0; - } + if(trajectory.size() == 0) return 0; + + if(p2.iFront == p1.iFront && p2.iBack == p1.iBack) + { + return p2.to_front_distance - p1.to_front_distance; + } + else if(p2.iBack >= p1.iFront) + { + double d_on_path = p1.to_front_distance + p2.from_back_distance; + for(int i = p1.iFront; i < p2.iBack; i++) + d_on_path += hypot(trajectory.at(i+1).pos.y - trajectory.at(i).pos.y, trajectory.at(i+1).pos.x - trajectory.at(i).pos.x); + + return d_on_path; + } + else if(p2.iFront <= p1.iBack) + { + double d_on_path = p1.from_back_distance + p2.to_front_distance; + for(int i = p2.iFront; i < p1.iBack; i++) + d_on_path += hypot(trajectory.at(i+1).pos.y - trajectory.at(i).pos.y, trajectory.at(i+1).pos.x - trajectory.at(i).pos.x); + + return -d_on_path; + } + else + { + return 0; + } } int PlanningHelpers::GetClosestNextPointIndex_obsolete(const vector& trajectory, const WayPoint& p,const int& prevIndex ) { - if(trajectory.size() == 0 || prevIndex < 0) return 0; - - double d = 0, minD = DBL_MAX; - int min_index = prevIndex; - - for(unsigned int i=prevIndex; i< trajectory.size(); i++) - { - d = distance2pointsSqr(trajectory.at(i).pos, p.pos); - if(d < minD) - { - min_index = i; - minD = d; - } - } - -// cout << "Slow=> Start: " << 0; -// cout << ", End: " << trajectory.size(); -// cout << ", Minimum Before: " << min_index; - - if(min_index < (int)trajectory.size()-2) - { - GPSPoint curr, next; - curr = trajectory.at(min_index).pos; - next = trajectory.at(min_index+1).pos; - GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); - double norm1 = pointNorm(v_1); - GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); - double norm2 = pointNorm(v_2); - double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; - double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); - if(a <= M_PI_2) - min_index = min_index+1; - } - -// cout << ", Minimum After: " << min_index << ", Big O: " << trajectory.size() << endl; - - return min_index; + if(trajectory.size() == 0 || prevIndex < 0) return 0; + + double d = 0, minD = DBL_MAX; + int min_index = prevIndex; + + for(unsigned int i=prevIndex; i< trajectory.size(); i++) + { + d = distance2pointsSqr(trajectory.at(i).pos, p.pos); + if(d < minD) + { + min_index = i; + minD = d; + } + } + +// cout << "Slow=> Start: " << 0; +// cout << ", End: " << trajectory.size(); +// cout << ", Minimum Before: " << min_index; + + if(min_index < (int)trajectory.size()-2) + { + GPSPoint curr, next; + curr = trajectory.at(min_index).pos; + next = trajectory.at(min_index+1).pos; + GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); + double norm1 = pointNorm(v_1); + GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); + double norm2 = pointNorm(v_2); + double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; + double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); + if(a <= M_PI_2) + min_index = min_index+1; + } + +// cout << ", Minimum After: " << min_index << ", Big O: " << trajectory.size() << endl; + + return min_index; } int PlanningHelpers::GetClosestNextPointIndexFastV2(const vector& trajectory, const WayPoint& p,const int& prevIndex) { - int size = (int)trajectory.size(); - - if(size < 2 || prevIndex < 0) return 0; - - double d = 0, minD = DBL_MAX; - - - double resolution = hypot(trajectory[1].pos.y -trajectory[0].pos.y , trajectory[1].pos.x -trajectory[0].pos.x); - double d_to_zero = hypot(p.pos.y -trajectory[0].pos.y , p.pos.x - trajectory[0].pos.x); - double d_to_size = hypot(trajectory[size-1].pos.y - p.pos.y , trajectory[size-1].pos.x - p.pos.x); - - int iStart = d_to_zero / resolution; - WayPoint perp_p; - double lat_d = 0; - double long_d = 0; - - if(iStart > 0 && iStart < size-1 && GetThreePointsInfo(trajectory.at(0), trajectory.at(iStart), p, perp_p, long_d, lat_d)) - { - // m_TestingClosestPoint.push_back(make_pair(trajectory.at(0).pos, p.pos)); - // m_TestingClosestPoint.push_back(make_pair(trajectory.at(iStart).pos, p.pos)); - iStart = long_d / resolution; - } - - if(iStart>0) - iStart--; - - int iEnd = size - (d_to_size / resolution); - - if(iEnd >= 0 && iEnd < size-2 && GetThreePointsInfo(trajectory.at(size-1), trajectory.at(iEnd), p, perp_p, long_d, lat_d)) - { - // m_TestingClosestPoint.push_back(make_pair(trajectory.at(size-1).pos, p.pos)); - // m_TestingClosestPoint.push_back(make_pair(trajectory.at(iEnd).pos, p.pos)); - iEnd = size - (long_d / resolution); - } - - if(iEnd < size-1) - iEnd++; - - // cout << "Fast=>"; - // cout << " Start: " << iStart; - // cout << ", End: " << iEnd; - - double d_from_start = d_to_zero; - if(iStart < size) - d_from_start = hypot(trajectory[iStart].pos.y - p.pos.y , trajectory[iStart].pos.x - p.pos.x); - - double d_from_end = d_to_size; - if(iEnd >= 0) - d_from_end = hypot(trajectory[iEnd].pos.y - p.pos.y , trajectory[iEnd].pos.x - p.pos.x); - - if(iStart >= size && iEnd < 0) - { - if(d_to_zero < d_to_size) - { - iStart = 0; - iEnd = size/2 -1; - } - else - { - iStart = size/2; - iEnd = size - 1; - } - } - else - { - if(iStart >=size || (d_from_start > d_to_zero)) - iStart = 0; - - if(iEnd < 0 || (d_from_end > d_to_size)) - iEnd = size-1; - } - - if(iStart > iEnd) - iEnd = size-1; - - int min_index = iStart; - - int ncout = 0; - for(int i=iStart; i<= iEnd; i++) - { - d = distance2pointsSqr(trajectory[i].pos, p.pos); - if(d < minD) - { - min_index = i; - minD = d; - } - ncout++; - } - - // cout << ", Minimum Before: " << min_index; - - if(min_index < size-2) - { - GPSPoint curr, next; - curr = trajectory[min_index].pos; - next = trajectory[min_index+1].pos; - GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); - double norm1 = pointNorm(v_1); - GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); - double norm2 = pointNorm(v_2); - double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; - double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); - if(a <= M_PI_2) - min_index = min_index+1; - } - - // m_TestingClosestPoint.push_back(make_pair(trajectory.at(min_index).pos, p.pos)); - - // cout << ", Minimum After: " << min_index << ", Big O: " << ncout << endl; - // cout << "d_zero: " << d_to_zero << ", d_start: " << d_from_start << endl; - // cout << "d_size: " << d_to_size << ", d_end: " << d_from_end << endl; - return min_index; + int size = (int)trajectory.size(); + + if(size < 2 || prevIndex < 0) return 0; + + double d = 0, minD = DBL_MAX; + + + double resolution = hypot(trajectory[1].pos.y -trajectory[0].pos.y , trajectory[1].pos.x -trajectory[0].pos.x); + double d_to_zero = hypot(p.pos.y -trajectory[0].pos.y , p.pos.x - trajectory[0].pos.x); + double d_to_size = hypot(trajectory[size-1].pos.y - p.pos.y , trajectory[size-1].pos.x - p.pos.x); + + int iStart = d_to_zero / resolution; + WayPoint perp_p; + double lat_d = 0; + double long_d = 0; + + if(iStart > 0 && iStart < size-1 && GetThreePointsInfo(trajectory.at(0), trajectory.at(iStart), p, perp_p, long_d, lat_d)) + { + // m_TestingClosestPoint.push_back(make_pair(trajectory.at(0).pos, p.pos)); + // m_TestingClosestPoint.push_back(make_pair(trajectory.at(iStart).pos, p.pos)); + iStart = long_d / resolution; + } + + if(iStart>0) + iStart--; + + int iEnd = size - (d_to_size / resolution); + + if(iEnd >= 0 && iEnd < size-2 && GetThreePointsInfo(trajectory.at(size-1), trajectory.at(iEnd), p, perp_p, long_d, lat_d)) + { + // m_TestingClosestPoint.push_back(make_pair(trajectory.at(size-1).pos, p.pos)); + // m_TestingClosestPoint.push_back(make_pair(trajectory.at(iEnd).pos, p.pos)); + iEnd = size - (long_d / resolution); + } + + if(iEnd < size-1) + iEnd++; + + // cout << "Fast=>"; + // cout << " Start: " << iStart; + // cout << ", End: " << iEnd; + + double d_from_start = d_to_zero; + if(iStart < size) + d_from_start = hypot(trajectory[iStart].pos.y - p.pos.y , trajectory[iStart].pos.x - p.pos.x); + + double d_from_end = d_to_size; + if(iEnd >= 0) + d_from_end = hypot(trajectory[iEnd].pos.y - p.pos.y , trajectory[iEnd].pos.x - p.pos.x); + + if(iStart >= size && iEnd < 0) + { + if(d_to_zero < d_to_size) + { + iStart = 0; + iEnd = size/2 -1; + } + else + { + iStart = size/2; + iEnd = size - 1; + } + } + else + { + if(iStart >=size || (d_from_start > d_to_zero)) + iStart = 0; + + if(iEnd < 0 || (d_from_end > d_to_size)) + iEnd = size-1; + } + + if(iStart > iEnd) + iEnd = size-1; + + int min_index = iStart; + + int ncout = 0; + for(int i=iStart; i<= iEnd; i++) + { + d = distance2pointsSqr(trajectory[i].pos, p.pos); + if(d < minD) + { + min_index = i; + minD = d; + } + ncout++; + } + + // cout << ", Minimum Before: " << min_index; + + if(min_index < size-2) + { + GPSPoint curr, next; + curr = trajectory[min_index].pos; + next = trajectory[min_index+1].pos; + GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); + double norm1 = pointNorm(v_1); + GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); + double norm2 = pointNorm(v_2); + double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; + double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); + if(a <= M_PI_2) + min_index = min_index+1; + } + + // m_TestingClosestPoint.push_back(make_pair(trajectory.at(min_index).pos, p.pos)); + + // cout << ", Minimum After: " << min_index << ", Big O: " << ncout << endl; + // cout << "d_zero: " << d_to_zero << ", d_start: " << d_from_start << endl; + // cout << "d_size: " << d_to_size << ", d_end: " << d_from_end << endl; + return min_index; } int PlanningHelpers::GetClosestNextPointIndexFast(const vector& trajectory, const WayPoint& p,const int& prevIndex ) { - int size = (int)trajectory.size(); - - if(size < 2 || prevIndex < 0) return 0; - - double d = 0, minD = DBL_MAX; - int min_index = prevIndex; - int iStart = prevIndex; - int iEnd = size; - double resolution = hypot(trajectory[1].pos.y -trajectory[0].pos.y , trajectory[1].pos.x -trajectory[0].pos.x); - - //divide every 5 meters - int skip_factor = 5; - if(resolution > skip_factor) - resolution = skip_factor; - - - int skip = 1; - if(resolution > 0) - skip = skip_factor/resolution; - - for(int i=0; i< size; i+=skip) - { - if(i+skip/2 < size) - d = (distance2pointsSqr(trajectory[i].pos, p.pos) + distance2pointsSqr(trajectory[i+skip/2].pos, p.pos))/2.0; - else - d = distance2pointsSqr(trajectory[i].pos, p.pos); - if(d < minD) - { - iStart = i-skip; - iEnd = i+skip; - minD = d; - min_index = i; - } - } - - if((size - skip/2 - 1) > 0) - d = (distance2pointsSqr(trajectory[size-1].pos, p.pos) + distance2pointsSqr(trajectory[size - skip/2 -1 ].pos, p.pos))/2.0; - else - d = distance2pointsSqr(trajectory[size-1].pos, p.pos); - - if(d < minD) - { - iStart = size-skip; - iEnd = size+skip; - minD = d; - min_index = size-1; - } - - if(iStart < 0) iStart = 0; - if(iEnd >= size) iEnd = size -1; - - for(int i=iStart; i< iEnd; i++) - { - d = distance2pointsSqr(trajectory[i].pos, p.pos); - if(d < minD) - { - min_index = i; - minD = d; - } - } - - if(min_index < size-1) - { - GPSPoint curr, next; - curr = trajectory[min_index].pos; - next = trajectory[min_index+1].pos; - GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); - double norm1 = pointNorm(v_1); - GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); - double norm2 = pointNorm(v_2); - double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; - double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); - if(a <= M_PI_2) - min_index = min_index+1; - } - - //m_TestingClosestPoint.push_back(make_pair(trajectory.at(min_index).pos, p.pos)); - - return min_index; + int size = (int)trajectory.size(); + + if(size < 2 || prevIndex < 0) return 0; + + double d = 0, minD = DBL_MAX; + int min_index = prevIndex; + int iStart = prevIndex; + int iEnd = size; + double resolution = hypot(trajectory[1].pos.y -trajectory[0].pos.y , trajectory[1].pos.x -trajectory[0].pos.x); + + //divide every 5 meters + int skip_factor = 5; + if(resolution > skip_factor) + resolution = skip_factor; + + + int skip = 1; + if(resolution > 0) + skip = skip_factor/resolution; + + for(int i=0; i< size; i+=skip) + { + if(i+skip/2 < size) + d = (distance2pointsSqr(trajectory[i].pos, p.pos) + distance2pointsSqr(trajectory[i+skip/2].pos, p.pos))/2.0; + else + d = distance2pointsSqr(trajectory[i].pos, p.pos); + if(d < minD) + { + iStart = i-skip; + iEnd = i+skip; + minD = d; + min_index = i; + } + } + + if((size - skip/2 - 1) > 0) + d = (distance2pointsSqr(trajectory[size-1].pos, p.pos) + distance2pointsSqr(trajectory[size - skip/2 -1 ].pos, p.pos))/2.0; + else + d = distance2pointsSqr(trajectory[size-1].pos, p.pos); + + if(d < minD) + { + iStart = size-skip; + iEnd = size+skip; + minD = d; + min_index = size-1; + } + + if(iStart < 0) iStart = 0; + if(iEnd >= size) iEnd = size -1; + + for(int i=iStart; i< iEnd; i++) + { + d = distance2pointsSqr(trajectory[i].pos, p.pos); + if(d < minD) + { + min_index = i; + minD = d; + } + } + + if(min_index < size-1) + { + GPSPoint curr, next; + curr = trajectory[min_index].pos; + next = trajectory[min_index+1].pos; + GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); + double norm1 = pointNorm(v_1); + GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); + double norm2 = pointNorm(v_2); + double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; + double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); + if(a <= M_PI_2) + min_index = min_index+1; + } + + //m_TestingClosestPoint.push_back(make_pair(trajectory.at(min_index).pos, p.pos)); + + return min_index; } int PlanningHelpers::GetClosestNextPointIndexDirectionFast(const vector& trajectory, const WayPoint& p,const int& prevIndex ) { - int size = (int)trajectory.size(); - - if(size < 2 || prevIndex < 0) return 0; - - double d = 0, minD = DBL_MAX; - int min_index = prevIndex; - - for(unsigned int i=prevIndex; i< size; i++) - { - d = distance2pointsSqr(trajectory[i].pos, p.pos); - double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(trajectory[i].pos.a, p.pos.a)*RAD2DEG; - - if(d < minD && angle_diff < 45) - { - min_index = i; - minD = d; - } - } - - if(min_index < (int)trajectory.size()-2) - { - GPSPoint curr, next; - curr = trajectory.at(min_index).pos; - next = trajectory.at(min_index+1).pos; - GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); - double norm1 = pointNorm(v_1); - GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); - double norm2 = pointNorm(v_2); - double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; - double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); - if(a <= M_PI_2) - min_index = min_index+1; - } - - return min_index; + int size = (int)trajectory.size(); + + if(size < 2 || prevIndex < 0) return 0; + + double d = 0, minD = DBL_MAX; + int min_index = prevIndex; + + for(unsigned int i=prevIndex; i< size; i++) + { + d = distance2pointsSqr(trajectory[i].pos, p.pos); + double angle_diff = UtilityH::AngleBetweenTwoAnglesPositive(trajectory[i].pos.a, p.pos.a)*RAD2DEG; + + if(d < minD && angle_diff < 45) + { + min_index = i; + minD = d; + } + } + + if(min_index < (int)trajectory.size()-2) + { + GPSPoint curr, next; + curr = trajectory.at(min_index).pos; + next = trajectory.at(min_index+1).pos; + GPSPoint v_1(p.pos.x - curr.x ,p.pos.y - curr.y,0,0); + double norm1 = pointNorm(v_1); + GPSPoint v_2(next.x - curr.x,next.y - curr.y,0,0); + double norm2 = pointNorm(v_2); + double dot_pro = v_1.x*v_2.x + v_1.y*v_2.y; + double a = UtilityH::FixNegativeAngle(acos(dot_pro/(norm1*norm2))); + if(a <= M_PI_2) + min_index = min_index+1; + } + + return min_index; } int PlanningHelpers::GetClosestPointIndex_obsolete(const vector& trajectory, const WayPoint& p,const int& prevIndex ) { - if(trajectory.size() == 0 || prevIndex < 0) return 0; - - double d = 0, minD = DBL_MAX; - int min_index = prevIndex; - - for(unsigned int i=prevIndex; i< trajectory.size(); i++) - { - d = distance2pointsSqr(trajectory.at(i).pos, p.pos); - if(d < minD) - { - min_index = i; - minD = d; - } - } - - return min_index; + if(trajectory.size() == 0 || prevIndex < 0) return 0; + + double d = 0, minD = DBL_MAX; + int min_index = prevIndex; + + for(unsigned int i=prevIndex; i< trajectory.size(); i++) + { + d = distance2pointsSqr(trajectory.at(i).pos, p.pos); + if(d < minD) + { + min_index = i; + minD = d; + } + } + + return min_index; } WayPoint PlanningHelpers::GetPerpendicularOnTrajectory_obsolete(const vector& trajectory, const WayPoint& p, double& distance, const int& prevIndex ) { - if(trajectory.size() < 2) return p; - - WayPoint p0, p1, p2, perp; - if(trajectory.size()==2) - { - p0 = trajectory.at(0); - p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, - (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, - (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); - p2 = trajectory.at(1); - } - else - { - int next_index = GetClosestNextPointIndex_obsolete(trajectory, p, prevIndex); - - if(next_index == 0) - { - p0 = trajectory[next_index]; - p1 = trajectory[next_index+1]; - p2 = trajectory[next_index+2]; - } - else if(next_index > 0 && next_index < trajectory.size()-1) - { - p0 = trajectory[next_index-1]; - p1 = trajectory[next_index]; - p2 = trajectory[next_index+1]; - } - else - { - p0 = trajectory[next_index-1]; - p2 = trajectory[next_index]; - - p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); - - } - } - - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-p.pos.x, -p.pos.y); - Mat3 invRotationMat(p1.pos.a); - Mat3 invTranslationMat(p.pos.x, p.pos.y); - - p0.pos = translationMat*p0.pos; - p0.pos = rotationMat*p0.pos; - - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; - - p2.pos = translationMat*p2.pos; - p2.pos= rotationMat*p2.pos; - - double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); - double d = p1.pos.y - m*p1.pos.x; // solve for x = 0 - distance = p1.pos.x; // distance on the x axes - - perp = p1; - perp.pos.x = 0; // on the same y axis of the car - perp.pos.y = d; //perp distance between the car and the trajectory - - perp.pos = invRotationMat * perp.pos; - perp.pos = invTranslationMat * perp.pos; - - return perp; + if(trajectory.size() < 2) return p; + + WayPoint p0, p1, p2, perp; + if(trajectory.size()==2) + { + p0 = trajectory.at(0); + p1 = WayPoint((trajectory.at(0).pos.x+trajectory.at(1).pos.x)/2.0, + (trajectory.at(0).pos.y+trajectory.at(1).pos.y)/2.0, + (trajectory.at(0).pos.z+trajectory.at(1).pos.z)/2.0, trajectory.at(0).pos.a); + p2 = trajectory.at(1); + } + else + { + int next_index = GetClosestNextPointIndex_obsolete(trajectory, p, prevIndex); + + if(next_index == 0) + { + p0 = trajectory[next_index]; + p1 = trajectory[next_index+1]; + p2 = trajectory[next_index+2]; + } + else if(next_index > 0 && next_index < trajectory.size()-1) + { + p0 = trajectory[next_index-1]; + p1 = trajectory[next_index]; + p2 = trajectory[next_index+1]; + } + else + { + p0 = trajectory[next_index-1]; + p2 = trajectory[next_index]; + + p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); + + } + } + + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-p.pos.x, -p.pos.y); + Mat3 invRotationMat(p1.pos.a); + Mat3 invTranslationMat(p.pos.x, p.pos.y); + + p0.pos = translationMat*p0.pos; + p0.pos = rotationMat*p0.pos; + + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; + + p2.pos = translationMat*p2.pos; + p2.pos= rotationMat*p2.pos; + + double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); + double d = p1.pos.y - m*p1.pos.x; // solve for x = 0 + distance = p1.pos.x; // distance on the x axes + + perp = p1; + perp.pos.x = 0; // on the same y axis of the car + perp.pos.y = d; //perp distance between the car and the trajectory + + perp.pos = invRotationMat * perp.pos; + perp.pos = invTranslationMat * perp.pos; + + return perp; } double PlanningHelpers::GetPerpDistanceToTrajectorySimple_obsolete(const vector& trajectory, const WayPoint& p,const int& prevIndex) { - if(trajectory.size() < 2) - return 0; - - WayPoint p0, p1, p2; - int next_index = 0; - if(trajectory.size()==2) - { - p0 = trajectory.at(0); - p2 = trajectory.at(1); - p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); - - } - else - { - next_index = GetClosestNextPointIndexFast(trajectory, p, prevIndex); - if(next_index == 0) - { - p0 = trajectory[next_index]; - p1 = trajectory[next_index+1]; - p2 = trajectory[next_index+2]; - } - else if(next_index > 0 && next_index < trajectory.size()-1) - { - p0 = trajectory[next_index-1]; - p1 = trajectory[next_index]; - p2 = trajectory[next_index+1]; - } - else - { - p0 = trajectory[next_index-1]; - p2 = trajectory[next_index]; - - p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); - - } - - } - - - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-p.pos.x, -p.pos.y); - - p0.pos = translationMat*p0.pos; - p0.pos = rotationMat*p0.pos; - - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; - - p2.pos = translationMat*p2.pos; - p2.pos = rotationMat*p2.pos; - - double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); - double d = p1.pos.y - m*p1.pos.x; - - if(std::isnan(d) || std::isinf(d)) - { - //assert(false); - d = 0; - } - - return d; + if(trajectory.size() < 2) + return 0; + + WayPoint p0, p1, p2; + int next_index = 0; + if(trajectory.size()==2) + { + p0 = trajectory.at(0); + p2 = trajectory.at(1); + p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); + + } + else + { + next_index = GetClosestNextPointIndexFast(trajectory, p, prevIndex); + if(next_index == 0) + { + p0 = trajectory[next_index]; + p1 = trajectory[next_index+1]; + p2 = trajectory[next_index+2]; + } + else if(next_index > 0 && next_index < trajectory.size()-1) + { + p0 = trajectory[next_index-1]; + p1 = trajectory[next_index]; + p2 = trajectory[next_index+1]; + } + else + { + p0 = trajectory[next_index-1]; + p2 = trajectory[next_index]; + + p1 = WayPoint((p0.pos.x+p2.pos.x)/2.0, (p0.pos.y+p2.pos.y)/2.0, (p0.pos.z+p2.pos.z)/2.0, p0.pos.a); + + } + + } + + + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-p.pos.x, -p.pos.y); + + p0.pos = translationMat*p0.pos; + p0.pos = rotationMat*p0.pos; + + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; + + p2.pos = translationMat*p2.pos; + p2.pos = rotationMat*p2.pos; + + double m = (p1.pos.y-p0.pos.y)/(p1.pos.x-p0.pos.x); + double d = p1.pos.y - m*p1.pos.x; + + if(std::isnan(d) || std::isinf(d)) + { + //assert(false); + d = 0; + } + + return d; } double PlanningHelpers::GetPerpDistanceToVectorSimple_obsolete(const WayPoint& point1, const WayPoint& point2, const WayPoint& pose) { - WayPoint p1 = point1, p2 = point2; - Mat3 rotationMat(-p1.pos.a); - Mat3 translationMat(-pose.pos.x, -pose.pos.y); + WayPoint p1 = point1, p2 = point2; + Mat3 rotationMat(-p1.pos.a); + Mat3 translationMat(-pose.pos.x, -pose.pos.y); - p1.pos = translationMat*p1.pos; - p1.pos = rotationMat*p1.pos; + p1.pos = translationMat*p1.pos; + p1.pos = rotationMat*p1.pos; - p2.pos = translationMat*p2.pos; - p2.pos = rotationMat*p2.pos; + p2.pos = translationMat*p2.pos; + p2.pos = rotationMat*p2.pos; - double m = (p2.pos.y-p1.pos.y)/(p2.pos.x-p1.pos.x); - double d = p2.pos.y - m*p2.pos.x; + double m = (p2.pos.y-p1.pos.y)/(p2.pos.x-p1.pos.x); + double d = p2.pos.y - m*p2.pos.x; - if(std::isnan(d) || std::isinf(d)) - { - //assert(false); - d = 0; - } + if(std::isnan(d) || std::isinf(d)) + { + //assert(false); + d = 0; + } - return d; + return d; } WayPoint PlanningHelpers::GetNextPointOnTrajectory_obsolete(const vector& trajectory, const double& distance, const int& currIndex) { - assert(trajectory.size()>0); + assert(trajectory.size()>0); - int local_currIndex = currIndex; + int local_currIndex = currIndex; - if(local_currIndex < 0 || local_currIndex >= trajectory.size()) - return trajectory.at(0); + if(local_currIndex < 0 || local_currIndex >= trajectory.size()) + return trajectory.at(0); - WayPoint p1 = trajectory.at(local_currIndex); - WayPoint p2; + WayPoint p1 = trajectory.at(local_currIndex); + WayPoint p2; - double d = 0; - while(local_currIndex < (trajectory.size()-1) && d < distance) - { - local_currIndex++; - p2 = p1; - p1 = trajectory.at(local_currIndex); - d += distance2points(p1.pos, p2.pos); - } + double d = 0; + while(local_currIndex < (trajectory.size()-1) && d < distance) + { + local_currIndex++; + p2 = p1; + p1 = trajectory.at(local_currIndex); + d += distance2points(p1.pos, p2.pos); + } - if(local_currIndex >= trajectory.size()-1) - return p1; + if(local_currIndex >= trajectory.size()-1) + return p1; - double distance_diff = distance - d; + double distance_diff = distance - d; - p2 = trajectory.at(local_currIndex); - p1 = trajectory.at(local_currIndex+1); + p2 = trajectory.at(local_currIndex); + p1 = trajectory.at(local_currIndex+1); - GPSPoint uv(p1.pos.x - p2.pos.x, p1.pos.y - p2.pos.y ,0,0); - double v_norm = pointNorm(uv); + GPSPoint uv(p1.pos.x - p2.pos.x, p1.pos.y - p2.pos.y ,0,0); + double v_norm = pointNorm(uv); - assert(v_norm != 0); + assert(v_norm != 0); - uv.x = (uv.x / v_norm) * distance_diff; - uv.y = (uv.y / v_norm) * distance_diff; + uv.x = (uv.x / v_norm) * distance_diff; + uv.y = (uv.y / v_norm) * distance_diff; - double ydiff = p1.pos.y-p2.pos.y; - double xdiff = p1.pos.x-p2.pos.x; - double a = atan2(ydiff,xdiff); + double ydiff = p1.pos.y-p2.pos.y; + double xdiff = p1.pos.x-p2.pos.x; + double a = atan2(ydiff,xdiff); - WayPoint abs_waypoint = p2; + WayPoint abs_waypoint = p2; - abs_waypoint.pos.x = p2.pos.x + uv.x; - abs_waypoint.pos.y = p2.pos.y + uv.y; - abs_waypoint.pos.a = a; + abs_waypoint.pos.x = p2.pos.x + uv.x; + abs_waypoint.pos.y = p2.pos.y + uv.y; + abs_waypoint.pos.a = a; - return abs_waypoint; + return abs_waypoint; } double PlanningHelpers::GetDistanceOnTrajectory_obsolete(const std::vector& path, const int& start_index, const WayPoint& p) { - int end_point_index = GetClosestPointIndex_obsolete(path, p); - if(end_point_index > 0) - end_point_index--; + int end_point_index = GetClosestPointIndex_obsolete(path, p); + if(end_point_index > 0) + end_point_index--; - double padding_distance = distance2points(path.at(end_point_index).pos, p.pos); + double padding_distance = distance2points(path.at(end_point_index).pos, p.pos); - double d_on_path = 0; - if(end_point_index >= start_index) - { - for(unsigned int i = start_index; i < end_point_index; i++) - d_on_path += distance2points(path.at(i).pos, path.at(i+1).pos); + double d_on_path = 0; + if(end_point_index >= start_index) + { + for(unsigned int i = start_index; i < end_point_index; i++) + d_on_path += distance2points(path.at(i).pos, path.at(i+1).pos); - d_on_path += padding_distance; - } - else - { - for(unsigned int i = start_index; i > end_point_index; i--) - d_on_path -= distance2points(path.at(i).pos, path.at(i-1).pos); - } + d_on_path += padding_distance; + } + else + { + for(unsigned int i = start_index; i > end_point_index; i--) + d_on_path -= distance2points(path.at(i).pos, path.at(i-1).pos); + } - return d_on_path; + return d_on_path; } bool PlanningHelpers::CompareTrajectories(const std::vector& path1, const std::vector& path2) { - if(path1.size() != path2.size()) - return false; + if(path1.size() != path2.size()) + return false; - for(unsigned int i=0; i< path1.size(); i++) - { - if(path1.at(i).v != path2.at(i).v || path1.at(i).pos.x != path2.at(i).pos.x || path1.at(i).pos.y != path2.at(i).pos.y || path1.at(i).pos.alt != path2.at(i).pos.alt || path1.at(i).pos.lon != path2.at(i).pos.lon) - return false; - } + for(unsigned int i=0; i< path1.size(); i++) + { + if(path1.at(i).v != path2.at(i).v || path1.at(i).pos.x != path2.at(i).pos.x || path1.at(i).pos.y != path2.at(i).pos.y || path1.at(i).pos.alt != path2.at(i).pos.alt || path1.at(i).pos.lon != path2.at(i).pos.lon) + return false; + } - return true; + return true; } double PlanningHelpers::GetDistanceToClosestStopLineAndCheck(const std::vector& path, const WayPoint& p, const double& giveUpDistance, int& stopLineID, int& stopSignID, int& trafficLightID, const int& prevIndex) { - trafficLightID = stopSignID = stopLineID = -1; - - RelativeInfo info; - GetRelativeInfo(path, p, info, prevIndex); - - for(unsigned int i=info.iBack; i 0 && path.at(i).pLane) - { - - for(unsigned int j = 0; j < path.at(i).pLane->stopLines.size(); j++) - { - - if(path.at(i).pLane->stopLines.at(j).id == path.at(i).stopLineID) - { - stopLineID = path.at(i).stopLineID; - - RelativeInfo stop_info; - WayPoint stopLineWP ; - stopLineWP.pos = path.at(i).pLane->stopLines.at(j).points.at(0); - GetRelativeInfo(path, stopLineWP, stop_info); - double localDistance = GetExactDistanceOnTrajectory(path, info, stop_info); - - if(localDistance > giveUpDistance) - { - stopSignID = path.at(i).pLane->stopLines.at(j).stopSignID; - trafficLightID = path.at(i).pLane->stopLines.at(j).trafficLightID; - return localDistance; - } - } - } - } - } - - return -1; + trafficLightID = stopSignID = stopLineID = -1; + + RelativeInfo info; + GetRelativeInfo(path, p, info, prevIndex); + + for(unsigned int i=info.iBack; i 0 && path.at(i).pLane) + { + + for(unsigned int j = 0; j < path.at(i).pLane->stopLines.size(); j++) + { + + if(path.at(i).pLane->stopLines.at(j).id == path.at(i).stopLineID) + { + stopLineID = path.at(i).stopLineID; + + RelativeInfo stop_info; + WayPoint stopLineWP ; + stopLineWP.pos = path.at(i).pLane->stopLines.at(j).points.at(0); + GetRelativeInfo(path, stopLineWP, stop_info); + double localDistance = GetExactDistanceOnTrajectory(path, info, stop_info); + + if(localDistance > giveUpDistance) + { + stopSignID = path.at(i).pLane->stopLines.at(j).stopSignID; + trafficLightID = path.at(i).pLane->stopLines.at(j).trafficLightID; + return localDistance; + } + } + } + } + } + + return -1; } void PlanningHelpers::CreateManualBranchFromTwoPoints(WayPoint& p1,WayPoint& p2 , const double& distance, const DIRECTION_TYPE& direction, std::vector& path) { - WayPoint endWP, midWP; - - double branch_angle = 0; - if(direction == FORWARD_RIGHT_DIR) - { - branch_angle = p1.pos.a-M_PI_2; - } - else if(direction == FORWARD_LEFT_DIR) - { - branch_angle = p1.pos.a+M_PI_2; - } - endWP.pos.y = p2.pos.y + distance*sin(branch_angle); - endWP.pos.x = p2.pos.x + distance*cos(branch_angle); - - midWP = p2; - midWP.pos.x = (p1.pos.x+p2.pos.x)/2.0; - midWP.pos.y = (p1.pos.y+p2.pos.y)/2.0; - endWP.bDir = midWP.bDir = direction; - - path.clear(); - path.push_back(p1); - path.push_back(p2); - path.push_back(endWP); - - //PlanningHelpers::SmoothPath(path, 0.4, 0.1); - PlanningHelpers::FixPathDensity(path, 1); - PlanningHelpers::SmoothPath(path, 0.4, 0.25); - PlanningHelpers::FixPathDensity(path, 0.5); - PlanningHelpers::SmoothPath(path, 0.25, 0.4); - - for(unsigned int i=0; i < path.size(); i++) - { - if(direction == FORWARD_LEFT_DIR) - { - path.at(i).state = INITIAL_STATE; - path.at(i).beh_state = BEH_BRANCH_LEFT_STATE; - path.at(i).laneId = -2; - } - if(direction == FORWARD_RIGHT_DIR) - { - path.at(i).state = INITIAL_STATE; - path.at(i).beh_state = BEH_BRANCH_RIGHT_STATE; - path.at(i).laneId = -3; - } - } + WayPoint endWP, midWP; + + double branch_angle = 0; + if(direction == FORWARD_RIGHT_DIR) + { + branch_angle = p1.pos.a-M_PI_2; + } + else if(direction == FORWARD_LEFT_DIR) + { + branch_angle = p1.pos.a+M_PI_2; + } + endWP.pos.y = p2.pos.y + distance*sin(branch_angle); + endWP.pos.x = p2.pos.x + distance*cos(branch_angle); + + midWP = p2; + midWP.pos.x = (p1.pos.x+p2.pos.x)/2.0; + midWP.pos.y = (p1.pos.y+p2.pos.y)/2.0; + endWP.bDir = midWP.bDir = direction; + + path.clear(); + path.push_back(p1); + path.push_back(p2); + path.push_back(endWP); + + //PlanningHelpers::SmoothPath(path, 0.4, 0.1); + PlanningHelpers::FixPathDensity(path, 1); + PlanningHelpers::SmoothPath(path, 0.4, 0.25); + PlanningHelpers::FixPathDensity(path, 0.5); + PlanningHelpers::SmoothPath(path, 0.25, 0.4); + + for(unsigned int i=0; i < path.size(); i++) + { + if(direction == FORWARD_LEFT_DIR) + { + path.at(i).state = INITIAL_STATE; + path.at(i).beh_state = BEH_BRANCH_LEFT_STATE; + path.at(i).laneId = -2; + } + if(direction == FORWARD_RIGHT_DIR) + { + path.at(i).state = INITIAL_STATE; + path.at(i).beh_state = BEH_BRANCH_RIGHT_STATE; + path.at(i).laneId = -3; + } + } } void PlanningHelpers::CreateManualBranch(std::vector& path, const int& degree, const DIRECTION_TYPE& direction) { - if(path.size() < 5) return; - - //start branch point - WayPoint branch_start = path.at(path.size()-5); - WayPoint last_wp = path.at(path.size()-1); - - - WayPoint endWP; - vector goal_path; - double branch_angle = 0; - if(direction == FORWARD_RIGHT_DIR) - { - branch_angle = last_wp.pos.a-M_PI_2; - } - else if(direction == FORWARD_LEFT_DIR) - { - branch_angle = last_wp.pos.a+M_PI_2; - } - endWP.pos.y = last_wp.pos.y + 10*sin(branch_angle); - endWP.pos.x = last_wp.pos.x + 10*cos(branch_angle); - - WayPoint wp = last_wp; - wp.pos.x = (last_wp.pos.x+endWP.pos.x)/2.0; - wp.pos.y = (last_wp.pos.y+endWP.pos.y)/2.0; - endWP.bDir = wp.bDir = direction; - goal_path.push_back(wp); - goal_path.push_back(endWP); - - goal_path.insert(goal_path.begin(), path.end()-5, path.end()); - PlanningHelpers::SmoothPath(goal_path, 0.25, 0.25); - PlanningHelpers::FixPathDensity(goal_path, 0.75); - PlanningHelpers::SmoothPath(goal_path, 0.25, 0.35); - - path.erase(path.end()-5, path.end()); - path.insert(path.end(), goal_path.begin(), goal_path.end()); - - PlanningHelpers::CalcAngleAndCost(path); - - for(unsigned int i=0; i < path.size(); i++) - { - if(direction == FORWARD_LEFT_DIR) - { - path.at(i).state = INITIAL_STATE; - path.at(i).beh_state = BEH_BRANCH_LEFT_STATE; - } - if(direction == FORWARD_RIGHT_DIR) - { - path.at(i).state = INITIAL_STATE; - path.at(i).beh_state = BEH_BRANCH_RIGHT_STATE; - } - } + if(path.size() < 5) return; + + //start branch point + WayPoint branch_start = path.at(path.size()-5); + WayPoint last_wp = path.at(path.size()-1); + + + WayPoint endWP; + vector goal_path; + double branch_angle = 0; + if(direction == FORWARD_RIGHT_DIR) + { + branch_angle = last_wp.pos.a-M_PI_2; + } + else if(direction == FORWARD_LEFT_DIR) + { + branch_angle = last_wp.pos.a+M_PI_2; + } + endWP.pos.y = last_wp.pos.y + 10*sin(branch_angle); + endWP.pos.x = last_wp.pos.x + 10*cos(branch_angle); + + WayPoint wp = last_wp; + wp.pos.x = (last_wp.pos.x+endWP.pos.x)/2.0; + wp.pos.y = (last_wp.pos.y+endWP.pos.y)/2.0; + endWP.bDir = wp.bDir = direction; + goal_path.push_back(wp); + goal_path.push_back(endWP); + + goal_path.insert(goal_path.begin(), path.end()-5, path.end()); + PlanningHelpers::SmoothPath(goal_path, 0.25, 0.25); + PlanningHelpers::FixPathDensity(goal_path, 0.75); + PlanningHelpers::SmoothPath(goal_path, 0.25, 0.35); + + path.erase(path.end()-5, path.end()); + path.insert(path.end(), goal_path.begin(), goal_path.end()); + + PlanningHelpers::CalcAngleAndCost(path); + + for(unsigned int i=0; i < path.size(); i++) + { + if(direction == FORWARD_LEFT_DIR) + { + path.at(i).state = INITIAL_STATE; + path.at(i).beh_state = BEH_BRANCH_LEFT_STATE; + } + if(direction == FORWARD_RIGHT_DIR) + { + path.at(i).state = INITIAL_STATE; + path.at(i).beh_state = BEH_BRANCH_RIGHT_STATE; + } + } } void PlanningHelpers::FixPathDensity(vector& path, const double& distanceDensity) { - if(path.size() == 0 || distanceDensity==0) return; - - double d = 0, a = 0; - double margin = distanceDensity*0.01; - double remaining = 0; - int nPoints = 0; - vector fixedPath; - fixedPath.push_back(path.at(0)); - for(unsigned int si = 0, ei=1; ei < path.size(); ) - { - d += hypot(path.at(ei).pos.x- path.at(ei-1).pos.x, path.at(ei).pos.y- path.at(ei-1).pos.y) + remaining; - a = atan2(path.at(ei).pos.y - path.at(si).pos.y, path.at(ei).pos.x - path.at(si).pos.x); - - if(d < distanceDensity - margin ) // skip - { - ei++; - remaining = 0; - } - else if(d > (distanceDensity + margin)) // skip - { - WayPoint pm = path.at(si); - nPoints = d / distanceDensity; - for(int k = 0; k < nPoints; k++) - { - pm.pos.x = pm.pos.x + distanceDensity * cos(a); - pm.pos.y = pm.pos.y + distanceDensity * sin(a); - fixedPath.push_back(pm); - } - remaining = d - nPoints*distanceDensity; - si++; - path.at(si).pos = pm.pos; - d = 0; - ei++; - } - else - { - d = 0; - remaining = 0; - fixedPath.push_back(path.at(ei)); - ei++; - si = ei - 1; - } - } - - path = fixedPath; + if(path.size() == 0 || distanceDensity==0) return; + + double d = 0, a = 0; + double margin = distanceDensity*0.01; + double remaining = 0; + int nPoints = 0; + vector fixedPath; + fixedPath.push_back(path.at(0)); + for(unsigned int si = 0, ei=1; ei < path.size(); ) + { + d += hypot(path.at(ei).pos.x- path.at(ei-1).pos.x, path.at(ei).pos.y- path.at(ei-1).pos.y) + remaining; + a = atan2(path.at(ei).pos.y - path.at(si).pos.y, path.at(ei).pos.x - path.at(si).pos.x); + + if(d < distanceDensity - margin ) // skip + { + ei++; + remaining = 0; + } + else if(d > (distanceDensity + margin)) // skip + { + WayPoint pm = path.at(si); + nPoints = d / distanceDensity; + for(int k = 0; k < nPoints; k++) + { + pm.pos.x = pm.pos.x + distanceDensity * cos(a); + pm.pos.y = pm.pos.y + distanceDensity * sin(a); + fixedPath.push_back(pm); + } + remaining = d - nPoints*distanceDensity; + si++; + path.at(si).pos = pm.pos; + d = 0; + ei++; + } + else + { + d = 0; + remaining = 0; + fixedPath.push_back(path.at(ei)); + ei++; + si = ei - 1; + } + } + + path = fixedPath; } void PlanningHelpers::SmoothPath(vector& path, double weight_data, - double weight_smooth, double tolerance) + double weight_smooth, double tolerance) { - if (path.size() <= 2 ) - { - //cout << "Can't Smooth Path, Path_in Size=" << path.size() << endl; - return; - } + if (path.size() <= 2 ) + { + //cout << "Can't Smooth Path, Path_in Size=" << path.size() << endl; + return; + } - const vector& path_in = path; - vector smoothPath_out = path_in; + const vector& path_in = path; + vector smoothPath_out = path_in; - double change = tolerance; - double xtemp, ytemp; - int nIterations = 0; + double change = tolerance; + double xtemp, ytemp; + int nIterations = 0; - int size = path_in.size(); + int size = path_in.size(); - while (change >= tolerance) - { - change = 0.0; - for (int i = 1; i < size - 1; i++) - { -// if (smoothPath_out[i].pos.a != smoothPath_out[i - 1].pos.a) -// continue; + while (change >= tolerance) + { + change = 0.0; + for (int i = 1; i < size - 1; i++) + { +// if (smoothPath_out[i].pos.a != smoothPath_out[i - 1].pos.a) +// continue; - xtemp = smoothPath_out[i].pos.x; - ytemp = smoothPath_out[i].pos.y; + xtemp = smoothPath_out[i].pos.x; + ytemp = smoothPath_out[i].pos.y; - smoothPath_out[i].pos.x += weight_data - * (path_in[i].pos.x - smoothPath_out[i].pos.x); - smoothPath_out[i].pos.y += weight_data - * (path_in[i].pos.y - smoothPath_out[i].pos.y); + smoothPath_out[i].pos.x += weight_data + * (path_in[i].pos.x - smoothPath_out[i].pos.x); + smoothPath_out[i].pos.y += weight_data + * (path_in[i].pos.y - smoothPath_out[i].pos.y); - smoothPath_out[i].pos.x += weight_smooth - * (smoothPath_out[i - 1].pos.x + smoothPath_out[i + 1].pos.x - - (2.0 * smoothPath_out[i].pos.x)); - smoothPath_out[i].pos.y += weight_smooth - * (smoothPath_out[i - 1].pos.y + smoothPath_out[i + 1].pos.y - - (2.0 * smoothPath_out[i].pos.y)); + smoothPath_out[i].pos.x += weight_smooth + * (smoothPath_out[i - 1].pos.x + smoothPath_out[i + 1].pos.x + - (2.0 * smoothPath_out[i].pos.x)); + smoothPath_out[i].pos.y += weight_smooth + * (smoothPath_out[i - 1].pos.y + smoothPath_out[i + 1].pos.y + - (2.0 * smoothPath_out[i].pos.y)); - change += fabs(xtemp - smoothPath_out[i].pos.x); - change += fabs(ytemp - smoothPath_out[i].pos.y); + change += fabs(xtemp - smoothPath_out[i].pos.x); + change += fabs(ytemp - smoothPath_out[i].pos.y); - } - nIterations++; - } + } + nIterations++; + } - path = smoothPath_out; + path = smoothPath_out; } void PlanningHelpers::PredictConstantTimeCostForTrajectory(std::vector& path, const PlannerHNS::WayPoint& currPose, const double& minVelocity, const double& minDist) { - if(path.size() == 0) return; + if(path.size() == 0) return; - for(unsigned int i = 0 ; i < path.size(); i++) - path.at(i).timeCost = -1; + for(unsigned int i = 0 ; i < path.size(); i++) + path.at(i).timeCost = -1; - if(currPose.v == 0 || currPose.v < minVelocity) return; + if(currPose.v == 0 || currPose.v < minVelocity) return; - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(path, currPose, info); + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(path, currPose, info); - double total_distance = 0; - double accum_time = 0; + double total_distance = 0; + double accum_time = 0; - path.at(info.iFront).timeCost = 0; - if(info.iFront == 0 ) info.iFront++; + path.at(info.iFront).timeCost = 0; + if(info.iFront == 0 ) info.iFront++; - for(unsigned int i=info.iFront; i& path) { - if(path.size() <= 2) return; + if(path.size() <= 2) return; - path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); + path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); - for(int j = 1; j < path.size()-1; j++) - path[j].pos.a = UtilityH::FixNegativeAngle(atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x )); + for(int j = 1; j < path.size()-1; j++) + path[j].pos.a = UtilityH::FixNegativeAngle(atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x )); - int j = (int)path.size()-1; + int j = (int)path.size()-1; - path[j].pos.a = path[j-1].pos.a; + path[j].pos.a = path[j-1].pos.a; - for(int j = 0; j < path.size()-1; j++) - { - if(path.at(j).pos.x == path.at(j+1).pos.x && path.at(j).pos.y == path.at(j+1).pos.y) - path.at(j).pos.a = path.at(j+1).pos.a; - } + for(int j = 0; j < path.size()-1; j++) + { + if(path.at(j).pos.x == path.at(j+1).pos.x && path.at(j).pos.y == path.at(j+1).pos.y) + path.at(j).pos.a = path.at(j+1).pos.a; + } } double PlanningHelpers::CalcAngleAndCost(vector& path, const double& lastCost, const bool& bSmooth) { - if(path.size() < 2) return 0; - if(path.size() == 2) - { - path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); - path[0].cost = lastCost; - path[1].pos.a = path[0].pos.a; - path[1].cost = path[0].cost + distance2points(path[0].pos, path[1].pos); - return path[1].cost; - } - - path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); - path[0].cost = lastCost; - - for(int j = 1; j < path.size()-1; j++) - { - path[j].pos.a = UtilityH::FixNegativeAngle(atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x )); - path[j].cost = path[j-1].cost + distance2points(path[j-1].pos, path[j].pos); - } - - int j = (int)path.size()-1; - - path[j].pos.a = path[j-1].pos.a; - path[j].cost = path[j-1].cost + distance2points(path[j-1].pos, path[j].pos); - - for(int j = 0; j < path.size()-1; j++) - { - if(path.at(j).pos.x == path.at(j+1).pos.x && path.at(j).pos.y == path.at(j+1).pos.y) - path.at(j).pos.a = path.at(j+1).pos.a; - } - - return path[j].cost; + if(path.size() < 2) return 0; + if(path.size() == 2) + { + path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); + path[0].cost = lastCost; + path[1].pos.a = path[0].pos.a; + path[1].cost = path[0].cost + distance2points(path[0].pos, path[1].pos); + return path[1].cost; + } + + path[0].pos.a = UtilityH::FixNegativeAngle(atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x )); + path[0].cost = lastCost; + + for(int j = 1; j < path.size()-1; j++) + { + path[j].pos.a = UtilityH::FixNegativeAngle(atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x )); + path[j].cost = path[j-1].cost + distance2points(path[j-1].pos, path[j].pos); + } + + int j = (int)path.size()-1; + + path[j].pos.a = path[j-1].pos.a; + path[j].cost = path[j-1].cost + distance2points(path[j-1].pos, path[j].pos); + + for(int j = 0; j < path.size()-1; j++) + { + if(path.at(j).pos.x == path.at(j+1).pos.x && path.at(j).pos.y == path.at(j+1).pos.y) + path.at(j).pos.a = path.at(j+1).pos.a; + } + + return path[j].cost; } double PlanningHelpers::CalcAngleAndCostAndCurvatureAnd2D(vector& path, const double& lastCost) { - if(path.size() < 2) return -1; + if(path.size() < 2) return -1; - path[0].pos.a = atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x ); - path[0].cost = lastCost; + path[0].pos.a = atan2(path[1].pos.y - path[0].pos.y, path[1].pos.x - path[0].pos.x ); + path[0].cost = lastCost; - double k = 0; - GPSPoint center; + double k = 0; + GPSPoint center; - for(unsigned int j = 1; j < path.size()-1; j++) - { - k = CalcCircle(path[j-1].pos,path[j].pos, path[j+1].pos, center); - if(k > 150.0 || std::isnan(k)) - k = 150.0; + for(unsigned int j = 1; j < path.size()-1; j++) + { + k = CalcCircle(path[j-1].pos,path[j].pos, path[j+1].pos, center); + if(k > 150.0 || std::isnan(k)) + k = 150.0; - if(k<1.0) - path[j].cost = 0; - else - path[j].cost = 1.0-1.0/k; + if(k<1.0) + path[j].cost = 0; + else + path[j].cost = 1.0-1.0/k; - path[j].pos.a = atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x ); - } - unsigned int j = path.size()-1; + path[j].pos.a = atan2(path[j+1].pos.y - path[j].pos.y, path[j+1].pos.x - path[j].pos.x ); + } + unsigned int j = path.size()-1; - path[0].cost = path[1].cost; - path[j].cost = path[j-1].cost; - path[j].pos.a = path[j-1].pos.a; - path[j].cost = path[j-1].cost ; + path[0].cost = path[1].cost; + path[j].cost = path[j-1].cost; + path[j].pos.a = path[j-1].pos.a; + path[j].cost = path[j-1].cost ; - return path[j].cost; + return path[j].cost; } double PlanningHelpers::CalcCircle(const GPSPoint& pt1, const GPSPoint& pt2, const GPSPoint& pt3, GPSPoint& center) { - double yDelta_a= pt2.y - pt1.y; - double xDelta_a= pt2.x - pt1.x; - double yDelta_b= pt3.y - pt2.y; - double xDelta_b= pt3.x - pt2.x; - - if (fabs(xDelta_a) <= 0.000000000001 && fabs(yDelta_b) <= 0.000000000001) - { - center.x= 0.5*(pt2.x + pt3.x); - center.y= 0.5*(pt1.y + pt2.y); - return distance2points(center,pt1); - } - - double aSlope=yDelta_a/xDelta_a; - double bSlope=yDelta_b/xDelta_b; - if (fabs(aSlope-bSlope) <= 0.000000000001) - { - return 100000; - } - - center.x= (aSlope*bSlope*(pt1.y - pt3.y) + bSlope*(pt1.x + pt2 .x) - aSlope*(pt2.x+pt3.x) )/(2.0* (bSlope-aSlope) ); - center.y = -1.0*(center.x - (pt1.x+pt2.x)/2.0)/aSlope + (pt1.y+pt2.y)/2.0; - - return distance2points(center,pt1); + double yDelta_a= pt2.y - pt1.y; + double xDelta_a= pt2.x - pt1.x; + double yDelta_b= pt3.y - pt2.y; + double xDelta_b= pt3.x - pt2.x; + + if (fabs(xDelta_a) <= 0.000000000001 && fabs(yDelta_b) <= 0.000000000001) + { + center.x= 0.5*(pt2.x + pt3.x); + center.y= 0.5*(pt1.y + pt2.y); + return distance2points(center,pt1); + } + + double aSlope=yDelta_a/xDelta_a; + double bSlope=yDelta_b/xDelta_b; + if (fabs(aSlope-bSlope) <= 0.000000000001) + { + return 100000; + } + + center.x= (aSlope*bSlope*(pt1.y - pt3.y) + bSlope*(pt1.x + pt2 .x) - aSlope*(pt2.x+pt3.x) )/(2.0* (bSlope-aSlope) ); + center.y = -1.0*(center.x - (pt1.x+pt2.x)/2.0)/aSlope + (pt1.y+pt2.y)/2.0; + + return distance2points(center,pt1); } void PlanningHelpers::ExtractPartFromPointToDistance(const vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance) -{ - extractedPath.clear(); - unsigned int close_index = GetClosestNextPointIndexDirectionFast(originalPath, pos); -// int i_slow = GetClosestNextPointIndexDirection(originalPath, pos); -// if(close_index != i_slow) -// cout << "Aler Alert !!! fast: " << close_index << ", slow: " << i_slow << endl; - //vector tempPath; - double d_limit = 0; - if(close_index >= 2) close_index -=2; - else close_index = 0; - - for(unsigned int i=close_index; i< originalPath.size(); i++) - { - extractedPath.push_back(originalPath.at(i)); - - if(i>0) - d_limit += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); - - if(d_limit > minDistance) - break; - } - - if(extractedPath.size() < 2) - { - cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; - return; - } - - FixPathDensity(extractedPath, pathDensity); - SmoothPath(extractedPath, SmoothDataWeight, SmoothWeight , SmoothTolerance); - CalcAngleAndCost(extractedPath); - - //extractedPath = tempPath; - //tempPath.clear(); - //TestQuadraticSpline(extractedPath, tempPath); + const double& pathDensity, vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance) +{ + extractedPath.clear(); + unsigned int close_index = GetClosestNextPointIndexDirectionFast(originalPath, pos); +// int i_slow = GetClosestNextPointIndexDirection(originalPath, pos); +// if(close_index != i_slow) +// cout << "Aler Alert !!! fast: " << close_index << ", slow: " << i_slow << endl; + //vector tempPath; + double d_limit = 0; + if(close_index >= 2) close_index -=2; + else close_index = 0; + + for(unsigned int i=close_index; i< originalPath.size(); i++) + { + extractedPath.push_back(originalPath.at(i)); + + if(i>0) + d_limit += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); + + if(d_limit > minDistance) + break; + } + + if(extractedPath.size() < 2) + { + cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; + return; + } + + FixPathDensity(extractedPath, pathDensity); + SmoothPath(extractedPath, SmoothDataWeight, SmoothWeight , SmoothTolerance); + CalcAngleAndCost(extractedPath); + + //extractedPath = tempPath; + //tempPath.clear(); + //TestQuadraticSpline(extractedPath, tempPath); } void PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(const vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, vector& extractedPath) -{ - if(originalPath.size() < 2 ) return; - - extractedPath.clear(); - - int close_index = GetClosestNextPointIndexDirectionFast(originalPath, pos); - double d = 0; - - if(close_index + 1 >= originalPath.size()) - close_index = originalPath.size() - 2; - - for(int i=close_index; i >= 0; i--) - { - extractedPath.insert(extractedPath.begin(), originalPath.at(i)); - if(i < originalPath.size()) - d += hypot(originalPath.at(i).pos.y - originalPath.at(i+1).pos.y, originalPath.at(i).pos.x - originalPath.at(i+1).pos.x); - if(d > 10) - break; - } - - //extractedPath.push_back(info.perp_point); - d = 0; - for(int i=close_index+1; i < (int)originalPath.size(); i++) - { - extractedPath.push_back(originalPath.at(i)); - if(i > 0) - d += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); - if(d > minDistance) - break; - } - - if(extractedPath.size() < 2) - { - cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; - return; - } - - FixPathDensity(extractedPath, pathDensity); - CalcAngleAndCost(extractedPath); + const double& pathDensity, vector& extractedPath) +{ + if(originalPath.size() < 2 ) return; + + extractedPath.clear(); + + int close_index = GetClosestNextPointIndexDirectionFast(originalPath, pos); + double d = 0; + + if(close_index + 1 >= originalPath.size()) + close_index = originalPath.size() - 2; + + for(int i=close_index; i >= 0; i--) + { + extractedPath.insert(extractedPath.begin(), originalPath.at(i)); + if(i < originalPath.size()) + d += hypot(originalPath.at(i).pos.y - originalPath.at(i+1).pos.y, originalPath.at(i).pos.x - originalPath.at(i+1).pos.x); + if(d > 10) + break; + } + + //extractedPath.push_back(info.perp_point); + d = 0; + for(int i=close_index+1; i < (int)originalPath.size(); i++) + { + extractedPath.push_back(originalPath.at(i)); + if(i > 0) + d += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); + if(d > minDistance) + break; + } + + if(extractedPath.size() < 2) + { + cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; + return; + } + + FixPathDensity(extractedPath, pathDensity); + CalcAngleAndCost(extractedPath); } void PlanningHelpers::ExtractPartFromPointToDistanceFast(const vector& originalPath, const WayPoint& pos, const double& minDistance, - const double& pathDensity, vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance) -{ - extractedPath.clear(); - RelativeInfo info; - GetRelativeInfo(originalPath, pos, info); - double d = 0; - if(info.iBack > 0) - info.iBack--; - - for(int i=info.iBack; i >= 0; i--) - { - extractedPath.insert(extractedPath.begin(), originalPath.at(i)); - if(i < originalPath.size()) - d += hypot(originalPath.at(i).pos.y - originalPath.at(i+1).pos.y, originalPath.at(i).pos.x - originalPath.at(i+1).pos.x); - if(d > 10) - break; - } - - //extractedPath.push_back(info.perp_point); - d = 0; - for(int i=info.iBack+1; i < (int)originalPath.size(); i++) - { - extractedPath.push_back(originalPath.at(i)); - if(i > 0) - d += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); - if(d > minDistance) - break; - } - - if(extractedPath.size() < 2) - { - cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; - return; - } - - FixPathDensity(extractedPath, pathDensity); - CalcAngleAndCost(extractedPath); + const double& pathDensity, vector& extractedPath, const double& SmoothDataWeight, const double& SmoothWeight, const double& SmoothTolerance) +{ + extractedPath.clear(); + RelativeInfo info; + GetRelativeInfo(originalPath, pos, info); + double d = 0; + if(info.iBack > 0) + info.iBack--; + + for(int i=info.iBack; i >= 0; i--) + { + extractedPath.insert(extractedPath.begin(), originalPath.at(i)); + if(i < originalPath.size()) + d += hypot(originalPath.at(i).pos.y - originalPath.at(i+1).pos.y, originalPath.at(i).pos.x - originalPath.at(i+1).pos.x); + if(d > 10) + break; + } + + //extractedPath.push_back(info.perp_point); + d = 0; + for(int i=info.iBack+1; i < (int)originalPath.size(); i++) + { + extractedPath.push_back(originalPath.at(i)); + if(i > 0) + d += hypot(originalPath.at(i).pos.y - originalPath.at(i-1).pos.y, originalPath.at(i).pos.x - originalPath.at(i-1).pos.x); + if(d > minDistance) + break; + } + + if(extractedPath.size() < 2) + { + cout << endl << "### Planner Z . Extracted Rollout Path is too Small, Size = " << extractedPath.size() << endl; + return; + } + + FixPathDensity(extractedPath, pathDensity); + CalcAngleAndCost(extractedPath); } void PlanningHelpers::CalculateRollInTrajectories(const WayPoint& carPos, const double& speed, const vector& originalCenter, int& start_index, - int& end_index, vector& end_laterals , - vector >& rollInPaths, const double& max_roll_distance, - const double& maxSpeed, const double& carTipMargin, const double& rollInMargin, - const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, - const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, - const double& SmoothTolerance, const bool& bHeadingSmooth, - std::vector& sampledPoints) -{ - WayPoint p; - double dummyd = 0; - - int iLimitIndex = (carTipMargin/0.3)/pathDensity; - if(iLimitIndex >= originalCenter.size()) - iLimitIndex = originalCenter.size() - 1; - - //Get Closest Index - RelativeInfo info; - GetRelativeInfo(originalCenter, carPos, info); - double remaining_distance = 0; - int close_index = info.iBack; - for(unsigned int i=close_index; i< originalCenter.size()-1; i++) - { - if(i>0) - remaining_distance += distance2points(originalCenter[i].pos, originalCenter[i+1].pos); - } - - double initial_roll_in_distance = info.perp_distance ; //GetPerpDistanceToTrajectorySimple(originalCenter, carPos, close_index); - - - vector RollOutStratPath; - ///*** Smoothing From Car Heading Section ***/// -// if(bHeadingSmooth) -// { -// unsigned int num_of_strait_points = carTipMargin / pathDensity; -// int closest_for_each_iteration = 0; -// WayPoint np = GetPerpendicularOnTrajectory_obsolete(originalCenter, carPos, dummyd, closest_for_each_iteration); -// np.pos = carPos.pos; + int& end_index, vector& end_laterals , + vector >& rollInPaths, const double& max_roll_distance, + const double& maxSpeed, const double& carTipMargin, const double& rollInMargin, + const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity, + const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight, + const double& SmoothTolerance, const bool& bHeadingSmooth, + std::vector& sampledPoints) +{ + WayPoint p; + double dummyd = 0; + + int iLimitIndex = (carTipMargin/0.3)/pathDensity; + if(iLimitIndex >= originalCenter.size()) + iLimitIndex = originalCenter.size() - 1; + + //Get Closest Index + RelativeInfo info; + GetRelativeInfo(originalCenter, carPos, info); + double remaining_distance = 0; + int close_index = info.iBack; + for(unsigned int i=close_index; i< originalCenter.size()-1; i++) + { + if(i>0) + remaining_distance += distance2points(originalCenter[i].pos, originalCenter[i+1].pos); + } + + double initial_roll_in_distance = info.perp_distance ; //GetPerpDistanceToTrajectorySimple(originalCenter, carPos, close_index); + + + vector RollOutStratPath; + ///*** Smoothing From Car Heading Section ***/// +// if(bHeadingSmooth) +// { +// unsigned int num_of_strait_points = carTipMargin / pathDensity; +// int closest_for_each_iteration = 0; +// WayPoint np = GetPerpendicularOnTrajectory_obsolete(originalCenter, carPos, dummyd, closest_for_each_iteration); +// np.pos = carPos.pos; // -// RollOutStratPath.push_back(np); -// for(unsigned int i = 0; i < num_of_strait_points; i++) -// { -// p = RollOutStratPath.at(i); -// p.pos.x = p.pos.x + pathDensity*cos(p.pos.a); -// p.pos.y = p.pos.y + pathDensity*sin(p.pos.a); -// np = GetPerpendicularOnTrajectory_obsolete(originalCenter, p, dummyd, closest_for_each_iteration); -// np.pos = p.pos; -// RollOutStratPath.push_back(np); -// } +// RollOutStratPath.push_back(np); +// for(unsigned int i = 0; i < num_of_strait_points; i++) +// { +// p = RollOutStratPath.at(i); +// p.pos.x = p.pos.x + pathDensity*cos(p.pos.a); +// p.pos.y = p.pos.y + pathDensity*sin(p.pos.a); +// np = GetPerpendicularOnTrajectory_obsolete(originalCenter, p, dummyd, closest_for_each_iteration); +// np.pos = p.pos; +// RollOutStratPath.push_back(np); +// } // -// initial_roll_in_distance = GetPerpDistanceToTrajectorySimple_obsolete(originalCenter, RollOutStratPath.at(RollOutStratPath.size()-1), close_index); -// } - ///*** -------------------------------- ***/// - - - //printf("\n Lateral Distance: %f" , initial_roll_in_distance); - - //calculate the starting index - double d_limit = 0; - unsigned int far_index = close_index; - - //calculate end index - double start_distance = rollInSpeedFactor*speed+rollInMargin; - if(start_distance > remaining_distance) - start_distance = remaining_distance; - - d_limit = 0; - for(unsigned int i=close_index; i< originalCenter.size(); i++) - { - if(i>0) - d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); - - if(d_limit >= start_distance) - { - far_index = i; - break; - } - } - - int centralTrajectoryIndex = rollOutNumber/2; - vector end_distance_list; - for(int i=0; i< rollOutNumber+1; i++) - { - double end_roll_in_distance = rollOutDensity*(i - centralTrajectoryIndex); - end_distance_list.push_back(end_roll_in_distance); - } - - start_index = close_index; - end_index = far_index; - end_laterals = end_distance_list; - - //calculate the actual calculation starting index - d_limit = 0; - unsigned int smoothing_start_index = start_index; - unsigned int smoothing_end_index = end_index; - - for(unsigned int i=smoothing_start_index; i< originalCenter.size(); i++) - { - if(i > 0) - d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); - if(d_limit > carTipMargin) - break; - - smoothing_start_index++; - } - - d_limit = 0; - for(unsigned int i=end_index; i< originalCenter.size(); i++) - { - if(i > 0) - d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); - if(d_limit > carTipMargin) - break; - - smoothing_end_index++; - } - - int nSteps = end_index - smoothing_start_index; - - - vector inc_list; - rollInPaths.clear(); - vector inc_list_inc; - for(int i=0; i< rollOutNumber+1; i++) - { - double diff = end_laterals.at(i)-initial_roll_in_distance; - inc_list.push_back(diff/(double)nSteps); - rollInPaths.push_back(vector()); - inc_list_inc.push_back(0); - } - - - - vector > execluded_from_smoothing; - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - execluded_from_smoothing.push_back(vector()); - - - - //Insert First strait points within the tip of the car range - for(unsigned int j = start_index; j < smoothing_start_index; j++) - { - p = originalCenter.at(j); - double original_speed = p.v; - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - { - p.pos.x = originalCenter.at(j).pos.x - initial_roll_in_distance*cos(p.pos.a + M_PI_2); - p.pos.y = originalCenter.at(j).pos.y - initial_roll_in_distance*sin(p.pos.a + M_PI_2); - if(i!=centralTrajectoryIndex) - p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; - else - p.v = original_speed ; - - if(j < iLimitIndex) - execluded_from_smoothing.at(i).push_back(p); - else - rollInPaths.at(i).push_back(p); - - sampledPoints.push_back(p); - } - } - - for(unsigned int j = smoothing_start_index; j < end_index; j++) - { - p = originalCenter.at(j); - double original_speed = p.v; - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - { - inc_list_inc[i] += inc_list[i]; - double d = inc_list_inc[i]; - p.pos.x = originalCenter.at(j).pos.x - initial_roll_in_distance*cos(p.pos.a + M_PI_2) - d*cos(p.pos.a+ M_PI_2); - p.pos.y = originalCenter.at(j).pos.y - initial_roll_in_distance*sin(p.pos.a + M_PI_2) - d*sin(p.pos.a+ M_PI_2); - if(i!=centralTrajectoryIndex) - p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; - else - p.v = original_speed ; - - rollInPaths.at(i).push_back(p); - - sampledPoints.push_back(p); - } - } - - //Insert last strait points to make better smoothing - for(unsigned int j = end_index; j < smoothing_end_index; j++) - { - p = originalCenter.at(j); - double original_speed = p.v; - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - { - double d = end_laterals.at(i); - p.pos.x = originalCenter.at(j).pos.x - d*cos(p.pos.a + M_PI_2); - p.pos.y = originalCenter.at(j).pos.y - d*sin(p.pos.a + M_PI_2); - if(i!=centralTrajectoryIndex) - p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; - else - p.v = original_speed ; - rollInPaths.at(i).push_back(p); - - sampledPoints.push_back(p); - } - } - - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - rollInPaths.at(i).insert(rollInPaths.at(i).begin(), execluded_from_smoothing.at(i).begin(), execluded_from_smoothing.at(i).end()); - - ///*** Smoothing From Car Heading Section ***/// -// if(bHeadingSmooth) -// { -// for(unsigned int i=0; i< rollOutNumber+1 ; i++) -// { -// unsigned int cut_index = GetClosestNextPointIndex(rollInPaths.at(i), RollOutStratPath.at(RollOutStratPath.size()-1)); -// rollInPaths.at(i).erase(rollInPaths.at(i).begin(), rollInPaths.at(i).begin()+cut_index); -// rollInPaths.at(i).insert(rollInPaths.at(i).begin(), RollOutStratPath.begin(), RollOutStratPath.end()); -// } -// } - ///*** -------------------------------- ***/// - - - - d_limit = 0; - for(unsigned int j = smoothing_end_index; j < originalCenter.size(); j++) - { - if(j > 0) - d_limit += distance2points(originalCenter.at(j).pos, originalCenter.at(j-1).pos); - - if(d_limit > max_roll_distance) - break; - - p = originalCenter.at(j); - double original_speed = p.v; - for(unsigned int i=0; i< rollInPaths.size() ; i++) - { - double d = end_laterals.at(i); - p.pos.x = originalCenter.at(j).pos.x - d*cos(p.pos.a + M_PI_2); - p.pos.y = originalCenter.at(j).pos.y - d*sin(p.pos.a + M_PI_2); - - if(i!=centralTrajectoryIndex) - p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; - else - p.v = original_speed ; - - rollInPaths.at(i).push_back(p); - - sampledPoints.push_back(p); - } - } - - for(unsigned int i=0; i< rollOutNumber+1 ; i++) - { - SmoothPath(rollInPaths.at(i), SmoothDataWeight, SmoothWeight, SmoothTolerance); - } - -// for(unsigned int i=0; i< rollInPaths.size(); i++) -// CalcAngleAndCost(rollInPaths.at(i)); +// initial_roll_in_distance = GetPerpDistanceToTrajectorySimple_obsolete(originalCenter, RollOutStratPath.at(RollOutStratPath.size()-1), close_index); +// } + ///*** -------------------------------- ***/// + + + //printf("\n Lateral Distance: %f" , initial_roll_in_distance); + + //calculate the starting index + double d_limit = 0; + unsigned int far_index = close_index; + + //calculate end index + double start_distance = rollInSpeedFactor*speed+rollInMargin; + if(start_distance > remaining_distance) + start_distance = remaining_distance; + + d_limit = 0; + for(unsigned int i=close_index; i< originalCenter.size(); i++) + { + if(i>0) + d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); + + if(d_limit >= start_distance) + { + far_index = i; + break; + } + } + + int centralTrajectoryIndex = rollOutNumber/2; + vector end_distance_list; + for(int i=0; i< rollOutNumber+1; i++) + { + double end_roll_in_distance = rollOutDensity*(i - centralTrajectoryIndex); + end_distance_list.push_back(end_roll_in_distance); + } + + start_index = close_index; + end_index = far_index; + end_laterals = end_distance_list; + + //calculate the actual calculation starting index + d_limit = 0; + unsigned int smoothing_start_index = start_index; + unsigned int smoothing_end_index = end_index; + + for(unsigned int i=smoothing_start_index; i< originalCenter.size(); i++) + { + if(i > 0) + d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); + if(d_limit > carTipMargin) + break; + + smoothing_start_index++; + } + + d_limit = 0; + for(unsigned int i=end_index; i< originalCenter.size(); i++) + { + if(i > 0) + d_limit += distance2points(originalCenter[i].pos, originalCenter[i-1].pos); + if(d_limit > carTipMargin) + break; + + smoothing_end_index++; + } + + int nSteps = end_index - smoothing_start_index; + + + vector inc_list; + rollInPaths.clear(); + vector inc_list_inc; + for(int i=0; i< rollOutNumber+1; i++) + { + double diff = end_laterals.at(i)-initial_roll_in_distance; + inc_list.push_back(diff/(double)nSteps); + rollInPaths.push_back(vector()); + inc_list_inc.push_back(0); + } + + + + vector > execluded_from_smoothing; + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + execluded_from_smoothing.push_back(vector()); + + + + //Insert First strait points within the tip of the car range + for(unsigned int j = start_index; j < smoothing_start_index; j++) + { + p = originalCenter.at(j); + double original_speed = p.v; + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + { + p.pos.x = originalCenter.at(j).pos.x - initial_roll_in_distance*cos(p.pos.a + M_PI_2); + p.pos.y = originalCenter.at(j).pos.y - initial_roll_in_distance*sin(p.pos.a + M_PI_2); + if(i!=centralTrajectoryIndex) + p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; + else + p.v = original_speed ; + + if(j < iLimitIndex) + execluded_from_smoothing.at(i).push_back(p); + else + rollInPaths.at(i).push_back(p); + + sampledPoints.push_back(p); + } + } + + for(unsigned int j = smoothing_start_index; j < end_index; j++) + { + p = originalCenter.at(j); + double original_speed = p.v; + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + { + inc_list_inc[i] += inc_list[i]; + double d = inc_list_inc[i]; + p.pos.x = originalCenter.at(j).pos.x - initial_roll_in_distance*cos(p.pos.a + M_PI_2) - d*cos(p.pos.a+ M_PI_2); + p.pos.y = originalCenter.at(j).pos.y - initial_roll_in_distance*sin(p.pos.a + M_PI_2) - d*sin(p.pos.a+ M_PI_2); + if(i!=centralTrajectoryIndex) + p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; + else + p.v = original_speed ; + + rollInPaths.at(i).push_back(p); + + sampledPoints.push_back(p); + } + } + + //Insert last strait points to make better smoothing + for(unsigned int j = end_index; j < smoothing_end_index; j++) + { + p = originalCenter.at(j); + double original_speed = p.v; + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + { + double d = end_laterals.at(i); + p.pos.x = originalCenter.at(j).pos.x - d*cos(p.pos.a + M_PI_2); + p.pos.y = originalCenter.at(j).pos.y - d*sin(p.pos.a + M_PI_2); + if(i!=centralTrajectoryIndex) + p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; + else + p.v = original_speed ; + rollInPaths.at(i).push_back(p); + + sampledPoints.push_back(p); + } + } + + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + rollInPaths.at(i).insert(rollInPaths.at(i).begin(), execluded_from_smoothing.at(i).begin(), execluded_from_smoothing.at(i).end()); + + ///*** Smoothing From Car Heading Section ***/// +// if(bHeadingSmooth) +// { +// for(unsigned int i=0; i< rollOutNumber+1 ; i++) +// { +// unsigned int cut_index = GetClosestNextPointIndex(rollInPaths.at(i), RollOutStratPath.at(RollOutStratPath.size()-1)); +// rollInPaths.at(i).erase(rollInPaths.at(i).begin(), rollInPaths.at(i).begin()+cut_index); +// rollInPaths.at(i).insert(rollInPaths.at(i).begin(), RollOutStratPath.begin(), RollOutStratPath.end()); +// } +// } + ///*** -------------------------------- ***/// + + + + d_limit = 0; + for(unsigned int j = smoothing_end_index; j < originalCenter.size(); j++) + { + if(j > 0) + d_limit += distance2points(originalCenter.at(j).pos, originalCenter.at(j-1).pos); + + if(d_limit > max_roll_distance) + break; + + p = originalCenter.at(j); + double original_speed = p.v; + for(unsigned int i=0; i< rollInPaths.size() ; i++) + { + double d = end_laterals.at(i); + p.pos.x = originalCenter.at(j).pos.x - d*cos(p.pos.a + M_PI_2); + p.pos.y = originalCenter.at(j).pos.y - d*sin(p.pos.a + M_PI_2); + + if(i!=centralTrajectoryIndex) + p.v = original_speed * LANE_CHANGE_SPEED_FACTOR; + else + p.v = original_speed ; + + rollInPaths.at(i).push_back(p); + + sampledPoints.push_back(p); + } + } + + for(unsigned int i=0; i< rollOutNumber+1 ; i++) + { + SmoothPath(rollInPaths.at(i), SmoothDataWeight, SmoothWeight, SmoothTolerance); + } + +// for(unsigned int i=0; i< rollInPaths.size(); i++) +// CalcAngleAndCost(rollInPaths.at(i)); } bool PlanningHelpers::FindInList(const std::vector& list,const int& x) { - for(unsigned int i = 0 ; i < list.size(); i++) - { - if(list.at(i) == x) - return true; - } - return false; + for(unsigned int i = 0 ; i < list.size(); i++) + { + if(list.at(i) == x) + return true; + } + return false; } void PlanningHelpers::RemoveWithValue(std::vector& list,const int& x) { - for(unsigned int i = 0 ; i < list.size(); i++) - { - if(list.at(i) == x) - { - list.erase(list.begin()+i); - } - } + for(unsigned int i = 0 ; i < list.size(); i++) + { + if(list.at(i) == x) + { + list.erase(list.begin()+i); + } + } } std::vector PlanningHelpers::GetUniqueLeftRightIds(const std::vector& path) { - vector sideLanes; - for(unsigned int iwp = 0; iwp < path.size(); iwp++) - { - if(path.at(iwp).LeftPointId>0) - { - bool bFound = false; - for(unsigned int is = 0 ; is < sideLanes.size(); is++) - { - if(sideLanes.at(is) == path.at(iwp).LeftPointId) - { - bFound = true; - break; - } - } - - if(!bFound) - sideLanes.push_back(path.at(iwp).LeftPointId); - } - - if(path.at(iwp).RightPointId>0) - { - bool bFound = false; - for(unsigned int is = 0 ; is < sideLanes.size(); is++) - { - if(sideLanes.at(is) == path.at(iwp).RightPointId) - { - bFound = true; - break; - } - } - - if(!bFound) - sideLanes.push_back(path.at(iwp).RightPointId); - } - - //RemoveWithValue(sideLanes, path.at(iwp).laneId); - } - return sideLanes; + vector sideLanes; + for(unsigned int iwp = 0; iwp < path.size(); iwp++) + { + if(path.at(iwp).LeftPointId>0) + { + bool bFound = false; + for(unsigned int is = 0 ; is < sideLanes.size(); is++) + { + if(sideLanes.at(is) == path.at(iwp).LeftPointId) + { + bFound = true; + break; + } + } + + if(!bFound) + sideLanes.push_back(path.at(iwp).LeftPointId); + } + + if(path.at(iwp).RightPointId>0) + { + bool bFound = false; + for(unsigned int is = 0 ; is < sideLanes.size(); is++) + { + if(sideLanes.at(is) == path.at(iwp).RightPointId) + { + bFound = true; + break; + } + } + + if(!bFound) + sideLanes.push_back(path.at(iwp).RightPointId); + } + + //RemoveWithValue(sideLanes, path.at(iwp).laneId); + } + return sideLanes; } -void PlanningHelpers::SmoothSpeedProfiles(vector& path_in, double weight_data, double weight_smooth, double tolerance ) +void PlanningHelpers::SmoothSpeedProfiles(vector& path_in, double weight_data, double weight_smooth, double tolerance ) { - if (path_in.size() <= 1) - return; - vector newpath = path_in; - - double change = tolerance; - double xtemp; - int nIterations = 0; - int size = newpath.size(); - - while (change >= tolerance) - { - change = 0.0; - for (int i = 1; i < size -1; i++) - { - xtemp = newpath[i].v; - newpath[i].v += weight_data * (path_in[i].v - newpath[i].v); - newpath[i].v += weight_smooth * (newpath[i - 1].v + newpath[i + 1].v - (2.0 * newpath[i].v)); - change += fabs(xtemp - newpath[i].v); - - } - nIterations++; - } - - path_in = newpath; + if (path_in.size() <= 1) + return; + vector newpath = path_in; + + double change = tolerance; + double xtemp; + int nIterations = 0; + int size = newpath.size(); + + while (change >= tolerance) + { + change = 0.0; + for (int i = 1; i < size -1; i++) + { + xtemp = newpath[i].v; + newpath[i].v += weight_data * (path_in[i].v - newpath[i].v); + newpath[i].v += weight_smooth * (newpath[i - 1].v + newpath[i + 1].v - (2.0 * newpath[i].v)); + change += fabs(xtemp - newpath[i].v); + + } + nIterations++; + } + + path_in = newpath; } void PlanningHelpers::SmoothCurvatureProfiles(vector& path_in, double weight_data, double weight_smooth, double tolerance) { - if (path_in.size() <= 1) - return; - vector newpath = path_in; - - double change = tolerance; - double xtemp; - int nIterations = 0; - int size = newpath.size(); - - while (change >= tolerance) - { - change = 0.0; - for (int i = 1; i < size -1; i++) - { - xtemp = newpath[i].cost; - newpath[i].cost += weight_data * (path_in[i].cost - newpath[i].cost); - newpath[i].cost += weight_smooth * (newpath[i - 1].cost + newpath[i + 1].cost - (2.0 * newpath[i].cost)); - change += fabs(xtemp - newpath[i].cost); - - } - nIterations++; - } - path_in = newpath; + if (path_in.size() <= 1) + return; + vector newpath = path_in; + + double change = tolerance; + double xtemp; + int nIterations = 0; + int size = newpath.size(); + + while (change >= tolerance) + { + change = 0.0; + for (int i = 1; i < size -1; i++) + { + xtemp = newpath[i].cost; + newpath[i].cost += weight_data * (path_in[i].cost - newpath[i].cost); + newpath[i].cost += weight_smooth * (newpath[i - 1].cost + newpath[i + 1].cost - (2.0 * newpath[i].cost)); + change += fabs(xtemp - newpath[i].cost); + + } + nIterations++; + } + path_in = newpath; } -void PlanningHelpers::SmoothWayPointsDirections(vector& path_in, double weight_data, double weight_smooth, double tolerance ) +void PlanningHelpers::SmoothWayPointsDirections(vector& path_in, double weight_data, double weight_smooth, double tolerance ) { - if (path_in.size() <= 1) - return; - - vector newpath = path_in; - - double change = tolerance; - double xtemp; - int nIterations = 0; - int size = newpath.size(); - - while (change >= tolerance) - { - change = 0.0; - for (int i = 1; i < size -1; i++) - { - xtemp = newpath[i].pos.a; - newpath[i].pos.a += weight_data * (path_in[i].pos.a - newpath[i].pos.a); - newpath[i].pos.a += weight_smooth * (newpath[i - 1].pos.a + newpath[i + 1].pos.a - (2.0 * newpath[i].pos.a)); - change += fabs(xtemp - newpath[i].pos.a); - - } - nIterations++; - } - path_in = newpath; + if (path_in.size() <= 1) + return; + + vector newpath = path_in; + + double change = tolerance; + double xtemp; + int nIterations = 0; + int size = newpath.size(); + + while (change >= tolerance) + { + change = 0.0; + for (int i = 1; i < size -1; i++) + { + xtemp = newpath[i].pos.a; + newpath[i].pos.a += weight_data * (path_in[i].pos.a - newpath[i].pos.a); + newpath[i].pos.a += weight_smooth * (newpath[i - 1].pos.a + newpath[i + 1].pos.a - (2.0 * newpath[i].pos.a)); + change += fabs(xtemp - newpath[i].pos.a); + + } + nIterations++; + } + path_in = newpath; } void PlanningHelpers::SmoothGlobalPathSpeed(vector& path) { - CalcAngleAndCostAndCurvatureAnd2D(path); - SmoothSpeedProfiles(path, 0.45,0.25, 0.01); + CalcAngleAndCostAndCurvatureAnd2D(path); + SmoothSpeedProfiles(path, 0.45,0.25, 0.01); } void PlanningHelpers::GenerateRecommendedSpeed(vector& path, const double& max_speed, const double& speedProfileFactor) { - CalcAngleAndCostAndCurvatureAnd2D(path); - SmoothCurvatureProfiles(path, 0.4, 0.3, 0.01); - double v = 0; - - for(unsigned int i = 0 ; i < path.size(); i++) - { - double k_ratio = path.at(i).cost*10.0; - double local_max = (path.at(i).v >= 0 && max_speed > path.at(i).v) ? path.at(i).v : max_speed; - - if(k_ratio >= 9.5) - v = local_max; - else if(k_ratio <= 8.5) - v = 1.0*speedProfileFactor; - else - { - k_ratio = k_ratio - 8.5; - v = (local_max - 1.0) * k_ratio + 1.0; - v = v*speedProfileFactor; - } - - if(v > local_max) - path.at(i).v = local_max; - else - path.at(i).v = v; - - } - - SmoothSpeedProfiles(path, 0.4,0.3, 0.01); + CalcAngleAndCostAndCurvatureAnd2D(path); + SmoothCurvatureProfiles(path, 0.4, 0.3, 0.01); + double v = 0; + + for(unsigned int i = 0 ; i < path.size(); i++) + { + double k_ratio = path.at(i).cost*10.0; + double local_max = (path.at(i).v >= 0 && max_speed > path.at(i).v) ? path.at(i).v : max_speed; + + if(k_ratio >= 9.5) + v = local_max; + else if(k_ratio <= 8.5) + v = 1.0*speedProfileFactor; + else + { + k_ratio = k_ratio - 8.5; + v = (local_max - 1.0) * k_ratio + 1.0; + v = v*speedProfileFactor; + } + + if(v > local_max) + path.at(i).v = local_max; + else + path.at(i).v = v; + + } + + SmoothSpeedProfiles(path, 0.4,0.3, 0.01); } WayPoint* PlanningHelpers::BuildPlanningSearchTreeV2(WayPoint* pStart, - const WayPoint& goalPos, - const vector& globalPath, - const double& DistanceLimit, - const bool& bEnableLaneChange, - vector& all_cells_to_delete) -{ - if(!pStart) return NULL; - - vector >nextLeafToTrace; - - WayPoint* pZero = 0; - WayPoint* wp = new WayPoint(); - *wp = *pStart; - nextLeafToTrace.push_back(make_pair(pZero, wp)); - all_cells_to_delete.push_back(wp); - - double distance = 0; - double before_change_distance = 0; - WayPoint* pGoalCell = 0; - double nCounter = 0; - - - while(nextLeafToTrace.size()>0) - { - nCounter++; - - unsigned int min_cost_index = 0; - double min_cost = DBL_MAX; - - for(unsigned int i=0; i < nextLeafToTrace.size(); i++) - { - if(nextLeafToTrace.at(i).second->cost < min_cost) - { - min_cost = nextLeafToTrace.at(i).second->cost; - min_cost_index = i; - } - } - - WayPoint* pH = nextLeafToTrace.at(min_cost_index).second; - - assert(pH != 0); - - nextLeafToTrace.erase(nextLeafToTrace.begin()+min_cost_index); - - double distance_to_goal = distance2points(pH->pos, goalPos.pos); - double angle_to_goal = UtilityH::AngleBetweenTwoAnglesPositive(UtilityH::FixNegativeAngle(pH->pos.a), UtilityH::FixNegativeAngle(goalPos.pos.a)); - if( distance_to_goal <= 0.1 && angle_to_goal < M_PI_4) - { - cout << "Goal Found, LaneID: " << pH->laneId <<", Distance : " << distance_to_goal << ", Angle: " << angle_to_goal*RAD2DEG << endl; - pGoalCell = pH; - break; - } - else - { - - if(pH->pLeft && !CheckLaneExits(all_cells_to_delete, pH->pLeft->pLane) && !CheckNodeExits(all_cells_to_delete, pH->pLeft) && bEnableLaneChange && before_change_distance > LANE_CHANGE_MIN_DISTANCE) - { - wp = new WayPoint(); - *wp = *pH->pLeft; - double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); - distance += d; - before_change_distance = -LANE_CHANGE_MIN_DISTANCE*3; - - for(unsigned int a = 0; a < wp->actionCost.size(); a++) - { - //if(wp->actionCost.at(a).first == LEFT_TURN_ACTION) - d += wp->actionCost.at(a).second; - } - - wp->cost = pH->cost + d; - wp->pRight = pH; - wp->pLeft = 0; - - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - - if(pH->pRight && !CheckLaneExits(all_cells_to_delete, pH->pRight->pLane) && !CheckNodeExits(all_cells_to_delete, pH->pRight) && bEnableLaneChange && before_change_distance > LANE_CHANGE_MIN_DISTANCE) - { - wp = new WayPoint(); - *wp = *pH->pRight; - double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); - distance += d; - before_change_distance = -LANE_CHANGE_MIN_DISTANCE*3; - - for(unsigned int a = 0; a < wp->actionCost.size(); a++) - { - //if(wp->actionCost.at(a).first == RIGHT_TURN_ACTION) - d += wp->actionCost.at(a).second; - } - - wp->cost = pH->cost + d ; - wp->pLeft = pH; - wp->pRight = 0; - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - - for(unsigned int i =0; i< pH->pFronts.size(); i++) - { - if(CheckLaneIdExits(globalPath, pH->pLane) && pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) - { - wp = new WayPoint(); - *wp = *pH->pFronts.at(i); - - double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); - distance += d; - before_change_distance += d; - - for(unsigned int a = 0; a < wp->actionCost.size(); a++) - { - //if(wp->actionCost.at(a).first == FORWARD_ACTION) - d += wp->actionCost.at(a).second; - } - - wp->cost = pH->cost + d; - wp->pBacks.push_back(pH); - - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - } - } - - if(distance > DistanceLimit && globalPath.size()==0) - { - //if(!pGoalCell) - cout << "Goal Not Found, LaneID: " << pH->laneId <<", Distance : " << distance << endl; - pGoalCell = pH; - break; - } - - //pGoalCell = pH; - } - - while(nextLeafToTrace.size()!=0) - nextLeafToTrace.pop_back(); - //closed_nodes.clear(); - - return pGoalCell; + const WayPoint& goalPos, + const vector& globalPath, + const double& DistanceLimit, + const bool& bEnableLaneChange, + vector& all_cells_to_delete, + double fallback_min_goal_distance_th) +{ + if(!pStart) return nullptr; + + vector >nextLeafToTrace; + + WayPoint* pZero = 0; + WayPoint* wp = new WayPoint(); + *wp = *pStart; + nextLeafToTrace.push_back(make_pair(pZero, wp)); + all_cells_to_delete.push_back(wp); + + double distance = 0; + double before_change_distance = 0; + WayPoint* pGoalCell = 0; + double nCounter = 0; + WayPoint* pH = nullptr; + WayPoint* pMinGoalDistanceNode = nullptr; + double min_goal_distance_to_waypoint = std::numeric_limits::max(); + + while(nextLeafToTrace.size()>0) + { + nCounter++; + + unsigned int min_cost_index = 0; + double min_cost = DBL_MAX; + + for(unsigned int i=0; i < nextLeafToTrace.size(); i++) + { + if(nextLeafToTrace.at(i).second->cost < min_cost) + { + min_cost = nextLeafToTrace.at(i).second->cost; + min_cost_index = i; + } + } + + pH = nextLeafToTrace.at(min_cost_index).second; + + assert(pH != 0); + + nextLeafToTrace.erase(nextLeafToTrace.begin()+min_cost_index); + + double distance_to_goal = distance2points(pH->pos, goalPos.pos); + double angle_to_goal = UtilityH::AngleBetweenTwoAnglesPositive(UtilityH::FixNegativeAngle(pH->pos.a), UtilityH::FixNegativeAngle(goalPos.pos.a)); + if( distance_to_goal <= 0.1 && angle_to_goal < M_PI_4) + { + cout << "Goal Found, LaneID: " << pH->laneId <<", Distance : " << distance_to_goal << ", Angle: " << angle_to_goal*RAD2DEG << endl; + pGoalCell = pH; + break; + } + else + { + // Keep track of minimum distance for any waypoint to the target + // destination and the corresponding pH (waypoint pointer) + if(distance_to_goal < min_goal_distance_to_waypoint) { + min_goal_distance_to_waypoint = distance_to_goal; + pMinGoalDistanceNode = pH; + } + + if(pH->pLeft && !CheckLaneExits(all_cells_to_delete, pH->pLeft->pLane) && !CheckNodeExits(all_cells_to_delete, pH->pLeft) && bEnableLaneChange && before_change_distance > LANE_CHANGE_MIN_DISTANCE) + { + wp = new WayPoint(); + *wp = *pH->pLeft; + double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); + distance += d; + before_change_distance = -LANE_CHANGE_MIN_DISTANCE*3; + + for(unsigned int a = 0; a < wp->actionCost.size(); a++) + { + //if(wp->actionCost.at(a).first == LEFT_TURN_ACTION) + d += wp->actionCost.at(a).second; + } + + wp->cost = pH->cost + d; + wp->pRight = pH; + wp->pLeft = 0; + + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + + if(pH->pRight && !CheckLaneExits(all_cells_to_delete, pH->pRight->pLane) && !CheckNodeExits(all_cells_to_delete, pH->pRight) && bEnableLaneChange && before_change_distance > LANE_CHANGE_MIN_DISTANCE) + { + wp = new WayPoint(); + *wp = *pH->pRight; + double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); + distance += d; + before_change_distance = -LANE_CHANGE_MIN_DISTANCE*3; + + for(unsigned int a = 0; a < wp->actionCost.size(); a++) + { + //if(wp->actionCost.at(a).first == RIGHT_TURN_ACTION) + d += wp->actionCost.at(a).second; + } + + wp->cost = pH->cost + d ; + wp->pLeft = pH; + wp->pRight = 0; + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + + for(unsigned int i =0; i< pH->pFronts.size(); i++) + { + if(CheckLaneIdExits(globalPath, pH->pLane) && pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) + { + wp = new WayPoint(); + *wp = *pH->pFronts.at(i); + + double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); + distance += d; + before_change_distance += d; + + for(unsigned int a = 0; a < wp->actionCost.size(); a++) + { + //if(wp->actionCost.at(a).first == FORWARD_ACTION) + d += wp->actionCost.at(a).second; + } + + wp->cost = pH->cost + d; + wp->pBacks.push_back(pH); + + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + } + } + + if(distance > DistanceLimit && globalPath.size()==0) + { + //if(!pGoalCell) + cout << "Goal Not Found, LaneID: " << pH->laneId <<", Distance : " << distance << endl; + pGoalCell = pH; + break; + } + + //pGoalCell = pH; + } + + while(nextLeafToTrace.size()!=0) + nextLeafToTrace.pop_back(); + //closed_nodes.clear(); + + if(pGoalCell) { + cout << endl << "PlanningHelpers::BuildPlanningSearchTreeV2 pGoalCell=(" + << pGoalCell->pos.x << "," << pGoalCell->pos.y << ")" << endl; + } else { + // If we reach this point, it means that we couldn't find a waypoint to + // reach the destination. But let's try to find a waypoint close enough + // and use that as the nearest destination. + if(min_goal_distance_to_waypoint < fallback_min_goal_distance_th) { + // If we found a node close enough, lets find the index of that in + // all_cells_to_delete and then we would remove any nodes added in the + // list afterwards as that would be the final/destination waypoint + int min_node_index = FindNodeIndex(all_cells_to_delete, + pMinGoalDistanceNode); + cout << endl + << "PlanningHelpers::BuildPlanningSearchTreeV2 min_node_index:" + << min_node_index << " min_goal_distance_to_waypoint:" + << min_goal_distance_to_waypoint << endl; + if(min_node_index >= 0) { + pGoalCell = pMinGoalDistanceNode; + cout << endl + << "PlanningHelpers::BuildPlanningSearchTreeV2 pGoalCell is NULL, but " + << "pH=(" << pGoalCell->pos.x << "," << pGoalCell->pos.y << ")" << endl; + all_cells_to_delete.erase( + all_cells_to_delete.begin()+min_node_index, + all_cells_to_delete.end() + ); + } + } else { + cout << endl << "PlanningHelpers::BuildPlanningSearchTreeV2 Unable to " + <<"find pGoalCell, minimum goal distance waypoint beyond threshold: " + << min_goal_distance_to_waypoint << endl; + } + } + + return pGoalCell; } WayPoint* PlanningHelpers::BuildPlanningSearchTreeStraight(WayPoint* pStart, - const double& DistanceLimit, - vector& all_cells_to_delete) -{ - if(!pStart) return NULL; - - vector >nextLeafToTrace; - - WayPoint* pZero = 0; - WayPoint* wp = new WayPoint(); - *wp = *pStart; - wp->cost = 0; - nextLeafToTrace.push_back(make_pair(pZero, wp)); - all_cells_to_delete.push_back(wp); - - double distance = 0; - WayPoint* pGoalCell = 0; - double nCounter = 0; - - while(nextLeafToTrace.size()>0) - { - nCounter++; - - unsigned int min_cost_index = 0; - double min_cost = DBL_MAX; - - for(unsigned int i=0; i < nextLeafToTrace.size(); i++) - { - if(nextLeafToTrace.at(i).second->cost < min_cost) - { - min_cost = nextLeafToTrace.at(i).second->cost; - min_cost_index = i; - } - } - - WayPoint* pH = nextLeafToTrace.at(min_cost_index).second; - assert(pH != 0); - - nextLeafToTrace.erase(nextLeafToTrace.begin()+min_cost_index); - - for(unsigned int i =0; i< pH->pFronts.size(); i++) - { - if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) - { - wp = new WayPoint(); - *wp = *pH->pFronts.at(i); - - double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); - distance += d; - -// for(unsigned int a = 0; a < wp->actionCost.size(); a++) -// { -// //if(wp->actionCost.at(a).first == FORWARD_ACTION) -// d += wp->actionCost.at(a).second; -// } - - wp->cost = pH->cost + d; - wp->pBacks.push_back(pH); - if(wp->cost < DistanceLimit) - { - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - else - delete wp; - } - } - -// if(pH->pLeft && !CheckLaneExits(all_cells_to_delete, pH->pLeft->pLane)) -// { -// wp = new WayPoint(); -// *wp = *pH->pLeft; -// double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); + const double& DistanceLimit, + vector& all_cells_to_delete) +{ + if(!pStart) return nullptr; + + vector >nextLeafToTrace; + + WayPoint* pZero = 0; + WayPoint* wp = new WayPoint(); + *wp = *pStart; + wp->cost = 0; + nextLeafToTrace.push_back(make_pair(pZero, wp)); + all_cells_to_delete.push_back(wp); + + double distance = 0; + WayPoint* pGoalCell = 0; + double nCounter = 0; + + while(nextLeafToTrace.size()>0) + { + nCounter++; + + unsigned int min_cost_index = 0; + double min_cost = DBL_MAX; + + for(unsigned int i=0; i < nextLeafToTrace.size(); i++) + { + if(nextLeafToTrace.at(i).second->cost < min_cost) + { + min_cost = nextLeafToTrace.at(i).second->cost; + min_cost_index = i; + } + } + + WayPoint* pH = nextLeafToTrace.at(min_cost_index).second; + assert(pH != 0); + + nextLeafToTrace.erase(nextLeafToTrace.begin()+min_cost_index); + + for(unsigned int i =0; i< pH->pFronts.size(); i++) + { + if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) + { + wp = new WayPoint(); + *wp = *pH->pFronts.at(i); + + double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); + distance += d; + +// for(unsigned int a = 0; a < wp->actionCost.size(); a++) +// { +// //if(wp->actionCost.at(a).first == FORWARD_ACTION) +// d += wp->actionCost.at(a).second; +// } + + wp->cost = pH->cost + d; + wp->pBacks.push_back(pH); + if(wp->cost < DistanceLimit) + { + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + else + delete wp; + } + } + +// if(pH->pLeft && !CheckLaneExits(all_cells_to_delete, pH->pLeft->pLane)) +// { +// wp = new WayPoint(); +// *wp = *pH->pLeft; +// double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x); // -// for(unsigned int a = 0; a < wp->actionCost.size(); a++) -// { -// //if(wp->actionCost.at(a).first == LEFT_TURN_ACTION) -// d += wp->actionCost.at(a).second; -// } +// for(unsigned int a = 0; a < wp->actionCost.size(); a++) +// { +// //if(wp->actionCost.at(a).first == LEFT_TURN_ACTION) +// d += wp->actionCost.at(a).second; +// } // -// wp->cost = pH->cost + d + LANE_CHANGE_COST; -// wp->pRight = pH; -// wp->pRight = 0; +// wp->cost = pH->cost + d + LANE_CHANGE_COST; +// wp->pRight = pH; +// wp->pRight = 0; // -// nextLeafToTrace.push_back(make_pair(pH, wp)); -// all_cells_to_delete.push_back(wp); -// } +// nextLeafToTrace.push_back(make_pair(pH, wp)); +// all_cells_to_delete.push_back(wp); +// } // -// if(pH->pRight && !CheckLaneExits(all_cells_to_delete, pH->pRight->pLane)) -// { -// wp = new WayPoint(); -// *wp = *pH->pRight; -// double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x);; +// if(pH->pRight && !CheckLaneExits(all_cells_to_delete, pH->pRight->pLane)) +// { +// wp = new WayPoint(); +// *wp = *pH->pRight; +// double d = hypot(wp->pos.y - pH->pos.y, wp->pos.x - pH->pos.x);; // -// for(unsigned int a = 0; a < wp->actionCost.size(); a++) -// { -// //if(wp->actionCost.at(a).first == RIGHT_TURN_ACTION) -// d += wp->actionCost.at(a).second; -// } +// for(unsigned int a = 0; a < wp->actionCost.size(); a++) +// { +// //if(wp->actionCost.at(a).first == RIGHT_TURN_ACTION) +// d += wp->actionCost.at(a).second; +// } // -// wp->cost = pH->cost + d + LANE_CHANGE_COST; -// wp->pLeft = pH; -// wp->pRight = 0; -// nextLeafToTrace.push_back(make_pair(pH, wp)); -// all_cells_to_delete.push_back(wp); -// } +// wp->cost = pH->cost + d + LANE_CHANGE_COST; +// wp->pLeft = pH; +// wp->pRight = 0; +// nextLeafToTrace.push_back(make_pair(pH, wp)); +// all_cells_to_delete.push_back(wp); +// } - pGoalCell = pH; - } + pGoalCell = pH; + } - while(nextLeafToTrace.size()!=0) - nextLeafToTrace.pop_back(); + while(nextLeafToTrace.size()!=0) + nextLeafToTrace.pop_back(); - return pGoalCell; + return pGoalCell; } int PlanningHelpers::PredictiveIgnorIdsDP(WayPoint* pStart, const double& DistanceLimit, - vector& all_cells_to_delete,vector& end_waypoints, std::vector& lanes_ids) -{ - if(!pStart) return 0; - - vector >nextLeafToTrace; - - WayPoint* pZero = 0; - WayPoint* wp = new WayPoint(); - *wp = *pStart; - wp->cost = 0; - wp->pLeft = 0; - wp->pRight = 0; - nextLeafToTrace.push_back(make_pair(pZero, wp)); - all_cells_to_delete.push_back(wp); - - double distance = 0; - end_waypoints.clear(); - double nCounter = 0; - - while(nextLeafToTrace.size()>0) - { - nCounter++; - - WayPoint* pH = nextLeafToTrace.at(0).second; - - assert(pH != 0); - - nextLeafToTrace.erase(nextLeafToTrace.begin()+0); - - for(unsigned int i =0; i< pH->pFronts.size(); i++) - { - if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) - { - if(pH->cost < DistanceLimit) - { - wp = new WayPoint(); - *wp = *pH->pFronts.at(i); - - double d = distance2points(wp->pos, pH->pos); - distance += d; - wp->cost = pH->cost + d; - wp->pBacks.push_back(pH); - wp->pLeft = 0; - wp->pRight = 0; - - bool bFoundLane = false; - for(unsigned int k = 0 ; k < lanes_ids.size(); k++) - { - if(wp->laneId == lanes_ids.at(k)) - { - bFoundLane = true; - break; - } - } - - if(!bFoundLane) - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - else - { - end_waypoints.push_back(pH); - } - } - } - } - - while(nextLeafToTrace.size()!=0) - nextLeafToTrace.pop_back(); - //closed_nodes.clear(); - - return end_waypoints.size(); + vector& all_cells_to_delete,vector& end_waypoints, std::vector& lanes_ids) +{ + if(!pStart) return 0; + + vector >nextLeafToTrace; + + WayPoint* pZero = 0; + WayPoint* wp = new WayPoint(); + *wp = *pStart; + wp->cost = 0; + wp->pLeft = 0; + wp->pRight = 0; + nextLeafToTrace.push_back(make_pair(pZero, wp)); + all_cells_to_delete.push_back(wp); + + double distance = 0; + end_waypoints.clear(); + double nCounter = 0; + + while(nextLeafToTrace.size()>0) + { + nCounter++; + + WayPoint* pH = nextLeafToTrace.at(0).second; + + assert(pH != 0); + + nextLeafToTrace.erase(nextLeafToTrace.begin()+0); + + for(unsigned int i =0; i< pH->pFronts.size(); i++) + { + if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) + { + if(pH->cost < DistanceLimit) + { + wp = new WayPoint(); + *wp = *pH->pFronts.at(i); + + double d = distance2points(wp->pos, pH->pos); + distance += d; + wp->cost = pH->cost + d; + wp->pBacks.push_back(pH); + wp->pLeft = 0; + wp->pRight = 0; + + bool bFoundLane = false; + for(unsigned int k = 0 ; k < lanes_ids.size(); k++) + { + if(wp->laneId == lanes_ids.at(k)) + { + bFoundLane = true; + break; + } + } + + if(!bFoundLane) + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + else + { + end_waypoints.push_back(pH); + } + } + } + } + + while(nextLeafToTrace.size()!=0) + nextLeafToTrace.pop_back(); + //closed_nodes.clear(); + + return end_waypoints.size(); } int PlanningHelpers::PredictiveDP(WayPoint* pStart, const double& DistanceLimit, - vector& all_cells_to_delete,vector& end_waypoints) -{ - if(!pStart) return 0; - - vector >nextLeafToTrace; - - WayPoint* pZero = 0; - WayPoint* wp = new WayPoint(); - *wp = *pStart; - wp->pLeft = 0; - wp->pRight = 0; - nextLeafToTrace.push_back(make_pair(pZero, wp)); - all_cells_to_delete.push_back(wp); - - double distance = 0; - end_waypoints.clear(); - double nCounter = 0; - - while(nextLeafToTrace.size()>0) - { - nCounter++; - - WayPoint* pH = nextLeafToTrace.at(0).second; - - assert(pH != 0); - - nextLeafToTrace.erase(nextLeafToTrace.begin()+0); - - for(unsigned int i =0; i< pH->pFronts.size(); i++) - { - if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) - { - if(pH->cost < DistanceLimit) - { - wp = new WayPoint(); - *wp = *pH->pFronts.at(i); - - double d = distance2points(wp->pos, pH->pos); - distance += d; - wp->cost = pH->cost + d; - wp->pBacks.push_back(pH); - wp->pLeft = 0; - wp->pRight = 0; - - nextLeafToTrace.push_back(make_pair(pH, wp)); - all_cells_to_delete.push_back(wp); - } - else - { - end_waypoints.push_back(pH); - } - } - } - } - - while(nextLeafToTrace.size()!=0) - nextLeafToTrace.pop_back(); - //closed_nodes.clear(); - - return end_waypoints.size(); + vector& all_cells_to_delete,vector& end_waypoints) +{ + if(!pStart) return 0; + + vector >nextLeafToTrace; + + WayPoint* pZero = 0; + WayPoint* wp = new WayPoint(); + *wp = *pStart; + wp->pLeft = 0; + wp->pRight = 0; + nextLeafToTrace.push_back(make_pair(pZero, wp)); + all_cells_to_delete.push_back(wp); + + double distance = 0; + end_waypoints.clear(); + double nCounter = 0; + + while(nextLeafToTrace.size()>0) + { + nCounter++; + + WayPoint* pH = nextLeafToTrace.at(0).second; + + assert(pH != 0); + + nextLeafToTrace.erase(nextLeafToTrace.begin()+0); + + for(unsigned int i =0; i< pH->pFronts.size(); i++) + { + if(pH->pFronts.at(i) && !CheckNodeExits(all_cells_to_delete, pH->pFronts.at(i))) + { + if(pH->cost < DistanceLimit) + { + wp = new WayPoint(); + *wp = *pH->pFronts.at(i); + + double d = distance2points(wp->pos, pH->pos); + distance += d; + wp->cost = pH->cost + d; + wp->pBacks.push_back(pH); + wp->pLeft = 0; + wp->pRight = 0; + + nextLeafToTrace.push_back(make_pair(pH, wp)); + all_cells_to_delete.push_back(wp); + } + else + { + end_waypoints.push_back(pH); + } + } + } + } + + while(nextLeafToTrace.size()!=0) + nextLeafToTrace.pop_back(); + //closed_nodes.clear(); + + return end_waypoints.size(); } bool PlanningHelpers::CheckLaneIdExits(const std::vector& lanes, const Lane* pL) { - if(lanes.size()==0) return true; + if(lanes.size()==0) return true; - for(unsigned int i=0; i< lanes.size(); i++) - { - if(lanes.at(i) == pL->id) - return true; - } + for(unsigned int i=0; i< lanes.size(); i++) + { + if(lanes.at(i) == pL->id) + return true; + } - return false; + return false; } WayPoint* PlanningHelpers::CheckLaneExits(const vector& nodes, const Lane* pL) { - if(nodes.size()==0) return nullptr; + if(nodes.size()==0) return nullptr; - for(unsigned int i=0; i< nodes.size(); i++) - { - if(nodes.at(i)->pLane == pL) - return nodes.at(i); - } + for(unsigned int i=0; i< nodes.size(); i++) + { + if(nodes.at(i)->pLane == pL) + return nodes.at(i); + } - return nullptr; + return nullptr; } WayPoint* PlanningHelpers::CheckNodeExits(const vector& nodes, const WayPoint* pL) { - if(nodes.size()==0) return nullptr; + if(nodes.size()==0) return nullptr; - for(unsigned int i=0; i< nodes.size(); i++) - { - if(nodes.at(i)->laneId == pL->laneId && nodes.at(i)->id == pL->id) - return nodes.at(i); - } + for(unsigned int i=0; i< nodes.size(); i++) + { + if(nodes.at(i)->laneId == pL->laneId && nodes.at(i)->id == pL->id) + return nodes.at(i); + } - return nullptr; + return nullptr; +} + +//Given the vector nodes, returns the index of p in it +int PlanningHelpers::FindNodeIndex(const vector& nodes, const WayPoint* p) +{ + if(nodes.size()==0) return -1; + + for(unsigned int i=0; i< nodes.size(); i++) + { + if(nodes.at(i)->laneId == p->laneId && nodes.at(i)->id == p->id) + return i; + } + + return -1; } WayPoint* PlanningHelpers::CreateLaneHeadCell(Lane* pLane, WayPoint* pLeft, WayPoint* pRight, - WayPoint* pBack) -{ - if(!pLane) return nullptr; - if(pLane->points.size()==0) return nullptr; - - WayPoint* c = new WayPoint; - c->pLane = pLane; - c->pos = pLane->points.at(0).pos; - c->v = pLane->speed; - c->laneId = pLane->id; - c->pLeft = pLeft; - if(pLeft) - c->cost = pLeft->cost; - - c->pRight = pRight; - if(pRight) - c->cost = pRight->cost; - - if(pBack) - { - pBack->pFronts.push_back(c); - c->pBacks.push_back(pBack); - c->cost = pBack->cost + distance2points(c->pos, pBack->pos); - - for(unsigned int i=0; i< c->pBacks.size(); i++) - { - if(c->pBacks.at(i)->cost < c->cost) - c->cost = c->pBacks.at(i)->cost; - } - } - return c; + WayPoint* pBack) +{ + if(!pLane) return nullptr; + if(pLane->points.size()==0) return nullptr; + + WayPoint* c = new WayPoint; + c->pLane = pLane; + c->pos = pLane->points.at(0).pos; + c->v = pLane->speed; + c->laneId = pLane->id; + c->pLeft = pLeft; + if(pLeft) + c->cost = pLeft->cost; + + c->pRight = pRight; + if(pRight) + c->cost = pRight->cost; + + if(pBack) + { + pBack->pFronts.push_back(c); + c->pBacks.push_back(pBack); + c->cost = pBack->cost + distance2points(c->pos, pBack->pos); + + for(unsigned int i=0; i< c->pBacks.size(); i++) + { + if(c->pBacks.at(i)->cost < c->cost) + c->cost = c->pBacks.at(i)->cost; + } + } + return c; } double PlanningHelpers::GetLanePoints(Lane* l, const WayPoint& prevWayPointIndex, - const double& minDistance , const double& prevCost, vector& points) + const double& minDistance , const double& prevCost, vector& points) { - if(l == NULL || minDistance<=0) return 0; + if(l == nullptr || minDistance<=0) return 0; - int index = 0; - WayPoint p1, p2; - WayPoint idx; + int index = 0; + WayPoint p1, p2; + WayPoint idx; - p2 = p1 = l->points.at(index); - p1.pLane = l; - p1.cost = prevCost; - p2.cost = p1.cost + distance2points(p1.pos, p2.pos); + p2 = p1 = l->points.at(index); + p1.pLane = l; + p1.cost = prevCost; + p2.cost = p1.cost + distance2points(p1.pos, p2.pos); - points.push_back(p1); + points.push_back(p1); - for(unsigned int i=index+1; ipoints.size(); i++) - { + for(unsigned int i=index+1; ipoints.size(); i++) + { - p2 = l->points.at(i); - p2.pLane = l; - p2.cost = p1.cost + distance2points(p1.pos, p2.pos); - points.push_back(p2); + p2 = l->points.at(i); + p2.pLane = l; + p2.cost = p1.cost + distance2points(p1.pos, p2.pos); + points.push_back(p2); - if(p2.cost >= minDistance) - break; - p1 = p2; - } - return p2.cost; + if(p2.cost >= minDistance) + break; + p1 = p2; + } + return p2.cost; } WayPoint* PlanningHelpers::GetMinCostCell(const vector& cells, const vector& globalPathIds) { - if(cells.size() == 1) - { -// for(unsigned int j = 0; j < cells.at(0)->actionCost.size(); j++) -// cout << "Cost (" << cells.at(0)->laneId << ") of going : " << cells.at(0)->actionCost.at(j).first << ", is : " << cells.at(0)->actionCost.at(j).second << endl; - return cells.at(0); - } - - WayPoint* pC = cells.at(0); //cost is distance - for(unsigned int i=1; i < cells.size(); i++) - { - bool bFound = false; - if(globalPathIds.size()==0) - bFound = true; - - int iLaneID = cells.at(i)->id; - for(unsigned int j=0; j < globalPathIds.size(); j++) - { - if(globalPathIds.at(j) == iLaneID) - { - bFound = true; - break; - } - } - -// for(unsigned int j = 0; j < cells.at(0)->actionCost.size(); j++) -// cout << "Cost ("<< i <<") of going : " << cells.at(0)->actionCost.at(j).first << ", is : " << cells.at(0)->actionCost.at(j).second << endl; - - - if(cells.at(i)->cost < pC->cost && bFound == true) - pC = cells.at(i); - } - - - return pC; + if(cells.size() == 1) + { +// for(unsigned int j = 0; j < cells.at(0)->actionCost.size(); j++) +// cout << "Cost (" << cells.at(0)->laneId << ") of going : " << cells.at(0)->actionCost.at(j).first << ", is : " << cells.at(0)->actionCost.at(j).second << endl; + return cells.at(0); + } + + WayPoint* pC = cells.at(0); //cost is distance + for(unsigned int i=1; i < cells.size(); i++) + { + bool bFound = false; + if(globalPathIds.size()==0) + bFound = true; + + int iLaneID = cells.at(i)->id; + for(unsigned int j=0; j < globalPathIds.size(); j++) + { + if(globalPathIds.at(j) == iLaneID) + { + bFound = true; + break; + } + } + +// for(unsigned int j = 0; j < cells.at(0)->actionCost.size(); j++) +// cout << "Cost ("<< i <<") of going : " << cells.at(0)->actionCost.at(j).first << ", is : " << cells.at(0)->actionCost.at(j).second << endl; + + + if(cells.at(i)->cost < pC->cost && bFound == true) + pC = cells.at(i); + } + + + return pC; } void PlanningHelpers::ExtractPlanAlernatives(const std::vector& singlePath, std::vector >& allPaths) { - if(singlePath.size() == 0) - return; - - allPaths.clear(); - std::vector path; - path.push_back(singlePath.at(0)); - double skip_distance = 8; - double d = 0; - bool bStartSkip = false; - for(unsigned int i= 1; i < singlePath.size(); i++) - { - if(singlePath.at(i).bDir != FORWARD_DIR && singlePath.at(i).pLane && singlePath.at(i).pFronts.size() > 0) - { - - bStartSkip = true; - WayPoint start_point = singlePath.at(i-1); - - cout << "Current Velocity = " << start_point.v << endl; - - RelativeInfo start_info; - PlanningHelpers::GetRelativeInfo(start_point.pLane->points, start_point, start_info); - vector local_cell_to_delete; - PlannerHNS::WayPoint* pStart = &start_point.pLane->points.at(start_info.iFront); - WayPoint* pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, local_cell_to_delete); - if(pLaneCell) - { - vector straight_path; - vector > tempCurrentForwardPathss; - vector globalPathIds; - PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPathIds, straight_path, tempCurrentForwardPathss); - if(straight_path.size() > 2) - { - straight_path.insert(straight_path.begin(), path.begin(), path.end()); - for(unsigned int ic = 0; ic < straight_path.size(); ic++) - straight_path.at(ic).laneChangeCost = 1; - allPaths.push_back(straight_path); - } - } - } - - if(bStartSkip) - { - d += hypot(singlePath.at(i).pos.y - singlePath.at(i-1).pos.y, singlePath.at(i).pos.x - singlePath.at(i-1).pos.x); - if(d > skip_distance) - { - d = 0; - bStartSkip = false; - } - } - - if(!bStartSkip) - path.push_back(singlePath.at(i)); - } - - allPaths.push_back(path); + if(singlePath.size() == 0) + return; + + allPaths.clear(); + std::vector path; + path.push_back(singlePath.at(0)); + double skip_distance = 8; + double d = 0; + bool bStartSkip = false; + for(unsigned int i= 1; i < singlePath.size(); i++) + { + if(singlePath.at(i).bDir != FORWARD_DIR && singlePath.at(i).pLane && singlePath.at(i).pFronts.size() > 0) + { + + bStartSkip = true; + WayPoint start_point = singlePath.at(i-1); + + cout << "Current Velocity = " << start_point.v << endl; + + RelativeInfo start_info; + PlanningHelpers::GetRelativeInfo(start_point.pLane->points, start_point, start_info); + vector local_cell_to_delete; + PlannerHNS::WayPoint* pStart = &start_point.pLane->points.at(start_info.iFront); + WayPoint* pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, local_cell_to_delete); + if(pLaneCell) + { + vector straight_path; + vector > tempCurrentForwardPathss; + vector globalPathIds; + PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPathIds, straight_path, tempCurrentForwardPathss); + if(straight_path.size() > 2) + { + straight_path.insert(straight_path.begin(), path.begin(), path.end()); + for(unsigned int ic = 0; ic < straight_path.size(); ic++) + straight_path.at(ic).laneChangeCost = 1; + allPaths.push_back(straight_path); + } + } + } + + if(bStartSkip) + { + d += hypot(singlePath.at(i).pos.y - singlePath.at(i-1).pos.y, singlePath.at(i).pos.x - singlePath.at(i-1).pos.x); + if(d > skip_distance) + { + d = 0; + bStartSkip = false; + } + } + + if(!bStartSkip) + path.push_back(singlePath.at(i)); + } + + allPaths.push_back(path); } void PlanningHelpers::TraversePathTreeBackwards(WayPoint* pHead, WayPoint* pStartWP,const vector& globalPathIds, - vector& localPath, std::vector >& localPaths) -{ - if(pHead != NULL && pHead->id != pStartWP->id) - { - if(pHead->pBacks.size()>0) - { - localPaths.push_back(localPath); - TraversePathTreeBackwards(GetMinCostCell(pHead->pBacks, globalPathIds),pStartWP, globalPathIds, localPath, localPaths); - pHead->bDir = FORWARD_DIR; - localPath.push_back(*pHead); - } - else if(pHead->pLeft && pHead->cost > 0) - { - //vector forward_path; - //TravesePathTreeForwards(pHead->pLeft, forward_path, FORWARD_RIGHT); - //localPaths.push_back(forward_path); - cout << "Global Lane Change Right " << endl; - TraversePathTreeBackwards(pHead->pLeft,pStartWP, globalPathIds, localPath, localPaths); - pHead->bDir = FORWARD_RIGHT_DIR; - localPath.push_back(*pHead); - } - else if(pHead->pRight && pHead->cost > 0) - { - //vector forward_path; - //TravesePathTreeForwards(pHead->pRight, forward_path, FORWARD_LEFT); - //localPaths.push_back(forward_path); - - cout << "Global Lane Change Left " << endl; - TraversePathTreeBackwards(pHead->pRight,pStartWP, globalPathIds, localPath, localPaths); - pHead->bDir = FORWARD_LEFT_DIR; - localPath.push_back(*pHead); - } -// else -// cout << "Err: PlannerZ -> NULL Back Pointer " << pHead; - } - else - assert(pHead); + vector& localPath, std::vector >& localPaths) +{ + if(pHead != nullptr && pHead->id != pStartWP->id) + { + if(pHead->pBacks.size()>0) + { + localPaths.push_back(localPath); + TraversePathTreeBackwards(GetMinCostCell(pHead->pBacks, globalPathIds),pStartWP, globalPathIds, localPath, localPaths); + pHead->bDir = FORWARD_DIR; + localPath.push_back(*pHead); + } + else if(pHead->pLeft && pHead->cost > 0) + { + //vector forward_path; + //TravesePathTreeForwards(pHead->pLeft, forward_path, FORWARD_RIGHT); + //localPaths.push_back(forward_path); + cout << "Global Lane Change Right " << endl; + TraversePathTreeBackwards(pHead->pLeft,pStartWP, globalPathIds, localPath, localPaths); + pHead->bDir = FORWARD_RIGHT_DIR; + localPath.push_back(*pHead); + } + else if(pHead->pRight && pHead->cost > 0) + { + //vector forward_path; + //TravesePathTreeForwards(pHead->pRight, forward_path, FORWARD_LEFT); + //localPaths.push_back(forward_path); + + cout << "Global Lane Change Left " << endl; + TraversePathTreeBackwards(pHead->pRight,pStartWP, globalPathIds, localPath, localPaths); + pHead->bDir = FORWARD_LEFT_DIR; + localPath.push_back(*pHead); + } +// else +// cout << "Err: PlannerZ -> NULL Back Pointer " << pHead; + } + else + assert(pHead); } ACTION_TYPE PlanningHelpers::GetBranchingDirection(WayPoint& currWP, WayPoint& nextWP) { - ACTION_TYPE t = FORWARD_ACTION; + ACTION_TYPE t = FORWARD_ACTION; -// //first Get the average of the next 3 waypoint directions -// double angle = 0; -// if(nextWP.pLane->id == 487) -// angle = 11; +// //first Get the average of the next 3 waypoint directions +// double angle = 0; +// if(nextWP.pLane->id == 487) +// angle = 11; // -// int counter = 0; -// angle = 0; +// int counter = 0; +// angle = 0; // -// for(unsigned int i=0; i < nextWP.pLane->points.size() && counter < 10; i++, counter++) -// { -// angle += nextWP.pLane->points.at(i).pos.a; -// } -// angle = angle / counter; +// for(unsigned int i=0; i < nextWP.pLane->points.size() && counter < 10; i++, counter++) +// { +// angle += nextWP.pLane->points.at(i).pos.a; +// } +// angle = angle / counter; // -// //Get Circular angle for correct subtraction -// double circle_angle = UtilityH::GetCircularAngle(currWP.pos.a, angle); +// //Get Circular angle for correct subtraction +// double circle_angle = UtilityH::GetCircularAngle(currWP.pos.a, angle); // -// if( currWP.pos.a - circle_angle > (7.5*DEG2RAD)) -// { -// t = RIGHT_TURN_ACTION; -// cout << "Right Lane, Average Angle = " << angle*RAD2DEG << ", Circle Angle = " << circle_angle*RAD2DEG << ", currAngle = " << currWP.pos.a*RAD2DEG << endl; -// } -// else if( currWP.pos.a - circle_angle < (-7.5*DEG2RAD)) -// { -// t = LEFT_TURN_ACTION; -// cout << "Left Lane, Average Angle = " << angle*RAD2DEG << ", Circle Angle = " << circle_angle*RAD2DEG << ", currAngle = " << currWP.pos.a*RAD2DEG << endl; -// } - - return t; +// if( currWP.pos.a - circle_angle > (7.5*DEG2RAD)) +// { +// t = RIGHT_TURN_ACTION; +// cout << "Right Lane, Average Angle = " << angle*RAD2DEG << ", Circle Angle = " << circle_angle*RAD2DEG << ", currAngle = " << currWP.pos.a*RAD2DEG << endl; +// } +// else if( currWP.pos.a - circle_angle < (-7.5*DEG2RAD)) +// { +// t = LEFT_TURN_ACTION; +// cout << "Left Lane, Average Angle = " << angle*RAD2DEG << ", Circle Angle = " << circle_angle*RAD2DEG << ", currAngle = " << currWP.pos.a*RAD2DEG << endl; +// } + + return t; } void PlanningHelpers::CalcContourPointsForDetectedObjects(const WayPoint& currPose, vector& obj_list, const double& filterDistance) { - vector res_list; - for(unsigned int i = 0; i < obj_list.size(); i++) - { - GPSPoint center = obj_list.at(i).center.pos; - double distance = distance2points(center, currPose.pos); - - if(distance < filterDistance) - { - DetectedObject obj = obj_list.at(i); - - Mat3 rotationMat(center.a); - Mat3 translationMat(center.x, center.y); - double w2 = obj.w/2.0; - double h2 = obj.l/2.0; - double z = center.z + obj.h/2.0; - - GPSPoint left_bottom(-w2, -h2, z,0); - GPSPoint right_bottom(w2,-h2, z,0); - GPSPoint right_top(w2,h2, z,0); - GPSPoint left_top(-w2,h2, z,0); - - left_bottom = rotationMat * left_bottom; - right_bottom = rotationMat * right_bottom; - right_top = rotationMat * right_top; - left_top = rotationMat * left_top; - - left_bottom = translationMat * left_bottom; - right_bottom = translationMat * right_bottom; - right_top = translationMat * right_top; - left_top = translationMat * left_top; - - obj.contour.clear(); - obj.contour.push_back(left_bottom); - obj.contour.push_back(right_bottom); - obj.contour.push_back(right_top); - obj.contour.push_back(left_top); - - res_list.push_back(obj); - } - } - - obj_list = res_list; + vector res_list; + for(unsigned int i = 0; i < obj_list.size(); i++) + { + GPSPoint center = obj_list.at(i).center.pos; + double distance = distance2points(center, currPose.pos); + + if(distance < filterDistance) + { + DetectedObject obj = obj_list.at(i); + + Mat3 rotationMat(center.a); + Mat3 translationMat(center.x, center.y); + double w2 = obj.w/2.0; + double h2 = obj.l/2.0; + double z = center.z + obj.h/2.0; + + GPSPoint left_bottom(-w2, -h2, z,0); + GPSPoint right_bottom(w2,-h2, z,0); + GPSPoint right_top(w2,h2, z,0); + GPSPoint left_top(-w2,h2, z,0); + + left_bottom = rotationMat * left_bottom; + right_bottom = rotationMat * right_bottom; + right_top = rotationMat * right_top; + left_top = rotationMat * left_top; + + left_bottom = translationMat * left_bottom; + right_bottom = translationMat * right_bottom; + right_top = translationMat * right_top; + left_top = translationMat * left_top; + + obj.contour.clear(); + obj.contour.push_back(left_bottom); + obj.contour.push_back(right_bottom); + obj.contour.push_back(right_top); + obj.contour.push_back(left_top); + + res_list.push_back(obj); + } + } + + obj_list = res_list; } double PlanningHelpers::GetVelocityAhead(const std::vector& path, const RelativeInfo& info, int& prev_index, const double& reasonable_brake_distance) { - if(path.size()==0) return 0; + if(path.size()==0) return 0; - double min_v = path.at(info.iBack).v; - double d = info.to_front_distance; + double min_v = path.at(info.iBack).v; + double d = info.to_front_distance; - int local_i = info.iFront; - while(local_i < path.size()-1 && d < reasonable_brake_distance) - { - local_i++; - d += hypot(path.at(local_i).pos.y - path.at(local_i-1).pos.y, path.at(local_i).pos.x - path.at(local_i-1).pos.x); - if(path.at(local_i).v < min_v) - min_v = path.at(local_i).v; - } + int local_i = info.iFront; + while(local_i < path.size()-1 && d < reasonable_brake_distance) + { + local_i++; + d += hypot(path.at(local_i).pos.y - path.at(local_i-1).pos.y, path.at(local_i).pos.x - path.at(local_i-1).pos.x); + if(path.at(local_i).v < min_v) + min_v = path.at(local_i).v; + } - if(local_i < prev_index && prev_index < path.size()) - { - min_v = path.at(prev_index).v; - } - else - prev_index = local_i; + if(local_i < prev_index && prev_index < path.size()) + { + min_v = path.at(prev_index).v; + } + else + prev_index = local_i; - return min_v; + return min_v; } void PlanningHelpers::WritePathToFile(const string& fileName, const vector& path) { - DataRW dataFile; - ostringstream str_header; - str_header << "laneID" << "," << "wpID" << "," "x" << "," << "y" << "," << "a"<<","<< "cost" << "," << "Speed" << "," ; - vector dataList; - for(unsigned int i=0; i dataList; + for(unsigned int i=0; i& path, const WayPoint& pose, const double& seachDistance) { - if(path.size() < 2) - return INDICATOR_NONE; - - LIGHT_INDICATOR ind = INDICATOR_NONE; - RelativeInfo info; - PlanningHelpers::GetRelativeInfo(path, pose, info); - - if(info.perp_point.actionCost.size() > 0) - { - if(info.perp_point.actionCost.at(0).first == LEFT_TURN_ACTION) - ind = INDICATOR_LEFT; - else if(info.perp_point.actionCost.at(0).first == RIGHT_TURN_ACTION) - ind = INDICATOR_RIGHT; - } - - double total_d = 0; - for(unsigned int i=info.iFront; i < path.size()-2; i++) - { - - total_d+= hypot(path.at(i+1).pos.y - path.at(i).pos.y, path.at(i+1).pos.x - path.at(i).pos.x); - if(path.at(i).actionCost.size() > 0) - { - if(path.at(i).actionCost.at(0).first == LEFT_TURN_ACTION) - return INDICATOR_LEFT; - else if(path.at(i).actionCost.at(0).first == RIGHT_TURN_ACTION) - return INDICATOR_RIGHT; - } - - if(total_d > seachDistance) - break; - } - - return ind; + if(path.size() < 2) + return INDICATOR_NONE; + + LIGHT_INDICATOR ind = INDICATOR_NONE; + RelativeInfo info; + PlanningHelpers::GetRelativeInfo(path, pose, info); + + if(info.perp_point.actionCost.size() > 0) + { + if(info.perp_point.actionCost.at(0).first == LEFT_TURN_ACTION) + ind = INDICATOR_LEFT; + else if(info.perp_point.actionCost.at(0).first == RIGHT_TURN_ACTION) + ind = INDICATOR_RIGHT; + } + + double total_d = 0; + for(unsigned int i=info.iFront; i < path.size()-2; i++) + { + + total_d+= hypot(path.at(i+1).pos.y - path.at(i).pos.y, path.at(i+1).pos.x - path.at(i).pos.x); + if(path.at(i).actionCost.size() > 0) + { + if(path.at(i).actionCost.at(0).first == LEFT_TURN_ACTION) + return INDICATOR_LEFT; + else if(path.at(i).actionCost.at(0).first == RIGHT_TURN_ACTION) + return INDICATOR_RIGHT; + } + + if(total_d > seachDistance) + break; + } + + return ind; } PlannerHNS::WayPoint PlanningHelpers::GetRealCenter(const PlannerHNS::WayPoint& currState, const double& wheel_base) { - PlannerHNS::WayPoint pose_center = currState; - PlannerHNS::Mat3 rotationMat(-currState.pos.a); - PlannerHNS::Mat3 translationMat(-currState.pos.x, -currState.pos.y); + PlannerHNS::WayPoint pose_center = currState; + PlannerHNS::Mat3 rotationMat(-currState.pos.a); + PlannerHNS::Mat3 translationMat(-currState.pos.x, -currState.pos.y); - PlannerHNS::Mat3 rotationMatInv(currState.pos.a); - PlannerHNS::Mat3 translationMatInv(currState.pos.x, currState.pos.y); + PlannerHNS::Mat3 rotationMatInv(currState.pos.a); + PlannerHNS::Mat3 translationMatInv(currState.pos.x, currState.pos.y); - pose_center.pos = translationMat*pose_center.pos; - pose_center.pos = rotationMat*pose_center.pos; + pose_center.pos = translationMat*pose_center.pos; + pose_center.pos = rotationMat*pose_center.pos; - pose_center.pos.x += wheel_base/3.0; + pose_center.pos.x += wheel_base/3.0; - pose_center.pos = rotationMatInv*pose_center.pos; - pose_center.pos = translationMatInv*pose_center.pos; + pose_center.pos = rotationMatInv*pose_center.pos; + pose_center.pos = translationMatInv*pose_center.pos; - return pose_center; + return pose_center; } double PlanningHelpers::frunge ( double x ) diff --git a/common/op_planner/src/SimuDecisionMaker.cpp b/common/op_planner/src/SimuDecisionMaker.cpp index 063a2274430..52cb7577d31 100644 --- a/common/op_planner/src/SimuDecisionMaker.cpp +++ b/common/op_planner/src/SimuDecisionMaker.cpp @@ -16,13 +16,13 @@ namespace PlannerHNS SimuDecisionMaker::SimuDecisionMaker() { - m_CurrentVelocity = m_CurrentVelocityD =0; - m_CurrentSteering = m_CurrentSteeringD =0; - m_CurrentShift = m_CurrentShiftD = PlannerHNS::SHIFT_POS_NN; - m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; + m_CurrentVelocity = m_CurrentVelocityD =0; + m_CurrentSteering = m_CurrentSteeringD =0; + m_CurrentShift = m_CurrentShiftD = PlannerHNS::SHIFT_POS_NN; + m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; - m_SimulationSteeringDelayFactor = 0.1; - UtilityHNS::UtilityH::GetTickCount(m_SteerDelayTimer); + m_SimulationSteeringDelayFactor = 0.1; + UtilityHNS::UtilityH::GetTickCount(m_SteerDelayTimer); } SimuDecisionMaker::~SimuDecisionMaker() @@ -31,220 +31,220 @@ SimuDecisionMaker::~SimuDecisionMaker() void SimuDecisionMaker::ReInitializePlanner(const WayPoint& start_pose) { - m_pidVelocity.Init(0.01, 0.004, 0.01); - m_pidVelocity.Setlimit(m_params.maxSpeed, 0); - - m_pidStopping.Init(0.05, 0.05, 0.1); - m_pidStopping.Setlimit(m_params.horizonDistance, 0); - - m_pidFollowing.Init(0.05, 0.05, 0.01); - m_pidFollowing.Setlimit(m_params.minFollowingDistance, 0); - - m_iCurrentTotalPathId = 0; - m_CurrentVelocity = m_CurrentVelocityD =0; - m_CurrentSteering = m_CurrentSteeringD =0; - m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; - m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; - - m_pCurrentBehaviorState = m_pFollowState; - m_TotalPath.clear(); - m_TotalOriginalPath.clear(); - m_Path.clear(); - m_RollOuts.clear(); - m_pCurrentBehaviorState->m_Behavior = PlannerHNS::FORWARD_STATE; - FirstLocalizeMe(start_pose); - LocalizeMe(0); + m_pidVelocity.Init(0.01, 0.004, 0.01); + m_pidVelocity.Setlimit(m_params.maxSpeed, 0); + + m_pidStopping.Init(0.05, 0.05, 0.1); + m_pidStopping.Setlimit(m_params.horizonDistance, 0); + + m_pidFollowing.Init(0.05, 0.05, 0.01); + m_pidFollowing.Setlimit(m_params.minFollowingDistance, 0); + + m_iCurrentTotalPathId = 0; + m_CurrentVelocity = m_CurrentVelocityD =0; + m_CurrentSteering = m_CurrentSteeringD =0; + m_CurrentShift = m_CurrentShiftD = SHIFT_POS_NN; + m_CurrentAccSteerAngle = m_CurrentAccVelocity = 0; + + m_pCurrentBehaviorState = m_pFollowState; + m_TotalPath.clear(); + m_TotalOriginalPath.clear(); + m_Path.clear(); + m_RollOuts.clear(); + m_pCurrentBehaviorState->m_Behavior = PlannerHNS::FORWARD_STATE; + FirstLocalizeMe(start_pose); + LocalizeMe(0); } void SimuDecisionMaker::SetSimulatedTargetOdometryReadings(const double& velocity_d, const double& steering_d, const SHIFT_POS& shift_d) { - m_CurrentVelocityD = velocity_d; - m_CurrentSteeringD = steering_d; - m_CurrentShiftD = shift_d; + m_CurrentVelocityD = velocity_d; + m_CurrentSteeringD = steering_d; + m_CurrentShiftD = shift_d; } void SimuDecisionMaker::FirstLocalizeMe(const WayPoint& initCarPos) { - pLane = initCarPos.pLane; - state = initCarPos; - m_OdometryState.pos.a = initCarPos.pos.a; - m_OdometryState.pos.x = initCarPos.pos.x + (m_CarInfo.wheel_base/2.0 * cos(initCarPos.pos.a)); - m_OdometryState.pos.y = initCarPos.pos.y + (m_CarInfo.wheel_base/2.0 * sin(initCarPos.pos.a)); + pLane = initCarPos.pLane; + state = initCarPos; + m_OdometryState.pos.a = initCarPos.pos.a; + m_OdometryState.pos.x = initCarPos.pos.x + (m_CarInfo.wheel_base/2.0 * cos(initCarPos.pos.a)); + m_OdometryState.pos.y = initCarPos.pos.y + (m_CarInfo.wheel_base/2.0 * sin(initCarPos.pos.a)); } void SimuDecisionMaker::LocalizeMe(const double& dt) { - //calculate the new x, y , - WayPoint currPose = state; - - if(m_CurrentShift == SHIFT_POS_DD) - { - m_OdometryState.pos.x += m_CurrentVelocity * dt * cos(currPose.pos.a); - m_OdometryState.pos.y += m_CurrentVelocity * dt * sin(currPose.pos.a); - m_OdometryState.pos.a += m_CurrentVelocity * dt * tan(m_CurrentSteering) / m_CarInfo.wheel_base; - - } - else if(m_CurrentShift == SHIFT_POS_RR ) - { - m_OdometryState.pos.x += -m_CurrentVelocity * dt * cos(currPose.pos.a); - m_OdometryState.pos.y += -m_CurrentVelocity * dt * sin(currPose.pos.a); - m_OdometryState.pos.a += -m_CurrentVelocity * dt * tan(m_CurrentSteering); - } - - m_OdometryState.pos.a = atan2(sin(m_OdometryState.pos.a), cos(m_OdometryState.pos.a)); - m_OdometryState.pos.a = UtilityHNS::UtilityH::FixNegativeAngle(m_OdometryState.pos.a); - - state.pos.a = m_OdometryState.pos.a; - state.pos.x = m_OdometryState.pos.x - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base) * cos (m_OdometryState.pos.a)); - state.pos.y = m_OdometryState.pos.y - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base/2.0) * sin (m_OdometryState.pos.a)); + //calculate the new x, y , + WayPoint currPose = state; + + if(m_CurrentShift == SHIFT_POS_DD) + { + m_OdometryState.pos.x += m_CurrentVelocity * dt * cos(currPose.pos.a); + m_OdometryState.pos.y += m_CurrentVelocity * dt * sin(currPose.pos.a); + m_OdometryState.pos.a += m_CurrentVelocity * dt * tan(m_CurrentSteering) / m_CarInfo.wheel_base; + + } + else if(m_CurrentShift == SHIFT_POS_RR ) + { + m_OdometryState.pos.x += -m_CurrentVelocity * dt * cos(currPose.pos.a); + m_OdometryState.pos.y += -m_CurrentVelocity * dt * sin(currPose.pos.a); + m_OdometryState.pos.a += -m_CurrentVelocity * dt * tan(m_CurrentSteering); + } + + m_OdometryState.pos.a = atan2(sin(m_OdometryState.pos.a), cos(m_OdometryState.pos.a)); + m_OdometryState.pos.a = UtilityHNS::UtilityH::FixNegativeAngle(m_OdometryState.pos.a); + + state.pos.a = m_OdometryState.pos.a; + state.pos.x = m_OdometryState.pos.x - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base) * cos (m_OdometryState.pos.a)); + state.pos.y = m_OdometryState.pos.y - (m_CurrentVelocity*dt* (m_CarInfo.wheel_base/2.0) * sin (m_OdometryState.pos.a)); } void SimuDecisionMaker::UpdateState(const PlannerHNS::VehicleState& state, const bool& bUseDelay) { - if(!bUseDelay) - { - m_CurrentSteering = m_CurrentSteeringD; - } - else - { - double currSteerDeg = RAD2DEG * m_CurrentSteering; - double desiredSteerDeg = RAD2DEG * m_CurrentSteeringD; - - double mFact = UtilityHNS::UtilityH::GetMomentumScaleFactor(state.speed); - double diff = desiredSteerDeg - currSteerDeg; - double diffSign = UtilityHNS::UtilityH::GetSign(diff); - double inc = 1.0*diffSign; - if(fabs(diff) < 1.0 ) - inc = diff; - - if(UtilityHNS::UtilityH::GetTimeDiffNow(m_SteerDelayTimer) > m_SimulationSteeringDelayFactor*mFact) - { - UtilityHNS::UtilityH::GetTickCount(m_SteerDelayTimer); - currSteerDeg += inc; - } - - m_CurrentSteering = DEG2RAD * currSteerDeg; - } - - m_CurrentShift = m_CurrentShiftD; - m_CurrentVelocity = m_CurrentVelocityD; + if(!bUseDelay) + { + m_CurrentSteering = m_CurrentSteeringD; + } + else + { + double currSteerDeg = RAD2DEG * m_CurrentSteering; + double desiredSteerDeg = RAD2DEG * m_CurrentSteeringD; + + double mFact = UtilityHNS::UtilityH::GetMomentumScaleFactor(state.speed); + double diff = desiredSteerDeg - currSteerDeg; + double diffSign = UtilityHNS::UtilityH::GetSign(diff); + double inc = 1.0*diffSign; + if(fabs(diff) < 1.0 ) + inc = diff; + + if(UtilityHNS::UtilityH::GetTimeDiffNow(m_SteerDelayTimer) > m_SimulationSteeringDelayFactor*mFact) + { + UtilityHNS::UtilityH::GetTickCount(m_SteerDelayTimer); + currSteerDeg += inc; + } + + m_CurrentSteering = DEG2RAD * currSteerDeg; + } + + m_CurrentShift = m_CurrentShiftD; + m_CurrentVelocity = m_CurrentVelocityD; } void SimuDecisionMaker::GenerateLocalRollOuts() { - std::vector sampledPoints_debug; - std::vector > > _roll_outs; - PlannerHNS::PlannerH _planner; - _planner.GenerateRunoffTrajectory(m_TotalPath, state, - m_params.enableLaneChange, - state.v, - m_params.microPlanDistance, - m_params.maxSpeed, - m_params.minSpeed, - m_params.carTipMargin, - m_params.rollInMargin, - m_params.rollInSpeedFactor, - m_params.pathDensity, - m_params.rollOutDensity, - m_params.rollOutNumber, - m_params.smoothingDataWeight, - m_params.smoothingSmoothWeight, - m_params.smoothingToleranceError, - m_params.speedProfileFactor, - m_params.enableHeadingSmoothing, - -1 , -1, - _roll_outs, sampledPoints_debug); - - if(_roll_outs.size()>0) - m_RollOuts.clear(); - for(unsigned int i=0; i < _roll_outs.size(); i++) - { - for(unsigned int j=0; j < _roll_outs.at(i).size(); j++) - { - PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(_roll_outs.at(i).at(j), state, m_params.minSpeed, m_params.microPlanDistance); - m_RollOuts.push_back(_roll_outs.at(i).at(j)); - } - } + std::vector sampledPoints_debug; + std::vector > > _roll_outs; + PlannerHNS::PlannerH _planner; + _planner.GenerateRunoffTrajectory(m_TotalPath, state, + m_params.enableLaneChange, + state.v, + m_params.microPlanDistance, + m_params.maxSpeed, + m_params.minSpeed, + m_params.carTipMargin, + m_params.rollInMargin, + m_params.rollInSpeedFactor, + m_params.pathDensity, + m_params.rollOutDensity, + m_params.rollOutNumber, + m_params.smoothingDataWeight, + m_params.smoothingSmoothWeight, + m_params.smoothingToleranceError, + m_params.speedProfileFactor, + m_params.enableHeadingSmoothing, + -1 , -1, + _roll_outs, sampledPoints_debug); + + if(_roll_outs.size()>0) + m_RollOuts.clear(); + for(unsigned int i=0; i < _roll_outs.size(); i++) + { + for(unsigned int j=0; j < _roll_outs.at(i).size(); j++) + { + PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(_roll_outs.at(i).at(j), state, m_params.minSpeed, m_params.microPlanDistance); + m_RollOuts.push_back(_roll_outs.at(i).at(j)); + } + } } bool SimuDecisionMaker::SelectSafeTrajectory() { - bool bNewTrajectory = false; - PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); - - if(!preCalcPrams || m_TotalPath.size()==0) return bNewTrajectory; - - int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); - int index_limit = 0; - if(index_limit<=0) - index_limit = m_Path.size()/2.0; - if(currIndex > index_limit - || preCalcPrams->bRePlan - || preCalcPrams->bNewGlobalPath) - { - GenerateLocalRollOuts(); - if(m_RollOuts.size() <= preCalcPrams->iCurrSafeTrajectory) - return false; - - std::cout << "New Local Plan !! " << currIndex << ", "<< preCalcPrams->bRePlan << ", " << preCalcPrams->bNewGlobalPath << ", " << m_TotalOriginalPath.at(0).size() << ", PrevLocal: " << m_Path.size(); - std::cout << ", NewLocal: " << m_Path.size() << std::endl; - - m_Path = m_RollOuts.at(preCalcPrams->iCurrSafeTrajectory); - preCalcPrams->bNewGlobalPath = false; - preCalcPrams->bRePlan = false; - bNewTrajectory = true; - } - - return bNewTrajectory; + bool bNewTrajectory = false; + PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams(); + + if(!preCalcPrams || m_TotalPath.size()==0) return bNewTrajectory; + + int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state); + int index_limit = 0; + if(index_limit<=0) + index_limit = m_Path.size()/2.0; + if(currIndex > index_limit + || preCalcPrams->bRePlan + || preCalcPrams->bNewGlobalPath) + { + GenerateLocalRollOuts(); + if(m_RollOuts.size() <= preCalcPrams->iCurrSafeTrajectory) + return false; + + std::cout << "New Local Plan !! " << currIndex << ", "<< preCalcPrams->bRePlan << ", " << preCalcPrams->bNewGlobalPath << ", " << m_TotalOriginalPath.at(0).size() << ", PrevLocal: " << m_Path.size(); + std::cout << ", NewLocal: " << m_Path.size() << std::endl; + + m_Path = m_RollOuts.at(preCalcPrams->iCurrSafeTrajectory); + preCalcPrams->bNewGlobalPath = false; + preCalcPrams->bRePlan = false; + bNewTrajectory = true; + } + + return bNewTrajectory; } PlannerHNS::VehicleState SimuDecisionMaker::LocalizeStep(const double& dt, const PlannerHNS::VehicleState& desiredStatus) { - SetSimulatedTargetOdometryReadings(desiredStatus.speed, desiredStatus.steer, desiredStatus.shift); - UpdateState(desiredStatus, false); - LocalizeMe(dt); - PlannerHNS::VehicleState currStatus; - currStatus.shift = desiredStatus.shift; - currStatus.steer = m_CurrentSteering; - currStatus.speed = m_CurrentVelocity; - return currStatus; + SetSimulatedTargetOdometryReadings(desiredStatus.speed, desiredStatus.steer, desiredStatus.shift); + UpdateState(desiredStatus, false); + LocalizeMe(dt); + PlannerHNS::VehicleState currStatus; + currStatus.shift = desiredStatus.shift; + currStatus.steer = m_CurrentSteering; + currStatus.speed = m_CurrentVelocity; + return currStatus; } PlannerHNS::BehaviorState SimuDecisionMaker::DoOneStep(const double& dt, - const PlannerHNS::VehicleState& vehicleState, - const int& goalID, - const std::vector& trafficLight, - const std::vector& objects, - const bool& bEmergencyStop) + const PlannerHNS::VehicleState& vehicleState, + const int& goalID, + const std::vector& trafficLight, + const std::vector& objects, + const bool& bEmergencyStop) { - PlannerHNS::BehaviorState beh; - state.v = vehicleState.speed; - m_TotalPath.clear(); - for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) - { - t_centerTrajectorySmoothed.clear(); - PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_TotalOriginalPath.at(i), state, m_params.horizonDistance , m_params.pathDensity , t_centerTrajectorySmoothed); - m_TotalPath.push_back(t_centerTrajectorySmoothed); - } + PlannerHNS::BehaviorState beh; + state.v = vehicleState.speed; + m_TotalPath.clear(); + for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++) + { + t_centerTrajectorySmoothed.clear(); + PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_TotalOriginalPath.at(i), state, m_params.horizonDistance , m_params.pathDensity , t_centerTrajectorySmoothed); + m_TotalPath.push_back(t_centerTrajectorySmoothed); + } - if(m_TotalPath.size()==0) return beh; + if(m_TotalPath.size()==0) return beh; - UpdateCurrentLane(m_MaxLaneSearchDistance); + UpdateCurrentLane(m_MaxLaneSearchDistance); - PlannerHNS::TrajectoryCost tc = m_TrajectoryCostsCalculator.DoOneStepStatic(m_RollOuts, m_TotalPath.at(m_iCurrentTotalPathId), state, m_params, m_CarInfo, vehicleState, objects); + PlannerHNS::TrajectoryCost tc = m_TrajectoryCostsCalculator.DoOneStepStatic(m_RollOuts, m_TotalPath.at(m_iCurrentTotalPathId), state, m_params, m_CarInfo, vehicleState, objects); - //std::cout << "Detected Objects Distance: " << tc.closest_obj_distance << ", N RollOuts: " << m_RollOuts.size() << std::endl; + //std::cout << "Detected Objects Distance: " << tc.closest_obj_distance << ", N RollOuts: " << m_RollOuts.size() << std::endl; - CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); + CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc); - beh = GenerateBehaviorState(vehicleState); + beh = GenerateBehaviorState(vehicleState); - beh.bNewPlan = SelectSafeTrajectory(); + beh.bNewPlan = SelectSafeTrajectory(); - beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); + beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt); - //std::cout << "Eval_i: " << tc.index << ", Curr_i: " << m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << ", Prev_i: " << m_pCurrentBehaviorState->GetCalcParams()->iPrevSafeTrajectory << std::endl; + //std::cout << "Eval_i: " << tc.index << ", Curr_i: " << m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << ", Prev_i: " << m_pCurrentBehaviorState->GetCalcParams()->iPrevSafeTrajectory << std::endl; - return beh; + return beh; } } diff --git a/common/op_planner/src/TrajectoryCosts.cpp b/common/op_planner/src/TrajectoryCosts.cpp index f57473470e5..d4a1ca2d156 100755 --- a/common/op_planner/src/TrajectoryCosts.cpp +++ b/common/op_planner/src/TrajectoryCosts.cpp @@ -12,13 +12,13 @@ namespace PlannerHNS TrajectoryCosts::TrajectoryCosts() { - m_PrevCostIndex = -1; - m_WeightPriority = 0.125; - m_WeightTransition = 0.13; - m_WeightLong = 1.0; - m_WeightLat = 1.0; - m_WeightLaneChange = 1.0; - m_LateralSkipDistance = 10; + m_PrevCostIndex = -1; + m_WeightPriority = 0.125; + m_WeightTransition = 0.13; + m_WeightLong = 1.0; + m_WeightLat = 1.0; + m_WeightLaneChange = 1.0; + m_LateralSkipDistance = 10; } TrajectoryCosts::~TrajectoryCosts() @@ -26,346 +26,346 @@ TrajectoryCosts::~TrajectoryCosts() } TrajectoryCost TrajectoryCosts::DoOneStep(const vector > >& rollOuts, - const vector >& totalPaths, const WayPoint& currState, const int& currIndex, - const int& currLaneIndex, - const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list) + const vector >& totalPaths, const WayPoint& currState, const int& currIndex, + const int& currLaneIndex, + const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list) { - TrajectoryCost bestTrajectory; - bestTrajectory.bBlocked = true; - bestTrajectory.closest_obj_distance = params.horizonDistance; - bestTrajectory.closest_obj_velocity = 0; - bestTrajectory.index = -1; - - if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory; - - if(m_PrevCostIndex == -1) - m_PrevCostIndex = params.rollOutNumber/2; - - m_TrajectoryCosts.clear(); - - for(unsigned int il = 0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0) - { - vector costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params); - m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end()); - } - } - - CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); - - - WayPoint p; - m_AllContourPoints.clear(); - for(unsigned int io=0; io= 0) - { - bestTrajectory = m_TrajectoryCosts.at(smallestIndex); - //bestTrajectory.index = smallestIndex; - } - -// cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size() -// << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index -// << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance -// << ", Blocked: " << bestTrajectory.bBlocked -// << endl; - - m_PrevCostIndex = smallestIndex; - - return bestTrajectory; + TrajectoryCost bestTrajectory; + bestTrajectory.bBlocked = true; + bestTrajectory.closest_obj_distance = params.horizonDistance; + bestTrajectory.closest_obj_velocity = 0; + bestTrajectory.index = -1; + + if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory; + + if(m_PrevCostIndex == -1) + m_PrevCostIndex = params.rollOutNumber/2; + + m_TrajectoryCosts.clear(); + + for(unsigned int il = 0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0) + { + vector costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params); + m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end()); + } + } + + CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); + + + WayPoint p; + m_AllContourPoints.clear(); + for(unsigned int io=0; io= 0) + { + bestTrajectory = m_TrajectoryCosts.at(smallestIndex); + //bestTrajectory.index = smallestIndex; + } + +// cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size() +// << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index +// << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance +// << ", Blocked: " << bestTrajectory.bBlocked +// << endl; + + m_PrevCostIndex = smallestIndex; + + return bestTrajectory; } void TrajectoryCosts::CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, - const vector > >& rollOuts, const vector >& totalPaths, - const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, - const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) + const vector > >& rollOuts, const vector >& totalPaths, + const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, + const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) { - double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; - double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; - double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; - int iCostIndex = 0; - - PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); - PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); - - double corner_slide_distance = critical_lateral_distance/2.0; - double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; - double slide_distance = vehicleState.steer * ratio_to_angle; - - GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); - GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); - - GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - - GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); - GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); - - bottom_left = invRotationMat*bottom_left; - bottom_left = invTranslationMat*bottom_left; - - top_right = invRotationMat*top_right; - top_right = invTranslationMat*top_right; - - bottom_right = invRotationMat*bottom_right; - bottom_right = invTranslationMat*bottom_right; - - top_left = invRotationMat*top_left; - top_left = invTranslationMat*top_left; - - top_right_car = invRotationMat*top_right_car; - top_right_car = invTranslationMat*top_right_car; - - top_left_car = invRotationMat*top_left_car; - top_left_car = invTranslationMat*top_left_car; - - m_SafetyBorder.points.clear(); - m_SafetyBorder.points.push_back(bottom_left) ; - m_SafetyBorder.points.push_back(bottom_right) ; - m_SafetyBorder.points.push_back(top_right_car) ; - m_SafetyBorder.points.push_back(top_right) ; - m_SafetyBorder.points.push_back(top_left) ; - m_SafetyBorder.points.push_back(top_left_car) ; - - for(unsigned int il=0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0) - { - RelativeInfo car_info; - PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info); - - - for(unsigned int it=0; it< rollOuts.at(il).size(); it++) - { - int skip_id = -1; - for(unsigned int icon = 0; icon < contourPoints.size(); icon++) - { - if(skip_id == contourPoints.at(icon).id) - continue; - - RelativeInfo obj_info; - PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info); - double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info); - if(obj_info.iFront == 0 && longitudinalDist > 0) - longitudinalDist = -longitudinalDist; - - double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); - if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) - { - skip_id = contourPoints.at(icon).id; - continue; - } - - double close_in_percentage = 1; -// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; + double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; + double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; + double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; + int iCostIndex = 0; + + PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); + PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); + + double corner_slide_distance = critical_lateral_distance/2.0; + double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; + double slide_distance = vehicleState.steer * ratio_to_angle; + + GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); + GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); + + GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + + GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); + GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); + + bottom_left = invRotationMat*bottom_left; + bottom_left = invTranslationMat*bottom_left; + + top_right = invRotationMat*top_right; + top_right = invTranslationMat*top_right; + + bottom_right = invRotationMat*bottom_right; + bottom_right = invTranslationMat*bottom_right; + + top_left = invRotationMat*top_left; + top_left = invTranslationMat*top_left; + + top_right_car = invRotationMat*top_right_car; + top_right_car = invTranslationMat*top_right_car; + + top_left_car = invRotationMat*top_left_car; + top_left_car = invTranslationMat*top_left_car; + + m_SafetyBorder.points.clear(); + m_SafetyBorder.points.push_back(bottom_left) ; + m_SafetyBorder.points.push_back(bottom_right) ; + m_SafetyBorder.points.push_back(top_right_car) ; + m_SafetyBorder.points.push_back(top_right) ; + m_SafetyBorder.points.push_back(top_left) ; + m_SafetyBorder.points.push_back(top_left_car) ; + + for(unsigned int il=0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0) + { + RelativeInfo car_info; + PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info); + + + for(unsigned int it=0; it< rollOuts.at(il).size(); it++) + { + int skip_id = -1; + for(unsigned int icon = 0; icon < contourPoints.size(); icon++) + { + if(skip_id == contourPoints.at(icon).id) + continue; + + RelativeInfo obj_info; + PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info); + double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info); + if(obj_info.iFront == 0 && longitudinalDist > 0) + longitudinalDist = -longitudinalDist; + + double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); + if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) + { + skip_id = contourPoints.at(icon).id; + continue; + } + + double close_in_percentage = 1; +// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; // -// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; +// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; - double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; + double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; - if(close_in_percentage < 1) - distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); + if(close_in_percentage < 1) + distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); - double lateralDist = fabs(obj_info.perp_distance - distance_from_center); + double lateralDist = fabs(obj_info.perp_distance - distance_from_center); - if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) - { - continue; - } + if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) + { + continue; + } - longitudinalDist = longitudinalDist - critical_long_front_distance; + longitudinalDist = longitudinalDist - critical_long_front_distance; - if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist <= critical_lateral_distance - && longitudinalDist >= -carInfo.length/1.5 - && longitudinalDist < params.minFollowingDistance) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(lateralDist <= critical_lateral_distance + && longitudinalDist >= -carInfo.length/1.5 + && longitudinalDist < params.minFollowingDistance) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist != 0) - trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; + if(lateralDist != 0) + trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; - if(longitudinalDist != 0) - trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); + if(longitudinalDist != 0) + trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); - if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) - { - trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; - trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; - } - } + if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) + { + trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; + trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; + } + } - iCostIndex++; - } - } - } + iCostIndex++; + } + } + } } void TrajectoryCosts::NormalizeCosts(vector& trajectoryCosts) { - //Normalize costs - double totalPriorities = 0; - double totalChange = 0; - double totalLateralCosts = 0; - double totalLongitudinalCosts = 0; - double transitionCosts = 0; - - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - totalPriorities += trajectoryCosts.at(ic).priority_cost; - transitionCosts += trajectoryCosts.at(ic).transition_cost; - } - - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - totalChange += trajectoryCosts.at(ic).lane_change_cost; - totalLateralCosts += trajectoryCosts.at(ic).lateral_cost; - totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost; - } - -// cout << "------ Normalizing Step " << endl; - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - if(totalPriorities != 0) - trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities; - else - trajectoryCosts.at(ic).priority_cost = 0; - - if(transitionCosts != 0) - trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts; - else - trajectoryCosts.at(ic).transition_cost = 0; - - if(totalChange != 0) - trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange; - else - trajectoryCosts.at(ic).lane_change_cost = 0; - - if(totalLateralCosts != 0) - trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts; - else - trajectoryCosts.at(ic).lateral_cost = 0; - - if(totalLongitudinalCosts != 0) - trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts; - else - trajectoryCosts.at(ic).longitudinal_cost = 0; - - trajectoryCosts.at(ic).priority_cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost; - trajectoryCosts.at(ic).transition_cost = m_WeightTransition*trajectoryCosts.at(ic).transition_cost; - trajectoryCosts.at(ic).lane_change_cost = m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost; - trajectoryCosts.at(ic).lateral_cost = m_WeightLat*trajectoryCosts.at(ic).lateral_cost; - trajectoryCosts.at(ic).longitudinal_cost = m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost; - - - trajectoryCosts.at(ic).cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost/5.0 + - m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost/5.0 + - m_WeightLat*trajectoryCosts.at(ic).lateral_cost/5.0 + - m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost/5.0 + - m_WeightTransition*trajectoryCosts.at(ic).transition_cost/5.0; - -// cout << "Index: " << ic -// << ", Priority: " << trajectoryCosts.at(ic).priority_cost -// << ", Transition: " << trajectoryCosts.at(ic).transition_cost -// << ", Lat: " << trajectoryCosts.at(ic).lateral_cost -// << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost -// << ", Change: " << trajectoryCosts.at(ic).lane_change_cost -// << ", Avg: " << trajectoryCosts.at(ic).cost -// << endl; - } - -// cout << "------------------------ " << endl; + //Normalize costs + double totalPriorities = 0; + double totalChange = 0; + double totalLateralCosts = 0; + double totalLongitudinalCosts = 0; + double transitionCosts = 0; + + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + totalPriorities += trajectoryCosts.at(ic).priority_cost; + transitionCosts += trajectoryCosts.at(ic).transition_cost; + } + + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + totalChange += trajectoryCosts.at(ic).lane_change_cost; + totalLateralCosts += trajectoryCosts.at(ic).lateral_cost; + totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost; + } + +// cout << "------ Normalizing Step " << endl; + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + if(totalPriorities != 0) + trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities; + else + trajectoryCosts.at(ic).priority_cost = 0; + + if(transitionCosts != 0) + trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts; + else + trajectoryCosts.at(ic).transition_cost = 0; + + if(totalChange != 0) + trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange; + else + trajectoryCosts.at(ic).lane_change_cost = 0; + + if(totalLateralCosts != 0) + trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts; + else + trajectoryCosts.at(ic).lateral_cost = 0; + + if(totalLongitudinalCosts != 0) + trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts; + else + trajectoryCosts.at(ic).longitudinal_cost = 0; + + trajectoryCosts.at(ic).priority_cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost; + trajectoryCosts.at(ic).transition_cost = m_WeightTransition*trajectoryCosts.at(ic).transition_cost; + trajectoryCosts.at(ic).lane_change_cost = m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost; + trajectoryCosts.at(ic).lateral_cost = m_WeightLat*trajectoryCosts.at(ic).lateral_cost; + trajectoryCosts.at(ic).longitudinal_cost = m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost; + + + trajectoryCosts.at(ic).cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost/5.0 + + m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost/5.0 + + m_WeightLat*trajectoryCosts.at(ic).lateral_cost/5.0 + + m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost/5.0 + + m_WeightTransition*trajectoryCosts.at(ic).transition_cost/5.0; + +// cout << "Index: " << ic +// << ", Priority: " << trajectoryCosts.at(ic).priority_cost +// << ", Transition: " << trajectoryCosts.at(ic).transition_cost +// << ", Lat: " << trajectoryCosts.at(ic).lateral_cost +// << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost +// << ", Change: " << trajectoryCosts.at(ic).lane_change_cost +// << ", Avg: " << trajectoryCosts.at(ic).cost +// << endl; + } + +// cout << "------------------------ " << endl; } vector TrajectoryCosts::CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, - const int& lane_index, const PlanningParams& params) + const int& lane_index, const PlanningParams& params) { - vector costs; - TrajectoryCost tc; - int centralIndex = params.rollOutNumber/2; - - tc.lane_index = lane_index; - for(unsigned int it=0; it< laneRollOuts.size(); it++) - { - tc.index = it; - tc.relative_index = it - centralIndex; - tc.distance_from_center = params.rollOutDensity*tc.relative_index; - tc.priority_cost = fabs(tc.distance_from_center); - tc.closest_obj_distance = params.horizonDistance; - tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost; - -// if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR) -// tc.lane_change_cost = 1; -// else if(laneRollOuts.at(it).at(0).bDir == BACKWARD_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_RIGHT_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_LEFT_DIR) -// tc.lane_change_cost = 2; -// else -// tc.lane_change_cost = 0; - - costs.push_back(tc); - } - - return costs; + vector costs; + TrajectoryCost tc; + int centralIndex = params.rollOutNumber/2; + + tc.lane_index = lane_index; + for(unsigned int it=0; it< laneRollOuts.size(); it++) + { + tc.index = it; + tc.relative_index = it - centralIndex; + tc.distance_from_center = params.rollOutDensity*tc.relative_index; + tc.priority_cost = fabs(tc.distance_from_center); + tc.closest_obj_distance = params.horizonDistance; + tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost; + +// if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR) +// tc.lane_change_cost = 1; +// else if(laneRollOuts.at(it).at(0).bDir == BACKWARD_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_RIGHT_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_LEFT_DIR) +// tc.lane_change_cost = 2; +// else +// tc.lane_change_cost = 0; + + costs.push_back(tc); + } + + return costs; } void TrajectoryCosts::CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params) { - for(int ic = 0; ic< trajectoryCosts.size(); ic++) - { - trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex)); - } + for(int ic = 0; ic< trajectoryCosts.size(); ic++) + { + trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex)); + } } /** @@ -375,16 +375,16 @@ void TrajectoryCosts::CalculateTransitionCosts(vector& trajector */ bool TrajectoryCosts::ValidateRollOutsInput(const vector > >& rollOuts) { - if(rollOuts.size()==0) - return false; + if(rollOuts.size()==0) + return false; - for(unsigned int il = 0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size() == 0) - return false; - } + for(unsigned int il = 0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size() == 0) + return false; + } - return true; + return true; } } diff --git a/common/op_planner/src/TrajectoryDynamicCosts.cpp b/common/op_planner/src/TrajectoryDynamicCosts.cpp index 2ba0d509a9b..461e22d7bb4 100755 --- a/common/op_planner/src/TrajectoryDynamicCosts.cpp +++ b/common/op_planner/src/TrajectoryDynamicCosts.cpp @@ -14,19 +14,19 @@ namespace PlannerHNS TrajectoryDynamicCosts::TrajectoryDynamicCosts() { - m_PrevCostIndex = -1; - //m_WeightPriority = 0.125; - //m_WeightTransition = 0.13; - m_WeightLong = 1.0; - m_WeightLat = 1.2; - m_WeightLaneChange = 0.0; - m_LateralSkipDistance = 50; - - - m_CollisionTimeDiff = 6.0; //seconds - m_PrevIndex = -1; - m_WeightPriority = 0.9; - m_WeightTransition = 0.9; + m_PrevCostIndex = -1; + //m_WeightPriority = 0.125; + //m_WeightTransition = 0.13; + m_WeightLong = 1.0; + m_WeightLat = 1.2; + m_WeightLaneChange = 0.0; + m_LateralSkipDistance = 50; + + + m_CollisionTimeDiff = 6.0; //seconds + m_PrevIndex = -1; + m_WeightPriority = 0.9; + m_WeightTransition = 0.9; } TrajectoryDynamicCosts::~TrajectoryDynamicCosts() @@ -34,641 +34,641 @@ TrajectoryDynamicCosts::~TrajectoryDynamicCosts() } TrajectoryCost TrajectoryDynamicCosts::DoOneStepDynamic(const vector >& rollOuts, - const vector& totalPaths, const WayPoint& currState, - const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list, const int& iCurrentIndex) + const vector& totalPaths, const WayPoint& currState, + const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list, const int& iCurrentIndex) { - TrajectoryCost bestTrajectory; - bestTrajectory.bBlocked = true; - bestTrajectory.closest_obj_distance = params.horizonDistance; - bestTrajectory.closest_obj_velocity = 0; - bestTrajectory.index = -1; - - double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; - double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; - double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; - - int currIndex = -1; - if(iCurrentIndex >=0 && iCurrentIndex < rollOuts.size()) - currIndex = iCurrentIndex; - else - currIndex = GetCurrentRollOutIndex(totalPaths, currState, params); - - InitializeCosts(rollOuts, params); - - InitializeSafetyPolygon(currState, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance); - - CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); - - CalculateLateralAndLongitudinalCostsDynamic(obj_list, rollOuts, totalPaths, currState, params, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance); - - NormalizeCosts(m_TrajectoryCosts); - - int smallestIndex = -1; - double smallestCost = DBL_MAX; - double smallestDistance = DBL_MAX; - double velo_of_next = 0; - bool bAllFree = true; - - //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl; - for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++) - { - //cout << m_TrajectoryCosts.at(ic).ToString(); - if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost) - { - smallestCost = m_TrajectoryCosts.at(ic).cost; - smallestIndex = ic; - } - - if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance) - { - smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance; - velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity; - } - - if(m_TrajectoryCosts.at(ic).bBlocked) - bAllFree = false; - } - //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl; - - if(bAllFree && smallestIndex >=0) - smallestIndex = params.rollOutNumber/2; - - - if(smallestIndex == -1) - { - bestTrajectory.bBlocked = true; - bestTrajectory.lane_index = 0; - bestTrajectory.index = m_PrevCostIndex; - bestTrajectory.closest_obj_distance = smallestDistance; - bestTrajectory.closest_obj_velocity = velo_of_next; - } - else if(smallestIndex >= 0) - { - bestTrajectory = m_TrajectoryCosts.at(smallestIndex); - } - - m_PrevIndex = currIndex; - - //std::cout << "Current Selected Index : " << bestTrajectory.index << std::endl; - return bestTrajectory; + TrajectoryCost bestTrajectory; + bestTrajectory.bBlocked = true; + bestTrajectory.closest_obj_distance = params.horizonDistance; + bestTrajectory.closest_obj_velocity = 0; + bestTrajectory.index = -1; + + double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; + double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; + double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; + + int currIndex = -1; + if(iCurrentIndex >=0 && iCurrentIndex < rollOuts.size()) + currIndex = iCurrentIndex; + else + currIndex = GetCurrentRollOutIndex(totalPaths, currState, params); + + InitializeCosts(rollOuts, params); + + InitializeSafetyPolygon(currState, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance); + + CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); + + CalculateLateralAndLongitudinalCostsDynamic(obj_list, rollOuts, totalPaths, currState, params, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance); + + NormalizeCosts(m_TrajectoryCosts); + + int smallestIndex = -1; + double smallestCost = DBL_MAX; + double smallestDistance = DBL_MAX; + double velo_of_next = 0; + bool bAllFree = true; + + //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl; + for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++) + { + //cout << m_TrajectoryCosts.at(ic).ToString(); + if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost) + { + smallestCost = m_TrajectoryCosts.at(ic).cost; + smallestIndex = ic; + } + + if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance) + { + smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance; + velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity; + } + + if(m_TrajectoryCosts.at(ic).bBlocked) + bAllFree = false; + } + //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl; + + if(bAllFree && smallestIndex >=0) + smallestIndex = params.rollOutNumber/2; + + + if(smallestIndex == -1) + { + bestTrajectory.bBlocked = true; + bestTrajectory.lane_index = 0; + bestTrajectory.index = m_PrevCostIndex; + bestTrajectory.closest_obj_distance = smallestDistance; + bestTrajectory.closest_obj_velocity = velo_of_next; + } + else if(smallestIndex >= 0) + { + bestTrajectory = m_TrajectoryCosts.at(smallestIndex); + } + + m_PrevIndex = currIndex; + + //std::cout << "Current Selected Index : " << bestTrajectory.index << std::endl; + return bestTrajectory; } TrajectoryCost TrajectoryDynamicCosts::DoOneStepStatic(const vector >& rollOuts, - const vector& totalPaths, const WayPoint& currState, - const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list, const int& iCurrentIndex) + const vector& totalPaths, const WayPoint& currState, + const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list, const int& iCurrentIndex) { - TrajectoryCost bestTrajectory; - bestTrajectory.bBlocked = true; - bestTrajectory.closest_obj_distance = params.horizonDistance; - bestTrajectory.closest_obj_velocity = 0; - bestTrajectory.index = -1; - - RelativeInfo obj_info; - PlanningHelpers::GetRelativeInfo(totalPaths, currState, obj_info); - int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity); - //std::cout << "Current Index: " << currIndex << std::endl; - if(currIndex < 0) - currIndex = 0; - else if(currIndex > params.rollOutNumber) - currIndex = params.rollOutNumber; - - m_TrajectoryCosts.clear(); - if(rollOuts.size()>0) - { - TrajectoryCost tc; - int centralIndex = params.rollOutNumber/2; - tc.lane_index = 0; - for(unsigned int it=0; it< rollOuts.size(); it++) - { - tc.index = it; - tc.relative_index = it - centralIndex; - tc.distance_from_center = params.rollOutDensity*tc.relative_index; - tc.priority_cost = fabs(tc.distance_from_center); - tc.closest_obj_distance = params.horizonDistance; - if(rollOuts.at(it).size() > 0) - tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost; - m_TrajectoryCosts.push_back(tc); - } - } - - CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); - - WayPoint p; - m_AllContourPoints.clear(); - for(unsigned int io=0; io= 0) - { - bestTrajectory = m_TrajectoryCosts.at(smallestIndex); - } - - m_PrevIndex = currIndex; - return bestTrajectory; + TrajectoryCost bestTrajectory; + bestTrajectory.bBlocked = true; + bestTrajectory.closest_obj_distance = params.horizonDistance; + bestTrajectory.closest_obj_velocity = 0; + bestTrajectory.index = -1; + + RelativeInfo obj_info; + PlanningHelpers::GetRelativeInfo(totalPaths, currState, obj_info); + int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity); + //std::cout << "Current Index: " << currIndex << std::endl; + if(currIndex < 0) + currIndex = 0; + else if(currIndex > params.rollOutNumber) + currIndex = params.rollOutNumber; + + m_TrajectoryCosts.clear(); + if(rollOuts.size()>0) + { + TrajectoryCost tc; + int centralIndex = params.rollOutNumber/2; + tc.lane_index = 0; + for(unsigned int it=0; it< rollOuts.size(); it++) + { + tc.index = it; + tc.relative_index = it - centralIndex; + tc.distance_from_center = params.rollOutDensity*tc.relative_index; + tc.priority_cost = fabs(tc.distance_from_center); + tc.closest_obj_distance = params.horizonDistance; + if(rollOuts.at(it).size() > 0) + tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost; + m_TrajectoryCosts.push_back(tc); + } + } + + CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); + + WayPoint p; + m_AllContourPoints.clear(); + for(unsigned int io=0; io= 0) + { + bestTrajectory = m_TrajectoryCosts.at(smallestIndex); + } + + m_PrevIndex = currIndex; + return bestTrajectory; } TrajectoryCost TrajectoryDynamicCosts::DoOneStep(const vector > >& rollOuts, - const vector >& totalPaths, const WayPoint& currState, const int& currIndex, - const int& currLaneIndex, - const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, - const std::vector& obj_list) + const vector >& totalPaths, const WayPoint& currState, const int& currIndex, + const int& currLaneIndex, + const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, + const std::vector& obj_list) { - TrajectoryCost bestTrajectory; - bestTrajectory.bBlocked = true; - bestTrajectory.closest_obj_distance = params.horizonDistance; - bestTrajectory.closest_obj_velocity = 0; - bestTrajectory.index = -1; - - if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory; - - if(m_PrevCostIndex == -1) - m_PrevCostIndex = params.rollOutNumber/2; - - m_TrajectoryCosts.clear(); - - for(unsigned int il = 0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0) - { - vector costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params); - m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end()); - } - } - - CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); - - - WayPoint p; - m_AllContourPoints.clear(); - for(unsigned int io=0; io= 0) - { - bestTrajectory = m_TrajectoryCosts.at(smallestIndex); - //bestTrajectory.index = smallestIndex; - } - -// cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size() -// << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index -// << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance -// << ", Blocked: " << bestTrajectory.bBlocked -// << endl; - - m_PrevCostIndex = smallestIndex; - - return bestTrajectory; + TrajectoryCost bestTrajectory; + bestTrajectory.bBlocked = true; + bestTrajectory.closest_obj_distance = params.horizonDistance; + bestTrajectory.closest_obj_velocity = 0; + bestTrajectory.index = -1; + + if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory; + + if(m_PrevCostIndex == -1) + m_PrevCostIndex = params.rollOutNumber/2; + + m_TrajectoryCosts.clear(); + + for(unsigned int il = 0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0) + { + vector costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params); + m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end()); + } + } + + CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params); + + + WayPoint p; + m_AllContourPoints.clear(); + for(unsigned int io=0; io= 0) + { + bestTrajectory = m_TrajectoryCosts.at(smallestIndex); + //bestTrajectory.index = smallestIndex; + } + +// cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size() +// << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index +// << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance +// << ", Blocked: " << bestTrajectory.bBlocked +// << endl; + + m_PrevCostIndex = smallestIndex; + + return bestTrajectory; } void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCostsStatic(vector& trajectoryCosts, - const vector >& rollOuts, const vector& totalPaths, - const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, - const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) + const vector >& rollOuts, const vector& totalPaths, + const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, + const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) { - double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; - double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; - double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; - - PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); - PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); - - double corner_slide_distance = critical_lateral_distance/2.0; - double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; - double slide_distance = vehicleState.steer * ratio_to_angle; - - GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); - GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); - - GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - - GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); - GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); - - bottom_left = invRotationMat*bottom_left; - bottom_left = invTranslationMat*bottom_left; - - top_right = invRotationMat*top_right; - top_right = invTranslationMat*top_right; - - bottom_right = invRotationMat*bottom_right; - bottom_right = invTranslationMat*bottom_right; - - top_left = invRotationMat*top_left; - top_left = invTranslationMat*top_left; - - top_right_car = invRotationMat*top_right_car; - top_right_car = invTranslationMat*top_right_car; - - top_left_car = invRotationMat*top_left_car; - top_left_car = invTranslationMat*top_left_car; - - m_SafetyBorder.points.clear(); - m_SafetyBorder.points.push_back(bottom_left) ; - m_SafetyBorder.points.push_back(bottom_right) ; - m_SafetyBorder.points.push_back(top_right_car) ; - m_SafetyBorder.points.push_back(top_right) ; - m_SafetyBorder.points.push_back(top_left) ; - m_SafetyBorder.points.push_back(top_left_car) ; - - int iCostIndex = 0; - if(rollOuts.size() > 0 && rollOuts.at(0).size()>0) - { - RelativeInfo car_info; - PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info); - - - for(unsigned int it=0; it< rollOuts.size(); it++) - { - int skip_id = -1; - for(unsigned int icon = 0; icon < contourPoints.size(); icon++) - { - if(skip_id == contourPoints.at(icon).id) - continue; - - RelativeInfo obj_info; - PlanningHelpers::GetRelativeInfo(totalPaths, contourPoints.at(icon), obj_info); - double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info); - if(obj_info.iFront == 0 && longitudinalDist > 0) - longitudinalDist = -longitudinalDist; - - double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); - if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) - { - skip_id = contourPoints.at(icon).id; - continue; - } - - double close_in_percentage = 1; -// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; + double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; + double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; + double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; + + PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); + PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); + + double corner_slide_distance = critical_lateral_distance/2.0; + double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; + double slide_distance = vehicleState.steer * ratio_to_angle; + + GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); + GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); + + GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + + GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); + GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); + + bottom_left = invRotationMat*bottom_left; + bottom_left = invTranslationMat*bottom_left; + + top_right = invRotationMat*top_right; + top_right = invTranslationMat*top_right; + + bottom_right = invRotationMat*bottom_right; + bottom_right = invTranslationMat*bottom_right; + + top_left = invRotationMat*top_left; + top_left = invTranslationMat*top_left; + + top_right_car = invRotationMat*top_right_car; + top_right_car = invTranslationMat*top_right_car; + + top_left_car = invRotationMat*top_left_car; + top_left_car = invTranslationMat*top_left_car; + + m_SafetyBorder.points.clear(); + m_SafetyBorder.points.push_back(bottom_left) ; + m_SafetyBorder.points.push_back(bottom_right) ; + m_SafetyBorder.points.push_back(top_right_car) ; + m_SafetyBorder.points.push_back(top_right) ; + m_SafetyBorder.points.push_back(top_left) ; + m_SafetyBorder.points.push_back(top_left_car) ; + + int iCostIndex = 0; + if(rollOuts.size() > 0 && rollOuts.at(0).size()>0) + { + RelativeInfo car_info; + PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info); + + + for(unsigned int it=0; it< rollOuts.size(); it++) + { + int skip_id = -1; + for(unsigned int icon = 0; icon < contourPoints.size(); icon++) + { + if(skip_id == contourPoints.at(icon).id) + continue; + + RelativeInfo obj_info; + PlanningHelpers::GetRelativeInfo(totalPaths, contourPoints.at(icon), obj_info); + double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info); + if(obj_info.iFront == 0 && longitudinalDist > 0) + longitudinalDist = -longitudinalDist; + + double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); + if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) + { + skip_id = contourPoints.at(icon).id; + continue; + } + + double close_in_percentage = 1; +// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; // -// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; +// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; - double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; + double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; - if(close_in_percentage < 1) - distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); + if(close_in_percentage < 1) + distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); - double lateralDist = fabs(obj_info.perp_distance - distance_from_center); + double lateralDist = fabs(obj_info.perp_distance - distance_from_center); - if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) - { - continue; - } + if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) + { + continue; + } - longitudinalDist = longitudinalDist - critical_long_front_distance; + longitudinalDist = longitudinalDist - critical_long_front_distance; - if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist <= critical_lateral_distance - && longitudinalDist >= -carInfo.length/1.5 - && longitudinalDist < params.minFollowingDistance) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(lateralDist <= critical_lateral_distance + && longitudinalDist >= -carInfo.length/1.5 + && longitudinalDist < params.minFollowingDistance) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist != 0) - trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; + if(lateralDist != 0) + trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; - if(longitudinalDist != 0) - trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); + if(longitudinalDist != 0) + trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); - if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) - { - trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; - trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; - } - } + if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) + { + trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; + trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; + } + } - iCostIndex++; - } - } + iCostIndex++; + } + } } void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCosts(vector& trajectoryCosts, - const vector > >& rollOuts, const vector >& totalPaths, - const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, - const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) + const vector > >& rollOuts, const vector >& totalPaths, + const WayPoint& currState, const vector& contourPoints, const PlanningParams& params, + const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState) { - double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; - double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; - double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; - int iCostIndex = 0; - - PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); - PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); - - double corner_slide_distance = critical_lateral_distance/2.0; - double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; - double slide_distance = vehicleState.steer * ratio_to_angle; - - GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); - GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); - - GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - - GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); - GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); - - bottom_left = invRotationMat*bottom_left; - bottom_left = invTranslationMat*bottom_left; - - top_right = invRotationMat*top_right; - top_right = invTranslationMat*top_right; - - bottom_right = invRotationMat*bottom_right; - bottom_right = invTranslationMat*bottom_right; - - top_left = invRotationMat*top_left; - top_left = invTranslationMat*top_left; - - top_right_car = invRotationMat*top_right_car; - top_right_car = invTranslationMat*top_right_car; - - top_left_car = invRotationMat*top_left_car; - top_left_car = invTranslationMat*top_left_car; - - m_SafetyBorder.points.clear(); - m_SafetyBorder.points.push_back(bottom_left) ; - m_SafetyBorder.points.push_back(bottom_right) ; - m_SafetyBorder.points.push_back(top_right_car) ; - m_SafetyBorder.points.push_back(top_right) ; - m_SafetyBorder.points.push_back(top_left) ; - m_SafetyBorder.points.push_back(top_left_car) ; - - for(unsigned int il=0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0) - { - RelativeInfo car_info; - PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info); - - - for(unsigned int it=0; it< rollOuts.at(il).size(); it++) - { - int skip_id = -1; - for(unsigned int icon = 0; icon < contourPoints.size(); icon++) - { - if(skip_id == contourPoints.at(icon).id) - continue; - - RelativeInfo obj_info; - PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info); - double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info); - if(obj_info.iFront == 0 && longitudinalDist > 0) - longitudinalDist = -longitudinalDist; - - double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); - if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) - { - skip_id = contourPoints.at(icon).id; - continue; - } - - double close_in_percentage = 1; -// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; + double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel; + double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance; + double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0; + int iCostIndex = 0; + + PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); + PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); + + double corner_slide_distance = critical_lateral_distance/2.0; + double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; + double slide_distance = vehicleState.steer * ratio_to_angle; + + GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0); + GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0); + + GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + + GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0); + GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0); + + bottom_left = invRotationMat*bottom_left; + bottom_left = invTranslationMat*bottom_left; + + top_right = invRotationMat*top_right; + top_right = invTranslationMat*top_right; + + bottom_right = invRotationMat*bottom_right; + bottom_right = invTranslationMat*bottom_right; + + top_left = invRotationMat*top_left; + top_left = invTranslationMat*top_left; + + top_right_car = invRotationMat*top_right_car; + top_right_car = invTranslationMat*top_right_car; + + top_left_car = invRotationMat*top_left_car; + top_left_car = invTranslationMat*top_left_car; + + m_SafetyBorder.points.clear(); + m_SafetyBorder.points.push_back(bottom_left) ; + m_SafetyBorder.points.push_back(bottom_right) ; + m_SafetyBorder.points.push_back(top_right_car) ; + m_SafetyBorder.points.push_back(top_right) ; + m_SafetyBorder.points.push_back(top_left) ; + m_SafetyBorder.points.push_back(top_left_car) ; + + for(unsigned int il=0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0) + { + RelativeInfo car_info; + PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info); + + + for(unsigned int it=0; it< rollOuts.at(il).size(); it++) + { + int skip_id = -1; + for(unsigned int icon = 0; icon < contourPoints.size(); icon++) + { + if(skip_id == contourPoints.at(icon).id) + continue; + + RelativeInfo obj_info; + PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info); + double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info); + if(obj_info.iFront == 0 && longitudinalDist > 0) + longitudinalDist = -longitudinalDist; + + double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x); + if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost)) + { + skip_id = contourPoints.at(icon).id; + continue; + } + + double close_in_percentage = 1; +// close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0; // -// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; +// if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1; - double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; + double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center; - if(close_in_percentage < 1) - distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); + if(close_in_percentage < 1) + distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage); - double lateralDist = fabs(obj_info.perp_distance - distance_from_center); + double lateralDist = fabs(obj_info.perp_distance - distance_from_center); - if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) - { - continue; - } + if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance) + { + continue; + } - longitudinalDist = longitudinalDist - critical_long_front_distance; + longitudinalDist = longitudinalDist - critical_long_front_distance; - if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist <= critical_lateral_distance - && longitudinalDist >= -carInfo.length/1.5 - && longitudinalDist < params.minFollowingDistance) - trajectoryCosts.at(iCostIndex).bBlocked = true; + if(lateralDist <= critical_lateral_distance + && longitudinalDist >= -carInfo.length/1.5 + && longitudinalDist < params.minFollowingDistance) + trajectoryCosts.at(iCostIndex).bBlocked = true; - if(lateralDist != 0) - trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; + if(lateralDist != 0) + trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist; - if(longitudinalDist != 0) - trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); + if(longitudinalDist != 0) + trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist); - if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) - { - trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; - trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; - } - } + if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance) + { + trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist; + trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v; + } + } - iCostIndex++; - } - } - } + iCostIndex++; + } + } + } } void TrajectoryDynamicCosts::NormalizeCosts(vector& trajectoryCosts) { - //Normalize costs - double totalPriorities = 0; - double totalChange = 0; - double totalLateralCosts = 0; - double totalLongitudinalCosts = 0; - double transitionCosts = 0; - - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - totalPriorities += trajectoryCosts.at(ic).priority_cost; - transitionCosts += trajectoryCosts.at(ic).transition_cost; - } - - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - totalChange += trajectoryCosts.at(ic).lane_change_cost; - totalLateralCosts += trajectoryCosts.at(ic).lateral_cost; - totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost; - } - -// cout << "------ Normalizing Step " << endl; - for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) - { - if(totalPriorities != 0) - trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities; - else - trajectoryCosts.at(ic).priority_cost = 0; - - if(transitionCosts != 0) - trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts; - else - trajectoryCosts.at(ic).transition_cost = 0; - - if(totalChange != 0) - trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange; - else - trajectoryCosts.at(ic).lane_change_cost = 0; - - if(totalLateralCosts != 0) - trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts; - else - trajectoryCosts.at(ic).lateral_cost = 0; - - if(totalLongitudinalCosts != 0) - trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts; - else - trajectoryCosts.at(ic).longitudinal_cost = 0; - - trajectoryCosts.at(ic).cost = (m_WeightPriority*trajectoryCosts.at(ic).priority_cost + m_WeightTransition*trajectoryCosts.at(ic).transition_cost + m_WeightLat*trajectoryCosts.at(ic).lateral_cost + m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost)/4.0; - -// cout << "Index: " << ic -// << ", Priority: " << trajectoryCosts.at(ic).priority_cost -// << ", Transition: " << trajectoryCosts.at(ic).transition_cost -// << ", Lat: " << trajectoryCosts.at(ic).lateral_cost -// << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost -// << ", Change: " << trajectoryCosts.at(ic).lane_change_cost -// << ", Avg: " << trajectoryCosts.at(ic).cost -// << endl; - } - -// cout << "------------------------ " << endl; + //Normalize costs + double totalPriorities = 0; + double totalChange = 0; + double totalLateralCosts = 0; + double totalLongitudinalCosts = 0; + double transitionCosts = 0; + + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + totalPriorities += trajectoryCosts.at(ic).priority_cost; + transitionCosts += trajectoryCosts.at(ic).transition_cost; + } + + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + totalChange += trajectoryCosts.at(ic).lane_change_cost; + totalLateralCosts += trajectoryCosts.at(ic).lateral_cost; + totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost; + } + +// cout << "------ Normalizing Step " << endl; + for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++) + { + if(totalPriorities != 0) + trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities; + else + trajectoryCosts.at(ic).priority_cost = 0; + + if(transitionCosts != 0) + trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts; + else + trajectoryCosts.at(ic).transition_cost = 0; + + if(totalChange != 0) + trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange; + else + trajectoryCosts.at(ic).lane_change_cost = 0; + + if(totalLateralCosts != 0) + trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts; + else + trajectoryCosts.at(ic).lateral_cost = 0; + + if(totalLongitudinalCosts != 0) + trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts; + else + trajectoryCosts.at(ic).longitudinal_cost = 0; + + trajectoryCosts.at(ic).cost = (m_WeightPriority*trajectoryCosts.at(ic).priority_cost + m_WeightTransition*trajectoryCosts.at(ic).transition_cost + m_WeightLat*trajectoryCosts.at(ic).lateral_cost + m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost)/4.0; + +// cout << "Index: " << ic +// << ", Priority: " << trajectoryCosts.at(ic).priority_cost +// << ", Transition: " << trajectoryCosts.at(ic).transition_cost +// << ", Lat: " << trajectoryCosts.at(ic).lateral_cost +// << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost +// << ", Change: " << trajectoryCosts.at(ic).lane_change_cost +// << ", Avg: " << trajectoryCosts.at(ic).cost +// << endl; + } + +// cout << "------------------------ " << endl; } vector TrajectoryDynamicCosts::CalculatePriorityAndLaneChangeCosts(const vector >& laneRollOuts, - const int& lane_index, const PlanningParams& params) + const int& lane_index, const PlanningParams& params) { - vector costs; - TrajectoryCost tc; - int centralIndex = params.rollOutNumber/2; - - tc.lane_index = lane_index; - for(unsigned int it=0; it< laneRollOuts.size(); it++) - { - tc.index = it; - tc.relative_index = it - centralIndex; - tc.distance_from_center = params.rollOutDensity*tc.relative_index; - tc.priority_cost = fabs(tc.distance_from_center); - tc.closest_obj_distance = params.horizonDistance; - tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost; - -// if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR) -// tc.lane_change_cost = 1; -// else if(laneRollOuts.at(it).at(0).bDir == BACKWARD_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_RIGHT_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_LEFT_DIR) -// tc.lane_change_cost = 2; -// else -// tc.lane_change_cost = 0; - - costs.push_back(tc); - } - - return costs; + vector costs; + TrajectoryCost tc; + int centralIndex = params.rollOutNumber/2; + + tc.lane_index = lane_index; + for(unsigned int it=0; it< laneRollOuts.size(); it++) + { + tc.index = it; + tc.relative_index = it - centralIndex; + tc.distance_from_center = params.rollOutDensity*tc.relative_index; + tc.priority_cost = fabs(tc.distance_from_center); + tc.closest_obj_distance = params.horizonDistance; + tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost; + +// if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR) +// tc.lane_change_cost = 1; +// else if(laneRollOuts.at(it).at(0).bDir == BACKWARD_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_RIGHT_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_LEFT_DIR) +// tc.lane_change_cost = 2; +// else +// tc.lane_change_cost = 0; + + costs.push_back(tc); + } + + return costs; } void TrajectoryDynamicCosts::CalculateTransitionCosts(vector& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params) { - for(int ic = 0; ic< trajectoryCosts.size(); ic++) - { - trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex)); - } + for(int ic = 0; ic< trajectoryCosts.size(); ic++) + { + trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex)); + } } /** @@ -678,240 +678,240 @@ void TrajectoryDynamicCosts::CalculateTransitionCosts(vector& tr */ bool TrajectoryDynamicCosts::ValidateRollOutsInput(const vector > >& rollOuts) { - if(rollOuts.size()==0) - return false; + if(rollOuts.size()==0) + return false; - for(unsigned int il = 0; il < rollOuts.size(); il++) - { - if(rollOuts.at(il).size() == 0) - return false; - } + for(unsigned int il = 0; il < rollOuts.size(); il++) + { + if(rollOuts.at(il).size() == 0) + return false; + } - return true; + return true; } void TrajectoryDynamicCosts::CalculateIntersectionVelocities(const std::vector& path, const PlannerHNS::DetectedObject& obj, const WayPoint& currPose, const CAR_BASIC_INFO& carInfo, const double& c_lateral_d, WayPoint& collisionPoint, TrajectoryCost& trajectoryCosts) { - trajectoryCosts.bBlocked = false; - int closest_path_i = path.size(); - for(unsigned int k = 0; k < obj.predTrajectories.size(); k++) - { - for(unsigned int j = 0; j < obj.predTrajectories.at(k).size(); j++) - { - for(unsigned int i = 0; i < path.size(); i++) - { - //if(path.at(i).timeCost > -1) - { - double collision_distance = hypot(path.at(i).pos.x-obj.predTrajectories.at(k).at(j).pos.x, path.at(i).pos.y-obj.predTrajectories.at(k).at(j).pos.y); - double collision_t = fabs(path.at(i).timeCost - obj.predTrajectories.at(k).at(j).timeCost); - - //if(collision_distance <= c_lateral_d && i < closest_path_i && collision_t < m_CollisionTimeDiff) - if(collision_distance <= c_lateral_d && i < closest_path_i) - { - - closest_path_i = i; - double a = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(path.at(i).pos.a, obj.predTrajectories.at(k).at(j).pos.a)/M_PI; - if(a < 0.25 && (currPose.v - obj.center.v) > 0) - trajectoryCosts.closest_obj_velocity = (currPose.v - obj.center.v); - else - trajectoryCosts.closest_obj_velocity = currPose.v; - - collisionPoint = path.at(i); - collisionPoint.collisionCost = collision_t; - collisionPoint.cost = collision_distance; - trajectoryCosts.bBlocked = true; - } - } - } - } - } + trajectoryCosts.bBlocked = false; + int closest_path_i = path.size(); + for(unsigned int k = 0; k < obj.predTrajectories.size(); k++) + { + for(unsigned int j = 0; j < obj.predTrajectories.at(k).size(); j++) + { + for(unsigned int i = 0; i < path.size(); i++) + { + //if(path.at(i).timeCost > -1) + { + double collision_distance = hypot(path.at(i).pos.x-obj.predTrajectories.at(k).at(j).pos.x, path.at(i).pos.y-obj.predTrajectories.at(k).at(j).pos.y); + double collision_t = fabs(path.at(i).timeCost - obj.predTrajectories.at(k).at(j).timeCost); + + //if(collision_distance <= c_lateral_d && i < closest_path_i && collision_t < m_CollisionTimeDiff) + if(collision_distance <= c_lateral_d && i < closest_path_i) + { + + closest_path_i = i; + double a = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(path.at(i).pos.a, obj.predTrajectories.at(k).at(j).pos.a)/M_PI; + if(a < 0.25 && (currPose.v - obj.center.v) > 0) + trajectoryCosts.closest_obj_velocity = (currPose.v - obj.center.v); + else + trajectoryCosts.closest_obj_velocity = currPose.v; + + collisionPoint = path.at(i); + collisionPoint.collisionCost = collision_t; + collisionPoint.cost = collision_distance; + trajectoryCosts.bBlocked = true; + } + } + } + } + } } int TrajectoryDynamicCosts::GetCurrentRollOutIndex(const std::vector& path, const WayPoint& currState, const PlanningParams& params) { - RelativeInfo obj_info; - PlanningHelpers::GetRelativeInfo(path, currState, obj_info); - int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity); - if(currIndex < 0) - currIndex = 0; - else if(currIndex > params.rollOutNumber) - currIndex = params.rollOutNumber; - - return currIndex; + RelativeInfo obj_info; + PlanningHelpers::GetRelativeInfo(path, currState, obj_info); + int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity); + if(currIndex < 0) + currIndex = 0; + else if(currIndex > params.rollOutNumber) + currIndex = params.rollOutNumber; + + return currIndex; } void TrajectoryDynamicCosts::InitializeCosts(const vector >& rollOuts, const PlanningParams& params) { - m_TrajectoryCosts.clear(); - if(rollOuts.size()>0) - { - TrajectoryCost tc; - int centralIndex = params.rollOutNumber/2; - tc.lane_index = 0; - for(unsigned int it=0; it< rollOuts.size(); it++) - { - tc.index = it; - tc.relative_index = it - centralIndex; - tc.distance_from_center = params.rollOutDensity*tc.relative_index; - tc.priority_cost = fabs(tc.distance_from_center); - tc.closest_obj_distance = params.horizonDistance; - if(rollOuts.at(it).size() > 0) - tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost; - m_TrajectoryCosts.push_back(tc); - } - } + m_TrajectoryCosts.clear(); + if(rollOuts.size()>0) + { + TrajectoryCost tc; + int centralIndex = params.rollOutNumber/2; + tc.lane_index = 0; + for(unsigned int it=0; it< rollOuts.size(); it++) + { + tc.index = it; + tc.relative_index = it - centralIndex; + tc.distance_from_center = params.rollOutDensity*tc.relative_index; + tc.priority_cost = fabs(tc.distance_from_center); + tc.closest_obj_distance = params.horizonDistance; + if(rollOuts.at(it).size() > 0) + tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost; + m_TrajectoryCosts.push_back(tc); + } + } } void TrajectoryDynamicCosts::InitializeSafetyPolygon(const WayPoint& currState, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d) { - PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); - PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); + PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2); + PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y); - double corner_slide_distance = c_lateral_d/2.0; - double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; - double slide_distance = vehicleState.steer * ratio_to_angle; + double corner_slide_distance = c_lateral_d/2.0; + double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle; + double slide_distance = vehicleState.steer * ratio_to_angle; - GPSPoint bottom_left(-c_lateral_d ,-c_long_back_d, currState.pos.z, 0); - GPSPoint bottom_right(c_lateral_d, -c_long_back_d, currState.pos.z, 0); + GPSPoint bottom_left(-c_lateral_d ,-c_long_back_d, currState.pos.z, 0); + GPSPoint bottom_right(c_lateral_d, -c_long_back_d, currState.pos.z, 0); - GPSPoint top_right_car(c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - GPSPoint top_left_car(-c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + GPSPoint top_right_car(c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); + GPSPoint top_left_car(-c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0); - GPSPoint top_right(c_lateral_d - slide_distance, c_long_front_d, currState.pos.z, 0); - GPSPoint top_left(-c_lateral_d - slide_distance , c_long_front_d, currState.pos.z, 0); + GPSPoint top_right(c_lateral_d - slide_distance, c_long_front_d, currState.pos.z, 0); + GPSPoint top_left(-c_lateral_d - slide_distance , c_long_front_d, currState.pos.z, 0); - bottom_left = invRotationMat*bottom_left; - bottom_left = invTranslationMat*bottom_left; + bottom_left = invRotationMat*bottom_left; + bottom_left = invTranslationMat*bottom_left; - top_right = invRotationMat*top_right; - top_right = invTranslationMat*top_right; + top_right = invRotationMat*top_right; + top_right = invTranslationMat*top_right; - bottom_right = invRotationMat*bottom_right; - bottom_right = invTranslationMat*bottom_right; + bottom_right = invRotationMat*bottom_right; + bottom_right = invTranslationMat*bottom_right; - top_left = invRotationMat*top_left; - top_left = invTranslationMat*top_left; + top_left = invRotationMat*top_left; + top_left = invTranslationMat*top_left; - top_right_car = invRotationMat*top_right_car; - top_right_car = invTranslationMat*top_right_car; + top_right_car = invRotationMat*top_right_car; + top_right_car = invTranslationMat*top_right_car; - top_left_car = invRotationMat*top_left_car; - top_left_car = invTranslationMat*top_left_car; + top_left_car = invRotationMat*top_left_car; + top_left_car = invTranslationMat*top_left_car; - m_SafetyBorder.points.clear(); - m_SafetyBorder.points.push_back(bottom_left) ; - m_SafetyBorder.points.push_back(bottom_right) ; - m_SafetyBorder.points.push_back(top_right_car) ; - m_SafetyBorder.points.push_back(top_right) ; - m_SafetyBorder.points.push_back(top_left) ; - m_SafetyBorder.points.push_back(top_left_car) ; + m_SafetyBorder.points.clear(); + m_SafetyBorder.points.push_back(bottom_left) ; + m_SafetyBorder.points.push_back(bottom_right) ; + m_SafetyBorder.points.push_back(top_right_car) ; + m_SafetyBorder.points.push_back(top_right) ; + m_SafetyBorder.points.push_back(top_left) ; + m_SafetyBorder.points.push_back(top_left_car) ; } void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCostsDynamic(const std::vector& obj_list, const vector >& rollOuts, const vector& totalPaths, - const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, - const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d ) + const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo, + const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d ) { - RelativeInfo car_info; - PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info); - m_CollisionPoints.clear(); - - for(unsigned int i=0; i < obj_list.size(); i++) - { - if(obj_list.at(i).label.compare("curb") == 0) - { - double d = hypot(obj_list.at(i).center.pos.y - currState.pos.y , obj_list.at(i).center.pos.x - currState.pos.x); - if(d > params.minFollowingDistance + c_lateral_d) - continue; - } - - if(obj_list.at(i).bVelocity && obj_list.at(i).predTrajectories.size() > 0) // dynamic - { - - for(unsigned int ir=0; ir < rollOuts.size(); ir++) - { - WayPoint collisionPoint; - TrajectoryCost trajectoryCosts; - CalculateIntersectionVelocities(rollOuts.at(ir), obj_list.at(i), currState, carInfo, c_lateral_d, collisionPoint,trajectoryCosts); - if(trajectoryCosts.bBlocked) - { - RelativeInfo col_info; - PlanningHelpers::GetRelativeInfo(totalPaths, collisionPoint, col_info); - double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, col_info); - - if(col_info.iFront == 0 && longitudinalDist > 0) - longitudinalDist = -longitudinalDist; - - if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || fabs(longitudinalDist) < carInfo.width/2.0) - continue; - - //std::cout << "LongDistance: " << longitudinalDist << std::endl; - - if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(ir).closest_obj_distance) - m_TrajectoryCosts.at(ir).closest_obj_distance = longitudinalDist; - - m_TrajectoryCosts.at(ir).closest_obj_velocity = trajectoryCosts.closest_obj_velocity; - m_TrajectoryCosts.at(ir).bBlocked = true; - - m_CollisionPoints.push_back(collisionPoint); - } - } - } - else - { - RelativeInfo obj_info; - WayPoint corner_p; - for(unsigned int icon = 0; icon < obj_list.at(i).contour.size(); icon++) - { - if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, obj_list.at(i).contour.at(icon)) == true) - { - for(unsigned int it=0; it< rollOuts.size(); it++) - m_TrajectoryCosts.at(it).bBlocked = true; - - return; - } - - corner_p.pos = obj_list.at(i).contour.at(icon); - PlanningHelpers::GetRelativeInfo(totalPaths, corner_p, obj_info); - double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info); - if(obj_info.iFront == 0 && longitudinalDist > 0) - longitudinalDist = -longitudinalDist; - - - if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance) - continue; - - longitudinalDist = longitudinalDist - c_long_front_d; - - for(unsigned int it=0; it< rollOuts.size(); it++) - { - double lateralDist = fabs(obj_info.perp_distance - m_TrajectoryCosts.at(it).distance_from_center); - - if(lateralDist > m_LateralSkipDistance) - continue; - - if(lateralDist <= c_lateral_d && longitudinalDist > -carInfo.length && longitudinalDist < params.minFollowingDistance) - { - m_TrajectoryCosts.at(it).bBlocked = true; - m_CollisionPoints.push_back(obj_info.perp_point); - } - - if(lateralDist != 0) - m_TrajectoryCosts.at(it).lateral_cost += 1.0/lateralDist; - - if(longitudinalDist != 0) - m_TrajectoryCosts.at(it).longitudinal_cost += 1.0/fabs(longitudinalDist); - - if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(it).closest_obj_distance) - { - m_TrajectoryCosts.at(it).closest_obj_distance = longitudinalDist; - m_TrajectoryCosts.at(it).closest_obj_velocity = obj_list.at(i).center.v; - } - } - } - - } - } + RelativeInfo car_info; + PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info); + m_CollisionPoints.clear(); + + for(unsigned int i=0; i < obj_list.size(); i++) + { + if(obj_list.at(i).label.compare("curb") == 0) + { + double d = hypot(obj_list.at(i).center.pos.y - currState.pos.y , obj_list.at(i).center.pos.x - currState.pos.x); + if(d > params.minFollowingDistance + c_lateral_d) + continue; + } + + if(obj_list.at(i).bVelocity && obj_list.at(i).predTrajectories.size() > 0) // dynamic + { + + for(unsigned int ir=0; ir < rollOuts.size(); ir++) + { + WayPoint collisionPoint; + TrajectoryCost trajectoryCosts; + CalculateIntersectionVelocities(rollOuts.at(ir), obj_list.at(i), currState, carInfo, c_lateral_d, collisionPoint,trajectoryCosts); + if(trajectoryCosts.bBlocked) + { + RelativeInfo col_info; + PlanningHelpers::GetRelativeInfo(totalPaths, collisionPoint, col_info); + double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, col_info); + + if(col_info.iFront == 0 && longitudinalDist > 0) + longitudinalDist = -longitudinalDist; + + if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || fabs(longitudinalDist) < carInfo.width/2.0) + continue; + + //std::cout << "LongDistance: " << longitudinalDist << std::endl; + + if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(ir).closest_obj_distance) + m_TrajectoryCosts.at(ir).closest_obj_distance = longitudinalDist; + + m_TrajectoryCosts.at(ir).closest_obj_velocity = trajectoryCosts.closest_obj_velocity; + m_TrajectoryCosts.at(ir).bBlocked = true; + + m_CollisionPoints.push_back(collisionPoint); + } + } + } + else + { + RelativeInfo obj_info; + WayPoint corner_p; + for(unsigned int icon = 0; icon < obj_list.at(i).contour.size(); icon++) + { + if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, obj_list.at(i).contour.at(icon)) == true) + { + for(unsigned int it=0; it< rollOuts.size(); it++) + m_TrajectoryCosts.at(it).bBlocked = true; + + return; + } + + corner_p.pos = obj_list.at(i).contour.at(icon); + PlanningHelpers::GetRelativeInfo(totalPaths, corner_p, obj_info); + double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info); + if(obj_info.iFront == 0 && longitudinalDist > 0) + longitudinalDist = -longitudinalDist; + + + if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance) + continue; + + longitudinalDist = longitudinalDist - c_long_front_d; + + for(unsigned int it=0; it< rollOuts.size(); it++) + { + double lateralDist = fabs(obj_info.perp_distance - m_TrajectoryCosts.at(it).distance_from_center); + + if(lateralDist > m_LateralSkipDistance) + continue; + + if(lateralDist <= c_lateral_d && longitudinalDist > -carInfo.length && longitudinalDist < params.minFollowingDistance) + { + m_TrajectoryCosts.at(it).bBlocked = true; + m_CollisionPoints.push_back(obj_info.perp_point); + } + + if(lateralDist != 0) + m_TrajectoryCosts.at(it).lateral_cost += 1.0/lateralDist; + + if(longitudinalDist != 0) + m_TrajectoryCosts.at(it).longitudinal_cost += 1.0/fabs(longitudinalDist); + + if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(it).closest_obj_distance) + { + m_TrajectoryCosts.at(it).closest_obj_distance = longitudinalDist; + m_TrajectoryCosts.at(it).closest_obj_velocity = obj_list.at(i).center.v; + } + } + } + + } + } } } diff --git a/common/op_planner/test/src/test_BuildPlanningSearchTreeV2.cpp b/common/op_planner/test/src/test_BuildPlanningSearchTreeV2.cpp new file mode 100644 index 00000000000..a72e3540613 --- /dev/null +++ b/common/op_planner/test/src/test_BuildPlanningSearchTreeV2.cpp @@ -0,0 +1,228 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "op_planner/PlanningHelpers.h" + +using namespace PlannerHNS; + +#include +#include +#include + +class TestSuite: + public ::testing::Test +{ +public: + TestSuite() {} +}; + +TEST(TestSuite, TestNoPathFound) +{ + WayPoint start_position; + WayPoint intermediate_position_1; + WayPoint intermediate_position_2; + WayPoint intermediate_position_3; + WayPoint goal_position; + WayPoint* result; + std::vector global_path; + double distance_limit = 34; + bool enable_line_change = false; + std::vector all_cell_to_delete; + double fallback_min_goal_distance_th = 0; + + start_position.pos.x = 0; + start_position.pos.y = 0; + start_position.pos.z = 0; + start_position.pos.a = 0; + start_position.pFronts.push_back(&intermediate_position_1); + + intermediate_position_1.pos.x = 10; + intermediate_position_1.pos.y = 0; + intermediate_position_1.pos.z = 0; + intermediate_position_1.pos.a = 0; + intermediate_position_1.pFronts.push_back(&intermediate_position_2); + intermediate_position_1.pBacks.push_back(&start_position); + intermediate_position_1.id = 1; + + intermediate_position_2.pos.x = 20; + intermediate_position_2.pos.y = 0; + intermediate_position_2.pos.z = 0; + intermediate_position_2.pos.a = 0; + intermediate_position_2.pFronts.push_back(&intermediate_position_3); + intermediate_position_2.pBacks.push_back(&intermediate_position_1); + intermediate_position_2.id = 2; + + intermediate_position_3.pos.x = 30; + intermediate_position_3.pos.y = 0; + intermediate_position_3.pos.z = 0; + intermediate_position_3.pos.a = 0; + intermediate_position_3.pBacks.push_back(&intermediate_position_2); + intermediate_position_3.id = 3; + + goal_position.pos.x = 34; + goal_position.pos.y = 0; + goal_position.pos.z = 0; + goal_position.pos.a = 0; + + result = PlanningHelpers::BuildPlanningSearchTreeV2( + &start_position, + goal_position, + global_path, + distance_limit, + enable_line_change, + all_cell_to_delete, + fallback_min_goal_distance_th); + + // Assert no path is found + ASSERT_TRUE(result == 0); +} + +TEST(TestSuite, TestPathFound) +{ + WayPoint start_position; + WayPoint intermediate_position_1; + WayPoint intermediate_position_2; + WayPoint intermediate_position_3; + WayPoint goal_position; + WayPoint* result; + std::vector global_path; + double distance_limit = 34; + bool enable_line_change = false; + std::vector all_cell_to_delete; + double fallback_min_goal_distance_th = 0; + + start_position.pos.x = 0; + start_position.pos.y = 0; + start_position.pos.z = 0; + start_position.pos.a = 0; + start_position.pFronts.push_back(&intermediate_position_1); + + intermediate_position_1.pos.x = 10; + intermediate_position_1.pos.y = 0; + intermediate_position_1.pos.z = 0; + intermediate_position_1.pos.a = 0; + intermediate_position_1.pFronts.push_back(&intermediate_position_2); + intermediate_position_1.pBacks.push_back(&start_position); + intermediate_position_1.id = 1; + + intermediate_position_2.pos.x = 20; + intermediate_position_2.pos.y = 0; + intermediate_position_2.pos.z = 0; + intermediate_position_2.pos.a = 0; + intermediate_position_2.pFronts.push_back(&intermediate_position_3); + intermediate_position_2.pBacks.push_back(&intermediate_position_1); + intermediate_position_2.id = 2; + + intermediate_position_3.pos.x = 34; + intermediate_position_3.pos.y = 0; + intermediate_position_3.pos.z = 0; + intermediate_position_3.pos.a = 0; + intermediate_position_3.pBacks.push_back(&intermediate_position_2); + intermediate_position_3.id = 3; + + goal_position.pos.x = 34; + goal_position.pos.y = 0; + goal_position.pos.z = 0; + goal_position.pos.a = 0; + + result = PlanningHelpers::BuildPlanningSearchTreeV2( + &start_position, + goal_position, + global_path, + distance_limit, + enable_line_change, + all_cell_to_delete, + fallback_min_goal_distance_th); + + // Assert a path is found + ASSERT_TRUE(result != 0); + ASSERT_DOUBLE_EQ(result->pos.x, 34); + ASSERT_DOUBLE_EQ(result->pos.y, 0); + ASSERT_DOUBLE_EQ(result->pos.z, 0); + ASSERT_DOUBLE_EQ(result->pos.a, 0); +} + +TEST(TestSuite, TestPathCloseEnough) +{ + WayPoint start_position; + WayPoint intermediate_position_1; + WayPoint intermediate_position_2; + WayPoint intermediate_position_3; + WayPoint goal_position; + WayPoint* result; + std::vector global_path; + double distance_limit = 34; + bool enable_line_change = false; + std::vector all_cell_to_delete; + double fallback_min_goal_distance_th = 5; + + start_position.pos.x = 0; + start_position.pos.y = 0; + start_position.pos.z = 0; + start_position.pos.a = 0; + start_position.pFronts.push_back(&intermediate_position_1); + + intermediate_position_1.pos.x = 10; + intermediate_position_1.pos.y = 0; + intermediate_position_1.pos.z = 0; + intermediate_position_1.pos.a = 0; + intermediate_position_1.pFronts.push_back(&intermediate_position_2); + intermediate_position_1.pBacks.push_back(&start_position); + intermediate_position_1.id = 1; + + intermediate_position_2.pos.x = 20; + intermediate_position_2.pos.y = 0; + intermediate_position_2.pos.z = 0; + intermediate_position_2.pos.a = 0; + intermediate_position_2.pFronts.push_back(&intermediate_position_3); + intermediate_position_2.pBacks.push_back(&intermediate_position_1); + intermediate_position_2.id = 2; + + intermediate_position_3.pos.x = 30; + intermediate_position_3.pos.y = 0; + intermediate_position_3.pos.z = 0; + intermediate_position_3.pos.a = 0; + intermediate_position_3.pBacks.push_back(&intermediate_position_2); + intermediate_position_3.id = 3; + + goal_position.pos.x = 34; + goal_position.pos.y = 0; + goal_position.pos.z = 0; + goal_position.pos.a = 0; + + result = PlanningHelpers::BuildPlanningSearchTreeV2( + &start_position, + goal_position, + global_path, + distance_limit, + enable_line_change, + all_cell_to_delete, + fallback_min_goal_distance_th); + + // Assert a close enough path is found + ASSERT_TRUE(result != 0); + ASSERT_DOUBLE_EQ(result->pos.x, 30); + ASSERT_DOUBLE_EQ(result->pos.y, 0); + ASSERT_DOUBLE_EQ(result->pos.z, 0); + ASSERT_DOUBLE_EQ(result->pos.a, 0); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "TestNode"); + return RUN_ALL_TESTS(); +} \ No newline at end of file diff --git a/common/op_ros_helpers/CMakeLists.txt b/common/op_ros_helpers/CMakeLists.txt index 38df0e2d73c..43cb6def5de 100644 --- a/common/op_ros_helpers/CMakeLists.txt +++ b/common/op_ros_helpers/CMakeLists.txt @@ -5,18 +5,18 @@ project(op_ros_helpers) find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS + autoware_msgs geometry_msgs + jsk_recognition_msgs + libwaypoint_follower map_file + op_planner + op_simu + op_utility pcl_conversions pcl_ros sensor_msgs tf - jsk_recognition_msgs - op_utility - op_planner - op_simu - libwaypoint_follower - autoware_msgs vector_map_msgs ) @@ -24,19 +24,10 @@ catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} CATKIN_DEPENDS - geometry_msgs - autoware_msgs - map_file - pcl_conversions - pcl_ros - sensor_msgs - tf - jsk_recognition_msgs - op_utility - op_planner - op_simu - libwaypoint_follower - vector_map_msgs + autoware_msgs + geometry_msgs + libwaypoint_follower + vector_map_msgs ) set(CMAKE_CXX_FLAGS "-O2 -g -Wall -Wno-unused-result ${CMAKE_CXX_FLAGS}") diff --git a/common/op_ros_helpers/include/op_ros_helpers/PolygonGenerator.h b/common/op_ros_helpers/include/op_ros_helpers/PolygonGenerator.h index 4ac09278b23..8bc18128ffd 100644 --- a/common/op_ros_helpers/include/op_ros_helpers/PolygonGenerator.h +++ b/common/op_ros_helpers/include/op_ros_helpers/PolygonGenerator.h @@ -20,58 +20,58 @@ namespace PlannerHNS class QuarterView { public: - int id; - int min_ang; - int max_ang; - WayPoint max_from_center; - bool bFirst; - - QuarterView(const int& min_a, const int& max_a, const int& index) - { - min_ang = min_a; - max_ang = max_a; - id = index; - bFirst = true; - } - - void InitQuarterView(const int& min_a, const int& max_a, const int& index) - { - min_ang = min_a; - max_ang = max_a; - id = index; - bFirst = true; - } - - void ResetQuarterView() - { - bFirst = true; - } - - bool UpdateQuarterView(const WayPoint& v) - { - if(v.pos.a <= min_ang || v.pos.a > max_ang) - return false; - - if(bFirst) - { - max_from_center = v; - bFirst = false; - } - else if(v.cost > max_from_center.cost) - max_from_center = v; - - return true; - } - - bool GetMaxPoint(WayPoint& maxPoint) - { - if(bFirst) - return false; - else - maxPoint = max_from_center; - - return true; - } + int id; + int min_ang; + int max_ang; + WayPoint max_from_center; + bool bFirst; + + QuarterView(const int& min_a, const int& max_a, const int& index) + { + min_ang = min_a; + max_ang = max_a; + id = index; + bFirst = true; + } + + void InitQuarterView(const int& min_a, const int& max_a, const int& index) + { + min_ang = min_a; + max_ang = max_a; + id = index; + bFirst = true; + } + + void ResetQuarterView() + { + bFirst = true; + } + + bool UpdateQuarterView(const WayPoint& v) + { + if(v.pos.a <= min_ang || v.pos.a > max_ang) + return false; + + if(bFirst) + { + max_from_center = v; + bFirst = false; + } + else if(v.cost > max_from_center.cost) + max_from_center = v; + + return true; + } + + bool GetMaxPoint(WayPoint& maxPoint) + { + if(bFirst) + return false; + else + maxPoint = max_from_center; + + return true; + } }; class PolygonGenerator @@ -79,14 +79,14 @@ class PolygonGenerator public: - GPSPoint m_Centroid; - std::vector m_Quarters; - std::vector m_Polygon; + GPSPoint m_Centroid; + std::vector m_Quarters; + std::vector m_Polygon; - PolygonGenerator(int nQuarters); - virtual ~PolygonGenerator(); - std::vector CreateQuarterViews(const int& nResolution); - std::vector EstimateClusterPolygon(const pcl::PointCloud& cluster, const GPSPoint& original_centroid, GPSPoint& new_centroid, const double& polygon_resolution = 1.0); + PolygonGenerator(int nQuarters); + virtual ~PolygonGenerator(); + std::vector CreateQuarterViews(const int& nResolution); + std::vector EstimateClusterPolygon(const pcl::PointCloud& cluster, const GPSPoint& original_centroid, GPSPoint& new_centroid, const double& polygon_resolution = 1.0); }; } /* namespace PlannerXNS */ diff --git a/common/op_ros_helpers/include/op_ros_helpers/op_ROSHelpers.h b/common/op_ros_helpers/include/op_ros_helpers/op_ROSHelpers.h index 13593c3f2c1..27b12102234 100644 --- a/common/op_ros_helpers/include/op_ros_helpers/op_ROSHelpers.h +++ b/common/op_ros_helpers/include/op_ros_helpers/op_ROSHelpers.h @@ -51,237 +51,237 @@ namespace PlannerHNS class AutowareRoadNetwork { public: - vector_map_msgs::PointArray points; - vector_map_msgs::LaneArray lanes; - vector_map_msgs::NodeArray nodes; - vector_map_msgs::StopLineArray stoplines; - vector_map_msgs::DTLaneArray dtlanes; //center lines - bool bPoints; - bool bLanes; - bool bNodes; - bool bStopLines; - bool bDtLanes; - - AutowareRoadNetwork() - { - bPoints = false; - bLanes = false; - bStopLines = false; - bDtLanes = false; - bNodes = false; - } + vector_map_msgs::PointArray points; + vector_map_msgs::LaneArray lanes; + vector_map_msgs::NodeArray nodes; + vector_map_msgs::StopLineArray stoplines; + vector_map_msgs::DTLaneArray dtlanes; //center lines + bool bPoints; + bool bLanes; + bool bNodes; + bool bStopLines; + bool bDtLanes; + + AutowareRoadNetwork() + { + bPoints = false; + bLanes = false; + bStopLines = false; + bDtLanes = false; + bNodes = false; + } }; enum AUTOWARE_STATE_TYPE {AW_INITIAL_STATE, AW_WAITING_STATE, AW_FORWARD_STATE, AW_STOPPING_STATE, AW_EMERGENCY_STATE, - AW_TRAFFIC_LIGHT_STOP_STATE, AW_STOP_SIGN_STOP_STATE, AW_FOLLOW_STATE, AW_LANE_CHANGE_STATE, AW_OBSTACLE_AVOIDANCE_STATE, AW_FINISH_STATE}; + AW_TRAFFIC_LIGHT_STOP_STATE, AW_STOP_SIGN_STOP_STATE, AW_FOLLOW_STATE, AW_LANE_CHANGE_STATE, AW_OBSTACLE_AVOIDANCE_STATE, AW_FINISH_STATE}; enum AUTOWARE_LIGHT_INDICATOR {AW_INDICATOR_LEFT, AW_INDICATOR_RIGHT, AW_INDICATOR_BOTH , AW_INDICATOR_NONE}; enum AUTOWARE_SHIFT_POS {AW_SHIFT_POS_PP = 0x60, AW_SHIFT_POS_RR = 0x40, AW_SHIFT_POS_NN = 0x20, - AW_SHIFT_POS_DD = 0x10, AW_SHIFT_POS_BB = 0xA0, AW_SHIFT_POS_SS = 0x0f, AW_SHIFT_POS_UU = 0xff }; + AW_SHIFT_POS_DD = 0x10, AW_SHIFT_POS_BB = 0xA0, AW_SHIFT_POS_SS = 0x0f, AW_SHIFT_POS_UU = 0xff }; class AutowareBehaviorState { public: - AUTOWARE_STATE_TYPE state; - double maxVelocity; - double minVelocity; - double stopDistance; - double followVelocity; - double followDistance; - AUTOWARE_LIGHT_INDICATOR indicator; - - AutowareBehaviorState() - { - state = AW_INITIAL_STATE; - maxVelocity = 0; - minVelocity = 0; - stopDistance = 0; - followVelocity = 0; - followDistance = 0; - indicator = AW_INDICATOR_NONE; - } + AUTOWARE_STATE_TYPE state; + double maxVelocity; + double minVelocity; + double stopDistance; + double followVelocity; + double followDistance; + AUTOWARE_LIGHT_INDICATOR indicator; + + AutowareBehaviorState() + { + state = AW_INITIAL_STATE; + maxVelocity = 0; + minVelocity = 0; + stopDistance = 0; + followVelocity = 0; + followDistance = 0; + indicator = AW_INDICATOR_NONE; + } }; class AutowareVehicleState { public: - double speed; - double steer; - AUTOWARE_SHIFT_POS shift; - - AutowareVehicleState() - { - speed = 0; - steer = 0; - shift = AW_SHIFT_POS_NN; - } + double speed; + double steer; + AUTOWARE_SHIFT_POS shift; + + AutowareVehicleState() + { + speed = 0; + steer = 0; + shift = AW_SHIFT_POS_NN; + } }; class AutowarePlanningParams { public: - double maxSpeed; - double minSpeed; - double planningDistance; - double microPlanDistance; - double carTipMargin; - double rollInMargin; - double rollInSpeedFactor; - double pathDensity; - double rollOutDensity; - int rollOutNumber; - double horizonDistance; - double minFollowingDistance; - double maxFollowingDistance; - double minDistanceToAvoid; - double speedProfileFactor; - - bool enableLaneChange; - bool enableSwerving; - bool enableFollowing; - bool enableHeadingSmoothing; - bool enableTrafficLightBehavior; - - AutowarePlanningParams() - { - maxSpeed = 3; - minSpeed = 0; - planningDistance = 10000; - microPlanDistance = 35; - carTipMargin = 8.0; - rollInMargin = 20.0; - rollInSpeedFactor = 0.25; - pathDensity = 0.25; - rollOutDensity = 0.5; - rollOutNumber = 4; - horizonDistance = 120; - minFollowingDistance = 35; - maxFollowingDistance = 40; - minDistanceToAvoid = 15; - speedProfileFactor = 1.0; - - enableHeadingSmoothing = false; - enableSwerving = false; - enableFollowing = false; - enableTrafficLightBehavior = false; - enableLaneChange = false; - } + double maxSpeed; + double minSpeed; + double planningDistance; + double microPlanDistance; + double carTipMargin; + double rollInMargin; + double rollInSpeedFactor; + double pathDensity; + double rollOutDensity; + int rollOutNumber; + double horizonDistance; + double minFollowingDistance; + double maxFollowingDistance; + double minDistanceToAvoid; + double speedProfileFactor; + + bool enableLaneChange; + bool enableSwerving; + bool enableFollowing; + bool enableHeadingSmoothing; + bool enableTrafficLightBehavior; + + AutowarePlanningParams() + { + maxSpeed = 3; + minSpeed = 0; + planningDistance = 10000; + microPlanDistance = 35; + carTipMargin = 8.0; + rollInMargin = 20.0; + rollInSpeedFactor = 0.25; + pathDensity = 0.25; + rollOutDensity = 0.5; + rollOutNumber = 4; + horizonDistance = 120; + minFollowingDistance = 35; + maxFollowingDistance = 40; + minDistanceToAvoid = 15; + speedProfileFactor = 1.0; + + enableHeadingSmoothing = false; + enableSwerving = false; + enableFollowing = false; + enableTrafficLightBehavior = false; + enableLaneChange = false; + } }; class ROSHelpers { public: - ROSHelpers(); - virtual ~ROSHelpers(); + ROSHelpers(); + virtual ~ROSHelpers(); - static void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform); + static void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform); - static void ConvertFromAutowareCloudClusterObstaclesToPlannerH(const PlannerHNS::WayPoint& currState, const double& car_width, - const double& car_length, const autoware_msgs::CloudClusterArray& clusters, - std::vector& impObstacles, const double max_obj_size, const double& min_obj_size, const double& detection_radius, - const int& n_poly_quarters,const double& poly_resolution, int& nOriginalPoints, int& nContourPoints); + static void ConvertFromAutowareCloudClusterObstaclesToPlannerH(const PlannerHNS::WayPoint& currState, const double& car_width, + const double& car_length, const autoware_msgs::CloudClusterArray& clusters, + std::vector& impObstacles, const double max_obj_size, const double& min_obj_size, const double& detection_radius, + const int& n_poly_quarters,const double& poly_resolution, int& nOriginalPoints, int& nContourPoints); - static visualization_msgs::Marker CreateGenMarker(const double& x, const double& y, const double& z,const double& a, - const double& r, const double& g, const double& b, const double& scale, const int& id, const std::string& ns, const int& type); + static visualization_msgs::Marker CreateGenMarker(const double& x, const double& y, const double& z,const double& a, + const double& r, const double& g, const double& b, const double& scale, const int& id, const std::string& ns, const int& type); - static void InitMatchingMarkers(const int& nMarkers, visualization_msgs::MarkerArray& connections); + static void InitMatchingMarkers(const int& nMarkers, visualization_msgs::MarkerArray& connections); - static void ConvertMatchingMarkers(const std::vector >& match_list, - visualization_msgs::MarkerArray& tracked_traj_d, visualization_msgs::MarkerArray& tracked_traj, int start_id=0); + static void ConvertMatchingMarkers(const std::vector >& match_list, + visualization_msgs::MarkerArray& tracked_traj_d, visualization_msgs::MarkerArray& tracked_traj, int start_id=0); - static void InitMarkers(const int& nMarkers, - visualization_msgs::MarkerArray& centers, - visualization_msgs::MarkerArray& dirs, - visualization_msgs::MarkerArray& text_info, - visualization_msgs::MarkerArray& polygons, - visualization_msgs::MarkerArray& trajectories); + static void InitMarkers(const int& nMarkers, + visualization_msgs::MarkerArray& centers, + visualization_msgs::MarkerArray& dirs, + visualization_msgs::MarkerArray& text_info, + visualization_msgs::MarkerArray& polygons, + visualization_msgs::MarkerArray& trajectories); - static int ConvertTrackedObjectsMarkers(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, - visualization_msgs::MarkerArray& centers_d, - visualization_msgs::MarkerArray& dirs_d, - visualization_msgs::MarkerArray& text_info_d, - visualization_msgs::MarkerArray& polygons_d, - visualization_msgs::MarkerArray& tracked_traj_d, - visualization_msgs::MarkerArray& centers, - visualization_msgs::MarkerArray& dirs, - visualization_msgs::MarkerArray& text_info, - visualization_msgs::MarkerArray& polygons, - visualization_msgs::MarkerArray& tracked_traj); + static int ConvertTrackedObjectsMarkers(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, + visualization_msgs::MarkerArray& centers_d, + visualization_msgs::MarkerArray& dirs_d, + visualization_msgs::MarkerArray& text_info_d, + visualization_msgs::MarkerArray& polygons_d, + visualization_msgs::MarkerArray& tracked_traj_d, + visualization_msgs::MarkerArray& centers, + visualization_msgs::MarkerArray& dirs, + visualization_msgs::MarkerArray& text_info, + visualization_msgs::MarkerArray& polygons, + visualization_msgs::MarkerArray& tracked_traj); - static void CreateCircleMarker(const PlannerHNS::WayPoint& _center, const double& radius, const int& start_id, visualization_msgs::Marker& circle_points); + static void CreateCircleMarker(const PlannerHNS::WayPoint& _center, const double& radius, const int& start_id, visualization_msgs::Marker& circle_points); - static void InitPredMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths); + static void InitPredMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths); - static void InitCurbsMarkers(const int& nMarkers, visualization_msgs::MarkerArray& curbs); + static void InitCurbsMarkers(const int& nMarkers, visualization_msgs::MarkerArray& curbs); - static void ConvertPredictedTrqajectoryMarkers(std::vector >& paths,visualization_msgs::MarkerArray& path_markers, visualization_msgs::MarkerArray& path_markers_d); + static void ConvertPredictedTrajectoriesMarkers(std::vector >& paths,visualization_msgs::MarkerArray& path_markers, visualization_msgs::MarkerArray& path_markers_d); - static void ConvertCurbsMarkers(const std::vector& curbs, visualization_msgs::MarkerArray& curbs_markers, visualization_msgs::MarkerArray& curbs_markers_d); + static void ConvertCurbsMarkers(const std::vector& curbs, visualization_msgs::MarkerArray& curbs_markers, visualization_msgs::MarkerArray& curbs_markers_d); - static void TrajectoriesToMarkers(const std::vector > >& paths, visualization_msgs::MarkerArray& markerArray); + static void TrajectoriesToMarkers(const std::vector > >& paths, visualization_msgs::MarkerArray& markerArray); - static void TrajectoriesToColoredMarkers(const std::vector >& paths,const std::vector& traj_costs, const int& iClosest, visualization_msgs::MarkerArray& markerArray); + static void TrajectoriesToColoredMarkers(const std::vector >& paths,const std::vector& traj_costs, const int& iClosest, visualization_msgs::MarkerArray& markerArray); - static void InitCollisionPointsMarkers(const int& nMarkers, visualization_msgs::MarkerArray& col_points); + static void InitCollisionPointsMarkers(const int& nMarkers, visualization_msgs::MarkerArray& col_points); - static void ConvertCollisionPointsMarkers(const std::vector& col_pointss, visualization_msgs::MarkerArray& collision_markers, visualization_msgs::MarkerArray& collision_markers_d); + static void ConvertCollisionPointsMarkers(const std::vector& col_pointss, visualization_msgs::MarkerArray& collision_markers, visualization_msgs::MarkerArray& collision_markers_d); - static void InitPredParticlesMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths); + static void InitPredParticlesMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths); - static void ConvertParticles(std::vector& points, visualization_msgs::MarkerArray& part_mkrs, visualization_msgs::MarkerArray& part_markers_d); + static void ConvertParticles(std::vector& points, visualization_msgs::MarkerArray& part_mkrs, visualization_msgs::MarkerArray& part_markers_d); - static void ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, const int& iStart, - autoware_msgs::Lane & trajectory); + static void ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, const int& iStart, + autoware_msgs::Lane & trajectory); - static void ConvertFromPlannerHRectangleToAutowareRviz(const std::vector& safety_rect, - visualization_msgs::Marker& marker); + static void ConvertFromPlannerHRectangleToAutowareRviz(const std::vector& safety_rect, + visualization_msgs::Marker& marker); - static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, - const std::vector > >& paths, const PlannerHNS::LocalPlannerH& localPlanner, - visualization_msgs::MarkerArray& markerArray); + static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, + const std::vector > >& paths, const PlannerHNS::LocalPlannerH& localPlanner, + visualization_msgs::MarkerArray& markerArray); - static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector >& globalPaths, visualization_msgs::MarkerArray& markerArray); + static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector >& globalPaths, visualization_msgs::MarkerArray& markerArray); - static void ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray); + static void ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray); - static void ConvertFromAutowareBoundingBoxObstaclesToPlannerH(const jsk_recognition_msgs::BoundingBoxArray& detectedObstacles, - std::vector& impObstacles); + static void ConvertFromAutowareBoundingBoxObstaclesToPlannerH(const jsk_recognition_msgs::BoundingBoxArray& detectedObstacles, + std::vector& impObstacles); - static void ConvertFromPlannerObstaclesToAutoware(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, - visualization_msgs::MarkerArray& detectedPolygons); + static void ConvertFromPlannerObstaclesToAutoware(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, + visualization_msgs::MarkerArray& detectedPolygons); - static void ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory , const unsigned int& iStart = 0); + static void ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory , const unsigned int& iStart = 0); - static void ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory); + static void ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory); - static void ConvertFromAutowareLaneToLocalLane(const autoware_msgs::Lane& trajectory, std::vector& path); + static void ConvertFromAutowareLaneToLocalLane(const autoware_msgs::Lane& trajectory, std::vector& path); - static void createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray); - static void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array , visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array , visualization_msgs::MarkerArray& markerArray); - static void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array , visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array , visualization_msgs::MarkerArray& markerArray); - static void GetTrafficLightForVisualization(std::vector& lights, visualization_msgs::MarkerArray& markerArray); + static void GetTrafficLightForVisualization(std::vector& lights, visualization_msgs::MarkerArray& markerArray); - static void ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(const autoware_msgs::DetectedObject& det_obj, PlannerHNS::DetectedObject& obj); + static void ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(const autoware_msgs::DetectedObject& det_obj, PlannerHNS::DetectedObject& obj); - static void ConvertFromOpenPlannerDetectedObjectToAutowareDetectedObject(const PlannerHNS::DetectedObject& det_obj, const bool& bSimulationMode, autoware_msgs::DetectedObject& obj); + static void ConvertFromOpenPlannerDetectedObjectToAutowareDetectedObject(const PlannerHNS::DetectedObject& det_obj, const bool& bSimulationMode, autoware_msgs::DetectedObject& obj); - static PlannerHNS::SHIFT_POS ConvertShiftFromAutowareToPlannerH(const PlannerHNS::AUTOWARE_SHIFT_POS& shift); + static PlannerHNS::SHIFT_POS ConvertShiftFromAutowareToPlannerH(const PlannerHNS::AUTOWARE_SHIFT_POS& shift); - static PlannerHNS::AUTOWARE_SHIFT_POS ConvertShiftFromPlannerHToAutoware(const PlannerHNS::SHIFT_POS& shift); + static PlannerHNS::AUTOWARE_SHIFT_POS ConvertShiftFromPlannerHToAutoware(const PlannerHNS::SHIFT_POS& shift); - static PlannerHNS::AutowareBehaviorState ConvertBehaviorStateFromPlannerHToAutoware(const PlannerHNS::BehaviorState& beh); + static PlannerHNS::AutowareBehaviorState ConvertBehaviorStateFromPlannerHToAutoware(const PlannerHNS::BehaviorState& beh); - static std::string GetBehaviorNameFromCode(const PlannerHNS::STATE_TYPE& behState); + static std::string GetBehaviorNameFromCode(const PlannerHNS::STATE_TYPE& behState); - static void VisualizeBehaviorState(const PlannerHNS::WayPoint& currState, const PlannerHNS::BehaviorState& beh, const bool& bGreenLight, const int& avoidDirection, visualization_msgs::Marker& behaviorMarker, std::string ns,double size_factor = 1); + static void VisualizeBehaviorState(const PlannerHNS::WayPoint& currState, const PlannerHNS::BehaviorState& beh, const bool& bGreenLight, const int& avoidDirection, visualization_msgs::Marker& behaviorMarker, std::string ns,double size_factor = 1); - static void UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map); + static void UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map); - static void GetIndicatorArrows(const PlannerHNS::WayPoint& center, const double& width,const double& length, const PlannerHNS::LIGHT_INDICATOR& indicator, const int& id,visualization_msgs::MarkerArray& markerArray); + static void GetIndicatorArrows(const PlannerHNS::WayPoint& center, const double& width,const double& length, const PlannerHNS::LIGHT_INDICATOR& indicator, const int& id,visualization_msgs::MarkerArray& markerArray); - static void TTC_PathRviz(const std::vector& path, visualization_msgs::MarkerArray& markerArray); + static void TTC_PathRviz(const std::vector& path, visualization_msgs::MarkerArray& markerArray); }; } diff --git a/common/op_ros_helpers/src/PolygonGenerator.cpp b/common/op_ros_helpers/src/PolygonGenerator.cpp index b9df47c8ee6..84e5cb40b8e 100644 --- a/common/op_ros_helpers/src/PolygonGenerator.cpp +++ b/common/op_ros_helpers/src/PolygonGenerator.cpp @@ -11,7 +11,7 @@ namespace PlannerHNS PolygonGenerator::PolygonGenerator(int nQuarters) { - m_Quarters = CreateQuarterViews(nQuarters); + m_Quarters = CreateQuarterViews(nQuarters); } PolygonGenerator::~PolygonGenerator() @@ -20,93 +20,93 @@ PolygonGenerator::~PolygonGenerator() std::vector PolygonGenerator::EstimateClusterPolygon(const pcl::PointCloud& cluster, const GPSPoint& original_centroid, GPSPoint& new_centroid, const double& polygon_resolution) { - for(unsigned int i=0; i < m_Quarters.size(); i++) - m_Quarters.at(i).ResetQuarterView(); - - WayPoint p; - for(unsigned int i=0; i< cluster.points.size(); i++) - { - p.pos.x = cluster.points.at(i).x; - p.pos.y = cluster.points.at(i).y; - p.pos.z = original_centroid.z; - - GPSPoint v(p.pos.x - original_centroid.x , p.pos.y - original_centroid.y, 0, 0); - p.cost = pointNorm(v); - p.pos.a = UtilityHNS::UtilityH::FixNegativeAngle(atan2(v.y, v.x))*(180. / M_PI); - - for(unsigned int j = 0 ; j < m_Quarters.size(); j++) - { - if(m_Quarters.at(j).UpdateQuarterView(p)) - break; - } - } - - m_Polygon.clear(); - WayPoint wp; - for(unsigned int j = 0 ; j < m_Quarters.size(); j++) - { - if(m_Quarters.at(j).GetMaxPoint(wp)) - m_Polygon.push_back(wp.pos); - } - -// //Fix Resolution: - bool bChange = true; - while (bChange && m_Polygon.size()>1) - { - bChange = false; - GPSPoint p1 = m_Polygon.at(m_Polygon.size()-1); - for(unsigned int i=0; i< m_Polygon.size(); i++) - { - GPSPoint p2 = m_Polygon.at(i); - double d = hypot(p2.y- p1.y, p2.x - p1.x); - if(d > polygon_resolution) - { - GPSPoint center_p = p1; - center_p.x = (p2.x + p1.x)/2.0; - center_p.y = (p2.y + p1.y)/2.0; - m_Polygon.insert(m_Polygon.begin()+i, center_p); - bChange = true; - break; - } - - p1 = p2; - } - } - GPSPoint sum_p; - for(unsigned int i = 0 ; i< m_Polygon.size(); i++) - { - sum_p.x += m_Polygon.at(i).x; - sum_p.y += m_Polygon.at(i).y; - } - - new_centroid = original_centroid; - - if(m_Polygon.size() > 0) - { - new_centroid.x = sum_p.x / (double)m_Polygon.size(); - new_centroid.y = sum_p.y / (double)m_Polygon.size(); - } - - return m_Polygon; + for(unsigned int i=0; i < m_Quarters.size(); i++) + m_Quarters.at(i).ResetQuarterView(); + + WayPoint p; + for(unsigned int i=0; i< cluster.points.size(); i++) + { + p.pos.x = cluster.points.at(i).x; + p.pos.y = cluster.points.at(i).y; + p.pos.z = original_centroid.z; + + GPSPoint v(p.pos.x - original_centroid.x , p.pos.y - original_centroid.y, 0, 0); + p.cost = pointNorm(v); + p.pos.a = UtilityHNS::UtilityH::FixNegativeAngle(atan2(v.y, v.x))*(180. / M_PI); + + for(unsigned int j = 0 ; j < m_Quarters.size(); j++) + { + if(m_Quarters.at(j).UpdateQuarterView(p)) + break; + } + } + + m_Polygon.clear(); + WayPoint wp; + for(unsigned int j = 0 ; j < m_Quarters.size(); j++) + { + if(m_Quarters.at(j).GetMaxPoint(wp)) + m_Polygon.push_back(wp.pos); + } + +// //Fix Resolution: + bool bChange = true; + while (bChange && m_Polygon.size()>1) + { + bChange = false; + GPSPoint p1 = m_Polygon.at(m_Polygon.size()-1); + for(unsigned int i=0; i< m_Polygon.size(); i++) + { + GPSPoint p2 = m_Polygon.at(i); + double d = hypot(p2.y- p1.y, p2.x - p1.x); + if(d > polygon_resolution) + { + GPSPoint center_p = p1; + center_p.x = (p2.x + p1.x)/2.0; + center_p.y = (p2.y + p1.y)/2.0; + m_Polygon.insert(m_Polygon.begin()+i, center_p); + bChange = true; + break; + } + + p1 = p2; + } + } + GPSPoint sum_p; + for(unsigned int i = 0 ; i< m_Polygon.size(); i++) + { + sum_p.x += m_Polygon.at(i).x; + sum_p.y += m_Polygon.at(i).y; + } + + new_centroid = original_centroid; + + if(m_Polygon.size() > 0) + { + new_centroid.x = sum_p.x / (double)m_Polygon.size(); + new_centroid.y = sum_p.y / (double)m_Polygon.size(); + } + + return m_Polygon; } std::vector PolygonGenerator::CreateQuarterViews(const int& nResolution) { - std::vector quarters; - if(nResolution <= 0) - return quarters; - - double range = 360.0 / nResolution; - double angle = 0; - for(int i = 0; i < nResolution; i++) - { - QuarterView q(angle, angle+range, i); - quarters.push_back(q); - angle+=range; - } - - return quarters; + std::vector quarters; + if(nResolution <= 0) + return quarters; + + double range = 360.0 / nResolution; + double angle = 0; + for(int i = 0; i < nResolution; i++) + { + QuarterView q(angle, angle+range, i); + quarters.push_back(q); + angle+=range; + } + + return quarters; } } /* namespace PlannerXNS */ diff --git a/common/op_ros_helpers/src/op_ROSHelpers.cpp b/common/op_ros_helpers/src/op_ROSHelpers.cpp index 068efbae2cc..e3d0cc55945 100644 --- a/common/op_ros_helpers/src/op_ROSHelpers.cpp +++ b/common/op_ros_helpers/src/op_ROSHelpers.cpp @@ -26,1374 +26,1374 @@ ROSHelpers::~ROSHelpers() { void ROSHelpers::GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform) { - static tf::TransformListener listener; - - int nFailedCounter = 0; - while (1) - { - try - { - listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); - break; - } - catch (tf::TransformException& ex) - { - if(nFailedCounter > 2) - { - ROS_ERROR("%s", ex.what()); - } - ros::Duration(1.0).sleep(); - nFailedCounter ++; - } - } + static tf::TransformListener listener; + + int nFailedCounter = 0; + while (1) + { + try + { + listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); + break; + } + catch (tf::TransformException& ex) + { + if(nFailedCounter > 2) + { + ROS_ERROR("%s", ex.what()); + } + ros::Duration(1.0).sleep(); + nFailedCounter ++; + } + } } visualization_msgs::Marker ROSHelpers::CreateGenMarker(const double& x, const double& y, const double& z,const double& a, - const double& r, const double& g, const double& b, const double& scale, const int& id, const std::string& ns, const int& type) + const double& r, const double& g, const double& b, const double& scale, const int& id, const std::string& ns, const int& type) { - visualization_msgs::Marker mkr; - mkr.header.frame_id = "map"; - mkr.header.stamp = ros::Time(); - mkr.ns = ns; - mkr.type = type; - mkr.action = visualization_msgs::Marker::ADD; - mkr.scale.x = scale; - mkr.scale.y = scale; - mkr.scale.z = scale; - mkr.color.a = 0.8; - mkr.color.r = r; - mkr.color.g = g; - mkr.color.b = b; - mkr.pose.position.x = x; - mkr.pose.position.y = y; - mkr.pose.position.z = z; - mkr.pose.orientation = tf::createQuaternionMsgFromYaw(a); - mkr.id = id; - return mkr; + visualization_msgs::Marker mkr; + mkr.header.frame_id = "map"; + mkr.header.stamp = ros::Time(); + mkr.ns = ns; + mkr.type = type; + mkr.action = visualization_msgs::Marker::ADD; + mkr.scale.x = scale; + mkr.scale.y = scale; + mkr.scale.z = scale; + mkr.color.a = 0.8; + mkr.color.r = r; + mkr.color.g = g; + mkr.color.b = b; + mkr.pose.position.x = x; + mkr.pose.position.y = y; + mkr.pose.position.z = z; + mkr.pose.orientation = tf::createQuaternionMsgFromYaw(a); + mkr.id = id; + return mkr; } void ROSHelpers::InitMarkers(const int& nMarkers, - visualization_msgs::MarkerArray& centers, - visualization_msgs::MarkerArray& dirs, - visualization_msgs::MarkerArray& text_info, - visualization_msgs::MarkerArray& polygons, - visualization_msgs::MarkerArray& trajectories) + visualization_msgs::MarkerArray& centers, + visualization_msgs::MarkerArray& dirs, + visualization_msgs::MarkerArray& text_info, + visualization_msgs::MarkerArray& polygons, + visualization_msgs::MarkerArray& trajectories) { - centers.markers.clear(); - dirs.markers.clear(); - text_info.markers.clear(); - polygons.markers.clear(); - trajectories.markers.clear(); - - for(int i=0; i >& match_list, - visualization_msgs::MarkerArray& tracked_traj_d, visualization_msgs::MarkerArray& tracked_traj, int start_id) + visualization_msgs::MarkerArray& tracked_traj_d, visualization_msgs::MarkerArray& tracked_traj, int start_id) { - tracked_traj = tracked_traj_d; - - for(unsigned int i = 0; i < match_list.size(); i++) - { - visualization_msgs::Marker match_mkr = CreateGenMarker(0,0,0,0,1,0,0,0.2, start_id+i,"matching_connections", visualization_msgs::Marker::LINE_STRIP); - geometry_msgs::Point point; - point.x = match_list.at(i).first.pos.x; - point.y = match_list.at(i).first.pos.y; - point.z = match_list.at(i).first.pos.z; - match_mkr.points.push_back(point); - - point.x = match_list.at(i).second.pos.x; - point.y = match_list.at(i).second.pos.y; - point.z = match_list.at(i).second.pos.z; - match_mkr.points.push_back(point); - - if(i < tracked_traj.markers.size()) - tracked_traj.markers.at(i) = match_mkr; - else - tracked_traj.markers.push_back(match_mkr); - } + tracked_traj = tracked_traj_d; + + for(unsigned int i = 0; i < match_list.size(); i++) + { + visualization_msgs::Marker match_mkr = CreateGenMarker(0,0,0,0,1,0,0,0.2, start_id+i,"matching_connections", visualization_msgs::Marker::LINE_STRIP); + geometry_msgs::Point point; + point.x = match_list.at(i).first.pos.x; + point.y = match_list.at(i).first.pos.y; + point.z = match_list.at(i).first.pos.z; + match_mkr.points.push_back(point); + + point.x = match_list.at(i).second.pos.x; + point.y = match_list.at(i).second.pos.y; + point.z = match_list.at(i).second.pos.z; + match_mkr.points.push_back(point); + + if(i < tracked_traj.markers.size()) + tracked_traj.markers.at(i) = match_mkr; + else + tracked_traj.markers.push_back(match_mkr); + } } int ROSHelpers::ConvertTrackedObjectsMarkers(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, - visualization_msgs::MarkerArray& centers_d, - visualization_msgs::MarkerArray& dirs_d, - visualization_msgs::MarkerArray& text_info_d, - visualization_msgs::MarkerArray& polygons_d, - visualization_msgs::MarkerArray& tracked_traj_d, - visualization_msgs::MarkerArray& centers, - visualization_msgs::MarkerArray& dirs, - visualization_msgs::MarkerArray& text_info, - visualization_msgs::MarkerArray& polygons, - visualization_msgs::MarkerArray& tracked_traj) + visualization_msgs::MarkerArray& centers_d, + visualization_msgs::MarkerArray& dirs_d, + visualization_msgs::MarkerArray& text_info_d, + visualization_msgs::MarkerArray& polygons_d, + visualization_msgs::MarkerArray& tracked_traj_d, + visualization_msgs::MarkerArray& centers, + visualization_msgs::MarkerArray& dirs, + visualization_msgs::MarkerArray& text_info, + visualization_msgs::MarkerArray& polygons, + visualization_msgs::MarkerArray& tracked_traj) { - int i_next_id = 0; - centers = centers_d; - dirs = dirs_d; - text_info = text_info_d; - polygons = polygons_d; - tracked_traj = tracked_traj_d; - - for(unsigned int i =0; i < trackedObstacles.size(); i++) - { - int speed = (trackedObstacles.at(i).center.v*3.6); - - //Update Stage - visualization_msgs::Marker center_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x,trackedObstacles.at(i).center.pos.y,trackedObstacles.at(i).center.pos.z, - trackedObstacles.at(i).center.pos.a,1,0,0,0.5,i,"CenterMarker", visualization_msgs::Marker::SPHERE); - if(i < centers.markers.size()) - { - center_mkr.id = centers.markers.at(i).id; - centers.markers.at(i) = center_mkr; - } - else - centers.markers.push_back(center_mkr); - - //Directions - if(trackedObstacles.at(i).bDirection) - { - visualization_msgs::Marker dir_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x,trackedObstacles.at(i).center.pos.y,trackedObstacles.at(i).center.pos.z+0.5, - trackedObstacles.at(i).center.pos.a,0,1,0,0.3,centers.markers.size()+i,"Directions", visualization_msgs::Marker::ARROW); - dir_mkr.scale.x = 0.4; - if(i < dirs.markers.size()) - { - dir_mkr.id = dirs.markers.at(i).id; - dirs.markers.at(i) = dir_mkr; - } - else - dirs.markers.push_back(dir_mkr); - } - - - //Text - visualization_msgs::Marker text_mkr; -// if(speed > 3.0) -// text_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x+0.5,trackedObstacles.at(i).center.pos.y+0.5,trackedObstacles.at(i).center.pos.z+1, -// trackedObstacles.at(i).center.pos.a,1,0,0,0.75,centers.markers.size()*2+i,"InfoText", visualization_msgs::Marker::TEXT_VIEW_FACING); -// else - text_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x+0.5,trackedObstacles.at(i).center.pos.y+0.5,trackedObstacles.at(i).center.pos.z+1, - trackedObstacles.at(i).center.pos.a,1,1,1,1.2,centers.markers.size()*2+i,"InfoText", visualization_msgs::Marker::TEXT_VIEW_FACING); - - std::ostringstream str_out; - //str_out << trackedObstacles.at(i).id << " ( " << speed << " )" << " (" << trackedObstacles.at(i).distance_to_center << ")"; - str_out << trackedObstacles.at(i).id << " (" << speed << ")"; - text_mkr.text = str_out.str(); - - if(i < text_info.markers.size()) - { - text_mkr.id = text_info.markers.at(i).id; - text_info.markers.at(i) = text_mkr; - } - else - text_info.markers.push_back(text_mkr); - - - //Polygons - visualization_msgs::Marker poly_mkr = CreateGenMarker(0,0,0,0, 1,0.25,0.25,0.1,centers.markers.size()*3+i,"detected_polygons", visualization_msgs::Marker::LINE_STRIP); - - for(unsigned int p = 0; p < trackedObstacles.at(i).contour.size(); p++) - { - geometry_msgs::Point point; - point.x = trackedObstacles.at(i).contour.at(p).x; - point.y = trackedObstacles.at(i).contour.at(p).y; - point.z = trackedObstacles.at(i).contour.at(p).z; - poly_mkr.points.push_back(point); - } - - if(trackedObstacles.at(i).contour.size()>0) - { - geometry_msgs::Point point; - point.x = trackedObstacles.at(i).contour.at(0).x; - point.y = trackedObstacles.at(i).contour.at(0).y; - point.z = trackedObstacles.at(i).contour.at(0).z; - poly_mkr.points.push_back(point); - } - - if(i < polygons.markers.size()) - { - poly_mkr.id = polygons.markers.at(i).id; - polygons.markers.at(i) = poly_mkr; - } - else - polygons.markers.push_back(poly_mkr); - - - //Trajectories - visualization_msgs::Marker traj_mkr = CreateGenMarker(0,0,0,0,1,1,0,0.1,centers.markers.size()*4+i,"tracked_trajectories", visualization_msgs::Marker::LINE_STRIP); - - for(unsigned int p = 0; p < trackedObstacles.at(i).centers_list.size(); p++) - { - geometry_msgs::Point point; - point.x = trackedObstacles.at(i).centers_list.at(p).pos.x; - point.y = trackedObstacles.at(i).centers_list.at(p).pos.y; - point.z = trackedObstacles.at(i).centers_list.at(p).pos.z; - traj_mkr.points.push_back(point); - } - - - if(i < tracked_traj.markers.size()) - { - traj_mkr.id = tracked_traj.markers.at(i).id ; - tracked_traj.markers.at(i) = traj_mkr; - } - else - tracked_traj.markers.push_back(traj_mkr); - - i_next_id = traj_mkr.id; - - } - - return i_next_id +1; + int i_next_id = 0; + centers = centers_d; + dirs = dirs_d; + text_info = text_info_d; + polygons = polygons_d; + tracked_traj = tracked_traj_d; + + for(unsigned int i =0; i < trackedObstacles.size(); i++) + { + int speed = (trackedObstacles.at(i).center.v*3.6); + + //Update Stage + visualization_msgs::Marker center_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x,trackedObstacles.at(i).center.pos.y,trackedObstacles.at(i).center.pos.z, + trackedObstacles.at(i).center.pos.a,1,0,0,0.5,i,"CenterMarker", visualization_msgs::Marker::SPHERE); + if(i < centers.markers.size()) + { + center_mkr.id = centers.markers.at(i).id; + centers.markers.at(i) = center_mkr; + } + else + centers.markers.push_back(center_mkr); + + //Directions + if(trackedObstacles.at(i).bDirection) + { + visualization_msgs::Marker dir_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x,trackedObstacles.at(i).center.pos.y,trackedObstacles.at(i).center.pos.z+0.5, + trackedObstacles.at(i).center.pos.a,0,1,0,0.3,centers.markers.size()+i,"Directions", visualization_msgs::Marker::ARROW); + dir_mkr.scale.x = 0.4; + if(i < dirs.markers.size()) + { + dir_mkr.id = dirs.markers.at(i).id; + dirs.markers.at(i) = dir_mkr; + } + else + dirs.markers.push_back(dir_mkr); + } + + + //Text + visualization_msgs::Marker text_mkr; +// if(speed > 3.0) +// text_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x+0.5,trackedObstacles.at(i).center.pos.y+0.5,trackedObstacles.at(i).center.pos.z+1, +// trackedObstacles.at(i).center.pos.a,1,0,0,0.75,centers.markers.size()*2+i,"InfoText", visualization_msgs::Marker::TEXT_VIEW_FACING); +// else + text_mkr = CreateGenMarker(trackedObstacles.at(i).center.pos.x+0.5,trackedObstacles.at(i).center.pos.y+0.5,trackedObstacles.at(i).center.pos.z+1, + trackedObstacles.at(i).center.pos.a,1,1,1,1.2,centers.markers.size()*2+i,"InfoText", visualization_msgs::Marker::TEXT_VIEW_FACING); + + std::ostringstream str_out; + //str_out << trackedObstacles.at(i).id << " ( " << speed << " )" << " (" << trackedObstacles.at(i).distance_to_center << ")"; + str_out << trackedObstacles.at(i).id << " (" << speed << ")"; + text_mkr.text = str_out.str(); + + if(i < text_info.markers.size()) + { + text_mkr.id = text_info.markers.at(i).id; + text_info.markers.at(i) = text_mkr; + } + else + text_info.markers.push_back(text_mkr); + + + //Polygons + visualization_msgs::Marker poly_mkr = CreateGenMarker(0,0,0,0, 1,0.25,0.25,0.1,centers.markers.size()*3+i,"detected_polygons", visualization_msgs::Marker::LINE_STRIP); + + for(unsigned int p = 0; p < trackedObstacles.at(i).contour.size(); p++) + { + geometry_msgs::Point point; + point.x = trackedObstacles.at(i).contour.at(p).x; + point.y = trackedObstacles.at(i).contour.at(p).y; + point.z = trackedObstacles.at(i).contour.at(p).z; + poly_mkr.points.push_back(point); + } + + if(trackedObstacles.at(i).contour.size()>0) + { + geometry_msgs::Point point; + point.x = trackedObstacles.at(i).contour.at(0).x; + point.y = trackedObstacles.at(i).contour.at(0).y; + point.z = trackedObstacles.at(i).contour.at(0).z; + poly_mkr.points.push_back(point); + } + + if(i < polygons.markers.size()) + { + poly_mkr.id = polygons.markers.at(i).id; + polygons.markers.at(i) = poly_mkr; + } + else + polygons.markers.push_back(poly_mkr); + + + //Trajectories + visualization_msgs::Marker traj_mkr = CreateGenMarker(0,0,0,0,1,1,0,0.1,centers.markers.size()*4+i,"tracked_trajectories", visualization_msgs::Marker::LINE_STRIP); + + for(unsigned int p = 0; p < trackedObstacles.at(i).centers_list.size(); p++) + { + geometry_msgs::Point point; + point.x = trackedObstacles.at(i).centers_list.at(p).pos.x; + point.y = trackedObstacles.at(i).centers_list.at(p).pos.y; + point.z = trackedObstacles.at(i).centers_list.at(p).pos.z; + traj_mkr.points.push_back(point); + } + + + if(i < tracked_traj.markers.size()) + { + traj_mkr.id = tracked_traj.markers.at(i).id ; + tracked_traj.markers.at(i) = traj_mkr; + } + else + tracked_traj.markers.push_back(traj_mkr); + + i_next_id = traj_mkr.id; + + } + + return i_next_id +1; } void ROSHelpers::CreateCircleMarker(const PlannerHNS::WayPoint& _center, const double& radius, const int& start_id, visualization_msgs::Marker& circle_points) { - circle_points = CreateGenMarker(0,0,0,0,1,1,1,0.2,start_id,"Detection_Circles", visualization_msgs::Marker::LINE_STRIP); - for (float i = 0; i < M_PI*2.0+0.05; i+=0.05) - { - geometry_msgs::Point point; - point.x = _center.pos.x + (radius * cos(i)); - point.y = _center.pos.y + (radius * sin(i)); - point.z = _center.pos.z; - circle_points.points.push_back(point); - } + circle_points = CreateGenMarker(0,0,0,0,1,1,1,0.2,start_id,"Detection_Circles", visualization_msgs::Marker::LINE_STRIP); + for (float i = 0; i < M_PI*2.0+0.05; i+=0.05) + { + geometry_msgs::Point point; + point.x = _center.pos.x + (radius * cos(i)); + point.y = _center.pos.y + (radius * sin(i)); + point.z = _center.pos.z; + circle_points.points.push_back(point); + } } void ROSHelpers::InitPredMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths) { - paths.markers.clear(); - for(int i=0; i >& paths,visualization_msgs::MarkerArray& path_markers, visualization_msgs::MarkerArray& path_markers_d) +void ROSHelpers::ConvertPredictedTrajectoriesMarkers(std::vector >& paths,visualization_msgs::MarkerArray& path_markers, visualization_msgs::MarkerArray& path_markers_d) { - path_markers = path_markers_d; - for(unsigned int i = 0; i < paths.size(); i++) - { - double additional_z = 0; - double basic_color = 0.5; - double prop = 1.0; - bool bCurrent = false; -// if(paths.at(i).size()>0) -// { + path_markers = path_markers_d; + for(unsigned int i = 0; i < paths.size(); i++) + { + double additional_z = 0; + double basic_color = 0.5; + double prop = 1.0; + bool bCurrent = false; +// if(paths.at(i).size()>0) +// { // -// prop = paths.at(i).at(0).collisionCost; -// if(prop < 0.5) -// continue; +// prop = paths.at(i).at(0).collisionCost; +// if(prop < 0.5) +// continue; // -// if(prop > 0.5) -// { -// additional_z = prop; -// bCurrent = true; -// } -// } - - -// double r = 0, g = 0, b = 0; -// if(bCurrent == true) -// { -// r = basic_color+additional_z; -// g = basic_color+additional_z; -// b = basic_color+additional_z; -// } -// else if(i == 0) -// { -// r = basic_color+additional_z; -// } -// else if(i == 1) -// { -// g = basic_color+additional_z; -// } -// else if(i == 2) -// { -// b = basic_color+additional_z; -// } -// else if(i == 3) -// { -// r = basic_color+additional_z; -// b = basic_color+additional_z; -// } -// else -// { -// g = basic_color+additional_z; -// b = basic_color+additional_z; -// } +// if(prop > 0.5) +// { +// additional_z = prop; +// bCurrent = true; +// } +// } + + +// double r = 0, g = 0, b = 0; +// if(bCurrent == true) +// { +// r = basic_color+additional_z; +// g = basic_color+additional_z; +// b = basic_color+additional_z; +// } +// else if(i == 0) +// { +// r = basic_color+additional_z; +// } +// else if(i == 1) +// { +// g = basic_color+additional_z; +// } +// else if(i == 2) +// { +// b = basic_color+additional_z; +// } +// else if(i == 3) +// { +// r = basic_color+additional_z; +// b = basic_color+additional_z; +// } +// else +// { +// g = basic_color+additional_z; +// b = basic_color+additional_z; +// } // -// visualization_msgs::Marker path_mkr = CreateGenMarker(0,0,0,0,r,g,b,0.1,i,"Predicted_Trajectories", visualization_msgs::Marker::LINE_STRIP); +// visualization_msgs::Marker path_mkr = CreateGenMarker(0,0,0,0,r,g,b,0.1,i,"Predicted_Trajectories", visualization_msgs::Marker::LINE_STRIP); - visualization_msgs::Marker path_mkr = CreateGenMarker(0,0,0,0,1.0*prop,0.1*prop,0.1*prop,0.1,i,"Predicted_Trajectories", visualization_msgs::Marker::LINE_STRIP); + visualization_msgs::Marker path_mkr = CreateGenMarker(0,0,0,0,1.0*prop,0.1*prop,0.1*prop,0.1,i,"Predicted_Trajectories", visualization_msgs::Marker::LINE_STRIP); - for(unsigned int p = 0; p < paths.at(i).size(); p++) - { - geometry_msgs::Point point; - point.x = paths.at(i).at(p).pos.x; - point.y = paths.at(i).at(p).pos.y; - point.z = paths.at(i).at(p).pos.z + additional_z; - path_mkr.points.push_back(point); - } + for(unsigned int p = 0; p < paths.at(i).size(); p++) + { + geometry_msgs::Point point; + point.x = paths.at(i).at(p).pos.x; + point.y = paths.at(i).at(p).pos.y; + point.z = paths.at(i).at(p).pos.z + additional_z; + path_mkr.points.push_back(point); + } - if(i < path_markers.markers.size()) - path_markers.markers.at(i) = path_mkr; - else - path_markers.markers.push_back(path_mkr); - } + if(i < path_markers.markers.size()) + path_markers.markers.at(i) = path_mkr; + else + path_markers.markers.push_back(path_mkr); + } } void ROSHelpers::ConvertCurbsMarkers(const std::vector& curbs, visualization_msgs::MarkerArray& curbs_markers, visualization_msgs::MarkerArray& curbs_markers_d) { - curbs_markers = curbs_markers_d; - for(unsigned int i = 0; i < curbs.size(); i++) - { - if(curbs.at(i).contour.size() > 0) - { - visualization_msgs::Marker curb_mkr = CreateGenMarker(curbs.at(i).contour.at(0).x,curbs.at(i).contour.at(0).y,curbs.at(i).contour.at(0).z,0,1,0.54,0,0.2,i,"map_detected_curbs", visualization_msgs::Marker::SPHERE); - - if(i < curbs_markers.markers.size()) - curbs_markers.markers.at(i) = curb_mkr; - else - curbs_markers.markers.push_back(curb_mkr); - } - } + curbs_markers = curbs_markers_d; + for(unsigned int i = 0; i < curbs.size(); i++) + { + if(curbs.at(i).contour.size() > 0) + { + visualization_msgs::Marker curb_mkr = CreateGenMarker(curbs.at(i).contour.at(0).x,curbs.at(i).contour.at(0).y,curbs.at(i).contour.at(0).z,0,1,0.54,0,0.2,i,"map_detected_curbs", visualization_msgs::Marker::SPHERE); + + if(i < curbs_markers.markers.size()) + curbs_markers.markers.at(i) = curb_mkr; + else + curbs_markers.markers.push_back(curb_mkr); + } + } } void ROSHelpers::InitCollisionPointsMarkers(const int& nMarkers, visualization_msgs::MarkerArray& col_points) { - col_points.markers.clear(); - for(int i=0; i& col_points, visualization_msgs::MarkerArray& collision_markers, visualization_msgs::MarkerArray& collision_markers_d) { - collision_markers = collision_markers_d; - for(unsigned int i = 0; i < col_points.size(); i++) - { - visualization_msgs::Marker mkr = CreateGenMarker(col_points.at(i).pos.x, col_points.at(i).pos.y, col_points.at(i).pos.z,0,1,0,0,0.5,i,"collision_points_rviz", visualization_msgs::Marker::SPHERE); + collision_markers = collision_markers_d; + for(unsigned int i = 0; i < col_points.size(); i++) + { + visualization_msgs::Marker mkr = CreateGenMarker(col_points.at(i).pos.x, col_points.at(i).pos.y, col_points.at(i).pos.z,0,1,0,0,0.5,i,"collision_points_rviz", visualization_msgs::Marker::SPHERE); - if(i < collision_markers.markers.size()) - collision_markers.markers.at(i) = mkr; - else - collision_markers.markers.push_back(mkr); + if(i < collision_markers.markers.size()) + collision_markers.markers.at(i) = mkr; + else + collision_markers.markers.push_back(mkr); - } + } } void ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, const int& iStart, - autoware_msgs::Lane& trajectory) + autoware_msgs::Lane& trajectory) { - trajectory.waypoints.clear(); - for(unsigned int i=iStart; i < path.size(); i++) - { - autoware_msgs::Waypoint wp; - wp.pose.pose.position.x = path.at(i).pos.x; - wp.pose.pose.position.y = path.at(i).pos.y; - wp.pose.pose.position.z = path.at(i).pos.z; - wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); - wp.twist.twist.linear.x = path.at(i).v; - if(path.at(i).bDir == FORWARD_DIR) - wp.dtlane.dir = 0; - else if(path.at(i).bDir == FORWARD_LEFT_DIR) - wp.dtlane.dir = 1; - else if(path.at(i).bDir == FORWARD_RIGHT_DIR) - wp.dtlane.dir = 2; - //PlannerHNS::GPSPoint p = path.at(i).pos; - //std::cout << p.ToString() << std::endl; - trajectory.waypoints.push_back(wp); - } + trajectory.waypoints.clear(); + for(unsigned int i=iStart; i < path.size(); i++) + { + autoware_msgs::Waypoint wp; + wp.pose.pose.position.x = path.at(i).pos.x; + wp.pose.pose.position.y = path.at(i).pos.y; + wp.pose.pose.position.z = path.at(i).pos.z; + wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); + wp.twist.twist.linear.x = path.at(i).v; + if(path.at(i).bDir == FORWARD_DIR) + wp.dtlane.dir = 0; + else if(path.at(i).bDir == FORWARD_LEFT_DIR) + wp.dtlane.dir = 1; + else if(path.at(i).bDir == FORWARD_RIGHT_DIR) + wp.dtlane.dir = 2; + //PlannerHNS::GPSPoint p = path.at(i).pos; + //std::cout << p.ToString() << std::endl; + trajectory.waypoints.push_back(wp); + } } -void ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray) +void ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "road_network_vector_map"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.25; - std_msgs::ColorRGBA roll_color, total_color, curr_color; - roll_color.r = 1; - roll_color.g = 1; - roll_color.b = 1; - roll_color.a = 0.5; - - lane_waypoint_marker.color = roll_color; - lane_waypoint_marker.frame_locked = false; - - markerArray.markers.clear(); - - for(unsigned int i = 0; i< map.roadSegments.size(); i++) - { - for(unsigned int j = 0; j < map.roadSegments.at(i).Lanes.size(); j++) - { - lane_waypoint_marker.points.clear(); - - lane_waypoint_marker.id = map.roadSegments.at(i).Lanes.at(j).id; - for(unsigned int p = 0; p < map.roadSegments.at(i).Lanes.at(j).points.size(); p++) - { - geometry_msgs::Point point; - - - - point.x = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.x; - point.y = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.y; - point.z = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(lane_waypoint_marker); - } - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "road_network_vector_map"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.25; + std_msgs::ColorRGBA roll_color, total_color, curr_color; + roll_color.r = 1; + roll_color.g = 1; + roll_color.b = 1; + roll_color.a = 0.5; + + lane_waypoint_marker.color = roll_color; + lane_waypoint_marker.frame_locked = false; + + markerArray.markers.clear(); + + for(unsigned int i = 0; i< map.roadSegments.size(); i++) + { + for(unsigned int j = 0; j < map.roadSegments.at(i).Lanes.size(); j++) + { + lane_waypoint_marker.points.clear(); + + lane_waypoint_marker.id = map.roadSegments.at(i).Lanes.at(j).id; + for(unsigned int p = 0; p < map.roadSegments.at(i).Lanes.at(j).points.size(); p++) + { + geometry_msgs::Point point; + + + + point.x = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.x; + point.y = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.y; + point.z = map.roadSegments.at(i).Lanes.at(j).points.at(p).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(lane_waypoint_marker); + } + } } void ROSHelpers::InitPredParticlesMarkers(const int& nMarkers, visualization_msgs::MarkerArray& paths) { - paths.markers.clear(); - for(int i=0; i& points, visualization_msgs::MarkerArray& part_mkrs, visualization_msgs::MarkerArray& part_markers_d) { - part_mkrs = part_markers_d; - for(unsigned int i = 0; i < points.size(); i++) - { - visualization_msgs::Marker mkr; - if(points.at(i).bDir == PlannerHNS::STANDSTILL_DIR) - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,0,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - else if(points.at(i).bDir == PlannerHNS::FORWARD_DIR) - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,1,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - else if(points.at(i).bDir == PlannerHNS::FORWARD_RIGHT_DIR) - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,0,1,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - else if(points.at(i).bDir == PlannerHNS::FORWARD_LEFT_DIR) - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,0,0,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - else if(points.at(i).bDir == PlannerHNS::BACKWARD_DIR) - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,0,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - else - mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,1,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); - - mkr.scale.x = 0.3; - if(i < part_mkrs.markers.size()) - part_mkrs.markers.at(i) = mkr; - else - part_mkrs.markers.push_back(mkr); - } + part_mkrs = part_markers_d; + for(unsigned int i = 0; i < points.size(); i++) + { + visualization_msgs::Marker mkr; + if(points.at(i).bDir == PlannerHNS::STANDSTILL_DIR) + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,0,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + else if(points.at(i).bDir == PlannerHNS::FORWARD_DIR) + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,1,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + else if(points.at(i).bDir == PlannerHNS::FORWARD_RIGHT_DIR) + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,0,1,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + else if(points.at(i).bDir == PlannerHNS::FORWARD_LEFT_DIR) + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,0,0,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + else if(points.at(i).bDir == PlannerHNS::BACKWARD_DIR) + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,0,1,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + else + mkr = CreateGenMarker(points.at(i).pos.x, points.at(i).pos.y,points.at(i).pos.z,points.at(i).pos.a,1,1,0,0.05,i,"Particles", visualization_msgs::Marker::ARROW); + + mkr.scale.x = 0.3; + if(i < part_mkrs.markers.size()) + part_mkrs.markers.at(i) = mkr; + else + part_mkrs.markers.push_back(mkr); + } } void ROSHelpers::ConvertFromPlannerHRectangleToAutowareRviz(const std::vector& safety_rect, - visualization_msgs::Marker& marker) + visualization_msgs::Marker& marker) { - //if(safety_rect.size() != 4) return; - - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.2; - lane_waypoint_marker.scale.y = 0.2; - //lane_waypoint_marker.scale.z = 0.1; - lane_waypoint_marker.frame_locked = false; - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 0.0; - lane_waypoint_marker.color.a = 0.6; - - for(unsigned int i = 0; i < safety_rect.size(); i++) - { - geometry_msgs::Point p; - p.x = safety_rect.at(i).x; - p.y = safety_rect.at(i).y; - p.z = safety_rect.at(i).z; - - lane_waypoint_marker.points.push_back(p); - } - if(safety_rect.size() > 0) - { - geometry_msgs::Point p; - p.x = safety_rect.at(0).x; - p.y = safety_rect.at(0).y; - p.z = safety_rect.at(0).z; - lane_waypoint_marker.points.push_back(p); - } - -// geometry_msgs::Point p1, p2,p3,p4; -// p1.x = safety_rect.at(0).x; -// p1.y = safety_rect.at(0).y; -// p1.z = safety_rect.at(0).z; + //if(safety_rect.size() != 4) return; + + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.2; + lane_waypoint_marker.scale.y = 0.2; + //lane_waypoint_marker.scale.z = 0.1; + lane_waypoint_marker.frame_locked = false; + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 0.0; + lane_waypoint_marker.color.a = 0.6; + + for(unsigned int i = 0; i < safety_rect.size(); i++) + { + geometry_msgs::Point p; + p.x = safety_rect.at(i).x; + p.y = safety_rect.at(i).y; + p.z = safety_rect.at(i).z; + + lane_waypoint_marker.points.push_back(p); + } + if(safety_rect.size() > 0) + { + geometry_msgs::Point p; + p.x = safety_rect.at(0).x; + p.y = safety_rect.at(0).y; + p.z = safety_rect.at(0).z; + lane_waypoint_marker.points.push_back(p); + } + +// geometry_msgs::Point p1, p2,p3,p4; +// p1.x = safety_rect.at(0).x; +// p1.y = safety_rect.at(0).y; +// p1.z = safety_rect.at(0).z; // -// p2.x = safety_rect.at(1).x; -// p2.y = safety_rect.at(1).y; -// p2.z = safety_rect.at(1).z; +// p2.x = safety_rect.at(1).x; +// p2.y = safety_rect.at(1).y; +// p2.z = safety_rect.at(1).z; // -// p3.x = safety_rect.at(2).x; -// p3.y = safety_rect.at(2).y; -// p3.z = safety_rect.at(2).z; +// p3.x = safety_rect.at(2).x; +// p3.y = safety_rect.at(2).y; +// p3.z = safety_rect.at(2).z; // -// p4.x = safety_rect.at(3).x; -// p4.y = safety_rect.at(3).y; -// p4.z = safety_rect.at(3).z; +// p4.x = safety_rect.at(3).x; +// p4.y = safety_rect.at(3).y; +// p4.z = safety_rect.at(3).z; // -// lane_waypoint_marker.points.push_back(p1); -// lane_waypoint_marker.points.push_back(p2); -// lane_waypoint_marker.points.push_back(p3); -// lane_waypoint_marker.points.push_back(p4); -// lane_waypoint_marker.points.push_back(p1); +// lane_waypoint_marker.points.push_back(p1); +// lane_waypoint_marker.points.push_back(p2); +// lane_waypoint_marker.points.push_back(p3); +// lane_waypoint_marker.points.push_back(p4); +// lane_waypoint_marker.points.push_back(p1); - marker = lane_waypoint_marker; + marker = lane_waypoint_marker; } void ROSHelpers::TrajectoriesToMarkers(const std::vector > >& paths, visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - //lane_waypoint_marker.scale.z = 0.1; - lane_waypoint_marker.frame_locked = false; - std_msgs::ColorRGBA total_color, curr_color; - - int count = 0; - for (unsigned int il = 0; il < paths.size(); il++) - { - for (unsigned int i = 0; i < paths.at(il).size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < paths.at(il).at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = paths.at(il).at(i).at(j).pos.x; - point.y = paths.at(il).at(i).at(j).pos.y; - point.z = paths.at(il).at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - lane_waypoint_marker.color.a = 0.9; - - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 0.0; - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + //lane_waypoint_marker.scale.z = 0.1; + lane_waypoint_marker.frame_locked = false; + std_msgs::ColorRGBA total_color, curr_color; + + int count = 0; + for (unsigned int il = 0; il < paths.size(); il++) + { + for (unsigned int i = 0; i < paths.at(il).size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j=0; j < paths.at(il).at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = paths.at(il).at(i).at(j).pos.x; + point.y = paths.at(il).at(i).at(j).pos.y; + point.z = paths.at(il).at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + lane_waypoint_marker.color.a = 0.9; + + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 0.0; + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } + } } void ROSHelpers::TrajectoriesToColoredMarkers(const std::vector >& paths, const std::vector& traj_costs,const int& iClosest, visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "local_lane_array_marker_colored"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - //lane_waypoint_marker.scale.z = 0.1; - lane_waypoint_marker.color.a = 0.9; - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 1.0; - lane_waypoint_marker.frame_locked = false; - - int count = 0; - for (unsigned int i = 0; i < paths.size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < paths.at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = paths.at(i).at(j).pos.x; - point.y = paths.at(i).at(j).pos.y; - point.z = paths.at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - lane_waypoint_marker.color.b = 0; - - if(traj_costs.size() == paths.size()) - { - float norm_cost = traj_costs.at(i).cost * paths.size(); - if(norm_cost <= 1.0) - { - lane_waypoint_marker.color.r = norm_cost; - lane_waypoint_marker.color.g = 1.0; - } - else if(norm_cost > 1.0) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 2.0 - norm_cost; - } - } - else - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - } - - if(traj_costs.at(i).bBlocked) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 0.0; - } - - if(i == iClosest) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 1.0; - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "local_lane_array_marker_colored"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + //lane_waypoint_marker.scale.z = 0.1; + lane_waypoint_marker.color.a = 0.9; + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 1.0; + lane_waypoint_marker.frame_locked = false; + + int count = 0; + for (unsigned int i = 0; i < paths.size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j=0; j < paths.at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = paths.at(i).at(j).pos.x; + point.y = paths.at(i).at(j).pos.y; + point.z = paths.at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + lane_waypoint_marker.color.b = 0; + + if(traj_costs.size() == paths.size()) + { + float norm_cost = traj_costs.at(i).cost * paths.size(); + if(norm_cost <= 1.0) + { + lane_waypoint_marker.color.r = norm_cost; + lane_waypoint_marker.color.g = 1.0; + } + else if(norm_cost > 1.0) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 2.0 - norm_cost; + } + } + else + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + } + + if(traj_costs.at(i).bBlocked) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 0.0; + } + + if(i == iClosest) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 1.0; + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } } void ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, - const std::vector > >& paths, const PlannerHNS::LocalPlannerH& localPlanner, - visualization_msgs::MarkerArray& markerArray) + const std::vector > >& paths, const PlannerHNS::LocalPlannerH& localPlanner, + visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - //lane_waypoint_marker.scale.z = 0.1; - lane_waypoint_marker.frame_locked = false; - std_msgs::ColorRGBA total_color, curr_color; - - - int count = 0; - for (unsigned int il = 0; il < paths.size(); il++) - { - for (unsigned int i = 0; i < paths.at(il).size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < paths.at(il).at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = paths.at(il).at(i).at(j).pos.x; - point.y = paths.at(il).at(i).at(j).pos.y; - point.z = paths.at(il).at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - lane_waypoint_marker.color.a = 0.9; - if(localPlanner.m_TrajectoryCostsCalculatotor.m_TrajectoryCosts.size() == paths.size()) - { - float norm_cost = localPlanner.m_TrajectoryCostsCalculatotor.m_TrajectoryCosts.at(i).cost * paths.size(); - if(norm_cost <= 1.0) - { - lane_waypoint_marker.color.r = norm_cost; - lane_waypoint_marker.color.g = 1.0; - } - else if(norm_cost > 1.0) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 2.0 - norm_cost; - } - } - else - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 1.0; - } - - if((int)i == localPlanner.m_iSafeTrajectory && (int)il == localPlanner.m_iCurrentTotalPathId) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 1.0; - } - else - { - lane_waypoint_marker.color.b = 0; - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + //lane_waypoint_marker.scale.z = 0.1; + lane_waypoint_marker.frame_locked = false; + std_msgs::ColorRGBA total_color, curr_color; + + + int count = 0; + for (unsigned int il = 0; il < paths.size(); il++) + { + for (unsigned int i = 0; i < paths.at(il).size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j=0; j < paths.at(il).at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = paths.at(il).at(i).at(j).pos.x; + point.y = paths.at(il).at(i).at(j).pos.y; + point.z = paths.at(il).at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + lane_waypoint_marker.color.a = 0.9; + if(localPlanner.m_TrajectoryCostsCalculatotor.m_TrajectoryCosts.size() == paths.size()) + { + float norm_cost = localPlanner.m_TrajectoryCostsCalculatotor.m_TrajectoryCosts.at(i).cost * paths.size(); + if(norm_cost <= 1.0) + { + lane_waypoint_marker.color.r = norm_cost; + lane_waypoint_marker.color.g = 1.0; + } + else if(norm_cost > 1.0) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 2.0 - norm_cost; + } + } + else + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 1.0; + } + + if((int)i == localPlanner.m_iSafeTrajectory && (int)il == localPlanner.m_iCurrentTotalPathId) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 1.0; + } + else + { + lane_waypoint_marker.color.b = 0; + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } + } } void ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector >& globalPaths, visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - - - std_msgs::ColorRGBA roll_color, total_color, curr_color; - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = 1; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - total_color.r = 1; - total_color.g = 0; - total_color.b = 0; - total_color.a = 0.5; - lane_waypoint_marker.color = total_color; - lane_waypoint_marker.frame_locked = false; - - int count = 0; - for (unsigned int i = 0; i < globalPaths.size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < globalPaths.at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = globalPaths.at(i).at(j).pos.x; - point.y = globalPaths.at(i).at(j).pos.y; - point.z = globalPaths.at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + + + std_msgs::ColorRGBA roll_color, total_color, curr_color; + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = 1; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + total_color.r = 1; + total_color.g = 0; + total_color.b = 0; + total_color.a = 0.5; + lane_waypoint_marker.color = total_color; + lane_waypoint_marker.frame_locked = false; + + int count = 0; + for (unsigned int i = 0; i < globalPaths.size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j=0; j < globalPaths.at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = globalPaths.at(i).at(j).pos.x; + point.y = globalPaths.at(i).at(j).pos.y; + point.z = globalPaths.at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } } void ROSHelpers::ConvertFromPlannerObstaclesToAutoware(const PlannerHNS::WayPoint& currState, const std::vector& trackedObstacles, - visualization_msgs::MarkerArray& detectedPolygons) + visualization_msgs::MarkerArray& detectedPolygons) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "detected_polygons"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = .1; - lane_waypoint_marker.scale.y = .1; - //lane_waypoint_marker.scale.z = .05; - lane_waypoint_marker.color.a = 0.8; - lane_waypoint_marker.frame_locked = false; - - visualization_msgs::Marker corner_marker; - corner_marker.header.frame_id = "map"; - corner_marker.header.stamp = ros::Time(); - corner_marker.ns = "Polygon_Corners"; - corner_marker.type = visualization_msgs::Marker::SPHERE; - corner_marker.action = visualization_msgs::Marker::ADD; - corner_marker.scale.x = .1; - corner_marker.scale.y = .1; - corner_marker.scale.z = .1; - corner_marker.color.a = 0.8; - corner_marker.frame_locked = false; - - - visualization_msgs::Marker quarters_marker; - quarters_marker.header.frame_id = "map"; - quarters_marker.header.stamp = ros::Time(); - quarters_marker.ns = "Quarters_Lines"; - quarters_marker.type = visualization_msgs::Marker::LINE_STRIP; - quarters_marker.action = visualization_msgs::Marker::ADD; - quarters_marker.scale.x = .03; - quarters_marker.scale.y = .03; - quarters_marker.scale.z = .03; - quarters_marker.color.a = 0.8; - quarters_marker.color.r = 0.6; - quarters_marker.color.g = 0.5; - quarters_marker.color.b = 0; - quarters_marker.frame_locked = false; - - visualization_msgs::Marker direction_marker; - direction_marker.header.frame_id = "map"; - direction_marker.header.stamp = ros::Time(); - direction_marker.ns = "Object_Direction"; - direction_marker.type = visualization_msgs::Marker::ARROW; - direction_marker.action = visualization_msgs::Marker::ADD; - direction_marker.scale.x = .9; - direction_marker.scale.y = .4; - direction_marker.scale.z = .4; - direction_marker.color.a = 0.8; - direction_marker.color.r = 0; - direction_marker.color.g = 1; - direction_marker.color.b = 0; - direction_marker.frame_locked = false; - - - visualization_msgs::Marker velocity_marker; - velocity_marker.header.frame_id = "map"; - velocity_marker.header.stamp = ros::Time(); - velocity_marker.ns = "detected_polygons_velocity"; - velocity_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; - //velocity_marker.action = visualization_msgs::Marker::ADD; - velocity_marker.scale.z = 0.9; - velocity_marker.scale.x = 0.9; - velocity_marker.scale.y = 0.9; - velocity_marker.color.a = 0.5; - - velocity_marker.frame_locked = false; - detectedPolygons.markers.clear(); - - int pointID = 0; - int quartersIds = 0; - for(unsigned int i =0; i < trackedObstacles.size(); i++) - { - //double distance = hypot(currState.pos.y-trackedObstacles.at(i).center.pos.y, currState.pos.x-trackedObstacles.at(i).center.pos.x); - - lane_waypoint_marker.color.g = 0; - lane_waypoint_marker.color.r = 0; - lane_waypoint_marker.color.b = 1; - - velocity_marker.color.r = 1;//trackedObstacles.at(i).center.v/16.0; - velocity_marker.color.g = 1;// - trackedObstacles.at(i).center.v/16.0; - velocity_marker.color.b = 1; - - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = i; - velocity_marker.id = i; - - //std::cout << " Distance : " << distance << ", Of Object" << trackedObstacles.at(i).id << std::endl; - - for(unsigned int p = 0; p < trackedObstacles.at(i).contour.size(); p++) - { - - geometry_msgs::Point point; - - point.x = trackedObstacles.at(i).contour.at(p).x; - point.y = trackedObstacles.at(i).contour.at(p).y; - point.z = trackedObstacles.at(i).contour.at(p).z; - - lane_waypoint_marker.points.push_back(point); - - corner_marker.pose.position = point; - corner_marker.color.r = 0.8; - corner_marker.color.g = 0; - corner_marker.color.b = 0.7; - corner_marker.color.a = 0.5; - corner_marker.id = pointID; - pointID++; - - detectedPolygons.markers.push_back(corner_marker); - } - - if(trackedObstacles.at(i).contour.size()>0) - { - geometry_msgs::Point point; - - point.x = trackedObstacles.at(i).contour.at(0).x; - point.y = trackedObstacles.at(i).contour.at(0).y; - point.z = trackedObstacles.at(i).contour.at(0).z+1; - - lane_waypoint_marker.points.push_back(point); - - } - - - geometry_msgs::Point point; - - point.x = trackedObstacles.at(i).center.pos.x; - point.y = trackedObstacles.at(i).center.pos.y; - point.z = trackedObstacles.at(i).center.pos.z+1; - -// geometry_msgs::Point relative_p; - //relative_p.y = 0.5; -// velocity_marker.pose.position = calcAbsoluteCoordinate(relative_p, point); - velocity_marker.pose.position = point; - velocity_marker.pose.position.z += 0.5; - - direction_marker.id = i; - direction_marker.pose.position = point; - direction_marker.pose.position.z += 0.5; - direction_marker.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(trackedObstacles.at(i).center.pos.a)); - - - for(unsigned int iq = 0; iq < 8; iq++) - { - quarters_marker.points.clear(); - quarters_marker.id = quartersIds; - quarters_marker.points.push_back(point); - geometry_msgs::Point point2 = point; - double a_q = UtilityHNS::UtilityH::SplitPositiveAngle(trackedObstacles.at(i).center.pos.a+(iq*M_PI_4)); - point2.x += 2.0*cos(a_q); - point2.y += 1.5*sin(a_q); - quarters_marker.points.push_back(point2); + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "detected_polygons"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = .1; + lane_waypoint_marker.scale.y = .1; + //lane_waypoint_marker.scale.z = .05; + lane_waypoint_marker.color.a = 0.8; + lane_waypoint_marker.frame_locked = false; - quartersIds++; - detectedPolygons.markers.push_back(quarters_marker); - } - - int speed = (trackedObstacles.at(i).center.v*3.6); - - // double to string - std::ostringstream str_out; - // if(trackedObstacles.at(i).center.v > 0.75) - str_out << "(" << trackedObstacles.at(i).id << " , " << speed << ")"; -// else -// str_out << trackedObstacles.at(i).id; - //std::string vel = str_out.str(); - velocity_marker.text = str_out.str();//vel.erase(vel.find_first_of(".") + 2); - //if(speed > 0.5) + visualization_msgs::Marker corner_marker; + corner_marker.header.frame_id = "map"; + corner_marker.header.stamp = ros::Time(); + corner_marker.ns = "Polygon_Corners"; + corner_marker.type = visualization_msgs::Marker::SPHERE; + corner_marker.action = visualization_msgs::Marker::ADD; + corner_marker.scale.x = .1; + corner_marker.scale.y = .1; + corner_marker.scale.z = .1; + corner_marker.color.a = 0.8; + corner_marker.frame_locked = false; + + + visualization_msgs::Marker quarters_marker; + quarters_marker.header.frame_id = "map"; + quarters_marker.header.stamp = ros::Time(); + quarters_marker.ns = "Quarters_Lines"; + quarters_marker.type = visualization_msgs::Marker::LINE_STRIP; + quarters_marker.action = visualization_msgs::Marker::ADD; + quarters_marker.scale.x = .03; + quarters_marker.scale.y = .03; + quarters_marker.scale.z = .03; + quarters_marker.color.a = 0.8; + quarters_marker.color.r = 0.6; + quarters_marker.color.g = 0.5; + quarters_marker.color.b = 0; + quarters_marker.frame_locked = false; + + visualization_msgs::Marker direction_marker; + direction_marker.header.frame_id = "map"; + direction_marker.header.stamp = ros::Time(); + direction_marker.ns = "Object_Direction"; + direction_marker.type = visualization_msgs::Marker::ARROW; + direction_marker.action = visualization_msgs::Marker::ADD; + direction_marker.scale.x = .9; + direction_marker.scale.y = .4; + direction_marker.scale.z = .4; + direction_marker.color.a = 0.8; + direction_marker.color.r = 0; + direction_marker.color.g = 1; + direction_marker.color.b = 0; + direction_marker.frame_locked = false; - detectedPolygons.markers.push_back(velocity_marker); - detectedPolygons.markers.push_back(lane_waypoint_marker); - detectedPolygons.markers.push_back(direction_marker); - } + visualization_msgs::Marker velocity_marker; + velocity_marker.header.frame_id = "map"; + velocity_marker.header.stamp = ros::Time(); + velocity_marker.ns = "detected_polygons_velocity"; + velocity_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; + //velocity_marker.action = visualization_msgs::Marker::ADD; + velocity_marker.scale.z = 0.9; + velocity_marker.scale.x = 0.9; + velocity_marker.scale.y = 0.9; + velocity_marker.color.a = 0.5; + + velocity_marker.frame_locked = false; + detectedPolygons.markers.clear(); + + int pointID = 0; + int quartersIds = 0; + for(unsigned int i =0; i < trackedObstacles.size(); i++) + { + //double distance = hypot(currState.pos.y-trackedObstacles.at(i).center.pos.y, currState.pos.x-trackedObstacles.at(i).center.pos.x); + + lane_waypoint_marker.color.g = 0; + lane_waypoint_marker.color.r = 0; + lane_waypoint_marker.color.b = 1; + + velocity_marker.color.r = 1;//trackedObstacles.at(i).center.v/16.0; + velocity_marker.color.g = 1;// - trackedObstacles.at(i).center.v/16.0; + velocity_marker.color.b = 1; + + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = i; + velocity_marker.id = i; + + //std::cout << " Distance : " << distance << ", Of Object" << trackedObstacles.at(i).id << std::endl; + + for(unsigned int p = 0; p < trackedObstacles.at(i).contour.size(); p++) + { + + geometry_msgs::Point point; + + point.x = trackedObstacles.at(i).contour.at(p).x; + point.y = trackedObstacles.at(i).contour.at(p).y; + point.z = trackedObstacles.at(i).contour.at(p).z; + + lane_waypoint_marker.points.push_back(point); + + corner_marker.pose.position = point; + corner_marker.color.r = 0.8; + corner_marker.color.g = 0; + corner_marker.color.b = 0.7; + corner_marker.color.a = 0.5; + corner_marker.id = pointID; + pointID++; + + detectedPolygons.markers.push_back(corner_marker); + } + + if(trackedObstacles.at(i).contour.size()>0) + { + geometry_msgs::Point point; + + point.x = trackedObstacles.at(i).contour.at(0).x; + point.y = trackedObstacles.at(i).contour.at(0).y; + point.z = trackedObstacles.at(i).contour.at(0).z+1; + + lane_waypoint_marker.points.push_back(point); + + } + + + geometry_msgs::Point point; + + point.x = trackedObstacles.at(i).center.pos.x; + point.y = trackedObstacles.at(i).center.pos.y; + point.z = trackedObstacles.at(i).center.pos.z+1; + +// geometry_msgs::Point relative_p; + //relative_p.y = 0.5; +// velocity_marker.pose.position = calcAbsoluteCoordinate(relative_p, point); + velocity_marker.pose.position = point; + velocity_marker.pose.position.z += 0.5; + + direction_marker.id = i; + direction_marker.pose.position = point; + direction_marker.pose.position.z += 0.5; + direction_marker.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(trackedObstacles.at(i).center.pos.a)); + + + for(unsigned int iq = 0; iq < 8; iq++) + { + quarters_marker.points.clear(); + quarters_marker.id = quartersIds; + quarters_marker.points.push_back(point); + geometry_msgs::Point point2 = point; + double a_q = UtilityHNS::UtilityH::SplitPositiveAngle(trackedObstacles.at(i).center.pos.a+(iq*M_PI_4)); + point2.x += 2.0*cos(a_q); + point2.y += 1.5*sin(a_q); + quarters_marker.points.push_back(point2); + + quartersIds++; + detectedPolygons.markers.push_back(quarters_marker); + } + + int speed = (trackedObstacles.at(i).center.v*3.6); + + // double to string + std::ostringstream str_out; + // if(trackedObstacles.at(i).center.v > 0.75) + str_out << "(" << trackedObstacles.at(i).id << " , " << speed << ")"; +// else +// str_out << trackedObstacles.at(i).id; + //std::string vel = str_out.str(); + velocity_marker.text = str_out.str();//vel.erase(vel.find_first_of(".") + 2); + //if(speed > 0.5) + + detectedPolygons.markers.push_back(velocity_marker); + detectedPolygons.markers.push_back(lane_waypoint_marker); + detectedPolygons.markers.push_back(direction_marker); + + } } std::string ROSHelpers::GetBehaviorNameFromCode(const PlannerHNS::STATE_TYPE& behState) { - std::string str = "Unknown"; - switch(behState) - { - case PlannerHNS::INITIAL_STATE: - str = "Init"; - break; - case PlannerHNS::WAITING_STATE: - str = "Waiting"; - break; - case PlannerHNS::FORWARD_STATE: - str = "Forward"; - break; - case PlannerHNS::STOPPING_STATE: - str = "Stop"; - break; - case PlannerHNS::FINISH_STATE: - str = "End"; - break; - case PlannerHNS::FOLLOW_STATE: - str = "Follow"; - break; - case PlannerHNS::OBSTACLE_AVOIDANCE_STATE: - str = "Swerving"; - break; - case PlannerHNS::TRAFFIC_LIGHT_STOP_STATE: - str = "Light Stop"; - break; - case PlannerHNS::TRAFFIC_LIGHT_WAIT_STATE: - str = "Light Wait"; - break; - case PlannerHNS::STOP_SIGN_STOP_STATE: - str = "Sign Stop"; - break; - case PlannerHNS::STOP_SIGN_WAIT_STATE: - str = "Sign Wait"; - break; - default: - str = "Unknown"; - break; - } - - return str; + std::string str = "Unknown"; + switch(behState) + { + case PlannerHNS::INITIAL_STATE: + str = "Init"; + break; + case PlannerHNS::WAITING_STATE: + str = "Waiting"; + break; + case PlannerHNS::FORWARD_STATE: + str = "Forward"; + break; + case PlannerHNS::STOPPING_STATE: + str = "Stop"; + break; + case PlannerHNS::FINISH_STATE: + str = "End"; + break; + case PlannerHNS::FOLLOW_STATE: + str = "Follow"; + break; + case PlannerHNS::OBSTACLE_AVOIDANCE_STATE: + str = "Swerving"; + break; + case PlannerHNS::TRAFFIC_LIGHT_STOP_STATE: + str = "Light Stop"; + break; + case PlannerHNS::TRAFFIC_LIGHT_WAIT_STATE: + str = "Light Wait"; + break; + case PlannerHNS::STOP_SIGN_STOP_STATE: + str = "Sign Stop"; + break; + case PlannerHNS::STOP_SIGN_WAIT_STATE: + str = "Sign Wait"; + break; + default: + str = "Unknown"; + break; + } + + return str; } void ROSHelpers::VisualizeBehaviorState(const PlannerHNS::WayPoint& currState, const PlannerHNS::BehaviorState& beh, const bool& bGreenLight, const int& avoidDirection, visualization_msgs::Marker& behaviorMarker, std::string ns,double size_factor) { - behaviorMarker.header.frame_id = "map"; - behaviorMarker.header.stamp = ros::Time(); - behaviorMarker.ns = ns; - behaviorMarker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; - behaviorMarker.scale.z = 1.0*size_factor; - behaviorMarker.scale.x = 1.0*size_factor; - behaviorMarker.scale.y = 1.0*size_factor; - behaviorMarker.color.a = 0.9; - behaviorMarker.frame_locked = false; - if(bGreenLight) - { - behaviorMarker.color.r = 0.1;//trackedObstacles.at(i).center.v/16.0; - behaviorMarker.color.g = 1;// - trackedObstacles.at(i).center.v/16.0; - behaviorMarker.color.b = 0.1; - } - else - { - behaviorMarker.color.r = 1;//trackedObstacles.at(i).center.v/16.0; - behaviorMarker.color.g = 0.1;// - trackedObstacles.at(i).center.v/16.0; - behaviorMarker.color.b = 0.1; - } - - behaviorMarker.id = 0; - - geometry_msgs::Point point; - - point.x = currState.pos.x; - point.y = currState.pos.y; - point.z = currState.pos.z+3.0; - - behaviorMarker.pose.position = point; - - std::ostringstream str_out; - - //str_out << "(" << (int)(beh.followDistance * 100) / 100 <<")"; - str_out << "(" << (int)(beh.stopDistance * 100.0) / 100.0 <<")"; - - if(avoidDirection == -1) - str_out << "<< "; - - str_out << GetBehaviorNameFromCode(beh.state); - if(avoidDirection == 1) - str_out << " >>"; - behaviorMarker.text = str_out.str(); + behaviorMarker.header.frame_id = "map"; + behaviorMarker.header.stamp = ros::Time(); + behaviorMarker.ns = ns; + behaviorMarker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; + behaviorMarker.scale.z = 1.0*size_factor; + behaviorMarker.scale.x = 1.0*size_factor; + behaviorMarker.scale.y = 1.0*size_factor; + behaviorMarker.color.a = 0.9; + behaviorMarker.frame_locked = false; + if(bGreenLight) + { + behaviorMarker.color.r = 0.1;//trackedObstacles.at(i).center.v/16.0; + behaviorMarker.color.g = 1;// - trackedObstacles.at(i).center.v/16.0; + behaviorMarker.color.b = 0.1; + } + else + { + behaviorMarker.color.r = 1;//trackedObstacles.at(i).center.v/16.0; + behaviorMarker.color.g = 0.1;// - trackedObstacles.at(i).center.v/16.0; + behaviorMarker.color.b = 0.1; + } + + behaviorMarker.id = 0; + + geometry_msgs::Point point; + + point.x = currState.pos.x; + point.y = currState.pos.y; + point.z = currState.pos.z+3.0; + + behaviorMarker.pose.position = point; + + std::ostringstream str_out; + + //str_out << "(" << (int)(beh.followDistance * 100) / 100 <<")"; + str_out << "(" << (int)(beh.stopDistance * 100.0) / 100.0 <<")"; + + if(avoidDirection == -1) + str_out << "<< "; + + str_out << GetBehaviorNameFromCode(beh.state); + if(avoidDirection == 1) + str_out << " >>"; + behaviorMarker.text = str_out.str(); } void ROSHelpers::ConvertFromAutowareBoundingBoxObstaclesToPlannerH(const jsk_recognition_msgs::BoundingBoxArray& detectedObstacles, - std::vector& obstacles_list) + std::vector& obstacles_list) { - obstacles_list.clear(); - for(unsigned int i =0; i < detectedObstacles.boxes.size(); i++) - { - PlannerHNS::DetectedObject obj; - obj.center = PlannerHNS::WayPoint(detectedObstacles.boxes.at(i).pose.position.x, - detectedObstacles.boxes.at(i).pose.position.y, - 0, - 0); - obj.w = detectedObstacles.boxes.at(i).dimensions.y; - obj.l = detectedObstacles.boxes.at(i).dimensions.x; - obj.h = detectedObstacles.boxes.at(i).dimensions.z; - //double objSize = obj.w*obj.l; - //double d = hypot(m_State.state.pos.y - obj.center.pos.y, m_State.state.pos.x - obj.center.pos.x); - //std::cout << ", Distance of : " << d; - //if(d < 7) - { - - double l2 = obj.l/2.0; - double w2 = obj.w/2.0; - - obj.contour.push_back(PlannerHNS::GPSPoint(-w2, -l2, 0,0)); - obj.contour.push_back(PlannerHNS::GPSPoint(w2, -l2, 0,0)); - obj.contour.push_back(PlannerHNS::GPSPoint(w2, l2, 0,0)); - obj.contour.push_back(PlannerHNS::GPSPoint(-w2, l2, 0,0)); - obstacles_list.push_back(obj); - } - } + obstacles_list.clear(); + for(unsigned int i =0; i < detectedObstacles.boxes.size(); i++) + { + PlannerHNS::DetectedObject obj; + obj.center = PlannerHNS::WayPoint(detectedObstacles.boxes.at(i).pose.position.x, + detectedObstacles.boxes.at(i).pose.position.y, + 0, + 0); + obj.w = detectedObstacles.boxes.at(i).dimensions.y; + obj.l = detectedObstacles.boxes.at(i).dimensions.x; + obj.h = detectedObstacles.boxes.at(i).dimensions.z; + //double objSize = obj.w*obj.l; + //double d = hypot(m_State.state.pos.y - obj.center.pos.y, m_State.state.pos.x - obj.center.pos.x); + //std::cout << ", Distance of : " << d; + //if(d < 7) + { + + double l2 = obj.l/2.0; + double w2 = obj.w/2.0; + + obj.contour.push_back(PlannerHNS::GPSPoint(-w2, -l2, 0,0)); + obj.contour.push_back(PlannerHNS::GPSPoint(w2, -l2, 0,0)); + obj.contour.push_back(PlannerHNS::GPSPoint(w2, l2, 0,0)); + obj.contour.push_back(PlannerHNS::GPSPoint(-w2, l2, 0,0)); + obstacles_list.push_back(obj); + } + } } void ROSHelpers::ConvertFromAutowareCloudClusterObstaclesToPlannerH(const PlannerHNS::WayPoint& currState, const double& car_width, - const double& car_length, const autoware_msgs::CloudClusterArray& clusters, vector& obstacles_list, - const double max_obj_size, const double& min_obj_size, const double& detection_radius, - const int& n_poly_quarters,const double& poly_resolution, int& nOriginalPoints, int& nContourPoints) + const double& car_length, const autoware_msgs::CloudClusterArray& clusters, vector& obstacles_list, + const double max_obj_size, const double& min_obj_size, const double& detection_radius, + const int& n_poly_quarters,const double& poly_resolution, int& nOriginalPoints, int& nContourPoints) { - PlannerHNS::Mat3 rotationMat(-currState.pos.a); - PlannerHNS::Mat3 translationMat(-currState.pos.x, -currState.pos.y); - - int nPoints = 0; - int nOrPoints = 0; - double object_size = 0; - PlannerHNS::GPSPoint relative_point; - PlannerHNS::GPSPoint avg_center; - PolygonGenerator polyGen(n_poly_quarters); - PlannerHNS::DetectedObject obj; - - for(unsigned int i =0; i < clusters.clusters.size(); i++) - { - obj.id = clusters.clusters.at(i).id; - obj.label = clusters.clusters.at(i).label; + PlannerHNS::Mat3 rotationMat(-currState.pos.a); + PlannerHNS::Mat3 translationMat(-currState.pos.x, -currState.pos.y); + + int nPoints = 0; + int nOrPoints = 0; + double object_size = 0; + PlannerHNS::GPSPoint relative_point; + PlannerHNS::GPSPoint avg_center; + PolygonGenerator polyGen(n_poly_quarters); + PlannerHNS::DetectedObject obj; + + for(unsigned int i =0; i < clusters.clusters.size(); i++) + { + obj.id = clusters.clusters.at(i).id; + obj.label = clusters.clusters.at(i).label; - obj.center.pos.x = clusters.clusters.at(i).centroid_point.point.x; - obj.center.pos.y = clusters.clusters.at(i).centroid_point.point.y; - obj.center.pos.z = clusters.clusters.at(i).centroid_point.point.z; - obj.center.pos.a = 0; - obj.center.v = 0; - obj.actual_yaw = clusters.clusters.at(i).estimated_angle; + obj.center.pos.x = clusters.clusters.at(i).centroid_point.point.x; + obj.center.pos.y = clusters.clusters.at(i).centroid_point.point.y; + obj.center.pos.z = clusters.clusters.at(i).centroid_point.point.z; + obj.center.pos.a = 0; + obj.center.v = 0; + obj.actual_yaw = clusters.clusters.at(i).estimated_angle; - obj.w = clusters.clusters.at(i).dimensions.x; - obj.l = clusters.clusters.at(i).dimensions.y; - obj.h = clusters.clusters.at(i).dimensions.z; + obj.w = clusters.clusters.at(i).dimensions.x; + obj.l = clusters.clusters.at(i).dimensions.y; + obj.h = clusters.clusters.at(i).dimensions.z; - pcl::PointCloud point_cloud; - pcl::fromROSMsg(clusters.clusters.at(i).cloud, point_cloud); + pcl::PointCloud point_cloud; + pcl::fromROSMsg(clusters.clusters.at(i).cloud, point_cloud); - obj.contour = polyGen.EstimateClusterPolygon(point_cloud ,obj.center.pos,avg_center, poly_resolution); + obj.contour = polyGen.EstimateClusterPolygon(point_cloud ,obj.center.pos,avg_center, poly_resolution); - obj.distance_to_center = hypot(obj.center.pos.y-currState.pos.y, obj.center.pos.x-currState.pos.x); + obj.distance_to_center = hypot(obj.center.pos.y-currState.pos.y, obj.center.pos.x-currState.pos.x); - object_size = hypot(obj.w, obj.l); + object_size = hypot(obj.w, obj.l); - if(obj.distance_to_center > detection_radius || object_size < min_obj_size || object_size > max_obj_size) - continue; + if(obj.distance_to_center > detection_radius || object_size < min_obj_size || object_size > max_obj_size) + continue; - relative_point = translationMat*obj.center.pos; - relative_point = rotationMat*relative_point; + relative_point = translationMat*obj.center.pos; + relative_point = rotationMat*relative_point; - double distance_x = fabs(relative_point.x - car_length/3.0); - double distance_y = fabs(relative_point.y); + double distance_x = fabs(relative_point.x - car_length/3.0); + double distance_y = fabs(relative_point.y); - if(distance_x <= car_length*0.5 && distance_y <= car_width*0.5) // don't detect yourself - continue; + if(distance_x <= car_length*0.5 && distance_y <= car_width*0.5) // don't detect yourself + continue; - //obj.center.pos = avg_center; - nOrPoints += point_cloud.points.size(); - nPoints += obj.contour.size(); - //std::cout << " Distance_X: " << distance_x << ", " << " Distance_Y: " << distance_y << ", " << " Size: " << object_size << std::endl; - obstacles_list.push_back(obj); - } + //obj.center.pos = avg_center; + nOrPoints += point_cloud.points.size(); + nPoints += obj.contour.size(); + //std::cout << " Distance_X: " << distance_x << ", " << " Distance_Y: " << distance_y << ", " << " Size: " << object_size << std::endl; + obstacles_list.push_back(obj); + } - nOriginalPoints = nOrPoints; - nContourPoints = nPoints; + nOriginalPoints = nOrPoints; + nContourPoints = nPoints; } PlannerHNS::SHIFT_POS ROSHelpers::ConvertShiftFromAutowareToPlannerH(const PlannerHNS::AUTOWARE_SHIFT_POS& shift) { - if(shift == PlannerHNS::AW_SHIFT_POS_DD) - return PlannerHNS::SHIFT_POS_DD; - else if(shift == PlannerHNS::AW_SHIFT_POS_RR) - return PlannerHNS::SHIFT_POS_RR; - else if(shift == PlannerHNS::AW_SHIFT_POS_NN) - return PlannerHNS::SHIFT_POS_NN; - else if(shift == PlannerHNS::AW_SHIFT_POS_PP) - return PlannerHNS::SHIFT_POS_PP; - else if(shift == PlannerHNS::AW_SHIFT_POS_BB) - return PlannerHNS::SHIFT_POS_BB; - else if(shift == PlannerHNS::AW_SHIFT_POS_SS) - return PlannerHNS::SHIFT_POS_SS; - else - return PlannerHNS::SHIFT_POS_UU; + if(shift == PlannerHNS::AW_SHIFT_POS_DD) + return PlannerHNS::SHIFT_POS_DD; + else if(shift == PlannerHNS::AW_SHIFT_POS_RR) + return PlannerHNS::SHIFT_POS_RR; + else if(shift == PlannerHNS::AW_SHIFT_POS_NN) + return PlannerHNS::SHIFT_POS_NN; + else if(shift == PlannerHNS::AW_SHIFT_POS_PP) + return PlannerHNS::SHIFT_POS_PP; + else if(shift == PlannerHNS::AW_SHIFT_POS_BB) + return PlannerHNS::SHIFT_POS_BB; + else if(shift == PlannerHNS::AW_SHIFT_POS_SS) + return PlannerHNS::SHIFT_POS_SS; + else + return PlannerHNS::SHIFT_POS_UU; } PlannerHNS::AUTOWARE_SHIFT_POS ROSHelpers::ConvertShiftFromPlannerHToAutoware(const PlannerHNS::SHIFT_POS& shift) { - if(shift == PlannerHNS::SHIFT_POS_DD) - return PlannerHNS::AW_SHIFT_POS_DD; - else if(shift == PlannerHNS::SHIFT_POS_RR) - return PlannerHNS::AW_SHIFT_POS_RR; - else if(shift == PlannerHNS::SHIFT_POS_NN) - return PlannerHNS::AW_SHIFT_POS_NN; - else if(shift == PlannerHNS::SHIFT_POS_PP) - return PlannerHNS::AW_SHIFT_POS_PP; - else if(shift == PlannerHNS::SHIFT_POS_BB) - return PlannerHNS::AW_SHIFT_POS_BB; - else if(shift == PlannerHNS::SHIFT_POS_SS) - return PlannerHNS::AW_SHIFT_POS_SS; - else - return PlannerHNS::AW_SHIFT_POS_UU; + if(shift == PlannerHNS::SHIFT_POS_DD) + return PlannerHNS::AW_SHIFT_POS_DD; + else if(shift == PlannerHNS::SHIFT_POS_RR) + return PlannerHNS::AW_SHIFT_POS_RR; + else if(shift == PlannerHNS::SHIFT_POS_NN) + return PlannerHNS::AW_SHIFT_POS_NN; + else if(shift == PlannerHNS::SHIFT_POS_PP) + return PlannerHNS::AW_SHIFT_POS_PP; + else if(shift == PlannerHNS::SHIFT_POS_BB) + return PlannerHNS::AW_SHIFT_POS_BB; + else if(shift == PlannerHNS::SHIFT_POS_SS) + return PlannerHNS::AW_SHIFT_POS_SS; + else + return PlannerHNS::AW_SHIFT_POS_UU; } PlannerHNS::AutowareBehaviorState ROSHelpers::ConvertBehaviorStateFromPlannerHToAutoware(const PlannerHNS::BehaviorState& beh) { - PlannerHNS::AutowareBehaviorState arw_state; - arw_state.followDistance = beh.followDistance; - arw_state.followVelocity = beh.followVelocity; - arw_state.maxVelocity = beh.maxVelocity; - arw_state.minVelocity = beh.minVelocity; - arw_state.stopDistance = beh.stopDistance; - - if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT) - arw_state.indicator = PlannerHNS::AW_INDICATOR_LEFT; - else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT) - arw_state.indicator = PlannerHNS::AW_INDICATOR_RIGHT; - else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH) - arw_state.indicator = PlannerHNS::AW_INDICATOR_BOTH; - else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE) - arw_state.indicator = PlannerHNS::AW_INDICATOR_NONE; - - if(beh.state == PlannerHNS::INITIAL_STATE) - arw_state.state = PlannerHNS::AW_INITIAL_STATE; - else if(beh.state == PlannerHNS::WAITING_STATE) - arw_state.state = PlannerHNS::AW_WAITING_STATE; - else if(beh.state == PlannerHNS::FORWARD_STATE) - arw_state.state = PlannerHNS::AW_FORWARD_STATE; - else if(beh.state == PlannerHNS::STOPPING_STATE) - arw_state.state = PlannerHNS::AW_STOPPING_STATE; - else if(beh.state == PlannerHNS::EMERGENCY_STATE) - arw_state.state = PlannerHNS::AW_EMERGENCY_STATE; - else if(beh.state == PlannerHNS::TRAFFIC_LIGHT_STOP_STATE) - arw_state.state = PlannerHNS::AW_TRAFFIC_LIGHT_STOP_STATE; - else if(beh.state == PlannerHNS::STOP_SIGN_STOP_STATE) - arw_state.state = PlannerHNS::AW_STOP_SIGN_STOP_STATE; - else if(beh.state == PlannerHNS::FOLLOW_STATE) - arw_state.state = PlannerHNS::AW_FOLLOW_STATE; - else if(beh.state == PlannerHNS::LANE_CHANGE_STATE) - arw_state.state = PlannerHNS::AW_LANE_CHANGE_STATE; - else if(beh.state == PlannerHNS::OBSTACLE_AVOIDANCE_STATE) - arw_state.state = PlannerHNS::AW_OBSTACLE_AVOIDANCE_STATE; - else if(beh.state == PlannerHNS::FINISH_STATE) - arw_state.state = PlannerHNS::AW_FINISH_STATE; - - - return arw_state; + PlannerHNS::AutowareBehaviorState arw_state; + arw_state.followDistance = beh.followDistance; + arw_state.followVelocity = beh.followVelocity; + arw_state.maxVelocity = beh.maxVelocity; + arw_state.minVelocity = beh.minVelocity; + arw_state.stopDistance = beh.stopDistance; + + if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT) + arw_state.indicator = PlannerHNS::AW_INDICATOR_LEFT; + else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT) + arw_state.indicator = PlannerHNS::AW_INDICATOR_RIGHT; + else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH) + arw_state.indicator = PlannerHNS::AW_INDICATOR_BOTH; + else if(beh.indicator == PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE) + arw_state.indicator = PlannerHNS::AW_INDICATOR_NONE; + + if(beh.state == PlannerHNS::INITIAL_STATE) + arw_state.state = PlannerHNS::AW_INITIAL_STATE; + else if(beh.state == PlannerHNS::WAITING_STATE) + arw_state.state = PlannerHNS::AW_WAITING_STATE; + else if(beh.state == PlannerHNS::FORWARD_STATE) + arw_state.state = PlannerHNS::AW_FORWARD_STATE; + else if(beh.state == PlannerHNS::STOPPING_STATE) + arw_state.state = PlannerHNS::AW_STOPPING_STATE; + else if(beh.state == PlannerHNS::EMERGENCY_STATE) + arw_state.state = PlannerHNS::AW_EMERGENCY_STATE; + else if(beh.state == PlannerHNS::TRAFFIC_LIGHT_STOP_STATE) + arw_state.state = PlannerHNS::AW_TRAFFIC_LIGHT_STOP_STATE; + else if(beh.state == PlannerHNS::STOP_SIGN_STOP_STATE) + arw_state.state = PlannerHNS::AW_STOP_SIGN_STOP_STATE; + else if(beh.state == PlannerHNS::FOLLOW_STATE) + arw_state.state = PlannerHNS::AW_FOLLOW_STATE; + else if(beh.state == PlannerHNS::LANE_CHANGE_STATE) + arw_state.state = PlannerHNS::AW_LANE_CHANGE_STATE; + else if(beh.state == PlannerHNS::OBSTACLE_AVOIDANCE_STATE) + arw_state.state = PlannerHNS::AW_OBSTACLE_AVOIDANCE_STATE; + else if(beh.state == PlannerHNS::FINISH_STATE) + arw_state.state = PlannerHNS::AW_FINISH_STATE; + + + return arw_state; } void ROSHelpers::ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory , const unsigned int& iStart) { - trajectory.waypoints.clear(); - - for(unsigned int i = iStart; i < path.size(); i++) - { - autoware_msgs::Waypoint wp; - wp.pose.pose.position.x = path.at(i).pos.x; - wp.pose.pose.position.y = path.at(i).pos.y; - wp.pose.pose.position.z = path.at(i).pos.z; - wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); - - wp.twist.twist.linear.x = path.at(i).v; - wp.lane_id = path.at(i).laneId; - wp.stop_line_id = path.at(i).stopLineID; - wp.left_lane_id = path.at(i).LeftPointId; - wp.right_lane_id = path.at(i).RightPointId; - wp.time_cost = path.at(i).timeCost; - - wp.gid = path.at(i).gid; - - //wp.cost = path.at(i).cost; - wp.cost = 0; - - if(path.at(i).actionCost.size()>0) - { - wp.direction = path.at(i).actionCost.at(0).first; - wp.cost += path.at(i).actionCost.at(0).second; - } - - trajectory.waypoints.push_back(wp); - } + trajectory.waypoints.clear(); + + for(unsigned int i = iStart; i < path.size(); i++) + { + autoware_msgs::Waypoint wp; + wp.pose.pose.position.x = path.at(i).pos.x; + wp.pose.pose.position.y = path.at(i).pos.y; + wp.pose.pose.position.z = path.at(i).pos.z; + wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); + + wp.twist.twist.linear.x = path.at(i).v; + wp.lane_id = path.at(i).laneId; + wp.stop_line_id = path.at(i).stopLineID; + wp.left_lane_id = path.at(i).LeftPointId; + wp.right_lane_id = path.at(i).RightPointId; + wp.time_cost = path.at(i).timeCost; + + wp.gid = path.at(i).gid; + + //wp.cost = path.at(i).cost; + wp.cost = 0; + + if(path.at(i).actionCost.size()>0) + { + wp.direction = path.at(i).actionCost.at(0).first; + wp.cost += path.at(i).actionCost.at(0).second; + } + + trajectory.waypoints.push_back(wp); + } } void ROSHelpers::ConvertFromLocalLaneToAutowareLane(const std::vector& path, autoware_msgs::Lane& trajectory) { - trajectory.waypoints.clear(); - - for(unsigned int i=0; i < path.size(); i++) - { - autoware_msgs::Waypoint wp; - wp.pose.pose.position.x = path.at(i).x; - wp.pose.pose.position.y = path.at(i).y; - wp.pose.pose.position.z = path.at(i).z; - wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).a)); - - trajectory.waypoints.push_back(wp); - } + trajectory.waypoints.clear(); + + for(unsigned int i=0; i < path.size(); i++) + { + autoware_msgs::Waypoint wp; + wp.pose.pose.position.x = path.at(i).x; + wp.pose.pose.position.y = path.at(i).y; + wp.pose.pose.position.z = path.at(i).z; + wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).a)); + + trajectory.waypoints.push_back(wp); + } } void ROSHelpers::ConvertFromAutowareLaneToLocalLane(const autoware_msgs::Lane& trajectory, std::vector& path) { - path.clear(); - - for(unsigned int i=0; i < trajectory.waypoints.size(); i++) - { - PlannerHNS::WayPoint wp; - wp.pos.x = trajectory.waypoints.at(i).pose.pose.position.x; - wp.pos.y = trajectory.waypoints.at(i).pose.pose.position.y; - wp.pos.z = trajectory.waypoints.at(i).pose.pose.position.z; - wp.pos.a = tf::getYaw(trajectory.waypoints.at(i).pose.pose.orientation); - - wp.v = trajectory.waypoints.at(i).twist.twist.linear.x; - - wp.gid = trajectory.waypoints.at(i).gid; - wp.laneId = trajectory.waypoints.at(i).lane_id; - wp.stopLineID = trajectory.waypoints.at(i).stop_line_id; - wp.LeftPointId = trajectory.waypoints.at(i).left_lane_id; - wp.RightPointId = trajectory.waypoints.at(i).right_lane_id; - wp.timeCost = trajectory.waypoints.at(i).time_cost; - - if(trajectory.waypoints.at(i).direction == 0) - wp.bDir = PlannerHNS::FORWARD_DIR; - else if(trajectory.waypoints.at(i).direction == 1) - wp.bDir = PlannerHNS::FORWARD_LEFT_DIR; - else if(trajectory.waypoints.at(i).direction == 2) - wp.bDir = PlannerHNS::FORWARD_RIGHT_DIR; - else if(trajectory.waypoints.at(i).direction == 3) - wp.bDir = PlannerHNS::BACKWARD_DIR; - else if(trajectory.waypoints.at(i).direction == 4) - wp.bDir = PlannerHNS::BACKWARD_LEFT_DIR; - else if(trajectory.waypoints.at(i).direction == 5) - wp.bDir = PlannerHNS::BACKWARD_RIGHT_DIR; - else if(trajectory.waypoints.at(i).direction == 6) - wp.bDir = PlannerHNS::STANDSTILL_DIR; - - wp.cost = trajectory.waypoints.at(i).cost; - - path.push_back(wp); - } + path.clear(); + + for(unsigned int i=0; i < trajectory.waypoints.size(); i++) + { + PlannerHNS::WayPoint wp; + wp.pos.x = trajectory.waypoints.at(i).pose.pose.position.x; + wp.pos.y = trajectory.waypoints.at(i).pose.pose.position.y; + wp.pos.z = trajectory.waypoints.at(i).pose.pose.position.z; + wp.pos.a = tf::getYaw(trajectory.waypoints.at(i).pose.pose.orientation); + + wp.v = trajectory.waypoints.at(i).twist.twist.linear.x; + + wp.gid = trajectory.waypoints.at(i).gid; + wp.laneId = trajectory.waypoints.at(i).lane_id; + wp.stopLineID = trajectory.waypoints.at(i).stop_line_id; + wp.LeftPointId = trajectory.waypoints.at(i).left_lane_id; + wp.RightPointId = trajectory.waypoints.at(i).right_lane_id; + wp.timeCost = trajectory.waypoints.at(i).time_cost; + + if(trajectory.waypoints.at(i).direction == 0) + wp.bDir = PlannerHNS::FORWARD_DIR; + else if(trajectory.waypoints.at(i).direction == 1) + wp.bDir = PlannerHNS::FORWARD_LEFT_DIR; + else if(trajectory.waypoints.at(i).direction == 2) + wp.bDir = PlannerHNS::FORWARD_RIGHT_DIR; + else if(trajectory.waypoints.at(i).direction == 3) + wp.bDir = PlannerHNS::BACKWARD_DIR; + else if(trajectory.waypoints.at(i).direction == 4) + wp.bDir = PlannerHNS::BACKWARD_LEFT_DIR; + else if(trajectory.waypoints.at(i).direction == 5) + wp.bDir = PlannerHNS::BACKWARD_RIGHT_DIR; + else if(trajectory.waypoints.at(i).direction == 6) + wp.bDir = PlannerHNS::STANDSTILL_DIR; + + wp.cost = trajectory.waypoints.at(i).cost; + + path.push_back(wp); + } } void ROSHelpers::createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, - const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray) + const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray) { visualization_msgs::Marker lane_waypoint_marker; lane_waypoint_marker.header.frame_id = "map"; @@ -1425,7 +1425,7 @@ void ROSHelpers::createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, } void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray) + , visualization_msgs::MarkerArray& markerArray) { visualization_msgs::MarkerArray tmp_marker_array; // display by markers the velocity of each waypoint. @@ -1445,8 +1445,8 @@ void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneAr for (unsigned int i=0; i< lane_waypoints_array.lanes.size(); i++) { - std::ostringstream str_count; - str_count << count; + std::ostringstream str_count; + str_count << count; velocity_marker.ns = "global_velocity_lane_" + str_count.str(); for (unsigned int j=0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) { @@ -1473,7 +1473,7 @@ void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneAr } void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray) + , visualization_msgs::MarkerArray& markerArray) { visualization_msgs::MarkerArray tmp_marker_array; visualization_msgs::Marker lane_waypoint_marker; @@ -1493,48 +1493,48 @@ void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::Lan int count = 1; for (unsigned int i=0; i< lane_waypoints_array.lanes.size(); i++) { -// std::ostringstream str_ns; -// str_ns << "global_lane_waypoint_orientation_marker_"; -// str_ns << i; -// lane_waypoint_marker.ns = str_ns.str(); +// std::ostringstream str_ns; +// str_ns << "global_lane_waypoint_orientation_marker_"; +// str_ns << i; +// lane_waypoint_marker.ns = str_ns.str(); for (unsigned int j=0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) { - lane_waypoint_marker.id = count; - lane_waypoint_marker.pose = lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose; - - if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 1) - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 0.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - else if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 2) - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 1.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - else - { - - if(lane_waypoints_array.lanes.at(i).waypoints.at(j).cost >= 100) - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 0.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - else - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 0.8; - lane_waypoint_marker.color.b = 0.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - } + lane_waypoint_marker.id = count; + lane_waypoint_marker.pose = lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose; + + if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 1) + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 0.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + else if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 2) + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 1.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + else + { + + if(lane_waypoints_array.lanes.at(i).waypoints.at(j).cost >= 100) + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 0.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + else + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 0.8; + lane_waypoint_marker.color.b = 0.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + } count++; @@ -1542,310 +1542,310 @@ void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::Lan } markerArray.markers.insert(markerArray.markers.end(), tmp_marker_array.markers.begin(), - tmp_marker_array.markers.end()); + tmp_marker_array.markers.end()); } void ROSHelpers::GetTrafficLightForVisualization(std::vector& lights, visualization_msgs::MarkerArray& markerArray) { - markerArray.markers.clear(); - for(unsigned int i=0; i _traj; - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(det_obj.candidate_trajectories.lanes.at(j), _traj); - for(unsigned int k=0; k < _traj.size(); k++) - _traj.at(k).collisionCost = det_obj.candidate_trajectories.lanes.at(j).cost; - - obj.predTrajectories.push_back(_traj); - } + obj.id = det_obj.id; + obj.label = det_obj.label; + obj.l = det_obj.dimensions.x; + obj.w = det_obj.dimensions.y; + obj.h = det_obj.dimensions.z; + + obj.center.pos.x = det_obj.pose.position.x; + obj.center.pos.y = det_obj.pose.position.y; + obj.center.pos.z = det_obj.pose.position.z; + obj.center.pos.a = tf::getYaw(det_obj.pose.orientation); + + obj.center.v = det_obj.velocity.linear.x; + obj.acceleration_raw = det_obj.velocity.linear.y; + obj.acceleration_desc = det_obj.velocity.linear.z; + obj.bVelocity = det_obj.velocity_reliable; + obj.bDirection = det_obj.pose_reliable; + + if(det_obj.indicator_state == 0) + obj.indicator_state = PlannerHNS::INDICATOR_LEFT; + else if(det_obj.indicator_state == 1) + obj.indicator_state = PlannerHNS::INDICATOR_RIGHT; + else if(det_obj.indicator_state == 2) + obj.indicator_state = PlannerHNS::INDICATOR_BOTH; + else if(det_obj.indicator_state == 3) + obj.indicator_state = PlannerHNS::INDICATOR_NONE; + + PlannerHNS::GPSPoint p; + obj.contour.clear(); + + for(unsigned int j=0; j < det_obj.convex_hull.polygon.points.size(); j++) + { + + p.x = det_obj.convex_hull.polygon.points.at(j).x; + p.y = det_obj.convex_hull.polygon.points.at(j).y; + p.z = det_obj.convex_hull.polygon.points.at(j).z; + obj.contour.push_back(p); + } + + obj.predTrajectories.clear(); + + for(unsigned int j = 0 ; j < det_obj.candidate_trajectories.lanes.size(); j++) + { + std::vector _traj; + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(det_obj.candidate_trajectories.lanes.at(j), _traj); + for(unsigned int k=0; k < _traj.size(); k++) + _traj.at(k).collisionCost = det_obj.candidate_trajectories.lanes.at(j).cost; + + obj.predTrajectories.push_back(_traj); + } } void ROSHelpers::ConvertFromOpenPlannerDetectedObjectToAutowareDetectedObject(const PlannerHNS::DetectedObject& det_obj, const bool& bSimulationMode, autoware_msgs::DetectedObject& obj) { - if(bSimulationMode) - obj.id = det_obj.originalID; - else - obj.id = det_obj.id; - - obj.label = det_obj.label; - obj.indicator_state = det_obj.indicator_state; - obj.dimensions.x = det_obj.l; - obj.dimensions.y = det_obj.w; - obj.dimensions.z = det_obj.h; - - obj.pose.position.x = det_obj.center.pos.x; - obj.pose.position.y = det_obj.center.pos.y; - obj.pose.position.z = det_obj.center.pos.z; - obj.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, UtilityHNS::UtilityH::SplitPositiveAngle(det_obj.center.pos.a)); - - obj.velocity.linear.x = det_obj.center.v; - obj.velocity.linear.y = det_obj.acceleration_raw; - obj.velocity.linear.z = det_obj.acceleration_desc; - obj.velocity_reliable = det_obj.bVelocity; - obj.pose_reliable = det_obj.bDirection; - - geometry_msgs::Point32 p; - obj.convex_hull.polygon.points.clear(); - - for(unsigned int j=0; j < det_obj.contour.size(); j++) - { - p.x = det_obj.contour.at(j).x; - p.y = det_obj.contour.at(j).y; - p.z = det_obj.contour.at(j).z; - obj.convex_hull.polygon.points.push_back(p); - } - - - obj.candidate_trajectories.lanes.clear(); - for(unsigned int j = 0 ; j < det_obj.predTrajectories.size(); j++) - { - autoware_msgs::Lane pred_traj; - PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(det_obj.predTrajectories.at(j), pred_traj); - if(det_obj.predTrajectories.at(j).size() > 0) - { - pred_traj.cost = det_obj.predTrajectories.at(j).at(0).collisionCost; - } - pred_traj.lane_index = 0; - obj.candidate_trajectories.lanes.push_back(pred_traj); - } + if(bSimulationMode) + obj.id = det_obj.originalID; + else + obj.id = det_obj.id; + + obj.label = det_obj.label; + obj.indicator_state = det_obj.indicator_state; + obj.dimensions.x = det_obj.l; + obj.dimensions.y = det_obj.w; + obj.dimensions.z = det_obj.h; + + obj.pose.position.x = det_obj.center.pos.x; + obj.pose.position.y = det_obj.center.pos.y; + obj.pose.position.z = det_obj.center.pos.z; + obj.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, UtilityHNS::UtilityH::SplitPositiveAngle(det_obj.center.pos.a)); + + obj.velocity.linear.x = det_obj.center.v; + obj.velocity.linear.y = det_obj.acceleration_raw; + obj.velocity.linear.z = det_obj.acceleration_desc; + obj.velocity_reliable = det_obj.bVelocity; + obj.pose_reliable = det_obj.bDirection; + + geometry_msgs::Point32 p; + obj.convex_hull.polygon.points.clear(); + + for(unsigned int j=0; j < det_obj.contour.size(); j++) + { + p.x = det_obj.contour.at(j).x; + p.y = det_obj.contour.at(j).y; + p.z = det_obj.contour.at(j).z; + obj.convex_hull.polygon.points.push_back(p); + } + + + obj.candidate_trajectories.lanes.clear(); + for(unsigned int j = 0 ; j < det_obj.predTrajectories.size(); j++) + { + autoware_msgs::Lane pred_traj; + PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(det_obj.predTrajectories.at(j), pred_traj); + if(det_obj.predTrajectories.at(j).size() > 0) + { + pred_traj.cost = det_obj.predTrajectories.at(j).at(0).collisionCost; + } + pred_traj.lane_index = 0; + obj.candidate_trajectories.lanes.push_back(pred_traj); + } } void ROSHelpers::UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map) { - std::vector lanes; - for(unsigned int i=0; i < src_map.lanes.data.size();i++) - { - UtilityHNS::AisanLanesFileReader::AisanLane l; - l.BLID = src_map.lanes.data.at(i).blid; - l.BLID2 = src_map.lanes.data.at(i).blid2; - l.BLID3 = src_map.lanes.data.at(i).blid3; - l.BLID4 = src_map.lanes.data.at(i).blid4; - l.BNID = src_map.lanes.data.at(i).bnid; - l.ClossID = src_map.lanes.data.at(i).clossid; - l.DID = src_map.lanes.data.at(i).did; - l.FLID = src_map.lanes.data.at(i).flid; - l.FLID2 = src_map.lanes.data.at(i).flid2; - l.FLID3 = src_map.lanes.data.at(i).flid3; - l.FLID4 = src_map.lanes.data.at(i).flid4; - l.FNID = src_map.lanes.data.at(i).fnid; - l.JCT = src_map.lanes.data.at(i).jct; - l.LCnt = src_map.lanes.data.at(i).lcnt; - l.LnID = src_map.lanes.data.at(i).lnid; - l.Lno = src_map.lanes.data.at(i).lno; - l.Span = src_map.lanes.data.at(i).span; - l.RefVel = src_map.lanes.data.at(i).refvel; - l.LimitVel = src_map.lanes.data.at(i).limitvel; - -// l.LaneChgFG = src_map.lanes.at(i).; -// l.LaneType = src_map.lanes.at(i).blid; -// l.LimitVel = src_map.lanes.at(i).; -// l.LinkWAID = src_map.lanes.at(i).blid; -// l.RefVel = src_map.lanes.at(i).blid; -// l.RoadSecID = src_map.lanes.at(i).; - - lanes.push_back(l); - } - - std::vector points; - - for(unsigned int i=0; i < src_map.points.data.size();i++) - { - UtilityHNS::AisanPointsFileReader::AisanPoints p; - double integ_part = src_map.points.data.at(i).l; - double deg = trunc(src_map.points.data.at(i).l); - double min = trunc((src_map.points.data.at(i).l - deg) * 100.0) / 60.0; - double sec = modf((src_map.points.data.at(i).l - deg) * 100.0, &integ_part)/36.0; - double L = deg + min + sec; - - deg = trunc(src_map.points.data.at(i).b); - min = trunc((src_map.points.data.at(i).b - deg) * 100.0) / 60.0; - sec = modf((src_map.points.data.at(i).b - deg) * 100.0, &integ_part)/36.0; - double B = deg + min + sec; - - p.B = B; - p.Bx = src_map.points.data.at(i).bx; - p.H = src_map.points.data.at(i).h; - p.L = L; - p.Ly = src_map.points.data.at(i).ly; - p.MCODE1 = src_map.points.data.at(i).mcode1; - p.MCODE2 = src_map.points.data.at(i).mcode2; - p.MCODE3 = src_map.points.data.at(i).mcode3; - p.PID = src_map.points.data.at(i).pid; - p.Ref = src_map.points.data.at(i).ref; - - points.push_back(p); - } - - - std::vector dts; - for(unsigned int i=0; i < src_map.dtlanes.data.size();i++) - { - UtilityHNS::AisanCenterLinesFileReader::AisanCenterLine dt; - - dt.Apara = src_map.dtlanes.data.at(i).apara; - dt.DID = src_map.dtlanes.data.at(i).did; - dt.Dir = src_map.dtlanes.data.at(i).dir; - dt.Dist = src_map.dtlanes.data.at(i).dist; - dt.LW = src_map.dtlanes.data.at(i).lw; - dt.PID = src_map.dtlanes.data.at(i).pid; - dt.RW = src_map.dtlanes.data.at(i).rw; - dt.cant = src_map.dtlanes.data.at(i).cant; - dt.r = src_map.dtlanes.data.at(i).r; - dt.slope = src_map.dtlanes.data.at(i).slope; - - dts.push_back(dt); - } - - std::vector areas; - std::vector inters; - std::vector line_data; - std::vector stop_line_data; - std::vector signal_data; - std::vector vector_data; - std::vector curb_data; - std::vector roadedge_data; - std::vector way_area; - std::vector crossing; - std::vector nodes_data; - std::vector conn_data; - - PlannerHNS::GPSPoint origin;//(m_OriginPos.position.x, m_OriginPos.position.y, m_OriginPos.position.z, 0); - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(lanes, points, dts, inters, areas, line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data,way_area, crossing, nodes_data, conn_data, origin, out_map); + std::vector lanes; + for(unsigned int i=0; i < src_map.lanes.data.size();i++) + { + UtilityHNS::AisanLanesFileReader::AisanLane l; + l.BLID = src_map.lanes.data.at(i).blid; + l.BLID2 = src_map.lanes.data.at(i).blid2; + l.BLID3 = src_map.lanes.data.at(i).blid3; + l.BLID4 = src_map.lanes.data.at(i).blid4; + l.BNID = src_map.lanes.data.at(i).bnid; + l.ClossID = src_map.lanes.data.at(i).clossid; + l.DID = src_map.lanes.data.at(i).did; + l.FLID = src_map.lanes.data.at(i).flid; + l.FLID2 = src_map.lanes.data.at(i).flid2; + l.FLID3 = src_map.lanes.data.at(i).flid3; + l.FLID4 = src_map.lanes.data.at(i).flid4; + l.FNID = src_map.lanes.data.at(i).fnid; + l.JCT = src_map.lanes.data.at(i).jct; + l.LCnt = src_map.lanes.data.at(i).lcnt; + l.LnID = src_map.lanes.data.at(i).lnid; + l.Lno = src_map.lanes.data.at(i).lno; + l.Span = src_map.lanes.data.at(i).span; + l.RefVel = src_map.lanes.data.at(i).refvel; + l.LimitVel = src_map.lanes.data.at(i).limitvel; + +// l.LaneChgFG = src_map.lanes.at(i).; +// l.LaneType = src_map.lanes.at(i).blid; +// l.LimitVel = src_map.lanes.at(i).; +// l.LinkWAID = src_map.lanes.at(i).blid; +// l.RefVel = src_map.lanes.at(i).blid; +// l.RoadSecID = src_map.lanes.at(i).; + + lanes.push_back(l); + } + + std::vector points; + + for(unsigned int i=0; i < src_map.points.data.size();i++) + { + UtilityHNS::AisanPointsFileReader::AisanPoints p; + double integ_part = src_map.points.data.at(i).l; + double deg = trunc(src_map.points.data.at(i).l); + double min = trunc((src_map.points.data.at(i).l - deg) * 100.0) / 60.0; + double sec = modf((src_map.points.data.at(i).l - deg) * 100.0, &integ_part)/36.0; + double L = deg + min + sec; + + deg = trunc(src_map.points.data.at(i).b); + min = trunc((src_map.points.data.at(i).b - deg) * 100.0) / 60.0; + sec = modf((src_map.points.data.at(i).b - deg) * 100.0, &integ_part)/36.0; + double B = deg + min + sec; + + p.B = B; + p.Bx = src_map.points.data.at(i).bx; + p.H = src_map.points.data.at(i).h; + p.L = L; + p.Ly = src_map.points.data.at(i).ly; + p.MCODE1 = src_map.points.data.at(i).mcode1; + p.MCODE2 = src_map.points.data.at(i).mcode2; + p.MCODE3 = src_map.points.data.at(i).mcode3; + p.PID = src_map.points.data.at(i).pid; + p.Ref = src_map.points.data.at(i).ref; + + points.push_back(p); + } + + + std::vector dts; + for(unsigned int i=0; i < src_map.dtlanes.data.size();i++) + { + UtilityHNS::AisanCenterLinesFileReader::AisanCenterLine dt; + + dt.Apara = src_map.dtlanes.data.at(i).apara; + dt.DID = src_map.dtlanes.data.at(i).did; + dt.Dir = src_map.dtlanes.data.at(i).dir; + dt.Dist = src_map.dtlanes.data.at(i).dist; + dt.LW = src_map.dtlanes.data.at(i).lw; + dt.PID = src_map.dtlanes.data.at(i).pid; + dt.RW = src_map.dtlanes.data.at(i).rw; + dt.cant = src_map.dtlanes.data.at(i).cant; + dt.r = src_map.dtlanes.data.at(i).r; + dt.slope = src_map.dtlanes.data.at(i).slope; + + dts.push_back(dt); + } + + std::vector areas; + std::vector inters; + std::vector line_data; + std::vector stop_line_data; + std::vector signal_data; + std::vector vector_data; + std::vector curb_data; + std::vector roadedge_data; + std::vector way_area; + std::vector crossing; + std::vector nodes_data; + std::vector conn_data; + + PlannerHNS::GPSPoint origin;//(m_OriginPos.position.x, m_OriginPos.position.y, m_OriginPos.position.z, 0); + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(lanes, points, dts, inters, areas, line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data,way_area, crossing, nodes_data, conn_data, origin, out_map); } void ROSHelpers::GetIndicatorArrows(const PlannerHNS::WayPoint& center, const double& width,const double& length, const PlannerHNS::LIGHT_INDICATOR& indicator, const int& id, visualization_msgs::MarkerArray& markerArray) { - double critical_lateral_distance = width/2.0 + 0.2; - //double critical_long_front_distance = carInfo.length/2.0 ; - PlannerHNS::GPSPoint top_right(critical_lateral_distance, length, center.pos.z, 0); - PlannerHNS::GPSPoint top_left(-critical_lateral_distance, length, center.pos.z, 0); - - PlannerHNS::Mat3 invRotationMat(center.pos.a-M_PI_2); - PlannerHNS::Mat3 invTranslationMat(center.pos.x, center.pos.y); - - top_right = invRotationMat*top_right; - top_right = invTranslationMat*top_right; - top_left = invRotationMat*top_left; - top_left = invTranslationMat*top_left; - - top_right.a = center.pos.a - M_PI_2; - top_left.a = center.pos.a + M_PI_2; - - std_msgs::ColorRGBA color_l, color_r; - color_l.r = 1; color_l.g = 1;color_l.b = 1; - color_r.r = 1; color_r.g = 1;color_r.b = 1; - - if(indicator == PlannerHNS::INDICATOR_LEFT) - { - color_l.b = 0; - } - else if(indicator == PlannerHNS::INDICATOR_RIGHT ) - { - color_r.b = 0; - } - else if(indicator == PlannerHNS::INDICATOR_BOTH) - { - color_l.b = 0; - color_r.b = 0; - } - - visualization_msgs::Marker mkr_l = PlannerHNS::ROSHelpers::CreateGenMarker(top_left.x,top_left.y,top_left.z,top_left.a,color_l.r,color_l.g,color_l.b,1.0, id,"simu_car_indicator_left", visualization_msgs::Marker::ARROW); - mkr_l.scale.y = 0.4; - mkr_l.scale.z = 0.4; - visualization_msgs::Marker mkr_r = PlannerHNS::ROSHelpers::CreateGenMarker(top_right.x,top_right.y,top_right.z,top_right.a,color_r.r,color_r.g,color_r.b,1.0, id,"simu_car_indicator_right", visualization_msgs::Marker::ARROW); - mkr_r.scale.y = 0.4; - mkr_r.scale.z = 0.4; - markerArray.markers.push_back(mkr_l); - markerArray.markers.push_back(mkr_r); + double critical_lateral_distance = width/2.0 + 0.2; + //double critical_long_front_distance = carInfo.length/2.0 ; + PlannerHNS::GPSPoint top_right(critical_lateral_distance, length, center.pos.z, 0); + PlannerHNS::GPSPoint top_left(-critical_lateral_distance, length, center.pos.z, 0); + + PlannerHNS::Mat3 invRotationMat(center.pos.a-M_PI_2); + PlannerHNS::Mat3 invTranslationMat(center.pos.x, center.pos.y); + + top_right = invRotationMat*top_right; + top_right = invTranslationMat*top_right; + top_left = invRotationMat*top_left; + top_left = invTranslationMat*top_left; + + top_right.a = center.pos.a - M_PI_2; + top_left.a = center.pos.a + M_PI_2; + + std_msgs::ColorRGBA color_l, color_r; + color_l.r = 1; color_l.g = 1;color_l.b = 1; + color_r.r = 1; color_r.g = 1;color_r.b = 1; + + if(indicator == PlannerHNS::INDICATOR_LEFT) + { + color_l.b = 0; + } + else if(indicator == PlannerHNS::INDICATOR_RIGHT ) + { + color_r.b = 0; + } + else if(indicator == PlannerHNS::INDICATOR_BOTH) + { + color_l.b = 0; + color_r.b = 0; + } + + visualization_msgs::Marker mkr_l = PlannerHNS::ROSHelpers::CreateGenMarker(top_left.x,top_left.y,top_left.z,top_left.a,color_l.r,color_l.g,color_l.b,1.0, id,"simu_car_indicator_left", visualization_msgs::Marker::ARROW); + mkr_l.scale.y = 0.4; + mkr_l.scale.z = 0.4; + visualization_msgs::Marker mkr_r = PlannerHNS::ROSHelpers::CreateGenMarker(top_right.x,top_right.y,top_right.z,top_right.a,color_r.r,color_r.g,color_r.b,1.0, id,"simu_car_indicator_right", visualization_msgs::Marker::ARROW); + mkr_r.scale.y = 0.4; + mkr_r.scale.z = 0.4; + markerArray.markers.push_back(mkr_l); + markerArray.markers.push_back(mkr_r); } void ROSHelpers::TTC_PathRviz(const std::vector& path, visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "ttc_path"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 1; - lane_waypoint_marker.scale.y = 1; - lane_waypoint_marker.scale.z = 1; - lane_waypoint_marker.frame_locked = false; - std_msgs::ColorRGBA total_color, curr_color; - - lane_waypoint_marker.color.a = 0.9; - lane_waypoint_marker.color.r = 0.5; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 0.0; - - lane_waypoint_marker.id = 1; - for (unsigned int i = 0; i < path.size(); i++) - { - geometry_msgs::Point point; - point.x = path.at(i).pos.x; - point.y = path.at(i).pos.y; - point.z = path.at(i).pos.z; - - lane_waypoint_marker.points.push_back(point); - - markerArray.markers.push_back(lane_waypoint_marker); - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "ttc_path"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 1; + lane_waypoint_marker.scale.y = 1; + lane_waypoint_marker.scale.z = 1; + lane_waypoint_marker.frame_locked = false; + std_msgs::ColorRGBA total_color, curr_color; + + lane_waypoint_marker.color.a = 0.9; + lane_waypoint_marker.color.r = 0.5; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 0.0; + + lane_waypoint_marker.id = 1; + for (unsigned int i = 0; i < path.size(); i++) + { + geometry_msgs::Point point; + point.x = path.at(i).pos.x; + point.y = path.at(i).pos.y; + point.z = path.at(i).pos.z; + + lane_waypoint_marker.points.push_back(point); + + markerArray.markers.push_back(lane_waypoint_marker); + } } } diff --git a/common/op_utility/CMakeLists.txt b/common/op_utility/CMakeLists.txt index 8d538555f40..769e43ac159 100644 --- a/common/op_utility/CMakeLists.txt +++ b/common/op_utility/CMakeLists.txt @@ -5,15 +5,12 @@ find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS cmake_modules - vector_map_msgs - vector_map_server + vector_map_msgs + vector_map_server ) find_package(TinyXML REQUIRED) -################################### -## catkin specific configuration ## -################################### catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} diff --git a/common/op_utility/include/op_utility/DataRW.h b/common/op_utility/include/op_utility/DataRW.h index 901966c0bb3..7793adf3c25 100644 --- a/common/op_utility/include/op_utility/DataRW.h +++ b/common/op_utility/include/op_utility/DataRW.h @@ -38,822 +38,822 @@ namespace UtilityHNS { class DataRW { public: - DataRW(); - virtual ~DataRW(); - - static std::string LoggingMainfolderName; - static std::string ControlLogFolderName; - static std::string PathLogFolderName; - static std::string GlobalPathLogFolderName; - static std::string StatesLogFolderName; - static std::string SimulationFolderName; - static std::string KmlMapsFolderName; - static std::string PredictionFolderName; - static std::string TrackingFolderName; - - - static void WriteKMLFile(const std::string& fileName, const std::vector& gps_list); - static void WriteKMLFile(const std::string& fileName, const std::vector >& gps_list); - static void WriteLogData(const std::string& logFolder, const std::string& logTitle, const std::string& header, const std::vector& logData); - static void CreateLoggingFolder(); + DataRW(); + virtual ~DataRW(); + + static std::string LoggingMainfolderName; + static std::string ControlLogFolderName; + static std::string PathLogFolderName; + static std::string GlobalPathLogFolderName; + static std::string StatesLogFolderName; + static std::string SimulationFolderName; + static std::string KmlMapsFolderName; + static std::string PredictionFolderName; + static std::string TrackingFolderName; + + + static void WriteKMLFile(const std::string& fileName, const std::vector& gps_list); + static void WriteKMLFile(const std::string& fileName, const std::vector >& gps_list); + static void WriteLogData(const std::string& logFolder, const std::string& logTitle, const std::string& header, const std::vector& logData); + static void CreateLoggingFolder(); }; class SimpleReaderBase { private: - std::ifstream* m_pFile; - std::vector m_RawHeaders; - std::vector m_DataTitlesHeader; - std::vector > > m_AllData; - int m_nHeders; - int m_iDataTitles; - int m_nVarPerObj; - int m_nLineHeaders; - std::string m_HeaderRepeatKey; - char m_Separator; - - void ReadHeaders(); - void ParseDataTitles(const std::string& header); + std::ifstream* m_pFile; + std::vector m_RawHeaders; + std::vector m_DataTitlesHeader; + std::vector > > m_AllData; + int m_nHeders; + int m_iDataTitles; + int m_nVarPerObj; + int m_nLineHeaders; + std::string m_HeaderRepeatKey; + char m_Separator; + + void ReadHeaders(); + void ParseDataTitles(const std::string& header); public: - /** - * - * @param fileName log file name - * @param nHeaders number of data headers - * @param iDataTitles which row contains the data titles - * @param nVariablesForOneObject 0 means each row represents one object - */ - SimpleReaderBase(const std::string& fileName, const int& nHeaders = 2, const char& separator = ',', - const int& iDataTitles = 1, const int& nVariablesForOneObject = 0, - const int& nLineHeaders = 0, const std::string& headerRepeatKey = "..."); - - ~SimpleReaderBase(); + /** + * + * @param fileName log file name + * @param nHeaders number of data headers + * @param iDataTitles which row contains the data titles + * @param nVariablesForOneObject 0 means each row represents one object + */ + SimpleReaderBase(const std::string& fileName, const int& nHeaders = 2, const char& separator = ',', + const int& iDataTitles = 1, const int& nVariablesForOneObject = 0, + const int& nLineHeaders = 0, const std::string& headerRepeatKey = "..."); + + ~SimpleReaderBase(); protected: - int ReadAllData(); - bool ReadSingleLine(std::vector >& line); + int ReadAllData(); + bool ReadSingleLine(std::vector >& line); }; class GPSDataReader : public SimpleReaderBase { public: - struct GPSBasicData - { - double lat; - double lon; - double alt; - double dir; - double distance; - - }; - - public: - GPSDataReader(const std::string& fileName) : SimpleReaderBase(fileName){} - ~GPSDataReader(){} - - bool ReadNextLine(GPSBasicData& data); - int ReadAllData(std::vector& data_list); + struct GPSBasicData + { + double lat; + double lon; + double alt; + double dir; + double distance; + + }; + + public: + GPSDataReader(const std::string& fileName) : SimpleReaderBase(fileName){} + ~GPSDataReader(){} + + bool ReadNextLine(GPSBasicData& data); + int ReadAllData(std::vector& data_list); }; class SimulationFileReader : public SimpleReaderBase { public: - struct SimulationPoint - { - double x; - double y; - double z; - double a; - double c; - double v; - std::string name; - }; - - struct SimulationData - { - SimulationPoint startPoint; - SimulationPoint goalPoint; - std::vector simuCars; - }; - - SimulationFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1){} - ~SimulationFileReader(){} - - bool ReadNextLine(SimulationPoint& data); - int ReadAllData(SimulationData& data_list); + struct SimulationPoint + { + double x; + double y; + double z; + double a; + double c; + double v; + std::string name; + }; + + struct SimulationData + { + SimulationPoint startPoint; + SimulationPoint goalPoint; + std::vector simuCars; + }; + + SimulationFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1){} + ~SimulationFileReader(){} + + bool ReadNextLine(SimulationPoint& data); + int ReadAllData(SimulationData& data_list); }; class LocalizationPathReader : public SimpleReaderBase { public: - struct LocalizationWayPoint - { - double t; - double x; - double y; - double z; - double a; - double v; - }; - - LocalizationPathReader(const std::string& fileName, const char& separator) : SimpleReaderBase(fileName, 1, separator){} - ~LocalizationPathReader(){} - - bool ReadNextLine(LocalizationWayPoint& data); - int ReadAllData(std::vector& data_list); + struct LocalizationWayPoint + { + double t; + double x; + double y; + double z; + double a; + double v; + }; + + LocalizationPathReader(const std::string& fileName, const char& separator) : SimpleReaderBase(fileName, 1, separator){} + ~LocalizationPathReader(){} + + bool ReadNextLine(LocalizationWayPoint& data); + int ReadAllData(std::vector& data_list); }; class AisanPointsFileReader : public SimpleReaderBase { public: - struct AisanPoints - { - int PID; - double B; - double L; - double H; - double Bx; - double Ly; - int Ref; - int MCODE1; - int MCODE2; - int MCODE3; - }; - - AisanPointsFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - - AisanPointsFileReader(const vector_map_msgs::PointArray& _points); - ~AisanPointsFileReader(){} - - bool ReadNextLine(AisanPoints& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Point& _rec, AisanPoints& data); - AisanPoints* GetDataRowById(int _pid); - std::vector m_data_list; + struct AisanPoints + { + int PID; + double B; + double L; + double H; + double Bx; + double Ly; + int Ref; + int MCODE1; + int MCODE2; + int MCODE3; + }; + + AisanPointsFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + + AisanPointsFileReader(const vector_map_msgs::PointArray& _points); + ~AisanPointsFileReader(){} + + bool ReadNextLine(AisanPoints& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Point& _rec, AisanPoints& data); + AisanPoints* GetDataRowById(int _pid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanNodesFileReader : public SimpleReaderBase { public: - struct AisanNode - { - int NID; - int PID; - }; + struct AisanNode + { + int NID; + int PID; + }; - AisanNodesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } + AisanNodesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } - AisanNodesFileReader(const vector_map_msgs::NodeArray& _nodes); - ~AisanNodesFileReader(){} + AisanNodesFileReader(const vector_map_msgs::NodeArray& _nodes); + ~AisanNodesFileReader(){} - bool ReadNextLine(AisanNode& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Node& _rec, AisanNode& data); - AisanNode* GetDataRowById(int _nid); - std::vector m_data_list; + bool ReadNextLine(AisanNode& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Node& _rec, AisanNode& data); + AisanNode* GetDataRowById(int _nid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanLinesFileReader : public SimpleReaderBase { public: - struct AisanLine - { - int LID; - int BPID; - int FPID; - int BLID; - int FLID; - }; - - AisanLinesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanLinesFileReader(const vector_map_msgs::LineArray & _lines); - ~AisanLinesFileReader(){} - - bool ReadNextLine(AisanLine& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Line& _rec, AisanLine& data); - AisanLine* GetDataRowById(int _lid); - std::vector m_data_list; + struct AisanLine + { + int LID; + int BPID; + int FPID; + int BLID; + int FLID; + }; + + AisanLinesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanLinesFileReader(const vector_map_msgs::LineArray & _lines); + ~AisanLinesFileReader(){} + + bool ReadNextLine(AisanLine& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Line& _rec, AisanLine& data); + AisanLine* GetDataRowById(int _lid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanCenterLinesFileReader : public SimpleReaderBase { public: - struct AisanCenterLine - { - int DID; - int Dist; - int PID; - double Dir; - double Apara; - double r; - double slope; - double cant; - double LW; - double RW; - }; - - AisanCenterLinesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanCenterLinesFileReader(const vector_map_msgs::DTLaneArray& _dtLanes); - ~AisanCenterLinesFileReader(){} - - bool ReadNextLine(AisanCenterLine& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::DTLane& _rec, AisanCenterLine& data); - AisanCenterLine* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanCenterLine + { + int DID; + int Dist; + int PID; + double Dir; + double Apara; + double r; + double slope; + double cant; + double LW; + double RW; + }; + + AisanCenterLinesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanCenterLinesFileReader(const vector_map_msgs::DTLaneArray& _dtLanes); + ~AisanCenterLinesFileReader(){} + + bool ReadNextLine(AisanCenterLine& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::DTLane& _rec, AisanCenterLine& data); + AisanCenterLine* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanAreasFileReader : public SimpleReaderBase { public: - struct AisanArea - { - int AID; - int SLID; - int ELID; - }; - - AisanAreasFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanAreasFileReader(const vector_map_msgs::AreaArray& _areas); - ~AisanAreasFileReader(){} - - bool ReadNextLine(AisanArea& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Area& _rec, AisanArea& data); - AisanArea* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanArea + { + int AID; + int SLID; + int ELID; + }; + + AisanAreasFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanAreasFileReader(const vector_map_msgs::AreaArray& _areas); + ~AisanAreasFileReader(){} + + bool ReadNextLine(AisanArea& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Area& _rec, AisanArea& data); + AisanArea* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanIntersectionFileReader : public SimpleReaderBase { public: - struct AisanIntersection - { - int ID; - int AID; - int LinkID; - }; - - AisanIntersectionFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanIntersectionFileReader(const vector_map_msgs::CrossRoadArray& _inters); - ~AisanIntersectionFileReader(){} - - bool ReadNextLine(AisanIntersection& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::CrossRoad& _rec, AisanIntersection& data); - AisanIntersection* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanIntersection + { + int ID; + int AID; + int LinkID; + }; + + AisanIntersectionFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanIntersectionFileReader(const vector_map_msgs::CrossRoadArray& _inters); + ~AisanIntersectionFileReader(){} + + bool ReadNextLine(AisanIntersection& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::CrossRoad& _rec, AisanIntersection& data); + AisanIntersection* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanLanesFileReader : public SimpleReaderBase { public: - struct AisanLane - { - int LnID ; - int DID ; - int BLID ; - int FLID ; - int BNID ; - int FNID ; - int JCT ; - int BLID2 ; - int BLID3 ; - int BLID4 ; - int FLID2 ; - int FLID3 ; - int FLID4 ; - int ClossID ; - double Span ; - int LCnt ; - int Lno ; - int LaneType; - int LimitVel; - int RefVel ; - int RoadSecID; - int LaneChgFG; - int LinkWAID; - char LaneDir; - int LeftLaneId; - int RightLaneId; - - int originalMapID; - }; - - AisanLanesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanLanesFileReader(const vector_map_msgs::LaneArray& _lanes); - ~AisanLanesFileReader(){} - - bool ReadNextLine(AisanLane& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Lane& _rec, AisanLane& data); - AisanLane* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanLane + { + int LnID ; + int DID ; + int BLID ; + int FLID ; + int BNID ; + int FNID ; + int JCT ; + int BLID2 ; + int BLID3 ; + int BLID4 ; + int FLID2 ; + int FLID3 ; + int FLID4 ; + int ClossID ; + double Span ; + int LCnt ; + int Lno ; + int LaneType; + int LimitVel; + int RefVel ; + int RoadSecID; + int LaneChgFG; + int LinkWAID; + char LaneDir; + int LeftLaneId; + int RightLaneId; + + int originalMapID; + }; + + AisanLanesFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanLanesFileReader(const vector_map_msgs::LaneArray& _lanes); + ~AisanLanesFileReader(){} + + bool ReadNextLine(AisanLane& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Lane& _rec, AisanLane& data); + AisanLane* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanStopLineFileReader : public SimpleReaderBase { public: - struct AisanStopLine - { - int ID; - int LID; - int TLID; - int SignID; - int LinkID; - }; - - AisanStopLineFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanStopLineFileReader(const vector_map_msgs::StopLineArray& _stopLines); - ~AisanStopLineFileReader(){} - - bool ReadNextLine(AisanStopLine& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::StopLine& _rec, AisanStopLine& data); - AisanStopLine* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanStopLine + { + int ID; + int LID; + int TLID; + int SignID; + int LinkID; + }; + + AisanStopLineFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanStopLineFileReader(const vector_map_msgs::StopLineArray& _stopLines); + ~AisanStopLineFileReader(){} + + bool ReadNextLine(AisanStopLine& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::StopLine& _rec, AisanStopLine& data); + AisanStopLine* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanRoadSignFileReader : public SimpleReaderBase { public: - struct AisanRoadSign - { - int ID; - int VID; - int PLID; - int Type; - int LinkID; - }; - - AisanRoadSignFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanRoadSignFileReader(const vector_map_msgs::RoadSignArray& _signs); - ~AisanRoadSignFileReader(){} - - bool ReadNextLine(AisanRoadSign& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::RoadSign& _rec, AisanRoadSign& data); - AisanRoadSign* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanRoadSign + { + int ID; + int VID; + int PLID; + int Type; + int LinkID; + }; + + AisanRoadSignFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanRoadSignFileReader(const vector_map_msgs::RoadSignArray& _signs); + ~AisanRoadSignFileReader(){} + + bool ReadNextLine(AisanRoadSign& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::RoadSign& _rec, AisanRoadSign& data); + AisanRoadSign* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanSignalFileReader : public SimpleReaderBase { public: - struct AisanSignal - { - int ID; - int VID; - int PLID; - int Type; - int LinkID; - }; - - AisanSignalFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanSignalFileReader(const vector_map_msgs::SignalArray& _signals); - ~AisanSignalFileReader(){} - - bool ReadNextLine(AisanSignal& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Signal& _rec, AisanSignal& data); - AisanSignal* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanSignal + { + int ID; + int VID; + int PLID; + int Type; + int LinkID; + }; + + AisanSignalFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanSignalFileReader(const vector_map_msgs::SignalArray& _signals); + ~AisanSignalFileReader(){} + + bool ReadNextLine(AisanSignal& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Signal& _rec, AisanSignal& data); + AisanSignal* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanVectorFileReader : public SimpleReaderBase { public: - struct AisanVector - { - int VID; - int PID; - double Hang; - double Vang; - }; - - AisanVectorFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanVectorFileReader(const vector_map_msgs::VectorArray& _vectors); - ~AisanVectorFileReader(){} - - bool ReadNextLine(AisanVector& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Vector& _rec, AisanVector& data); - AisanVector* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanVector + { + int VID; + int PID; + double Hang; + double Vang; + }; + + AisanVectorFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanVectorFileReader(const vector_map_msgs::VectorArray& _vectors); + ~AisanVectorFileReader(){} + + bool ReadNextLine(AisanVector& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Vector& _rec, AisanVector& data); + AisanVector* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanCurbFileReader : public SimpleReaderBase { public: - struct AisanCurb - { - int ID; - int LID; - double Height; - double Width; - int dir; - int LinkID; - }; - - AisanCurbFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanCurbFileReader(const vector_map_msgs::CurbArray& _curbs); - ~AisanCurbFileReader(){} - - bool ReadNextLine(AisanCurb& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::Curb& _rec, AisanCurb& data); - AisanCurb* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanCurb + { + int ID; + int LID; + double Height; + double Width; + int dir; + int LinkID; + }; + + AisanCurbFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanCurbFileReader(const vector_map_msgs::CurbArray& _curbs); + ~AisanCurbFileReader(){} + + bool ReadNextLine(AisanCurb& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::Curb& _rec, AisanCurb& data); + AisanCurb* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanRoadEdgeFileReader : public SimpleReaderBase { public: - struct AisanRoadEdge - { - int ID; - int LID; - int LinkID; - }; - - AisanRoadEdgeFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanRoadEdgeFileReader(const vector_map_msgs::RoadEdgeArray& _roadEdges); - ~AisanRoadEdgeFileReader(){} - - bool ReadNextLine(AisanRoadEdge& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::RoadEdge& _rec, AisanRoadEdge& data); - AisanRoadEdge* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanRoadEdge + { + int ID; + int LID; + int LinkID; + }; + + AisanRoadEdgeFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanRoadEdgeFileReader(const vector_map_msgs::RoadEdgeArray& _roadEdges); + ~AisanRoadEdgeFileReader(){} + + bool ReadNextLine(AisanRoadEdge& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::RoadEdge& _rec, AisanRoadEdge& data); + AisanRoadEdge* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanCrossWalkFileReader : public SimpleReaderBase { public: - struct AisanCrossWalk - { - int ID; - int AID; - int Type; - int BdID; - int LinkID; - }; - - AisanCrossWalkFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanCrossWalkFileReader(const vector_map_msgs::CrossWalkArray& _crossWalks); - ~AisanCrossWalkFileReader(){} - - bool ReadNextLine(AisanCrossWalk& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::CrossWalk& _rec, AisanCrossWalk& data); - AisanCrossWalk* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanCrossWalk + { + int ID; + int AID; + int Type; + int BdID; + int LinkID; + }; + + AisanCrossWalkFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanCrossWalkFileReader(const vector_map_msgs::CrossWalkArray& _crossWalks); + ~AisanCrossWalkFileReader(){} + + bool ReadNextLine(AisanCrossWalk& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::CrossWalk& _rec, AisanCrossWalk& data); + AisanCrossWalk* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanWayareaFileReader : public SimpleReaderBase { public: - struct AisanWayarea - { - int ID; - int AID; - int LinkID; - }; - - AisanWayareaFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) - { - m_min_id = std::numeric_limits::max(); - } - AisanWayareaFileReader(const vector_map_msgs::WayAreaArray& _wayArea); - ~AisanWayareaFileReader(){} - - bool ReadNextLine(AisanWayarea& data); - int ReadAllData(std::vector& data_list); - void ParseNextLine(const vector_map_msgs::WayArea& _rec, AisanWayarea& data); - AisanWayarea* GetDataRowById(int _lnid); - std::vector m_data_list; + struct AisanWayarea + { + int ID; + int AID; + int LinkID; + }; + + AisanWayareaFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1) + { + m_min_id = std::numeric_limits::max(); + } + AisanWayareaFileReader(const vector_map_msgs::WayAreaArray& _wayArea); + ~AisanWayareaFileReader(){} + + bool ReadNextLine(AisanWayarea& data); + int ReadAllData(std::vector& data_list); + void ParseNextLine(const vector_map_msgs::WayArea& _rec, AisanWayarea& data); + AisanWayarea* GetDataRowById(int _lnid); + std::vector m_data_list; private: - int m_min_id; - std::vector m_data_map; + int m_min_id; + std::vector m_data_map; }; class AisanDataConnFileReader : public SimpleReaderBase { public: - struct DataConn - { - int LID; // lane id - int SLID; // stop line id - int SID; // signal id - int SSID; // stop sign id - }; + struct DataConn + { + int LID; // lane id + int SLID; // stop line id + int SID; // signal id + int SSID; // stop sign id + }; - AisanDataConnFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1){} - ~AisanDataConnFileReader(){} + AisanDataConnFileReader(const std::string& fileName) : SimpleReaderBase(fileName, 1){} + ~AisanDataConnFileReader(){} - bool ReadNextLine(DataConn& data); - int ReadAllData(std::vector& data_list); + bool ReadNextLine(DataConn& data); + int ReadAllData(std::vector& data_list); }; class MapRaw { public: - UtilityHNS::AisanLanesFileReader* pLanes; - UtilityHNS::AisanPointsFileReader* pPoints; - UtilityHNS::AisanCenterLinesFileReader* pCenterLines; - UtilityHNS::AisanIntersectionFileReader* pIntersections; - UtilityHNS::AisanAreasFileReader* pAreas; - UtilityHNS::AisanLinesFileReader* pLines; - UtilityHNS::AisanStopLineFileReader* pStopLines; - UtilityHNS::AisanSignalFileReader* pSignals; - UtilityHNS::AisanVectorFileReader* pVectors; - UtilityHNS::AisanCurbFileReader* pCurbs; - UtilityHNS::AisanRoadEdgeFileReader* pRoadedges; - UtilityHNS::AisanWayareaFileReader* pWayAreas; - UtilityHNS::AisanCrossWalkFileReader* pCrossWalks; - UtilityHNS::AisanNodesFileReader* pNodes; - - struct timespec _time_out; - - MapRaw() - { - pLanes = nullptr; - pPoints = nullptr; - pCenterLines = nullptr; - pIntersections = nullptr; - pAreas = nullptr; - pLines = nullptr; - pStopLines = nullptr; - pSignals = nullptr; - pVectors = nullptr; - pCurbs = nullptr; - pRoadedges = nullptr; - pWayAreas = nullptr; - pCrossWalks = nullptr; - pNodes = nullptr; - - UtilityH::GetTickCount(_time_out); - } - - ~MapRaw() - { - if(pLanes != nullptr) - { - delete pLanes; - pLanes = nullptr; - } - - if(pPoints != nullptr) - { - delete pPoints; - pPoints = nullptr; - } - - if(pCenterLines != nullptr) - { - delete pCenterLines; - pCenterLines = nullptr; - } - - if(pIntersections != nullptr) - { - delete pIntersections; - pIntersections = nullptr; - } - - if(pAreas != nullptr) - { - delete pAreas; - pAreas = nullptr; - } - - if(pLines != nullptr) - { - delete pLines; - pLines = nullptr; - } - - if(pStopLines != nullptr) - { - delete pStopLines; - pStopLines = nullptr; - } - - if(pSignals != nullptr) - { - delete pSignals; - pSignals = nullptr; - } - - if(pVectors != nullptr) - { - delete pVectors; - pVectors = nullptr; - } - - if(pCurbs != nullptr) - { - delete pCurbs; - pCurbs = nullptr; - } - - if(pRoadedges != nullptr) - { - delete pRoadedges; - pRoadedges = nullptr; - } - - if(pWayAreas != nullptr) - { - delete pWayAreas; - pWayAreas = nullptr; - } - - if(pCrossWalks != nullptr) - { - delete pCrossWalks; - pCrossWalks = nullptr; - } - - if(pNodes != nullptr) - { - delete pNodes; - pNodes = nullptr; - } - } - - int GetVersion() - { - bool bTimeOut = UtilityH::GetTimeDiffNow(_time_out) > 2.0; - bool bLoaded = pLanes != nullptr && pPoints != nullptr && pCenterLines != nullptr && pNodes != nullptr; - int iVersion = 0; - if(bLoaded && bTimeOut) - { - iVersion = 2; - if(pNodes->m_data_list.size() == 0) - { - iVersion = 1; - } - } -// else -// { -// bLoaded = pLanes != nullptr && pPoints != nullptr && pCenterLines != nullptr; -// if(bLoaded && bTimeOut) -// { -// iVersion = 1; -// if(pNodes == nullptr) -// pNodes = new AisanNodesFileReader(vector_map_msgs::NodeArray()); -// } -// } - - if(bLoaded && bTimeOut) - { - if(pIntersections == nullptr) - pIntersections = new AisanIntersectionFileReader(vector_map_msgs::CrossRoadArray()); - - if(pLines == nullptr) - pLines = new AisanLinesFileReader(vector_map_msgs::LineArray()); - - if(pStopLines == nullptr) - pStopLines = new AisanStopLineFileReader(vector_map_msgs::StopLineArray()); - - if(pSignals == nullptr) - pSignals = new AisanSignalFileReader(vector_map_msgs::SignalArray()); - - if(pVectors == nullptr) - pVectors = new AisanVectorFileReader(vector_map_msgs::VectorArray()); - - if(pCurbs == nullptr) - pCurbs = new AisanCurbFileReader(vector_map_msgs::CurbArray()); - - if(pRoadedges == nullptr) - pRoadedges = new AisanRoadEdgeFileReader(vector_map_msgs::RoadEdgeArray()); - - if(pWayAreas == nullptr) - pWayAreas = new AisanWayareaFileReader(vector_map_msgs::WayAreaArray()); - - if(pCrossWalks == nullptr) - pCrossWalks = new AisanCrossWalkFileReader(vector_map_msgs::CrossWalkArray()); - } - - return iVersion; - } + UtilityHNS::AisanLanesFileReader* pLanes; + UtilityHNS::AisanPointsFileReader* pPoints; + UtilityHNS::AisanCenterLinesFileReader* pCenterLines; + UtilityHNS::AisanIntersectionFileReader* pIntersections; + UtilityHNS::AisanAreasFileReader* pAreas; + UtilityHNS::AisanLinesFileReader* pLines; + UtilityHNS::AisanStopLineFileReader* pStopLines; + UtilityHNS::AisanSignalFileReader* pSignals; + UtilityHNS::AisanVectorFileReader* pVectors; + UtilityHNS::AisanCurbFileReader* pCurbs; + UtilityHNS::AisanRoadEdgeFileReader* pRoadedges; + UtilityHNS::AisanWayareaFileReader* pWayAreas; + UtilityHNS::AisanCrossWalkFileReader* pCrossWalks; + UtilityHNS::AisanNodesFileReader* pNodes; + + struct timespec _time_out; + + MapRaw() + { + pLanes = nullptr; + pPoints = nullptr; + pCenterLines = nullptr; + pIntersections = nullptr; + pAreas = nullptr; + pLines = nullptr; + pStopLines = nullptr; + pSignals = nullptr; + pVectors = nullptr; + pCurbs = nullptr; + pRoadedges = nullptr; + pWayAreas = nullptr; + pCrossWalks = nullptr; + pNodes = nullptr; + + UtilityH::GetTickCount(_time_out); + } + + ~MapRaw() + { + if(pLanes != nullptr) + { + delete pLanes; + pLanes = nullptr; + } + + if(pPoints != nullptr) + { + delete pPoints; + pPoints = nullptr; + } + + if(pCenterLines != nullptr) + { + delete pCenterLines; + pCenterLines = nullptr; + } + + if(pIntersections != nullptr) + { + delete pIntersections; + pIntersections = nullptr; + } + + if(pAreas != nullptr) + { + delete pAreas; + pAreas = nullptr; + } + + if(pLines != nullptr) + { + delete pLines; + pLines = nullptr; + } + + if(pStopLines != nullptr) + { + delete pStopLines; + pStopLines = nullptr; + } + + if(pSignals != nullptr) + { + delete pSignals; + pSignals = nullptr; + } + + if(pVectors != nullptr) + { + delete pVectors; + pVectors = nullptr; + } + + if(pCurbs != nullptr) + { + delete pCurbs; + pCurbs = nullptr; + } + + if(pRoadedges != nullptr) + { + delete pRoadedges; + pRoadedges = nullptr; + } + + if(pWayAreas != nullptr) + { + delete pWayAreas; + pWayAreas = nullptr; + } + + if(pCrossWalks != nullptr) + { + delete pCrossWalks; + pCrossWalks = nullptr; + } + + if(pNodes != nullptr) + { + delete pNodes; + pNodes = nullptr; + } + } + + int GetVersion() + { + bool bTimeOut = UtilityH::GetTimeDiffNow(_time_out) > 2.0; + bool bLoaded = pLanes != nullptr && pPoints != nullptr && pCenterLines != nullptr && pNodes != nullptr; + int iVersion = 0; + if(bLoaded && bTimeOut) + { + iVersion = 2; + if(pNodes->m_data_list.size() == 0) + { + iVersion = 1; + } + } +// else +// { +// bLoaded = pLanes != nullptr && pPoints != nullptr && pCenterLines != nullptr; +// if(bLoaded && bTimeOut) +// { +// iVersion = 1; +// if(pNodes == nullptr) +// pNodes = new AisanNodesFileReader(vector_map_msgs::NodeArray()); +// } +// } + + if(bLoaded && bTimeOut) + { + if(pIntersections == nullptr) + pIntersections = new AisanIntersectionFileReader(vector_map_msgs::CrossRoadArray()); + + if(pLines == nullptr) + pLines = new AisanLinesFileReader(vector_map_msgs::LineArray()); + + if(pStopLines == nullptr) + pStopLines = new AisanStopLineFileReader(vector_map_msgs::StopLineArray()); + + if(pSignals == nullptr) + pSignals = new AisanSignalFileReader(vector_map_msgs::SignalArray()); + + if(pVectors == nullptr) + pVectors = new AisanVectorFileReader(vector_map_msgs::VectorArray()); + + if(pCurbs == nullptr) + pCurbs = new AisanCurbFileReader(vector_map_msgs::CurbArray()); + + if(pRoadedges == nullptr) + pRoadedges = new AisanRoadEdgeFileReader(vector_map_msgs::RoadEdgeArray()); + + if(pWayAreas == nullptr) + pWayAreas = new AisanWayareaFileReader(vector_map_msgs::WayAreaArray()); + + if(pCrossWalks == nullptr) + pCrossWalks = new AisanCrossWalkFileReader(vector_map_msgs::CrossWalkArray()); + } + + return iVersion; + } }; } /* namespace UtilityHNS */ diff --git a/common/op_utility/include/op_utility/UtilityH.h b/common/op_utility/include/op_utility/UtilityH.h index deb236e482f..880bf726877 100644 --- a/common/op_utility/include/op_utility/UtilityH.h +++ b/common/op_utility/include/op_utility/UtilityH.h @@ -25,85 +25,85 @@ namespace UtilityHNS class UtilityH { public: - UtilityH(); - virtual ~UtilityH(); - - - static double FixNegativeAngle(const double& a); - static double SplitPositiveAngle(const double& a); - static double InverseAngle(const double& a); - static double AngleBetweenTwoAnglesPositive(const double& a1, const double& a2); - static double GetCircularAngle(const double& prevContAngle, const double& prevAngle, const double& currAngle); - - //Time Functions - static void GetTickCount(struct timespec& t); - static std::string GetFilePrefixHourMinuteSeconds(); - static double GetTimeDiffNow(const struct timespec& old_t); - static double GetTimeDiff(const struct timespec& old_t,const struct timespec& curr_t); - static std::string GetDateTimeStr(); - static int tsCompare (struct timespec time1, struct timespec time2, int micro_tolerance = 10); - static int GetSign(double x); - static std::string GetHomeDirectory(); - static double GetMomentumScaleFactor(const double& v); - static timespec GetTimeSpec(const time_t& srcT); - static time_t GetLongTime(const struct timespec& srcT); + UtilityH(); + virtual ~UtilityH(); + + + static double FixNegativeAngle(const double& a); + static double SplitPositiveAngle(const double& a); + static double InverseAngle(const double& a); + static double AngleBetweenTwoAnglesPositive(const double& a1, const double& a2); + static double GetCircularAngle(const double& prevContAngle, const double& prevAngle, const double& currAngle); + + //Time Functions + static void GetTickCount(struct timespec& t); + static std::string GetFilePrefixHourMinuteSeconds(); + static double GetTimeDiffNow(const struct timespec& old_t); + static double GetTimeDiff(const struct timespec& old_t,const struct timespec& curr_t); + static std::string GetDateTimeStr(); + static int tsCompare (struct timespec time1, struct timespec time2, int micro_tolerance = 10); + static int GetSign(double x); + static std::string GetHomeDirectory(); + static double GetMomentumScaleFactor(const double& v); + static timespec GetTimeSpec(const time_t& srcT); + static time_t GetLongTime(const struct timespec& srcT); }; class PIDController { public: - PIDController(); - PIDController(const double& kp, const double& ki, const double& kd); - void Init(const double& kp, const double& ki, const double& kd); - void Setlimit(const double& upper,const double& lower); - double getPID(const double& currValue, const double& targetValue); - double getPID(const double& e); - void ResetD(); - void ResetI(); - std::string ToString(); - std::string ToStringHeader(); + PIDController(); + PIDController(const double& kp, const double& ki, const double& kd); + void Init(const double& kp, const double& ki, const double& kd); + void Setlimit(const double& upper,const double& lower); + double getPID(const double& currValue, const double& targetValue); + double getPID(const double& e); + void ResetD(); + void ResetI(); + std::string ToString(); + std::string ToStringHeader(); private: - double kp; - double ki; - double kd; - double kp_v; - double ki_v; - double kd_v; - double pid_v; - double pid_lim; - double upper_limit; - double lower_limit; - bool bEnableLimit; - double accumErr; - double prevErr; - bool bResetD; - bool bResetI; + double kp; + double ki; + double kd; + double kp_v; + double ki_v; + double kd_v; + double pid_v; + double pid_lim; + double upper_limit; + double lower_limit; + bool bEnableLimit; + double accumErr; + double prevErr; + bool bResetD; + bool bResetI; }; class LowpassFilter { public: - LowpassFilter(); - virtual ~LowpassFilter(); + LowpassFilter(); + virtual ~LowpassFilter(); - LowpassFilter(const int& filterOrder, const double& sampleFreq, const double& cutOffFreq); - void Init(const int& filterOrder, const double& sampleFreq, const double& cutOffFreq); - double getFilter(const double& value); + LowpassFilter(const int& filterOrder, const double& sampleFreq, const double& cutOffFreq); + void Init(const int& filterOrder, const double& sampleFreq, const double& cutOffFreq); + double getFilter(const double& value); private: - int m; - double sampleF; - double cutOffF; - double A ; - double d1 ; - double d2 ; - double w0 ; - double w1 ; - double w2 ; + int m; + double sampleF; + double cutOffF; + double A ; + double d1 ; + double d2 ; + double w0 ; + double w1 ; + double w2 ; }; diff --git a/common/op_utility/src/DataRW.cpp b/common/op_utility/src/DataRW.cpp index 3d8656dc117..f3fc8721252 100644 --- a/common/op_utility/src/DataRW.cpp +++ b/common/op_utility/src/DataRW.cpp @@ -16,15 +16,15 @@ using namespace std; namespace UtilityHNS { -std::string DataRW::LoggingMainfolderName = "/autoware_openplanner_logs/"; -std::string DataRW::ControlLogFolderName = "ControlLogs/"; +std::string DataRW::LoggingMainfolderName = "/autoware_openplanner_logs/"; +std::string DataRW::ControlLogFolderName = "ControlLogs/"; std::string DataRW::GlobalPathLogFolderName = "GlobalPathLogs/"; -std::string DataRW::PathLogFolderName = "TrajectoriesLogs/"; -std::string DataRW::StatesLogFolderName = "BehaviorsLogs/"; -std::string DataRW::SimulationFolderName = "SimulationData/"; -std::string DataRW::KmlMapsFolderName = "KmlMaps/"; -std::string DataRW::PredictionFolderName = "PredictionResults/"; -std::string DataRW::TrackingFolderName = "TrackingLogs/"; +std::string DataRW::PathLogFolderName = "TrajectoriesLogs/"; +std::string DataRW::StatesLogFolderName = "BehaviorsLogs/"; +std::string DataRW::SimulationFolderName = "SimulationData/"; +std::string DataRW::KmlMapsFolderName = "KmlMaps/"; +std::string DataRW::PredictionFolderName = "PredictionResults/"; +std::string DataRW::TrackingFolderName = "TrackingLogs/"; DataRW::DataRW() @@ -37,2039 +37,2039 @@ DataRW::~DataRW() void DataRW::CreateLoggingFolder() { - std::string main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName; - int dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - if (-1 == dir_err) - cout << "Can't Create OpenPlanner Log Path!n" << endl; + std::string main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName; + int dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + if (-1 == dir_err) + cout << "Can't Create OpenPlanner Log Path!n" << endl; - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::ControlLogFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::ControlLogFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::GlobalPathLogFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::GlobalPathLogFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::PathLogFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::PathLogFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::StatesLogFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::StatesLogFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::SimulationFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::SimulationFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::PredictionFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::PredictionFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::TrackingFolderName; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + DataRW::TrackingFolderName; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar1"; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar1"; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar2"; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar2"; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar3"; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar3"; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar4"; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar4"; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); - main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar5"; - dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); + main_folder = UtilityH::GetHomeDirectory() + DataRW::LoggingMainfolderName + "SimulatedCar5"; + dir_err = mkdir(main_folder.c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH); } void DataRW::WriteLogData(const std::string& logFolder, const std::string& logTitle, const std::string& header, const std::vector& logData) { - if(logData.size() < 2) - return; + if(logData.size() < 2) + return; - ostringstream fileName; - fileName << logFolder; - fileName << logTitle; - fileName << UtilityH::GetFilePrefixHourMinuteSeconds(); - fileName << ".csv"; + ostringstream fileName; + fileName << logFolder; + fileName << logTitle; + fileName << UtilityH::GetFilePrefixHourMinuteSeconds(); + fileName << ".csv"; - std::ofstream f(fileName.str().c_str()); + std::ofstream f(fileName.str().c_str()); - if(f.is_open()) - { - if(header.size() > 0) - f << header << "\r\n"; - for(unsigned int i = 0 ; i < logData.size(); i++) - f << logData.at(i) << "\r\n"; - } + if(f.is_open()) + { + if(header.size() > 0) + f << header << "\r\n"; + for(unsigned int i = 0 ; i < logData.size(); i++) + f << logData.at(i) << "\r\n"; + } - f.close(); + f.close(); } void DataRW::WriteKMLFile(const string& fileName, const vector& gps_list) { - TiXmlDocument kmldoc(UtilityH::GetHomeDirectory()+DataRW::KmlMapsFolderName + "KmlTemplate.kml"); + TiXmlDocument kmldoc(UtilityH::GetHomeDirectory()+DataRW::KmlMapsFolderName + "KmlTemplate.kml"); - bool bkmlFileLoaded = kmldoc.LoadFile(); + bool bkmlFileLoaded = kmldoc.LoadFile(); - assert(bkmlFileLoaded== true); + assert(bkmlFileLoaded== true); - TiXmlElement* pElem = kmldoc.FirstChildElement(); + TiXmlElement* pElem = kmldoc.FirstChildElement(); - if(!pElem) - { - printf("\n Empty KML File !"); - return; - } + if(!pElem) + { + printf("\n Empty KML File !"); + return; + } - TiXmlElement* pV=0; - TiXmlHandle hKmlFile(pElem); + TiXmlElement* pV=0; + TiXmlHandle hKmlFile(pElem); - //pV = hKmlFile.FirstChild("Folder").FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); - pV = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); - if(!pV) - pV = hKmlFile.FirstChild( "Placemark" ).FirstChild("LineString").FirstChild("coordinates").Element(); + //pV = hKmlFile.FirstChild("Folder").FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); + pV = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); + if(!pV) + pV = hKmlFile.FirstChild( "Placemark" ).FirstChild("LineString").FirstChild("coordinates").Element(); - if(pV) - { - ostringstream val; - val.precision(18); + if(pV) + { + ostringstream val; + val.precision(18); - for(unsigned int i =0; i < gps_list.size(); i++) - { - val << gps_list[i] << " "; - } + for(unsigned int i =0; i < gps_list.size(); i++) + { + val << gps_list[i] << " "; + } - TiXmlText * text = new TiXmlText( val.str() ); - pV->LinkEndChild(text); - } + TiXmlText * text = new TiXmlText( val.str() ); + pV->LinkEndChild(text); + } - kmldoc.SaveFile(fileName); + kmldoc.SaveFile(fileName); } void DataRW::WriteKMLFile(const string& fileName, const vector >& gps_list) { - TiXmlDocument kmldoc(UtilityH::GetHomeDirectory()+DataRW::KmlMapsFolderName + "KmlTemplate.kml"); + TiXmlDocument kmldoc(UtilityH::GetHomeDirectory()+DataRW::KmlMapsFolderName + "KmlTemplate.kml"); - bool bkmlFileLoaded = kmldoc.LoadFile(); + bool bkmlFileLoaded = kmldoc.LoadFile(); - assert(bkmlFileLoaded== true); + assert(bkmlFileLoaded== true); - TiXmlElement* pElem = kmldoc.FirstChildElement(); + TiXmlElement* pElem = kmldoc.FirstChildElement(); - if(!pElem) - { - printf("\n Empty KML File !"); - return; - } + if(!pElem) + { + printf("\n Empty KML File !"); + return; + } - TiXmlNode* pV=0; - TiXmlNode* pPlaceMarkNode=0; - TiXmlElement* pDocument=0; - TiXmlHandle hKmlFile(pElem); + TiXmlNode* pV=0; + TiXmlNode* pPlaceMarkNode=0; + TiXmlElement* pDocument=0; + TiXmlHandle hKmlFile(pElem); - //pV = hKmlFile.FirstChild("Folder").FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); + //pV = hKmlFile.FirstChild("Folder").FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); - pDocument = hKmlFile.FirstChild("Folder").FirstChild("Document").Element(); - pPlaceMarkNode = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").Node(); + pDocument = hKmlFile.FirstChild("Folder").FirstChild("Document").Element(); + pPlaceMarkNode = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").Node(); - if(!pDocument) - { - pDocument = hKmlFile.Element(); - pPlaceMarkNode = hKmlFile.FirstChild( "Placemark" ).Node(); - } + if(!pDocument) + { + pDocument = hKmlFile.Element(); + pPlaceMarkNode = hKmlFile.FirstChild( "Placemark" ).Node(); + } -// pV = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); -// if(!pV) -// pV = hKmlFile.FirstChild( "Placemark" ).FirstChild("LineString").FirstChild("coordinates").Element(); +// pV = hKmlFile.FirstChild("Folder").FirstChild("Document").FirstChild("Placemark").FirstChild("LineString").FirstChild("coordinates").Element(); +// if(!pV) +// pV = hKmlFile.FirstChild( "Placemark" ).FirstChild("LineString").FirstChild("coordinates").Element(); - if(pDocument) - { - for(unsigned int l = 0; l < gps_list.size(); l++) - { + if(pDocument) + { + for(unsigned int l = 0; l < gps_list.size(); l++) + { - pV = pPlaceMarkNode->Clone(); - TiXmlElement* pElement = pV->FirstChild("LineString")->FirstChild("coordinates")->ToElement(); + pV = pPlaceMarkNode->Clone(); + TiXmlElement* pElement = pV->FirstChild("LineString")->FirstChild("coordinates")->ToElement(); - ostringstream val; - val.precision(18); + ostringstream val; + val.precision(18); - for(unsigned int i =0; i < gps_list[l].size(); i++) - { - val << gps_list[l][i] << " "; - } + for(unsigned int i =0; i < gps_list[l].size(); i++) + { + val << gps_list[l][i] << " "; + } - TiXmlText * text = new TiXmlText( val.str() ); - pElement->LinkEndChild(text); + TiXmlText * text = new TiXmlText( val.str() ); + pElement->LinkEndChild(text); - pDocument->InsertEndChild(*pV); + pDocument->InsertEndChild(*pV); - } + } - } + } - kmldoc.SaveFile(fileName); + kmldoc.SaveFile(fileName); } SimpleReaderBase::SimpleReaderBase(const string& fileName, const int& nHeaders,const char& separator, - const int& iDataTitles, const int& nVariablesForOneObject , - const int& nLineHeaders, const string& headerRepeatKey) -{ - if(fileName.compare("d") != 0) - { - m_pFile = new ifstream(fileName.c_str(), ios::in); - if(!m_pFile->is_open()) - { - printf("\n Can't Open Map File !, %s", fileName.c_str()); - return; - } - - m_nHeders = nHeaders; - m_iDataTitles = iDataTitles; - m_nVarPerObj = nVariablesForOneObject; - m_HeaderRepeatKey = headerRepeatKey; - m_nLineHeaders = nLineHeaders; - m_Separator = separator; - m_pFile->precision(16); - - ReadHeaders(); - } + const int& iDataTitles, const int& nVariablesForOneObject , + const int& nLineHeaders, const string& headerRepeatKey) +{ + if(fileName.compare("d") != 0) + { + m_pFile = new ifstream(fileName.c_str(), ios::in); + if(!m_pFile->is_open()) + { + printf("\n Can't Open Map File !, %s", fileName.c_str()); + return; + } + + m_nHeders = nHeaders; + m_iDataTitles = iDataTitles; + m_nVarPerObj = nVariablesForOneObject; + m_HeaderRepeatKey = headerRepeatKey; + m_nLineHeaders = nLineHeaders; + m_Separator = separator; + m_pFile->precision(16); + + ReadHeaders(); + } } SimpleReaderBase::~SimpleReaderBase() { - if(m_pFile->is_open()) - m_pFile->close(); + if(m_pFile->is_open()) + m_pFile->close(); } bool SimpleReaderBase::ReadSingleLine(vector >& line) { - if(!m_pFile->is_open() || m_pFile->eof()) return false; - - string strLine, innerToken; - line.clear(); - getline(*m_pFile, strLine); - istringstream str_stream(strLine); - - vector header; - vector obj_part; - - if(m_nVarPerObj == 0) - { - while(getline(str_stream, innerToken, m_Separator)) - { - obj_part.push_back(innerToken); - } - - line.push_back(obj_part); - return true; - } - else - { - int iCounter = 0; - while(iCounter < m_nLineHeaders && getline(str_stream, innerToken, m_Separator)) - { - header.push_back(innerToken); - iCounter++; - } - obj_part.insert(obj_part.begin(), header.begin(), header.end()); - - iCounter = 1; - - while(getline(str_stream, innerToken, m_Separator)) - { - obj_part.push_back(innerToken); - if(iCounter == m_nVarPerObj) - { - line.push_back(obj_part); - obj_part.clear(); - - iCounter = 0; - obj_part.insert(obj_part.begin(), header.begin(), header.end()); - - } - iCounter++; - } - } - - return true; + if(!m_pFile->is_open() || m_pFile->eof()) return false; + + string strLine, innerToken; + line.clear(); + getline(*m_pFile, strLine); + istringstream str_stream(strLine); + + vector header; + vector obj_part; + + if(m_nVarPerObj == 0) + { + while(getline(str_stream, innerToken, m_Separator)) + { + obj_part.push_back(innerToken); + } + + line.push_back(obj_part); + return true; + } + else + { + int iCounter = 0; + while(iCounter < m_nLineHeaders && getline(str_stream, innerToken, m_Separator)) + { + header.push_back(innerToken); + iCounter++; + } + obj_part.insert(obj_part.begin(), header.begin(), header.end()); + + iCounter = 1; + + while(getline(str_stream, innerToken, m_Separator)) + { + obj_part.push_back(innerToken); + if(iCounter == m_nVarPerObj) + { + line.push_back(obj_part); + obj_part.clear(); + + iCounter = 0; + obj_part.insert(obj_part.begin(), header.begin(), header.end()); + + } + iCounter++; + } + } + + return true; } int SimpleReaderBase::ReadAllData() { - if(!m_pFile->is_open()) return 0; + if(!m_pFile->is_open()) return 0; - m_AllData.clear(); - vector > singleLine; - while(!m_pFile->eof()) - { - ReadSingleLine(singleLine); - m_AllData.push_back(singleLine); - } + m_AllData.clear(); + vector > singleLine; + while(!m_pFile->eof()) + { + ReadSingleLine(singleLine); + m_AllData.push_back(singleLine); + } - return m_AllData.size(); + return m_AllData.size(); } void SimpleReaderBase::ReadHeaders() { - if(!m_pFile->is_open()) return; + if(!m_pFile->is_open()) return; - string strLine; - int iCounter = 0; - m_RawHeaders.clear(); - while(!m_pFile->eof() && iCounter < m_nHeders) - { - getline(*m_pFile, strLine); - m_RawHeaders.push_back(strLine); - if(iCounter == m_iDataTitles) - ParseDataTitles(strLine); - iCounter++; - } + string strLine; + int iCounter = 0; + m_RawHeaders.clear(); + while(!m_pFile->eof() && iCounter < m_nHeders) + { + getline(*m_pFile, strLine); + m_RawHeaders.push_back(strLine); + if(iCounter == m_iDataTitles) + ParseDataTitles(strLine); + iCounter++; + } } void SimpleReaderBase::ParseDataTitles(const string& header) { - if(header.size()==0) return; + if(header.size()==0) return; - string innerToken; - istringstream str_stream(header); - m_DataTitlesHeader.clear(); - while(getline(str_stream, innerToken, m_Separator)) - { - if(innerToken.compare(m_HeaderRepeatKey)!=0) - m_DataTitlesHeader.push_back(innerToken); - } + string innerToken; + istringstream str_stream(header); + m_DataTitlesHeader.clear(); + while(getline(str_stream, innerToken, m_Separator)) + { + if(innerToken.compare(m_HeaderRepeatKey)!=0) + m_DataTitlesHeader.push_back(innerToken); + } } bool GPSDataReader::ReadNextLine(GPSBasicData& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.lat = strtod(lineData.at(0).at(2).c_str(), NULL); - data.lon = strtod(lineData.at(0).at(3).c_str(), NULL); - data.alt = strtod(lineData.at(0).at(4).c_str(), NULL); - data.distance = strtod(lineData.at(0).at(5).c_str(), NULL); + data.lat = strtod(lineData.at(0).at(2).c_str(), NULL); + data.lon = strtod(lineData.at(0).at(3).c_str(), NULL); + data.alt = strtod(lineData.at(0).at(4).c_str(), NULL); + data.distance = strtod(lineData.at(0).at(5).c_str(), NULL); - return true; + return true; - } - else - return false; + } + else + return false; } int GPSDataReader::ReadAllData(vector& data_list) { - data_list.clear(); - GPSBasicData data; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + GPSBasicData data; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } bool SimulationFileReader::ReadNextLine(SimulationPoint& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 6) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 6) return false; - data.x = strtod(lineData.at(0).at(0).c_str(), NULL); - data.y = strtod(lineData.at(0).at(1).c_str(), NULL); - data.z = strtod(lineData.at(0).at(2).c_str(), NULL); - data.a = strtod(lineData.at(0).at(3).c_str(), NULL); - data.c = strtod(lineData.at(0).at(4).c_str(), NULL); - data.v = strtod(lineData.at(0).at(5).c_str(), NULL); - data.name = lineData.at(0).at(6); + data.x = strtod(lineData.at(0).at(0).c_str(), NULL); + data.y = strtod(lineData.at(0).at(1).c_str(), NULL); + data.z = strtod(lineData.at(0).at(2).c_str(), NULL); + data.a = strtod(lineData.at(0).at(3).c_str(), NULL); + data.c = strtod(lineData.at(0).at(4).c_str(), NULL); + data.v = strtod(lineData.at(0).at(5).c_str(), NULL); + data.name = lineData.at(0).at(6); - return true; + return true; - } - else - return false; + } + else + return false; } int SimulationFileReader::ReadAllData(SimulationData& data_list) { - data_list.simuCars.clear(); - SimulationPoint data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - if(count == 0) - data_list.startPoint = data; - else if(count == 1) - data_list.goalPoint = data; - else - data_list.simuCars.push_back(data); - - count++; - } + data_list.simuCars.clear(); + SimulationPoint data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + if(count == 0) + data_list.startPoint = data; + else if(count == 1) + data_list.goalPoint = data; + else + data_list.simuCars.push_back(data); + + count++; + } - return count; + return count; } bool LocalizationPathReader::ReadNextLine(LocalizationWayPoint& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - //data.t = strtod(lineData.at(0).at(0).c_str(), NULL); - data.x = strtod(lineData.at(0).at(0).c_str(), NULL); - data.y = strtod(lineData.at(0).at(1).c_str(), NULL); - data.z = strtod(lineData.at(0).at(2).c_str(), NULL); - data.a = strtod(lineData.at(0).at(3).c_str(), NULL); - data.v = strtod(lineData.at(0).at(4).c_str(), NULL); + //data.t = strtod(lineData.at(0).at(0).c_str(), NULL); + data.x = strtod(lineData.at(0).at(0).c_str(), NULL); + data.y = strtod(lineData.at(0).at(1).c_str(), NULL); + data.z = strtod(lineData.at(0).at(2).c_str(), NULL); + data.a = strtod(lineData.at(0).at(3).c_str(), NULL); + data.v = strtod(lineData.at(0).at(4).c_str(), NULL); - return true; + return true; - } - else - return false; + } + else + return false; } int LocalizationPathReader::ReadAllData(vector& data_list) { - data_list.clear(); - LocalizationWayPoint data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + LocalizationWayPoint data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Nodes AisanNodesFileReader::AisanNodesFileReader(const vector_map_msgs::NodeArray& _nodes) : SimpleReaderBase("d", 1) { - if(_nodes.data.size()==0) return; + if(_nodes.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - //TODO Fix PID and NID problem + //TODO Fix PID and NID problem - m_data_list.clear(); - AisanNode data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanNode data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _nodes.data.size(); i++) - { - ParseNextLine(_nodes.data.at(i), data); + for(unsigned int i=0; i < _nodes.data.size(); i++) + { + ParseNextLine(_nodes.data.at(i), data); - m_data_list.push_back(data); - if(data.NID < m_min_id) - m_min_id = data.NID; + m_data_list.push_back(data); + if(data.NID < m_min_id) + m_min_id = data.NID; - if(data.NID > max_id) - max_id = data.NID; - } + if(data.NID > max_id) + max_id = data.NID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).NID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).NID-m_min_id) = &m_data_list.at(i); + } } void AisanNodesFileReader::ParseNextLine(const vector_map_msgs::Node& _rec, AisanNode& data) { - data.NID = _rec.nid; - data.PID = _rec.pid; + data.NID = _rec.nid; + data.PID = _rec.pid; } AisanNodesFileReader::AisanNode* AisanNodesFileReader::GetDataRowById(int _nid) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _nid-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).NID == _nid) - { - return &m_data_list.at(i); - } - } - } + int index = _nid-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).NID == _nid) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanNodesFileReader::ReadNextLine(AisanNode& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 2) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 2) return false; - data.NID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.PID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.NID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.PID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanNodesFileReader::ReadAllData(vector& data_list) { - m_data_list.clear(); - AisanNode data; - //double logTime = 0; - int max_id = std::numeric_limits::min(); - while(ReadNextLine(data)) - { - m_data_list.push_back(data); - if(data.NID < m_min_id) - m_min_id = data.NID; + m_data_list.clear(); + AisanNode data; + //double logTime = 0; + int max_id = std::numeric_limits::min(); + while(ReadNextLine(data)) + { + m_data_list.push_back(data); + if(data.NID < m_min_id) + m_min_id = data.NID; - if(data.NID > max_id) - max_id = data.NID; - } + if(data.NID > max_id) + max_id = data.NID; + } - m_data_map.resize(max_id - m_min_id + 2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).NID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id - m_min_id + 2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).NID-m_min_id) = &m_data_list.at(i); + } - data_list = m_data_list; - return m_data_list.size(); + data_list = m_data_list; + return m_data_list.size(); } //Points AisanPointsFileReader::AisanPointsFileReader(const vector_map_msgs::PointArray& _points) : SimpleReaderBase("d", 1) { - if(_points.data.size()==0) return; + if(_points.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanPoints data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanPoints data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _points.data.size(); i++) - { - ParseNextLine(_points.data.at(i), data); + for(unsigned int i=0; i < _points.data.size(); i++) + { + ParseNextLine(_points.data.at(i), data); - m_data_list.push_back(data); - if(data.PID < m_min_id) - m_min_id = data.PID; + m_data_list.push_back(data); + if(data.PID < m_min_id) + m_min_id = data.PID; - if(data.PID > max_id) - max_id = data.PID; - } + if(data.PID > max_id) + max_id = data.PID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).PID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).PID-m_min_id) = &m_data_list.at(i); + } } void AisanPointsFileReader::ParseNextLine(const vector_map_msgs::Point& _rec, AisanPoints& data) { - data.B = _rec.b; - data.Bx = _rec.bx; - data.H = _rec.h; - data.L = _rec.l; - data.Ly = _rec.ly; - data.MCODE1 = _rec.mcode1; - data.MCODE2 = _rec.mcode2; - data.MCODE3 = _rec.mcode3; - data.PID = _rec.pid; - data.Ref = _rec.ref; + data.B = _rec.b; + data.Bx = _rec.bx; + data.H = _rec.h; + data.L = _rec.l; + data.Ly = _rec.ly; + data.MCODE1 = _rec.mcode1; + data.MCODE2 = _rec.mcode2; + data.MCODE3 = _rec.mcode3; + data.PID = _rec.pid; + data.Ref = _rec.ref; } AisanPointsFileReader::AisanPoints* AisanPointsFileReader::GetDataRowById(int _pid) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _pid-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).PID == _pid) - { - return &m_data_list.at(i); - } - } - } + int index = _pid-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).PID == _pid) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanPointsFileReader::ReadNextLine(AisanPoints& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 10) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 10) return false; - data.PID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.B = strtod(lineData.at(0)[1].c_str(), NULL); - data.L = strtod(lineData.at(0)[2].c_str(), NULL); - data.H = strtod(lineData.at(0)[3].c_str(), NULL); + data.PID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.B = strtod(lineData.at(0)[1].c_str(), NULL); + data.L = strtod(lineData.at(0)[2].c_str(), NULL); + data.H = strtod(lineData.at(0)[3].c_str(), NULL); - data.Bx = strtod(lineData.at(0)[4].c_str(), NULL); - data.Ly = strtod(lineData.at(0)[5].c_str(), NULL); - data.Ref = strtol(lineData.at(0).at(6).c_str(), NULL, 10); - data.MCODE1 = strtol(lineData.at(0).at(7).c_str(), NULL, 10); - data.MCODE2 = strtol(lineData.at(0).at(8).c_str(), NULL, 10); - data.MCODE3 = strtol(lineData.at(0).at(9).c_str(), NULL, 10); + data.Bx = strtod(lineData.at(0)[4].c_str(), NULL); + data.Ly = strtod(lineData.at(0)[5].c_str(), NULL); + data.Ref = strtol(lineData.at(0).at(6).c_str(), NULL, 10); + data.MCODE1 = strtol(lineData.at(0).at(7).c_str(), NULL, 10); + data.MCODE2 = strtol(lineData.at(0).at(8).c_str(), NULL, 10); + data.MCODE3 = strtol(lineData.at(0).at(9).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanPointsFileReader::ReadAllData(vector& data_list) { - m_data_list.clear(); - AisanPoints data; - //double logTime = 0; - int max_id = std::numeric_limits::min(); - while(ReadNextLine(data)) - { - m_data_list.push_back(data); - if(data.PID < m_min_id) - m_min_id = data.PID; + m_data_list.clear(); + AisanPoints data; + //double logTime = 0; + int max_id = std::numeric_limits::min(); + while(ReadNextLine(data)) + { + m_data_list.push_back(data); + if(data.PID < m_min_id) + m_min_id = data.PID; - if(data.PID > max_id) - max_id = data.PID; - } + if(data.PID > max_id) + max_id = data.PID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).PID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).PID-m_min_id) = &m_data_list.at(i); + } - data_list = m_data_list; - return m_data_list.size(); + data_list = m_data_list; + return m_data_list.size(); } // Lines AisanLinesFileReader::AisanLinesFileReader(const vector_map_msgs::LineArray& _nodes) : SimpleReaderBase("d", 1) { - if(_nodes.data.size()==0) return; + if(_nodes.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanLine data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanLine data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _nodes.data.size(); i++) - { - ParseNextLine(_nodes.data.at(i), data); + for(unsigned int i=0; i < _nodes.data.size(); i++) + { + ParseNextLine(_nodes.data.at(i), data); - m_data_list.push_back(data); - if(data.LID < m_min_id) - m_min_id = data.LID; + m_data_list.push_back(data); + if(data.LID < m_min_id) + m_min_id = data.LID; - if(data.LID > max_id) - max_id = data.LID; - } + if(data.LID > max_id) + max_id = data.LID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).LID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).LID-m_min_id) = &m_data_list.at(i); + } } void AisanLinesFileReader::ParseNextLine(const vector_map_msgs::Line& _rec, AisanLine& data) { - data.BLID = _rec.blid; - data.BPID = _rec.bpid; - data.FLID = _rec.flid; - data.FPID = _rec.fpid; - data.LID = _rec.lid; + data.BLID = _rec.blid; + data.BPID = _rec.bpid; + data.FLID = _rec.flid; + data.FPID = _rec.fpid; + data.LID = _rec.lid; } AisanLinesFileReader::AisanLine* AisanLinesFileReader::GetDataRowById(int _lid) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _lid-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).LID == _lid) - { - return &m_data_list.at(i); - } - } - } + int index = _lid-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).LID == _lid) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanLinesFileReader::ReadNextLine(AisanLine& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.LID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.BPID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.FPID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.BLID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.FLID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.LID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.BPID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.FPID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.BLID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.FLID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - return true; - } - else - return false; + return true; + } + else + return false; } int AisanLinesFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanLine data; - //double logTime = 0; + data_list.clear(); + AisanLine data; + //double logTime = 0; - int max_id = std::numeric_limits::min(); - while(ReadNextLine(data)) - { - m_data_list.push_back(data); - if(data.LID < m_min_id) - m_min_id = data.LID; + int max_id = std::numeric_limits::min(); + while(ReadNextLine(data)) + { + m_data_list.push_back(data); + if(data.LID < m_min_id) + m_min_id = data.LID; - if(data.LID > max_id) - max_id = data.LID; - } + if(data.LID > max_id) + max_id = data.LID; + } - m_data_map.resize(max_id - m_min_id + 2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).LID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id - m_min_id + 2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).LID-m_min_id) = &m_data_list.at(i); + } - data_list = m_data_list; - return m_data_list.size(); + data_list = m_data_list; + return m_data_list.size(); } //dt Lanes (center lines) AisanCenterLinesFileReader::AisanCenterLinesFileReader(const vector_map_msgs::DTLaneArray& _Lines) : SimpleReaderBase("d", 1) { - if(_Lines.data.size()==0) return; + if(_Lines.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanCenterLine data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanCenterLine data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _Lines.data.size(); i++) - { - ParseNextLine(_Lines.data.at(i), data); + for(unsigned int i=0; i < _Lines.data.size(); i++) + { + ParseNextLine(_Lines.data.at(i), data); - m_data_list.push_back(data); - if(data.DID < m_min_id) - m_min_id = data.DID; + m_data_list.push_back(data); + if(data.DID < m_min_id) + m_min_id = data.DID; - if(data.DID > max_id) - max_id = data.DID; - } + if(data.DID > max_id) + max_id = data.DID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).DID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).DID-m_min_id) = &m_data_list.at(i); + } } void AisanCenterLinesFileReader::ParseNextLine(const vector_map_msgs::DTLane& _rec, AisanCenterLine& data) { - data.Apara = _rec.apara; - data.DID = _rec.did; - data.Dir = _rec.dir; - data.Dist = _rec.dist; - data.LW = _rec.lw; - data.PID = _rec.pid; - data.RW = _rec.rw; - data.cant = _rec.cant; - data.r = _rec.r; - data.slope = _rec.slope; + data.Apara = _rec.apara; + data.DID = _rec.did; + data.Dir = _rec.dir; + data.Dist = _rec.dist; + data.LW = _rec.lw; + data.PID = _rec.pid; + data.RW = _rec.rw; + data.cant = _rec.cant; + data.r = _rec.r; + data.slope = _rec.slope; } AisanCenterLinesFileReader::AisanCenterLine* AisanCenterLinesFileReader::GetDataRowById(int _did) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _did-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).DID == _did) - { - return &m_data_list.at(i); - } - } - } + int index = _did-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).DID == _did) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanCenterLinesFileReader::ReadNextLine(AisanCenterLine& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 10) return false; - - data.DID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.Dist = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.PID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - - data.Dir = strtod(lineData.at(0)[3].c_str(), NULL); - data.Apara = strtod(lineData.at(0)[4].c_str(), NULL); - data.r = strtod(lineData.at(0)[5].c_str(), NULL); - data.slope = strtod(lineData.at(0)[6].c_str(), NULL); - data.cant = strtod(lineData.at(0)[7].c_str(), NULL); - data.LW = strtod(lineData.at(0)[8].c_str(), NULL); - data.RW = strtod(lineData.at(0)[9].c_str(), NULL); - - return true; - } - else - return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 10) return false; + + data.DID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.Dist = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.PID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + + data.Dir = strtod(lineData.at(0)[3].c_str(), NULL); + data.Apara = strtod(lineData.at(0)[4].c_str(), NULL); + data.r = strtod(lineData.at(0)[5].c_str(), NULL); + data.slope = strtod(lineData.at(0)[6].c_str(), NULL); + data.cant = strtod(lineData.at(0)[7].c_str(), NULL); + data.LW = strtod(lineData.at(0)[8].c_str(), NULL); + data.RW = strtod(lineData.at(0)[9].c_str(), NULL); + + return true; + } + else + return false; } int AisanCenterLinesFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanCenterLine data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanCenterLine data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Lane AisanLanesFileReader::AisanLanesFileReader(const vector_map_msgs::LaneArray& _lanes) : SimpleReaderBase("d", 1) { - if(_lanes.data.size()==0) return; + if(_lanes.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanLane data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanLane data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _lanes.data.size(); i++) - { - ParseNextLine(_lanes.data.at(i), data); + for(unsigned int i=0; i < _lanes.data.size(); i++) + { + ParseNextLine(_lanes.data.at(i), data); - m_data_list.push_back(data); - if(data.LnID < m_min_id) - m_min_id = data.LnID; + m_data_list.push_back(data); + if(data.LnID < m_min_id) + m_min_id = data.LnID; - if(data.LnID > max_id) - max_id = data.LnID; - } + if(data.LnID > max_id) + max_id = data.LnID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).LnID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).LnID-m_min_id) = &m_data_list.at(i); + } } void AisanLanesFileReader::ParseNextLine(const vector_map_msgs::Lane& _rec, AisanLane& data) { - data.BLID = _rec.blid; - data.BLID2 = _rec.blid2; - data.BLID3 = _rec.blid3; - data.BLID4 = _rec.blid4; - data.BNID = _rec.bnid; - data.ClossID = _rec.clossid; - data.DID = _rec.did; - data.FLID = _rec.flid; - data.FLID2 = _rec.flid2; - data.FLID3 = _rec.flid3; - data.FLID4 = _rec.flid4; - - data.FNID = _rec.fnid; - data.JCT = _rec.jct; - data.LCnt = _rec.lcnt; - data.LaneChgFG = _rec.lanecfgfg; - //data.LaneDir = _rec.; - data.LaneType = _rec.lanetype; - //data.LeftLaneId = _rec.; - data.LimitVel = _rec.limitvel; - data.LinkWAID = _rec.linkwaid; - data.LnID = _rec.lnid; - data.Lno = _rec.lno; - data.RefVel = _rec.refvel; - //data.RightLaneId = _rec.; - data.RoadSecID = _rec.roadsecid; - data.Span = _rec.span; - //data.originalMapID = _rec.; + data.BLID = _rec.blid; + data.BLID2 = _rec.blid2; + data.BLID3 = _rec.blid3; + data.BLID4 = _rec.blid4; + data.BNID = _rec.bnid; + data.ClossID = _rec.clossid; + data.DID = _rec.did; + data.FLID = _rec.flid; + data.FLID2 = _rec.flid2; + data.FLID3 = _rec.flid3; + data.FLID4 = _rec.flid4; + + data.FNID = _rec.fnid; + data.JCT = _rec.jct; + data.LCnt = _rec.lcnt; + data.LaneChgFG = _rec.lanecfgfg; + //data.LaneDir = _rec.; + data.LaneType = _rec.lanetype; + //data.LeftLaneId = _rec.; + data.LimitVel = _rec.limitvel; + data.LinkWAID = _rec.linkwaid; + data.LnID = _rec.lnid; + data.Lno = _rec.lno; + data.RefVel = _rec.refvel; + //data.RightLaneId = _rec.; + data.RoadSecID = _rec.roadsecid; + data.Span = _rec.span; + //data.originalMapID = _rec.; } AisanLanesFileReader::AisanLane* AisanLanesFileReader::GetDataRowById(int _lnid) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _lnid-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).LnID == _lnid) - { - return &m_data_list.at(i); - } - } - } + int index = _lnid-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).LnID == _lnid) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanLanesFileReader::ReadNextLine(AisanLane& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size() == 0) return false; - if(lineData.at(0).size() < 17) return false; - - data.LnID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.DID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.BLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.FLID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.BNID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - data.FNID = strtol(lineData.at(0).at(5).c_str(), NULL, 10); - data.JCT = strtol(lineData.at(0).at(6).c_str(), NULL, 10); - data.BLID2 = strtol(lineData.at(0).at(7).c_str(), NULL, 10); - data.BLID3 = strtol(lineData.at(0).at(8).c_str(), NULL, 10); - data.BLID4 = strtol(lineData.at(0).at(9).c_str(), NULL, 10); - data.FLID2 = strtol(lineData.at(0).at(10).c_str(), NULL, 10); - data.FLID3 = strtol(lineData.at(0).at(11).c_str(), NULL, 10); - data.FLID4 = strtol(lineData.at(0).at(12).c_str(), NULL, 10); - data.ClossID = strtol(lineData.at(0).at(13).c_str(), NULL, 10); - data.Span = strtod(lineData.at(0).at(14).c_str(), NULL); - data.LCnt = strtol(lineData.at(0).at(15).c_str(), NULL, 10); - data.Lno = strtol(lineData.at(0).at(16).c_str(), NULL, 10); - - - if(lineData.at(0).size() < 23) return true; - - data.LaneType = strtol(lineData.at(0).at(17).c_str(), NULL, 10); - data.LimitVel = strtol(lineData.at(0).at(18).c_str(), NULL, 10); - data.RefVel = strtol(lineData.at(0).at(19).c_str(), NULL, 10); - data.RoadSecID = strtol(lineData.at(0).at(20).c_str(), NULL, 10); - data.LaneChgFG = strtol(lineData.at(0).at(21).c_str(), NULL, 10); - data.LinkWAID = strtol(lineData.at(0).at(22).c_str(), NULL, 10); - - - if(lineData.at(0).size() > 23) - { - string str_dir = lineData.at(0).at(23); - if(str_dir.size() > 0) - data.LaneDir = str_dir.at(0); - else - data.LaneDir = 'F'; - } - -// data.LeftLaneId = 0; -// data.RightLaneId = 0; -// data.LeftLaneId = strtol(lineData.at(0).at(24).c_str(), NULL, 10); -// data.RightLaneId = strtol(lineData.at(0).at(25).c_str(), NULL, 10); - - - return true; - } - else - return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size() == 0) return false; + if(lineData.at(0).size() < 17) return false; + + data.LnID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.DID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.BLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.FLID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.BNID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.FNID = strtol(lineData.at(0).at(5).c_str(), NULL, 10); + data.JCT = strtol(lineData.at(0).at(6).c_str(), NULL, 10); + data.BLID2 = strtol(lineData.at(0).at(7).c_str(), NULL, 10); + data.BLID3 = strtol(lineData.at(0).at(8).c_str(), NULL, 10); + data.BLID4 = strtol(lineData.at(0).at(9).c_str(), NULL, 10); + data.FLID2 = strtol(lineData.at(0).at(10).c_str(), NULL, 10); + data.FLID3 = strtol(lineData.at(0).at(11).c_str(), NULL, 10); + data.FLID4 = strtol(lineData.at(0).at(12).c_str(), NULL, 10); + data.ClossID = strtol(lineData.at(0).at(13).c_str(), NULL, 10); + data.Span = strtod(lineData.at(0).at(14).c_str(), NULL); + data.LCnt = strtol(lineData.at(0).at(15).c_str(), NULL, 10); + data.Lno = strtol(lineData.at(0).at(16).c_str(), NULL, 10); + + + if(lineData.at(0).size() < 23) return true; + + data.LaneType = strtol(lineData.at(0).at(17).c_str(), NULL, 10); + data.LimitVel = strtol(lineData.at(0).at(18).c_str(), NULL, 10); + data.RefVel = strtol(lineData.at(0).at(19).c_str(), NULL, 10); + data.RoadSecID = strtol(lineData.at(0).at(20).c_str(), NULL, 10); + data.LaneChgFG = strtol(lineData.at(0).at(21).c_str(), NULL, 10); + data.LinkWAID = strtol(lineData.at(0).at(22).c_str(), NULL, 10); + + + if(lineData.at(0).size() > 23) + { + string str_dir = lineData.at(0).at(23); + if(str_dir.size() > 0) + data.LaneDir = str_dir.at(0); + else + data.LaneDir = 'F'; + } + +// data.LeftLaneId = 0; +// data.RightLaneId = 0; +// data.LeftLaneId = strtol(lineData.at(0).at(24).c_str(), NULL, 10); +// data.RightLaneId = strtol(lineData.at(0).at(25).c_str(), NULL, 10); + + + return true; + } + else + return false; } int AisanLanesFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanLane data; - //double logTime = 0; - int max_id = std::numeric_limits::min(); + data_list.clear(); + AisanLane data; + //double logTime = 0; + int max_id = std::numeric_limits::min(); - while(ReadNextLine(data)) - { - m_data_list.push_back(data); - if(data.LnID < m_min_id) - m_min_id = data.LnID; + while(ReadNextLine(data)) + { + m_data_list.push_back(data); + if(data.LnID < m_min_id) + m_min_id = data.LnID; - if(data.LnID > max_id) - max_id = data.LnID; - } + if(data.LnID > max_id) + max_id = data.LnID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).LnID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).LnID-m_min_id) = &m_data_list.at(i); + } - data_list = m_data_list; + data_list = m_data_list; - return m_data_list.size(); + return m_data_list.size(); } //Area AisanAreasFileReader::AisanAreasFileReader(const vector_map_msgs::AreaArray& _areas) : SimpleReaderBase("d", 1) { - if(_areas.data.size()==0) return; + if(_areas.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanArea data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanArea data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _areas.data.size(); i++) - { - ParseNextLine(_areas.data.at(i), data); + for(unsigned int i=0; i < _areas.data.size(); i++) + { + ParseNextLine(_areas.data.at(i), data); - m_data_list.push_back(data); - if(data.AID < m_min_id) - m_min_id = data.AID; + m_data_list.push_back(data); + if(data.AID < m_min_id) + m_min_id = data.AID; - if(data.AID > max_id) - max_id = data.AID; - } + if(data.AID > max_id) + max_id = data.AID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).AID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).AID-m_min_id) = &m_data_list.at(i); + } } void AisanAreasFileReader::ParseNextLine(const vector_map_msgs::Area& _rec, AisanArea& data) { - data.AID = _rec.aid; - data.ELID = _rec.elid; - data.SLID = _rec.slid; + data.AID = _rec.aid; + data.ELID = _rec.elid; + data.SLID = _rec.slid; } AisanAreasFileReader::AisanArea* AisanAreasFileReader::GetDataRowById(int _aid) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _aid-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).AID == _aid) - { - return &m_data_list.at(i); - } - } - } + int index = _aid-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).AID == _aid) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanAreasFileReader::ReadNextLine(AisanArea& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 3) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 3) return false; - data.AID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.SLID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.ELID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.AID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.SLID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.ELID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanAreasFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanArea data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanArea data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Intersection AisanIntersectionFileReader::AisanIntersectionFileReader(const vector_map_msgs::CrossRoadArray& _inters) : SimpleReaderBase("d", 1) { - if(_inters.data.size()==0) return; + if(_inters.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanIntersection data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanIntersection data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _inters.data.size(); i++) - { - ParseNextLine(_inters.data.at(i), data); + for(unsigned int i=0; i < _inters.data.size(); i++) + { + ParseNextLine(_inters.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanIntersectionFileReader::ParseNextLine(const vector_map_msgs::CrossRoad& _rec, AisanIntersection& data) { - data.AID = _rec.aid; - data.ID = _rec.id; - data.LinkID = _rec.linkid; + data.AID = _rec.aid; + data.ID = _rec.id; + data.LinkID = _rec.linkid; } AisanIntersectionFileReader::AisanIntersection* AisanIntersectionFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanIntersectionFileReader::ReadNextLine(AisanIntersection& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 3) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 3) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanIntersectionFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanIntersection data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanIntersection data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //StopLine AisanStopLineFileReader::AisanStopLineFileReader(const vector_map_msgs::StopLineArray& _stopLines) : SimpleReaderBase("d", 1) { - if(_stopLines.data.size()==0) return; + if(_stopLines.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanStopLine data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanStopLine data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _stopLines.data.size(); i++) - { - ParseNextLine(_stopLines.data.at(i), data); + for(unsigned int i=0; i < _stopLines.data.size(); i++) + { + ParseNextLine(_stopLines.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanStopLineFileReader::ParseNextLine(const vector_map_msgs::StopLine& _rec, AisanStopLine& data) { - data.ID = _rec.id; - data.LID = _rec.lid; - data.LinkID = _rec.linkid; - data.SignID = _rec.signid; - data.TLID = _rec.tlid; + data.ID = _rec.id; + data.LID = _rec.lid; + data.LinkID = _rec.linkid; + data.SignID = _rec.signid; + data.TLID = _rec.tlid; } AisanStopLineFileReader::AisanStopLine* AisanStopLineFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanStopLineFileReader::ReadNextLine(AisanStopLine& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.TLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.SignID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.TLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.SignID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanStopLineFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanStopLine data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanStopLine data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //RoadSign AisanRoadSignFileReader::AisanRoadSignFileReader(const vector_map_msgs::RoadSignArray& _signs) : SimpleReaderBase("d", 1) { - if(_signs.data.size()==0) return; + if(_signs.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanRoadSign data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanRoadSign data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _signs.data.size(); i++) - { - ParseNextLine(_signs.data.at(i), data); + for(unsigned int i=0; i < _signs.data.size(); i++) + { + ParseNextLine(_signs.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanRoadSignFileReader::ParseNextLine(const vector_map_msgs::RoadSign& _rec, AisanRoadSign& data) { - data.ID = _rec.id; - data.LinkID = _rec.linkid; - data.PLID = _rec.plid; - data.Type = _rec.type; - data.VID = _rec.vid; + data.ID = _rec.id; + data.LinkID = _rec.linkid; + data.PLID = _rec.plid; + data.Type = _rec.type; + data.VID = _rec.vid; } AisanRoadSignFileReader::AisanRoadSign* AisanRoadSignFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanRoadSignFileReader::ReadNextLine(AisanRoadSign& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.VID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.PLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.Type = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.VID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.PLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.Type = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanRoadSignFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanRoadSign data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanRoadSign data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Signal AisanSignalFileReader::AisanSignalFileReader(const vector_map_msgs::SignalArray& _signal) : SimpleReaderBase("d", 1) { - if(_signal.data.size()==0) return; + if(_signal.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanSignal data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanSignal data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _signal.data.size(); i++) - { - ParseNextLine(_signal.data.at(i), data); + for(unsigned int i=0; i < _signal.data.size(); i++) + { + ParseNextLine(_signal.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanSignalFileReader::ParseNextLine(const vector_map_msgs::Signal& _rec, AisanSignal& data) { - data.ID = _rec.id; - data.LinkID = _rec.linkid; - data.PLID = _rec.plid; - data.Type = _rec.type; - data.VID = _rec.vid; + data.ID = _rec.id; + data.LinkID = _rec.linkid; + data.PLID = _rec.plid; + data.Type = _rec.type; + data.VID = _rec.vid; } AisanSignalFileReader::AisanSignal* AisanSignalFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanSignalFileReader::ReadNextLine(AisanSignal& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.VID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.PLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.Type = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.VID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.PLID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.Type = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanSignalFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanSignal data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } + data_list.clear(); + AisanSignal data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } - return count; + return count; } //Vector AisanVectorFileReader::AisanVectorFileReader(const vector_map_msgs::VectorArray& _vectors) : SimpleReaderBase("d", 1) { - if(_vectors.data.size()==0) return; + if(_vectors.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanVector data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanVector data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _vectors.data.size(); i++) - { - ParseNextLine(_vectors.data.at(i), data); + for(unsigned int i=0; i < _vectors.data.size(); i++) + { + ParseNextLine(_vectors.data.at(i), data); - m_data_list.push_back(data); - if(data.VID < m_min_id) - m_min_id = data.VID; + m_data_list.push_back(data); + if(data.VID < m_min_id) + m_min_id = data.VID; - if(data.VID > max_id) - max_id = data.VID; - } + if(data.VID > max_id) + max_id = data.VID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).VID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).VID-m_min_id) = &m_data_list.at(i); + } } void AisanVectorFileReader::ParseNextLine(const vector_map_msgs::Vector& _rec, AisanVector& data) { - data.Hang = _rec.hang; - data.PID = _rec.pid; - data.VID = _rec.vid; - data.Vang = _rec.vang; + data.Hang = _rec.hang; + data.PID = _rec.pid; + data.VID = _rec.vid; + data.Vang = _rec.vang; } AisanVectorFileReader::AisanVector* AisanVectorFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).VID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).VID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanVectorFileReader::ReadNextLine(AisanVector& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 4) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 4) return false; - data.VID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.PID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.Hang = strtod(lineData.at(0).at(2).c_str(), NULL); - data.Vang = strtod(lineData.at(0).at(3).c_str(), NULL); + data.VID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.PID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.Hang = strtod(lineData.at(0).at(2).c_str(), NULL); + data.Vang = strtod(lineData.at(0).at(3).c_str(), NULL); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanVectorFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanVector data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanVector data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Curb AisanCurbFileReader::AisanCurbFileReader(const vector_map_msgs::CurbArray& _curbs) : SimpleReaderBase("d", 1) { - if(_curbs.data.size()==0) return; + if(_curbs.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanCurb data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanCurb data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _curbs.data.size(); i++) - { - ParseNextLine(_curbs.data.at(i), data); + for(unsigned int i=0; i < _curbs.data.size(); i++) + { + ParseNextLine(_curbs.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanCurbFileReader::ParseNextLine(const vector_map_msgs::Curb& _rec, AisanCurb& data) { - data.Height = _rec.height; - data.ID = _rec.id; - data.LID = _rec.lid; - data.LinkID = _rec.linkid; - data.Width = _rec.width; - data.dir = _rec.dir; + data.Height = _rec.height; + data.ID = _rec.id; + data.LID = _rec.lid; + data.LinkID = _rec.linkid; + data.Width = _rec.width; + data.dir = _rec.dir; } AisanCurbFileReader::AisanCurb* AisanCurbFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanCurbFileReader::ReadNextLine(AisanCurb& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 6) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 6) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.Height = strtod(lineData.at(0).at(2).c_str(), NULL); - data.Width = strtod(lineData.at(0).at(3).c_str(), NULL); - data.dir = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(5).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.Height = strtod(lineData.at(0).at(2).c_str(), NULL); + data.Width = strtod(lineData.at(0).at(3).c_str(), NULL); + data.dir = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(5).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanCurbFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanCurb data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanCurb data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } // RoadEdge AisanRoadEdgeFileReader::AisanRoadEdgeFileReader(const vector_map_msgs::RoadEdgeArray& _edges) : SimpleReaderBase("d", 1) { - if(_edges.data.size()==0) return; + if(_edges.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanRoadEdge data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanRoadEdge data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _edges.data.size(); i++) - { - ParseNextLine(_edges.data.at(i), data); + for(unsigned int i=0; i < _edges.data.size(); i++) + { + ParseNextLine(_edges.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanRoadEdgeFileReader::ParseNextLine(const vector_map_msgs::RoadEdge& _rec, AisanRoadEdge& data) { - data.ID = _rec.id; - data.LID = _rec.lid; - data.LinkID = _rec.linkid; + data.ID = _rec.id; + data.LID = _rec.lid; + data.LinkID = _rec.linkid; } AisanRoadEdgeFileReader::AisanRoadEdge* AisanRoadEdgeFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanRoadEdgeFileReader::ReadNextLine(AisanRoadEdge& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 3) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 3) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.LID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanRoadEdgeFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanRoadEdge data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanRoadEdge data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //CrossWalk AisanCrossWalkFileReader::AisanCrossWalkFileReader(const vector_map_msgs::CrossWalkArray& _crossWalks) : SimpleReaderBase("d", 1) { - if(_crossWalks.data.size()==0) return; + if(_crossWalks.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanCrossWalk data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanCrossWalk data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _crossWalks.data.size(); i++) - { - ParseNextLine(_crossWalks.data.at(i), data); + for(unsigned int i=0; i < _crossWalks.data.size(); i++) + { + ParseNextLine(_crossWalks.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanCrossWalkFileReader::ParseNextLine(const vector_map_msgs::CrossWalk& _rec, AisanCrossWalk& data) { - data.AID = _rec.aid; - data.BdID = _rec.bdid; - data.ID = _rec.id; - data.LinkID = _rec.linkid; - data.Type = _rec.type; + data.AID = _rec.aid; + data.BdID = _rec.bdid; + data.ID = _rec.id; + data.LinkID = _rec.linkid; + data.Type = _rec.type; } AisanCrossWalkFileReader::AisanCrossWalk* AisanCrossWalkFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanCrossWalkFileReader::ReadNextLine(AisanCrossWalk& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 5) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 5) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.Type = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.BdID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.Type = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.BdID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(4).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanCrossWalkFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanCrossWalk data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanCrossWalk data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //WayArea AisanWayareaFileReader::AisanWayareaFileReader(const vector_map_msgs::WayAreaArray& _wayAreas) : SimpleReaderBase("d", 1) { - if(_wayAreas.data.size()==0) return; + if(_wayAreas.data.size()==0) return; - m_min_id = std::numeric_limits::max(); + m_min_id = std::numeric_limits::max(); - m_data_list.clear(); - AisanWayarea data; - int max_id = std::numeric_limits::min(); + m_data_list.clear(); + AisanWayarea data; + int max_id = std::numeric_limits::min(); - for(unsigned int i=0; i < _wayAreas.data.size(); i++) - { - ParseNextLine(_wayAreas.data.at(i), data); + for(unsigned int i=0; i < _wayAreas.data.size(); i++) + { + ParseNextLine(_wayAreas.data.at(i), data); - m_data_list.push_back(data); - if(data.ID < m_min_id) - m_min_id = data.ID; + m_data_list.push_back(data); + if(data.ID < m_min_id) + m_min_id = data.ID; - if(data.ID > max_id) - max_id = data.ID; - } + if(data.ID > max_id) + max_id = data.ID; + } - m_data_map.resize(max_id-m_min_id+2); - for(unsigned int i=0; i < m_data_list.size(); i++) - { - m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); - } + m_data_map.resize(max_id-m_min_id+2); + for(unsigned int i=0; i < m_data_list.size(); i++) + { + m_data_map.at(m_data_list.at(i).ID-m_min_id) = &m_data_list.at(i); + } } void AisanWayareaFileReader::ParseNextLine(const vector_map_msgs::WayArea& _rec, AisanWayarea& data) { - data.AID = _rec.aid; - data.ID = _rec.waid; - //data.LinkID = _rec.; + data.AID = _rec.aid; + data.ID = _rec.waid; + //data.LinkID = _rec.; } AisanWayareaFileReader::AisanWayarea* AisanWayareaFileReader::GetDataRowById(int _id) { - if(m_data_map.size()==0) return nullptr; + if(m_data_map.size()==0) return nullptr; - int index = _id-m_min_id; - if(index >= 0 && index < m_data_map.size()) - { - return m_data_map.at(index); - } - else - { - for(unsigned int i=0; i < m_data_list.size(); i++) - { - if(m_data_list.at(i).ID == _id) - { - return &m_data_list.at(i); - } - } - } + int index = _id-m_min_id; + if(index >= 0 && index < m_data_map.size()) + { + return m_data_map.at(index); + } + else + { + for(unsigned int i=0; i < m_data_list.size(); i++) + { + if(m_data_list.at(i).ID == _id) + { + return &m_data_list.at(i); + } + } + } - return nullptr; + return nullptr; } bool AisanWayareaFileReader::ReadNextLine(AisanWayarea& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 3) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 3) return false; - data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.ID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.AID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.LinkID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanWayareaFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - AisanWayarea data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + AisanWayarea data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } //Data Conn bool AisanDataConnFileReader::ReadNextLine(DataConn& data) { - vector > lineData; - if(ReadSingleLine(lineData)) - { - if(lineData.size()==0) return false; - if(lineData.at(0).size() < 4) return false; + vector > lineData; + if(ReadSingleLine(lineData)) + { + if(lineData.size()==0) return false; + if(lineData.at(0).size() < 4) return false; - data.LID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); - data.SLID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); - data.SID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); - data.SSID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); + data.LID = strtol(lineData.at(0).at(0).c_str(), NULL, 10); + data.SLID = strtol(lineData.at(0).at(1).c_str(), NULL, 10); + data.SID = strtol(lineData.at(0).at(2).c_str(), NULL, 10); + data.SSID = strtol(lineData.at(0).at(3).c_str(), NULL, 10); - return true; + return true; - } - else - return false; + } + else + return false; } int AisanDataConnFileReader::ReadAllData(vector& data_list) { - data_list.clear(); - DataConn data; - //double logTime = 0; - int count = 0; - while(ReadNextLine(data)) - { - data_list.push_back(data); - count++; - } - return count; + data_list.clear(); + DataConn data; + //double logTime = 0; + int count = 0; + while(ReadNextLine(data)) + { + data_list.push_back(data); + count++; + } + return count; } } /* namespace UtilityHNS */ diff --git a/common/op_utility/src/UtilityH.cpp b/common/op_utility/src/UtilityH.cpp index 18160b2699b..d50f3f96a0f 100755 --- a/common/op_utility/src/UtilityH.cpp +++ b/common/op_utility/src/UtilityH.cpp @@ -29,32 +29,32 @@ UtilityH::UtilityH() std::string UtilityH::GetHomeDirectory() { - struct passwd *pw = getpwuid(getuid()); - const char *homedir = pw->pw_dir; - return string(homedir); + struct passwd *pw = getpwuid(getuid()); + const char *homedir = pw->pw_dir; + return string(homedir); } double UtilityH::GetMomentumScaleFactor(const double& v) { - if(v < 0.3) - return 0.6; - else if(v <6.4) - return 0.3; - else if(v < 20) - { - double m = 0.7/3.6; - return m*(v - 6.4) + 0.3; - } - else - return 0.9; + if(v < 0.3) + return 0.6; + else if(v <6.4) + return 0.3; + else if(v < 20) + { + double m = 0.7/3.6; + return m*(v - 6.4) + 0.3; + } + else + return 0.9; } int UtilityH::GetSign(double x) { - if(x < 0 ) - return -1; - else - return 1; + if(x < 0 ) + return -1; + else + return 1; } double UtilityH::FixNegativeAngle(const double& a) @@ -107,10 +107,10 @@ double UtilityH::AngleBetweenTwoAnglesPositive(const double& a1, const double& a { double diff = a1 - a2; if(diff < 0) - diff = a2 - a1; + diff = a2 - a1; if(diff > M_PI) - diff = 2.0*M_PI - diff; + diff = 2.0*M_PI - diff; return diff; } @@ -118,79 +118,79 @@ double UtilityH::AngleBetweenTwoAnglesPositive(const double& a1, const double& a double UtilityH::GetCircularAngle(const double& prevContAngle, const double& prevAngle, const double& currAngle) { - double diff = currAngle - prevAngle; - if(diff > M_PI) - diff = diff - 2.0*M_PI; - if(diff < -M_PI) - diff = diff + 2.0*M_PI; + double diff = currAngle - prevAngle; + if(diff > M_PI) + diff = diff - 2.0*M_PI; + if(diff < -M_PI) + diff = diff + 2.0*M_PI; - double c_ang = 0; - if(prevContAngle == 0 || fabs(diff) < M_PI_2) - c_ang = prevContAngle + diff; - else - c_ang = prevContAngle; + double c_ang = 0; + if(prevContAngle == 0 || fabs(diff) < M_PI_2) + c_ang = prevContAngle + diff; + else + c_ang = prevContAngle; - return c_ang; + return c_ang; } void UtilityH::GetTickCount(struct timespec& t) { - while(clock_gettime(0, & t) == -1); + while(clock_gettime(0, & t) == -1); } double UtilityH::GetTimeDiff(const struct timespec& old_t,const struct timespec& curr_t) { - return (curr_t.tv_sec - old_t.tv_sec) + ((double)(curr_t.tv_nsec - old_t.tv_nsec)/ 1000000000.0); + return (curr_t.tv_sec - old_t.tv_sec) + ((double)(curr_t.tv_nsec - old_t.tv_nsec)/ 1000000000.0); } double UtilityH::GetTimeDiffNow(const struct timespec& old_t) { - struct timespec curr_t; - GetTickCount(curr_t); - return (curr_t.tv_sec - old_t.tv_sec) + ((double)(curr_t.tv_nsec - old_t.tv_nsec)/ 1000000000.0); + struct timespec curr_t; + GetTickCount(curr_t); + return (curr_t.tv_sec - old_t.tv_sec) + ((double)(curr_t.tv_nsec - old_t.tv_nsec)/ 1000000000.0); } string UtilityH::GetFilePrefixHourMinuteSeconds() { - struct timespec now_time; - UtilityH::GetTickCount(now_time); - tm *gmtm = localtime(&now_time.tv_sec); - ostringstream str; - - str << "Y" << gmtm->tm_year; - str << "-"; - str << "M" << gmtm->tm_mon; - str << "-"; - str << "D" << gmtm->tm_mday; - str << "-"; - str << "H" << gmtm->tm_hour; - str << "-"; - str << "M" << gmtm->tm_min; - str << "-"; - str << "S" << gmtm->tm_sec; - - return str.str(); + struct timespec now_time; + UtilityH::GetTickCount(now_time); + tm *gmtm = localtime(&now_time.tv_sec); + ostringstream str; + + str << "Y" << gmtm->tm_year; + str << "-"; + str << "M" << gmtm->tm_mon; + str << "-"; + str << "D" << gmtm->tm_mday; + str << "-"; + str << "H" << gmtm->tm_hour; + str << "-"; + str << "M" << gmtm->tm_min; + str << "-"; + str << "S" << gmtm->tm_sec; + + return str.str(); } string UtilityH::GetDateTimeStr() { - time_t now = time(0); - char* dateStr = ctime(&now); - string str(dateStr, strlen(dateStr)-1); - int index = str.find(" "); - while(index > 0) - { - str.replace(index,1, "_"); - index = str.find(" "); - } - - index = str.find(":"); - while(index > 0) - { - str.replace(index,1, "-"); - index = str.find(":"); - } - return str; + time_t now = time(0); + char* dateStr = ctime(&now); + string str(dateStr, strlen(dateStr)-1); + int index = str.find(" "); + while(index > 0) + { + str.replace(index,1, "_"); + index = str.find(" "); + } + + index = str.find(":"); + while(index > 0) + { + str.replace(index,1, "-"); + index = str.find(":"); + } + return str; } int UtilityH::tsCompare (struct timespec time1, struct timespec time2, int micro_tolerance) @@ -210,251 +210,251 @@ int UtilityH::tsCompare (struct timespec time1, struct timespec time2, in timespec UtilityH::GetTimeSpec(const time_t& srcT) { - timespec dstT; - dstT.tv_sec = srcT/1000000000; - dstT.tv_nsec = srcT - (dstT.tv_sec*1000000000); - return dstT; + timespec dstT; + dstT.tv_sec = srcT/1000000000; + dstT.tv_nsec = srcT - (dstT.tv_sec*1000000000); + return dstT; } time_t UtilityH::GetLongTime(const struct timespec& srcT) { - time_t dstT; - dstT = srcT.tv_sec * 1000000000 + srcT.tv_nsec; - return dstT; + time_t dstT; + dstT = srcT.tv_sec * 1000000000 + srcT.tv_nsec; + return dstT; } PIDController::PIDController() { - kp = kp_v = 0; - ki = ki_v = 0; - kd = kd_v = 0; - pid_lim = pid_v = 0; - upper_limit = lower_limit = 0; - bEnableLimit= false; - accumErr = 0; - prevErr = 0; - bResetD = false; - bResetI = false; + kp = kp_v = 0; + ki = ki_v = 0; + kd = kd_v = 0; + pid_lim = pid_v = 0; + upper_limit = lower_limit = 0; + bEnableLimit= false; + accumErr = 0; + prevErr = 0; + bResetD = false; + bResetI = false; } PIDController::PIDController(const double& kp, const double& ki, const double& kd) { - Init(kp, ki, kd); - upper_limit = lower_limit = 0; - bEnableLimit= false; - accumErr = 0; - prevErr = 0; - bResetD = false; - bResetI = false; + Init(kp, ki, kd); + upper_limit = lower_limit = 0; + bEnableLimit= false; + accumErr = 0; + prevErr = 0; + bResetD = false; + bResetI = false; } void PIDController::Setlimit(const double& upper,const double& lower) { - upper_limit = upper; - lower_limit = lower; - bEnableLimit = true; + upper_limit = upper; + lower_limit = lower; + bEnableLimit = true; } double PIDController::getPID(const double& currValue, const double& targetValue) { - double e = targetValue - currValue; - return getPID(e); + double e = targetValue - currValue; + return getPID(e); } double PIDController::getPID(const double& e) { - //TODO Remember to add sampling time and multiply the time elapsed by the error - //complex PID error calculation - //TODO //De = ( e(i) + 3*e(i-1) - 3*e(i-2) - e(i-3) ) / 6 - - - if(bResetI) - { - bResetI = false; - accumErr = 0; - } - - if(bResetD) - { - bResetD = false; - prevErr = e; - } - - if(pid_v < upper_limit && pid_v > lower_limit) - accumErr += e; - - double edot= e - prevErr; - - kp_v = kp * e; - ki_v = ki * accumErr; - kd_v = kd * edot; - - pid_v = kp_v + ki_v + kd_v; - pid_lim = pid_v; - if(bEnableLimit) - { - if(pid_v > upper_limit) - { - pid_lim = upper_limit; - } - else if ( pid_v < lower_limit) - { - pid_lim = lower_limit; - } - } - - prevErr = e; - - return pid_lim; + //TODO Remember to add sampling time and multiply the time elapsed by the error + //complex PID error calculation + //TODO //De = ( e(i) + 3*e(i-1) - 3*e(i-2) - e(i-3) ) / 6 + + + if(bResetI) + { + bResetI = false; + accumErr = 0; + } + + if(bResetD) + { + bResetD = false; + prevErr = e; + } + + if(pid_v < upper_limit && pid_v > lower_limit) + accumErr += e; + + double edot= e - prevErr; + + kp_v = kp * e; + ki_v = ki * accumErr; + kd_v = kd * edot; + + pid_v = kp_v + ki_v + kd_v; + pid_lim = pid_v; + if(bEnableLimit) + { + if(pid_v > upper_limit) + { + pid_lim = upper_limit; + } + else if ( pid_v < lower_limit) + { + pid_lim = lower_limit; + } + } + + prevErr = e; + + return pid_lim; } std::string PIDController::ToStringHeader() { - std::ostringstream str_out; - str_out << "Time" << "," <<"KP" << "," << "KI" << "," << "KD" << "," << "KP_v" << "," << "KI_v" << "," << "KD_v" - << "," << "pid_v" << "," << "," << "pid_lim" << "," << "," << "prevErr" << "," << "accumErr" << "," ; - return str_out.str(); + std::ostringstream str_out; + str_out << "Time" << "," <<"KP" << "," << "KI" << "," << "KD" << "," << "KP_v" << "," << "KI_v" << "," << "KD_v" + << "," << "pid_v" << "," << "," << "pid_lim" << "," << "," << "prevErr" << "," << "accumErr" << "," ; + return str_out.str(); } std::string PIDController::ToString() { - std::ostringstream str_out; - timespec t_stamp; - UtilityH::GetTickCount(t_stamp); - str_out << UtilityH::GetLongTime(t_stamp) << "," <kp = kp; - this->ki = ki; - this->kd = kd; + this->kp = kp; + this->ki = ki; + this->kd = kd; } LowpassFilter::LowpassFilter() { - A = 0; - d1 = 0; - d2 = 0; - w0 = 0; - w1 = 0; - w2 = 0; - - m = 0; - sampleF = 0; - cutOffF = 0; + A = 0; + d1 = 0; + d2 = 0; + w0 = 0; + w1 = 0; + w2 = 0; + + m = 0; + sampleF = 0; + cutOffF = 0; } LowpassFilter::~LowpassFilter() { -// if(A) -// delete A; -// if(d1) -// delete d1; -// if(d2) -// delete d2; -// if(w0) -// delete w0; -// if(w1) -// delete w1; -// if(w2) -// delete w2; +// if(A) +// delete A; +// if(d1) +// delete d1; +// if(d2) +// delete d2; +// if(w0) +// delete w0; +// if(w1) +// delete w1; +// if(w2) +// delete w2; } LowpassFilter::LowpassFilter(const int& filterOrder, const double& sampleFreq, const double& cutOffFreq) { - Init(filterOrder, sampleFreq, cutOffFreq); + Init(filterOrder, sampleFreq, cutOffFreq); } void LowpassFilter::Init(const int& n, const double& sampleFreq, const double& cutOffFreq) { - if(!(n == 2 || n == 4 || n == 6 || n == 8)) - { - cout << "Undefined LowpassFilter order ! " << endl; - - A = 0; - d1 = 0; - d2 = 0; - w0 = 0; - w1 = 0; - w2 = 0; - - m = 0; - sampleF = 0; - cutOffF = 0; - } - else - { - m = n/2; - sampleF = sampleFreq; - cutOffF = cutOffFreq; - double ep = 1; - double s = sampleFreq; - double f = cutOffFreq; - double a = tan(M_PI*f/s); - double a2 = a*a; - double u = log((1.0+sqrt(1.0+ep*ep))/ep); - double su = sinh(u/(double)n); - double cu = cosh(u/(double)n); - double b, c; - -// A = new double[m]; -// d1 = new double[m]; -// d2 = new double[m]; -// w0 = new double[m]; -// w1 = new double[m]; -// w2 = new double[m]; + if(!(n == 2 || n == 4 || n == 6 || n == 8)) + { + cout << "Undefined LowpassFilter order ! " << endl; + + A = 0; + d1 = 0; + d2 = 0; + w0 = 0; + w1 = 0; + w2 = 0; + + m = 0; + sampleF = 0; + cutOffF = 0; + } + else + { + m = n/2; + sampleF = sampleFreq; + cutOffF = cutOffFreq; + double ep = 1; + double s = sampleFreq; + double f = cutOffFreq; + double a = tan(M_PI*f/s); + double a2 = a*a; + double u = log((1.0+sqrt(1.0+ep*ep))/ep); + double su = sinh(u/(double)n); + double cu = cosh(u/(double)n); + double b, c; + +// A = new double[m]; +// d1 = new double[m]; +// d2 = new double[m]; +// w0 = new double[m]; +// w1 = new double[m]; +// w2 = new double[m]; // -// for(int i=0; i < m ; i++) -// { -// A[i] = 0; -// d1[i] = 0; -// d2[i] = 0; -// w0[i] = 0; -// w1[i] = 0; -// w2[i] = 0; -// } - - for(int i=0; i< m; ++i) - { - b = sin(M_PI*(2.0*i+1.0)/(2.0*n))*su; - c = cos(M_PI*(2.0*i+1.0)/(2.0*n))*cu; - c = b*b + c*c; - s = a2*c + 2.0*a*b + 1.0; - A = a2/(4.0*s); // 4.0 - d1 = 2.0*(1-a2*c)/s; - d2 = -(a2*c - 2.0*a*b + 1.0)/s; - } - } +// for(int i=0; i < m ; i++) +// { +// A[i] = 0; +// d1[i] = 0; +// d2[i] = 0; +// w0[i] = 0; +// w1[i] = 0; +// w2[i] = 0; +// } + + for(int i=0; i< m; ++i) + { + b = sin(M_PI*(2.0*i+1.0)/(2.0*n))*su; + c = cos(M_PI*(2.0*i+1.0)/(2.0*n))*cu; + c = b*b + c*c; + s = a2*c + 2.0*a*b + 1.0; + A = a2/(4.0*s); // 4.0 + d1 = 2.0*(1-a2*c)/s; + d2 = -(a2*c - 2.0*a*b + 1.0)/s; + } + } } double LowpassFilter::getFilter(const double& value) { - double ep = 2.3/1.0; // used to normalize - double x = value; - for(int i=0; i("/points_raw", 1, [pipeline, pub]() { + pub.publish(pipeline.schedule(msg)); + }); +} +``` + +## The Utility Functions + +A set of utility functions common in machine learning that can be used in +building the pipeline. + +## Error + +`std::runtime_error` should be thrown whenever error is encountered. It should +be populated with an appropriate text error description. diff --git a/common/tvm_utility/include/tvm_utility/pipeline.h b/common/tvm_utility/include/tvm_utility/pipeline.h new file mode 100644 index 00000000000..0c199bab09e --- /dev/null +++ b/common/tvm_utility/include/tvm_utility/pipeline.h @@ -0,0 +1,310 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifndef TVM_UTILITY_PIPELINE_H +#define TVM_UTILITY_PIPELINE_H + +namespace tvm_utility +{ +namespace pipeline +{ + +class TVMArrayContainer +{ +public: + TVMArrayContainer() = default; + + TVMArrayContainer(std::vector shape, DLDataTypeCode dtype_code, + uint32_t dtype_bits, uint32_t dtype_lanes, + DLDeviceType device_type, uint32_t device_id) + { + TVMArrayHandle x{}; + TVMArrayAlloc(&shape[0], shape.size(), dtype_code, dtype_bits, dtype_lanes, + device_type, device_id, &x); + handle_ = std::make_shared(x); + } + + TVMArrayHandle getArray() const { return *handle_.get(); } + +private: + std::shared_ptr handle_ + { + nullptr, + [](TVMArrayHandle ptr) + { + if (ptr) + TVMArrayFree(ptr); + } + }; +}; + +using TVMArrayContainerVector = std::vector; + +/** + * @class PipelineStage + * @brief Base class for all types of pipeline stages. + * + * @tparam InputType The datatype of the input of the pipeline stage. + * @tparam OutputType The datatype of the output from the pipeline stage. + */ +template class PipelineStage +{ +public: + /** + * @brief Execute the pipeline stage + * + * @param input The data to push into the pipeline stage. The pipeline stage + * should not modify the input data. + * @return The output of the pipeline + */ + virtual OutputType schedule(const InputType &input) = 0; + InputType input_type_indicator_; + OutputType output_type_indicator_; +}; + +/** + * @class PreProcessor + * @brief Pre processor of the inference pipeline. In charge of converting data + * from InputType into TVMArrayContainer format. Any necessary pre processing + * of the data, such as image resizing or padding, should also be done in this + * stage . + * + * @tparam InputType The data type of the input to the pre-processing pipeline + * stage. Usually a ROS message type. + */ +template +class PreProcessor : public PipelineStage {}; + +/** + * @class InferenceEngine + * @brief Pipeline stage in charge of machine learning inference. + */ +class InferenceEngine + : public PipelineStage {}; + +/** + * @class PostProcessor + * @brief The post processing stage of the inference pipeline. In charge of + * converting the tensor data from the inference stage into detections in + * OutputType, usually a ROS message format. Thing such as decoding bounding + * boxes, non-maximum-supperssion and minimum score filtering should be done in + * this stage. + * + * @tparam OutputType The data type of the output of the inference pipeline. + * Usually a ROS message type. + */ +template +class PostProcessor + : public PipelineStage {}; + +/** + * @class Pipeline + * @brief Inference Pipeline. Consists of 3 stages: preprocessor, inference + * stage and postprocessor. + */ +template +class Pipeline +{ + using InputType = + decltype(std::declval().input_type_indicator_); + using OutputType = + decltype(std::declval().output_type_indicator_); + +public: + /** + * @brief Construct a new Pipeline object + * + * @param pre_processor a PreProcessor object + * @param post_processor a PostProcessor object + * @param inference_engine a InferenceEngine object + */ + Pipeline(PreProcessorType pre_processor, InferenceEngineType inference_engine, + PostProcessorType post_processor) + : pre_processor_(pre_processor), post_processor_(post_processor), + inference_engine_(inference_engine) {} + + /** + * @brief run the pipeline. Return asynchronously in a callback. + * + * @param input The data to push into the pipeline + * @return The pipeline output + */ + OutputType schedule(const InputType &input) + { + auto input_tensor = pre_processor_.schedule(input); + auto output_tensor = inference_engine_.schedule(input_tensor); + return post_processor_.schedule(output_tensor); + }; + +private: + PreProcessorType pre_processor_{}; + InferenceEngineType inference_engine_{}; + PostProcessorType post_processor_{}; +}; + +// each node should be specificed with a string name and a shape +using NetworkNode = std::pair>; +typedef struct +{ + // network files + std::string network_module_path; + std::string network_graph_path; + std::string network_params_path; + + // network data type configurations + DLDataTypeCode tvm_dtype_code; + uint32_t tvm_dtype_bits; + uint32_t tvm_dtype_lanes; + + // inference hardware configuration + DLDeviceType tvm_device_type; + uint32_t tvm_device_id; + + // network inputs + std::vector network_inputs; + + // network outputs + std::vector network_outputs; +} +InferenceEngineTVMConfig; + +class InferenceEngineTVM : public InferenceEngine +{ +public: + explicit InferenceEngineTVM(InferenceEngineTVMConfig config) : config_(config) + { + // load compiled functions + std::ifstream module(config.network_module_path); + if (!module.good()) + { + throw std::runtime_error( + "File " + config.network_module_path + + " specified in inference_engine_tvm_config.h not " + "found"); + } + module.close(); + tvm::runtime::Module mod = + tvm::runtime::Module::LoadFromFile(config.network_module_path); + + // load json graph + std::ifstream json_in(config.network_graph_path, std::ios::in); + if (!json_in.good()) + { + throw std::runtime_error( + "File " + config.network_graph_path + + " specified in inference_engine_tvm_config.h not " + "found"); + } + std::string json_data((std::istreambuf_iterator(json_in)), + std::istreambuf_iterator()); + json_in.close(); + + // load parameters from binary file + std::ifstream params_in(config.network_params_path, std::ios::binary); + if (!params_in.good()) + { + throw std::runtime_error( + "File " + config.network_params_path + + " specified in inference_engine_tvm_config.h not " + "found"); + } + std::string params_data((std::istreambuf_iterator(params_in)), + std::istreambuf_iterator()); + params_in.close(); + + // parameters need to be in TVMByteArray format + TVMByteArray params_arr; + params_arr.data = params_data.c_str(); + params_arr.size = params_data.length(); + + // create tvm runtime module + tvm::runtime::Module runtime_mod = + (*tvm::runtime::Registry::Get("tvm.graph_runtime.create"))( + json_data, mod, static_cast(config.tvm_device_type), config.tvm_device_id); + + // load parameters + auto load_params = runtime_mod.GetFunction("load_params"); + load_params(params_arr); + + // get set_input function + set_input = runtime_mod.GetFunction("set_input"); + + // get the function which executes the network + execute = runtime_mod.GetFunction("run"); + + // get the function to get output data + get_output = runtime_mod.GetFunction("get_output"); + + for (auto &output_config : config.network_outputs) + { + output_.push_back( + TVMArrayContainer(output_config.second, config.tvm_dtype_code, + config.tvm_dtype_bits, config.tvm_dtype_lanes, + config.tvm_device_type, config.tvm_device_id)); + } + } + + TVMArrayContainerVector schedule(const TVMArrayContainerVector &input) + { + // set input(s) + for (int index = 0; index < input.size(); ++index) + { + if (input[index].getArray() == nullptr) + { + throw std::runtime_error("input variable is null"); + } + set_input(config_.network_inputs[index].first.c_str(), + input[index].getArray()); + } + + // execute the inference + execute(); + + // get output(s) + for (int index = 0; index < output_.size(); ++index) + { + if (output_[index].getArray() == nullptr) + { + throw std::runtime_error("output variable is null"); + } + get_output(index, output_[index].getArray()); + } + return output_; + } + +private: + InferenceEngineTVMConfig config_; + TVMArrayContainerVector output_; + tvm::runtime::PackedFunc set_input; + tvm::runtime::PackedFunc execute; + tvm::runtime::PackedFunc get_output; +}; + +} // namespace pipeline +} // namespace tvm_utility + +#endif // TVM_UTILITY_PIPELINE_H diff --git a/common/tvm_utility/package.xml b/common/tvm_utility/package.xml new file mode 100644 index 00000000000..0fa05a106ac --- /dev/null +++ b/common/tvm_utility/package.xml @@ -0,0 +1,23 @@ + + + + tvm_utility + 0.1.0 + + A set of utility functions to help build an machine learning pipeline using + TVM as the inference engine. + + Liyou Zhou + Luca Foschiani + Apache 2 + + autoware_build_flags + catkin + cmake_modules + pcl_ros + tvm_vendor + autoware_msgs + rostest + libboost-system-dev + libopencv-dev + diff --git a/common/tvm_utility/test/yolo_v2_tiny/README.md b/common/tvm_utility/test/yolo_v2_tiny/README.md new file mode 100644 index 00000000000..3a2cdcf79bb --- /dev/null +++ b/common/tvm_utility/test/yolo_v2_tiny/README.md @@ -0,0 +1,35 @@ +# Example Pipeline + +This is an example implementation of an inference pipeline using the pipeline +framework. This example pipeline executes the +[YOLO V2 Tiny](https://pjreddie.com/darknet/yolov2/) model and decodes its +output. + +## Compiling the Example + +1. Download an example image to be used as test input. this image needs to be + saved in the `test/yolo_v2_tiny/` folder + + ```sh + $ curl https://raw.githubusercontent.com/pjreddie/darknet/master/data/dog.jpg \ + > test/yolo_v2_tiny/test_image_0.jpg + ``` + +2. Compile the neural network model using TVM. A CLI utility program and + instructions on how to compile can be found in `/modelzoo/scripts/tvm_cli/` + The files produced by the tvm_cli must then be placed in + `test/yolo_v2_tiny/`. These files are: + + - inference_engine_tvm_config.hpp + - deploy_lib.so + - deploy_graph.json + - deploy_param.params + +3. Start autoware docker environment. + +4. Build and test inside the container. + + ```sh + $ colcon build --packages-up-to tvm_utility + $ colcon test --packages-select tvm_utility + ``` diff --git a/common/tvm_utility/test/yolo_v2_tiny/labels.txt b/common/tvm_utility/test/yolo_v2_tiny/labels.txt new file mode 100644 index 00000000000..941cb4e1392 --- /dev/null +++ b/common/tvm_utility/test/yolo_v2_tiny/labels.txt @@ -0,0 +1,80 @@ +person +bicycle +car +motorcycle +airplane +bus +train +truck +boat +traffic light +fire hydrant +stop sign +parking meter +bench +bird +cat +dog +horse +sheep +cow +elephant +bear +zebra +giraffe +backpack +umbrella +handbag +tie +suitcase +frisbee +skis +snowboard +sports ball +kite +baseball bat +baseball glove +skateboard +surfboard +tennis racket +bottle +wine glass +cup +fork +knife +spoon +bowl +banana +apple +sandwich +orange +broccoli +carrot +hot dog +pizza +donut +cake +chair +couch +potted plant +bed +dining table +toilet +tv +laptop +mouse +remote +keyboard +cell phone +microwave +oven +toaster +sink +refrigerator +book +clock +vase +scissors +teddy bear +hair drier +toothbrush diff --git a/common/tvm_utility/test/yolo_v2_tiny/main.cpp b/common/tvm_utility/test/yolo_v2_tiny/main.cpp new file mode 100644 index 00000000000..87a384d19c5 --- /dev/null +++ b/common/tvm_utility/test/yolo_v2_tiny/main.cpp @@ -0,0 +1,331 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "gtest/gtest.h" + +#include "autoware_msgs/DetectedObjectArray.h" +#include "pcl_ros/point_cloud.h" +#include +#include +#include +#include +#include +#include + +#include "inference_engine_tvm_config.hpp" + +#include +#include +#include +#include + +// Name of file containing the human readable names of the classes. One class +// on each line. +#define LABEL_FILENAME "labels.txt" +// Name of file containing the anchor values for the network. Each line is one +// anchor. each anchor has 2 comma separated floating point values. +#define ANCHOR_FILENAME "anchors.csv" +// filename of the image on which to run the inference +#define IMAGE_FILENAME "test_image_0.jpg" + +class PreProcessorYoloV2Tiny + : public tvm_utility::pipeline::PreProcessor +{ +public: + explicit PreProcessorYoloV2Tiny(tvm_utility::pipeline::InferenceEngineTVMConfig config) + : network_input_width(config.network_inputs[0].second[1]), + network_input_height(config.network_inputs[0].second[2]), + network_input_depth(config.network_inputs[0].second[3]), + network_datatype_bytes(config.tvm_dtype_bits / 8) + { + // allocate input variable + std::vector shape_x + { + 1, + network_input_width, + network_input_height, + network_input_depth + }; + tvm_utility::pipeline::TVMArrayContainer x + { + shape_x, + config.tvm_dtype_code, + config.tvm_dtype_bits, + config.tvm_dtype_lanes, + config.tvm_device_type, + config.tvm_device_id + }; + + output = x; + } + + tvm_utility::pipeline::TVMArrayContainerVector + schedule(const sensor_msgs::PointCloud2 &input) + { + // read input image + auto image = cv::imread(IMAGE_FILENAME, CV_LOAD_IMAGE_COLOR); + if (!image.data) + { + throw std::runtime_error("File " IMAGE_FILENAME " not found"); + } + + // Compute the ratio for resizing and size for padding + double scale_x = + static_cast(image.size().width) / network_input_width; + double scale_y = + static_cast(image.size().height) / network_input_height; + double scale = std::max(scale_x, scale_y); + + // perform padding + if (scale != 1) + { + cv::resize(image, image, cv::Size(), 1.0f / scale, 1.0f / scale); + } + + size_t w_pad = network_input_width - image.size().width; + size_t h_pad = network_input_height - image.size().height; + + if (w_pad || h_pad) + { + cv::copyMakeBorder(image, image, h_pad / 2, (h_pad - h_pad / 2), + w_pad / 2, (w_pad - w_pad / 2), cv::BORDER_CONSTANT, + cv::Scalar(0, 0, 0)); + } + + // convert pixel values from int8 to float32. convert pixel value range from + // 0 - 255 to 0 - 1. + cv::Mat3f image_3f{}; + image.convertTo(image_3f, CV_32FC3, 1 / 255.0f); + + // cv library use BGR as a default color format, the network expects the + // data in RGB format + cv::cvtColor(image_3f, image_3f, CV_BGR2RGB); + + TVMArrayCopyFromBytes(output.getArray(), image_3f.data, + network_input_width * network_input_height * + network_input_depth * network_datatype_bytes); + + return {output}; + } + +private: + int64_t network_input_width; + int64_t network_input_height; + int64_t network_input_depth; + int64_t network_datatype_bytes; + tvm_utility::pipeline::TVMArrayContainer output; +}; + +class PostProcessorYoloV2Tiny + : public tvm_utility::pipeline::PostProcessor> +{ +public: + PostProcessorYoloV2Tiny( + tvm_utility::pipeline::InferenceEngineTVMConfig config) + : network_output_width(config.network_outputs[0].second[1]), + network_output_height(config.network_outputs[0].second[2]), + network_output_depth(config.network_outputs[0].second[3]) + { + // parse human readable names for the classes + std::ifstream label_file{LABEL_FILENAME}; + if (!label_file.good()) + { + throw std::runtime_error("unable to open label file:" LABEL_FILENAME); + } + std::string line{}; + while (std::getline(label_file, line)) + { + labels.push_back(line); + } + + // Get anchor values for this network from the anchor file + std::ifstream anchor_file{ANCHOR_FILENAME}; + if (!anchor_file.good()) + { + throw std::runtime_error("unable to open anchor file:" ANCHOR_FILENAME); + } + std::string first{}; + std::string second{}; + while (std::getline(anchor_file, line)) + { + std::stringstream line_stream(line); + std::getline(line_stream, first, ','); + std::getline(line_stream, second, ','); + anchors.push_back( + std::make_pair(std::atof(first.c_str()), std::atof(second.c_str()))); + } + } + + // sigmoid function + float sigmoid(float x) { return static_cast(1.0 / (1.0 + std::exp(-x))); } + + std::vector + schedule(const tvm_utility::pipeline::TVMArrayContainerVector &input) + { + auto l_h = network_output_width; // layer height + auto l_w = network_output_height; // layer width + auto n_classes = labels.size(); // total number of classes + auto n_anchors = anchors.size(); // total number of anchors + const uint32_t n_coords = 4; // number of coordinates in a single anchor box + + // assert data is stored row-majored in input and the dtype is float + assert(input[0].getArray()->strides == nullptr); + assert(input[0].getArray()->dtype.bits == sizeof(float) * 8); + + // get a pointer to the output data + float *data_ptr = + reinterpret_cast(reinterpret_cast(input[0].getArray()->data) + + input[0].getArray()->byte_offset); + + // utility function to return data from y given index + auto get_output_data = [this, data_ptr, n_classes, n_anchors, + n_coords](size_t row_i, size_t col_j, + size_t anchor_k, size_t offset) + { + auto box_index = + (row_i * network_output_height + col_j) * network_output_depth; + auto index = box_index + anchor_k * (n_classes + n_coords + 1); + return data_ptr[index + offset]; + }; + + // vector used to check if the result is accurate, + // this is also the output of this (schedule) function + std::vector scores_above_threshold{}; + + // Parse results into detections. Loop over each detection cell in the model + // output + for (size_t i = 0; i < l_w; i++) + { + for (size_t j = 0; j < l_h; j++) + { + for (size_t anchor_k = 0; anchor_k < n_anchors; anchor_k++) + { + float anchor_w = anchors[anchor_k].first; + float anchor_h = anchors[anchor_k].second; + + // Compute property indices + auto box_x = get_output_data(i, j, anchor_k, 0); + auto box_y = get_output_data(i, j, anchor_k, 1); + auto box_w = get_output_data(i, j, anchor_k, 2); + auto box_h = get_output_data(i, j, anchor_k, 3); + auto box_p = get_output_data(i, j, anchor_k, 4); + + // Transform log-space predicted coordinates to absolute space + + // offset Transform bounding box position from offset to absolute + // (ratio) + auto x = (sigmoid(box_x) + j) / l_w; + auto y = (sigmoid(box_y) + i) / l_h; + + // Transform bounding box height and width from log to absolute space + auto w = anchor_w * exp(box_w) / l_w; + auto h = anchor_h * exp(box_h) / l_h; + + // Decode the confidence of detection in this anchor box + auto p_0 = sigmoid(box_p); + + // find maximum probability of all classes + float max_p = 0.0f; + int max_ind = -1; + for (int i_class = 0; i_class < n_classes; i_class++) + { + auto class_p = get_output_data(i, j, anchor_k, 5 + i_class); + if (max_p < class_p) + { + max_p = class_p; + max_ind = i_class; + } + } + + // decode and copy class probabilities + std::vector class_probabilities{}; + float p_total = 0; + for (size_t i_class = 0; i_class < n_classes; i_class++) + { + auto class_p = get_output_data(i, j, anchor_k, 5 + i_class); + class_probabilities.push_back(std::exp(class_p - max_p)); + p_total += class_probabilities[i_class]; + } + + // Find the most likely score + auto max_score = class_probabilities[max_ind] * p_0 / p_total; + + // draw all detections with high scores + if (max_score > 0.3) + { + scores_above_threshold.push_back(max_score); + } + } + } + } + + return scores_above_threshold; + } + +private: + int64_t network_output_width; + int64_t network_output_height; + int64_t network_output_depth; + std::vector labels{}; + std::vector> anchors{}; +}; + +// bring config into scope +namespace model_config = model_zoo::perception::camera_obstacle_detection:: + yolo_v2_tiny::tensorflow_fp32_coco; +using tvm_utility::pipeline::InferenceEngineTVM; +using tvm_utility::pipeline::Pipeline; + +TEST(PipelineExamples, SimplePipeline) +{ + // instantiate the pipeline + Pipeline + pipeline(PreProcessorYoloV2Tiny{model_config::config}, + InferenceEngineTVM{model_config::config}, + PostProcessorYoloV2Tiny{model_config::config}); // NOLINT + + // push data input the pipeline and get the output + sensor_msgs::PointCloud2 msg{}; + auto output = pipeline.schedule(msg); + + // define reference vector containing expected values + std::vector expected_output + { + 0.360896, + 0.763201, + 0.402838, + 0.302775, + 0.612508, + 0.583656, + 0.422576, + 0.452684, + 0.372608, + 0.806072, + 0.572778 + }; + + // test: check if the generated output is equal to the reference + EXPECT_EQ(expected_output.size(), output.size()) << "Unexpected output size"; + for (auto i = 0; i < output.size(); ++i) + { + EXPECT_NEAR(expected_output[i], output[i], 0.0001) << "at index: " << i; + } +} + +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/common/vector_map/CMakeLists.txt b/common/vector_map/CMakeLists.txt index 034aee22be8..2b87e783996 100644 --- a/common/vector_map/CMakeLists.txt +++ b/common/vector_map/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS tf geometry_msgs + roslint vector_map_msgs visualization_msgs ) @@ -34,6 +35,9 @@ target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ) +set(ROSLINT_CPP_OPTS "--filter=-build/c++14,-runtime/references") +roslint_cpp() + ## Install project namespaced headers install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} @@ -44,4 +48,8 @@ install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) \ No newline at end of file +) + +if(CATKIN_ENABLE_TESTING) + roslint_add_test() +endif() diff --git a/common/vector_map/include/vector_map/vector_map.h b/common/vector_map/include/vector_map/vector_map.h index cea878b1ec0..8e7c512343b 100644 --- a/common/vector_map/include/vector_map/vector_map.h +++ b/common/vector_map/include/vector_map/vector_map.h @@ -17,7 +17,6 @@ #ifndef VECTOR_MAP_VECTOR_MAP_H #define VECTOR_MAP_VECTOR_MAP_H -#include #include #include #include @@ -56,6 +55,11 @@ #include #include +#include +#include +#include +#include + namespace vector_map { using vector_map_msgs::Point; @@ -124,7 +128,7 @@ using vector_map_msgs::WallArray; using vector_map_msgs::FenceArray; using vector_map_msgs::RailCrossingArray; -using category_t = unsigned long long; +using category_t = uint32_t; enum Category : category_t { @@ -297,7 +301,7 @@ std::vector parse(const std::string& csv_file) { std::ifstream ifs(csv_file.c_str()); std::string line; - std::getline(ifs, line); // remove first line + std::getline(ifs, line); // remove first line std::vector objs; while (std::getline(ifs, line)) { @@ -309,42 +313,6 @@ std::vector parse(const std::string& csv_file) return objs; } -/* namespace */ -/* { */ -/* void updatePoint(std::map, Point>& map, const PointArray& msg); */ -/* void updateVector(std::map, Vector>& map, const VectorArray& msg); */ -/* void updateLine(std::map, Line>& map, const LineArray& msg); */ -/* void updateArea(std::map, Area>& map, const AreaArray& msg); */ -/* void updatePole(std::map, Pole>& map, const PoleArray& msg); */ -/* void updateBox(std::map, Box>& map, const BoxArray& msg); */ -/* void updateDTLane(std::map, DTLane>& map, const DTLaneArray& msg); */ -/* void updateNode(std::map, Node>& map, const NodeArray& msg); */ -/* void updateLane(std::map, Lane>& map, const LaneArray& msg); */ -/* void updateWayArea(std::map, WayArea>& map, const WayAreaArray& msg); */ -/* void updateRoadEdge(std::map, RoadEdge>& map, const RoadEdgeArray& msg); */ -/* void updateGutter(std::map, Gutter>& map, const GutterArray& msg); */ -/* void updateCurb(std::map, Curb>& map, const CurbArray& msg); */ -/* void updateWhiteLine(std::map, WhiteLine>& map, const WhiteLineArray& msg); */ -/* void updateStopLine(std::map, StopLine>& map, const StopLineArray& msg); */ -/* void updateZebraZone(std::map, ZebraZone>& map, const ZebraZoneArray& msg); */ -/* void updateCrossWalk(std::map, CrossWalk>& map, const CrossWalkArray& msg); */ -/* void updateRoadMark(std::map, RoadMark>& map, const RoadMarkArray& msg); */ -/* void updateRoadPole(std::map, RoadPole>& map, const RoadPoleArray& msg); */ -/* void updateRoadSign(std::map, RoadSign>& map, const RoadSignArray& msg); */ -/* void updateSignal(std::map, Signal>& map, const SignalArray& msg); */ -/* void updateStreetLight(std::map, StreetLight>& map, const StreetLightArray& msg); */ -/* void updateUtilityPole(std::map, UtilityPole>& map, const UtilityPoleArray& msg); */ -/* void updateGuardRail(std::map, GuardRail>& map, const GuardRailArray& msg); */ -/* void updateSideWalk(std::map, SideWalk>& map, const SideWalkArray& msg); */ -/* void updateDriveOnPortion(std::map, DriveOnPortion>& map, const DriveOnPortionArray& msg); */ -/* void updateCrossRoad(std::map, CrossRoad>& map, const CrossRoadArray& msg); */ -/* void updateSideStrip(std::map, SideStrip>& map, const SideStripArray& msg); */ -/* void updateCurveMirror(std::map, CurveMirror>& map, const CurveMirrorArray& msg); */ -/* void updateWall(std::map, Wall>& map, const WallArray& msg); */ -/* void updateFence(std::map, Fence>& map, const FenceArray& msg); */ -/* void updateRailCrossing(std::map, RailCrossing>& map, const RailCrossingArray& msg); */ -/* } // namespace */ - class VectorMap { private: @@ -530,7 +498,7 @@ geometry_msgs::Point convertPointToGeomPoint(const Point& point); Point convertGeomPointToPoint(const geometry_msgs::Point& geom_point); geometry_msgs::Quaternion convertVectorToGeomQuaternion(const Vector& vector); Vector convertGeomQuaternionToVector(const geometry_msgs::Quaternion& geom_quaternion); -} // namespace vector_map +} // namespace vector_map std::ostream& operator<<(std::ostream& os, const vector_map::Point& obj); std::ostream& operator<<(std::ostream& os, const vector_map::Vector& obj); @@ -598,4 +566,4 @@ std::istream& operator>>(std::istream& is, vector_map::Wall& obj); std::istream& operator>>(std::istream& is, vector_map::Fence& obj); std::istream& operator>>(std::istream& is, vector_map::RailCrossing& obj); -#endif // VECTOR_MAP_VECTOR_MAP_H +#endif // VECTOR_MAP_VECTOR_MAP_H diff --git a/common/vector_map/lib/vector_map/vector_map.cpp b/common/vector_map/lib/vector_map/vector_map.cpp index a2c34a5c7e9..6602cbdde20 100644 --- a/common/vector_map/lib/vector_map/vector_map.cpp +++ b/common/vector_map/lib/vector_map/vector_map.cpp @@ -17,6 +17,10 @@ #include #include +#include +#include +#include + namespace vector_map { namespace @@ -372,7 +376,7 @@ void updateRailCrossing(std::map, RailCrossing>& map, const Ra map.insert(std::make_pair(Key(item.id), item)); } } -} // namespace +} // namespace bool VectorMap::hasSubscribed(category_t category) const { @@ -1302,7 +1306,7 @@ std_msgs::ColorRGBA createColorRGBA(Color color) color_rgba.b = COLOR_VALUE_MAX; break; default: - color_rgba.a = COLOR_VALUE_MIN; // hide color from view + color_rgba.a = COLOR_VALUE_MIN; // hide color from view break; } @@ -1427,7 +1431,7 @@ visualization_msgs::Marker createAreaMarker(const std::string& ns, int id, Color Line line = vmap.findByKey(Key(area.slid)); if (line.lid == 0) return marker; - if (line.blid != 0) // must set beginning line + if (line.blid != 0) // must set beginning line return marker; while (line.flid != 0) @@ -1611,8 +1615,8 @@ Point convertGeomPointToPoint(const geometry_msgs::Point& geom_point) geometry_msgs::Quaternion convertVectorToGeomQuaternion(const Vector& vector) { - double pitch = convertDegreeToRadian(vector.vang - 90); // convert vertical angle to pitch - double yaw = convertDegreeToRadian(-vector.hang + 90); // convert horizontal angle to yaw + double pitch = convertDegreeToRadian(vector.vang - 90); // convert vertical angle to pitch + double yaw = convertDegreeToRadian(-vector.hang + 90); // convert horizontal angle to yaw return tf::createQuaternionMsgFromRollPitchYaw(0, pitch, yaw); } @@ -1626,7 +1630,7 @@ Vector convertGeomQuaternionToVector(const geometry_msgs::Quaternion& geom_quate vector.hang = -convertRadianToDegree(yaw) + 90; return vector; } -} // namespace vector_map +} // namespace vector_map std::ostream& operator<<(std::ostream& os, const vector_map::Point& obj) { diff --git a/common/vector_map/package.xml b/common/vector_map/package.xml index c6f79bd7254..2a137505f69 100644 --- a/common/vector_map/package.xml +++ b/common/vector_map/package.xml @@ -11,6 +11,7 @@ geometry_msgs tf + roslint vector_map_msgs visualization_msgs diff --git a/common/vector_map_server/CMakeLists.txt b/common/vector_map_server/CMakeLists.txt index d065b3a7840..1bfdbe95b96 100644 --- a/common/vector_map_server/CMakeLists.txt +++ b/common/vector_map_server/CMakeLists.txt @@ -4,63 +4,64 @@ project(vector_map_server) find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS - roscpp + autoware_msgs geometry_msgs - visualization_msgs message_generation + roscpp + roslint vector_map - autoware_msgs vector_map_msgs + visualization_msgs ) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") add_service_files( FILES + GetCrossRoad.srv + GetCrossWalk.srv + GetCurb.srv + GetCurveMirror.srv GetDTLane.srv - GetNode.srv + GetDriveOnPortion.srv + GetFence.srv + GetGuardRail.srv + GetGutter.srv GetLane.srv - GetWayArea.srv + GetNode.srv + GetRailCrossing.srv GetRoadEdge.srv - GetGutter.srv - GetCurb.srv - GetWhiteLine.srv - GetStopLine.srv - GetZebraZone.srv - GetCrossWalk.srv GetRoadMark.srv GetRoadPole.srv GetRoadSign.srv + GetSideStrip.srv + GetSideWalk.srv GetSignal.srv + GetStopLine.srv GetStreetLight.srv GetUtilityPole.srv - GetGuardRail.srv - GetSideWalk.srv - GetDriveOnPortion.srv - GetCrossRoad.srv - GetSideStrip.srv - GetCurveMirror.srv GetWall.srv - GetFence.srv - GetRailCrossing.srv + GetWayArea.srv + GetWhiteLine.srv + GetZebraZone.srv PositionState.srv ) generate_messages( DEPENDENCIES - geometry_msgs - autoware_msgs - vector_map_msgs + autoware_msgs + geometry_msgs + vector_map_msgs ) catkin_package( CATKIN_DEPENDS - message_runtime - geometry_msgs - autoware_msgs - vector_map_msgs - vector_map - visualization_msgs + message_runtime + geometry_msgs + autoware_msgs + vector_map_msgs + vector_map + visualization_msgs ) include_directories( @@ -93,8 +94,15 @@ add_dependencies(vector_map_client ${catkin_EXPORTED_TARGETS} ) +set(ROSLINT_CPP_OPTS "--filter=-build/c++14,-runtime/references,-whitespace/braces") +roslint_cpp() + install(TARGETS ${PROJECT_NAME} vector_map_client ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) + +if(CATKIN_ENABLE_TESTING) + roslint_add_test() +endif() diff --git a/common/vector_map_server/nodes/vector_map_client/vector_map_client.cpp b/common/vector_map_server/nodes/vector_map_client/vector_map_client.cpp index 6aebaaa41f9..42d3283c7d9 100644 --- a/common/vector_map_server/nodes/vector_map_client/vector_map_client.cpp +++ b/common/vector_map_server/nodes/vector_map_client/vector_map_client.cpp @@ -15,9 +15,9 @@ */ #include -#include "autoware_msgs/Lane.h" +#include #include -#include "vector_map/vector_map.h" +#include #include "vector_map_server/GetWhiteLine.h" #include "vector_map_server/GetStopLine.h" @@ -74,7 +74,7 @@ class VectorMapClient waypoints_ = waypoints; } }; -} // namespace +} // namespace int main(int argc, char **argv) { @@ -89,7 +89,7 @@ int main(int argc, char **argv) vmap.subscribe(nh, Category::POINT | Category::VECTOR | Category::LINE | Category::AREA | Category::POLE | Category::WHITE_LINE | Category::STOP_LINE | Category::CROSS_WALK | Category::SIGNAL, - ros::Duration(0)); // non-blocking + ros::Duration(0)); // non-blocking ros::Subscriber pose_sub = nh.subscribe("current_pose", 1, &VectorMapClient::setPose, &vmc); ros::Subscriber waypoints_sub = nh.subscribe("final_waypoints", 1, &VectorMapClient::setWaypoints, &vmc); @@ -264,7 +264,7 @@ int main(int argc, char **argv) { for (auto& marker : marker_array.markers) marker.action = visualization_msgs::Marker::DELETE; - marker_array_pub.publish(marker_array); // clear previous marker + marker_array_pub.publish(marker_array); // clear previous marker } marker_array = marker_array_buffer; marker_array_pub.publish(marker_array); diff --git a/common/vector_map_server/nodes/vector_map_server/vector_map_server.cpp b/common/vector_map_server/nodes/vector_map_server/vector_map_server.cpp index e9e4b2db4e3..17411d3aa3b 100644 --- a/common/vector_map_server/nodes/vector_map_server/vector_map_server.cpp +++ b/common/vector_map_server/nodes/vector_map_server/vector_map_server.cpp @@ -15,9 +15,9 @@ */ #include -#include "autoware_msgs/Lane.h" +#include #include -#include "vector_map/vector_map.h" +#include #include "vector_map_server/GetDTLane.h" #include "vector_map_server/GetNode.h" @@ -47,6 +47,8 @@ #include "vector_map_server/GetRailCrossing.h" #include "vector_map_server/PositionState.h" +#include + using vector_map::VectorMap; using vector_map::Category; using vector_map::Color; @@ -106,12 +108,12 @@ bool isMergingLane(const Lane& lane) double computeDistance(const Point& p1, const Point& p2) { - return std::hypot(p2.bx - p1.bx, p2.ly - p1.ly); // XXX: don't consider z axis + return std::hypot(p2.bx - p1.bx, p2.ly - p1.ly); // XXX: don't consider z axis } double computeAngle(const Point& p1, const Point& p2) { - return std::atan2(p2.ly - p1.ly, p2.bx - p1.bx); // XXX: don't consider z axis + return std::atan2(p2.ly - p1.ly, p2.bx - p1.bx); // XXX: don't consider z axis } double computeScore(const Point& bp1, const Point& bp2, const Point& p1, const Point& p2, double radius) @@ -362,7 +364,7 @@ std::vector createFineLanes(const VectorMap& vmap, const autoware_msgs::La if (fine_p1.pid == 0) return null_lanes; - Point coarse_p1 = findNearestPoint(coarse_points, fine_p1); // certainly succeed + Point coarse_p1 = findNearestPoint(coarse_points, fine_p1); // certainly succeed if (computeDistance(fine_p1, coarse_p1) > radius) return null_lanes; @@ -373,7 +375,7 @@ std::vector createFineLanes(const VectorMap& vmap, const autoware_msgs::La { if (distance == -DBL_MAX) { - if (coarse_point.bx == coarse_p1.bx && coarse_point.ly == coarse_p1.ly) // XXX: don't consider z axis + if (coarse_point.bx == coarse_p1.bx && coarse_point.ly == coarse_p1.ly) // XXX: don't consider z axis distance = 0; continue; } @@ -574,7 +576,7 @@ class VectorMapServer { for (auto& marker : marker_array_.markers) marker.action = visualization_msgs::Marker::DELETE; - marker_array_pub_.publish(marker_array_); // clear previous marker + marker_array_pub_.publish(marker_array_); // clear previous marker } marker_array_ = marker_array_buffer; marker_array_pub_.publish(marker_array_); @@ -1033,7 +1035,7 @@ class VectorMapServer return true; } }; -} // namespace +} // namespace int main(int argc, char **argv) { diff --git a/common/vector_map_server/package.xml b/common/vector_map_server/package.xml index 11cd7a7c0d8..084652d1336 100644 --- a/common/vector_map_server/package.xml +++ b/common/vector_map_server/package.xml @@ -12,6 +12,7 @@ autoware_msgs geometry_msgs + roslint vector_map vector_map_msgs visualization_msgs diff --git a/common/vehicle_sim_model/CMakeLists.txt b/common/vehicle_sim_model/CMakeLists.txt new file mode 100644 index 00000000000..76959f026a4 --- /dev/null +++ b/common/vehicle_sim_model/CMakeLists.txt @@ -0,0 +1,65 @@ +cmake_minimum_required(VERSION 2.8.3) +project(vehicle_sim_model) + +find_package(autoware_build_flags REQUIRED) +find_package(catkin REQUIRED COMPONENTS + roslint +) +find_package(Eigen3 QUIET) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES vehicle_sim_model +) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++11") +roslint_cpp() + +SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") +add_compile_options(-std=c++14) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +set(vehicle_sim_model_SRC + src/vehicle_model_interface.cpp + src/vehicle_model_ideal.cpp + src/vehicle_model_constant_acceleration.cpp + src/vehicle_model_time_delay.cpp +) + +add_library(vehicle_sim_model ${vehicle_sim_model_SRC}) +add_dependencies(vehicle_sim_model ${catkin_EXPORTED_TARGETS}) +target_link_libraries(vehicle_sim_model ${catkin_LIBRARIES}) + +install(TARGETS vehicle_sim_model + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +catkin_install_python( + PROGRAMS scripts/fitParamDelayInputModel.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_rostest_gtest(test-vehicle_sim_model + test/test_vehicle_sim_model.test + test/src/test_vehicle_sim_model.cpp + ) + add_dependencies(test-vehicle_sim_model ${catkin_EXPORTED_TARGETS}) + target_link_libraries(test-vehicle_sim_model + vehicle_sim_model + ${catkin_LIBRARIES} + ) + roslint_add_test() +endif () diff --git a/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_constant_acceleration.h b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_constant_acceleration.h new file mode 100644 index 00000000000..28aab86097e --- /dev/null +++ b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_constant_acceleration.h @@ -0,0 +1,113 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file vehicle_model_constant_acceleration.h + * @brief vehicle model with constant acceleration for velocity & steeiring + * @author Takamasa Horibe + * @date 2019.08.17 + */ + +#ifndef VEHICLE_SIM_MODEL_VEHICLE_MODEL_CONSTANT_ACCELERATION_H +#define VEHICLE_SIM_MODEL_VEHICLE_MODEL_CONSTANT_ACCELERATION_H + +#include "vehicle_sim_model/vehicle_model_interface.h" + +#include +#include +#include + +/** + * @class vehicle constant acceleration twist model + * @brief calculate velocity & angular-velocity with constant acceleration + */ +class VehicleModelConstantAccelTwist : public VehicleModelInterface +{ +public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] wz_lim angular velocity limit [m/s] + * @param [in] vx_rate acceleration for velocity [m/ss] + * @param [in] wz_rate acceleration for angular velocity [rad/ss] + */ + VehicleModelConstantAccelTwist(double vx_lim, double wz_lim, double vx_rate, double wz_rate); + +private: + enum class IDX : int + { + X = 0, + Y, + YAW, + VX, + WZ, + }; + enum class IDX_U : int + { + VX_DES = 0, + WZ_DES, + }; + + const double vx_lim_; //!< @brief velocity limit + const double wz_lim_; //!< @brief angular velocity limit + const double vx_rate_; //!< @brief velocity rate + const double wz_rate_; //!< @brief angular velocity rate + + /** + * @brief get vehicle position x + */ + const double getX() const override; + + /** + * @brief get vehicle position y + */ + const double getY() const override; + + /** + * @brief get vehicle angle yaw + */ + const double getYaw() const override; + + /** + * @brief get vehicle velocity vx + */ + const double getVx() const override; + + /** + * @brief get vehicle angular-velocity wz + */ + const double getWz() const override; + + /** + * @brief get vehicle steering angle + */ + const double getSteer() const override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double& dt) override; + + /** + * @brief calculate derivative of states with constant acceleration + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) override; +}; + +#endif // VEHICLE_SIM_MODEL_VEHICLE_MODEL_CONSTANT_ACCELERATION_H diff --git a/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_ideal.h b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_ideal.h new file mode 100644 index 00000000000..1f0d8df0f13 --- /dev/null +++ b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_ideal.h @@ -0,0 +1,174 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file vehicle_model_ideal.h + * @brief vehicle ideal velocity model (no dynamics for desired velocity & anguler-velocity or steering) + * @author Takamasa Horibe + * @date 2019.08.17 + */ + +#ifndef VEHICLE_SIM_MODEL_VEHICLE_MODEL_IDEAL_H +#define VEHICLE_SIM_MODEL_VEHICLE_MODEL_IDEAL_H + +#include "vehicle_sim_model/vehicle_model_interface.h" + +#include +#include +#include + +/** + * @class vehicle ideal twist model + * @brief calculate ideal twist dynamics + */ +class VehicleModelIdealTwist : public VehicleModelInterface +{ +public: + /** + * @brief constructor + */ + VehicleModelIdealTwist(); + +private: + enum class IDX : int + { + X = 0, + Y, + YAW, + }; + enum class IDX_U : int + { + VX_DES = 0, + WZ_DES, + }; + + /** + * @brief get vehicle position x + */ + const double getX() const override; + + /** + * @brief get vehicle position y + */ + const double getY() const override; + + /** + * @brief get vehicle angle yaw + */ + const double getYaw() const override; + + /** + * @brief get vehicle velocity vx + */ + const double getVx() const override; + + /** + * @brief get vehicle angular-velocity wz + */ + const double getWz() const override; + + /** + * @brief get vehicle steering angle + */ + const double getSteer() const override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double& dt) override; + + /** + * @brief calculate derivative of states with ideal twist model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) override; +}; + +/** + * @class vehicle ideal steering model + * @brief calculate ideal steering dynamics + */ +class VehicleModelIdealSteer : public VehicleModelInterface +{ +public: + /** + * @brief constructor + * @param [in] wheelbase vehicle wheelbase length [m] + */ + explicit VehicleModelIdealSteer(double wheelbase); + +private: + enum class IDX : int + { + X = 0, + Y, + YAW, + }; + enum class IDX_U : int + { + VX_DES = 0, + STEER_DES, + }; + + const double wheelbase_; //!< @brief vehicle wheelbase length + + /** + * @brief get vehicle position x + */ + const double getX() const override; + + /** + * @brief get vehicle position y + */ + const double getY() const override; + + /** + * @brief get vehicle angle yaw + */ + const double getYaw() const override; + + /** + * @brief get vehicle velocity vx + */ + const double getVx() const override; + + /** + * @brief get vehicle angular-velocity wz + */ + const double getWz() const override; + + /** + * @brief get vehicle steering angle + */ + const double getSteer() const override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double& dt) override; + + /** + * @brief calculate derivative of states with ideal steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) override; +}; + +#endif // VEHICLE_SIM_MODEL_VEHICLE_MODEL_IDEAL_H diff --git a/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_interface.h b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_interface.h new file mode 100644 index 00000000000..a2b89598b46 --- /dev/null +++ b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_interface.h @@ -0,0 +1,129 @@ +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file vehicle_model_interface.h + * @brief vehicle model interface class + * @author Takamasa Horibe + * @date 2019.08.17 + */ + +#ifndef VEHICLE_SIM_MODEL_VEHICLE_MODEL_INTERFACE_H +#define VEHICLE_SIM_MODEL_VEHICLE_MODEL_INTERFACE_H + +#include + +/** + * @class vehicle model class + * @brief calculate vehicle dynamics + */ +class VehicleModelInterface +{ +protected: + const int dim_x_; //!< @brief dimension of state x + const int dim_u_; //!< @brief dimension of input u + Eigen::VectorXd state_; //!< @brief vehicle state vector + Eigen::VectorXd input_; //!< @brief vehicle input vector + +public: + /** + * @brief constructor + * @param [in] dim_x dimension of state x + * @param [in] dim_u dimension of input u + */ + VehicleModelInterface(int dim_x, int dim_u); + + /** + * @brief get state vector of model + */ + const Eigen::VectorXd& getState() const; + + /** + * @brief get input vector of model + */ + const Eigen::VectorXd& getInput() const; + + /** + * @brief set state vector of model + * @param [in] state state vector + */ + void setState(const Eigen::VectorXd& state); + + /** + * @brief set input vector of model + * @param [in] input input vector + */ + void setInput(const Eigen::VectorXd& input); + + /** + * @brief update vehicle states with Runge-Kutta methods + * @param [in] dt delta time [s] + * @param [in] input vehicle input + */ + void updateRungeKutta(const double& dt, const Eigen::VectorXd& input); + + /** + * @brief update vehicle states with Euler methods + * @param [in] dt delta time [s] + * @param [in] input vehicle input + */ + void updateEuler(const double& dt, const Eigen::VectorXd& input); + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + virtual void update(const double& dt) = 0; + + /** + * @brief get vehicle position x + */ + virtual const double getX() const = 0; + + /** + * @brief get vehicle position y + */ + virtual const double getY() const = 0; + + /** + * @brief get vehicle angle yaw + */ + virtual const double getYaw() const = 0; + + /** + * @brief get vehicle velocity vx + */ + virtual const double getVx() const = 0; + + /** + * @brief get vehicle angular-velocity wz + */ + virtual const double getWz() const = 0; + + /** + * @brief get vehicle steering angle + */ + virtual const double getSteer() const = 0; + + /** + * @brief calculate derivative of states with vehicle model + * @param [in] state current model state + * @param [in] input input vector to model + */ + virtual Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) = 0; +}; + +#endif // VEHICLE_SIM_MODEL_VEHICLE_MODEL_INTERFACE_H diff --git a/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_time_delay.h b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_time_delay.h new file mode 100644 index 00000000000..d30aa096768 --- /dev/null +++ b/common/vehicle_sim_model/include/vehicle_sim_model/vehicle_model_time_delay.h @@ -0,0 +1,242 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file vehicle_model_time_delay.h + * @brief vehicle model with time delay and 1-dimensional dynamics for velocity & steeiring + * @author Takamasa Horibe, Kim-Ngoc-Khanh Nguyen + * @date 2019.08.17 + */ + +#ifndef VEHICLE_SIM_MODEL_VEHICLE_MODEL_TIME_DELAY_H +#define VEHICLE_SIM_MODEL_VEHICLE_MODEL_TIME_DELAY_H + +#include "vehicle_sim_model/vehicle_model_interface.h" + +#include +#include +#include +#include +#include + +/** + * @class vehicle time delay twist model + * @brief calculate time delay twist dynamics + */ +class VehicleModelTimeDelayTwist : public VehicleModelInterface +{ +public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] angvel_lim angular velocity limit [m/s] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] wz_rate_lim angular acceleration llimit [rad/ss] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] vx_delay time delay for velocity command [s] + * @param [in] vx_time_constant time constant for 1D model of velocity dynamics + * @param [in] wx_delay time delay for angular-velocity command [s] + * @param [in] wz_time_constant time constant for 1D model of angular-velocity dynamics + */ + VehicleModelTimeDelayTwist(double vx_lim, double angvel_lim, double vx_rate_lim, double wz_rate_lim, double dt, + double vx_delay, double vx_time_constant, double wz_delay, double wz_time_constant); + +private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum class IDX : int + { + X = 0, + Y, + YAW, + VX, + WZ, + }; + enum class IDX_U : int + { + VX_DES = 0, + WZ_DES, + }; + + const double vx_lim_; //!< @brief velocity limit + const double vx_rate_lim_; //!< @brief acceleration limit + const double wz_lim_; //!< @brief angular velocity limit + const double wz_rate_lim_; //!< @brief angular acceleration limit + + std::deque vx_input_queue_; //!< @brief buffer for velocity command + std::deque wz_input_queue_; //!< @brief buffer for angular velocity command + const double vx_delay_; //!< @brief time delay for velocity command [s] + const double vx_time_constant_; //!< @brief time constant for 1D model of velocity dynamics + const double wz_delay_; //!< @brief time delay for angular-velocity command [s] + const double wz_time_constant_; //!< @brief time constant for 1D model of angular-velocity dynamics + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double& dt); + + /** + * @brief get vehicle position x + */ + const double getX() const override; + + /** + * @brief get vehicle position y + */ + const double getY() const override; + + /** + * @brief get vehicle angle yaw + */ + const double getYaw() const override; + + /** + * @brief get vehicle velocity vx + */ + const double getVx() const override; + + /** + * @brief get vehicle angular-velocity wz + */ + const double getWz() const override; + + /** + * @brief get vehicle steering angle + */ + const double getSteer() const override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double& dt) override; + + /** + * @brief calculate derivative of states with time delay twist model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) override; +}; + +class VehicleModelTimeDelaySteer : public VehicleModelInterface +{ +public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] vx_delay time delay for velocity command [s] + * @param [in] vx_time_constant time constant for 1D model of velocity dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + */ + VehicleModelTimeDelaySteer( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double vx_delay, double vx_time_constant, double steer_delay, + double steer_time_constant); + + /** + * @brief default destructor + */ + ~VehicleModelTimeDelaySteer() = default; + +private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum class IDX : int + { + X = 0, + Y, + YAW, + VX, + STEER, + }; + enum class IDX_U : int + { + VX_DES = 0, + STEER_DES, + }; + + const double vx_lim_; //!< @brief velocity limit [m/s] + const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] + const double steer_lim_; //!< @brief steering limit [rad] + const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_; //!< @brief vehicle wheelbase length [m] + + std::deque vx_input_queue_; //!< @brief buffer for velocity command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double vx_delay_; //!< @brief time delay for velocity command [s] + const double vx_time_constant_; //!< @brief time constant for 1D model of velocity dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for 1D model of steering dynamics + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double& dt); + + /** + * @brief get vehicle position x + */ + const double getX() const override; + + /** + * @brief get vehicle position y + */ + const double getY() const override; + + /** + * @brief get vehicle angle yaw + */ + const double getYaw() const override; + + /** + * @brief get vehicle velocity vx + */ + const double getVx() const override; + + /** + * @brief get vehicle angular-velocity wz + */ + const double getWz() const override; + + /** + * @brief get vehicle steering angle + */ + const double getSteer() const override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double& dt) override; + + /** + * @brief calculate derivative of states with time delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) override; +}; + +#endif // VEHICLE_SIM_MODEL_VEHICLE_MODEL_TIME_DELAY_H diff --git a/common/vehicle_sim_model/package.xml b/common/vehicle_sim_model/package.xml new file mode 100644 index 00000000000..c3fcacd7437 --- /dev/null +++ b/common/vehicle_sim_model/package.xml @@ -0,0 +1,20 @@ + + + vehicle_sim_model + 1.13.0 + The vehicle_sim_model package + Takamasa HORIBE + Takamasa HORIBE + + Apache 2 + + autoware_build_flags + catkin + + roscpp + roslint + python-numpy + python-pandas + rostest + rosunit + diff --git a/common/vehicle_sim_model/scripts/README_fitParamDelayInputModel.md b/common/vehicle_sim_model/scripts/README_fitParamDelayInputModel.md new file mode 100644 index 00000000000..511852ede90 --- /dev/null +++ b/common/vehicle_sim_model/scripts/README_fitParamDelayInputModel.md @@ -0,0 +1,28 @@ +# fitParamDelayInputModel.py scripts +## How to use +``` +python fitParamDelayInputModel.py --bag_file [bagfile] (--cutoff_time [cutoff_time] --cutoff_freq [cutoff_freq] --min_delay [min_delay] --max_delay [max_delay] --delay_incr [delay_incr]) +# in round brakets is optional arguments +python fitParamDelayInputModel.py --help # for more information +``` + +## Requirements python packages: +* numpy +* pandas + +## Required topics +* autoware_msgs::VehicleCmd /vehicle_cmd: assuming + * vehicle_cmd/ctrl_cmd/steering_angle is the steering angle input [rad] + * vehicle_cmd/ctrl_cmd/linear_velocity is the vehicle velocity input [m/s] +* autoware_msgs::VehicleStatus /vehicle_status : assuming + * vehicle_status/angle is the measured steering angle [rad] + * vehicle_status/speed is the measured vehicle speed [km/h] + +## Description +* Paramter fitting for Input Delay Model (First Order System with Dead Time) with rosbag file input +* Arguments explaining: + * CUTOFF_TIME: Cutoff time[sec]. Rosbag file often was start recording before autoware was run. Time before autoware was run should be cut off. This script will only consider data from t=cutoff_time to the end of the bag file (default is 1.0) + * CUTOFF_FREQ: Cutoff freq for low-pass filter[Hz], negative value will disable low-pass filter (default is 0.1) + * MIN_DELAY: Min value for searching delay loop (default is 0.1) + * MAX_DELAY: Max value for searching delay loop (default is 1.0) + * DELAY_INCR: Step value for searching delay loop (default is 0.01) diff --git a/common/vehicle_sim_model/scripts/fitParamDelayInputModel.py b/common/vehicle_sim_model/scripts/fitParamDelayInputModel.py new file mode 100644 index 00000000000..b40899e9292 --- /dev/null +++ b/common/vehicle_sim_model/scripts/fitParamDelayInputModel.py @@ -0,0 +1,139 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +import numpy as np +import argparse +import subprocess +import sys +from os import getcwd +from os.path import dirname, basename, splitext, join, exists +try: + import pandas as pd +except ImportError: + print ('Please install pandas. See http://pandas.pydata.org/pandas-docs/stable/') + sys.exit(1) + +FREQ_SAMPLE = 0.001 + +# low pass filter +def lowpass_filter(data, cutoff_freq=2, order=1, dt=FREQ_SAMPLE): + tau = 1.0 / (2 * np.pi * cutoff_freq) + for _ in range(order): + for i in range(1,len(data)): + data[i] = (tau / (tau + dt) * data[i-1] + dt / (tau + dt) * data[i]) + return data + +def rel2abs(path): + ''' + Return absolute path from relative path input + ''' + return join(getcwd(), path) + +def rosbag_to_csv(path, topic_name): + name = splitext(basename(path))[0] + suffix = topic_name.replace('/', '-') + output_path = join(dirname(path), name + '_' + suffix + '.csv') + if exists(output_path): + return output_path + else: + command = "rostopic echo -b {0} -p /{1} | sed -e 's/,/ /g' > {2}".format(path, topic_name, output_path) + print (command) + subprocess.check_call(command, shell=True) + return output_path + +def getActValue(df, speed_type): + tm = np.array(list(df['%time'])) * 1e-9 + # Unit Conversion + if speed_type: + val = np.array(list(df['field'])) / 3.6 + else: + val = np.array(list(df['field'])) + # Calc differential + dval = (val[2:] - val[:-2]) / (tm[2:] - tm[:-2]) + return tm[1:-1], val[1:-1], dval + +def getCmdValueWithDelay(df, delay): + tm = np.array(list(df['%time'])) * 1e-9 + val = np.array(list(df['field'])) + return tm + delay, val + +def getLinearInterpolate(_tm, _val, _index, ti): + tmp_t = _tm[_index] + tmp_nextt = _tm[_index + 1] + tmp_val = _val[_index] + tmp_nextval = _val[_index + 1] + val_i = tmp_val + (tmp_nextval - tmp_val) / (tmp_nextt - tmp_t) * (ti - tmp_t) + return val_i + +def getFittingTimeConstantParam(cmd_data, act_data, \ + delay, args, speed_type = False): + tm_cmd, cmd_delay = getCmdValueWithDelay(cmd_data, delay) + tm_act, act, dact = getActValue(act_data, speed_type) + _t_min = max(tm_cmd[0], tm_act[0]) + _t_max = min(tm_cmd[-1], tm_act[-1]) + tm_cmd = tm_cmd - _t_min + tm_act = tm_act - _t_min + MAX_CNT = int((_t_max - _t_min - args.cutoff_time) / FREQ_SAMPLE) + dact_samp = [None] * MAX_CNT + diff_actcmd_samp = [None] * MAX_CNT + ind_cmd = 0 + ind_act = 0 + for ind in range(MAX_CNT): + ti = ind * FREQ_SAMPLE + args.cutoff_time + while (tm_cmd[ind_cmd + 1] < ti): + ind_cmd += 1 + cmd_delay_i = getLinearInterpolate(tm_cmd, cmd_delay, ind_cmd, ti) + while (tm_act[ind_act + 1] < ti): + ind_act += 1 + act_i = getLinearInterpolate(tm_act, act, ind_act, ti) + dact_i = getLinearInterpolate(tm_act, dact, ind_act, ti) + dact_samp[ind] = dact_i + diff_actcmd_samp[ind] = act_i - cmd_delay_i + dact_samp = np.array(dact_samp) + diff_actcmd_samp = np.array(diff_actcmd_samp) + if args.cutoff_freq > 0: + dact_samp = lowpass_filter(dact_samp, cutoff_freq=args.cutoff_freq) + diff_actcmd_samp = lowpass_filter(diff_actcmd_samp, cutoff_freq=args.cutoff_freq) + dact_samp = dact_samp.reshape(1,-1) + diff_actcmd_samp = diff_actcmd_samp.reshape(1,-1) + tau = -np.dot(diff_actcmd_samp, np.linalg.pinv(dact_samp))[0,0] + error = np.linalg.norm(diff_actcmd_samp + tau * dact_samp) / dact_samp.shape[1] + return tau, error + +def getFittingParam(cmd_data, act_data, args, speed_type = False): + delay_range = int((args.max_delay - args.min_delay) / args.delay_incr) + delays = [args.min_delay + i * args.delay_incr for i in range(delay_range + 1)] + error_min = 1.0e10 + delay_opt = -1 + tau_opt = -1 + for delay in delays: + tau, error = getFittingTimeConstantParam(cmd_data, act_data, delay, args, speed_type=speed_type) + if tau > 0: + if error < error_min: + error_min = error + delay_opt = delay + tau_opt = tau + else: + break + return tau_opt, delay_opt, error_min + +if __name__ == '__main__': + topics = [ 'vehicle_cmd/ctrl_cmd/steering_angle', 'vehicle_status/angle', \ + 'vehicle_cmd/ctrl_cmd/linear_velocity', 'vehicle_status/speed'] + pd_data = [None] * len(topics) + parser = argparse.ArgumentParser(description='Paramter fitting for Input Delay Model (First Order System with Dead Time) with rosbag file input') + parser.add_argument('--bag_file', '-b', required=True, type=str, help='rosbag file', metavar='file') + parser.add_argument('--cutoff_time', default=1.0, type=float, help='Cutoff time[sec], Parameter fitting will only consider data from t= cutoff_time to the end of the bag file (default is 1.0)') + parser.add_argument('--cutoff_freq', default=0.1, type=float, help='Cutoff freq for low-pass filter[Hz], negative value will disable low-pass filter (default is 0.1)') + parser.add_argument('--min_delay', default=0.1, type=float, help='Min value for searching delay loop (default is 0.1)') + parser.add_argument('--max_delay', default=1.0, type=float, help='Max value for searching delay loop (default is 1.0)') + parser.add_argument('--delay_incr', default=0.01, type=float, help='Step value for searching delay loop (default is 0.01)') + args = parser.parse_args() + + for i, topic in enumerate(topics): + csv_log = rosbag_to_csv(rel2abs(args.bag_file), topic) + pd_data[i] = pd.read_csv(csv_log, sep=' ') + tau_opt, delay_opt, error = getFittingParam(pd_data[0], pd_data[1], args, speed_type=False) + print ('Steer angle: tau_opt = %2.4f, delay_opt = %2.4f, error = %2.4e' %(tau_opt, delay_opt, error)) + tau_opt, delay_opt, error = getFittingParam(pd_data[2], pd_data[3], args, speed_type=True) + print ('Velocity : tau_opt = %2.4f, delay_opt = %2.4f, error = %2.4e' %(tau_opt, delay_opt, error)) diff --git a/common/vehicle_sim_model/src/vehicle_model_constant_acceleration.cpp b/common/vehicle_sim_model/src/vehicle_model_constant_acceleration.cpp new file mode 100644 index 00000000000..21d472f418e --- /dev/null +++ b/common/vehicle_sim_model/src/vehicle_model_constant_acceleration.cpp @@ -0,0 +1,92 @@ + +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "vehicle_sim_model/vehicle_model_constant_acceleration.h" +#include + +VehicleModelConstantAccelTwist::VehicleModelConstantAccelTwist( + double vx_lim, double wz_lim, double vx_rate, double wz_rate) + : VehicleModelInterface(5 /* dim x */, 2 /* dim u */) + , vx_lim_(vx_lim) + , wz_lim_(wz_lim) + , vx_rate_(vx_rate) + , wz_rate_(wz_rate) {} + +const double VehicleModelConstantAccelTwist::getX() const +{ + return state_(static_cast(IDX::X)); +} +const double VehicleModelConstantAccelTwist::getY() const +{ + return state_(static_cast(IDX::Y)); +} +const double VehicleModelConstantAccelTwist::getYaw() const +{ + return state_(static_cast(IDX::YAW)); +} +const double VehicleModelConstantAccelTwist::getVx() const +{ + return state_(static_cast(IDX::VX)); +} +const double VehicleModelConstantAccelTwist::getWz() const +{ + return state_(static_cast(IDX::WZ)); +} +const double VehicleModelConstantAccelTwist::getSteer() const +{ + return 0.0; +} +void VehicleModelConstantAccelTwist::update(const double& dt) +{ + updateRungeKutta(dt, input_); +} +Eigen::VectorXd VehicleModelConstantAccelTwist::calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) +{ + const double vel = state(static_cast(IDX::VX)); + const double angvel = state(static_cast(IDX::WZ)); + const double yaw = state(static_cast(IDX::YAW)); + const double vx_des = std::max(std::min(input(static_cast(IDX_U::VX_DES)), vx_lim_), -vx_lim_); + const double wz_des = std::max(std::min(input(static_cast(IDX_U::WZ_DES)), wz_lim_), -wz_lim_); + double vx_rate = 0.0; + double wz_rate = 0.0; + if (vx_des > vel) + { + vx_rate = vx_rate_; + } + else if (vx_des < vel) + { + vx_rate = -vx_rate_; + } + + if (wz_des > angvel) + { + wz_rate = wz_rate_; + } + else if (wz_des < angvel) + { + wz_rate = -wz_rate_; + } + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(static_cast(IDX::X)) = vel * cos(yaw); + d_state(static_cast(IDX::Y)) = vel * sin(yaw); + d_state(static_cast(IDX::YAW)) = angvel; + d_state(static_cast(IDX::VX)) = vx_rate; + d_state(static_cast(IDX::WZ)) = wz_rate; + + return d_state; +} diff --git a/common/vehicle_sim_model/src/vehicle_model_ideal.cpp b/common/vehicle_sim_model/src/vehicle_model_ideal.cpp new file mode 100644 index 00000000000..a7b44af054a --- /dev/null +++ b/common/vehicle_sim_model/src/vehicle_model_ideal.cpp @@ -0,0 +1,108 @@ + +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "vehicle_sim_model/vehicle_model_ideal.h" + +VehicleModelIdealTwist::VehicleModelIdealTwist() : VehicleModelInterface(3 /* dim x */, 2 /* dim u */) {} + +const double VehicleModelIdealTwist::getX() const +{ + return state_(static_cast(IDX::X)); +} +const double VehicleModelIdealTwist::getY() const +{ + return state_(static_cast(IDX::Y)); +} +const double VehicleModelIdealTwist::getYaw() const +{ + return state_(static_cast(IDX::YAW)); +} +const double VehicleModelIdealTwist::getVx() const +{ + return input_(static_cast(IDX_U::VX_DES)); +} +const double VehicleModelIdealTwist::getWz() const +{ + return input_(static_cast(IDX_U::WZ_DES)); +} +const double VehicleModelIdealTwist::getSteer() const +{ + return 0.0; +} +void VehicleModelIdealTwist::update(const double& dt) +{ + updateRungeKutta(dt, input_); +} +Eigen::VectorXd VehicleModelIdealTwist::calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) +{ + const double yaw = state(static_cast(IDX::YAW)); + const double vx = input(static_cast(IDX_U::VX_DES)); + const double wz = input(static_cast(IDX_U::WZ_DES)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(static_cast(IDX::X)) = vx * cos(yaw); + d_state(static_cast(IDX::Y)) = vx * sin(yaw); + d_state(static_cast(IDX::YAW)) = wz; + + return d_state; +} + +VehicleModelIdealSteer::VehicleModelIdealSteer(double wheelbase) + : VehicleModelInterface(3 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase) {} + +const double VehicleModelIdealSteer::getX() const +{ + return state_(static_cast(IDX::X)); +} +const double VehicleModelIdealSteer::getY() const +{ + return state_(static_cast(IDX::Y)); +} +const double VehicleModelIdealSteer::getYaw() const +{ + return state_(static_cast(IDX::YAW)); +} +const double VehicleModelIdealSteer::getVx() const +{ + return input_(static_cast(IDX_U::VX_DES)); +} +const double VehicleModelIdealSteer::getWz() const +{ + return input_(static_cast(IDX_U::VX_DES)) + * std::tan(input_(static_cast(IDX_U::STEER_DES))) / wheelbase_; +} +const double VehicleModelIdealSteer::getSteer() const +{ + return input_(static_cast(IDX_U::STEER_DES)); +} +void VehicleModelIdealSteer::update(const double& dt) +{ + updateRungeKutta(dt, input_); +} +Eigen::VectorXd VehicleModelIdealSteer::calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) +{ + const double yaw = state(static_cast(IDX::YAW)); + const double vx = input(static_cast(IDX_U::VX_DES)); + const double steer = input(static_cast(IDX_U::STEER_DES)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(static_cast(IDX::X)) = vx * cos(yaw); + d_state(static_cast(IDX::Y)) = vx * sin(yaw); + d_state(static_cast(IDX::YAW)) = vx * std::tan(steer) / wheelbase_; + + return d_state; +} diff --git a/common/vehicle_sim_model/src/vehicle_model_interface.cpp b/common/vehicle_sim_model/src/vehicle_model_interface.cpp new file mode 100644 index 00000000000..727d349b040 --- /dev/null +++ b/common/vehicle_sim_model/src/vehicle_model_interface.cpp @@ -0,0 +1,53 @@ +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "vehicle_sim_model/vehicle_model_interface.h" + +VehicleModelInterface::VehicleModelInterface(int dim_x, int dim_u) : dim_x_(dim_x), dim_u_(dim_u) +{ + state_ = Eigen::VectorXd::Zero(dim_x_); + input_ = Eigen::VectorXd::Zero(dim_u_); +} + +void VehicleModelInterface::updateRungeKutta(const double& dt, const Eigen::VectorXd& input) +{ + Eigen::VectorXd k1 = calcModel(state_, input); + Eigen::VectorXd k2 = calcModel(state_ + k1 * 0.5 * dt, input); + Eigen::VectorXd k3 = calcModel(state_ + k2 * 0.5 * dt, input); + Eigen::VectorXd k4 = calcModel(state_ + k3 * dt, input); + + state_ += 1.0 / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4) * dt; +} +void VehicleModelInterface::updateEuler(const double& dt, const Eigen::VectorXd& input) +{ + state_ += calcModel(state_, input) * dt; +} +const Eigen::VectorXd& VehicleModelInterface::getState() const +{ + return state_; +} +const Eigen::VectorXd& VehicleModelInterface::getInput() const +{ + return input_; +} +void VehicleModelInterface::setState(const Eigen::VectorXd& state) +{ + state_ = state; +} +void VehicleModelInterface::setInput(const Eigen::VectorXd& input) +{ + input_ = input; +} diff --git a/common/vehicle_sim_model/src/vehicle_model_time_delay.cpp b/common/vehicle_sim_model/src/vehicle_model_time_delay.cpp new file mode 100644 index 00000000000..13c0ab8567f --- /dev/null +++ b/common/vehicle_sim_model/src/vehicle_model_time_delay.cpp @@ -0,0 +1,240 @@ + +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "vehicle_sim_model/vehicle_model_time_delay.h" +#include + +/* + * + * VehicleModelTimeDelayTwist + * + */ + +VehicleModelTimeDelayTwist::VehicleModelTimeDelayTwist( + double vx_lim, double wz_lim, double vx_rate_lim, double wz_rate_lim, + double dt, double vx_delay, double vx_time_constant, double wz_delay, + double wz_time_constant) + : VehicleModelInterface(5 /* dim x */, 2 /* dim u */) + , MIN_TIME_CONSTANT(0.03) + , vx_lim_(vx_lim) + , vx_rate_lim_(vx_rate_lim) + , wz_lim_(wz_lim) + , wz_rate_lim_(wz_rate_lim) + , vx_delay_(vx_delay) + , vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)) + , wz_delay_(wz_delay) + , wz_time_constant_(std::max(wz_time_constant, MIN_TIME_CONSTANT)) +{ + if (vx_time_constant < MIN_TIME_CONSTANT) + { + std::cerr << "Settings vx_time_constant is too small, replace it by " + << MIN_TIME_CONSTANT << std::endl; + } + if (wz_time_constant < MIN_TIME_CONSTANT) + { + std::cerr << "Settings wz_time_constant is too small, replace it by " + << MIN_TIME_CONSTANT << std::endl; + } + initializeInputQueue(dt); +} + +const double VehicleModelTimeDelayTwist::getX() const +{ + return state_(static_cast(IDX::X)); +} +const double VehicleModelTimeDelayTwist::getY() const +{ + return state_(static_cast(IDX::Y)); +} +const double VehicleModelTimeDelayTwist::getYaw() const +{ + return state_(static_cast(IDX::YAW)); +} +const double VehicleModelTimeDelayTwist::getVx() const +{ + return state_(static_cast(IDX::VX)); +} +const double VehicleModelTimeDelayTwist::getWz() const +{ + return state_(static_cast(IDX::WZ)); +} +const double VehicleModelTimeDelayTwist::getSteer() const +{ + return 0.0; +} +void VehicleModelTimeDelayTwist::update(const double& dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + vx_input_queue_.push_back(input_(static_cast(IDX_U::VX_DES))); + delayed_input(static_cast(IDX_U::VX_DES)) = vx_input_queue_.front(); + vx_input_queue_.pop_front(); + wz_input_queue_.push_back(input_(static_cast(IDX_U::WZ_DES))); + delayed_input(static_cast(IDX_U::WZ_DES)) = wz_input_queue_.front(); + wz_input_queue_.pop_front(); + + updateRungeKutta(dt, delayed_input); +} +void VehicleModelTimeDelayTwist::initializeInputQueue(const double& dt) +{ + size_t vx_input_queue_size = static_cast(round(vx_delay_ / dt)); + for (size_t i = 0; i < vx_input_queue_size; i++) + { + vx_input_queue_.push_back(0.0); + } + size_t wz_input_queue_size = static_cast(round(wz_delay_ / dt)); + for (size_t i = 0; i < wz_input_queue_size; i++) + { + wz_input_queue_.push_back(0.0); + } +} + +Eigen::VectorXd VehicleModelTimeDelayTwist::calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) +{ + const double vx = state(static_cast(IDX::VX)); + const double wz = state(static_cast(IDX::WZ)); + const double yaw = state(static_cast(IDX::YAW)); + const double delay_input_vx = input(static_cast(IDX_U::VX_DES)); + const double delay_input_wz = input(static_cast(IDX_U::WZ_DES)); + const double delay_vx_des = std::max(std::min(delay_input_vx, vx_lim_), -vx_lim_); + const double delay_wz_des = std::max(std::min(delay_input_wz, wz_lim_), -wz_lim_); + double vx_rate = -(vx - delay_vx_des) / vx_time_constant_; + double wz_rate = -(wz - delay_wz_des) / wz_time_constant_; + vx_rate = std::min(vx_rate_lim_, std::max(-vx_rate_lim_, vx_rate)); + wz_rate = std::min(wz_rate_lim_, std::max(-wz_rate_lim_, wz_rate)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(static_cast(IDX::X)) = vx * cos(yaw); + d_state(static_cast(IDX::Y)) = vx * sin(yaw); + d_state(static_cast(IDX::YAW)) = wz; + d_state(static_cast(IDX::VX)) = vx_rate; + d_state(static_cast(IDX::WZ)) = wz_rate; + + return d_state; +}; + +/* + * + * VehicleModelTimeDelaySteer + * + */ +VehicleModelTimeDelaySteer::VehicleModelTimeDelaySteer( + double vx_lim, double steer_lim, double vx_rate_lim, + double steer_rate_lim, double wheelbase, double dt, double vx_delay, + double vx_time_constant, double steer_delay, + double steer_time_constant) + : VehicleModelInterface(5 /* dim x */, 2 /* dim u */) + , MIN_TIME_CONSTANT(0.03) + , vx_lim_(vx_lim) + , vx_rate_lim_(vx_rate_lim) + , steer_lim_(steer_lim) + , steer_rate_lim_(steer_rate_lim) + , wheelbase_(wheelbase) + , vx_delay_(vx_delay) + , vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)) + , steer_delay_(steer_delay) + , steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)) +{ + if (vx_time_constant < MIN_TIME_CONSTANT) + { + std::cerr << "Settings vx_time_constant is too small, replace it by " + << MIN_TIME_CONSTANT << std::endl; + } + if (steer_time_constant < MIN_TIME_CONSTANT) + { + std::cerr << "Settings wz_time_constant is too small, replace it by " + << MIN_TIME_CONSTANT << std::endl; + } + + initializeInputQueue(dt); +} + +const double VehicleModelTimeDelaySteer::getX() const +{ + return state_(static_cast(IDX::X)); +} +const double VehicleModelTimeDelaySteer::getY() const +{ + return state_(static_cast(IDX::Y)); +} +const double VehicleModelTimeDelaySteer::getYaw() const +{ + return state_(static_cast(IDX::YAW)); +} +const double VehicleModelTimeDelaySteer::getVx() const +{ + return state_(static_cast(IDX::VX)); +} +const double VehicleModelTimeDelaySteer::getWz() const +{ + return state_(static_cast(IDX::VX)) + * std::tan(state_(static_cast(IDX::STEER))) / wheelbase_; +} +const double VehicleModelTimeDelaySteer::getSteer() const +{ + return state_(static_cast(IDX::STEER)); +} +void VehicleModelTimeDelaySteer::update(const double& dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + vx_input_queue_.push_back(input_(static_cast(IDX_U::VX_DES))); + delayed_input(static_cast(IDX_U::VX_DES)) = vx_input_queue_.front(); + vx_input_queue_.pop_front(); + steer_input_queue_.push_back(input_(static_cast(IDX_U::STEER_DES))); + delayed_input(static_cast(IDX_U::STEER_DES)) = steer_input_queue_.front(); + steer_input_queue_.pop_front(); + + updateRungeKutta(dt, delayed_input); +} +void VehicleModelTimeDelaySteer::initializeInputQueue(const double& dt) +{ + size_t vx_input_queue_size = static_cast(round(vx_delay_ / dt)); + for (size_t i = 0; i < vx_input_queue_size; i++) + { + vx_input_queue_.push_back(0.0); + } + size_t steer_input_queue_size = static_cast(round(steer_delay_ / dt)); + for (size_t i = 0; i < steer_input_queue_size; i++) + { + steer_input_queue_.push_back(0.0); + } +} + +Eigen::VectorXd VehicleModelTimeDelaySteer::calcModel(const Eigen::VectorXd& state, const Eigen::VectorXd& input) +{ + const double vel = state(static_cast(IDX::VX)); + const double yaw = state(static_cast(IDX::YAW)); + const double steer = state(static_cast(IDX::STEER)); + const double delay_input_vel = input(static_cast(IDX_U::VX_DES)); + const double delay_input_steer = input(static_cast(IDX_U::STEER_DES)); + const double delay_vx_des = std::max(std::min(delay_input_vel, vx_lim_), -vx_lim_); + const double delay_steer_des = std::max(std::min(delay_input_steer, steer_lim_), -steer_lim_); + double vx_rate = -(vel - delay_vx_des) / vx_time_constant_; + double steer_rate = -(steer - delay_steer_des) / steer_time_constant_; + vx_rate = std::min(vx_rate_lim_, std::max(-vx_rate_lim_, vx_rate)); + steer_rate = std::min(steer_rate_lim_, std::max(-steer_rate_lim_, steer_rate)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(static_cast(IDX::X)) = vel * cos(yaw); + d_state(static_cast(IDX::Y)) = vel * sin(yaw); + d_state(static_cast(IDX::YAW)) = vel * std::tan(steer) / wheelbase_; + d_state(static_cast(IDX::VX)) = vx_rate; + d_state(static_cast(IDX::STEER)) = steer_rate; + + return d_state; +} diff --git a/common/vehicle_sim_model/test/src/test_vehicle_sim_model.cpp b/common/vehicle_sim_model/test/src/test_vehicle_sim_model.cpp new file mode 100644 index 00000000000..96a2d4fe021 --- /dev/null +++ b/common/vehicle_sim_model/test/src/test_vehicle_sim_model.cpp @@ -0,0 +1,255 @@ +/* + * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include + +#include "vehicle_sim_model/vehicle_model_interface.h" +#include "vehicle_sim_model/vehicle_model_ideal.h" +#include "vehicle_sim_model/vehicle_model_time_delay.h" +#include "vehicle_sim_model/vehicle_model_constant_acceleration.h" + +enum class VehicleModelType +{ + IDEAL_TWIST = 0, + IDEAL_STEER = 1, + DELAY_TWIST = 2, + DELAY_STEER = 3, + CONST_ACCEL_TWIST = 4 +}; + +class TestSuite : public ::testing::Test +{ +public: + VehicleModelType vehicle_model_type_; + std::shared_ptr vehicle_model_ptr_; + const double wheelbase_; + const double dt_, angvel_lim_, vel_lim_, steer_lim_, accel_rate_, angvel_rate_, + steer_rate_lim_, vel_time_delay_, vel_time_constant_, steer_time_delay_, + steer_time_constant_, angvel_time_delay_, angvel_time_constant_; + + TestSuite() + : wheelbase_(2.7) + , dt_(0.02) + , angvel_lim_(3.0) + , vel_lim_(10.0) + , steer_lim_(3.14 / 3.0) + , accel_rate_(1.0) + , angvel_rate_(1.0) + , steer_rate_lim_(0.3) + , vel_time_delay_(0.25) + , vel_time_constant_(0.6197) + , steer_time_delay_(0.24) + , steer_time_constant_(0.27) + , angvel_time_delay_(0.2) + , angvel_time_constant_(0.5) {} + ~TestSuite() + { + } + + void resetVehicleModel() + { + vehicle_model_ptr_.reset(); + if (vehicle_model_type_ == VehicleModelType::IDEAL_TWIST) + { + vehicle_model_ptr_ = std::make_shared(); + } + else if (vehicle_model_type_ == VehicleModelType::IDEAL_STEER) + { + vehicle_model_ptr_ = std::make_shared(wheelbase_); + } + else if (vehicle_model_type_ == VehicleModelType::DELAY_TWIST) + { + vehicle_model_ptr_ = std::make_shared( + vel_lim_, angvel_lim_, accel_rate_, angvel_rate_, dt_, vel_time_delay_, + vel_time_constant_, angvel_time_delay_, angvel_time_constant_); + } + else if (vehicle_model_type_ == VehicleModelType::DELAY_STEER) + { + vehicle_model_ptr_ = std::make_shared( + vel_lim_, steer_lim_, accel_rate_, steer_rate_lim_, + wheelbase_, dt_, vel_time_delay_, vel_time_constant_, + steer_time_delay_, steer_time_constant_); + } + else if (vehicle_model_type_ == VehicleModelType::CONST_ACCEL_TWIST) + { + vehicle_model_ptr_ = std::make_shared( + vel_lim_, angvel_lim_, accel_rate_, angvel_rate_); + } + + + if (vehicle_model_type_ == VehicleModelType::IDEAL_TWIST || + vehicle_model_type_ == VehicleModelType::IDEAL_STEER) + { + Eigen::VectorXd state(3); + state << 0.0, 0.0, 0.0; + vehicle_model_ptr_->setState(state); + } + else + { + Eigen::VectorXd state(5); + state << 0.0, 0.0, 0.0, 0.0, 0.0; + vehicle_model_ptr_->setState(state); + } + } + + void updateNLoopWithConstantInput( + const Eigen::VectorXd& input, const int loop_count) + { + for (int i = 0; i < loop_count; ++i) + { + vehicle_model_ptr_->setInput(input); + vehicle_model_ptr_->update(dt_); + } + } + + void checkVel(const double vel) + { + if (vel > 0.0) // Forward + { + ASSERT_GT(vehicle_model_ptr_->getVx(), vel) + << "Forward: It should be greater than " << vel; + } + else if (vel < 0.0) + { + ASSERT_LT(vehicle_model_ptr_->getVx(), vel) + << "Backward: It should be less than " << vel; + } + } + + void checkStraight(const double pos_x) + { + if (pos_x > 0.0) + { + ASSERT_GT(vehicle_model_ptr_->getX(), pos_x) + << "Forward: It should be greater than " << pos_x; + } + else if (pos_x < 0.0) + { + ASSERT_LT(vehicle_model_ptr_->getX(), pos_x) + << "Backward: It should be less than " << pos_x; + } + } + + void checkTurn(const double pos_y) + { + if (pos_y > 0.0) + { + ASSERT_GT(vehicle_model_ptr_->getY(), pos_y) + << "Right turn: It should be greater than " << pos_y; + } + else if (pos_y < 0.0) + { + ASSERT_LT(vehicle_model_ptr_->getY(), pos_y) + << "Left turn: It should be less than " << pos_y; + } + } + + void testGoStraightForward() + { + Eigen::VectorXd input(2); + input << 3.0, 0.0; + const double v_threshold = 0.5; + const double x_threshold = 1.0; + resetVehicleModel(); + updateNLoopWithConstantInput(input, 150); + checkVel(v_threshold); + checkStraight(x_threshold); + } + + void testGoStraightBackward() + { + Eigen::VectorXd input(2); + input << -3.0, 0.0; + const double v_threshold = -0.5; + const double x_threshold = -1.0; + resetVehicleModel(); + updateNLoopWithConstantInput(input, 150); + checkVel(v_threshold); + checkStraight(x_threshold); + } + + void testGoRightForward() + { + Eigen::VectorXd input(2); + input << 3.0, 0.1; + const double v_threshold = 0.5; + const double y_threshold = 0.1; + resetVehicleModel(); + updateNLoopWithConstantInput(input, 150); + checkVel(v_threshold); + checkTurn(y_threshold); + } + + void testGoLeftForward() + { + Eigen::VectorXd input(2); + input << 3.0, -0.1; + const double v_threshold = 0.5; + const double y_threshold = -0.1; + resetVehicleModel(); + updateNLoopWithConstantInput(input, 150); + checkVel(v_threshold); + checkTurn(y_threshold); + } + + void testAllMotion() + { + testGoStraightForward(); + testGoStraightBackward(); + testGoRightForward(); + testGoLeftForward(); + } +}; + +TEST_F(TestSuite, TestIdealTwist) +{ + vehicle_model_type_ = VehicleModelType::IDEAL_TWIST; + testAllMotion(); +} + +TEST_F(TestSuite, TestIdealSteer) +{ + vehicle_model_type_ = VehicleModelType::IDEAL_STEER; + testAllMotion(); +} + +TEST_F(TestSuite, TestDelayTwist) +{ + vehicle_model_type_ = VehicleModelType::DELAY_TWIST; + testAllMotion(); +} + +TEST_F(TestSuite, TestDelaySteer) +{ + vehicle_model_type_ = VehicleModelType::DELAY_STEER; + testAllMotion(); +} + +TEST_F(TestSuite, TestConstAccelTwist) +{ + vehicle_model_type_ = VehicleModelType::CONST_ACCEL_TWIST; + testAllMotion(); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/common/vehicle_sim_model/test/test_vehicle_sim_model.test b/common/vehicle_sim_model/test/test_vehicle_sim_model.test new file mode 100644 index 00000000000..03279ddba94 --- /dev/null +++ b/common/vehicle_sim_model/test/test_vehicle_sim_model.test @@ -0,0 +1,5 @@ + + + + + diff --git a/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.h b/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.h index 209f10f81a9..812083596ef 100644 --- a/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.h +++ b/core_perception/ekf_localizer/include/ekf_localizer/ekf_localizer.h @@ -57,7 +57,6 @@ class EKFLocalizer ros::Subscriber sub_pose_with_cov_; //!< @brief measurement pose with covariance subscriber ros::Subscriber sub_twist_with_cov_; //!< @brief measurement twist with covariance subscriber ros::Timer timer_control_; //!< @brief time for ekf calculation callback - ros::Timer timer_tf_; //!< @brief timer to send transform tf2_ros::TransformBroadcaster tf_br_; //!< @brief tf broadcaster TimeDelayKalmanFilter ekf_; //!< @brief extended kalman filter instance. @@ -66,7 +65,6 @@ class EKFLocalizer bool show_debug_info_; double ekf_rate_; //!< @brief EKF predict rate double ekf_dt_; //!< @brief = 1 / ekf_rate_ - double tf_rate_; //!< @brief tf publish rate bool enable_yaw_bias_estimation_; //!< @brief for LiDAR mount error. if true, publish /estimate_yaw_bias std::string pose_frame_id_; //!< @brief Parent frame for pose and tf output std::string child_frame_id_; //!< @brief Child frame for pose and tf output @@ -126,9 +124,9 @@ class EKFLocalizer void timerCallback(const ros::TimerEvent& e); /** - * @brief publish tf for tf_rate [Hz] + * @brief publish tf */ - void timerTFCallback(const ros::TimerEvent& e); + void broadcastTF(); /** * @brief set pose measurement diff --git a/core_perception/ekf_localizer/launch/ekf_localizer.launch b/core_perception/ekf_localizer/launch/ekf_localizer.launch index 0afde631ab2..5beec061b2e 100644 --- a/core_perception/ekf_localizer/launch/ekf_localizer.launch +++ b/core_perception/ekf_localizer/launch/ekf_localizer.launch @@ -3,7 +3,6 @@ - @@ -56,7 +55,6 @@ - @@ -82,4 +80,4 @@ - \ No newline at end of file + diff --git a/core_perception/ekf_localizer/src/ekf_localizer.cpp b/core_perception/ekf_localizer/src/ekf_localizer.cpp index a48ccf60a2d..5acad4a5923 100644 --- a/core_perception/ekf_localizer/src/ekf_localizer.cpp +++ b/core_perception/ekf_localizer/src/ekf_localizer.cpp @@ -27,7 +27,6 @@ EKFLocalizer::EKFLocalizer() : nh_(""), pnh_("~"), dim_x_(6 /* x, y, yaw, yaw_bi pnh_.param("show_debug_info", show_debug_info_, bool(false)); pnh_.param("predict_frequency", ekf_rate_, double(50.0)); ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1); - pnh_.param("tf_rate", tf_rate_, double(10.0)); pnh_.param("enable_yaw_bias_estimation", enable_yaw_bias_estimation_, bool(true)); pnh_.param("extend_state_step", extend_state_step_, int(50)); pnh_.param("pose_frame_id", pose_frame_id_, std::string("/map")); @@ -71,7 +70,6 @@ EKFLocalizer::EKFLocalizer() : nh_(""), pnh_("~"), dim_x_(6 /* x, y, yaw, yaw_bi /* initialize ros system */ timer_control_ = nh_.createTimer(ros::Duration(ekf_dt_), &EKFLocalizer::timerCallback, this); - timer_tf_ = nh_.createTimer(ros::Duration(1.0 / tf_rate_), &EKFLocalizer::timerTFCallback, this); pub_pose_ = nh_.advertise("ekf_pose", 1); pub_pose_cov_ = nh_.advertise("ekf_pose_with_covariance", 1); pub_twist_ = nh_.advertise("ekf_twist", 1); @@ -184,9 +182,9 @@ void EKFLocalizer::setCurrentResult() } /* - * timerTFCallback + * broadcastTF */ -void EKFLocalizer::timerTFCallback(const ros::TimerEvent& e) +void EKFLocalizer::broadcastTF() { if (current_ekf_pose_.header.frame_id == "") return; diff --git a/core_perception/gnss_localizer/CMakeLists.txt b/core_perception/gnss_localizer/CMakeLists.txt index 772da84547a..67a04736f7e 100644 --- a/core_perception/gnss_localizer/CMakeLists.txt +++ b/core_perception/gnss_localizer/CMakeLists.txt @@ -3,11 +3,11 @@ project(gnss_localizer) find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS - roscpp geometry_msgs - std_msgs - nmea_msgs gnss + nmea_msgs + roscpp + std_msgs tf ) @@ -34,6 +34,17 @@ target_include_directories(nmea2tfpose PRIVATE nodes/nmea2tfpose ${catkin_INCLUD target_link_libraries(nmea2tfpose ${catkin_LIBRARIES}) add_dependencies(nmea2tfpose ${catkin_EXPORTED_TARGETS}) +install(TARGETS nmea2tfpose fix2tfpose + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) + if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) find_package(rosunit REQUIRED) @@ -42,12 +53,3 @@ if(CATKIN_ENABLE_TESTING) target_link_libraries(nmea_test ${catkin_LIBRARIES}) add_dependencies(nmea_test ${catkin_EXPORTED_TARGETS}) endif() - -install(TARGETS nmea2tfpose fix2tfpose - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) diff --git a/core_perception/gnss_localizer/launch/nmea2tfpose.launch b/core_perception/gnss_localizer/launch/nmea2tfpose.launch index 66ae131e52e..814d59f74e9 100644 --- a/core_perception/gnss_localizer/launch/nmea2tfpose.launch +++ b/core_perception/gnss_localizer/launch/nmea2tfpose.launch @@ -2,9 +2,11 @@ + + diff --git a/core_perception/gnss_localizer/test/nmea_test.cpp b/core_perception/gnss_localizer/test/nmea_test.cpp index 814fb706608..2a7df2fd13a 100644 --- a/core_perception/gnss_localizer/test/nmea_test.cpp +++ b/core_perception/gnss_localizer/test/nmea_test.cpp @@ -1,163 +1,137 @@ +#include + #include #include #include #include -class NmeaHelper -{ -public: - NmeaHelper() : rcvd_msg() - { - } +#define DUMMY_NMEA_SENTENCE_0 \ + "$GPGGA,0,80.000,N,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47" +#define DUMMY_NMEA_SENTENCE_1 \ + "$GPGGA,0,81.000,N,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47" - void pose_callback(const geometry_msgs::PoseStamped::ConstPtr &msg) - { - rcvd_msg = *msg; - ROS_ERROR("Got message!"); +class NmeaHelper { +public: + NmeaHelper() = default; + + // Initialise the subscriber and publisher. Wait for connection before + // continuing. + void init() { + sub = nh.subscribe("/test/gnss_pose", 1, &NmeaHelper::pose_callback, this); + pub = nh.advertise("/test/nmea_sentence", 1, true); + auto timeout = wait_for_connection(); + ASSERT_FALSE(timeout); } - geometry_msgs::PoseStamped rcvd_msg; -}; - -TEST(Nmea2TfPose, ggaTest) -{ - ros::NodeHandle nh; - NmeaHelper nmeah; - nmea_msgs::Sentence msg; - ros::Subscriber sub = nh.subscribe("/test/gnss_pose", 1, &NmeaHelper::pose_callback, &nmeah); - ros::Publisher pub = nh.advertise("/test/nmea_sentence", 1); - - // Give time to set up pub/sub - ros::WallDuration(0.5).sleep(); - - // Send a dummy message, because nodes only respond after they can compute orientation, - // which requires having seen two different positions - msg.sentence = "$GPGGA,0,80.000,N,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); + // run test case. Send nmea sentence on published, wait for message on + // subscriber. Assert on the value of the returned message. + void test_case(std::string nmea_sentence, float expected_x, float expected_y, + float expected_z = NAN) { + reset(); - // Start sending messages which are actually checked + nmea_msgs::Sentence msg; + msg.sentence = nmea_sentence.c_str(); + pub.publish(msg); - msg.sentence = "$GPGGA,0,90.000,N,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47"; - pub.publish(msg); + auto timeout = wait_for_new_msg(); - // Give time to publish - ros::WallDuration(0.5).sleep(); + ASSERT_FALSE(timeout); + ASSERT_FLOAT_EQ(expected_x, rcvd_msg.pose.position.x); + ASSERT_FLOAT_EQ(expected_y, rcvd_msg.pose.position.y); - ros::spinOnce(); - - ASSERT_FLOAT_EQ(-81305263.475,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(5958827.35862,nmeah.rcvd_msg.pose.position.y); - ASSERT_FLOAT_EQ(545.4,nmeah.rcvd_msg.pose.position.z); - - msg.sentence = "$GPGGA,0,90.000,N,90.000,W,1,08,0.9,545.4,M,46.9,M,,*47"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); - - ros::spinOnce(); - - ASSERT_FLOAT_EQ(-90207689.8924,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(7519179.29268,nmeah.rcvd_msg.pose.position.y); - ASSERT_FLOAT_EQ(545.4,nmeah.rcvd_msg.pose.position.z); - - msg.sentence = "$GPGGA,0,90.000,S,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); + if (!std::isnan(expected_z)) { + ASSERT_FLOAT_EQ(expected_z, rcvd_msg.pose.position.z); + } + } - ros::spinOnce(); +private: + // The callback invoked when a message is received by the subscriber. + void pose_callback(const geometry_msgs::PoseStamped::ConstPtr &msg) { + rcvd_msg = *msg; + new_msg = true; + } - ASSERT_FLOAT_EQ(-81305263.475,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(-13929115.5907,nmeah.rcvd_msg.pose.position.y); - ASSERT_FLOAT_EQ(545.4,nmeah.rcvd_msg.pose.position.z); + // Reset the new message flag + void reset() { new_msg = false; } - msg.sentence = "$GPGGA,0,90.000,S,90.000,W,1,08,0.9,545.4,M,46.9,M,,*47"; - pub.publish(msg); + // Wait for message to arrive at the subscriber. return true if timed out + // without receiving any message, return false otherwise + bool wait_for_new_msg() { + int loops = static_cast(ceil(timeout_s / delay_s)); - // Give time to publish - ros::WallDuration(0.5).sleep(); + for (int i = 0; i < loops && new_msg == false; ++i) { + ros::WallDuration(delay_s).sleep(); + ros::spinOnce(); + } - ros::spinOnce(); + auto timed_out = !new_msg; + return timed_out; + } - ASSERT_FLOAT_EQ(-90207689.8924,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(-15489467.5247,nmeah.rcvd_msg.pose.position.y); - ASSERT_FLOAT_EQ(545.4,nmeah.rcvd_msg.pose.position.z); -} + // Send some initial messages to setup the node under test. wait for the first + // message received on the subscriber before continuing. return true if timed + // out without receiving any message, return false otherwise. + bool wait_for_connection() { + int loops = static_cast(ceil(timeout_s / delay_s)); + + nmea_msgs::Sentence msg; + reset(); + + // nmea2tfpose node requires 2 different initial gps readings before being + // able to output the correct transforms. Before the connection between + // nodes are established, the messages sent by the publisher are prone to + // get lost. 2 initial dummy gps sentences are sent alternatively until the + // node under test responds. + for (int i = 0; i < loops && new_msg == false; ++i) { + msg.sentence = i % 2 ? DUMMY_NMEA_SENTENCE_0 : DUMMY_NMEA_SENTENCE_1; + pub.publish(msg); + ros::WallDuration(delay_s).sleep(); + ros::spinOnce(); + } + + auto timed_out = !new_msg; + return timed_out; + } -TEST(Nmea2TfPose, rmcTest) -{ + geometry_msgs::PoseStamped rcvd_msg; // message received from subscriber + std::atomic new_msg{false}; // flag set when a new message is received ros::NodeHandle nh; - NmeaHelper nmeah; - nmea_msgs::Sentence msg; - ros::Subscriber sub = nh.subscribe("/test/gnss_pose", 1, &NmeaHelper::pose_callback, &nmeah); - ros::Publisher pub = nh.advertise("/test/nmea_sentence", 1); - - // Give time to set up pub/sub - ros::WallDuration(0.5).sleep(); - - // Send a dummy message, because nodes only respond after they can compute orientation, - // which requires having seen two different positions - msg.sentence = "$GPRMC,0,A,80.000,N,90.000,E,022.4,084.4,230394,003.1,W*6A"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); - - // Start sending messages which are actually checked - - msg.sentence = "$GPRMC,0,A,90.000,N,90.000,E,022.4,084.4,230394,003.1,W*6A"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); - - ros::spinOnce(); - - ASSERT_FLOAT_EQ(-81305263.475,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(5958827.35862,nmeah.rcvd_msg.pose.position.y); - - msg.sentence = "$GPRMC,0,A,90.000,N,90.000,W,022.4,084.4,230394,003.1,W*6A"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); - - ros::spinOnce(); - - ASSERT_FLOAT_EQ(-90207689.8924,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(7519179.29268,nmeah.rcvd_msg.pose.position.y); - - msg.sentence = "$GPRMC,0,A,90.000,S,90.000,E,022.4,084.4,230394,003.1,W*6A"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); - - ros::spinOnce(); - - ASSERT_FLOAT_EQ(-81305263.475,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(-13929115.5907,nmeah.rcvd_msg.pose.position.y); - - msg.sentence = "$GPRMC,0,A,90.000,S,90.000,W,022.4,084.4,230394,003.1,W*6A"; - pub.publish(msg); - - // Give time to publish - ros::WallDuration(0.5).sleep(); + ros::Subscriber sub; + ros::Publisher pub; + const float timeout_s{5}; // timeout in seconds + const float delay_s{0.1}; // delay between calling spinOnce in wait loop +}; - ros::spinOnce(); +TEST(Nmea2TfPose, ggaTest) { + NmeaHelper nmeah{}; + nmeah.init(); + + nmeah.test_case("$GPGGA,0,90.000,N,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47", + -81305263.475, 5958827.35862, 545.4); + nmeah.test_case("$GPGGA,0,90.000,N,90.000,W,1,08,0.9,545.4,M,46.9,M,,*47", + -90207689.8924, 7519179.29268, 545.4); + nmeah.test_case("$GPGGA,0,90.000,S,90.000,E,1,08,0.9,545.4,M,46.9,M,,*47", + -81305263.475, -13929115.5907, 545.4); + nmeah.test_case("$GPGGA,0,90.000,S,90.000,W,1,08,0.9,545.4,M,46.9,M,,*47", + -90207689.8924, -15489467.5247, 545.4); +} - ASSERT_FLOAT_EQ(-90207689.8924,nmeah.rcvd_msg.pose.position.x); - ASSERT_FLOAT_EQ(-15489467.5247,nmeah.rcvd_msg.pose.position.y); +TEST(Nmea2TfPose, rmcTest) { + NmeaHelper nmeah{}; + nmeah.init(); + + nmeah.test_case("$GPRMC,0,A,90.000,N,90.000,E,022.4,084.4,230394,003.1,W*6A", + -81305263.475, 5958827.35862); + nmeah.test_case("$GPRMC,0,A,90.000,N,90.000,W,022.4,084.4,230394,003.1,W*6A", + -90207689.8924, 7519179.29268); + nmeah.test_case("$GPRMC,0,A,90.000,S,90.000,E,022.4,084.4,230394,003.1,W*6A", + -81305263.475, -13929115.5907); + nmeah.test_case("$GPRMC,0,A,90.000,S,90.000,W,022.4,084.4,230394,003.1,W*6A", + -90207689.8924, -15489467.5247); } -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "nmea_test"); ros::NodeHandle nh; diff --git a/core_perception/lidar_imm_ukf_pda_track/CHANGELOG.rst b/core_perception/imm_ukf_pda_track/CHANGELOG.rst similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/CHANGELOG.rst rename to core_perception/imm_ukf_pda_track/CHANGELOG.rst diff --git a/core_perception/imm_ukf_pda_track/CMakeLists.txt b/core_perception/imm_ukf_pda_track/CMakeLists.txt new file mode 100644 index 00000000000..bf43c3bdb64 --- /dev/null +++ b/core_perception/imm_ukf_pda_track/CMakeLists.txt @@ -0,0 +1,80 @@ +cmake_minimum_required(VERSION 2.8.3) +project(imm_ukf_pda_track) + +find_package(autoware_build_flags REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + amathutils_lib + autoware_msgs + geometry_msgs + lanelet2_extension + pcl_ros + roscpp + roslint + tf + vector_map +) + + +set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") + +catkin_package( + CATKIN_DEPENDS + vector_map + amathutils_lib +) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") +roslint_cpp( + include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h + nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp + nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +#imm_ukf_pda +add_executable(imm_ukf_pda + nodes/imm_ukf_pda/imm_ukf_pda_main.cpp + nodes/imm_ukf_pda/imm_ukf_pda.cpp + nodes/imm_ukf_pda/ukf.cpp +) +target_link_libraries(imm_ukf_pda + ${catkin_LIBRARIES} +) +add_dependencies(imm_ukf_pda + ${catkin_EXPORTED_TARGETS} +) + +add_executable(imm_ukf_pda_lanelet2 + nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp + nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp + nodes/imm_ukf_pda/ukf.cpp +) +target_link_libraries(imm_ukf_pda_lanelet2 + ${catkin_LIBRARIES} +) +add_dependencies(imm_ukf_pda_lanelet2 + ${catkin_EXPORTED_TARGETS} +) + +install( + TARGETS + imm_ukf_pda + imm_ukf_pda_lanelet2 + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) + +if (CATKIN_ENABLE_TESTING) + roslint_add_test() +endif() diff --git a/core_perception/lidar_imm_ukf_pda_track/README.md b/core_perception/imm_ukf_pda_track/README.md similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/README.md rename to core_perception/imm_ukf_pda_track/README.md diff --git a/core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda/imm_ukf_pda.h b/core_perception/imm_ukf_pda_track/include/imm_ukf_pda/imm_ukf_pda.h similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda/imm_ukf_pda.h rename to core_perception/imm_ukf_pda_track/include/imm_ukf_pda/imm_ukf_pda.h diff --git a/core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda/ukf.h b/core_perception/imm_ukf_pda_track/include/imm_ukf_pda/ukf.h similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda/ukf.h rename to core_perception/imm_ukf_pda_track/include/imm_ukf_pda/ukf.h diff --git a/core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h b/core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h rename to core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h diff --git a/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track.launch b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track.launch new file mode 100644 index 00000000000..5d5fb6757ea --- /dev/null +++ b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track.launch @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch new file mode 100644 index 00000000000..8ce96fe2bb8 --- /dev/null +++ b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch new file mode 100644 index 00000000000..3c81281f4ed --- /dev/null +++ b/core_perception/imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp similarity index 99% rename from core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp rename to core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp index f43e58504b4..13555d712e7 100644 --- a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp +++ b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda.cpp @@ -25,7 +25,7 @@ ImmUkfPda::ImmUkfPda() has_subscribed_vectormap_(false), private_nh_("~") { - private_nh_.param("tracking_frame", tracking_frame_, "world"); + private_nh_.param("tracking_frame", tracking_frame_, "map"); private_nh_.param("life_time_threshold", life_time_threshold_, 8); private_nh_.param("gating_threshold", gating_threshold_, 9.22); private_nh_.param("gate_probability", gate_probability_, 0.99); @@ -54,8 +54,8 @@ ImmUkfPda::ImmUkfPda() void ImmUkfPda::run() { - pub_object_array_ = node_handle_.advertise("/detection/objects", 1); - sub_detected_array_ = node_handle_.subscribe("/detection/fusion_tools/objects", 1, &ImmUkfPda::callback, this); + pub_object_array_ = node_handle_.advertise("objects_out", 1); + sub_detected_array_ = node_handle_.subscribe("objects_in", 1, &ImmUkfPda::callback, this); if (use_vectormap_) { diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda_main.cpp b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda_main.cpp similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda_main.cpp rename to core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/imm_ukf_pda_main.cpp diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/ukf.cpp b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/ukf.cpp similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda/ukf.cpp rename to core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda/ukf.cpp diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp similarity index 98% rename from core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp rename to core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp index 217341abdec..084237acecf 100644 --- a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp +++ b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp @@ -44,7 +44,7 @@ geometry_msgs::Pose getTransformedPose(const geometry_msgs::Pose& in_pose, const ImmUkfPdaLanelet2::ImmUkfPdaLanelet2() : target_id_(0), is_tracker_initialized_(false), frame_count_(0), has_loaded_lanelet_map_(false), private_nh_("~") { - private_nh_.param("tracking_frame", tracking_frame_, "world"); + private_nh_.param("tracking_frame", tracking_frame_, "map"); private_nh_.param("life_time_threshold", param_.life_time_threshold_, 8); private_nh_.param("gating_threshold", param_.gating_threshold_, 9.22); private_nh_.param("gate_probability", param_.gate_probability_, 0.99); @@ -84,8 +84,8 @@ void ImmUkfPdaLanelet2::run() } } - pub_object_array_ = nh_.advertise("detection/objects", 1); - sub_detected_array_ = nh_.subscribe("detection/fusion_tools/objects", 1, &ImmUkfPdaLanelet2::callback, this); + pub_object_array_ = nh_.advertise("objects_out", 1); + sub_detected_array_ = nh_.subscribe("objects_in", 1, &ImmUkfPdaLanelet2::callback, this); } void ImmUkfPdaLanelet2::binMapCallback(const autoware_lanelet2_msgs::MapBin& msg) @@ -102,7 +102,7 @@ void ImmUkfPdaLanelet2::callback(const autoware_msgs::DetectedObjectArray& input bool success = updateNecessaryTransform(); if (!success) { - ROS_WARN("Could not find coordiante transformation"); + ROS_WARN_THROTTLE(2, "Could not find coordinate transformation"); return; } @@ -124,25 +124,23 @@ bool ImmUkfPdaLanelet2::updateNecessaryTransform() bool success = true; try { - tf_listener_.waitForTransform(input_header_.frame_id, tracking_frame_, ros::Time(0), ros::Duration(1.0)); tf_listener_.lookupTransform(tracking_frame_, input_header_.frame_id, ros::Time(0), tf_local2global_); } catch (tf::TransformException ex) { - ROS_ERROR("%s", ex.what()); + ROS_ERROR_THROTTLE(2, "%s", ex.what()); success = false; } if (use_map_info_ && has_loaded_lanelet_map_) { try { - tf_listener_.waitForTransform(map_frame_, tracking_frame_, ros::Time(0), ros::Duration(1.0)); tf_listener_.lookupTransform(tracking_frame_, map_frame_, ros::Time(0), tf_map2tracking_); tf_tracking2map_ = tf_map2tracking_.inverse(); } catch (tf::TransformException ex) { - ROS_ERROR("%s", ex.what()); + ROS_ERROR_THROTTLE(2, "%s", ex.what()); success = false; } } diff --git a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp similarity index 92% rename from core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp rename to core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp index a13fa30a0bd..9aa66a9d767 100644 --- a/core_perception/lidar_imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp +++ b/core_perception/imm_ukf_pda_track/nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp @@ -14,14 +14,11 @@ * limitations under the License. */ - - - #include int main(int argc, char** argv) { - ros::init(argc, argv, "imm_ukf_pda_tracker_lanelet2"); + ros::init(argc, argv, "imm_ukf_pda_tracker"); ImmUkfPdaLanelet2 app; app.run(); ros::spin(); diff --git a/core_perception/lidar_imm_ukf_pda_track/package.xml b/core_perception/imm_ukf_pda_track/package.xml similarity index 100% rename from core_perception/lidar_imm_ukf_pda_track/package.xml rename to core_perception/imm_ukf_pda_track/package.xml diff --git a/core_perception/lidar_apollo_cnn_seg_detect/CMakeLists.txt b/core_perception/lidar_apollo_cnn_seg_detect/CMakeLists.txt index 38d035c8f5b..ef70df96634 100755 --- a/core_perception/lidar_apollo_cnn_seg_detect/CMakeLists.txt +++ b/core_perception/lidar_apollo_cnn_seg_detect/CMakeLists.txt @@ -1,31 +1,22 @@ cmake_minimum_required(VERSION 2.8.3) project(lidar_apollo_cnn_seg_detect) +find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS - autoware_build_flags - roscpp - tf - tf_conversions - pcl_ros - sensor_msgs - geometry_msgs - autoware_msgs - ) + autoware_msgs + geometry_msgs + pcl_ros + roscpp + sensor_msgs + tf + tf_conversions +) find_package(CUDA) find_package(OpenCV REQUIRED) catkin_package( - INCLUDE_DIRS - include - CATKIN_DEPENDS - roscpp - tf - tf_conversions - pcl_ros - sensor_msgs - geometry_msgs - autoware_msgs + INCLUDE_DIRS include ) ###CAFFE @@ -33,48 +24,49 @@ set(CAFFE_PATH "$ENV{HOME}/caffe/distribute") AW_CHECK_CUDA() -if (USE_CUDA AND EXISTS "${CAFFE_PATH}") - include_directories(${CUDA_INCLUDE_DIRS}) +if(USE_CUDA AND EXISTS "${CAFFE_PATH}") + include_directories(${CUDA_INCLUDE_DIRS}) - IF ("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "^arm") - link_directories(/usr/lib/arm-linux-gnueabihf/tegra) - endif () + IF ("${CMAKE_SYSTEM_PROCESSOR}" MATCHES "^arm") + link_directories(/usr/lib/arm-linux-gnueabihf/tegra) + endif () - include_directories( - include - ${catkin_INCLUDE_DIRS} - ${OpenCV_INCLUDE_DIRS} - ${CAFFE_PATH}/include - ) + include_directories( + include + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} + ${CAFFE_PATH}/include + ) - add_executable(lidar_apollo_cnn_seg_detect - nodes/lidar_apollo_cnn_seg_detect_node.cpp - nodes/cnn_segmentation.cpp - nodes/cluster2d.cpp - nodes/feature_generator.cpp - ) - target_link_libraries(lidar_apollo_cnn_seg_detect - ${catkin_LIBRARIES} - ${OpenCV_LIBRARIES} - ${CUDA_LIBRARIES} - ${CUDA_CUBLAS_LIBRARIES} - ${CUDA_curand_LIBRARY} - ${CAFFE_PATH}/lib/libcaffe.so - glog - ) - add_dependencies(lidar_apollo_cnn_seg_detect - ${catkin_EXPORTED_TARGETS} - ) + add_executable(lidar_apollo_cnn_seg_detect + nodes/lidar_apollo_cnn_seg_detect_node.cpp + nodes/cnn_segmentation.cpp + nodes/cluster2d.cpp + nodes/feature_generator.cpp + ) + target_link_libraries(lidar_apollo_cnn_seg_detect + ${catkin_LIBRARIES} + ${OpenCV_LIBRARIES} + ${CUDA_LIBRARIES} + ${CUDA_CUBLAS_LIBRARIES} + ${CUDA_curand_LIBRARY} + ${CAFFE_PATH}/lib/libcaffe.so + glog + ) + add_dependencies(lidar_apollo_cnn_seg_detect + ${catkin_EXPORTED_TARGETS} + ) - install(TARGETS - lidar_apollo_cnn_seg_detect - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) -else () - message("'Caffe' is not installed. 'lidar_apollo_cnn_seg_detect' will not be built.") -endif () \ No newline at end of file + install(TARGETS + lidar_apollo_cnn_seg_detect + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE + ) +else() + message("'Caffe' is not installed. 'lidar_apollo_cnn_seg_detect' will not be built.") +endif() diff --git a/core_perception/lidar_apollo_cnn_seg_detect/README.md b/core_perception/lidar_apollo_cnn_seg_detect/README.md index d2a945c0638..8e5f8dc7bee 100644 --- a/core_perception/lidar_apollo_cnn_seg_detect/README.md +++ b/core_perception/lidar_apollo_cnn_seg_detect/README.md @@ -13,7 +13,7 @@ $ cd caffe ``` Follow instructions from [Installing Caffe from source](http://caffe.berkeleyvision.org/installation.html). -* **Use offical Make compilation procedure**. +* **Use offical Make compilation procedure**. * Do not use thirdparty CMake setup. Compile and create distributable: @@ -24,6 +24,17 @@ $ make distribute **Recompile Autoware to build the node.** +## The Pretrained model + +Use this link to download the pretrained model from Baidu: + +https://github.com/ApolloAuto/apollo/tree/v5.5.0/modules/perception/production/data/perception/lidar/models/cnnseg + +These two files are needed: + +* deploy.prototxt +* deploy.caffemodel + ## How to launch * From a sourced terminal: @@ -48,6 +59,11 @@ Computing Tab -> Detection/ lidar_detector -> `lidar_cnn_baidu_detect`. Configur |`score_threshold`|*Double*|Minimum score required as given by the network to include the result (0.-1.)|0.6| |`use_gpu`|*Bool*|Whether ot not to use a GPU device|`true`| |`gpu_device_id`|*Int*|GPU ID|`0`| +|`width`|*Int*|Width of the 2d cluster|`512`| +|`height`|*Int*|Height of the 2d cluster|`512`| +|`range`|*Int*|Range for the 2d cluster|`60`| +|`use_constant_feature`|*Bool*|Use constant model feature (8 features) |`false`| +|`normalize_lidar_intensity`|*Bool*|Normalize the received lidar intensity data|`false`| ## Outputs @@ -61,4 +77,4 @@ Computing Tab -> Detection/ lidar_detector -> `lidar_cnn_baidu_detect`. Configur * To display the results in Rviz `objects_visualizer` is required. (Launch file launches automatically this node). -* Pre trained models can be downloaded from the Apollo project repository. \ No newline at end of file +* Pre trained models can be downloaded from the Apollo project repository. diff --git a/core_perception/lidar_apollo_cnn_seg_detect/include/cnn_segmentation.h b/core_perception/lidar_apollo_cnn_seg_detect/include/cnn_segmentation.h index 475eb9a248d..c4cd062e37f 100755 --- a/core_perception/lidar_apollo_cnn_seg_detect/include/cnn_segmentation.h +++ b/core_perception/lidar_apollo_cnn_seg_detect/include/cnn_segmentation.h @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -35,8 +35,6 @@ #include "cluster2d.h" #include "feature_generator.h" -#define __APP_NAME__ "lidar_apollo_cnn_seg_detect" - struct CellStat { CellStat() : point_num(0), valid_point_num(0) @@ -61,6 +59,8 @@ class CNNSegmentation double range_, score_threshold_; int width_; int height_; + bool use_constant_feature_; + bool normalize_lidar_intensity_; std_msgs::Header message_header_; std::string topic_src_; diff --git a/core_perception/lidar_apollo_cnn_seg_detect/include/feature_generator.h b/core_perception/lidar_apollo_cnn_seg_detect/include/feature_generator.h index 74e73ac451a..0051f905628 100755 --- a/core_perception/lidar_apollo_cnn_seg_detect/include/feature_generator.h +++ b/core_perception/lidar_apollo_cnn_seg_detect/include/feature_generator.h @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -31,7 +31,7 @@ class FeatureGenerator FeatureGenerator(){} ~FeatureGenerator(){} - bool init(caffe::Blob* out_blob); + bool init(caffe::Blob* out_blob, bool use_constant_feature, bool normalize_lidar_intensity); void generate( const pcl::PointCloud::Ptr& pc_ptr); private: @@ -42,6 +42,8 @@ class FeatureGenerator float min_height_ = 0.0; float max_height_ = 0.0; + bool normalize_lidar_intensity_ = false; + // raw feature data float* max_height_data_ = nullptr; float* mean_height_data_ = nullptr; diff --git a/core_perception/lidar_apollo_cnn_seg_detect/launch/lidar_apollo_cnn_seg_detect.launch b/core_perception/lidar_apollo_cnn_seg_detect/launch/lidar_apollo_cnn_seg_detect.launch index d79f05387d6..3bc3578321e 100644 --- a/core_perception/lidar_apollo_cnn_seg_detect/launch/lidar_apollo_cnn_seg_detect.launch +++ b/core_perception/lidar_apollo_cnn_seg_detect/launch/lidar_apollo_cnn_seg_detect.launch @@ -6,6 +6,11 @@ + + + + + @@ -14,6 +19,11 @@ + + + + + ("points_src", topic_src_, "points_raw"); - ROS_INFO("[%s] points_src: %s", __APP_NAME__, topic_src_.c_str()); + ROS_INFO("points_src: %s", topic_src_.c_str()); private_node_handle.param("range", range_, 60.); - ROS_INFO("[%s] Pretrained Model File: %.2f", __APP_NAME__, range_); + ROS_INFO("range: %.2f", range_); private_node_handle.param("score_threshold", score_threshold_, 0.6); - ROS_INFO("[%s] score_threshold: %.2f", __APP_NAME__, score_threshold_); + ROS_INFO("score_threshold: %.2f", score_threshold_); private_node_handle.param("width", width_, 512); - ROS_INFO("[%s] width: %d", __APP_NAME__, width_); + ROS_INFO("width: %d", width_); private_node_handle.param("height", height_, 512); - ROS_INFO("[%s] height: %d", __APP_NAME__, height_); + ROS_INFO("height: %d", height_); + + private_node_handle.param("use_constant_feature", use_constant_feature_, false); + ROS_INFO("[%s] whether to use constant features: %d", __APP_NAME__, use_constant_feature_); + + private_node_handle.param("normalize_lidar_intensity", normalize_lidar_intensity_, false); + ROS_INFO("[%s] whether to normalize lidar intensity data: %d", __APP_NAME__, normalize_lidar_intensity_); private_node_handle.param("use_gpu", use_gpu_, false); - ROS_INFO("[%s] use_gpu: %d", __APP_NAME__, use_gpu_); + ROS_INFO("use_gpu: %d", use_gpu_); private_node_handle.param("gpu_device_id", gpu_device_id_, 0); - ROS_INFO("[%s] gpu_device_id: %d", __APP_NAME__, gpu_device_id_); + ROS_INFO("gpu_device_id: %d", gpu_device_id_); /// Instantiate Caffe net if (!use_gpu_) @@ -115,14 +121,14 @@ bool CNNSegmentation::init() cluster2d_.reset(new Cluster2D()); if (!cluster2d_->init(height_, width_, range_)) { - ROS_ERROR("[%s] Fail to Initialize cluster2d for CNNSegmentation", __APP_NAME__); + ROS_ERROR("Failed to Initialize cluster2d for CNNSegmentation"); return false; } feature_generator_.reset(new FeatureGenerator()); - if (!feature_generator_->init(feature_blob_.get())) + if (!feature_generator_->init(feature_blob_.get(), use_constant_feature_, normalize_lidar_intensity_)) { - ROS_ERROR("[%s] Fail to Initialize feature generator for CNNSegmentation", __APP_NAME__); + ROS_ERROR("Failed to Initialize feature generator for CNNSegmentation"); return false; } @@ -136,22 +142,14 @@ bool CNNSegmentation::segment(const pcl::PointCloud::Ptr &pc_ptr int num_pts = static_cast(pc_ptr->points.size()); if (num_pts == 0) { - ROS_INFO("[%s] Empty point cloud.", __APP_NAME__); + ROS_INFO("Empty point cloud."); return true; } feature_generator_->generate(pc_ptr); -// network forward process + // network forward process caffe_net_->Forward(); -#ifndef USE_CAFFE_GPU -// caffe::Caffe::set_mode(caffe::Caffe::CPU); -#else -// int gpu_id = 0; -// caffe::Caffe::SetDevice(gpu_id); -// caffe::Caffe::set_mode(caffe::Caffe::GPU); -// caffe::Caffe::DeviceQuery(); -#endif // clutser points and construct segments/objects float objectness_thresh = 0.5; @@ -185,19 +183,21 @@ void CNNSegmentation::test_run() autoware_msgs::DetectedObjectArray objects; init(); segment(in_pc_ptr, valid_idx, objects); - - } void CNNSegmentation::run() { - init(); + if(this->init()){ + ROS_INFO("Network init successfully!"); + }else{ + ROS_ERROR("Network init fail!!!"); + } points_sub_ = nh_.subscribe(topic_src_, 1, &CNNSegmentation::pointsCallback, this); points_pub_ = nh_.advertise("/detection/lidar_detector/points_cluster", 1); objects_pub_ = nh_.advertise("/detection/lidar_detector/objects", 1); - ROS_INFO("[%s] Ready. Waiting for data...", __APP_NAME__); + ROS_INFO("Ready. Waiting for data..."); } void CNNSegmentation::pointsCallback(const sensor_msgs::PointCloud2 &msg) diff --git a/core_perception/lidar_apollo_cnn_seg_detect/nodes/feature_generator.cpp b/core_perception/lidar_apollo_cnn_seg_detect/nodes/feature_generator.cpp index d6a782991a0..5c6663cb9eb 100755 --- a/core_perception/lidar_apollo_cnn_seg_detect/nodes/feature_generator.cpp +++ b/core_perception/lidar_apollo_cnn_seg_detect/nodes/feature_generator.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -16,7 +16,7 @@ #include "feature_generator.h" -bool FeatureGenerator::init(caffe::Blob* out_blob) +bool FeatureGenerator::init(caffe::Blob* out_blob, bool use_constant_feature, bool normalize_lidar_intensity) { out_blob_ = out_blob; @@ -29,8 +29,14 @@ bool FeatureGenerator::init(caffe::Blob* out_blob) CHECK_EQ(width_, height_) << "Current implementation version requires input_width == input_height."; + normalize_lidar_intensity_ = normalize_lidar_intensity; + // set output blob and log lookup table - out_blob_->Reshape(1, 8, height_, width_); + if(use_constant_feature){ + out_blob_->Reshape(1, 8, height_, width_); + }else{ + out_blob_->Reshape(1, 6, height_, width_); + } log_table_.resize(256); for (size_t i = 0; i < log_table_.size(); ++i) { @@ -40,37 +46,44 @@ bool FeatureGenerator::init(caffe::Blob* out_blob) float* out_blob_data = nullptr; out_blob_data = out_blob_->mutable_cpu_data(); + // the pretrained model inside apollo project don't use the constant feature like direction_data_ and distance_data_ int channel_index = 0; max_height_data_ = out_blob_data + out_blob_->offset(0, channel_index++); mean_height_data_ = out_blob_data + out_blob_->offset(0, channel_index++); count_data_ = out_blob_data + out_blob_->offset(0, channel_index++); - direction_data_ = out_blob_data + out_blob_->offset(0, channel_index++); + if(use_constant_feature){ + direction_data_ = out_blob_data + out_blob_->offset(0, channel_index++); + } top_intensity_data_ = out_blob_data + out_blob_->offset(0, channel_index++); mean_intensity_data_ = out_blob_data + out_blob_->offset(0, channel_index++); - distance_data_ = out_blob_data + out_blob_->offset(0, channel_index++); + if(use_constant_feature){ + distance_data_ = out_blob_data + out_blob_->offset(0, channel_index++); + } nonempty_data_ = out_blob_data + out_blob_->offset(0, channel_index++); CHECK_EQ(out_blob_->offset(0, channel_index), out_blob_->count()); - // compute direction and distance features - int siz = height_ * width_; - std::vector direction_data(siz); - std::vector distance_data(siz); - - for (int row = 0; row < height_; ++row) { - for (int col = 0; col < width_; ++col) { - int idx = row * width_ + col; - // * row <-> x, column <-> y - float center_x = Pixel2Pc(row, height_, range_); - float center_y = Pixel2Pc(col, width_, range_); - constexpr double K_CV_PI = 3.1415926535897932384626433832795; - direction_data[idx] = - static_cast(std::atan2(center_y, center_x) / (2.0 * K_CV_PI)); - distance_data[idx] = - static_cast(std::hypot(center_x, center_y) / 60.0 - 0.5); + if(use_constant_feature){ + // compute direction and distance features + int siz = height_ * width_; + std::vector direction_data(siz); + std::vector distance_data(siz); + + for (int row = 0; row < height_; ++row) { + for (int col = 0; col < width_; ++col) { + int idx = row * width_ + col; + // * row <-> x, column <-> y + float center_x = Pixel2Pc(row, height_, range_); + float center_y = Pixel2Pc(col, width_, range_); + constexpr double K_CV_PI = 3.1415926535897932384626433832795; + direction_data[idx] = + static_cast(std::atan2(center_y, center_x) / (2.0 * K_CV_PI)); + distance_data[idx] = + static_cast(std::hypot(center_x, center_y) / 60.0 - 0.5); + } } + caffe::caffe_copy(siz, direction_data.data(), direction_data_); + caffe::caffe_copy(siz, distance_data.data(), distance_data_); } - caffe::caffe_copy(siz, direction_data.data(), direction_data_); - caffe::caffe_copy(siz, distance_data.data(), distance_data_); return true; } @@ -123,7 +136,11 @@ void FeatureGenerator::generate( int idx = map_idx_[i]; float pz = points[i].z; - float pi = points[i].intensity / 255.0; + float pi = points[i].intensity; + if (normalize_lidar_intensity_) + { + pi = pi / 255.0; + } if (max_height_data_[idx] < pz) { max_height_data_[idx] = pz; top_intensity_data_[idx] = pi; diff --git a/core_perception/lidar_apollo_cnn_seg_detect/nodes/lidar_apollo_cnn_seg_detect_node.cpp b/core_perception/lidar_apollo_cnn_seg_detect/nodes/lidar_apollo_cnn_seg_detect_node.cpp index 9c79ef2e35e..8babc599039 100755 --- a/core_perception/lidar_apollo_cnn_seg_detect/nodes/lidar_apollo_cnn_seg_detect_node.cpp +++ b/core_perception/lidar_apollo_cnn_seg_detect/nodes/lidar_apollo_cnn_seg_detect_node.cpp @@ -20,6 +20,8 @@ int main(int argc, char** argv) { ros::init(argc, argv, "lidar_apollo_cnn_seg_detect"); + caffe::GlobalInit(&argc, &argv); + CNNSegmentation node; node.run(); ros::spin(); diff --git a/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp b/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp index af26fc0784b..ba019088373 100644 --- a/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp +++ b/core_perception/lidar_euclidean_cluster_detect/nodes/lidar_euclidean_cluster_detect/lidar_euclidean_cluster_detect.cpp @@ -216,41 +216,67 @@ void publishDetectedObjects(const autoware_msgs::CloudClusterArray &in_clusters) _pub_detected_objects.publish(detected_objects); } -void publishCloudClusters(const ros::Publisher *in_publisher, const autoware_msgs::CloudClusterArray &in_clusters, - const std::string &in_target_frame, const std_msgs::Header &in_header) +void publishCloudClusters(const ros::Publisher* in_publisher, const autoware_msgs::CloudClusterArray& in_clusters, + const std::string& in_target_frame, const std_msgs::Header& in_header) { if (in_target_frame != in_header.frame_id) { autoware_msgs::CloudClusterArray clusters_transformed; clusters_transformed.header = in_header; clusters_transformed.header.frame_id = in_target_frame; - for (auto i = in_clusters.clusters.begin(); i != in_clusters.clusters.end(); i++) + geometry_msgs::PointStamped new_point_stamped; + geometry_msgs::PointStamped new_point_stamped_tfed; + + for (const auto& cluster : in_clusters.clusters) { autoware_msgs::CloudCluster cluster_transformed; cluster_transformed.header = in_header; try { - _transform_listener->lookupTransform(in_target_frame, _velodyne_header.frame_id, ros::Time(), - *_transform); - pcl_ros::transformPointCloud(in_target_frame, *_transform, i->cloud, cluster_transformed.cloud); - _transform_listener->transformPoint(in_target_frame, ros::Time(), i->min_point, in_header.frame_id, + _transform_listener->lookupTransform(in_target_frame, _velodyne_header.frame_id, ros::Time(), *_transform); + pcl_ros::transformPointCloud(in_target_frame, *_transform, cluster.cloud, cluster_transformed.cloud); + _transform_listener->transformPoint(in_target_frame, ros::Time(), cluster.min_point, in_header.frame_id, cluster_transformed.min_point); - _transform_listener->transformPoint(in_target_frame, ros::Time(), i->max_point, in_header.frame_id, + _transform_listener->transformPoint(in_target_frame, ros::Time(), cluster.max_point, in_header.frame_id, cluster_transformed.max_point); - _transform_listener->transformPoint(in_target_frame, ros::Time(), i->avg_point, in_header.frame_id, + _transform_listener->transformPoint(in_target_frame, ros::Time(), cluster.avg_point, in_header.frame_id, cluster_transformed.avg_point); - _transform_listener->transformPoint(in_target_frame, ros::Time(), i->centroid_point, in_header.frame_id, + _transform_listener->transformPoint(in_target_frame, ros::Time(), cluster.centroid_point, in_header.frame_id, cluster_transformed.centroid_point); - cluster_transformed.dimensions = i->dimensions; - cluster_transformed.eigen_values = i->eigen_values; - cluster_transformed.eigen_vectors = i->eigen_vectors; + // Convex_hull + cluster_transformed.convex_hull.polygon.points.resize(cluster.convex_hull.polygon.points.size()); + cluster_transformed.convex_hull.header.frame_id = in_target_frame; + for (size_t i = 0; i < cluster.convex_hull.polygon.points.size(); i++) + { + geometry_msgs::Point32 new_point32; + new_point_stamped.header.frame_id = in_header.frame_id; + new_point_stamped.point.x = static_cast(cluster.convex_hull.polygon.points[i].x); + new_point_stamped.point.y = static_cast(cluster.convex_hull.polygon.points[i].y); + new_point_stamped.point.z = static_cast(cluster.convex_hull.polygon.points[i].z); + _transform_listener->transformPoint(in_target_frame, ros::Time(), new_point_stamped, in_header.frame_id, + new_point_stamped_tfed); + new_point32.x = static_cast(new_point_stamped_tfed.point.x); + new_point32.y = static_cast(new_point_stamped_tfed.point.y); + new_point32.z = static_cast(new_point_stamped_tfed.point.z); + cluster_transformed.convex_hull.polygon.points[i] = new_point32; + } + + // BoundingBox + geometry_msgs::PoseStamped bb_pose_stamped; + geometry_msgs::PoseStamped bb_pose_stamped_tfed; + bb_pose_stamped.header = in_header; + bb_pose_stamped.pose = cluster.bounding_box.pose; + _transform_listener->transformPose(in_target_frame, bb_pose_stamped, bb_pose_stamped_tfed); + cluster_transformed.bounding_box.pose = bb_pose_stamped_tfed.pose; + + cluster_transformed.dimensions = cluster.dimensions; + cluster_transformed.eigen_values = cluster.eigen_values; + cluster_transformed.eigen_vectors = cluster.eigen_vectors; - cluster_transformed.convex_hull = i->convex_hull; - cluster_transformed.bounding_box.pose.position = i->bounding_box.pose.position; - if(_pose_estimation) + if (_pose_estimation) { - cluster_transformed.bounding_box.pose.orientation = i->bounding_box.pose.orientation; + cluster_transformed.bounding_box.pose.orientation = cluster.bounding_box.pose.orientation; } else { @@ -258,14 +284,15 @@ void publishCloudClusters(const ros::Publisher *in_publisher, const autoware_msg } clusters_transformed.clusters.push_back(cluster_transformed); } - catch (tf::TransformException &ex) + catch (tf::TransformException& ex) { ROS_ERROR("publishCloudClusters: %s", ex.what()); } } in_publisher->publish(clusters_transformed); publishDetectedObjects(clusters_transformed); - } else + } + else { in_publisher->publish(in_clusters); publishDetectedObjects(in_clusters); @@ -439,7 +466,7 @@ std::vector clusterAndColor(const pcl::PointCloud::Pt // use indices on 3d cloud ///////////////////////////////// - //--- 3. Color clustered points + //--- 3. Color clustered points ///////////////////////////////// unsigned int k = 0; // pcl::PointCloud::Ptr final_cluster (new pcl::PointCloud); @@ -832,7 +859,7 @@ void differenceNormalsSegmentation(const pcl::PointCloud::Ptr in_ // Apply filter cond_removal.filter(*diffnormals_cloud_filtered); - pcl::copyPointCloud(*diffnormals_cloud, *out_cloud_ptr); + pcl::copyPointCloud(*diffnormals_cloud_filtered, *out_cloud_ptr); } void removePointsUpTo(const pcl::PointCloud::Ptr in_cloud_ptr, diff --git a/core_perception/lidar_fake_perception/CMakeLists.txt b/core_perception/lidar_fake_perception/CMakeLists.txt index f4013c9d629..700ed853adf 100644 --- a/core_perception/lidar_fake_perception/CMakeLists.txt +++ b/core_perception/lidar_fake_perception/CMakeLists.txt @@ -3,30 +3,24 @@ project(lidar_fake_perception) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") - find_package(autoware_build_flags REQUIRED) -find_package(autoware_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS + autoware_msgs + geometry_msgs + pcl_ros roscpp + sensor_msgs tf tf_conversions - pcl_ros - sensor_msgs - geometry_msgs - autoware_msgs ) catkin_package( INCLUDE_DIRS include CATKIN_DEPENDS - roscpp - tf - tf_conversions - pcl_ros - sensor_msgs - geometry_msgs - autoware_msgs + autoware_msgs + geometry_msgs + sensor_msgs ) include_directories( @@ -53,5 +47,6 @@ install(TARGETS ) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) diff --git a/core_perception/lidar_fake_perception/nodes/lidar_fake_perception.cpp b/core_perception/lidar_fake_perception/nodes/lidar_fake_perception.cpp index e72ba2938ad..457f5438a7b 100644 --- a/core_perception/lidar_fake_perception/nodes/lidar_fake_perception.cpp +++ b/core_perception/lidar_fake_perception/nodes/lidar_fake_perception.cpp @@ -232,8 +232,8 @@ void LidarFakePerception::publishFakes() if (fake_points_.size() != 0) // publish empty { - fake_points_.header.frame_id = pointcloud_frame_; fake_points_.header = pcl_conversions::toPCL(fake_object_.header); + fake_points_.header.frame_id = pointcloud_frame_; } if (publish_objects_) diff --git a/core_perception/lidar_imm_ukf_pda_track/CMakeLists.txt b/core_perception/lidar_imm_ukf_pda_track/CMakeLists.txt deleted file mode 100644 index e8a524b4c7b..00000000000 --- a/core_perception/lidar_imm_ukf_pda_track/CMakeLists.txt +++ /dev/null @@ -1,84 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(imm_ukf_pda_track) - -find_package(autoware_build_flags REQUIRED) - -find_package(autoware_msgs REQUIRED) -find_package(catkin REQUIRED COMPONENTS - roscpp - roslint - pcl_ros - geometry_msgs - tf - vector_map - lanelet2_extension - autoware_msgs - amathutils_lib - ) - - -set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") - -catkin_package( - CATKIN_DEPENDS - roscpp - pcl_ros - autoware_msgs - tf - vector_map - amathutils_lib - ) - -set(ROSLINT_CPP_OPTS "--filter=-build/c++14") -roslint_cpp( - include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h - nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp - nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp - ) - -include_directories( - ${catkin_INCLUDE_DIRS} - include) - - -#imm_ukf_pda -add_executable(imm_ukf_pda - nodes/imm_ukf_pda/imm_ukf_pda_main.cpp - nodes/imm_ukf_pda/imm_ukf_pda.cpp - nodes/imm_ukf_pda/ukf.cpp - ) -target_link_libraries(imm_ukf_pda - ${catkin_LIBRARIES} - ) -add_dependencies(imm_ukf_pda - ${catkin_EXPORTED_TARGETS} - ) - -add_executable(imm_ukf_pda_lanelet2 - nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_main_lanelet2.cpp - nodes/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.cpp - nodes/imm_ukf_pda/ukf.cpp - ) -target_link_libraries(imm_ukf_pda_lanelet2 - ${catkin_LIBRARIES} - ) -add_dependencies(imm_ukf_pda_lanelet2 - ${catkin_EXPORTED_TARGETS} - ) - - -install(TARGETS - imm_ukf_pda - imm_ukf_pda_lanelet2 - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) - -if (CATKIN_ENABLE_TESTING) - roslint_add_test() -endif() diff --git a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track.launch b/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track.launch deleted file mode 100644 index 6d759729291..00000000000 --- a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track.launch +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch b/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch deleted file mode 100644 index d7ebdafcd4e..00000000000 --- a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_lanelet2.launch +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch b/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch index c8889fc8aac..fb4f183d6a9 100644 --- a/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch +++ b/core_perception/lidar_imm_ukf_pda_track/launch/imm_ukf_pda_track_option.launch @@ -57,7 +57,7 @@ - + diff --git a/core_perception/lidar_kf_contour_track/CMakeLists.txt b/core_perception/lidar_kf_contour_track/CMakeLists.txt index b59d3180384..2a3318ab41f 100644 --- a/core_perception/lidar_kf_contour_track/CMakeLists.txt +++ b/core_perception/lidar_kf_contour_track/CMakeLists.txt @@ -10,8 +10,10 @@ find_package(catkin REQUIRED COMPONENTS tf jsk_recognition_msgs op_ros_helpers + op_planner cv_bridge autoware_msgs + pcl_conversions ) find_package(OpenCV REQUIRED) diff --git a/core_perception/lidar_kf_contour_track/package.xml b/core_perception/lidar_kf_contour_track/package.xml index a71d48b8bfe..6ee596d04f3 100644 --- a/core_perception/lidar_kf_contour_track/package.xml +++ b/core_perception/lidar_kf_contour_track/package.xml @@ -12,6 +12,8 @@ autoware_msgs cv_bridge geometry_msgs + op_planner + pcl_conversions jsk_recognition_msgs op_ros_helpers roscpp diff --git a/core_perception/lidar_localizer/CMakeLists.txt b/core_perception/lidar_localizer/CMakeLists.txt index 35fd12abee9..2c917a539f2 100644 --- a/core_perception/lidar_localizer/CMakeLists.txt +++ b/core_perception/lidar_localizer/CMakeLists.txt @@ -3,83 +3,76 @@ project(lidar_localizer) find_package(PCL REQUIRED) -IF (NOT (PCL_VERSION VERSION_LESS "1.7.2")) - SET(PCL_OPENMP_PACKAGES pcl_omp_registration) -ENDIF (NOT (PCL_VERSION VERSION_LESS "1.7.2")) +if(NOT (PCL_VERSION VERSION_LESS "1.7.2")) + SET(PCL_OPENMP_PACKAGES pcl_omp_registration) +endif() find_package(OpenMP) -if (OPENMP_FOUND) - set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") -endif () +if(OPENMP_FOUND) + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") +endif() find_package(CUDA) find_package(Eigen3 QUIET) find_package(autoware_build_flags REQUIRED) -find_package(autoware_msgs REQUIRED) -find_package(autoware_config_msgs REQUIRED) AW_CHECK_CUDA() -if (USE_CUDA) - add_definitions(-DCUDA_FOUND) - list(APPEND PCL_OPENMP_PACKAGES ndt_gpu) -endif () - -if (NOT EIGEN3_FOUND) - # Fallback to cmake_modules - find_package(cmake_modules REQUIRED) - find_package(Eigen REQUIRED) - set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) - set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only - # Possibly map additional variables to the EIGEN3_ prefix. -else () - set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) -endif () +if(USE_CUDA) + add_definitions(-DCUDA_FOUND) + list(APPEND PCL_OPENMP_PACKAGES ndt_gpu) +endif() + +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() find_package(catkin REQUIRED COMPONENTS - roscpp - std_msgs - nav_msgs - tf - pcl_ros - sensor_msgs - pcl_conversions - velodyne_pointcloud - velodyne_pcl - ndt_tku - ndt_cpu - autoware_health_checker - jsk_rviz_plugins - ${PCL_OPENMP_PACKAGES} - autoware_msgs - autoware_config_msgs - ) - -################################### -## catkin specific configuration ## -################################### -catkin_package( - CATKIN_DEPENDS - std_msgs - velodyne_pointcloud - velodyne_pcl - autoware_msgs - autoware_config_msgs - autoware_health_checker - ndt_tku - ndt_cpu - jsk_rviz_plugins - ${PCL_OPENMP_PACKAGES} - DEPENDS PCL + ${PCL_OPENMP_PACKAGES} + autoware_config_msgs + autoware_health_checker + autoware_msgs + jsk_rviz_plugins + nav_msgs + ndt_cpu + ndt_tku + pcl_conversions + pcl_ros + roscpp + sensor_msgs + std_msgs + tf + tf_conversions + velodyne_pointcloud ) -########### -## Build ## -########### +catkin_package( + CATKIN_DEPENDS + ${PCL_OPENMP_PACKAGES} + autoware_config_msgs + autoware_health_checker + autoware_msgs + jsk_rviz_plugins + ndt_cpu + ndt_tku + std_msgs + velodyne_pointcloud + DEPENDS PCL +) -include_directories(include ${catkin_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIRS}) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") @@ -91,17 +84,16 @@ add_executable(ndt_mapping nodes/ndt_mapping/ndt_mapping.cpp) target_link_libraries(ndt_mapping ${catkin_LIBRARIES}) add_dependencies(ndt_mapping ${catkin_EXPORTED_TARGETS}) -if (USE_CUDA) - target_include_directories(ndt_matching PRIVATE ${CUDA_INCLUDE_DIRS}) - target_include_directories(ndt_mapping PRIVATE ${CUDA_INCLUDE_DIRS}) -endif () - +if(USE_CUDA) + target_include_directories(ndt_matching PRIVATE ${CUDA_INCLUDE_DIRS}) + target_include_directories(ndt_mapping PRIVATE ${CUDA_INCLUDE_DIRS}) +endif() -if (NOT (PCL_VERSION VERSION_LESS "1.7.2")) - set_target_properties(ndt_matching PROPERTIES COMPILE_DEFINITIONS "USE_PCL_OPENMP") - set_target_properties(ndt_mapping PROPERTIES COMPILE_DEFINITIONS "USE_PCL_OPENMP") -endif (NOT (PCL_VERSION VERSION_LESS "1.7.2")) +if(NOT (PCL_VERSION VERSION_LESS "1.7.2")) + set_target_properties(ndt_matching PROPERTIES COMPILE_DEFINITIONS "USE_PCL_OPENMP") + set_target_properties(ndt_mapping PROPERTIES COMPILE_DEFINITIONS "USE_PCL_OPENMP") +endif() add_executable(approximate_ndt_mapping nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp) target_link_libraries(approximate_ndt_mapping ${catkin_LIBRARIES}) @@ -111,7 +103,6 @@ add_executable(queue_counter nodes/queue_counter/queue_counter.cpp) target_link_libraries(queue_counter ${catkin_LIBRARIES}) add_dependencies(queue_counter ${catkin_EXPORTED_TARGETS}) - add_executable(ndt_matching_tku nodes/ndt_matching_tku/ndt_matching_tku.cpp) target_link_libraries(ndt_matching_tku ${catkin_LIBRARIES}) add_dependencies(ndt_matching_tku ${catkin_EXPORTED_TARGETS}) @@ -125,16 +116,16 @@ target_link_libraries(mapping ${catkin_LIBRARIES}) add_dependencies(mapping ${catkin_EXPORTED_TARGETS}) add_library(ndt_matching_monitor_lib SHARED - nodes/ndt_matching_monitor/ndt_matching_monitor.h - nodes/ndt_matching_monitor/ndt_matching_monitor.cpp - ) + nodes/ndt_matching_monitor/ndt_matching_monitor.h + nodes/ndt_matching_monitor/ndt_matching_monitor.cpp +) target_include_directories(ndt_matching_monitor_lib PRIVATE - ${catkin_INCLUDE_DIRS} - ${PCL_INCLUDE_DIRS} - ) + ${catkin_INCLUDE_DIRS} + ${PCL_INCLUDE_DIRS} +) add_dependencies(ndt_matching_monitor_lib - ${catkin_EXPORTED_TARGETS} - ) + ${catkin_EXPORTED_TARGETS} +) target_link_libraries(ndt_matching_monitor_lib ${catkin_LIBRARIES}) add_executable(ndt_matching_monitor nodes/ndt_matching_monitor/ndt_matching_monitor_node.cpp) @@ -144,26 +135,28 @@ add_executable(icp_matching nodes/icp_matching/icp_matching.cpp) target_link_libraries(icp_matching ${catkin_LIBRARIES}) add_dependencies(icp_matching ${catkin_EXPORTED_TARGETS}) -install(TARGETS - ndt_matching - ndt_mapping - approximate_ndt_mapping - ndt_mapping_tku - mapping - ndt_matching_monitor_lib - ndt_matching_monitor - icp_matching - queue_counter - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) +install( + TARGETS + approximate_ndt_mapping + icp_matching + mapping + ndt_mapping + ndt_mapping_tku + ndt_matching + ndt_matching_monitor + ndt_matching_monitor_lib + queue_counter + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) -if (CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) add_rostest_gtest(test_launch_ndt_matching @@ -174,4 +167,4 @@ if (CATKIN_ENABLE_TESTING) target_link_libraries(test_launch_ndt_matching ${catkin_LIBRARIES} ) -endif () +endif() diff --git a/core_perception/lidar_localizer/launch/ndt_matching.launch b/core_perception/lidar_localizer/launch/ndt_matching.launch index 6d0fd94b8ac..824742349ae 100644 --- a/core_perception/lidar_localizer/launch/ndt_matching.launch +++ b/core_perception/lidar_localizer/launch/ndt_matching.launch @@ -10,11 +10,11 @@ - + + - @@ -28,8 +28,8 @@ + - diff --git a/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp b/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp index 84de089cfcd..39dce174120 100644 --- a/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp +++ b/core_perception/lidar_localizer/nodes/approximate_ndt_mapping/approximate_ndt_mapping.cpp @@ -121,7 +121,8 @@ static double max_scan_range = 200.0; static double min_add_scan_shift = 1.0; static double max_submap_size = 100.0; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static float _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static std::vector _tf_baselink2primarylidar; static Eigen::Matrix4f tf_btol, tf_ltob; static bool isMapUpdate = true; @@ -893,37 +894,24 @@ int main(int argc, char** argv) std::cout << "use_odom: " << _use_odom << std::endl; std::cout << "imu_topic: " << _imu_topic << std::endl; - if (nh.getParam("tf_x", _tf_x) == false) + if (!nh.getParam("tf_baselink2primarylidar", _tf_baselink2primarylidar)) { - std::cout << "tf_x is not set." << std::endl; + std::cout << "baselink to primary lidar transform is not set." << std::endl; return 1; } - if (nh.getParam("tf_y", _tf_y) == false) - { - std::cout << "tf_y is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_z", _tf_z) == false) - { - std::cout << "tf_z is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_roll", _tf_roll) == false) - { - std::cout << "tf_roll is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_pitch", _tf_pitch) == false) - { - std::cout << "tf_pitch is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_yaw", _tf_yaw) == false) - { - std::cout << "tf_yaw is not set." << std::endl; + + // translation x, y, z, yaw, pitch, and roll + if (_tf_baselink2primarylidar.size() != 6) { + std::cout << "baselink to primary lidar transform is not valid." << std::endl; return 1; } + _tf_x = _tf_baselink2primarylidar[0]; + _tf_y = _tf_baselink2primarylidar[1]; + _tf_z = _tf_baselink2primarylidar[2]; + _tf_yaw = _tf_baselink2primarylidar[3]; + _tf_pitch = _tf_baselink2primarylidar[4]; + _tf_roll = _tf_baselink2primarylidar[5]; std::cout << "(tf_x,tf_y,tf_z,tf_roll,tf_pitch,tf_yaw): (" << _tf_x << ", " << _tf_y << ", " << _tf_z << ", " << _tf_roll << ", " << _tf_pitch << ", " << _tf_yaw << ")" << std::endl; diff --git a/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp b/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp index 9f597afe598..9e395f50652 100644 --- a/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp +++ b/core_perception/lidar_localizer/nodes/icp_matching/icp_matching.cpp @@ -148,7 +148,8 @@ static autoware_msgs::ICPStat icp_stat_msg; static double predict_pose_error = 0.0; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static float _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static std::vector _tf_baselink2primarylidar; static Eigen::Matrix4f tf_btol, tf_ltob; static std::string _localizer = "velodyne"; @@ -566,7 +567,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) std::cout << "Sequence: " << input->header.seq << std::endl; std::cout << "Timestamp: " << input->header.stamp << std::endl; std::cout << "Frame ID: " << input->header.frame_id << std::endl; - // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; + // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; std::cout << "Number of Filtered Scan Points: " << scan_points_num << " points." << std::endl; std::cout << "ICP has converged: " << icp.hasConverged() << std::endl; std::cout << "Fitness Score: " << fitness_score << std::endl; @@ -651,37 +652,25 @@ int main(int argc, char** argv) return 1; } - if (nh.getParam("tf_x", _tf_x) == false) + if (!nh.getParam("tf_baselink2primarylidar", _tf_baselink2primarylidar)) { - std::cout << "tf_x is not set." << std::endl; + std::cout << "baselink to primary lidar transform is not set." << std::endl; return 1; } - if (nh.getParam("tf_y", _tf_y) == false) - { - std::cout << "tf_y is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_z", _tf_z) == false) - { - std::cout << "tf_z is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_roll", _tf_roll) == false) - { - std::cout << "tf_roll is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_pitch", _tf_pitch) == false) - { - std::cout << "tf_pitch is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_yaw", _tf_yaw) == false) - { - std::cout << "tf_yaw is not set." << std::endl; + + // translation x, y, z, yaw, pitch, and roll + if (_tf_baselink2primarylidar.size() != 6) { + std::cout << "baselink to primary lidar transform is not valid." << std::endl; return 1; } + _tf_x = _tf_baselink2primarylidar[0]; + _tf_y = _tf_baselink2primarylidar[1]; + _tf_z = _tf_baselink2primarylidar[2]; + _tf_yaw = _tf_baselink2primarylidar[3]; + _tf_pitch = _tf_baselink2primarylidar[4]; + _tf_roll = _tf_baselink2primarylidar[5]; + std::cout << "-----------------------------------------------------------------" << std::endl; std::cout << "Log file: " << filename << std::endl; std::cout << "use_gnss: " << _use_gnss << std::endl; diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp index 8d94572fcd9..497354a42ac 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping/ndt_mapping.cpp @@ -38,6 +38,8 @@ #include #include +#include +#include #include #include @@ -140,7 +142,6 @@ static double min_scan_range = 5.0; static double max_scan_range = 200.0; static double min_add_scan_shift = 1.0; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; static Eigen::Matrix4f tf_btol, tf_ltob; static bool _use_imu = false; @@ -368,12 +369,17 @@ static double calcDiffForRadian(const double lhs_rad, const double rhs_rad) } static void odom_callback(const nav_msgs::Odometry::ConstPtr& input) { - // std::cout << __func__ << std::endl; - odom = *input; odom_calc(input->header.stamp); } +static void vehicle_twist_callback(const geometry_msgs::TwistStampedConstPtr& msg) +{ + odom.header = msg->header; + odom.twist.twist = msg->twist; + odom_calc(odom.header.stamp); +} + static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) { double input_roll, input_pitch, input_yaw; @@ -971,40 +977,79 @@ int main(int argc, char** argv) std::cout << "imu_topic: " << _imu_topic << std::endl; std::cout << "incremental_voxel_update: " << _incremental_voxel_update << std::endl; - if (nh.getParam("tf_x", _tf_x) == false) + std::string lidar_frame; + nh.param("localizer", lidar_frame, std::string("lidar")); + tf::TransformListener tf_listener; + tf::StampedTransform tf_baselink2primarylidar; + bool received_tf = true; + + // 1. Try getting base_link -> lidar TF from TF tree + try { - std::cout << "tf_x is not set." << std::endl; - return 1; + tf_listener.waitForTransform("base_link", lidar_frame, ros::Time(), ros::Duration(1.0)); + tf_listener.lookupTransform("base_link", lidar_frame, ros::Time(), tf_baselink2primarylidar); } - if (nh.getParam("tf_y", _tf_y) == false) + catch (tf::TransformException& ex) { - std::cout << "tf_y is not set." << std::endl; - return 1; + ROS_WARN("Query base_link to primary lidar frame through TF tree failed: %s", ex.what()); + received_tf = false; } - if (nh.getParam("tf_z", _tf_z) == false) + + // 2. Try getting base_link -> lidar TF from tf_baselink2primarylidar param + if (!received_tf) { - std::cout << "tf_z is not set." << std::endl; - return 1; + std::vector bl2pl_vec; + if (nh.getParam("tf_baselink2primarylidar", bl2pl_vec) && bl2pl_vec.size() == 6) + { + tf::Vector3 trans(bl2pl_vec[0], bl2pl_vec[1], bl2pl_vec[2]); + tf::Quaternion quat; + quat.setRPY(bl2pl_vec[5], bl2pl_vec[4], bl2pl_vec[3]); + tf_baselink2primarylidar.setOrigin(trans); + tf_baselink2primarylidar.setRotation(quat); + + received_tf = true; + } + else + { + ROS_WARN("Query base_link to primary lidar frame through tf_baselink2primarylidar param failed"); + } } - if (nh.getParam("tf_roll", _tf_roll) == false) + + // 3. Try getting base_link -> lidar TF from tf_* params + if (!received_tf) { - std::cout << "tf_roll is not set." << std::endl; - return 1; + float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw; + if (nh.getParam("tf_x", tf_x) && + nh.getParam("tf_y", tf_y) && + nh.getParam("tf_z", tf_z) && + nh.getParam("tf_roll", tf_roll) && + nh.getParam("tf_pitch", tf_pitch) && + nh.getParam("tf_yaw", tf_yaw)) + { + tf::Vector3 trans(tf_x, tf_y, tf_z); + tf::Quaternion quat; + quat.setRPY(tf_roll, tf_pitch, tf_yaw); + tf_baselink2primarylidar.setOrigin(trans); + tf_baselink2primarylidar.setRotation(quat); + + received_tf = true; + } + else + { + ROS_WARN("Query base_link to primary lidar frame through tf_* params failed"); + } } - if (nh.getParam("tf_pitch", _tf_pitch) == false) + + if (received_tf) { - std::cout << "tf_pitch is not set." << std::endl; - return 1; + ROS_INFO("base_link to primary lidar transform queried successfully"); } - if (nh.getParam("tf_yaw", _tf_yaw) == false) + else { - std::cout << "tf_yaw is not set." << std::endl; + ROS_ERROR("Failed to query base_link to primary lidar transform"); return 1; } - std::cout << "(tf_x,tf_y,tf_z,tf_roll,tf_pitch,tf_yaw): (" << _tf_x << ", " << _tf_y << ", " << _tf_z << ", " - << _tf_roll << ", " << _tf_pitch << ", " << _tf_yaw << ")" << std::endl; - #ifndef CUDA_FOUND if (_method_type == MethodType::PCL_ANH_GPU) { @@ -1024,13 +1069,6 @@ int main(int argc, char** argv) } #endif - Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation - Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation - Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); - Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ()); - tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix(); - tf_ltob = tf_btol.inverse(); - map.header.frame_id = "map"; ndt_map_pub = nh.advertise("/ndt_map", 1000); @@ -1039,8 +1077,9 @@ int main(int argc, char** argv) ros::Subscriber param_sub = nh.subscribe("config/ndt_mapping", 10, param_callback); ros::Subscriber output_sub = nh.subscribe("config/ndt_mapping_output", 10, output_callback); ros::Subscriber points_sub = nh.subscribe("points_raw", 100000, points_callback); - ros::Subscriber odom_sub = nh.subscribe("/vehicle/odom", 100000, odom_callback); + ros::Subscriber odom_sub = nh.subscribe("vehicle/odom", 100000, odom_callback); ros::Subscriber imu_sub = nh.subscribe(_imu_topic, 100000, imu_callback); + ros::Subscriber twist_sub = nh.subscribe("vehicle/twist", 100000, vehicle_twist_callback); ros::spin(); diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp index 95ca8a39740..347f3fc32bd 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/mapping.cpp @@ -20,6 +20,7 @@ #include #include +pcl::PointCloud map; tf::TransformListener *tf_listener; ros::Publisher velodyne_pub; @@ -93,11 +94,11 @@ void points_callback(const pcl::PointCloud::ConstPtr &msg) for (int i = 0; i < (int)pcl_out.points.size(); i++) { - // fprintf(fp_points,"%.3f %.3f %.3f %.1f\n", pcl_out.points[i].y, pcl_out.points[i].x, + // fprintf(fp_points,"%.3f %.3f %.3f %.1f\n", pcl_out.points[i].y, pcl_out.points[i].x, // pcl_out.points[i].z, pcl_out.points[i].intensity); ofs << pcl_out.points[i].x << "," << pcl_out.points[i].y << "," << pcl_out.points[i].z << "," << pcl_out.points[i].intensity << std::endl; - // ofs << pcl_out.points[i].x << " " << pcl_out.points[i].y << " " << pcl_out.points[i].z << " " << + // ofs << pcl_out.points[i].x << " " << pcl_out.points[i].y << " " << pcl_out.points[i].z << " " << // pcl_out.points[i].intensity << std::endl; } // fclose(fp_points); diff --git a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp index 3f28f3c9ff8..16fa2a804d7 100644 --- a/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_mapping_tku/ndt_mapping_tku.cpp @@ -68,7 +68,8 @@ int g_use_gnss; int g_map_update = 1; double g_ini_x, g_ini_y, g_ini_z, g_ini_roll, g_ini_pitch, g_ini_yaw; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static float _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static std::vector _tf_baselink2primarylidar; static Eigen::Matrix4f tf_btol, tf_ltob; // tf between base_link and localizer static tf::Quaternion q_local_to_global; static Eigen::Matrix4f tf_local_to_global; @@ -483,37 +484,25 @@ int main(int argc, char *argv[]) private_nh.getParam("init_pitch", g_ini_pitch); private_nh.getParam("init_yaw", g_ini_yaw); - if (!nh.getParam("tf_x", _tf_x)) + if (!nh.getParam("tf_baselink2primarylidar", _tf_baselink2primarylidar)) { - std::cout << "tf_x is not set." << std::endl; + std::cout << "baselink to primary lidar transform is not set." << std::endl; return 1; } - if (!nh.getParam("tf_y", _tf_y)) - { - std::cout << "tf_y is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_z", _tf_z)) - { - std::cout << "tf_z is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_roll", _tf_roll)) - { - std::cout << "tf_roll is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_pitch", _tf_pitch)) - { - std::cout << "tf_pitch is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_yaw", _tf_yaw)) - { - std::cout << "tf_yaw is not set." << std::endl; + + // translation x, y, z, yaw, pitch, and roll + if (_tf_baselink2primarylidar.size() != 6) { + std::cout << "baselink to primary lidar transform is not valid." << std::endl; return 1; } + _tf_x = _tf_baselink2primarylidar[0]; + _tf_y = _tf_baselink2primarylidar[1]; + _tf_z = _tf_baselink2primarylidar[2]; + _tf_yaw = _tf_baselink2primarylidar[3]; + _tf_pitch = _tf_baselink2primarylidar[4]; + _tf_roll = _tf_baselink2primarylidar[5]; + Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); @@ -574,4 +563,4 @@ int main(int argc, char *argv[]) save_nd_map((char *)"/tmp/ndmap"); return 1; -} +} \ No newline at end of file diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 5c055f9cc4d..40ab46777cc 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -30,10 +30,10 @@ #include -#include #include #include #include +#include #include #include #include @@ -43,10 +43,10 @@ #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -62,9 +62,6 @@ #include #endif -#include -#include - #include #include @@ -108,8 +105,7 @@ static double offset_odom_x, offset_odom_y, offset_odom_z, offset_odom_roll, off static double offset_imu_odom_x, offset_imu_odom_y, offset_imu_odom_z, offset_imu_odom_roll, offset_imu_odom_pitch, offset_imu_odom_yaw; -// Can't load if typed "pcl::PointCloud map, add;" -static pcl::PointCloud map, add; +static pcl::PointCloud map; // If the map is loaded, map_loaded will be 1. static int map_loaded = 0; @@ -147,12 +143,6 @@ static geometry_msgs::PoseStamped predict_pose_imu_odom_msg; static ros::Publisher ndt_pose_pub; static geometry_msgs::PoseStamped ndt_pose_msg; -// current_pose is published by vel_pose_mux -/* -static ros::Publisher current_pose_pub; -static geometry_msgs::PoseStamped current_pose_msg; - */ - static ros::Publisher localizer_pose_pub; static geometry_msgs::PoseStamped localizer_pose_msg; @@ -177,7 +167,6 @@ static double current_velocity = 0.0, previous_velocity = 0.0, previous_previous static double current_velocity_x = 0.0, previous_velocity_x = 0.0; static double current_velocity_y = 0.0, previous_velocity_y = 0.0; static double current_velocity_z = 0.0, previous_velocity_z = 0.0; -// static double current_velocity_yaw = 0.0, previous_velocity_yaw = 0.0; static double current_velocity_smooth = 0.0; static double current_velocity_imu_x = 0.0; @@ -188,7 +177,6 @@ static double current_accel = 0.0, previous_accel = 0.0; // [m/s^2] static double current_accel_x = 0.0; static double current_accel_y = 0.0; static double current_accel_z = 0.0; -// static double current_accel_yaw = 0.0; static double angular_velocity = 0.0; @@ -209,10 +197,9 @@ static autoware_msgs::NDTStat ndt_stat_msg; static double predict_pose_error = 0.0; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +// hold transfrom from baselink to primary lidar static Eigen::Matrix4f tf_btol; -static std::string _localizer = "velodyne"; static std::string _offset = "linear"; // linear, zero, quadratic static ros::Publisher ndt_reliability_pub; @@ -224,6 +211,8 @@ static bool _use_imu = false; static bool _use_odom = false; static bool _imu_upside_down = false; static bool _output_log_data = false; +static std::string _output_tf_frame_id = "base_link"; +static std::string _map_frame = "map"; static std::string _imu_topic = "/imu_raw"; @@ -233,11 +222,7 @@ static std::string filename; static sensor_msgs::Imu imu; static nav_msgs::Odometry odom; -// static tf::TransformListener local_transform_listener; -static tf::StampedTransform local_transform; - -static std::string _base_frame = "base_link"; -static std::string _map_frame = "map"; +static tf2::Stamped local_transform; static unsigned int points_map_num = 0; @@ -245,23 +230,23 @@ pthread_mutex_t mutex; static pose convertPoseIntoRelativeCoordinate(const pose &target_pose, const pose &reference_pose) { - tf::Quaternion target_q; + tf2::Quaternion target_q; target_q.setRPY(target_pose.roll, target_pose.pitch, target_pose.yaw); - tf::Vector3 target_v(target_pose.x, target_pose.y, target_pose.z); - tf::Transform target_tf(target_q, target_v); + tf2::Vector3 target_v(target_pose.x, target_pose.y, target_pose.z); + tf2::Transform target_tf(target_q, target_v); - tf::Quaternion reference_q; + tf2::Quaternion reference_q; reference_q.setRPY(reference_pose.roll, reference_pose.pitch, reference_pose.yaw); - tf::Vector3 reference_v(reference_pose.x, reference_pose.y, reference_pose.z); - tf::Transform reference_tf(reference_q, reference_v); + tf2::Vector3 reference_v(reference_pose.x, reference_pose.y, reference_pose.z); + tf2::Transform reference_tf(reference_q, reference_v); - tf::Transform trans_target_tf = reference_tf.inverse() * target_tf; + tf2::Transform trans_target_tf = reference_tf.inverse() * target_tf; pose trans_target_pose; trans_target_pose.x = trans_target_tf.getOrigin().getX(); trans_target_pose.y = trans_target_tf.getOrigin().getY(); trans_target_pose.z = trans_target_tf.getOrigin().getZ(); - tf::Matrix3x3 tmp_m(trans_target_tf.getRotation()); + tf2::Matrix3x3 tmp_m(trans_target_tf.getRotation()); tmp_m.getRPY(trans_target_pose.roll, trans_target_pose.pitch, trans_target_pose.yaw); return trans_target_pose; @@ -315,7 +300,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setStepSize(ndt_res); + omp_ndt.setStepSize(step_size); #endif } @@ -333,7 +318,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setTransformationEpsilon(ndt_res); + omp_ndt.setTransformationEpsilon(trans_eps); #endif } @@ -351,7 +336,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setMaximumIterations(ndt_res); + omp_ndt.setMaximumIterations(max_iter); #endif } @@ -366,15 +351,15 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu if (_use_local_transform == true) { - tf::Vector3 v(input->x, input->y, input->z); - tf::Quaternion q; + tf2::Vector3 v(input->x, input->y, input->z); + tf2::Quaternion q; q.setRPY(input->roll, input->pitch, input->yaw); - tf::Transform transform(q, v); + tf2::Transform transform(q, v); initial_pose.x = (local_transform.inverse() * transform).getOrigin().getX(); initial_pose.y = (local_transform.inverse() * transform).getOrigin().getY(); initial_pose.z = (local_transform.inverse() * transform).getOrigin().getZ(); - tf::Matrix3x3 m(q); + tf2::Matrix3x3 m(q); m.getRPY(initial_pose.roll, initial_pose.pitch, initial_pose.yaw); std::cout << "initial_pose.x: " << initial_pose.x << std::endl; @@ -433,9 +418,7 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) if (points_map_num != input->width) { std::cout << "Update points_map." << std::endl; - _map_frame = input->header.frame_id; // Update map frame to be the frame of the map points topic - points_map_num = input->width; // Convert the data type(from sensor_msgs to pcl). @@ -443,19 +426,20 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) if (_use_local_transform == true) { - tf::TransformListener local_transform_listener; + tf2_ros::Buffer tf_buffer; + tf2_ros::TransformListener tf_listener(tf_buffer); + geometry_msgs::TransformStamped local_transform_msg; try { - ros::Time now = ros::Time(0); - local_transform_listener.waitForTransform(_map_frame, "/world", now, ros::Duration(10.0)); - local_transform_listener.lookupTransform(_map_frame, "world", now, local_transform); + local_transform_msg = tf_buffer.lookupTransform(_map_frame, "world", ros::Time::now(), ros::Duration(3.0)); } - catch (tf::TransformException& ex) + catch (tf2::TransformException& ex) { ROS_ERROR("%s", ex.what()); } - pcl_ros::transformPointCloud(map, map, local_transform.inverse()); + tf2::fromMsg(local_transform_msg, local_transform); + pcl::transformPointCloud(map, map, tf2::transformToEigen(local_transform_msg).matrix().inverse().cast()); } pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); @@ -544,9 +528,9 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) static void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input) { - tf::Quaternion gnss_q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z, + tf2::Quaternion gnss_q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z, input->pose.orientation.w); - tf::Matrix3x3 gnss_m(gnss_q); + tf2::Matrix3x3 gnss_m(gnss_q); pose current_gnss_pose; current_gnss_pose.x = input->pose.position.x; @@ -611,22 +595,21 @@ static void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input) static void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& input) { - tf::TransformListener listener; - tf::StampedTransform transform; + tf2_ros::Buffer tf_buffer; + tf2_ros::TransformListener tf_listener(tf_buffer); + geometry_msgs::TransformStamped tf_msg; try { - ros::Time now = ros::Time(0); - listener.waitForTransform(_map_frame, input->header.frame_id, now, ros::Duration(10.0)); - listener.lookupTransform(_map_frame, input->header.frame_id, now, transform); + tf_msg = tf_buffer.lookupTransform(_map_frame, input->header.frame_id, ros::Time::now(), ros::Duration(3.0)); } - catch (tf::TransformException& ex) + catch (tf2::TransformException& ex) { ROS_ERROR("%s", ex.what()); } - tf::Quaternion q(input->pose.pose.orientation.x, input->pose.pose.orientation.y, input->pose.pose.orientation.z, + tf2::Quaternion q(input->pose.pose.orientation.x, input->pose.pose.orientation.y, input->pose.pose.orientation.z, input->pose.pose.orientation.w); - tf::Matrix3x3 m(q); + tf2::Matrix3x3 m(q); if (_use_local_transform == true) { @@ -636,9 +619,9 @@ static void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped: } else { - current_pose.x = input->pose.pose.position.x + transform.getOrigin().x(); - current_pose.y = input->pose.pose.position.y + transform.getOrigin().y(); - current_pose.z = input->pose.pose.position.z + transform.getOrigin().z(); + current_pose.x = input->pose.pose.position.x + tf_msg.transform.translation.x; + current_pose.y = input->pose.pose.position.y + tf_msg.transform.translation.y; + current_pose.z = input->pose.pose.position.z + tf_msg.transform.translation.z; } m.getRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); @@ -845,19 +828,24 @@ static double calcDiffForRadian(const double lhs_rad, const double rhs_rad) static void odom_callback(const nav_msgs::Odometry::ConstPtr& input) { - // std::cout << __func__ << std::endl; - odom = *input; odom_calc(input->header.stamp); } +static void vehicle_twist_callback(const geometry_msgs::TwistStampedConstPtr& msg) +{ + odom.header = msg->header; + odom.twist.twist = msg->twist; + odom_calc(odom.header.stamp); +} + static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) { double input_roll, input_pitch, input_yaw; - tf::Quaternion input_orientation; - tf::quaternionMsgToTF(input->orientation, input_orientation); - tf::Matrix3x3(input_orientation).getRPY(input_roll, input_pitch, input_yaw); + tf2::Quaternion input_orientation; + tf2::fromMsg(input->orientation, input_orientation); + tf2::Matrix3x3(input_orientation).getRPY(input_roll, input_pitch, input_yaw); input->angular_velocity.x *= -1; input->angular_velocity.y *= -1; @@ -871,7 +859,9 @@ static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) input_pitch *= -1; input_yaw *= -1; - input->orientation = tf::createQuaternionMsgFromRollPitchYaw(input_roll, input_pitch, input_yaw); + tf2::Quaternion tf_quat; + tf_quat.setRPY(input_roll, input_pitch, input_yaw); + input->orientation = tf2::toMsg(tf_quat); } static void imu_callback(const sensor_msgs::Imu::Ptr& input) @@ -886,9 +876,9 @@ static void imu_callback(const sensor_msgs::Imu::Ptr& input) const double diff_time = (current_time - previous_time).toSec(); double imu_roll, imu_pitch, imu_yaw; - tf::Quaternion imu_orientation; - tf::quaternionMsgToTF(input->orientation, imu_orientation); - tf::Matrix3x3(imu_orientation).getRPY(imu_roll, imu_pitch, imu_yaw); + tf2::Quaternion imu_orientation; + tf2::fromMsg(input->orientation, imu_orientation); + tf2::Matrix3x3(imu_orientation).getRPY(imu_roll, imu_pitch, imu_yaw); imu_roll = wrapToPmPi(imu_roll); imu_pitch = wrapToPmPi(imu_pitch); @@ -934,9 +924,9 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) { matching_start = std::chrono::system_clock::now(); - static tf::TransformBroadcaster br; - tf::Transform transform; - tf::Quaternion predict_q, ndt_q, current_q, localizer_q; + static tf2_ros::TransformBroadcaster br; + tf2::Transform transform; + tf2::Quaternion predict_q, ndt_q, current_q, localizer_q; pcl::PointXYZ p; pcl::PointCloud filtered_scan; @@ -1109,7 +1099,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) pthread_mutex_unlock(&mutex); - tf::Matrix3x3 mat_l; // localizer + tf2::Matrix3x3 mat_l; // localizer mat_l.setValue(static_cast(t(0, 0)), static_cast(t(0, 1)), static_cast(t(0, 2)), static_cast(t(1, 0)), static_cast(t(1, 1)), static_cast(t(1, 2)), static_cast(t(2, 0)), static_cast(t(2, 1)), static_cast(t(2, 2))); @@ -1120,7 +1110,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) localizer_pose.z = t(2, 3); mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1); - tf::Matrix3x3 mat_b; // base_link + tf2::Matrix3x3 mat_b; // base_link mat_b.setValue(static_cast(t2(0, 0)), static_cast(t2(0, 1)), static_cast(t2(0, 2)), static_cast(t2(1, 0)), static_cast(t2(1, 1)), static_cast(t2(1, 2)), static_cast(t2(2, 0)), static_cast(t2(2, 1)), static_cast(t2(2, 2))); @@ -1227,8 +1217,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_q.setRPY(predict_pose.roll, predict_pose.pitch, predict_pose.yaw); if (_use_local_transform == true) { - tf::Vector3 v(predict_pose.x, predict_pose.y, predict_pose.z); - tf::Transform transform(predict_q, v); + tf2::Vector3 v(predict_pose.x, predict_pose.y, predict_pose.z); + tf2::Transform transform(predict_q, v); predict_pose_msg.header.frame_id = _map_frame; predict_pose_msg.header.stamp = current_scan_time; predict_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1252,7 +1242,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_msg.pose.orientation.w = predict_q.w(); } - tf::Quaternion predict_q_imu; + tf2::Quaternion predict_q_imu; predict_q_imu.setRPY(predict_pose_imu.roll, predict_pose_imu.pitch, predict_pose_imu.yaw); predict_pose_imu_msg.header.frame_id = _map_frame; predict_pose_imu_msg.header.stamp = input->header.stamp; @@ -1265,7 +1255,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_imu_msg.pose.orientation.w = predict_q_imu.w(); predict_pose_imu_pub.publish(predict_pose_imu_msg); - tf::Quaternion predict_q_odom; + tf2::Quaternion predict_q_odom; predict_q_odom.setRPY(predict_pose_odom.roll, predict_pose_odom.pitch, predict_pose_odom.yaw); predict_pose_odom_msg.header.frame_id = _map_frame; predict_pose_odom_msg.header.stamp = input->header.stamp; @@ -1278,7 +1268,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_odom_msg.pose.orientation.w = predict_q_odom.w(); predict_pose_odom_pub.publish(predict_pose_odom_msg); - tf::Quaternion predict_q_imu_odom; + tf2::Quaternion predict_q_imu_odom; predict_q_imu_odom.setRPY(predict_pose_imu_odom.roll, predict_pose_imu_odom.pitch, predict_pose_imu_odom.yaw); predict_pose_imu_odom_msg.header.frame_id = _map_frame; predict_pose_imu_odom_msg.header.stamp = input->header.stamp; @@ -1294,8 +1284,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) ndt_q.setRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw); if (_use_local_transform == true) { - tf::Vector3 v(ndt_pose.x, ndt_pose.y, ndt_pose.z); - tf::Transform transform(ndt_q, v); + tf2::Vector3 v(ndt_pose.x, ndt_pose.y, ndt_pose.z); + tf2::Transform transform(ndt_q, v); ndt_pose_msg.header.frame_id = _map_frame; ndt_pose_msg.header.stamp = current_scan_time; ndt_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1322,7 +1312,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) current_q.setRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); // current_pose is published by vel_pose_mux /* - current_pose_msg.header.frame_id = _map_frame; + current_pose_msg.header.frame_id = "map"; current_pose_msg.header.stamp = current_scan_time; current_pose_msg.pose.position.x = current_pose.x; current_pose_msg.pose.position.y = current_pose.y; @@ -1336,8 +1326,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) localizer_q.setRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw); if (_use_local_transform == true) { - tf::Vector3 v(localizer_pose.x, localizer_pose.y, localizer_pose.z); - tf::Transform transform(localizer_q, v); + tf2::Vector3 v(localizer_pose.x, localizer_pose.y, localizer_pose.z); + tf2::Transform transform(localizer_q, v); localizer_pose_msg.header.frame_id = _map_frame; localizer_pose_msg.header.stamp = current_scan_time; localizer_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1364,24 +1354,19 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_pub.publish(predict_pose_msg); health_checker_ptr_->CHECK_RATE("topic_rate_ndt_pose_slow", 8, 5, 1, "topic ndt_pose publish rate slow."); ndt_pose_pub.publish(ndt_pose_msg); - // current_pose is published by vel_pose_mux - // current_pose_pub.publish(current_pose_msg); localizer_pose_pub.publish(localizer_pose_msg); - // Send TF _base_frame to _map_frame - transform.setOrigin(tf::Vector3(current_pose.x, current_pose.y, current_pose.z)); + // Send TF "base_link" to "map" + transform.setOrigin(tf2::Vector3(current_pose.x, current_pose.y, current_pose.z)); transform.setRotation(current_q); - // br.sendTransform(tf::StampedTransform(transform, current_scan_time, _map_frame, _base_frame)); - /* Removed to allow CARMA localization node to publish this TF if (_use_local_transform == true) { - br.sendTransform(tf::StampedTransform(local_transform * transform, current_scan_time, _map_frame, _base_frame)); - } - else - { - br.sendTransform(tf::StampedTransform(transform, current_scan_time, _map_frame, _base_frame)); + transform = local_transform * transform; } - */ + tf2::Stamped tf(transform, current_scan_time, _map_frame); + geometry_msgs::TransformStamped tf_msg = tf2::toMsg(tf); + tf_msg.child_frame_id = _output_tf_frame_id; + br.sendTransform(tf_msg); matching_end = std::chrono::system_clock::now(); exe_time = std::chrono::duration_cast(matching_end - matching_start).count() / 1000.0; @@ -1391,7 +1376,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) // Set values for /estimate_twist estimate_twist_msg.header.stamp = current_scan_time; - estimate_twist_msg.header.frame_id = _base_frame; + estimate_twist_msg.header.frame_id = "base_link"; estimate_twist_msg.twist.linear.x = current_velocity; estimate_twist_msg.twist.linear.y = 0.0; estimate_twist_msg.twist.linear.z = 0.0; @@ -1451,7 +1436,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) std::cout << "Sequence: " << input->header.seq << std::endl; std::cout << "Timestamp: " << input->header.stamp << std::endl; std::cout << "Frame ID: " << input->header.frame_id << std::endl; - // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; + // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; std::cout << "Number of Filtered Scan Points: " << scan_points_num << " points." << std::endl; std::cout << "NDT has converged: " << has_converged << std::endl; std::cout << "Fitness Score: " << fitness_score << std::endl; @@ -1566,45 +1551,84 @@ int main(int argc, char** argv) private_nh.getParam("imu_upside_down", _imu_upside_down); private_nh.getParam("imu_topic", _imu_topic); private_nh.param("gnss_reinit_fitness", _gnss_reinit_fitness, 500.0); - private_nh.getParam("base_frame", _base_frame); + private_nh.getParam("output_tf_frame_id", _output_tf_frame_id); + std::string lidar_frame; + nh.param("localizer", lidar_frame, std::string("lidar")); + tf2_ros::Buffer tf_buffer; + tf2_ros::TransformListener tf_listener(tf_buffer); + geometry_msgs::TransformStamped tf_baselink2primarylidar; + bool received_tf = true; - if (nh.getParam("localizer", _localizer) == false) - { - std::cout << "localizer is not set." << std::endl; - return 1; - } - if (nh.getParam("tf_x", _tf_x) == false) + // 1. Try getting base_link -> lidar TF from TF tree + try { - std::cout << "tf_x is not set." << std::endl; - return 1; + tf_baselink2primarylidar = + tf_buffer.lookupTransform("base_link", lidar_frame, ros::Time().now(), ros::Duration(3.0)); } - if (nh.getParam("tf_y", _tf_y) == false) + catch (tf2::TransformException& ex) { - std::cout << "tf_y is not set." << std::endl; - return 1; + ROS_WARN("Query base_link to primary lidar frame through TF tree failed: %s", ex.what()); + received_tf = false; } - if (nh.getParam("tf_z", _tf_z) == false) + + // 2. Try getting base_link -> lidar TF from tf_baselink2primarylidar param + if (!received_tf) { - std::cout << "tf_z is not set." << std::endl; - return 1; + std::vector bl2pl_vec; + if (nh.getParam("tf_baselink2primarylidar", bl2pl_vec) && bl2pl_vec.size() == 6) + { + tf2::Vector3 tf_trans(bl2pl_vec[0], bl2pl_vec[1], bl2pl_vec[2]); + tf2::Quaternion tf_quat; + tf_quat.setRPY(bl2pl_vec[5], bl2pl_vec[4], bl2pl_vec[3]); + tf_baselink2primarylidar.transform.translation = tf2::toMsg(tf_trans); + tf_baselink2primarylidar.transform.rotation = tf2::toMsg(tf_quat); + + received_tf = true; + } + else + { + ROS_WARN("Query base_link to primary lidar frame through tf_baselink2primarylidar param failed"); + } } - if (nh.getParam("tf_roll", _tf_roll) == false) + + // 3. Try getting base_link -> lidar TF from tf_* params + if (!received_tf) { - std::cout << "tf_roll is not set." << std::endl; - return 1; + float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw; + if (nh.getParam("tf_x", tf_x) && + nh.getParam("tf_y", tf_y) && + nh.getParam("tf_z", tf_z) && + nh.getParam("tf_roll", tf_roll) && + nh.getParam("tf_pitch", tf_pitch) && + nh.getParam("tf_yaw", tf_yaw)) + { + tf2::Vector3 tf_trans(tf_x, tf_y, tf_z); + tf2::Quaternion tf_quat; + tf_quat.setRPY(tf_roll, tf_pitch, tf_yaw); + tf_baselink2primarylidar.transform.translation = tf2::toMsg(tf_trans); + tf_baselink2primarylidar.transform.rotation = tf2::toMsg(tf_quat); + + received_tf = true; + } + else + { + ROS_WARN("Query base_link to primary lidar frame through tf_* params failed"); + } } - if (nh.getParam("tf_pitch", _tf_pitch) == false) + + if (received_tf) { - std::cout << "tf_pitch is not set." << std::endl; - return 1; + ROS_INFO("base_link to primary lidar transform queried successfully"); } - if (nh.getParam("tf_yaw", _tf_yaw) == false) + else { - std::cout << "tf_yaw is not set." << std::endl; + ROS_ERROR("Failed to query base_link to primary lidar transform"); return 1; } + tf_btol = tf2::transformToEigen(tf_baselink2primarylidar).matrix().cast(); + std::cout << "-----------------------------------------------------------------" << std::endl; std::cout << "Log file: " << filename << std::endl; std::cout << "method_type: " << static_cast(_method_type) << std::endl; @@ -1617,11 +1641,9 @@ int main(int argc, char** argv) std::cout << "use_imu: " << _use_imu << std::endl; std::cout << "imu_upside_down: " << _imu_upside_down << std::endl; std::cout << "imu_topic: " << _imu_topic << std::endl; - std::cout << "localizer: " << _localizer << std::endl; + std::cout << "localizer: " << lidar_frame << std::endl; std::cout << "gnss_reinit_fitness: " << _gnss_reinit_fitness << std::endl; - std::cout << "base_frame: " << _base_frame << std::endl; - std::cout << "(tf_x,tf_y,tf_z,tf_roll,tf_pitch,tf_yaw): (" << _tf_x << ", " << _tf_y << ", " << _tf_z << ", " - << _tf_roll << ", " << _tf_pitch << ", " << _tf_yaw << ")" << std::endl; + std::cout << "tf_baselink2primarylidar: \n" << tf_btol << std::endl; std::cout << "-----------------------------------------------------------------" << std::endl; #ifndef CUDA_FOUND @@ -1643,12 +1665,6 @@ int main(int argc, char** argv) } #endif - Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation - Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation - Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); - Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ()); - tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix(); - // Updated in initialpose_callback or gnss_callback initial_pose.x = 0.0; initial_pose.y = 0.0; @@ -1675,22 +1691,18 @@ int main(int argc, char** argv) // Subscribers ros::Subscriber param_sub = nh.subscribe("config/ndt", 10, param_callback); - ros::Subscriber gnss_sub = nh.subscribe("gnss_pose", _queue_size, gnss_callback); + ros::Subscriber gnss_sub = nh.subscribe("gnss_pose", 10, gnss_callback); // ros::Subscriber map_sub = nh.subscribe("points_map", 1, map_callback); - ros::Subscriber initialpose_sub = nh.subscribe("initialpose", _queue_size, initialpose_callback); + ros::Subscriber initialpose_sub = nh.subscribe("initialpose", 10, initialpose_callback); ros::Subscriber points_sub = nh.subscribe("filtered_points", _queue_size, points_callback); - ros::Subscriber odom_sub = nh.subscribe("/vehicle/odom", _queue_size, odom_callback); - ros::Subscriber imu_sub = nh.subscribe(_imu_topic.c_str(), _queue_size, imu_callback); + ros::Subscriber odom_sub = nh.subscribe("vehicle/odom", _queue_size * 10, odom_callback); + ros::Subscriber imu_sub = nh.subscribe(_imu_topic.c_str(), _queue_size * 10, imu_callback); + ros::Subscriber twist_sub = nh.subscribe("vehicle/twist", 10, vehicle_twist_callback); pthread_t thread; pthread_create(&thread, NULL, thread_func, NULL); - ros::Rate r(10); - while (nh.ok()) - { - ros::spinOnce(); - r.sleep(); - } + ros::spin(); return 0; } diff --git a/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor.h b/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor.h index 9faf7cf22df..b4031cdb793 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor.h +++ b/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor.h @@ -63,83 +63,83 @@ class ROSNDTMatchingMonitor { - enum ndt_status{ - NDT_NOT_INITIALIZED, - NDT_OK, - NDT_WARNING, - NDT_ERROR, - NDT_FATAL - }; - const std::vector ndt_status_names = {"NDT_NOT_INITIALIZED", "NDT_OK", "NDT_WARNING", "NDT_ERROR", "NDT_FATAL"}; - ros::Publisher initialpose_pub_; - ros::Publisher overlay_info_text_pub_; - ros::Publisher ndt_status_pub_; - ros::Time last_prediction_time_; - - double last_score_; - double current_score_; - double score_delta_threshold_; - double score_delta_; - int iteration_threshold_warning_; - int iteration_threshold_stop_; - double fatal_time_threshold_; - ndt_status ndt_status_; - - int iteration_count_; - bool gnss_pose_available_; - bool initialized_; - int min_stable_samples_; - unsigned int stable_samples_; - unsigned int prediction_samples_; - std::string gnss_text_; - - jsk_rviz_plugins::OverlayText ndt_normal_text_; - jsk_rviz_plugins::OverlayText ndt_warn_text_; - jsk_rviz_plugins::OverlayText ndt_error_text_; - jsk_rviz_plugins::OverlayText ndt_fatal_text_; - jsk_rviz_plugins::OverlayText ndt_not_ready_text_; - - geometry_msgs::PoseWithCovarianceStamped initialpose_; - geometry_msgs::PoseWithCovarianceStamped prev_initialpose_; - geometry_msgs::PoseWithCovarianceStamped gnss_pose_; - geometry_msgs::PoseWithCovarianceStamped prev_gnss_pose_; - std::deque< geometry_msgs::PoseWithCovarianceStamped > ndt_pose_array_; - - /*! - * Callback for NDT statistics - * @param input message published by ndt - */ - void ndt_stat_callback(const autoware_msgs::NDTStat::ConstPtr& input); - - /*! - * Callback for transformation result from NDT - * @param input message published by ndt containing the pose of the ego-vehicle - */ - void ndt_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& input); - - /*! - * If available GNSS will be used to try to reset - * @param input message containing the pose as given by the GNSS device - */ - void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input); - - /*! - * Calculates the possible next location based on the current and previous positions - * @param prev_pose previous position - * @param current_pose current position - * @return the estimated position - */ - geometry_msgs::PoseWithCovarianceStamped predict_next_pose(geometry_msgs::PoseWithCovarianceStamped prev_pose, - geometry_msgs::PoseWithCovarianceStamped current_pose); - - /*! - * In case of Fatal status a halt will be generated, the only way to recover would be using a reinitialization - * @param input the pose as given by rviz - */ - void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& input); + enum ndt_status{ + NDT_NOT_INITIALIZED, + NDT_OK, + NDT_WARNING, + NDT_ERROR, + NDT_FATAL + }; + const std::vector ndt_status_names = {"NDT_NOT_INITIALIZED", "NDT_OK", "NDT_WARNING", "NDT_ERROR", "NDT_FATAL"}; + ros::Publisher initialpose_pub_; + ros::Publisher overlay_info_text_pub_; + ros::Publisher ndt_status_pub_; + ros::Time last_prediction_time_; + + double last_score_; + double current_score_; + double score_delta_threshold_; + double score_delta_; + int iteration_threshold_warning_; + int iteration_threshold_stop_; + double fatal_time_threshold_; + ndt_status ndt_status_; + + int iteration_count_; + bool gnss_pose_available_; + bool initialized_; + int min_stable_samples_; + unsigned int stable_samples_; + unsigned int prediction_samples_; + std::string gnss_text_; + + jsk_rviz_plugins::OverlayText ndt_normal_text_; + jsk_rviz_plugins::OverlayText ndt_warn_text_; + jsk_rviz_plugins::OverlayText ndt_error_text_; + jsk_rviz_plugins::OverlayText ndt_fatal_text_; + jsk_rviz_plugins::OverlayText ndt_not_ready_text_; + + geometry_msgs::PoseWithCovarianceStamped initialpose_; + geometry_msgs::PoseWithCovarianceStamped prev_initialpose_; + geometry_msgs::PoseWithCovarianceStamped gnss_pose_; + geometry_msgs::PoseWithCovarianceStamped prev_gnss_pose_; + std::deque< geometry_msgs::PoseWithCovarianceStamped > ndt_pose_array_; + + /*! + * Callback for NDT statistics + * @param input message published by ndt + */ + void ndt_stat_callback(const autoware_msgs::NDTStat::ConstPtr& input); + + /*! + * Callback for transformation result from NDT + * @param input message published by ndt containing the pose of the ego-vehicle + */ + void ndt_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& input); + + /*! + * If available GNSS will be used to try to reset + * @param input message containing the pose as given by the GNSS device + */ + void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input); + + /*! + * Calculates the possible next location based on the current and previous positions + * @param prev_pose previous position + * @param current_pose current position + * @return the estimated position + */ + geometry_msgs::PoseWithCovarianceStamped predict_next_pose(geometry_msgs::PoseWithCovarianceStamped prev_pose, + geometry_msgs::PoseWithCovarianceStamped current_pose); + + /*! + * In case of Fatal status a halt will be generated, the only way to recover would be using a reinitialization + * @param input the pose as given by rviz + */ + void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& input); public: - void Run(); - ROSNDTMatchingMonitor(); + void Run(); + ROSNDTMatchingMonitor(); }; #endif //PROJECT_NDT_MATCHING_MONITOR_H diff --git a/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor_node.cpp b/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor_node.cpp index 70e3056774e..50da5453dae 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor_node.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching_monitor/ndt_matching_monitor_node.cpp @@ -24,11 +24,11 @@ int main(int argc, char **argv) { - ros::init(argc, argv, __APP_NAME__); + ros::init(argc, argv, __APP_NAME__); - ROSNDTMatchingMonitor app; + ROSNDTMatchingMonitor app; - app.Run(); + app.Run(); - return 0; + return 0; } diff --git a/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp b/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp index 240d9c44b35..7063b7ee266 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching_tku/ndt_matching_tku.cpp @@ -67,7 +67,8 @@ int g_use_gnss; int g_map_update = 1; double g_ini_x, g_ini_y, g_ini_z, g_ini_roll, g_ini_pitch, g_ini_yaw; -static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static float _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static std::vector _tf_baselink2primarylidar; static Eigen::Matrix4f tf_btol, tf_ltob; // tf between base_link and localizer static tf::Quaternion q_local_to_global, q_global_to_local; static Eigen::Matrix4f tf_local_to_global, tf_global_to_local; @@ -457,37 +458,25 @@ int main(int argc, char *argv[]) private_nh.getParam("init_yaw", g_ini_yaw); private_nh.getParam("use_gnss", g_use_gnss); - if (!nh.getParam("tf_x", _tf_x)) + if (!nh.getParam("tf_baselink2primarylidar", _tf_baselink2primarylidar)) { - std::cout << "tf_x is not set." << std::endl; + std::cout << "baselink to primary lidar transform is not set." << std::endl; return 1; } - if (!nh.getParam("tf_y", _tf_y)) - { - std::cout << "tf_y is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_z", _tf_z)) - { - std::cout << "tf_z is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_roll", _tf_roll)) - { - std::cout << "tf_roll is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_pitch", _tf_pitch)) - { - std::cout << "tf_pitch is not set." << std::endl; - return 1; - } - if (!nh.getParam("tf_yaw", _tf_yaw)) - { - std::cout << "tf_yaw is not set." << std::endl; + + // translation x, y, z, yaw, pitch, and roll + if (_tf_baselink2primarylidar.size() != 6) { + std::cout << "baselink to primary lidar transform is not valid." << std::endl; return 1; } + _tf_x = _tf_baselink2primarylidar[0]; + _tf_y = _tf_baselink2primarylidar[1]; + _tf_z = _tf_baselink2primarylidar[2]; + _tf_yaw = _tf_baselink2primarylidar[3]; + _tf_pitch = _tf_baselink2primarylidar[4]; + _tf_roll = _tf_baselink2primarylidar[5]; + Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); diff --git a/core_perception/lidar_localizer/nodes/queue_counter/queue_counter.cpp b/core_perception/lidar_localizer/nodes/queue_counter/queue_counter.cpp index bbd027e1a4e..00a64c3f090 100644 --- a/core_perception/lidar_localizer/nodes/queue_counter/queue_counter.cpp +++ b/core_perception/lidar_localizer/nodes/queue_counter/queue_counter.cpp @@ -35,14 +35,14 @@ static int dequeue = 0; static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) { - enqueue++; + enqueue++; } static void ndt_map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) { - dequeue++; + dequeue++; - std::cout << "(Processed/Input): (" << dequeue << " / " << enqueue << ")" << std::endl; + std::cout << "(Processed/Input): (" << dequeue << " / " << enqueue << ")" << std::endl; } int main(int argc, char **argv) diff --git a/core_perception/lidar_localizer/package.xml b/core_perception/lidar_localizer/package.xml index c817153dac8..e8cdd3b4fc1 100644 --- a/core_perception/lidar_localizer/package.xml +++ b/core_perception/lidar_localizer/package.xml @@ -27,6 +27,7 @@ sensor_msgs std_msgs tf + tf_conversions velodyne_pointcloud velodyne_pcl diff --git a/core_perception/lidar_localizer/test/test_launch_ndt_matching.test b/core_perception/lidar_localizer/test/test_launch_ndt_matching.test index 2d78c0a2083..b224bed4f0e 100644 --- a/core_perception/lidar_localizer/test/test_launch_ndt_matching.test +++ b/core_perception/lidar_localizer/test/test_launch_ndt_matching.test @@ -1,10 +1,5 @@ - - - - - - + [1.2, 0.0, 2.0, 0.0, 0.0, 0.0] diff --git a/core_perception/lidar_point_pillars/CMakeLists.txt b/core_perception/lidar_point_pillars/CMakeLists.txt index b3158133286..36d83c9d9ac 100755 --- a/core_perception/lidar_point_pillars/CMakeLists.txt +++ b/core_perception/lidar_point_pillars/CMakeLists.txt @@ -24,12 +24,13 @@ option(TRT_AVAIL "TensorRT available" OFF) find_library(NVINFER NAMES nvinfer) find_library(NVPARSERS NAMES nvparsers) find_library(NVONNXPARSERS NAMES nvonnxparser) + if(NVINFER AND NVPARSERS AND NVONNXPARSERS) - message("TensorRT is available!") - message("NVINFER: ${NVINFER}") - message("NVPARSERS: ${NVPARSERS}") - message("NVONNXPARSERS: ${NVONNXPARSERS}") - set(TRT_AVAIL ON) + message("TensorRT is available!") + message("NVINFER: ${NVINFER}") + message("NVPARSERS: ${NVPARSERS}") + message("NVONNXPARSERS: ${NVONNXPARSERS}") + set(TRT_AVAIL ON) else() message("TensorRT is NOT Available") set(TRT_AVAIL OFF) @@ -39,107 +40,161 @@ endif() option(CUDNN_AVAIL "CUDNN available" OFF) # try to find the CUDNN module find_library(CUDNN_LIBRARY -NAMES libcudnn.so${__cudnn_ver_suffix} libcudnn${__cudnn_ver_suffix}.dylib ${__cudnn_lib_win_name} -PATHS $ENV{LD_LIBRARY_PATH} ${__libpath_cudart} ${CUDNN_ROOT_DIR} ${PC_CUDNN_LIBRARY_DIRS} ${CMAKE_INSTALL_PREFIX} -PATH_SUFFIXES lib lib64 bin -DOC "CUDNN library." ) + NAMES libcudnn.so${__cudnn_ver_suffix} libcudnn${__cudnn_ver_suffix}.dylib ${__cudnn_lib_win_name} + PATHS $ENV{LD_LIBRARY_PATH} ${__libpath_cudart} ${CUDNN_ROOT_DIR} ${PC_CUDNN_LIBRARY_DIRS} ${CMAKE_INSTALL_PREFIX} + PATH_SUFFIXES lib lib64 bin + DOC "CUDNN library." +) + if(CUDNN_LIBRARY) - message("CUDNN is available!") - message("CUDNN_LIBRARY: ${CUDNN_LIBRARY}") - set(CUDNN_AVAIL ON) + message("CUDNN is available!") + message("CUDNN_LIBRARY: ${CUDNN_LIBRARY}") + set(CUDNN_AVAIL ON) else() message("CUDNN is NOT Available") set(CUDNN_AVAIL OFF) endif() -if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) +# Check TVM utility, runtime libraries and TVM files +find_library(TVM_LIBRARY NAMES tvm_runtime) +set(TVM_AVAIL OFF) + +set(TVM_PFE_FOLDER ${CMAKE_CURRENT_SOURCE_DIR}/tvm_models/tvm_point_pillars_pfe/) +set(TVM_RPN_FOLDER ${CMAKE_CURRENT_SOURCE_DIR}/tvm_models/tvm_point_pillars_rpn/) + +if (EXISTS "${TVM_PFE_FOLDER}/deploy_graph.json" + AND EXISTS "${TVM_PFE_FOLDER}/deploy_param.params" + AND EXISTS "${TVM_PFE_FOLDER}/deploy_lib.so" + AND EXISTS "${TVM_PFE_FOLDER}/inference_engine_tvm_config.hpp" + AND EXISTS "${TVM_RPN_FOLDER}/deploy_graph.json" + AND EXISTS "${TVM_RPN_FOLDER}/deploy_param.params" + AND EXISTS "${TVM_RPN_FOLDER}/deploy_lib.so" + AND EXISTS "${TVM_RPN_FOLDER}/inference_engine_tvm_config.hpp") + set(TVM_AVAIL true) +endif() +if(CUDA_AVAIL AND ((TRT_AVAIL AND CUDNN_AVAIL) OR (TVM_AVAIL AND TVM_LIBRARY))) find_package(catkin REQUIRED COMPONENTS - roscpp - roslib - pcl_ros - autoware_msgs - ) + roscpp + roslib + pcl_ros + autoware_msgs + ) + + catkin_package( + CATKIN_DEPENDS + roslib + pcl_ros + autoware_msgs + ) set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") - catkin_package( - CATKIN_DEPENDS - roscpp - roslib - pcl_ros - autoware_msgs - ) + # Look for tvm_utility if this build is using TVM model + if(TVM_AVAIL) + find_package(catkin REQUIRED COMPONENTS + tvm_vendor + tvm_utility + ) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_EXTENSIONS OFF) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DTVM_IMPLEMENTATION") + include_directories(tvm_models ${tvm_vendor_INCLUDE_DIRS}/tvm_vendor) + endif() include_directories( - include - ${catkin_INCLUDE_DIRS} + include + ${catkin_INCLUDE_DIRS} ) + set(SOURCE_FILES - nodes/lidar_point_pillars_node.cpp - nodes/point_pillars_ros.cpp - ) + nodes/lidar_point_pillars_node.cpp + nodes/point_pillars_ros.cpp + ) add_executable(lidar_point_pillars - ${SOURCE_FILES}) + ${SOURCE_FILES} + ) add_dependencies(lidar_point_pillars - ${catkin_EXPORTED_TARGETS} - ) + ${catkin_EXPORTED_TARGETS} + ) cuda_add_library(gpu_point_pillars_lib - nodes/preprocess_points_cuda.cu - nodes/anchor_mask_cuda.cu - nodes/scatter_cuda.cu - nodes/postprocess_cuda.cu - nodes/nms_cuda.cu - ) + nodes/preprocess_points_cuda.cu + nodes/anchor_mask_cuda.cu + nodes/scatter_cuda.cu + nodes/postprocess_cuda.cu + nodes/nms_cuda.cu + ) target_link_libraries(gpu_point_pillars_lib - ${CUDA_LIBRARIES} + ${CUDA_LIBRARIES} ) - add_library(point_pillars_lib - nodes/point_pillars.cpp - nodes/preprocess_points.cpp - ) - - target_link_libraries(point_pillars_lib - ${NVINFER} - ${NVONNXPARSERS} - ${CUDA_LIBRARIES} - ${CUDA_CUBLAS_LIBRARIES} - ${CUDA_curand_LIBRARY} - ${CUDNN_LIBRARY} - gpu_point_pillars_lib - ) + if(TVM_AVAIL) + add_library(point_pillars_lib + nodes/point_pillars.cpp + nodes/preprocess_points.cpp + nodes/pfe_tvm_pipeline.cpp + nodes/rpn_tvm_pipeline.cpp + ) + + target_link_libraries(point_pillars_lib + ${TVM_LIBRARY} + ${CUDA_LIBRARIES} + ${CUDA_CUBLAS_LIBRARIES} + ${CUDA_curand_LIBRARY} + gpu_point_pillars_lib + ) + else() + add_library(point_pillars_lib + nodes/point_pillars.cpp + nodes/preprocess_points.cpp + ) + + target_link_libraries(point_pillars_lib + ${NVINFER} + ${NVONNXPARSERS} + ${CUDA_LIBRARIES} + ${CUDA_CUBLAS_LIBRARIES} + ${CUDA_curand_LIBRARY} + ${CUDNN_LIBRARY} + gpu_point_pillars_lib + ) + endif() target_link_libraries(lidar_point_pillars - ${catkin_LIBRARIES} - point_pillars_lib - ) - - - install(TARGETS - gpu_point_pillars_lib - point_pillars_lib - lidar_point_pillars - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ${catkin_LIBRARIES} + point_pillars_lib + ) + + install( + TARGETS + gpu_point_pillars_lib + point_pillars_lib + lidar_point_pillars + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE + ) + + install(DIRECTORY tvm_models/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/tvm_models + ) install(DIRECTORY include/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}/${PROJECT_NAME}/ - PATTERN ".svn" EXCLUDE - ) + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}/${PROJECT_NAME}/ + PATTERN ".svn" EXCLUDE + ) - if (CATKIN_ENABLE_TESTING) + if (CATKIN_ENABLE_TESTING AND EXISTS /proc/driver/nvidia/) find_package(rostest REQUIRED) catkin_add_gtest(test-point_pillars test/src/test_point_pillars.cpp) target_link_libraries(test-point_pillars ${catkin_LIBRARIES} point_pillars_lib) diff --git a/core_perception/lidar_point_pillars/README.md b/core_perception/lidar_point_pillars/README.md index 3cef61d109a..f610a62d595 100644 --- a/core_perception/lidar_point_pillars/README.md +++ b/core_perception/lidar_point_pillars/README.md @@ -2,46 +2,52 @@ Autoware package for Point Pillars. [Referenced paper](https://arxiv.org/abs/1812.05784). -## Requirements +This node can be compiled either using cuDNN and TensorRT or by using TVM, the default are cuDNN and TensorRT. -CUDA Toolkit v9.0 or v10.0 +## Requirements -CUDNN: Tested with v7.3.1 +- CUDA Toolkit v9.0 or v10.0 -TensorRT: Tested with 5.0.2 -> [How to install](https://docs.nvidia.com/deeplearning/sdk/tensorrt-install-guide/index.html#installing) +To compile the node using the cuDNN and TensorRT support the requirements are: -## How to setup +- cuDNN: Tested with v7.3.1 -1. Install CUDA from this [website](https://developer.nvidia.com/cuda-downloads) +- TensorRT: Tested with 5.0.2 -> [How to install](https://docs.nvidia.com/deeplearning/sdk/tensorrt-install-guide/index.html#installing) -2. Install CUDNN +To compile the node using TVM support the requirements are: -3. [Download](https://docs.nvidia.com/deeplearning/sdk/tensorrt-install-guide/index.html#downloading) the TensorRT local repo file that matches the Ubuntu version you are using. +- TVM runtime, TVM Python bindings and dlpack headers -4. Install TensorRT from the Debian local repo package. +- tvm_utility package -``` -$ sudo dpkg -i -nv-tensorrt-repo-ubuntu1x04-cudax.x-trt5.x.x.x-ga-yyyymmdd_1-1_amd64.deb -$ sudo apt-key add /var/nv-tensorrt-repo-cudax.x-trt5.x.x.x-ga-yyyymmdd/7fa2af80.pub +## How to setup -$ sudo apt-get update -$ sudo apt-get install tensorrt -``` +Setup the node using cuDNN and TensorRT support: -4. Download the pretrained file from [here](https://github.com/cirpue49/kitti_pretrained_pp). +1. Download the pretrained file from [here](https://github.com/k0suke-murakami/kitti_pretrained_point_pillars). ``` -$ git clone git@github.com:cirpue49/kitti_pretrained_point_pillars.git +$ git clone https://github.com/k0suke-murakami/kitti_pretrained_point_pillars.git ``` +Setup the node using TVM support: + +1. Clone the modelzoo repository for Autoware [here](https://github.com/autowarefoundation/modelzoo). + +2. Use the TVM-CLI to export point pillars models to TVM (Instruction on how to do it are present in the repository ```modelzoo/scripts/tvm_cli/README.md```), models are ```perception/lidar_obstacle_detection/point_pillars_pfe/onnx_fp32_kitti``` and ```perception/lidar_obstacle_detection/point_pillars_rpn/onnx_fp32_kitti``` +3. Copy the generated files into the ```tvm_models/tvm_point_pillars_pfe``` and ```tvm_models/tvm_point_pillars_rpn``` folders respectively for each model. With these files in place, the package will be built using TVM. + +4. Compile the node. ## How to launch -* Launch file: +* Launch file (cuDNN and TensorRT support): `roslaunch lidar_point_pillars lidar_point_pillars.launch pfe_onnx_file:=/PATH/TO/FILE.onnx rpn_onnx_file:=/PATH/TO/FILE.onnx input_topic:=/points_raw` +* Launch file (TVM support): +`roslaunch lidar_point_pillars lidar_point_pillars.launch` + * You can launch it through the runtime manager in Computing tab, as well. ## API @@ -65,8 +71,8 @@ void doInference(float* in_points_array, int in_num_points, std::vector o |`reproduce_result_mode`|*Bool*|Whether to enable reproducible result mode at the cost of the runtime. |`False`| |`score_threshold`|*Float*|Minimum score required to include the result [0,1]|0.5| |`nms_overlap_threshold`|*Float*|Minimum IOU required to have when applying NMS [0,1]|0.5| -|`pfe_onnx_file`|*String* |Path to the PFE onnx file|| -|`rpn_onnx_file`|*String* |Path to the RPN onnx file|| +|`pfe_onnx_file`|*String* |Path to the PFE onnx file, unused if TVM build is chosen || +|`rpn_onnx_file`|*String* |Path to the RPN onnx file, unused if TVM build is chosen|| ## Outputs @@ -79,4 +85,4 @@ void doInference(float* in_points_array, int in_num_points, std::vector o * To display the results in Rviz `objects_visualizer` is required. (Launch file launches automatically this node). -* Pretrained models are available [here](https://github.com/cirpue49/kitti_pretrained_pp), trained with the help of the KITTI dataset. For this reason, these are not suitable for commercial purposes. Derivative works are bound to the BY-NC-SA 3.0 License. (https://creativecommons.org/licenses/by-nc-sa/3.0/) +* Pretrained models are available [here](https://github.com/k0suke-murakami/kitti_pretrained_point_pillars), trained with the help of the KITTI dataset. For this reason, these are not suitable for commercial purposes. Derivative works are bound to the BY-NC-SA 3.0 License. (https://creativecommons.org/licenses/by-nc-sa/3.0/) diff --git a/core_perception/lidar_point_pillars/include/lidar_point_pillars/point_pillars.h b/core_perception/lidar_point_pillars/include/lidar_point_pillars/point_pillars.h index 249a8da4245..08a550d2aaa 100644 --- a/core_perception/lidar_point_pillars/include/lidar_point_pillars/point_pillars.h +++ b/core_perception/lidar_point_pillars/include/lidar_point_pillars/point_pillars.h @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2021 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -17,8 +17,8 @@ /** * @file point_pillars.h * @brief Algorithm for PointPillars -* @author Kosuke Murakami -* @date 2019/02/26 +* @author Kosuke Murakami, Luca Fancellu +* @date 2020/09/04 */ #ifndef POINTS_PILLAR_H @@ -33,9 +33,16 @@ #include #include -// headers in TensorRT -#include "NvInfer.h" -#include "NvOnnxParser.h" +#ifdef TVM_IMPLEMENTATION + // headers in TVM + #include + #include "point_pillars_pfe/pfe_tvm_pipeline.h" + #include "point_pillars_rpn/rpn_tvm_pipeline.h" +#else + // headers in TensorRT + #include "NvInfer.h" + #include "NvOnnxParser.h" +#endif // headers in local files #include "lidar_point_pillars/common.h" @@ -45,43 +52,45 @@ #include "lidar_point_pillars/scatter_cuda.h" #include "lidar_point_pillars/postprocess_cuda.h" -// Logger for TensorRT info/warning/errors -class Logger : public nvinfer1::ILogger -{ -public: - Logger(Severity severity = Severity::kWARNING) : reportableSeverity(severity) +#ifndef TVM_IMPLEMENTATION + // Logger for TensorRT info/warning/errors + class Logger : public nvinfer1::ILogger { - } - - void log(Severity severity, const char* msg) override - { - // suppress messages with severity enum value greater than the reportable - if (severity > reportableSeverity) - return; + public: + Logger(Severity severity = Severity::kWARNING) : reportableSeverity(severity) + { + } - switch (severity) + void log(Severity severity, const char* msg) override { - case Severity::kINTERNAL_ERROR: - std::cerr << "INTERNAL_ERROR: "; - break; - case Severity::kERROR: - std::cerr << "ERROR: "; - break; - case Severity::kWARNING: - std::cerr << "WARNING: "; - break; - case Severity::kINFO: - std::cerr << "INFO: "; - break; - default: - std::cerr << "UNKNOWN: "; - break; + // suppress messages with severity enum value greater than the reportable + if (severity > reportableSeverity) + return; + + switch (severity) + { + case Severity::kINTERNAL_ERROR: + std::cerr << "INTERNAL_ERROR: "; + break; + case Severity::kERROR: + std::cerr << "ERROR: "; + break; + case Severity::kWARNING: + std::cerr << "WARNING: "; + break; + case Severity::kINFO: + std::cerr << "INFO: "; + break; + default: + std::cerr << "UNKNOWN: "; + break; + } + std::cerr << msg << std::endl; } - std::cerr << msg << std::endl; - } - Severity reportableSeverity; -}; + Severity reportableSeverity; + }; +#endif class PointPillars { @@ -171,8 +180,18 @@ class PointPillars float* dev_box_anchors_max_y_; int* dev_anchor_mask_; - void* pfe_buffers_[9]; - void* rpn_buffers_[4]; + #ifdef TVM_IMPLEMENTATION + void* pfe_net_output; + void* rpn_buffers_[3]; + + std::vector pfe_net_input_; + std::vector rpn_net_input_; + #else + void* pfe_buffers_[9]; + void* rpn_buffers_[4]; + #endif + + cudaStream_t stream_; float* dev_scattered_feature_; @@ -195,13 +214,23 @@ class PointPillars std::unique_ptr scatter_cuda_ptr_; std::unique_ptr postprocess_cuda_ptr_; - Logger g_logger_; - nvinfer1::IExecutionContext* pfe_context_; - nvinfer1::IExecutionContext* rpn_context_; - nvinfer1::IRuntime* pfe_runtime_; - nvinfer1::IRuntime* rpn_runtime_; - nvinfer1::ICudaEngine* pfe_engine_; - nvinfer1::ICudaEngine* rpn_engine_; + #ifdef TVM_IMPLEMENTATION + std::unique_ptr> pfe_engine_ptr_; + + std::unique_ptr> rpn_engine_ptr_; + #else + Logger g_logger_; + nvinfer1::IExecutionContext* pfe_context_; + nvinfer1::IExecutionContext* rpn_context_; + nvinfer1::IRuntime* pfe_runtime_; + nvinfer1::IRuntime* rpn_runtime_; + nvinfer1::ICudaEngine* pfe_engine_; + nvinfer1::ICudaEngine* rpn_engine_; + #endif /** * @brief Memory allocation for device memory @@ -216,10 +245,10 @@ class PointPillars void initAnchors(); /** - * @brief Initializing TensorRT instances + * @brief Initializing TensorRT/TVM instances * @details Called in the constructor */ - void initTRT(); + void initEngine(); /** * @brief Generate anchors @@ -235,6 +264,7 @@ class PointPillars void generateAnchors(float* anchors_px_, float* anchors_py_, float* anchors_pz_, float* anchors_dx_, float* anchors_dy_, float* anchors_dz_, float* anchors_ro_); +#ifndef TVM_IMPLEMENTATION /** * @brief Convert ONNX to TensorRT model * @param[in] model_file ONNX model file path @@ -242,6 +272,7 @@ class PointPillars * @details Load ONNX model, and convert it to TensorRT model */ void onnxToTRTModel(const std::string& model_file, nvinfer1::IHostMemory*& trt_model_stream); +#endif /** * @brief Preproces points diff --git a/core_perception/lidar_point_pillars/include/point_pillars_pfe/pfe_tvm_pipeline.h b/core_perception/lidar_point_pillars/include/point_pillars_pfe/pfe_tvm_pipeline.h new file mode 100644 index 00000000000..0285860061a --- /dev/null +++ b/core_perception/lidar_point_pillars/include/point_pillars_pfe/pfe_tvm_pipeline.h @@ -0,0 +1,85 @@ +/* + * Copyright 2021 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* @file pfe_tvm_pipeline.h +* @brief TVM pipeline definition for the PointPillars Feature Extractor +* @author Luca Fancellu +* @date 2020/09/04 +*/ + +#ifndef PFE_TVM_PIPELINE_H +#define PFE_TVM_PIPELINE_H + +#include +#include "lidar_point_pillars/common.h" + + +class PreProcessorPFE + : public tvm_utility::pipeline::PreProcessor> { +public: + + /** + * @brief Constructor + * @param[in] config The configuration of the TVM network + * @param[in] Pointer to the cuda stream to be used during operations + * @details Constructor for PFE pre-processor stage of the pipeline + */ + PreProcessorPFE(tvm_utility::pipeline::InferenceEngineTVMConfig config, + cudaStream_t* stream); + + /** + * @brief Pipeline stage schedule function + * @param[in] net_input Array of pointers to cuda memory array + * @return TVMArrayContainerVector for the TVM inference engine + * @details Pre-process input data to convert it to TVM structure + */ + tvm_utility::pipeline::TVMArrayContainerVector + schedule(const std::vector &net_input); + +private: + std::vector net_input_size_byte_; + tvm_utility::pipeline::TVMArrayContainerVector pfe_buffers_; + cudaStream_t* stream_; +}; + + +class PostProcessorPFE + : public tvm_utility::pipeline::PostProcessor> { +public: + + /** + * @brief Constructor + * @param[in] config The configuration of the TVM network + * @details Constructor for PFE post-processor stage of the pipeline + */ + PostProcessorPFE( + tvm_utility::pipeline::InferenceEngineTVMConfig config); + + /** + * @brief Pipeline stage schedule function + * @param[in] net_output TVMArrayContainerVector from the inference engine + * @return vector of float containing the network results + * @details Post-process the output of the inference engine + */ + std::vector + schedule(const tvm_utility::pipeline::TVMArrayContainerVector &net_output); + +private: + int64_t net_output_size_; +}; + +#endif // PFE_TVM_PIPELINE_H \ No newline at end of file diff --git a/core_perception/lidar_point_pillars/include/point_pillars_rpn/rpn_tvm_pipeline.h b/core_perception/lidar_point_pillars/include/point_pillars_rpn/rpn_tvm_pipeline.h new file mode 100644 index 00000000000..0c48439e2da --- /dev/null +++ b/core_perception/lidar_point_pillars/include/point_pillars_rpn/rpn_tvm_pipeline.h @@ -0,0 +1,92 @@ +/* + * Copyright 2021 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* @file rpn_tvm_pipeline.h +* @brief TVM pipeline definition for the RPN model +* @author Luca Fancellu +* @date 2020/09/04 +*/ + +#ifndef RPNTVM_PIPELINE_H +#define RPNTVM_PIPELINE_H + +#include +#include "lidar_point_pillars/common.h" + + +typedef struct RPN_Net_Output_ { + std::vector box_output; + std::vector cls_output; + std::vector dir_output; +} RPN_Net_Output; + + +class PreProcessorRPN + : public tvm_utility::pipeline::PreProcessor> { +public: + + /** + * @brief Constructor + * @param[in] config The configuration of the TVM network + * @param[in] stream Pointer to the cuda stream to be used during operations + * @details Constructor for RPN pre-processor stage of the pipeline + */ + PreProcessorRPN(tvm_utility::pipeline::InferenceEngineTVMConfig config, + cudaStream_t* stream); + + /** + * @brief Pipeline stage schedule function + * @param[in] net_input Array of pointers to cuda memory array + * @return TVMArrayContainerVector for the TVM inference engine + * @details Pre-process input data to convert it to TVM structure + */ + tvm_utility::pipeline::TVMArrayContainerVector + schedule(const std::vector &net_input); + +private: + tvm_utility::pipeline::TVMArrayContainer rpn_net_input_; + uint64_t net_input_size_byte_; + cudaStream_t* stream_; +}; + + +class PostProcessorRPN + : public tvm_utility::pipeline::PostProcessor { +public: + + /** + * @brief Constructor + * @param[in] config The configuration of the TVM network + * @details Constructor for RPN post-processor stage of the pipeline + */ + PostProcessorRPN( + tvm_utility::pipeline::InferenceEngineTVMConfig config); + + /** + * @brief Pipeline stage schedule function + * @param[in] net_output TVMArrayContainerVector from the inference engine + * @return structure with vectors of float containing the network results + * @details Post-process the output of the inference engine + */ + RPN_Net_Output + schedule(const tvm_utility::pipeline::TVMArrayContainerVector &net_output); + +private: + std::vector net_output_size_; +}; + +#endif // RPNTVM_PIPELINE_H \ No newline at end of file diff --git a/core_perception/lidar_point_pillars/nodes/pfe_tvm_pipeline.cpp b/core_perception/lidar_point_pillars/nodes/pfe_tvm_pipeline.cpp new file mode 100644 index 00000000000..a68a543b740 --- /dev/null +++ b/core_perception/lidar_point_pillars/nodes/pfe_tvm_pipeline.cpp @@ -0,0 +1,90 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* @file pfe_tvm_pipeline.cpp +* @brief TVM pipeline definition for the RPN model +* @author Luca Fancellu +* @date 2020/09/04 +*/ + +#include "point_pillars_pfe/pfe_tvm_pipeline.h" + + +PreProcessorPFE::PreProcessorPFE( + tvm_utility::pipeline::InferenceEngineTVMConfig config, + cudaStream_t* stream + ) : stream_(stream) +{ + // allocate input variables + uint64_t net_input_size; + for (uint64_t i = 0; i < config.network_inputs.size(); i++) { + net_input_size = 1; + for (uint64_t j = 0; j < config.network_inputs[i].second.size(); j++) + { + net_input_size *= config.network_inputs[i].second[j]; + } + net_input_size *= (config.tvm_dtype_bits / 8); + tvm_utility::pipeline::TVMArrayContainer input_var { + config.network_inputs[i].second, + config.tvm_dtype_code, + config.tvm_dtype_bits, + config.tvm_dtype_lanes, + config.tvm_device_type, + config.tvm_device_id + }; + + pfe_buffers_.push_back(input_var); + net_input_size_byte_.push_back(net_input_size); + } +} + +tvm_utility::pipeline::TVMArrayContainerVector + PreProcessorPFE::schedule(const std::vector &net_input) +{ + for (uint64_t i = 0; i < 8; i++) { + + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[i].getArray()->data, + net_input[i], + net_input_size_byte_[i], + cudaMemcpyDeviceToHost, + *stream_)); + } + + return pfe_buffers_; +} + +PostProcessorPFE::PostProcessorPFE( + tvm_utility::pipeline::InferenceEngineTVMConfig config) +{ + net_output_size_ = config.network_outputs[0].second[1] * + config.network_outputs[0].second[2] * + config.network_outputs[0].second[3]; +} + +std::vector PostProcessorPFE::schedule( + const tvm_utility::pipeline::TVMArrayContainerVector &net_output) +{ + std::vector output; + + // get a pointer to the output data + float *data_ptr = (float *)((uint8_t *)net_output[0].getArray()->data + + net_output[0].getArray()->byte_offset); + + output.insert(output.end(), data_ptr, data_ptr + net_output_size_); + + return output; +} diff --git a/core_perception/lidar_point_pillars/nodes/point_pillars.cpp b/core_perception/lidar_point_pillars/nodes/point_pillars.cpp index 52fa314bf85..a10f6715601 100644 --- a/core_perception/lidar_point_pillars/nodes/point_pillars.cpp +++ b/core_perception/lidar_point_pillars/nodes/point_pillars.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -21,6 +21,15 @@ // headers in local files #include "lidar_point_pillars/point_pillars.h" +#ifdef TVM_IMPLEMENTATION + #include "tvm_point_pillars_pfe/inference_engine_tvm_config.hpp" + #include "tvm_point_pillars_rpn/inference_engine_tvm_config.hpp" + + namespace pfe_model_cfg = model_zoo::perception::lidar_obstacle_detection:: + point_pillars_pfe::onnx_fp32_kitti; + namespace rpn_model_cfg = model_zoo::perception::lidar_obstacle_detection:: + point_pillars_rpn::onnx_fp32_kitti; +#endif // clang-format off PointPillars::PointPillars(const bool reproduce_result_mode, const float score_threshold, const float nms_overlap_threshold, const std::string pfe_onnx_file, @@ -90,7 +99,7 @@ PointPillars::PointPillars(const bool reproduce_result_mode, const float score_t nms_overlap_threshold_, NUM_BOX_CORNERS_, NUM_OUTPUT_BOX_FEATURE_)); deviceMemoryMalloc(); - initTRT(); + initEngine(); initAnchors(); } // clang-format on @@ -138,6 +147,13 @@ PointPillars::~PointPillars() GPU_CHECK(cudaFree(dev_box_anchors_max_y_)); GPU_CHECK(cudaFree(dev_anchor_mask_)); +#ifdef TVM_IMPLEMENTATION + GPU_CHECK(cudaFree(pfe_net_output)); + + GPU_CHECK(cudaFree(rpn_buffers_[0])); + GPU_CHECK(cudaFree(rpn_buffers_[1])); + GPU_CHECK(cudaFree(rpn_buffers_[2])); +#else GPU_CHECK(cudaFree(pfe_buffers_[0])); GPU_CHECK(cudaFree(pfe_buffers_[1])); GPU_CHECK(cudaFree(pfe_buffers_[2])); @@ -152,6 +168,7 @@ PointPillars::~PointPillars() GPU_CHECK(cudaFree(rpn_buffers_[1])); GPU_CHECK(cudaFree(rpn_buffers_[2])); GPU_CHECK(cudaFree(rpn_buffers_[3])); +#endif GPU_CHECK(cudaFree(dev_scattered_feature_)); @@ -168,6 +185,7 @@ PointPillars::~PointPillars() GPU_CHECK(cudaFree(dev_box_for_nms_)); GPU_CHECK(cudaFree(dev_filter_count_)); +#ifndef TVM_IMPLEMENTATION pfe_context_->destroy(); rpn_context_->destroy(); @@ -175,6 +193,7 @@ PointPillars::~PointPillars() rpn_runtime_->destroy(); pfe_engine_->destroy(); rpn_engine_->destroy(); +#endif } void PointPillars::deviceMemoryMalloc() @@ -216,6 +235,13 @@ void PointPillars::deviceMemoryMalloc() // for trt inference // create GPU buffers and a stream +#ifdef TVM_IMPLEMENTATION + GPU_CHECK(cudaMalloc(&pfe_net_output, PFE_OUTPUT_SIZE_ * sizeof(float))); + + GPU_CHECK(cudaMalloc(&rpn_buffers_[0], RPN_BOX_OUTPUT_SIZE_ * sizeof(float))); + GPU_CHECK(cudaMalloc(&rpn_buffers_[1], RPN_CLS_OUTPUT_SIZE_ * sizeof(float))); + GPU_CHECK(cudaMalloc(&rpn_buffers_[2], RPN_DIR_OUTPUT_SIZE_ * sizeof(float))); +#else GPU_CHECK(cudaMalloc(&pfe_buffers_[0], MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float))); GPU_CHECK(cudaMalloc(&pfe_buffers_[1], MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float))); GPU_CHECK(cudaMalloc(&pfe_buffers_[2], MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float))); @@ -230,6 +256,7 @@ void PointPillars::deviceMemoryMalloc() GPU_CHECK(cudaMalloc(&rpn_buffers_[1], RPN_BOX_OUTPUT_SIZE_ * sizeof(float))); GPU_CHECK(cudaMalloc(&rpn_buffers_[2], RPN_CLS_OUTPUT_SIZE_ * sizeof(float))); GPU_CHECK(cudaMalloc(&rpn_buffers_[3], RPN_DIR_OUTPUT_SIZE_ * sizeof(float))); +#endif // for scatter kernel GPU_CHECK(cudaMalloc((void**)&dev_scattered_feature_, NUM_THREADS_ * GRID_Y_SIZE_ * GRID_X_SIZE_ * sizeof(float))); @@ -382,8 +409,55 @@ void PointPillars::convertAnchors2BoxAnchors(float* anchors_px, float* anchors_p } } -void PointPillars::initTRT() +void PointPillars::initEngine() { +#ifdef TVM_IMPLEMENTATION + // Load TVM models + tvm_utility::pipeline::InferenceEngineTVMConfig pfe_config = pfe_model_cfg::config; + tvm_utility::pipeline::InferenceEngineTVMConfig rpn_config = rpn_model_cfg::config; + + pfe_config.network_module_path = pfe_onnx_file_ + + pfe_config.network_module_path; + pfe_config.network_graph_path = pfe_onnx_file_ + + pfe_config.network_graph_path; + pfe_config.network_params_path = pfe_onnx_file_ + + pfe_config.network_params_path; + + rpn_config.network_module_path = rpn_onnx_file_ + + rpn_config.network_module_path; + rpn_config.network_graph_path = rpn_onnx_file_ + + rpn_config.network_graph_path; + rpn_config.network_params_path = rpn_onnx_file_ + + rpn_config.network_params_path; + + pfe_engine_ptr_.reset(new tvm_utility::pipeline::Pipeline( + PreProcessorPFE(pfe_config, &stream_), + tvm_utility::pipeline::InferenceEngineTVM(pfe_config), + PostProcessorPFE(pfe_config) + ) + ); + rpn_engine_ptr_.reset(new tvm_utility::pipeline::Pipeline( + PreProcessorRPN(rpn_config, &stream_), + tvm_utility::pipeline::InferenceEngineTVM(rpn_config), + PostProcessorRPN(rpn_config) + ) + ); + + pfe_net_input_.push_back(dev_pillar_x_); + pfe_net_input_.push_back(dev_pillar_y_); + pfe_net_input_.push_back(dev_pillar_z_); + pfe_net_input_.push_back(dev_pillar_i_); + pfe_net_input_.push_back(dev_num_points_per_pillar_); + pfe_net_input_.push_back(dev_x_coors_for_sub_shaped_); + pfe_net_input_.push_back(dev_y_coors_for_sub_shaped_); + pfe_net_input_.push_back(dev_pillar_feature_mask_); + + rpn_net_input_.push_back(dev_scattered_feature_); +#else // create a TensorRT model from the onnx model and serialize it to a stream nvinfer1::IHostMemory* pfe_trt_model_stream{ nullptr }; nvinfer1::IHostMemory* rpn_trt_model_stream{ nullptr }; @@ -417,8 +491,10 @@ void PointPillars::initTRT() { std::cerr << "Failed to create TensorRT Execution Context." << std::endl;; } +#endif } +#ifndef TVM_IMPLEMENTATION void PointPillars::onnxToTRTModel(const std::string& model_file, // name of the onnx model nvinfer1::IHostMemory*& trt_model_stream) // output buffer for the TensorRT model { @@ -451,6 +527,7 @@ void PointPillars::onnxToTRTModel(const std::string& model_file, // network->destroy(); builder->destroy(); } +#endif void PointPillars::preprocessCPU(const float* in_points_array, const int in_num_points) { @@ -554,34 +631,85 @@ void PointPillars::doInference(const float* in_points_array, const int in_num_po dev_box_anchors_min_x_, dev_box_anchors_min_y_, dev_box_anchors_max_x_, dev_box_anchors_max_y_, dev_anchor_mask_); - cudaStream_t stream; - GPU_CHECK(cudaStreamCreate(&stream)); + GPU_CHECK(cudaStreamCreate(&stream_)); + +#ifdef TVM_IMPLEMENTATION + std::vector pfe_out = pfe_engine_ptr_->schedule(pfe_net_input_); + + // Copy from Host to device the PFE net result + GPU_CHECK(cudaMemcpyAsync(pfe_net_output, + pfe_out.data(), + PFE_OUTPUT_SIZE_ * sizeof(float), + cudaMemcpyHostToDevice, + stream_)); +#else // clang-format off - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[0], dev_pillar_x_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[1], dev_pillar_y_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[2], dev_pillar_z_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[3], dev_pillar_i_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[4], dev_num_points_per_pillar_, MAX_NUM_PILLARS_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[5], dev_x_coors_for_sub_shaped_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[6], dev_y_coors_for_sub_shaped_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); - GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[7], dev_pillar_feature_mask_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[0], dev_pillar_x_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[1], dev_pillar_y_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[2], dev_pillar_z_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[3], dev_pillar_i_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[4], dev_num_points_per_pillar_, MAX_NUM_PILLARS_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[5], dev_x_coors_for_sub_shaped_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[6], dev_y_coors_for_sub_shaped_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(pfe_buffers_[7], dev_pillar_feature_mask_, MAX_NUM_PILLARS_ * MAX_NUM_POINTS_PER_PILLAR_ * sizeof(float), cudaMemcpyDeviceToDevice, stream_)); // clang-format on - pfe_context_->enqueue(BATCH_SIZE_, pfe_buffers_, stream, nullptr); + pfe_context_->enqueue(BATCH_SIZE_, pfe_buffers_, stream_, nullptr); +#endif GPU_CHECK(cudaMemset(dev_scattered_feature_, 0, RPN_INPUT_SIZE_ * sizeof(float))); + +#ifdef TVM_IMPLEMENTATION + scatter_cuda_ptr_->doScatterCuda(host_pillar_count_[0], dev_x_coors_, + dev_y_coors_, (float*)pfe_net_output, + dev_scattered_feature_); + + // Infer from RPN engine + RPN_Net_Output rpn_out = rpn_engine_ptr_->schedule(rpn_net_input_); + + // Copy output from RPN engine to gpu device memory + GPU_CHECK(cudaMemcpyAsync(rpn_buffers_[0], rpn_out.box_output.data(), + rpn_out.box_output.size() * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(rpn_buffers_[1], rpn_out.cls_output.data(), + rpn_out.cls_output.size() * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + GPU_CHECK(cudaMemcpyAsync(rpn_buffers_[2], rpn_out.dir_output.data(), + rpn_out.dir_output.size() * sizeof(float), + cudaMemcpyHostToDevice, stream_)); + + GPU_CHECK(cudaMemset(dev_filter_count_, 0, sizeof(int))); + postprocess_cuda_ptr_->doPostprocessCuda((float*)rpn_buffers_[0], + (float*)rpn_buffers_[1], + (float*)rpn_buffers_[2], + dev_anchor_mask_, + dev_anchors_px_, + dev_anchors_py_, + dev_anchors_pz_, + dev_anchors_dx_, + dev_anchors_dy_, + dev_anchors_dz_, + dev_anchors_ro_, + dev_filtered_box_, + dev_filtered_score_, + dev_filtered_dir_, + dev_box_for_nms_, + dev_filter_count_, + out_detections); +#else scatter_cuda_ptr_->doScatterCuda(host_pillar_count_[0], dev_x_coors_, dev_y_coors_, (float*)pfe_buffers_[8], dev_scattered_feature_); GPU_CHECK(cudaMemcpyAsync(rpn_buffers_[0], dev_scattered_feature_, BATCH_SIZE_ * RPN_INPUT_SIZE_ * sizeof(float), - cudaMemcpyDeviceToDevice, stream)); - rpn_context_->enqueue(BATCH_SIZE_, rpn_buffers_, stream, nullptr); + cudaMemcpyDeviceToDevice, stream_)); + rpn_context_->enqueue(BATCH_SIZE_, rpn_buffers_, stream_, nullptr); GPU_CHECK(cudaMemset(dev_filter_count_, 0, sizeof(int))); postprocess_cuda_ptr_->doPostprocessCuda( (float*)rpn_buffers_[1], (float*)rpn_buffers_[2], (float*)rpn_buffers_[3], dev_anchor_mask_, dev_anchors_px_, dev_anchors_py_, dev_anchors_pz_, dev_anchors_dx_, dev_anchors_dy_, dev_anchors_dz_, dev_anchors_ro_, dev_filtered_box_, dev_filtered_score_, dev_filtered_dir_, dev_box_for_nms_, dev_filter_count_, out_detections); +#endif // release the stream and the buffers - cudaStreamDestroy(stream); + cudaStreamDestroy(stream_); } diff --git a/core_perception/lidar_point_pillars/nodes/point_pillars_ros.cpp b/core_perception/lidar_point_pillars/nodes/point_pillars_ros.cpp index 776ce59394a..06012a42b86 100644 --- a/core_perception/lidar_point_pillars/nodes/point_pillars_ros.cpp +++ b/core_perception/lidar_point_pillars/nodes/point_pillars_ros.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2018-2019 Autoware Foundation. All rights reserved. + * Copyright 2018-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -25,6 +25,7 @@ // headers in ROS #include +#include // headers in local files #include "autoware_msgs/DetectedObjectArray.h" @@ -48,9 +49,20 @@ PointPillarsROS::PointPillarsROS() private_nh_.param("nms_overlap_threshold", nms_overlap_threshold_, 0.5f); private_nh_.param("pfe_onnx_file", pfe_onnx_file_, ""); private_nh_.param("rpn_onnx_file", rpn_onnx_file_, ""); - +#ifdef TVM_IMPLEMENTATION + point_pillars_ptr_.reset( + new PointPillars( + reproduce_result_mode_, + score_threshold_, + nms_overlap_threshold_, + ros::package::getPath("lidar_point_pillars") + "/tvm_models/tvm_point_pillars_pfe/", + ros::package::getPath("lidar_point_pillars") + "/tvm_models/tvm_point_pillars_rpn/" + ) + ); +#else point_pillars_ptr_.reset(new PointPillars(reproduce_result_mode_, score_threshold_, nms_overlap_threshold_, - pfe_onnx_file_, rpn_onnx_file_)); + pfe_onnx_file_, rpn_onnx_file_)); +#endif } void PointPillarsROS::createROSPubSub() diff --git a/core_perception/lidar_point_pillars/nodes/rpn_tvm_pipeline.cpp b/core_perception/lidar_point_pillars/nodes/rpn_tvm_pipeline.cpp new file mode 100644 index 00000000000..d75c0c20243 --- /dev/null +++ b/core_perception/lidar_point_pillars/nodes/rpn_tvm_pipeline.cpp @@ -0,0 +1,90 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* @file rpn_tvm_pipeline.cpp +* @brief TVM pipeline definition for the RPN model +* @author Luca Fancellu +* @date 2020/09/04 +*/ + +#include "point_pillars_rpn/rpn_tvm_pipeline.h" + + +PreProcessorRPN::PreProcessorRPN( + tvm_utility::pipeline::InferenceEngineTVMConfig config, + cudaStream_t* stream + ) : stream_(stream) +{ + // allocate input variable + tvm_utility::pipeline::TVMArrayContainer input_var { + config.network_inputs[0].second, + config.tvm_dtype_code, + config.tvm_dtype_bits, + config.tvm_dtype_lanes, + config.tvm_device_type, + config.tvm_device_id + }; + + net_input_size_byte_ = config.network_inputs[0].second[1] * + config.network_inputs[0].second[2] * + config.network_inputs[0].second[3] * + (config.tvm_dtype_bits / 8); + + rpn_net_input_ = input_var; +} + +tvm_utility::pipeline::TVMArrayContainerVector + PreProcessorRPN::schedule(const std::vector &net_input) +{ + GPU_CHECK(cudaMemcpyAsync(rpn_net_input_.getArray()->data, + net_input[0], + net_input_size_byte_, + cudaMemcpyDeviceToHost, + *stream_)); + + return {rpn_net_input_}; +} + +PostProcessorRPN::PostProcessorRPN( + tvm_utility::pipeline::InferenceEngineTVMConfig config) +{ + for (uint64_t i = 0; i < config.network_outputs.size(); i++) { + int64_t output_size = config.network_outputs[i].second[1] * + config.network_outputs[i].second[2] * + config.network_outputs[i].second[3]; + net_output_size_.push_back(output_size); + } +} + +RPN_Net_Output PostProcessorRPN::schedule( + const tvm_utility::pipeline::TVMArrayContainerVector &net_output) +{ + RPN_Net_Output output; + std::vector* ptr_output[3] = {&output.box_output, + &output.cls_output, &output.dir_output}; + for (uint64_t i = 0; i < 3; i++) { + + // get a pointer to the output data + float *data_ptr = (float *)((uint8_t *)net_output[i].getArray()->data + + net_output[i].getArray()->byte_offset); + + ptr_output[i]->insert(ptr_output[i]->end(), data_ptr, data_ptr + + net_output_size_[i]); + } + + return output; +} diff --git a/core_perception/lidar_point_pillars/package.xml b/core_perception/lidar_point_pillars/package.xml index efd44533bf6..f78d314e5b3 100755 --- a/core_perception/lidar_point_pillars/package.xml +++ b/core_perception/lidar_point_pillars/package.xml @@ -13,4 +13,5 @@ pcl_ros roscpp roslib + tvm_utility diff --git a/core_perception/lidar_point_pillars/test/data/dummy.onnx b/core_perception/lidar_point_pillars/test/data/data_onnx/dummy.onnx similarity index 100% rename from core_perception/lidar_point_pillars/test/data/dummy.onnx rename to core_perception/lidar_point_pillars/test/data/data_onnx/dummy.onnx diff --git a/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_graph.json b/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_graph.json new file mode 100644 index 00000000000..093cae0653c --- /dev/null +++ b/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_graph.json @@ -0,0 +1,79 @@ +{ + "nodes": [ + { + "op": "null", + "name": "input", + "inputs": [] + }, + { + "op": "null", + "name": "p0", + "inputs": [] + }, + { + "op": "null", + "name": "p1", + "inputs": [] + }, + { + "op": "tvm_op", + "name": "fused_multiply_add", + "attrs": { + "num_outputs": "1", + "num_inputs": "3", + "func_name": "fused_multiply_add", + "flatten_data": "0" + }, + "inputs": [ + [ + 0, + 0, + 0 + ], + [ + 1, + 0, + 0 + ], + [ + 2, + 0, + 0 + ] + ] + } + ], + "arg_nodes": [0, 1, 2], + "heads": [ + [ + 3, + 0, + 0 + ] + ], + "attrs": { + "dltype": [ + "list_str", + [ + "float32", + "float32", + "float32", + "float32" + ] + ], + "shape": [ + "list_shape", + [ + [10, 6, 224, 224], + [6, 1, 1], + [6, 1, 1], + [10, 6, 224, 224] + ] + ], + "storage_id": [ + "list_int", + [0, 1, 2, 3] + ] + }, + "node_row_ptr": [0, 1, 2, 3, 4] +} \ No newline at end of file diff --git a/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_lib.so b/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_lib.so new file mode 100755 index 0000000000000000000000000000000000000000..d3f98561566c2547d4d0b7e5015771329168e6cf GIT binary patch literal 16720 zcmeHOdvILUc|WU_Y=PyyYo0P@;5wBZ3CMa^>xYaZTPs`Us+B<4a%yVa^-8;v7FN5P z-MdDzU68v`i=wD;T4qX8+MzE>VH!+^w7`_9AB-^2q)s~NI3X?Sv;-?8jfo4jfq47- z&SM{U?;0t%(|>$Mt8>2J_xrwc?z!JN_uSoc9_r}YTIFysm7HuNBPm%UkT$94SuYF7 z+E@!)i2pjfnR6wzKqxBdpB9438LTK#9SiVDdPt&NFUb!R0qKOym0cAuvKy0jW71CL zJ(92TT5^I^EkDYiHE-Z7##ByxN1@wwy99qiE8Tb_9J^f&)CyL0_NO~3iKcYpW&Q{SR0NKf~R?5KT@ zPV0`b>b83by8@p&d_H^h@1JY$_}))m{Ey#1@KAf~)bmsCx=ww5=Z%Yg^z7Gu{Lepg z9Y6oTi=f%2Z9sJ!O-lv*#tJyKPshiaz5-x5Tf}}K@5j}W@GNpSyPD}ariqi8ayTP~m-wT}lcrAXe1AY~|k{!6J$O(#n!tpCu zj|`4c6(qsn;BX=yOq-#U84R*uG#)isZ~z$#cJ_7$!;w^EFq$?asow6*u|z!58|sTi zgw9?Q>>mk{gHSBG55!>a=eh$uo!cX3S14_Eq*95L0NX?T_ebL4o=_?ji$!8xp-jAg z2r6^$aBw&jjiWUKnRFx^9L~hdXfie$428oi7zu~W5NLhrv}iS;cvxMn8qca<+vIhQ z$nmOh9)vKexAdQqPp;CrOERaJQ0Y_=PIH1vGetPXx=N>u@O<4+o+-i?DKheNMYtN% zq&BiYsWm2RUb;nR#`qDlDtFSzzFd1eZ<$;34XAP}p2L6b<~Ee>LuufUA{bMxe+^)V zF;(-Y$c^>qjET3*rEs~8M7UhMJ2x}n(Qf_%H`#rhycA^EM~OJKrjNU6x&V9Q=mn=S zamF}$dXwRpHokMgtcSz%O~PRvIjrPwtaT~;u*@nW+xibMK+DjcI%Bf+14yS^bGh7U z1OKLL-i7R-=8RFp&K`%$ErPy#b^r`12Yx;9xxkJEv*N|dsHP@^!(cH>4wOq5RM6;Z0>bPb_iROAp#^l26NUcK~-v}W) z;zsRTP#VaNTnDfd#j%lVb!~hTFI`imjZ+(pNuxfy{z`4U1wwYTc7d=zIO?9km1^Sw zzz0X`g>VNq2-bE@4!XN0gXrj5W1_18z$Kz4c(JwLw)z; zfd)t$x+k}z{A+qQZuOdg=4SX9Zf*ML!voshnqORr)@sQUcMfQ8oIv5|TPPeI&>oy_ zdw<%Yec^|Qbt5~{h*te4irM{cr#Ajmlm@c<=@Q>Vacnn28lg@L`8_}dHZu%g(yHXUXx~ov^9?zM2AiD|TbzJih zk;r`@`w)@nS=Nb)s8I_!e4v3SE-G*6Z9v0>;eLvPn}DKSyq73&0-~F45JhT~M#b#y zh=Y1w+DCz)Q}N(F8429*;651&w?NlD{;KK6Ep*`1nZJ!|@hG*ujYpouO{AXa6rH)4 z*Tj4CS}OAHq^25(8MiUni%818T)!)DZ(w)eHv_@lv&*=$=C+kOCV|!lRP>GqgZ)M! zKSA0>E}$?$#{_g(K#Q=(nSDk;e=MM#1U)98FAC@{2$~Sk0|NRv zL3;%h7Es&ufcgb=w}8$O)FYsc0@_gzs8v9>3g~HqZUJ;iBs_H*jR{Ny#sm$ZiQa~K znvZqFnnPIJfH~cmG8<}r-_5x(2pW$|Q=V<_oH#joXYEvA!&m?3{M20z?U@tV^Q|v_ zmL3G%uW8S`l0Da|bst-QLYrD!gW*4ExVtBN>T^eo{!?B3-#4PKGq;l&xz{@<-G<|} zPNz{@?Ea9^f7Xazc>1ZQZZRg#@dx(NpXrWQ9J#6Lhnl91{^_%rNU9Ig|GMASrjIaf z`c-DUGR@9>#4k~EU*pr<_xjx0JtwuD-_h-ZOOgOZq426(@E_uRrfaQ zr1z4(jr2WMeH-a}NWX{lNvnPj>64oK5#Jbfh5IodEon+wk2G`LlE<344&28j_pl9@ z>%iqYaF0mtNgFQLfy;H^&PeVV8!p#@%XQ$=vXR>Bro5!n9%<$}aJdd#U2?rPT&@F` z>%eW3+#VY)*MZA*;O>#!qz#wrz~wq{$0YZV4VUY{%cuCxhHM7 zTn8@Kfjc9)XKc7!2QJrv%c^AmQf}>E!oYQN4*FMey*6B~1DEUIw@q?;Y`9zpF4uv( zM{<)kT&@F`>%bk8+(R~8t^=3rzKb9nqxZtY*fz{QjU4*FMey*6B~1DET-ZIj#{8!p#@%XQ%Hk=&#Wm+QbKopEq_ zj40zfKExv?cicF5j8BILk5bmP{tfL*AAXR_`Ht*5j*-jXrApqO06tpH*vpL3C`RzH zKsp^snfgE|8oOO@jAw>}q10enZ*A3AH{GU}zn9*w=Q-)2L?#y2`y%>ki<`#AMtJdh z`V-*@x$-yZ2M*|^n9tv2gRZj!S2tB?O2k%GB!dv9?nNZ9oo-27<(?oSOW)O2NP0daE%9VO!CGOf{uD=TbdEdwt$Dm1uO+ zRqW$#QX6hB34TOTe_}Wp;!|oWG-|omJj&OuZsH+TDac#O1FLV;j06({1L=r4udee` zzm?bHD;dTK@-eL3&vOi0M;P1`4Ie(j$}X^M z293{K9x%nv)cH(o^lXlXFE&KiSF8+n^Qo%BM9^F^5j20oi9mRp+e9F^bDanT+kPTw z{zMZ&bH$0EpqW=smyQDEqK@`*sX|AZ3(++2JjC=d#d(6TO&E(#Mt-s)0L z1R_YvCW7WmJrRg{$|nK@V$tGyKBMzu6M?9$Y$C{4HqVKm!ouEPG7Pc@L?GDq6M=u86M^gE-!9mmH*>ij z*Wb?N-1H?J5`HA&$+2%6bBwqh%jy=^9)hj`DDB~?g%39|T<)!|`d`%+Jy1KwHr=q{ z7JtL12qyb2_?-E-Tn@i4=2IA@d+|8|d%hPY;BvRS>f2p-DyQLewFF#Vt_KTTcfeKK;p(aCv{M9Jbd6L$zE)&2Z{>1y{cMZNn{d@K z{CvcIh)*r9IZB;^`mu%OuIQKsePri7NMl{?_J0xNTy$_DbXXI(!=}XZ_UCh=J$XM;|NoV#ee>4( z)&AQ%HgCr7t~>fNaWkW@^Q`fBKjY7E$@ieI#p7MwBv6K3S4{NbO6iN%eWF)tdFNM2 z32Q`XKdoZef=`mbL~r?ZKp1!+gi;RZ4QUyL)T)4j4bfMA9gacVf=O* z^WgQEtulv`tAx|i27rIj+lVQ`EO>#19K(k3s zhAn3{$;sam$`wwgW~Wk}lZS69Mv{}M*{f9NIULa|`jOr+Am zP-cYD@4c~z83}vVtzF+@PvVDUuq_C`2;&5bnHpsSsnBpF7|sk2kHVx#;-_j#sWvBD zf?Kx*x;ug$cW$ABI9u+yGtk|+8IEx9MuEX_IuRTS#lv(2Cx`=A!45;38C$lo;2m9e zwFkO_cWvFey`wkS8))z9fGf+19C5^l4)@p};JMhbpW@RwC1-HNi6MD7hYsY-|KLx_ zK_uo$j}DumKICRf?Tx7(9S@KZ&e$dJ5kLt&UINtlZJCoEJMenZ32e$<~Z$up{@ z(@7p2PGZdGCd(^0VGy3h4YVUozh_OESH^m)PvIdSYs-CwT@A_A(?9Zsn)B?K?@4B z=2iA;y`%CTjBiR*FBO%&THm$-Bj3tit+Q3G*43c!B;6^IQTxcZvRCVBm7kJKYx`CG z+n^_(YF)41D^zZM!dv_A8y5Q>`8-uQ|Bh3(fifkle5b`;t=m+t`b)V`vdTji`=qR2 zW-d?>|j?lnDQam9Q zWQG4F6cl@^eziVP=aq}c5BX4bsvqgQaO!_$uhz#W@rFamE3*85Wv}wDLsM*@Uq?$r zHBOWRWvBALv)HTkQoXcSJgdEuUqXR6s{LwxseerU%KjJ%)PC!AD*GlylsR!Jsr>b# zGFQldozfvzbR|jIDUjBKR*ZDJq`mcZ$jW`Yg8e~hZ+-Ky+P_!9{tu=7P1Km8WVNTa zWWppp&-|tY=y#Cfr0i8*C+&+lRDM<3E1uF@0A2%Ugu~tri1|$o>~N*{8Yy literal 0 HcmV?d00001 diff --git a/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_param.params b/core_perception/lidar_point_pillars/test/data/data_tvm/deploy_param.params new file mode 100644 index 0000000000000000000000000000000000000000..6769646a14bc58ce41e30f9cb1897a579f770256 GIT binary patch literal 228 zcmdl!hlSO@_vv>AC}2XP3k+c*1qLvd{lYENJ~+hPh3R30GMIrhlL8|H8& cluster, autoware_msgs::DetectedObject& ouput) = 0; -}; \ No newline at end of file +}; diff --git a/core_perception/lidar_shape_estimation/include/lidar_shape_estimation/shape_estimator.hpp b/core_perception/lidar_shape_estimation/include/lidar_shape_estimation/shape_estimator.hpp index a46a156e22e..8ccb38fb272 100644 --- a/core_perception/lidar_shape_estimation/include/lidar_shape_estimation/shape_estimator.hpp +++ b/core_perception/lidar_shape_estimation/include/lidar_shape_estimation/shape_estimator.hpp @@ -34,4 +34,4 @@ class ShapeEstimator bool getShapeAndPose(const std::string& label, const pcl::PointCloud& cluster, autoware_msgs::DetectedObject& output); -}; \ No newline at end of file +}; diff --git a/core_perception/lidar_shape_estimation/package.xml b/core_perception/lidar_shape_estimation/package.xml index a55253395ff..35e3716dcdb 100644 --- a/core_perception/lidar_shape_estimation/package.xml +++ b/core_perception/lidar_shape_estimation/package.xml @@ -12,9 +12,10 @@ autoware_msgs pcl_ros roscpp + roslint tf2 tf2_geometry_msgs - + rostest rosunit diff --git a/core_perception/lidar_shape_estimation/src/model/bounding_box.cpp b/core_perception/lidar_shape_estimation/src/model/bounding_box.cpp index 684c142ed99..89115384d50 100644 --- a/core_perception/lidar_shape_estimation/src/model/bounding_box.cpp +++ b/core_perception/lidar_shape_estimation/src/model/bounding_box.cpp @@ -16,8 +16,12 @@ * v1.0 Yukihiro Saito */ -#include "bounding_box.hpp" #include +#include +#include +#include + +#include "bounding_box.hpp" #include #include #include @@ -44,9 +48,9 @@ bool BoundingBoxModel::estimate(const pcl::PointCloud& cluster, a centroid.y += pcl_point.y; centroid.z += pcl_point.z; } - centroid.x = centroid.x / (double)cluster.size(); - centroid.y = centroid.y / (double)cluster.size(); - centroid.z = centroid.z / (double)cluster.size(); + centroid.x = centroid.x / static_cast(cluster.size()); + centroid.y = centroid.y / static_cast(cluster.size()); + centroid.z = centroid.z / static_cast(cluster.size()); // calc min and max z for cylinder length double min_z = 0; @@ -60,7 +64,7 @@ bool BoundingBoxModel::estimate(const pcl::PointCloud& cluster, a } // calc circumscribed circle on x-y plane - cv::Mat_ cv_points((int)cluster.size(), 2); + cv::Mat_ cv_points(static_cast(cluster.size()), 2); for (size_t i = 0; i < cluster.size(); ++i) { cv_points(i, 0) = cluster.at(i).x; // x diff --git a/core_perception/lidar_shape_estimation/src/model/convex_hull.cpp b/core_perception/lidar_shape_estimation/src/model/convex_hull.cpp index 76eeb9ac0d6..7f0cf000818 100644 --- a/core_perception/lidar_shape_estimation/src/model/convex_hull.cpp +++ b/core_perception/lidar_shape_estimation/src/model/convex_hull.cpp @@ -21,7 +21,7 @@ bool ConvexHullModel::estimate(const pcl::PointCloud& cluster, autoware_msgs::DetectedObject& output) { - //currently no compatible model is available - //boilerplate + // currently no compatible model is available + // boilerplate return true; } diff --git a/core_perception/lidar_shape_estimation/src/model/cylinder.cpp b/core_perception/lidar_shape_estimation/src/model/cylinder.cpp index 170975c4b58..5fa72aac0f8 100644 --- a/core_perception/lidar_shape_estimation/src/model/cylinder.cpp +++ b/core_perception/lidar_shape_estimation/src/model/cylinder.cpp @@ -17,6 +17,8 @@ * v1.0 Yukihiro Saito */ +#include + #include "cylinder.hpp" #include #include @@ -38,9 +40,9 @@ bool CylinderModel::estimate(const pcl::PointCloud& cluster, auto centroid.y += pcl_point.y; centroid.z += pcl_point.z; } - centroid.x = centroid.x / (double)cluster.size(); - centroid.y = centroid.y / (double)cluster.size(); - centroid.z = centroid.z / (double)cluster.size(); + centroid.x = centroid.x / static_cast(cluster.size()); + centroid.y = centroid.y / static_cast(cluster.size()); + centroid.z = centroid.z / static_cast(cluster.size()); // calc min and max z for cylinder length double min_z = 0; @@ -54,7 +56,7 @@ bool CylinderModel::estimate(const pcl::PointCloud& cluster, auto } // calc circumscribed circle on x-y plane - cv::Mat_ cv_points((int)cluster.size(), 2); + cv::Mat_ cv_points(static_cast(cluster.size()), 2); for (size_t i = 0; i < cluster.size(); ++i) { cv_points(i, 0) = cluster.at(i).x; // x @@ -64,12 +66,12 @@ bool CylinderModel::estimate(const pcl::PointCloud& cluster, auto float radius; cv::minEnclosingCircle(cv::Mat(cv_points).reshape(2), center, radius); constexpr double ep = 0.001; - radius = std::max(radius, (float)ep); + radius = std::max(radius, static_cast(ep)); output.pose.position.x = center.x; output.pose.position.y = center.y; output.pose.position.z = centroid.z; - output.dimensions.x = (double)radius * 2.0; - output.dimensions.y = (double)radius * 2.0; + output.dimensions.x = static_cast(radius) * 2.0; + output.dimensions.y = static_cast(radius) * 2.0; output.dimensions.z = std::max((max_z - min_z), ep); output.pose_reliable = true; return true; diff --git a/core_perception/lidar_shape_estimation/src/shape_estimator.cpp b/core_perception/lidar_shape_estimation/src/shape_estimator.cpp index 3f4b76b2cb9..429ad6e702f 100644 --- a/core_perception/lidar_shape_estimation/src/shape_estimator.cpp +++ b/core_perception/lidar_shape_estimation/src/shape_estimator.cpp @@ -17,13 +17,14 @@ * v1.0 Yukihiro Saito */ +#include +#include + #include "lidar_shape_estimation/shape_estimator.hpp" #include "lidar_shape_estimation/model_interface.hpp" #include "model/bounding_box.hpp" #include "model/convex_hull.hpp" #include "model/cylinder.hpp" -#include -#include ShapeEstimator::ShapeEstimator() { diff --git a/core_perception/lidar_shape_estimation/test/src/test_lidar_shape_estimation.cpp b/core_perception/lidar_shape_estimation/test/src/test_lidar_shape_estimation.cpp index c030853474a..0245feccb72 100644 --- a/core_perception/lidar_shape_estimation/test/src/test_lidar_shape_estimation.cpp +++ b/core_perception/lidar_shape_estimation/test/src/test_lidar_shape_estimation.cpp @@ -17,6 +17,8 @@ * v1.0 Yukihiro Saito */ +#include + #include #include #include @@ -40,7 +42,9 @@ class ShapeEstimationTestSuite : public ::testing::Test class ShapeEstimationTestClass { public: - ShapeEstimationTestClass(){}; + ShapeEstimationTestClass() + { + } ShapeEstimator shape_estimator; }; diff --git a/core_perception/naive_motion_predict/README.md b/core_perception/naive_motion_predict/README.md index da2ae5aaef9..6d48acc4fe3 100644 --- a/core_perception/naive_motion_predict/README.md +++ b/core_perception/naive_motion_predict/README.md @@ -35,7 +35,7 @@ Launch file available parameters for `naive_motion_predict` |Topic|Type|Objective| ------|----|--------- -|`/detection/lidar_tracker/objects`|`autoware_msgs::DetectedObjectArray`|The result topic from Autoware Detection stack| +|`/detection/objects`|`autoware_msgs::DetectedObjectArray`|The result topic from Autoware Detection stack| ### Published topics diff --git a/core_perception/ndt_cpu/CMakeLists.txt b/core_perception/ndt_cpu/CMakeLists.txt index 9635f6085a9..21e10838ae5 100644 --- a/core_perception/ndt_cpu/CMakeLists.txt +++ b/core_perception/ndt_cpu/CMakeLists.txt @@ -6,68 +6,70 @@ find_package(PCL REQUIRED) find_package(Eigen3 QUIET) -if (NOT EIGEN3_FOUND) - # Fallback to cmake_modules - find_package(cmake_modules REQUIRED) - find_package(Eigen REQUIRED) - set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) - set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only - # Possibly map additional variables to the EIGEN3_ prefix. -else () - set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) -endif () +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() catkin_package( - INCLUDE_DIRS include - LIBRARIES ndt_cpu #The exported libraries from the project - DEPENDS PCL + INCLUDE_DIRS include + LIBRARIES ndt_cpu #The exported libraries from the project + DEPENDS PCL ) include_directories( - ${PCL_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - "include" - ${EIGEN3_INCLUDE_DIRS} + "include" + ${PCL_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) set(srcs - src/NormalDistributionsTransform.cpp - src/Registration.cpp - src/VoxelGrid.cpp - src/Octree.cpp - ) + src/NormalDistributionsTransform.cpp + src/Registration.cpp + src/VoxelGrid.cpp + src/Octree.cpp +) set(incs - include/ndt_cpu/debug.h - include/ndt_cpu/NormalDistributionsTransform.h - include/ndt_cpu/Registration.h - include/ndt_cpu/SymmetricEigenSolver.h - include/ndt_cpu/VoxelGrid.h - include/ndt_cpu/Octree.h - ) + include/ndt_cpu/debug.h + include/ndt_cpu/NormalDistributionsTransform.h + include/ndt_cpu/Registration.h + include/ndt_cpu/SymmetricEigenSolver.h + include/ndt_cpu/VoxelGrid.h + include/ndt_cpu/Octree.h +) -message(WARNING -"Adding 'EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT' macro to prevent ndt_matching's runtime error in debug mode. - The bug reasons and solutions are written in http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html . - This workaround was discussed on https://gitlab.com/autowarefoundation/autoware.ai/core_perception/merge_requests/57 .") +if(NOT ("${CMAKE_BUILD_TYPE}" STREQUAL "Release")) + message(WARNING "Not building for release, performance will be slow") -add_definitions(-DEIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT) + message(WARNING + "Adding 'EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT' macro to prevent ndt_matching's runtime error in debug mode. + The bug reasons and solutions are written in http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html . + This workaround was discussed on https://gitlab.com/autowarefoundation/autoware.ai/core_perception/merge_requests/57 .") + add_definitions(-DEIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT) +endif() add_library(ndt_cpu ${incs} ${srcs}) target_link_libraries(ndt_cpu - ${PCL_LIBRARIES} - ${catkin_LIBRARIES} - ) + ${PCL_LIBRARIES} + ${catkin_LIBRARIES} +) install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" - ) - + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) install(TARGETS ndt_cpu - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/core_perception/ndt_cpu/include/ndt_cpu/NormalDistributionsTransform.h b/core_perception/ndt_cpu/include/ndt_cpu/NormalDistributionsTransform.h index 25ef98170e8..11659508a13 100644 --- a/core_perception/ndt_cpu/include/ndt_cpu/NormalDistributionsTransform.h +++ b/core_perception/ndt_cpu/include/ndt_cpu/NormalDistributionsTransform.h @@ -10,104 +10,104 @@ namespace cpu { template class NormalDistributionsTransform: public Registration { public: - NormalDistributionsTransform(); + NormalDistributionsTransform(); - NormalDistributionsTransform(const NormalDistributionsTransform &other); + NormalDistributionsTransform(const NormalDistributionsTransform &other); - void setStepSize(double step_size); + void setStepSize(double step_size); - void setResolution(float resolution); + void setResolution(float resolution); - void setOutlierRatio(double olr); + void setOutlierRatio(double olr); - double getStepSize() const; + double getStepSize() const; - float getResolution() const; + float getResolution() const; - double getOutlierRatio() const; + double getOutlierRatio() const; - double getTransformationProbability() const; + double getTransformationProbability() const; - int getRealIterations(); + int getRealIterations(); - /* Set the input map points */ - void setInputTarget(typename pcl::PointCloud::Ptr input); + /* Set the input map points */ + void setInputTarget(typename pcl::PointCloud::Ptr input); - /* Compute and get fitness score */ - double getFitnessScore(double max_range = DBL_MAX); + /* Compute and get fitness score */ + double getFitnessScore(double max_range = DBL_MAX); - void updateVoxelGrid(typename pcl::PointCloud::Ptr new_cloud); + void updateVoxelGrid(typename pcl::PointCloud::Ptr new_cloud); protected: - void computeTransformation(const Eigen::Matrix &guess); + void computeTransformation(const Eigen::Matrix &guess); - using Registration::transformation_epsilon_; - using Registration::max_iterations_; - using Registration::source_cloud_; - using Registration::trans_cloud_; - using Registration::converged_; - using Registration::nr_iterations_; - using Registration::final_transformation_; - using Registration::transformation_; - using Registration::previous_transformation_; - using Registration::target_cloud_updated_; - using Registration::target_cloud_; + using Registration::transformation_epsilon_; + using Registration::max_iterations_; + using Registration::source_cloud_; + using Registration::trans_cloud_; + using Registration::converged_; + using Registration::nr_iterations_; + using Registration::final_transformation_; + using Registration::transformation_; + using Registration::previous_transformation_; + using Registration::target_cloud_updated_; + using Registration::target_cloud_; private: - //Copied from ndt.h + //Copied from ndt.h double auxilaryFunction_PsiMT (double a, double f_a, double f_0, double g_0, double mu = 1.e-4); //Copied from ndt.h double auxilaryFunction_dPsiMT (double g_a, double g_0, double mu = 1.e-4); double updateIntervalMT (double &a_l, double &f_l, double &g_l, - double &a_u, double &f_u, double &g_u, - double a_t, double f_t, double g_t); + double &a_u, double &f_u, double &g_u, + double a_t, double f_t, double g_t); double trialValueSelectionMT (double a_l, double f_l, double g_l, - double a_u, double f_u, double g_u, - double a_t, double f_t, double g_t); + double a_u, double f_u, double g_u, + double a_t, double f_t, double g_t); - void computeAngleDerivatives(Eigen::Matrix pose, bool compute_hessian = true); + void computeAngleDerivatives(Eigen::Matrix pose, bool compute_hessian = true); - double computeStepLengthMT(const Eigen::Matrix &x, Eigen::Matrix &step_dir, - double step_init, double step_max, double step_min, double &score, - Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - typename pcl::PointCloud &trans_cloud); + double computeStepLengthMT(const Eigen::Matrix &x, Eigen::Matrix &step_dir, + double step_init, double step_max, double step_min, double &score, + Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, + typename pcl::PointCloud &trans_cloud); - void computeHessian(Eigen::Matrix &hessian, typename pcl::PointCloud &trans_cloud, Eigen::Matrix &p); + void computeHessian(Eigen::Matrix &hessian, typename pcl::PointCloud &trans_cloud, Eigen::Matrix &p); - double computeDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - typename pcl::PointCloud &trans_cloud, - Eigen::Matrix pose, bool compute_hessian = true); - void computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix &point_gradient, Eigen::Matrix &point_hessian, bool computeHessian = true); - double updateDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, - Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, bool compute_hessian = true); - void updateHessian(Eigen::Matrix &hessian, - Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, - Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv); + double computeDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, + typename pcl::PointCloud &trans_cloud, + Eigen::Matrix pose, bool compute_hessian = true); + void computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix &point_gradient, Eigen::Matrix &point_hessian, bool computeHessian = true); + double updateDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, + Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, bool compute_hessian = true); + void updateHessian(Eigen::Matrix &hessian, + Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv); - double gauss_d1_, gauss_d2_; - double outlier_ratio_; - Eigen::Vector3d j_ang_a_, j_ang_b_, j_ang_c_, j_ang_d_, j_ang_e_, j_ang_f_, j_ang_g_, j_ang_h_; + double gauss_d1_, gauss_d2_; + double outlier_ratio_; + Eigen::Vector3d j_ang_a_, j_ang_b_, j_ang_c_, j_ang_d_, j_ang_e_, j_ang_f_, j_ang_g_, j_ang_h_; - Eigen::Vector3d h_ang_a2_, h_ang_a3_, - h_ang_b2_, h_ang_b3_, - h_ang_c2_, h_ang_c3_, - h_ang_d1_, h_ang_d2_, h_ang_d3_, - h_ang_e1_, h_ang_e2_, h_ang_e3_, - h_ang_f1_, h_ang_f2_, h_ang_f3_; + Eigen::Vector3d h_ang_a2_, h_ang_a3_, + h_ang_b2_, h_ang_b3_, + h_ang_c2_, h_ang_c3_, + h_ang_d1_, h_ang_d2_, h_ang_d3_, + h_ang_e1_, h_ang_e2_, h_ang_e3_, + h_ang_f1_, h_ang_f2_, h_ang_f3_; - double step_size_; - float resolution_; - double trans_probability_; + double step_size_; + float resolution_; + double trans_probability_; - int real_iterations_; + int real_iterations_; - VoxelGrid voxel_grid_; + VoxelGrid voxel_grid_; }; } diff --git a/core_perception/ndt_cpu/include/ndt_cpu/Octree.h b/core_perception/ndt_cpu/include/ndt_cpu/Octree.h index eeef1f0d37c..6045118e0e7 100644 --- a/core_perception/ndt_cpu/include/ndt_cpu/Octree.h +++ b/core_perception/ndt_cpu/include/ndt_cpu/Octree.h @@ -17,88 +17,88 @@ template class Octree { public: - Octree(); + Octree(); - /* Input is a vector of boundaries and ptsum of the voxel grid - * Those boundaries is needed since the number of actually occupied voxels may be - * much smaller than reserved number of voxels */ - void setInput(std::vector occupied_voxels, typename pcl::PointCloud::Ptr point_cloud); + /* Input is a vector of boundaries and ptsum of the voxel grid + * Those boundaries is needed since the number of actually occupied voxels may be + * much smaller than reserved number of voxels */ + void setInput(std::vector occupied_voxels, typename pcl::PointCloud::Ptr point_cloud); - void update(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud); + void update(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud); - Eigen::Matrix nearestOctreeNode(PointSourceType q); + Eigen::Matrix nearestOctreeNode(PointSourceType q); private: - typedef struct { - float lx, ux; - float ly, uy; - float lz, uz; - Eigen::Vector3d centroid; - int point_num; - } OctreeNode; + typedef struct { + float lx, ux; + float ly, uy; + float lz, uz; + Eigen::Vector3d centroid; + int point_num; + } OctreeNode; - typedef struct { - int lower_x, upper_x; - int lower_y, upper_y; - int lower_z, upper_z; - } OctreeLevelBoundaries; + typedef struct { + int lower_x, upper_x; + int lower_y, upper_y; + int lower_z, upper_z; + } OctreeLevelBoundaries; - typedef struct { - int x, y, z; - } OctreeLevelDim; + typedef struct { + int x, y, z; + } OctreeLevelDim; - // Convert from 3d indexes and level of the tree node to the actual index in the array - int index2id(int idx, int idy, int idz, int level); - int index2id(int idx, int idy, int idz, OctreeLevelBoundaries bounds, OctreeLevelDim dims); + // Convert from 3d indexes and level of the tree node to the actual index in the array + int index2id(int idx, int idy, int idz, int level); + int index2id(int idx, int idy, int idz, OctreeLevelBoundaries bounds, OctreeLevelDim dims); - // Convert from the index in the array to the 3d indexes of the tree node - Eigen::Vector3i id2index(int id, int level); - Eigen::Vector3i id2index(int id, OctreeLevelBoundaries bounds, OctreeLevelDim dims); + // Convert from the index in the array to the 3d indexes of the tree node + Eigen::Vector3i id2index(int id, int level); + Eigen::Vector3i id2index(int id, OctreeLevelBoundaries bounds, OctreeLevelDim dims); - void buildLevel(int level); + void buildLevel(int level); - bool isOccupied(int node_id, int level); + bool isOccupied(int node_id, int level); - bool isOccupied(std::vector occupancy, int node_id); + bool isOccupied(std::vector occupancy, int node_id); - void setOccupied(int node_id, int level); + void setOccupied(int node_id, int level); - void setOccupied(std::vector &occupancy, int node_id); + void setOccupied(std::vector &occupancy, int node_id); - void updateBoundaries(std::vector new_voxels); + void updateBoundaries(std::vector new_voxels); - int roundUp(int input, int factor); - int roundDown(int input, int factor); + int roundUp(int input, int factor); + int roundDown(int input, int factor); - int div(int input, int divisor); + int div(int input, int divisor); - void updateOctreeContent(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud); + void updateOctreeContent(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud); - double dist(OctreeNode node, PointSourceType q); + double dist(OctreeNode node, PointSourceType q); - /* Three functions to search for the nearest neighbor of a point */ + /* Three functions to search for the nearest neighbor of a point */ - void initRange(PointSourceType q, double &min_range, int ¤t_nn_voxel); + void initRange(PointSourceType q, double &min_range, int ¤t_nn_voxel); - void goUp(Eigen::Matrix tree_node, PointSourceType q, double &min_range, int ¤t_nn_voxel); + void goUp(Eigen::Matrix tree_node, PointSourceType q, double &min_range, int ¤t_nn_voxel); - void goDown(Eigen::Matrix tree_node, PointSourceType q, double &min_range, int ¤t_nn_voxel); + void goDown(Eigen::Matrix tree_node, PointSourceType q, double &min_range, int ¤t_nn_voxel); - boost::shared_ptr > > octree_; - boost::shared_ptr > reserved_size_; - boost::shared_ptr > dimension_; + boost::shared_ptr > > octree_; + boost::shared_ptr > reserved_size_; + boost::shared_ptr > dimension_; - /* Used for checking if an octree node is occupied or not - * If an octree node is occupied (containing some points), - * then the corresponding bit is set - */ - boost::shared_ptr > > occupancy_check_; + /* Used for checking if an octree node is occupied or not + * If an octree node is occupied (containing some points), + * then the corresponding bit is set + */ + boost::shared_ptr > > occupancy_check_; - int leaf_x_, leaf_y_, leaf_z_; // Number of voxels contained in each leaf + int leaf_x_, leaf_y_, leaf_z_; // Number of voxels contained in each leaf - static const int MAX_BX_ = 8; - static const int MAX_BY_ = 8; - static const int MAX_BZ_ = 4; + static const int MAX_BX_ = 8; + static const int MAX_BY_ = 8; + static const int MAX_BZ_ = 4; }; } diff --git a/core_perception/ndt_cpu/include/ndt_cpu/Registration.h b/core_perception/ndt_cpu/include/ndt_cpu/Registration.h index a22b1e6775d..1e447441daf 100644 --- a/core_perception/ndt_cpu/include/ndt_cpu/Registration.h +++ b/core_perception/ndt_cpu/include/ndt_cpu/Registration.h @@ -11,60 +11,60 @@ namespace cpu { template class Registration { public: - Registration(); + Registration(); - void align(const Eigen::Matrix &guess); + void align(const Eigen::Matrix &guess); - void align(typename pcl::PointCloud &output, const Eigen::Matrix &guess); + void align(typename pcl::PointCloud &output, const Eigen::Matrix &guess); - void setTransformationEpsilon(double trans_eps); + void setTransformationEpsilon(double trans_eps); - double getTransformationEpsilon() const; + double getTransformationEpsilon() const; - void setMaximumIterations(int max_itr); + void setMaximumIterations(int max_itr); - int getMaximumIterations() const; + int getMaximumIterations() const; - Eigen::Matrix getFinalTransformation() const; + Eigen::Matrix getFinalTransformation() const; - /* Set input Scanned point cloud. - * Simply set the point cloud input_ */ - void setInputSource(typename pcl::PointCloud::Ptr input); + /* Set input Scanned point cloud. + * Simply set the point cloud input_ */ + void setInputSource(typename pcl::PointCloud::Ptr input); - /* Set input reference map point cloud. - * Set the target point cloud ptr target_cloud_ */ - void setInputTarget(typename pcl::PointCloud::Ptr input); + /* Set input reference map point cloud. + * Set the target point cloud ptr target_cloud_ */ + void setInputTarget(typename pcl::PointCloud::Ptr input); - int getFinalNumIteration() const; + int getFinalNumIteration() const; - bool hasConverged() const; + bool hasConverged() const; - void updateInputTarget(typename pcl::PointCloud::Ptr new_cloud); + void updateInputTarget(typename pcl::PointCloud::Ptr new_cloud); - virtual ~Registration(); + virtual ~Registration(); protected: - virtual void computeTransformation(const Eigen::Matrix &guess); + virtual void computeTransformation(const Eigen::Matrix &guess); - double transformation_epsilon_; - int max_iterations_; + double transformation_epsilon_; + int max_iterations_; - //Original scanned point clouds - typename pcl::PointCloud::Ptr source_cloud_; + //Original scanned point clouds + typename pcl::PointCloud::Ptr source_cloud_; - //Transformed point clouds - typename pcl::PointCloud trans_cloud_; + //Transformed point clouds + typename pcl::PointCloud trans_cloud_; - bool converged_; - int nr_iterations_; + bool converged_; + int nr_iterations_; - Eigen::Matrix final_transformation_, transformation_, previous_transformation_; + Eigen::Matrix final_transformation_, transformation_, previous_transformation_; - bool target_cloud_updated_; + bool target_cloud_updated_; - // Reference map point - typename pcl::PointCloud::Ptr target_cloud_; + // Reference map point + typename pcl::PointCloud::Ptr target_cloud_; }; } diff --git a/core_perception/ndt_cpu/include/ndt_cpu/SymmetricEigenSolver.h b/core_perception/ndt_cpu/include/ndt_cpu/SymmetricEigenSolver.h index 78ed8be7854..67e8d77735a 100644 --- a/core_perception/ndt_cpu/include/ndt_cpu/SymmetricEigenSolver.h +++ b/core_perception/ndt_cpu/include/ndt_cpu/SymmetricEigenSolver.h @@ -10,265 +10,265 @@ namespace cpu { class SymmetricEigensolver3x3 { public: - SymmetricEigensolver3x3(); + SymmetricEigensolver3x3(); - SymmetricEigensolver3x3(const Eigen::Matrix3d input_matrix); + SymmetricEigensolver3x3(const Eigen::Matrix3d input_matrix); - void compute(); + void compute(); - Eigen::Vector3d eigenvalues(); + Eigen::Vector3d eigenvalues(); - Eigen::Matrix3d eigenvectors(); + Eigen::Matrix3d eigenvectors(); private: - void computeEigenvector0(double a00, double a01, double a02, double a11, double a12, double a22, int i0); + void computeEigenvector0(double a00, double a01, double a02, double a11, double a12, double a22, int i0); - void computeEigenvector1(double a00, double a01, double a02, double a11, double a12, double a22, int i0, int i1); + void computeEigenvector1(double a00, double a01, double a02, double a11, double a12, double a22, int i0, int i1); - void computeEigenvector2(int i0, int i1, int i2); + void computeEigenvector2(int i0, int i1, int i2); - void computeOrthogonalComplement(Eigen::Vector3d &w, Eigen::Vector3d &u, Eigen::Vector3d &v); + void computeOrthogonalComplement(Eigen::Vector3d &w, Eigen::Vector3d &u, Eigen::Vector3d &v); - Eigen::Vector3d cross(Eigen::Vector3d u, Eigen::Vector3d v); + Eigen::Vector3d cross(Eigen::Vector3d u, Eigen::Vector3d v); - Eigen::Matrix3d input_; - Eigen::Matrix3d evecs_; - Eigen::Vector3d evals_; + Eigen::Matrix3d input_; + Eigen::Matrix3d evecs_; + Eigen::Vector3d evals_; }; SymmetricEigensolver3x3::SymmetricEigensolver3x3() { - input_.setZero(); - evecs_.setZero(); - evals_.setZero(); + input_.setZero(); + evecs_.setZero(); + evals_.setZero(); } SymmetricEigensolver3x3::SymmetricEigensolver3x3(const Eigen::Matrix3d input_matrix) { - input_ = input_matrix; - evecs_.setZero(); - evals_.setZero(); + input_ = input_matrix; + evecs_.setZero(); + evals_.setZero(); } void SymmetricEigensolver3x3::compute() { - double a00 = input_(0, 0); - double a01 = input_(0, 1); - double a02 = input_(0, 2); - double a11 = input_(1, 1); - double a12 = input_(1, 2); - double a22 = input_(2, 2); - - double max0 = (fabs(a00) > fabs(a01)) ? fabs(a00) : fabs(a01); - double max1 = (fabs(a02) > fabs(a11)) ? fabs(a02) : fabs(a11); - double max2 = (fabs(a12) > fabs(a22)) ? fabs(a12) : fabs(a22); - - double maxAbsElement = (max0 > max1) ? max0 : max1; - - maxAbsElement = (maxAbsElement > max2) ? maxAbsElement : max2; - - if (maxAbsElement == 0.0) { - evecs_.setIdentity(); - evals_.setZero(); - - return; - } - - double invMaxAbsElement = 1.0 / maxAbsElement; - - a00 *= invMaxAbsElement; - a01 *= invMaxAbsElement; - a02 *= invMaxAbsElement; - a11 *= invMaxAbsElement; - a12 *= invMaxAbsElement; - a22 *= invMaxAbsElement; - - double norm = a01 * a01 + a02 * a02 + a12 * a12; - - if (norm > 0.0) { - double traceDiv3 = (a00 + a11 + a22) / 3.0; - double b00 = a00 - traceDiv3; - double b11 = a11 - traceDiv3; - double b22 = a22 - traceDiv3; - double denom = sqrt((b00 * b00 + b11 * b11 + b22 * b22 + norm * 2.0) / 6.0); - double c00 = b11 * b22 - a12 * a12; - double c01 = a01 * b22 - a12 * a02; - double c02 = a01 * a12 - b11 * a02; - double det = (b00 * c00 - a01 * c01 + a02 * c02) / (denom * denom * denom); - double halfDet = det * 0.5; - - halfDet = (halfDet > -1.0) ? halfDet : -1.0; - halfDet = (halfDet < 1.0) ? halfDet : 1.0; - - double angle = acos(halfDet) / 3.0; - double beta2 = cos(angle) * 2.0; - double beta0 = cos(angle + M_PI * 2.0 / 3.0) * 2.0; - double beta1 = -(beta0 + beta2); - - evals_(0) = traceDiv3 + denom * beta0; - evals_(1) = traceDiv3 + denom * beta1; - evals_(2) = traceDiv3 + denom * beta2; - - int i0, i2, i1 = 1; - - if (halfDet >= 0.0) { - i0 = 2; - i2 = 0; - } else { - i0 = 0; - i2 = 2; - } - - computeEigenvector0(a00, a01, a02, a11, a12, a22, i0); - computeEigenvector1(a00, a01, a02, a11, a12, a22, i0, i1); - computeEigenvector2(i0, i1, i2); - - } else { - evals_(0) = a00; - evals_(1) = a11; - evals_(2) = a22; - evecs_.setIdentity(); - } - - evals_ *= maxAbsElement; + double a00 = input_(0, 0); + double a01 = input_(0, 1); + double a02 = input_(0, 2); + double a11 = input_(1, 1); + double a12 = input_(1, 2); + double a22 = input_(2, 2); + + double max0 = (fabs(a00) > fabs(a01)) ? fabs(a00) : fabs(a01); + double max1 = (fabs(a02) > fabs(a11)) ? fabs(a02) : fabs(a11); + double max2 = (fabs(a12) > fabs(a22)) ? fabs(a12) : fabs(a22); + + double maxAbsElement = (max0 > max1) ? max0 : max1; + + maxAbsElement = (maxAbsElement > max2) ? maxAbsElement : max2; + + if (maxAbsElement == 0.0) { + evecs_.setIdentity(); + evals_.setZero(); + + return; + } + + double invMaxAbsElement = 1.0 / maxAbsElement; + + a00 *= invMaxAbsElement; + a01 *= invMaxAbsElement; + a02 *= invMaxAbsElement; + a11 *= invMaxAbsElement; + a12 *= invMaxAbsElement; + a22 *= invMaxAbsElement; + + double norm = a01 * a01 + a02 * a02 + a12 * a12; + + if (norm > 0.0) { + double traceDiv3 = (a00 + a11 + a22) / 3.0; + double b00 = a00 - traceDiv3; + double b11 = a11 - traceDiv3; + double b22 = a22 - traceDiv3; + double denom = sqrt((b00 * b00 + b11 * b11 + b22 * b22 + norm * 2.0) / 6.0); + double c00 = b11 * b22 - a12 * a12; + double c01 = a01 * b22 - a12 * a02; + double c02 = a01 * a12 - b11 * a02; + double det = (b00 * c00 - a01 * c01 + a02 * c02) / (denom * denom * denom); + double halfDet = det * 0.5; + + halfDet = (halfDet > -1.0) ? halfDet : -1.0; + halfDet = (halfDet < 1.0) ? halfDet : 1.0; + + double angle = acos(halfDet) / 3.0; + double beta2 = cos(angle) * 2.0; + double beta0 = cos(angle + M_PI * 2.0 / 3.0) * 2.0; + double beta1 = -(beta0 + beta2); + + evals_(0) = traceDiv3 + denom * beta0; + evals_(1) = traceDiv3 + denom * beta1; + evals_(2) = traceDiv3 + denom * beta2; + + int i0, i2, i1 = 1; + + if (halfDet >= 0.0) { + i0 = 2; + i2 = 0; + } else { + i0 = 0; + i2 = 2; + } + + computeEigenvector0(a00, a01, a02, a11, a12, a22, i0); + computeEigenvector1(a00, a01, a02, a11, a12, a22, i0, i1); + computeEigenvector2(i0, i1, i2); + + } else { + evals_(0) = a00; + evals_(1) = a11; + evals_(2) = a22; + evecs_.setIdentity(); + } + + evals_ *= maxAbsElement; } Eigen::Vector3d SymmetricEigensolver3x3::eigenvalues() { - return evals_; + return evals_; } Eigen::Matrix3d SymmetricEigensolver3x3::eigenvectors() { - return evecs_; + return evecs_; } void SymmetricEigensolver3x3::computeEigenvector0(double a00, double a01, double a02, double a11, double a12, double a22, int i0) { - Eigen::Matrix3d row_mat; - double eval0 = evals_(i0); + Eigen::Matrix3d row_mat; + double eval0 = evals_(i0); - row_mat(0, 0) = a00 - eval0; - row_mat(0, 1) = a01; - row_mat(0, 2) = a02; - row_mat(1, 0) = a01; - row_mat(1, 1) = a11 - eval0; - row_mat(1, 2) = a12; - row_mat(2, 0) = a02; - row_mat(2, 1) = a12; - row_mat(2, 2) = a22 - eval0; + row_mat(0, 0) = a00 - eval0; + row_mat(0, 1) = a01; + row_mat(0, 2) = a02; + row_mat(1, 0) = a01; + row_mat(1, 1) = a11 - eval0; + row_mat(1, 2) = a12; + row_mat(2, 0) = a02; + row_mat(2, 1) = a12; + row_mat(2, 2) = a22 - eval0; - //row0 is r0xr1, row1 is r0xr2, row2 is r1xr2 - Eigen::Matrix3d rxr; + //row0 is r0xr1, row1 is r0xr2, row2 is r1xr2 + Eigen::Matrix3d rxr; - rxr.row(0) = cross(row_mat.row(0), row_mat.row(1)); - rxr.row(1) = cross(row_mat.row(0), row_mat.row(2)); - rxr.row(2) = cross(row_mat.row(1), row_mat.row(2)); + rxr.row(0) = cross(row_mat.row(0), row_mat.row(1)); + rxr.row(1) = cross(row_mat.row(0), row_mat.row(2)); + rxr.row(2) = cross(row_mat.row(1), row_mat.row(2)); - double d0 = rxr(0, 0) * rxr(0, 0) + rxr(0, 1) * rxr(0, 1) * rxr(0, 2) * rxr(0, 2); - double d1 = rxr(1, 0) * rxr(1, 0) + rxr(1, 1) * rxr(1, 1) * rxr(1, 2) * rxr(1, 2); - double d2 = rxr(2, 0) * rxr(2, 0) + rxr(2, 1) * rxr(2, 1) * rxr(2, 2) * rxr(2, 2); + double d0 = rxr(0, 0) * rxr(0, 0) + rxr(0, 1) * rxr(0, 1) * rxr(0, 2) * rxr(0, 2); + double d1 = rxr(1, 0) * rxr(1, 0) + rxr(1, 1) * rxr(1, 1) * rxr(1, 2) * rxr(1, 2); + double d2 = rxr(2, 0) * rxr(2, 0) + rxr(2, 1) * rxr(2, 1) * rxr(2, 2) * rxr(2, 2); - double dmax = (d0 > d1) ? d0 : d1; - int imax = (d0 > d1) ? 0 : 1; + double dmax = (d0 > d1) ? d0 : d1; + int imax = (d0 > d1) ? 0 : 1; - dmax = (d2 > dmax) ? d2 : dmax; - imax = (d2 > dmax) ? 2 : imax; + dmax = (d2 > dmax) ? d2 : dmax; + imax = (d2 > dmax) ? 2 : imax; - evecs_.col(i0) = rxr.row(imax) / sqrt(dmax); + evecs_.col(i0) = rxr.row(imax) / sqrt(dmax); } void SymmetricEigensolver3x3::computeEigenvector1(double a00, double a01, double a02, double a11, double a12, double a22, int i0, int i1) { - Eigen::Vector3d u, v; - Eigen::Vector3d evec0 = evecs_.col(i0); + Eigen::Vector3d u, v; + Eigen::Vector3d evec0 = evecs_.col(i0); - computeOrthogonalComplement(evec0, u, v); + computeOrthogonalComplement(evec0, u, v); - Eigen::Vector3d au, av; - double t0, t1, t2; - double eval1 = evals_(i1); + Eigen::Vector3d au, av; + double t0, t1, t2; + double eval1 = evals_(i1); - t0 = u(0); - t1 = u(1); - t2 = u(2); + t0 = u(0); + t1 = u(1); + t2 = u(2); - au(0) = (a00 - eval1) * t0 + a01 * t1 + a02 * t2; - au(1) = a01 * t0 + (a11 - eval1) * t1 + a12 * t2; - au(2) = a02 * t0 + a12 * t1 + (a22 - eval1) * t2; + au(0) = (a00 - eval1) * t0 + a01 * t1 + a02 * t2; + au(1) = a01 * t0 + (a11 - eval1) * t1 + a12 * t2; + au(2) = a02 * t0 + a12 * t1 + (a22 - eval1) * t2; - t0 = v(0); - t1 = v(1); - t2 = v(2); + t0 = v(0); + t1 = v(1); + t2 = v(2); - av(0) = (a00 - eval1) * t0 + a01 * t1 + a02 * t2; - av(1) = a01 * t0 + (a11 - eval1) * t1 + a12 * t2; - av(2) = a02 * t0 + a12 * t1 + (a22 - eval1) * t2; + av(0) = (a00 - eval1) * t0 + a01 * t1 + a02 * t2; + av(1) = a01 * t0 + (a11 - eval1) * t1 + a12 * t2; + av(2) = a02 * t0 + a12 * t1 + (a22 - eval1) * t2; - double m00 = u(0) * au(0) + u(1) * au(1) + u(2) * au(2); - double m01 = u(0) * av(0) + u(1) * av(1) + u(2) * av(2); - double m11 = v(0) * av(0) + v(1) * av(1) + v(2) * av(2); + double m00 = u(0) * au(0) + u(1) * au(1) + u(2) * au(2); + double m01 = u(0) * av(0) + u(1) * av(1) + u(2) * av(2); + double m11 = v(0) * av(0) + v(1) * av(1) + v(2) * av(2); - double abs_m00 = fabs(m00); - double abs_m01 = fabs(m01); - double abs_m11 = fabs(m11); + double abs_m00 = fabs(m00); + double abs_m01 = fabs(m01); + double abs_m11 = fabs(m11); - if (abs_m00 > 0 || abs_m01 > 0 || abs_m11 > 0) { - double u_mult = (abs_m00 >= abs_m11) ? m01 : m11; - double v_mult = (abs_m00 >= abs_m11) ? m00 : m01; + if (abs_m00 > 0 || abs_m01 > 0 || abs_m11 > 0) { + double u_mult = (abs_m00 >= abs_m11) ? m01 : m11; + double v_mult = (abs_m00 >= abs_m11) ? m00 : m01; - bool res = fabs(u_mult) >= fabs(v_mult); - double *large = (res) ? &u_mult : &v_mult; - double *small = (res) ? &v_mult : &u_mult; + bool res = fabs(u_mult) >= fabs(v_mult); + double *large = (res) ? &u_mult : &v_mult; + double *small = (res) ? &v_mult : &u_mult; - *small /= (*large); - *large = 1.0 / sqrt(1.0 + (*small) * (*small)); - *small *= (*large); + *small /= (*large); + *large = 1.0 / sqrt(1.0 + (*small) * (*small)); + *small *= (*large); - u *= u_mult; - v *= v_mult; - evecs_.col(i1) = u - v; - } else { - evecs_.col(i1) = u; - } + u *= u_mult; + v *= v_mult; + evecs_.col(i1) = u - v; + } else { + evecs_.col(i1) = u; + } } Eigen::Vector3d SymmetricEigensolver3x3::cross(Eigen::Vector3d u, Eigen::Vector3d v) { - Eigen::Vector3d out; + Eigen::Vector3d out; - out(0) = u(1) * v(2) - u(2) * v(1); - out(1) = u(2) * v(0) - u(0) * v(2); - out(2) = u(0) * v(1) - u(1) * v(0); + out(0) = u(1) * v(2) - u(2) * v(1); + out(1) = u(2) * v(0) - u(0) * v(2); + out(2) = u(0) * v(1) - u(1) * v(0); - return out; + return out; } void SymmetricEigensolver3x3::computeOrthogonalComplement(Eigen::Vector3d &w, Eigen::Vector3d &u, Eigen::Vector3d &v) { - bool c = (fabs(w(0)) > fabs(w(1))); + bool c = (fabs(w(0)) > fabs(w(1))); - double inv_length = (c) ? (1.0 / sqrt(w(0) * w(0) + w(2) * w(2))) : (1.0 / sqrt(w(1) * w(1) + w(2) * w(2))); + double inv_length = (c) ? (1.0 / sqrt(w(0) * w(0) + w(2) * w(2))) : (1.0 / sqrt(w(1) * w(1) + w(2) * w(2))); - u(0) = (c) ? -w(2) * inv_length : 0.0; - u(1) = (c) ? 0.0 : w(2) * inv_length; - u(2) = (c) ? w(0) * inv_length : -w(1) * inv_length; + u(0) = (c) ? -w(2) * inv_length : 0.0; + u(1) = (c) ? 0.0 : w(2) * inv_length; + u(2) = (c) ? w(0) * inv_length : -w(1) * inv_length; - v = cross(w, u); + v = cross(w, u); } void SymmetricEigensolver3x3::computeEigenvector2(int i0, int i1, int i2) { - Eigen::Vector3d evec0 = evecs_.col(i0); - Eigen::Vector3d evec1 = evecs_.col(i1); + Eigen::Vector3d evec0 = evecs_.col(i0); + Eigen::Vector3d evec1 = evecs_.col(i1); - evecs_.col(i2) = cross(evec0, evec1); + evecs_.col(i2) = cross(evec0, evec1); } } diff --git a/core_perception/ndt_cpu/include/ndt_cpu/VoxelGrid.h b/core_perception/ndt_cpu/include/ndt_cpu/VoxelGrid.h index 36f69ee027d..927c9bc37d8 100644 --- a/core_perception/ndt_cpu/include/ndt_cpu/VoxelGrid.h +++ b/core_perception/ndt_cpu/include/ndt_cpu/VoxelGrid.h @@ -16,137 +16,137 @@ namespace cpu { template class VoxelGrid { public: - VoxelGrid(); + VoxelGrid(); - /* Set input points */ - void setInput(typename pcl::PointCloud::Ptr input); + /* Set input points */ + void setInput(typename pcl::PointCloud::Ptr input); - /* For each input point, search for voxels whose distance between their centroids and - * the input point are less than radius. - * The output is a list of candidate voxel ids */ - void radiusSearch(PointSourceType query_point, float radius, std::vector &voxel_ids, int max_nn = INT_MAX); + /* For each input point, search for voxels whose distance between their centroids and + * the input point are less than radius. + * The output is a list of candidate voxel ids */ + void radiusSearch(PointSourceType query_point, float radius, std::vector &voxel_ids, int max_nn = INT_MAX); - int getVoxelNum() const; + int getVoxelNum() const; - float getMaxX() const; - float getMaxY() const; - float getMaxZ() const; + float getMaxX() const; + float getMaxY() const; + float getMaxZ() const; - float getMinX() const; - float getMinY() const; - float getMinZ() const; + float getMinX() const; + float getMinY() const; + float getMinZ() const; - float getVoxelX() const; - float getVoxelY() const; - float getVoxelZ() const; + float getVoxelX() const; + float getVoxelY() const; + float getVoxelZ() const; - int getMaxBX() const; - int getMaxBY() const; - int getMaxBZ() const; + int getMaxBX() const; + int getMaxBY() const; + int getMaxBZ() const; - int getMinBX() const; - int getMinBY() const; - int getMinBZ() const; + int getMinBX() const; + int getMinBY() const; + int getMinBZ() const; - int getVgridX() const; - int getVgridY() const; - int getVgridZ() const; + int getVgridX() const; + int getVgridY() const; + int getVgridZ() const; - void setLeafSize(float voxel_x, float voxel_y, float voxel_z); + void setLeafSize(float voxel_x, float voxel_y, float voxel_z); - /* Searching for the nearest point of each input query point. - * Return the distance between the query point and its nearest neighbor. - * If the distance is larger than max_range, then return DBL_MAX. */ + /* Searching for the nearest point of each input query point. + * Return the distance between the query point and its nearest neighbor. + * If the distance is larger than max_range, then return DBL_MAX. */ - double nearestNeighborDistance(PointSourceType query_point, float max_range); + double nearestNeighborDistance(PointSourceType query_point, float max_range); - Eigen::Vector3d getCentroid(int voxel_id) const; - Eigen::Matrix3d getCovariance(int voxel_id) const; - Eigen::Matrix3d getInverseCovariance(int voxel_id) const; + Eigen::Vector3d getCentroid(int voxel_id) const; + Eigen::Matrix3d getCovariance(int voxel_id) const; + Eigen::Matrix3d getInverseCovariance(int voxel_id) const; - void update(typename pcl::PointCloud::Ptr new_cloud); + void update(typename pcl::PointCloud::Ptr new_cloud); private: - typedef struct { - int x, y, z; - } OctreeDim; + typedef struct { + int x, y, z; + } OctreeDim; - /* Construct the voxel grid and the build the octree. */ - void initialize(); + /* Construct the voxel grid and the build the octree. */ + void initialize(); - /* Put points into voxels */ - void scatterPointsToVoxelGrid(); + /* Put points into voxels */ + void scatterPointsToVoxelGrid(); - /* Compute centroids and covariances of voxels. */ - void computeCentroidAndCovariance(); + /* Compute centroids and covariances of voxels. */ + void computeCentroidAndCovariance(); - /* Find boundaries of input point cloud and compute - * the number of necessary voxels as well as boundaries - * measured in number of leaf size */ - void findBoundaries(); + /* Find boundaries of input point cloud and compute + * the number of necessary voxels as well as boundaries + * measured in number of leaf size */ + void findBoundaries(); - void findBoundaries(typename pcl::PointCloud::Ptr input_cloud, - float &max_x, float &max_y, float &max_z, - float &min_x, float &min_y, float &min_z); + void findBoundaries(typename pcl::PointCloud::Ptr input_cloud, + float &max_x, float &max_y, float &max_z, + float &min_x, float &min_y, float &min_z); - int voxelId(PointSourceType p); + int voxelId(PointSourceType p); - int voxelId(PointSourceType p, - float voxel_x, float voxel_y, float voxel_z, - int min_b_x, int min_b_y, int min_b_z, - int vgrid_x, int vgrid_y, int vgrid_z); + int voxelId(PointSourceType p, + float voxel_x, float voxel_y, float voxel_z, + int min_b_x, int min_b_y, int min_b_z, + int vgrid_x, int vgrid_y, int vgrid_z); - int voxelId(int idx, int idy, int idz, - int min_b_x, int min_b_y, int min_b_z, - int size_x, int size_y, int size_z); + int voxelId(int idx, int idy, int idz, + int min_b_x, int min_b_y, int min_b_z, + int size_x, int size_y, int size_z); - /* Private methods for merging new point cloud to the current point cloud */ - void updateBoundaries(float max_x, float max_y, float max_z, - float min_x, float min_y, float min_z); + /* Private methods for merging new point cloud to the current point cloud */ + void updateBoundaries(float max_x, float max_y, float max_z, + float min_x, float min_y, float min_z); - void updateVoxelContent(typename pcl::PointCloud::Ptr new_cloud); + void updateVoxelContent(typename pcl::PointCloud::Ptr new_cloud); - int nearestVoxel(PointSourceType query_point, Eigen::Matrix boundaries, float max_range); + int nearestVoxel(PointSourceType query_point, Eigen::Matrix boundaries, float max_range); - int roundUp(int input, int factor); + int roundUp(int input, int factor); - int roundDown(int input, int factor); + int roundDown(int input, int factor); - int div(int input, int divisor); + int div(int input, int divisor); - //Coordinate of input points - typename pcl::PointCloud::Ptr source_cloud_; + //Coordinate of input points + typename pcl::PointCloud::Ptr source_cloud_; - int voxel_num_; // Number of voxels - float max_x_, max_y_, max_z_; // Upper bounds of the grid (maximum coordinate) - float min_x_, min_y_, min_z_; // Lower bounds of the grid (minimum coordinate) - float voxel_x_, voxel_y_, voxel_z_; // Leaf size, a.k.a, size of each voxel + int voxel_num_; // Number of voxels + float max_x_, max_y_, max_z_; // Upper bounds of the grid (maximum coordinate) + float min_x_, min_y_, min_z_; // Lower bounds of the grid (minimum coordinate) + float voxel_x_, voxel_y_, voxel_z_; // Leaf size, a.k.a, size of each voxel - int max_b_x_, max_b_y_, max_b_z_; // Upper bounds of the grid, measured in number of voxels - int min_b_x_, min_b_y_, min_b_z_; // Lower bounds of the grid, measured in number of voxels - int vgrid_x_, vgrid_y_, vgrid_z_; // Size of the voxel grid, measured in number of voxels - int min_points_per_voxel_; // Minimum number of points per voxel. If the number of points - // per voxel is less than this number, then the voxel is ignored - // during computation (treated like it contains no point) + int max_b_x_, max_b_y_, max_b_z_; // Upper bounds of the grid, measured in number of voxels + int min_b_x_, min_b_y_, min_b_z_; // Lower bounds of the grid, measured in number of voxels + int vgrid_x_, vgrid_y_, vgrid_z_; // Size of the voxel grid, measured in number of voxels + int min_points_per_voxel_; // Minimum number of points per voxel. If the number of points + // per voxel is less than this number, then the voxel is ignored + // during computation (treated like it contains no point) - boost::shared_ptr > centroid_; // 3x1 Centroid vectors of voxels - boost::shared_ptr > icovariance_; // Inverse covariance matrixes of voxel - boost::shared_ptr > > points_id_; // Indexes of points belong to each voxel - boost::shared_ptr > points_per_voxel_; // Number of points belong to each voxel - // (may differ from size of each vector in points_id_ - // because of changes made during computing covariances - boost::shared_ptr > tmp_centroid_; - boost::shared_ptr > tmp_cov_; + boost::shared_ptr > centroid_; // 3x1 Centroid vectors of voxels + boost::shared_ptr > icovariance_; // Inverse covariance matrixes of voxel + boost::shared_ptr > > points_id_; // Indexes of points belong to each voxel + boost::shared_ptr > points_per_voxel_; // Number of points belong to each voxel + // (may differ from size of each vector in points_id_ + // because of changes made during computing covariances + boost::shared_ptr > tmp_centroid_; + boost::shared_ptr > tmp_cov_; - int real_max_bx_, real_max_by_, real_max_bz_; - int real_min_bx_, real_min_by_, real_min_bz_; + int real_max_bx_, real_max_by_, real_max_bz_; + int real_min_bx_, real_min_by_, real_min_bz_; - Octree octree_; + Octree octree_; - static const int MAX_BX_ = 16; - static const int MAX_BY_ = 16; - static const int MAX_BZ_ = 8; + static const int MAX_BX_ = 16; + static const int MAX_BY_ = 16; + static const int MAX_BZ_ = 8; }; } diff --git a/core_perception/ndt_cpu/src/NormalDistributionsTransform.cpp b/core_perception/ndt_cpu/src/NormalDistributionsTransform.cpp index d0be3382e40..29912333c95 100644 --- a/core_perception/ndt_cpu/src/NormalDistributionsTransform.cpp +++ b/core_perception/ndt_cpu/src/NormalDistributionsTransform.cpp @@ -11,72 +11,72 @@ namespace cpu { template NormalDistributionsTransform::NormalDistributionsTransform() { - gauss_d1_ = gauss_d2_ = 0; - outlier_ratio_ = 0.55; - step_size_ = 0.1; - resolution_ = 1.0f; - trans_probability_ = 0; - - double gauss_c1, gauss_c2, gauss_d3; - - // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] - gauss_c1 = 10.0 * (1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow (resolution_, 3); - gauss_d3 = -log (gauss_c2); - gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3; - gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3) / gauss_d1_); - - transformation_epsilon_ = 0.1; - max_iterations_ = 35; - real_iterations_ = 0; + gauss_d1_ = gauss_d2_ = 0; + outlier_ratio_ = 0.55; + step_size_ = 0.1; + resolution_ = 1.0f; + trans_probability_ = 0; + + double gauss_c1, gauss_c2, gauss_d3; + + // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009] + gauss_c1 = 10.0 * (1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow (resolution_, 3); + gauss_d3 = -log (gauss_c2); + gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3; + gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3) / gauss_d1_); + + transformation_epsilon_ = 0.1; + max_iterations_ = 35; + real_iterations_ = 0; } template void NormalDistributionsTransform::setStepSize(double step_size) { - step_size_ = step_size; + step_size_ = step_size; } template void NormalDistributionsTransform::setResolution(float resolution) { - resolution_ = resolution; + resolution_ = resolution; } template void NormalDistributionsTransform::setOutlierRatio(double olr) { - outlier_ratio_ = olr; + outlier_ratio_ = olr; } template double NormalDistributionsTransform::getStepSize() const { - return step_size_; + return step_size_; } template float NormalDistributionsTransform::getResolution() const { - return resolution_; + return resolution_; } template double NormalDistributionsTransform::getOutlierRatio() const { - return outlier_ratio_; + return outlier_ratio_; } template double NormalDistributionsTransform::getTransformationProbability() const { - return trans_probability_; + return trans_probability_; } template int NormalDistributionsTransform::getRealIterations() { - return real_iterations_; + return real_iterations_; } template @@ -94,624 +94,624 @@ double NormalDistributionsTransform::auxilaryF template void NormalDistributionsTransform::setInputTarget(typename pcl::PointCloud::Ptr input) { - Registration::setInputTarget(input); + Registration::setInputTarget(input); - // Build the voxel grid - if (input->points.size() > 0) { - voxel_grid_.setLeafSize(resolution_, resolution_, resolution_); - voxel_grid_.setInput(input); - } + // Build the voxel grid + if (input->points.size() > 0) { + voxel_grid_.setLeafSize(resolution_, resolution_, resolution_); + voxel_grid_.setInput(input); + } } template void NormalDistributionsTransform::computeTransformation(const Eigen::Matrix &guess) { - nr_iterations_ = 0; - converged_ = false; + nr_iterations_ = 0; + converged_ = false; - double gauss_c1, gauss_c2, gauss_d3; + double gauss_c1, gauss_c2, gauss_d3; - gauss_c1 = 10 * ( 1 - outlier_ratio_); - gauss_c2 = outlier_ratio_ / pow(resolution_, 3); - gauss_d3 = - log(gauss_c2); - gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3; - gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3) / gauss_d1_); + gauss_c1 = 10 * ( 1 - outlier_ratio_); + gauss_c2 = outlier_ratio_ / pow(resolution_, 3); + gauss_d3 = - log(gauss_c2); + gauss_d1_ = -log(gauss_c1 + gauss_c2) - gauss_d3; + gauss_d2_ = -2 * log((-log(gauss_c1 * exp(-0.5) + gauss_c2) - gauss_d3) / gauss_d1_); - if (guess != Eigen::Matrix4f::Identity()) { - final_transformation_ = guess; + if (guess != Eigen::Matrix4f::Identity()) { + final_transformation_ = guess; - pcl::transformPointCloud(*source_cloud_, trans_cloud_, guess); - } + pcl::transformPointCloud(*source_cloud_, trans_cloud_, guess); + } - Eigen::Transform eig_transformation; - eig_transformation.matrix() = final_transformation_; + Eigen::Transform eig_transformation; + eig_transformation.matrix() = final_transformation_; - Eigen::Matrix p, delta_p, score_gradient; - Eigen::Vector3f init_translation = eig_transformation.translation(); - Eigen::Vector3f init_rotation = eig_transformation.rotation().eulerAngles(0, 1, 2); + Eigen::Matrix p, delta_p, score_gradient; + Eigen::Vector3f init_translation = eig_transformation.translation(); + Eigen::Vector3f init_rotation = eig_transformation.rotation().eulerAngles(0, 1, 2); - p << init_translation(0), init_translation(1), init_translation(2), init_rotation(0), init_rotation(1), init_rotation(2); + p << init_translation(0), init_translation(1), init_translation(2), init_rotation(0), init_rotation(1), init_rotation(2); - Eigen::Matrix hessian; + Eigen::Matrix hessian; - double score = 0; - double delta_p_norm; + double score = 0; + double delta_p_norm; - score = computeDerivatives(score_gradient, hessian, trans_cloud_, p); + score = computeDerivatives(score_gradient, hessian, trans_cloud_, p); - int points_number = source_cloud_->points.size(); + int points_number = source_cloud_->points.size(); - while (!converged_) { - previous_transformation_ = transformation_; + while (!converged_) { + previous_transformation_ = transformation_; - Eigen::JacobiSVD > sv(hessian, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::JacobiSVD > sv(hessian, Eigen::ComputeFullU | Eigen::ComputeFullV); - delta_p = sv.solve(-score_gradient); + delta_p = sv.solve(-score_gradient); - delta_p_norm = delta_p.norm(); + delta_p_norm = delta_p.norm(); - if (delta_p_norm == 0 || delta_p_norm != delta_p_norm) { - trans_probability_ = score / static_cast(points_number); - converged_ = delta_p_norm == delta_p_norm; - return; - } + if (delta_p_norm == 0 || delta_p_norm != delta_p_norm) { + trans_probability_ = score / static_cast(points_number); + converged_ = delta_p_norm == delta_p_norm; + return; + } - delta_p.normalize(); - delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, trans_cloud_); - delta_p *= delta_p_norm; + delta_p.normalize(); + delta_p_norm = computeStepLengthMT(p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, trans_cloud_); + delta_p *= delta_p_norm; - transformation_ = (Eigen::Translation(static_cast(delta_p(0)), static_cast(delta_p(1)), static_cast(delta_p(2))) * - Eigen::AngleAxis(static_cast(delta_p(3)), Eigen::Vector3f::UnitX()) * - Eigen::AngleAxis(static_cast(delta_p(4)), Eigen::Vector3f::UnitY()) * - Eigen::AngleAxis(static_cast(delta_p(5)), Eigen::Vector3f::UnitZ())).matrix(); + transformation_ = (Eigen::Translation(static_cast(delta_p(0)), static_cast(delta_p(1)), static_cast(delta_p(2))) * + Eigen::AngleAxis(static_cast(delta_p(3)), Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(delta_p(4)), Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(delta_p(5)), Eigen::Vector3f::UnitZ())).matrix(); - p = p + delta_p; + p = p + delta_p; - //Not update visualizer + //Not update visualizer - if (nr_iterations_ > max_iterations_ || (nr_iterations_ && (std::fabs(delta_p_norm) < transformation_epsilon_))) { - converged_ = true; - } + if (nr_iterations_ > max_iterations_ || (nr_iterations_ && (std::fabs(delta_p_norm) < transformation_epsilon_))) { + converged_ = true; + } - nr_iterations_++; - } + nr_iterations_++; + } - if (source_cloud_->points.size() > 0) { - trans_probability_ = score / static_cast(source_cloud_->points.size()); - } + if (source_cloud_->points.size() > 0) { + trans_probability_ = score / static_cast(source_cloud_->points.size()); + } } template double NormalDistributionsTransform::computeDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - typename pcl::PointCloud &trans_cloud, - Eigen::Matrix pose, bool compute_hessian) + typename pcl::PointCloud &trans_cloud, + Eigen::Matrix pose, bool compute_hessian) { - PointSourceType x_pt, x_trans_pt; - Eigen::Vector3d x, x_trans; - Eigen::Matrix3d c_inv; + PointSourceType x_pt, x_trans_pt; + Eigen::Vector3d x, x_trans; + Eigen::Matrix3d c_inv; - score_gradient.setZero (); - hessian.setZero (); + score_gradient.setZero (); + hessian.setZero (); - //Compute Angle Derivatives - computeAngleDerivatives(pose); + //Compute Angle Derivatives + computeAngleDerivatives(pose); - std::vector neighbor_ids; - Eigen::Matrix point_gradient; - Eigen::Matrix point_hessian; - double score = 0; + std::vector neighbor_ids; + Eigen::Matrix point_gradient; + Eigen::Matrix point_hessian; + double score = 0; - point_gradient.setZero(); - point_gradient.block<3, 3>(0, 0).setIdentity(); - point_hessian.setZero(); + point_gradient.setZero(); + point_gradient.block<3, 3>(0, 0).setIdentity(); + point_hessian.setZero(); - for (int idx = 0; idx < source_cloud_->points.size(); idx++) { - neighbor_ids.clear(); - x_trans_pt = trans_cloud.points[idx]; + for (int idx = 0; idx < source_cloud_->points.size(); idx++) { + neighbor_ids.clear(); + x_trans_pt = trans_cloud.points[idx]; - voxel_grid_.radiusSearch(x_trans_pt, resolution_, neighbor_ids); + voxel_grid_.radiusSearch(x_trans_pt, resolution_, neighbor_ids); - for (int i = 0; i < neighbor_ids.size(); i++) { - int vid = neighbor_ids[i]; + for (int i = 0; i < neighbor_ids.size(); i++) { + int vid = neighbor_ids[i]; - x_pt = source_cloud_->points[idx]; - x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); + x_pt = source_cloud_->points[idx]; + x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); - x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); - x_trans -= voxel_grid_.getCentroid(vid); - c_inv = voxel_grid_.getInverseCovariance(vid); + x_trans -= voxel_grid_.getCentroid(vid); + c_inv = voxel_grid_.getInverseCovariance(vid); - computePointDerivatives(x, point_gradient, point_hessian, compute_hessian); + computePointDerivatives(x, point_gradient, point_hessian, compute_hessian); - score += updateDerivatives(score_gradient, hessian, point_gradient, point_hessian, x_trans, c_inv, compute_hessian); - } - } + score += updateDerivatives(score_gradient, hessian, point_gradient, point_hessian, x_trans, c_inv, compute_hessian); + } + } - return score; + return score; } template void NormalDistributionsTransform::computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix &point_gradient, Eigen::Matrix &point_hessian, bool compute_hessian) { - point_gradient(1, 3) = x.dot(j_ang_a_); - point_gradient(2, 3) = x.dot(j_ang_b_); - point_gradient(0, 4) = x.dot(j_ang_c_); - point_gradient(1, 4) = x.dot(j_ang_d_); - point_gradient(2, 4) = x.dot(j_ang_e_); - point_gradient(0, 5) = x.dot(j_ang_f_); - point_gradient(1, 5) = x.dot(j_ang_g_); - point_gradient(2, 5) = x.dot(j_ang_h_); - - if (compute_hessian) { - Eigen::Vector3d a, b, c, d, e, f; - - a << 0, x.dot(h_ang_a2_), x.dot(h_ang_a3_); - b << 0, x.dot(h_ang_b2_), x.dot(h_ang_b3_); - c << 0, x.dot(h_ang_c2_), x.dot(h_ang_c3_); - d << x.dot(h_ang_d1_), x.dot(h_ang_d2_), x.dot(h_ang_d3_); - e << x.dot(h_ang_e1_), x.dot(h_ang_e2_), x.dot(h_ang_e3_); - f << x.dot(h_ang_f1_), x.dot(h_ang_f2_), x.dot(h_ang_f3_); - - point_hessian.block<3, 1>(9, 3) = a; - point_hessian.block<3, 1>(12, 3) = b; - point_hessian.block<3, 1>(15, 3) = c; - point_hessian.block<3, 1>(9, 4) = b; - point_hessian.block<3, 1>(12, 4) = d; - point_hessian.block<3, 1>(15, 4) = e; - point_hessian.block<3, 1>(9, 5) = c; - point_hessian.block<3, 1>(12, 5) = e; - point_hessian.block<3, 1>(15, 5) = f; - } + point_gradient(1, 3) = x.dot(j_ang_a_); + point_gradient(2, 3) = x.dot(j_ang_b_); + point_gradient(0, 4) = x.dot(j_ang_c_); + point_gradient(1, 4) = x.dot(j_ang_d_); + point_gradient(2, 4) = x.dot(j_ang_e_); + point_gradient(0, 5) = x.dot(j_ang_f_); + point_gradient(1, 5) = x.dot(j_ang_g_); + point_gradient(2, 5) = x.dot(j_ang_h_); + + if (compute_hessian) { + Eigen::Vector3d a, b, c, d, e, f; + + a << 0, x.dot(h_ang_a2_), x.dot(h_ang_a3_); + b << 0, x.dot(h_ang_b2_), x.dot(h_ang_b3_); + c << 0, x.dot(h_ang_c2_), x.dot(h_ang_c3_); + d << x.dot(h_ang_d1_), x.dot(h_ang_d2_), x.dot(h_ang_d3_); + e << x.dot(h_ang_e1_), x.dot(h_ang_e2_), x.dot(h_ang_e3_); + f << x.dot(h_ang_f1_), x.dot(h_ang_f2_), x.dot(h_ang_f3_); + + point_hessian.block<3, 1>(9, 3) = a; + point_hessian.block<3, 1>(12, 3) = b; + point_hessian.block<3, 1>(15, 3) = c; + point_hessian.block<3, 1>(9, 4) = b; + point_hessian.block<3, 1>(12, 4) = d; + point_hessian.block<3, 1>(15, 4) = e; + point_hessian.block<3, 1>(9, 5) = c; + point_hessian.block<3, 1>(12, 5) = e; + point_hessian.block<3, 1>(15, 5) = f; + } } template double NormalDistributionsTransform::updateDerivatives(Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, - Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, bool compute_hessian) + Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, bool compute_hessian) { - Eigen::Vector3d cov_dxd_pi; - double e_x_cov_x = exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); - double score_inc = -gauss_d1_ * e_x_cov_x; + Eigen::Vector3d cov_dxd_pi; + double e_x_cov_x = exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); + double score_inc = -gauss_d1_ * e_x_cov_x; - e_x_cov_x = gauss_d2_ * e_x_cov_x; + e_x_cov_x = gauss_d2_ * e_x_cov_x; - if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) { - return 0.0; - } + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) { + return 0.0; + } - e_x_cov_x *= gauss_d1_; + e_x_cov_x *= gauss_d1_; - for (int i = 0; i < 6; i++) { - cov_dxd_pi = c_inv * point_gradient.col(i); + for (int i = 0; i < 6; i++) { + cov_dxd_pi = c_inv * point_gradient.col(i); - score_gradient(i) += x_trans.dot(cov_dxd_pi) * e_x_cov_x; + score_gradient(i) += x_trans.dot(cov_dxd_pi) * e_x_cov_x; - if (compute_hessian) { - for (int j = 0; j < hessian.cols(); j++) { - hessian(i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) * x_trans.dot(c_inv * point_gradient.col(j)) + - x_trans.dot(c_inv * point_hessian.block<3, 1>(3 * i, j)) + - point_gradient.col(j).dot(cov_dxd_pi)); - } - } - } + if (compute_hessian) { + for (int j = 0; j < hessian.cols(); j++) { + hessian(i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) * x_trans.dot(c_inv * point_gradient.col(j)) + + x_trans.dot(c_inv * point_hessian.block<3, 1>(3 * i, j)) + + point_gradient.col(j).dot(cov_dxd_pi)); + } + } + } - return score_inc; + return score_inc; } template void NormalDistributionsTransform::computeAngleDerivatives(Eigen::Matrix pose, bool compute_hessian) { - double cx, cy, cz, sx, sy, sz; - - if (fabs(pose(3)) < 10e-5) { - cx = 1.0; - sx = 0.0; - } else { - cx = cos(pose(3)); - sx = sin(pose(3)); - } - - if (fabs(pose(4)) < 10e-5) { - cy = 1.0; - sy = 0.0; - } else { - cy = cos(pose(4)); - sy = sin(pose(4)); - } - - if (fabs(pose(5)) < 10e-5) { - cz = 1.0; - sz = 0.0; - } else { - cz = cos(pose(5)); - sz = sin(pose(5)); - } - - j_ang_a_(0) = -sx * sz + cx * sy * cz; - j_ang_a_(1) = -sx * cz - cx * sy * sz; - j_ang_a_(2) = -cx * cy; - - j_ang_b_(0) = cx * sz + sx * sy * cz; - j_ang_b_(1) = cx * cz - sx * sy * sz; - j_ang_b_(2) = -sx * cy; - - j_ang_c_(0) = -sy * cz; - j_ang_c_(1) = sy * sz; - j_ang_c_(2) = cy; - - j_ang_d_(0) = sx * cy * cz; - j_ang_d_(1) = -sx * cy * sz; - j_ang_d_(2) = sx * sy; - - j_ang_e_(0) = -cx * cy * cz; - j_ang_e_(1) = cx * cy * sz; - j_ang_e_(2) = -cx * sy; - - j_ang_f_(0) = -cy * sz; - j_ang_f_(1) = -cy * cz; - j_ang_f_(2) = 0; - - j_ang_g_(0) = cx * cz - sx * sy * sz; - j_ang_g_(1) = -cx * sz - sx * sy * cz; - j_ang_g_(2) = 0; - - j_ang_h_(0) = sx * cz + cx * sy * sz; - j_ang_h_(1) = cx * sy * cz - sx * sz; - j_ang_h_(2) = 0; - - if (compute_hessian) { - h_ang_a2_(0) = -cx * sz - sx * sy * cz; - h_ang_a2_(1) = -cx * cz + sx * sy * sz; - h_ang_a2_(2) = sx * cy; - - h_ang_a3_(0) = -sx * sz + cx * sy * cz; - h_ang_a3_(1) = -cx * sy * sz - sx * cz; - h_ang_a3_(2) = -cx * cy; - - h_ang_b2_(0) = cx * cy * cz; - h_ang_b2_(1) = -cx * cy * sz; - h_ang_b2_(2) = cx * sy; - - h_ang_b3_(0) = sx * cy * cz; - h_ang_b3_(1) = -sx * cy * sz; - h_ang_b3_(2) = sx * sy; - - h_ang_c2_(0) = -sx * cz - cx * sy * sz; - h_ang_c2_(1) = sx * sz - cx * sy * cz; - h_ang_c2_(2) = 0; - - h_ang_c3_(0) = cx * cz - sx * sy * sz; - h_ang_c3_(1) = -sx * sy * cz - cx * sz; - h_ang_c3_(2) = 0; - - h_ang_d1_(0) = -cy * cz; - h_ang_d1_(1) = cy * sz; - h_ang_d1_(2) = sy; - - h_ang_d2_(0) = -sx * sy * cz; - h_ang_d2_(1) = sx * sy * sz; - h_ang_d2_(2) = sx * cy; - - h_ang_d3_(0) = cx * sy * cz; - h_ang_d3_(1) = -cx * sy * sz; - h_ang_d3_(2) = -cx * cy; - - h_ang_e1_(0) = sy * sz; - h_ang_e1_(1) = sy * cz; - h_ang_e1_(2) = 0; - - h_ang_e2_(0) = -sx * cy * sz; - h_ang_e2_(1) = -sx * cy * cz; - h_ang_e2_(2) = 0; - - h_ang_e3_(0) = cx * cy * sz; - h_ang_e3_(1) = cx * cy * cz; - h_ang_e3_(2) = 0; - - h_ang_f1_(0) = -cy * cz; - h_ang_f1_(1) = cy * sz; - h_ang_f1_(2) = 0; - - h_ang_f2_(0) = -cx * sz - sx * sy * cz; - h_ang_f2_(1) = -cx * cz + sx * sy * sz; - h_ang_f2_(2) = 0; - - h_ang_f3_(0) = -sx * sz + cx * sy * cz; - h_ang_f3_(1) = -cx * sy * sz - sx * cz; - h_ang_f3_(2) = 0; - } + double cx, cy, cz, sx, sy, sz; + + if (fabs(pose(3)) < 10e-5) { + cx = 1.0; + sx = 0.0; + } else { + cx = cos(pose(3)); + sx = sin(pose(3)); + } + + if (fabs(pose(4)) < 10e-5) { + cy = 1.0; + sy = 0.0; + } else { + cy = cos(pose(4)); + sy = sin(pose(4)); + } + + if (fabs(pose(5)) < 10e-5) { + cz = 1.0; + sz = 0.0; + } else { + cz = cos(pose(5)); + sz = sin(pose(5)); + } + + j_ang_a_(0) = -sx * sz + cx * sy * cz; + j_ang_a_(1) = -sx * cz - cx * sy * sz; + j_ang_a_(2) = -cx * cy; + + j_ang_b_(0) = cx * sz + sx * sy * cz; + j_ang_b_(1) = cx * cz - sx * sy * sz; + j_ang_b_(2) = -sx * cy; + + j_ang_c_(0) = -sy * cz; + j_ang_c_(1) = sy * sz; + j_ang_c_(2) = cy; + + j_ang_d_(0) = sx * cy * cz; + j_ang_d_(1) = -sx * cy * sz; + j_ang_d_(2) = sx * sy; + + j_ang_e_(0) = -cx * cy * cz; + j_ang_e_(1) = cx * cy * sz; + j_ang_e_(2) = -cx * sy; + + j_ang_f_(0) = -cy * sz; + j_ang_f_(1) = -cy * cz; + j_ang_f_(2) = 0; + + j_ang_g_(0) = cx * cz - sx * sy * sz; + j_ang_g_(1) = -cx * sz - sx * sy * cz; + j_ang_g_(2) = 0; + + j_ang_h_(0) = sx * cz + cx * sy * sz; + j_ang_h_(1) = cx * sy * cz - sx * sz; + j_ang_h_(2) = 0; + + if (compute_hessian) { + h_ang_a2_(0) = -cx * sz - sx * sy * cz; + h_ang_a2_(1) = -cx * cz + sx * sy * sz; + h_ang_a2_(2) = sx * cy; + + h_ang_a3_(0) = -sx * sz + cx * sy * cz; + h_ang_a3_(1) = -cx * sy * sz - sx * cz; + h_ang_a3_(2) = -cx * cy; + + h_ang_b2_(0) = cx * cy * cz; + h_ang_b2_(1) = -cx * cy * sz; + h_ang_b2_(2) = cx * sy; + + h_ang_b3_(0) = sx * cy * cz; + h_ang_b3_(1) = -sx * cy * sz; + h_ang_b3_(2) = sx * sy; + + h_ang_c2_(0) = -sx * cz - cx * sy * sz; + h_ang_c2_(1) = sx * sz - cx * sy * cz; + h_ang_c2_(2) = 0; + + h_ang_c3_(0) = cx * cz - sx * sy * sz; + h_ang_c3_(1) = -sx * sy * cz - cx * sz; + h_ang_c3_(2) = 0; + + h_ang_d1_(0) = -cy * cz; + h_ang_d1_(1) = cy * sz; + h_ang_d1_(2) = sy; + + h_ang_d2_(0) = -sx * sy * cz; + h_ang_d2_(1) = sx * sy * sz; + h_ang_d2_(2) = sx * cy; + + h_ang_d3_(0) = cx * sy * cz; + h_ang_d3_(1) = -cx * sy * sz; + h_ang_d3_(2) = -cx * cy; + + h_ang_e1_(0) = sy * sz; + h_ang_e1_(1) = sy * cz; + h_ang_e1_(2) = 0; + + h_ang_e2_(0) = -sx * cy * sz; + h_ang_e2_(1) = -sx * cy * cz; + h_ang_e2_(2) = 0; + + h_ang_e3_(0) = cx * cy * sz; + h_ang_e3_(1) = cx * cy * cz; + h_ang_e3_(2) = 0; + + h_ang_f1_(0) = -cy * cz; + h_ang_f1_(1) = cy * sz; + h_ang_f1_(2) = 0; + + h_ang_f2_(0) = -cx * sz - sx * sy * cz; + h_ang_f2_(1) = -cx * cz + sx * sy * sz; + h_ang_f2_(2) = 0; + + h_ang_f3_(0) = -sx * sz + cx * sy * cz; + h_ang_f3_(1) = -cx * sy * sz - sx * cz; + h_ang_f3_(2) = 0; + } } template double NormalDistributionsTransform::computeStepLengthMT(const Eigen::Matrix &x, Eigen::Matrix &step_dir, - double step_init, double step_max, double step_min, double &score, - Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, - typename pcl::PointCloud &trans_cloud) + double step_init, double step_max, double step_min, double &score, + Eigen::Matrix &score_gradient, Eigen::Matrix &hessian, + typename pcl::PointCloud &trans_cloud) { - double phi_0 = -score; - double d_phi_0 = -(score_gradient.dot(step_dir)); + double phi_0 = -score; + double d_phi_0 = -(score_gradient.dot(step_dir)); - Eigen::Matrix x_t; + Eigen::Matrix x_t; - if (d_phi_0 >= 0) { - if (d_phi_0 == 0) { - return 0; - } else { - d_phi_0 *= -1; - step_dir *= -1; - } - } + if (d_phi_0 >= 0) { + if (d_phi_0 == 0) { + return 0; + } else { + d_phi_0 *= -1; + step_dir *= -1; + } + } - int max_step_iterations = 10; - int step_iterations = 0; + int max_step_iterations = 10; + int step_iterations = 0; - double mu = 1.e-4; - double nu = 0.9; - double a_l = 0, a_u = 0; + double mu = 1.e-4; + double nu = 0.9; + double a_l = 0, a_u = 0; - double f_l = auxilaryFunction_PsiMT(a_l, phi_0, phi_0, d_phi_0, mu); - double g_l = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); + double f_l = auxilaryFunction_PsiMT(a_l, phi_0, phi_0, d_phi_0, mu); + double g_l = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); - double f_u = auxilaryFunction_PsiMT(a_u, phi_0, phi_0, d_phi_0, mu); - double g_u = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); + double f_u = auxilaryFunction_PsiMT(a_u, phi_0, phi_0, d_phi_0, mu); + double g_u = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu); - bool interval_converged = (step_max - step_min) > 0, open_interval = true; + bool interval_converged = (step_max - step_min) > 0, open_interval = true; - double a_t = step_init; - a_t = std::min(a_t, step_max); - a_t = std::max(a_t, step_min); + double a_t = step_init; + a_t = std::min(a_t, step_max); + a_t = std::max(a_t, step_min); - x_t = x + step_dir * a_t; + x_t = x + step_dir * a_t; - final_transformation_ = (Eigen::Translation(static_cast(x_t(0)), static_cast(x_t(1)), static_cast(x_t(2))) * - Eigen::AngleAxis(static_cast(x_t(3)), Eigen::Vector3f::UnitX()) * - Eigen::AngleAxis(static_cast(x_t(4)), Eigen::Vector3f::UnitY()) * - Eigen::AngleAxis(static_cast(x_t(5)), Eigen::Vector3f::UnitZ())).matrix(); + final_transformation_ = (Eigen::Translation(static_cast(x_t(0)), static_cast(x_t(1)), static_cast(x_t(2))) * + Eigen::AngleAxis(static_cast(x_t(3)), Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(x_t(4)), Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(x_t(5)), Eigen::Vector3f::UnitZ())).matrix(); - transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); + transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); - score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true); + score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true); - double phi_t = -score; - double d_phi_t = -(score_gradient.dot(step_dir)); - double psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); - double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); + double phi_t = -score; + double d_phi_t = -(score_gradient.dot(step_dir)); + double psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); + double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); - while (!interval_converged && step_iterations < max_step_iterations && !(psi_t <= 0 && d_phi_t <= -nu * d_phi_0)) { - if (open_interval) { - a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); - } else { - a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); - } + while (!interval_converged && step_iterations < max_step_iterations && !(psi_t <= 0 && d_phi_t <= -nu * d_phi_0)) { + if (open_interval) { + a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); + } else { + a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); + } - a_t = (a_t < step_max) ? a_t : step_max; - a_t = (a_t > step_min) ? a_t : step_min; + a_t = (a_t < step_max) ? a_t : step_max; + a_t = (a_t > step_min) ? a_t : step_min; - x_t = x + step_dir * a_t; + x_t = x + step_dir * a_t; - final_transformation_ = (Eigen::Translation(static_cast(x_t(0)), static_cast(x_t(1)), static_cast(x_t(2))) * - Eigen::AngleAxis(static_cast(x_t(3)), Eigen::Vector3f::UnitX()) * - Eigen::AngleAxis(static_cast(x_t(4)), Eigen::Vector3f::UnitY()) * - Eigen::AngleAxis(static_cast(x_t(5)), Eigen::Vector3f::UnitZ())).matrix(); + final_transformation_ = (Eigen::Translation(static_cast(x_t(0)), static_cast(x_t(1)), static_cast(x_t(2))) * + Eigen::AngleAxis(static_cast(x_t(3)), Eigen::Vector3f::UnitX()) * + Eigen::AngleAxis(static_cast(x_t(4)), Eigen::Vector3f::UnitY()) * + Eigen::AngleAxis(static_cast(x_t(5)), Eigen::Vector3f::UnitZ())).matrix(); - transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); + transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); - score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, false); + score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, false); - phi_t -= score; - d_phi_t -= (score_gradient.dot(step_dir)); - psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); - d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); + phi_t -= score; + d_phi_t -= (score_gradient.dot(step_dir)); + psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu); + d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); - if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) { - open_interval = false; + if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) { + open_interval = false; - f_l += phi_0 - mu * d_phi_0 * a_l; - g_l += mu * d_phi_0; + f_l += phi_0 - mu * d_phi_0 * a_l; + g_l += mu * d_phi_0; - f_u += phi_0 - mu * d_phi_0 * a_u; - g_u += mu * d_phi_0; - } + f_u += phi_0 - mu * d_phi_0 * a_u; + g_u += mu * d_phi_0; + } - if (open_interval) { - interval_converged = updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); - } else { - interval_converged = updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); - } - step_iterations++; - } + if (open_interval) { + interval_converged = updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t); + } else { + interval_converged = updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t); + } + step_iterations++; + } - if (step_iterations) { - computeHessian(hessian, trans_cloud, x_t); - } + if (step_iterations) { + computeHessian(hessian, trans_cloud, x_t); + } - real_iterations_ += step_iterations; + real_iterations_ += step_iterations; - return a_t; + return a_t; } //Copied from ndt.hpp template double NormalDistributionsTransform::trialValueSelectionMT (double a_l, double f_l, double g_l, - double a_u, double f_u, double g_u, - double a_t, double f_t, double g_t) + double a_u, double f_u, double g_u, + double a_t, double f_t, double g_t) { - // Case 1 in Trial Value Selection [More, Thuente 1994] - if (f_t > f_l) { - // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t - // Equation 2.4.52 [Sun, Yuan 2006] - double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; - double w = std::sqrt (z * z - g_t * g_l); - // Equation 2.4.56 [Sun, Yuan 2006] - double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); - - // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l - // Equation 2.4.2 [Sun, Yuan 2006] - double a_q = a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t)); - - if (std::fabs (a_c - a_l) < std::fabs (a_q - a_l)) { - return (a_c); - } else { - return (0.5 * (a_q + a_c)); - } - } - // Case 2 in Trial Value Selection [More, Thuente 1994] - else if (g_t * g_l < 0) { - // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t - // Equation 2.4.52 [Sun, Yuan 2006] - double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; - double w = std::sqrt (z * z - g_t * g_l); - // Equation 2.4.56 [Sun, Yuan 2006] - double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); - - // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t - // Equation 2.4.5 [Sun, Yuan 2006] - double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; - - if (std::fabs (a_c - a_t) >= std::fabs (a_s - a_t)) { - return (a_c); - } else { - return (a_s); - } - } - // Case 3 in Trial Value Selection [More, Thuente 1994] - else if (std::fabs (g_t) <= std::fabs (g_l)) { - // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t - // Equation 2.4.52 [Sun, Yuan 2006] - double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; - double w = std::sqrt (z * z - g_t * g_l); - double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); - - // Calculate the minimizer of the quadratic that interpolates g_l and g_t - // Equation 2.4.5 [Sun, Yuan 2006] - double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; - - double a_t_next; - - if (std::fabs (a_c - a_t) < std::fabs (a_s - a_t)) { - a_t_next = a_c; - } else { - a_t_next = a_s; - } - - if (a_t > a_l) { - return (std::min (a_t + 0.66 * (a_u - a_t), a_t_next)); - } else { - return (std::max (a_t + 0.66 * (a_u - a_t), a_t_next)); - } - } - // Case 4 in Trial Value Selection [More, Thuente 1994] - else { - // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t - // Equation 2.4.52 [Sun, Yuan 2006] - double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u; - double w = std::sqrt (z * z - g_t * g_u); - // Equation 2.4.56 [Sun, Yuan 2006] - return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w)); - } + // Case 1 in Trial Value Selection [More, Thuente 1994] + if (f_t > f_l) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l + // Equation 2.4.2 [Sun, Yuan 2006] + double a_q = a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t)); + + if (std::fabs (a_c - a_l) < std::fabs (a_q - a_l)) { + return (a_c); + } else { + return (0.5 * (a_q + a_c)); + } + } + // Case 2 in Trial Value Selection [More, Thuente 1994] + else if (g_t * g_l < 0) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + // Equation 2.4.56 [Sun, Yuan 2006] + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t + // Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + if (std::fabs (a_c - a_t) >= std::fabs (a_s - a_t)) { + return (a_c); + } else { + return (a_s); + } + } + // Case 3 in Trial Value Selection [More, Thuente 1994] + else if (std::fabs (g_t) <= std::fabs (g_l)) { + // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l; + double w = std::sqrt (z * z - g_t * g_l); + double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w); + + // Calculate the minimizer of the quadratic that interpolates g_l and g_t + // Equation 2.4.5 [Sun, Yuan 2006] + double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l; + + double a_t_next; + + if (std::fabs (a_c - a_t) < std::fabs (a_s - a_t)) { + a_t_next = a_c; + } else { + a_t_next = a_s; + } + + if (a_t > a_l) { + return (std::min (a_t + 0.66 * (a_u - a_t), a_t_next)); + } else { + return (std::max (a_t + 0.66 * (a_u - a_t), a_t_next)); + } + } + // Case 4 in Trial Value Selection [More, Thuente 1994] + else { + // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t + // Equation 2.4.52 [Sun, Yuan 2006] + double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u; + double w = std::sqrt (z * z - g_t * g_u); + // Equation 2.4.56 [Sun, Yuan 2006] + return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w)); + } } //Copied from ndt.hpp template double NormalDistributionsTransform::updateIntervalMT (double &a_l, double &f_l, double &g_l, - double &a_u, double &f_u, double &g_u, - double a_t, double f_t, double g_t) + double &a_u, double &f_u, double &g_u, + double a_t, double f_t, double g_t) { // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, Thuente 1994] - if (f_t > f_l) { - a_u = a_t; - f_u = f_t; - g_u = g_t; - return (false); - } - // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente 1994] - else if (g_t * (a_l - a_t) > 0) { - a_l = a_t; - f_l = f_t; - g_l = g_t; - return (false); - } - // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente 1994] - else if (g_t * (a_l - a_t) < 0) { - a_u = a_l; - f_u = f_l; - g_u = g_l; - - a_l = a_t; - f_l = f_t; - g_l = g_t; - return (false); - } - // Interval Converged - else { - return (true); - } + if (f_t > f_l) { + a_u = a_t; + f_u = f_t; + g_u = g_t; + return (false); + } + // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente 1994] + else if (g_t * (a_l - a_t) > 0) { + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente 1994] + else if (g_t * (a_l - a_t) < 0) { + a_u = a_l; + f_u = f_l; + g_u = g_l; + + a_l = a_t; + f_l = f_t; + g_l = g_t; + return (false); + } + // Interval Converged + else { + return (true); + } } template void NormalDistributionsTransform::updateHessian(Eigen::Matrix &hessian, - Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, - Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv) + Eigen::Matrix point_gradient, Eigen::Matrix point_hessian, + Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv) { - Eigen::Vector3d cov_dxd_pi; - double e_x_cov_x = gauss_d2_ * exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); + Eigen::Vector3d cov_dxd_pi; + double e_x_cov_x = gauss_d2_ * exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2); - if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) { - return; - } + if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x) { + return; + } - e_x_cov_x *= gauss_d1_; + e_x_cov_x *= gauss_d1_; - for (int i = 0; i < 6; i++) { - cov_dxd_pi = c_inv * point_gradient.col(i); + for (int i = 0; i < 6; i++) { + cov_dxd_pi = c_inv * point_gradient.col(i); - for (int j = 0; j < hessian.cols(); j++) { - hessian(i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) * x_trans.dot(c_inv * point_gradient.col(j)) + - x_trans.dot(c_inv * point_hessian.block<3, 1>(3 * i, j)) + - point_gradient.col(j).dot(cov_dxd_pi)); - } - } + for (int j = 0; j < hessian.cols(); j++) { + hessian(i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) * x_trans.dot(c_inv * point_gradient.col(j)) + + x_trans.dot(c_inv * point_hessian.block<3, 1>(3 * i, j)) + + point_gradient.col(j).dot(cov_dxd_pi)); + } + } } template void NormalDistributionsTransform::computeHessian(Eigen::Matrix &hessian, typename pcl::PointCloud &trans_cloud, Eigen::Matrix &p) { - PointSourceType x_pt, x_trans_pt; - Eigen::Vector3d x, x_trans; - Eigen::Matrix3d c_inv; + PointSourceType x_pt, x_trans_pt; + Eigen::Vector3d x, x_trans; + Eigen::Matrix3d c_inv; - hessian.setZero(); + hessian.setZero(); - Eigen::Matrix point_gradient; - Eigen::Matrix point_hessian; + Eigen::Matrix point_gradient; + Eigen::Matrix point_hessian; - for (int idx = 0; idx < source_cloud_->points.size(); idx++) { - x_trans_pt = trans_cloud.points[idx]; + for (int idx = 0; idx < source_cloud_->points.size(); idx++) { + x_trans_pt = trans_cloud.points[idx]; - std::vector neighbor_ids; + std::vector neighbor_ids; - voxel_grid_.radiusSearch(x_trans_pt, resolution_, neighbor_ids); + voxel_grid_.radiusSearch(x_trans_pt, resolution_, neighbor_ids); - for (int i = 0; i < neighbor_ids.size(); i++) { - int vid = neighbor_ids[i]; + for (int i = 0; i < neighbor_ids.size(); i++) { + int vid = neighbor_ids[i]; - x_pt = source_cloud_->points[idx]; - x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); - x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); - x_trans -= voxel_grid_.getCentroid(vid); - c_inv = voxel_grid_.getInverseCovariance(vid); + x_pt = source_cloud_->points[idx]; + x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z); + x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z); + x_trans -= voxel_grid_.getCentroid(vid); + c_inv = voxel_grid_.getInverseCovariance(vid); - computePointDerivatives(x, point_gradient, point_hessian); + computePointDerivatives(x, point_gradient, point_hessian); - updateHessian(hessian, point_gradient, point_hessian, x_trans, c_inv); - } - } + updateHessian(hessian, point_gradient, point_hessian, x_trans, c_inv); + } + } } @@ -719,39 +719,39 @@ void NormalDistributionsTransform::computeHess template double NormalDistributionsTransform::getFitnessScore(double max_range) { - double fitness_score = 0.0; + double fitness_score = 0.0; - typename pcl::PointCloud trans_cloud; + typename pcl::PointCloud trans_cloud; - transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); + transformPointCloud(*source_cloud_, trans_cloud, final_transformation_); - double distance; - int nr = 0; + double distance; + int nr = 0; - for (int i = 0; i < trans_cloud.points.size(); i++) { - PointSourceType q = trans_cloud.points[i]; + for (int i = 0; i < trans_cloud.points.size(); i++) { + PointSourceType q = trans_cloud.points[i]; - distance = voxel_grid_.nearestNeighborDistance(q, max_range); + distance = voxel_grid_.nearestNeighborDistance(q, max_range); - if (distance < max_range) { - fitness_score += distance; - nr++; - } - } + if (distance < max_range) { + fitness_score += distance; + nr++; + } + } - if (nr > 0) { - return (fitness_score / nr); - } + if (nr > 0) { + return (fitness_score / nr); + } - return DBL_MAX; + return DBL_MAX; } template void NormalDistributionsTransform::updateVoxelGrid(typename pcl::PointCloud::Ptr new_cloud) { - // Update voxel grid - voxel_grid_.update(new_cloud); + // Update voxel grid + voxel_grid_.update(new_cloud); } template class NormalDistributionsTransform; diff --git a/core_perception/ndt_cpu/src/Octree.cpp b/core_perception/ndt_cpu/src/Octree.cpp index 29b1e012a28..a52a982aa6e 100644 --- a/core_perception/ndt_cpu/src/Octree.cpp +++ b/core_perception/ndt_cpu/src/Octree.cpp @@ -18,899 +18,899 @@ namespace cpu { template Octree::Octree() { - leaf_x_ = 4; //16; - leaf_y_ = 4; //16; - leaf_z_ = 2; //4; - - octree_.reset(); - reserved_size_.reset(); - dimension_.reset(); - occupancy_check_.reset(); + leaf_x_ = 4; //16; + leaf_y_ = 4; //16; + leaf_z_ = 2; //4; + + octree_.reset(); + reserved_size_.reset(); + dimension_.reset(); + occupancy_check_.reset(); } template int Octree::roundUp(int input, int factor) { - return (input < 0) ? (-((-input) / factor) * factor) : ((input + factor - 1 ) / factor) * factor; + return (input < 0) ? (-((-input) / factor) * factor) : ((input + factor - 1 ) / factor) * factor; } template int Octree::roundDown(int input, int factor) { - return (input < 0) ? (-(-input + factor - 1) / factor) * factor : (input / factor) * factor; + return (input < 0) ? (-(-input + factor - 1) / factor) * factor : (input / factor) * factor; } template int Octree::div(int input, int divisor) { - return (input < 0) ? (-(-input + divisor - 1) / divisor) : (input / divisor); + return (input < 0) ? (-(-input + divisor - 1) / divisor) : (input / divisor); } template void Octree::setInput(std::vector occupied_voxels, typename pcl::PointCloud::Ptr point_cloud) { - octree_.reset(); - reserved_size_.reset(); - dimension_.reset(); - occupancy_check_.reset(); + octree_.reset(); + reserved_size_.reset(); + dimension_.reset(); + occupancy_check_.reset(); - octree_ = boost::make_shared > >(); - reserved_size_ = boost::make_shared >(); - dimension_ = boost::make_shared >(); - occupancy_check_ = boost::make_shared > >(); + octree_ = boost::make_shared > >(); + reserved_size_ = boost::make_shared >(); + dimension_ = boost::make_shared >(); + occupancy_check_ = boost::make_shared > >(); - // Reserve memory - int max_b_x, max_b_y, max_b_z; - int min_b_x, min_b_y, min_b_z; + // Reserve memory + int max_b_x, max_b_y, max_b_z; + int min_b_x, min_b_y, min_b_z; - max_b_x = max_b_y = max_b_z = INT_MIN; - min_b_x = min_b_y = min_b_z = INT_MAX; + max_b_x = max_b_y = max_b_z = INT_MIN; + min_b_x = min_b_y = min_b_z = INT_MAX; - for (int i = 0; i < occupied_voxels.size(); i++) { - Eigen::Vector3i vid = occupied_voxels[i]; + for (int i = 0; i < occupied_voxels.size(); i++) { + Eigen::Vector3i vid = occupied_voxels[i]; - if (min_b_x > vid(0)) { - min_b_x = vid(0); - } + if (min_b_x > vid(0)) { + min_b_x = vid(0); + } - if (max_b_x < vid(0)) { - max_b_x = vid(0); - } + if (max_b_x < vid(0)) { + max_b_x = vid(0); + } - if (min_b_y > vid(1)) { - min_b_y = vid(1); - } + if (min_b_y > vid(1)) { + min_b_y = vid(1); + } - if (max_b_y < vid(1)) { - max_b_y = vid(1); - } + if (max_b_y < vid(1)) { + max_b_y = vid(1); + } - if (min_b_z > vid(2)) { - min_b_z = vid(2); - } + if (min_b_z > vid(2)) { + min_b_z = vid(2); + } - if (max_b_z < vid(2)) { - max_b_z = vid(2); - } - } + if (max_b_z < vid(2)) { + max_b_z = vid(2); + } + } - OctreeLevelBoundaries level; + OctreeLevelBoundaries level; - int node_number; + int node_number; - OctreeLevelDim level_size; + OctreeLevelDim level_size; - level.lower_x = roundDown(div(min_b_x, leaf_x_), MAX_BX_); - level.lower_y = roundDown(div(min_b_y, leaf_y_), MAX_BY_); - level.lower_z = roundDown(div(min_b_z, leaf_z_), MAX_BZ_); + level.lower_x = roundDown(div(min_b_x, leaf_x_), MAX_BX_); + level.lower_y = roundDown(div(min_b_y, leaf_y_), MAX_BY_); + level.lower_z = roundDown(div(min_b_z, leaf_z_), MAX_BZ_); - level.upper_x = roundUp(div(max_b_x, leaf_x_), MAX_BX_); - level.upper_y = roundUp(div(max_b_y, leaf_y_), MAX_BY_); - level.upper_z = roundUp(div(max_b_z, leaf_z_), MAX_BZ_); + level.upper_x = roundUp(div(max_b_x, leaf_x_), MAX_BX_); + level.upper_y = roundUp(div(max_b_y, leaf_y_), MAX_BY_); + level.upper_z = roundUp(div(max_b_z, leaf_z_), MAX_BZ_); - level_size.x = level.upper_x - level.lower_x + 1; - level_size.y = level.upper_y - level.lower_y + 1; - level_size.z = level.upper_z - level.lower_z + 1; + level_size.x = level.upper_x - level.lower_x + 1; + level_size.y = level.upper_y - level.lower_y + 1; + level_size.z = level.upper_z - level.lower_z + 1; - node_number = level_size.x * level_size.y * level_size.z; + node_number = level_size.x * level_size.y * level_size.z; - // construct bottom + // construct bottom - std::vector level0(node_number); - std::vector occupancy0(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); + std::vector level0(node_number); + std::vector occupancy0(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); - (*octree_).push_back(level0); - (*reserved_size_).push_back(level); - (*dimension_).push_back(level_size); - (*occupancy_check_).push_back(occupancy0); + (*octree_).push_back(level0); + (*reserved_size_).push_back(level); + (*dimension_).push_back(level_size); + (*occupancy_check_).push_back(occupancy0); - int tree_level = 0; + int tree_level = 0; - while (node_number > 8) { - level.lower_x = div(level.lower_x, 2); - level.lower_y = div(level.lower_y, 2); - level.lower_z = div(level.lower_z, 2); + while (node_number > 8) { + level.lower_x = div(level.lower_x, 2); + level.lower_y = div(level.lower_y, 2); + level.lower_z = div(level.lower_z, 2); - level.upper_x = div(level.upper_x, 2); - level.upper_y = div(level.upper_y, 2); - level.upper_z = div(level.upper_z, 2); + level.upper_x = div(level.upper_x, 2); + level.upper_y = div(level.upper_y, 2); + level.upper_z = div(level.upper_z, 2); - level_size.x = level.upper_x - level.lower_x + 1; - level_size.y = level.upper_y - level.lower_y + 1; - level_size.z = level.upper_z - level.lower_z + 1; + level_size.x = level.upper_x - level.lower_x + 1; + level_size.y = level.upper_y - level.lower_y + 1; + level_size.z = level.upper_z - level.lower_z + 1; - node_number = level_size.x * level_size.y * level_size.z; + node_number = level_size.x * level_size.y * level_size.z; - std::vector new_level(node_number); - std::vector new_occupancy_check(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); + std::vector new_level(node_number); + std::vector new_occupancy_check(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); - (*octree_).push_back(new_level); - (*reserved_size_).push_back(level); - (*dimension_).push_back(level_size); - (*occupancy_check_).push_back(new_occupancy_check); - } + (*octree_).push_back(new_level); + (*reserved_size_).push_back(level); + (*dimension_).push_back(level_size); + (*occupancy_check_).push_back(new_occupancy_check); + } - // Setup the lowest level - for (int i = 0; i < occupied_voxels.size(); i++) { - Eigen::Vector3i vid = occupied_voxels[i]; + // Setup the lowest level + for (int i = 0; i < occupied_voxels.size(); i++) { + Eigen::Vector3i vid = occupied_voxels[i]; - // Indexes of the octree node that contains the current voxel - int nidx = div(vid(0), leaf_x_); - int nidy = div(vid(1), leaf_y_); - int nidz = div(vid(2), leaf_z_); + // Indexes of the octree node that contains the current voxel + int nidx = div(vid(0), leaf_x_); + int nidy = div(vid(1), leaf_y_); + int nidz = div(vid(2), leaf_z_); - int nid = index2id(nidx, nidy, nidz, 0); + int nid = index2id(nidx, nidy, nidz, 0); - std::vector ¤t_level = (*octree_)[0]; - OctreeLevelBoundaries curb = (*reserved_size_)[0]; - OctreeNode ¤t_node = current_level[nid]; - PointSourceType p = point_cloud->points[i]; + std::vector ¤t_level = (*octree_)[0]; + OctreeLevelBoundaries curb = (*reserved_size_)[0]; + OctreeNode ¤t_node = current_level[nid]; + PointSourceType p = point_cloud->points[i]; - // Update boundaries inside the node - if (!isOccupied(nid, 0)) { - /* If the current octree node is empty, - * just set boundaries inside the node - */ - current_node.lx = current_node.ux = p.x; - current_node.ly = current_node.uy = p.y; - current_node.lz = current_node.uz = p.z; - current_node.point_num = 1; - current_node.centroid(0) = p.x; - current_node.centroid(1) = p.y; - current_node.centroid(2) = p.z; + // Update boundaries inside the node + if (!isOccupied(nid, 0)) { + /* If the current octree node is empty, + * just set boundaries inside the node + */ + current_node.lx = current_node.ux = p.x; + current_node.ly = current_node.uy = p.y; + current_node.lz = current_node.uz = p.z; + current_node.point_num = 1; + current_node.centroid(0) = p.x; + current_node.centroid(1) = p.y; + current_node.centroid(2) = p.z; - // Update occupancy status - setOccupied(nid, 0); + // Update occupancy status + setOccupied(nid, 0); - } else { - /* Otherwise, update boundaries inside the node */ - if (p.x < current_node.lx) { - current_node.lx = p.x; - } + } else { + /* Otherwise, update boundaries inside the node */ + if (p.x < current_node.lx) { + current_node.lx = p.x; + } - if (p.y < current_node.ly) { - current_node.ly = p.y; - } + if (p.y < current_node.ly) { + current_node.ly = p.y; + } - if (p.z < current_node.lz) { - current_node.lz = p.z; - } + if (p.z < current_node.lz) { + current_node.lz = p.z; + } - if (p.x > current_node.ux) { - current_node.ux = p.x; - } + if (p.x > current_node.ux) { + current_node.ux = p.x; + } - if (p.y > current_node.uy) { - current_node.uy = p.y; - } + if (p.y > current_node.uy) { + current_node.uy = p.y; + } - if (p.z > current_node.uz) { - current_node.uz = p.z; - } + if (p.z > current_node.uz) { + current_node.uz = p.z; + } - Eigen::Vector3d new_node(p.x, p.y, p.z); + Eigen::Vector3d new_node(p.x, p.y, p.z); - current_node.centroid = current_node.centroid * current_node.point_num + new_node; - current_node.point_num++; - current_node.centroid /= current_node.point_num; + current_node.centroid = current_node.centroid * current_node.point_num + new_node; + current_node.point_num++; + current_node.centroid /= current_node.point_num; - } - } + } + } - // Build higher levels - OctreeLevelBoundaries child, parent; + // Build higher levels + OctreeLevelBoundaries child, parent; - for (int level = 1; level < (*octree_).size(); level++) { - buildLevel(level); - } + for (int level = 1; level < (*octree_).size(); level++) { + buildLevel(level); + } } template bool Octree::isOccupied(int node_id, int level) { - std::vector ¤t_occ = (*occupancy_check_)[level]; + std::vector ¤t_occ = (*occupancy_check_)[level]; - int val_loc = node_id / (sizeof(int) * 8); - int bit_loc = node_id % (sizeof(int) * 8); + int val_loc = node_id / (sizeof(int) * 8); + int bit_loc = node_id % (sizeof(int) * 8); - return ((current_occ[val_loc] & (1 << bit_loc)) == (1 << bit_loc)); + return ((current_occ[val_loc] & (1 << bit_loc)) == (1 << bit_loc)); } template bool Octree::isOccupied(std::vector occupancy, int node_id) { - int val_loc = node_id / (sizeof(int) * 8); - int bit_loc = node_id % (sizeof(int) * 8); + int val_loc = node_id / (sizeof(int) * 8); + int bit_loc = node_id % (sizeof(int) * 8); - return ((occupancy[val_loc] & (1 << bit_loc)) == (1 << bit_loc)); + return ((occupancy[val_loc] & (1 << bit_loc)) == (1 << bit_loc)); } template void Octree::setOccupied(int node_id, int level) { - std::vector ¤t_occ = (*occupancy_check_)[level]; - int val_loc = node_id / (sizeof(int) * 8); - int bit_loc = node_id % (sizeof(int) * 8); + std::vector ¤t_occ = (*occupancy_check_)[level]; + int val_loc = node_id / (sizeof(int) * 8); + int bit_loc = node_id % (sizeof(int) * 8); - current_occ[val_loc] |= (1 << bit_loc); + current_occ[val_loc] |= (1 << bit_loc); } template void Octree::setOccupied(std::vector &occupancy, int node_id) { - int val_loc = node_id / (sizeof(int) * 8); - int bit_loc = node_id % (sizeof(int) * 8); + int val_loc = node_id / (sizeof(int) * 8); + int bit_loc = node_id % (sizeof(int) * 8); - occupancy[val_loc] |= (1 << bit_loc); + occupancy[val_loc] |= (1 << bit_loc); } template void Octree::buildLevel(int level) { - // Parent list - std::vector &parent = (*octree_)[level]; - std::vector &poccupancy = (*occupancy_check_)[level]; - - // Child list - std::vector &child = (*octree_)[level - 1]; - std::vector &coccupancy = (*occupancy_check_)[level - 1]; - OctreeLevelBoundaries cbounds = (*reserved_size_)[level - 1]; - - for (int i = cbounds.lower_x; i <= cbounds.upper_x; i++) { - for (int j = cbounds.lower_y; j <= cbounds.upper_y; j++) { - for (int k = cbounds.lower_z; k <= cbounds.upper_z; k++) { - int cid = index2id(i, j, k, level - 1); // Child id - int pidx = div(i, 2); - int pidy = div(j, 2); - int pidz = div(k, 2); - int pid = index2id(pidx, pidy, pidz, level); // Parent id - OctreeNode &cnode = child[cid]; - OctreeNode &pnode = parent[pid]; - - if (isOccupied(cid, level - 1)) { - if (isOccupied(pid, level)) { - if (pnode.lx > cnode.lx) { - pnode.lx = cnode.lx; - } - - if (pnode.ly > cnode.ly) { - pnode.ly = cnode.ly; - } - - if (pnode.lz > cnode.lz) { - pnode.lz = cnode.lz; - } - - if (pnode.ux < cnode.ux) { - pnode.ux = cnode.ux; - } - - if (pnode.uy < cnode.uy) { - pnode.uy = cnode.uy; - } - - if (pnode.uz < cnode.uz) { - pnode.uz = cnode.uz; - } - - // If the parent node is already occupied, update its centroid - pnode.centroid = pnode.centroid * pnode.point_num + cnode.centroid * cnode.point_num; - pnode.point_num += cnode.point_num; - pnode.centroid /= pnode.point_num; - } else { - // Otherwise, set cnode to pnode and mark the pnode as occupied - pnode = cnode; - - setOccupied(pid, level); - } - } - } - } - } + // Parent list + std::vector &parent = (*octree_)[level]; + std::vector &poccupancy = (*occupancy_check_)[level]; + + // Child list + std::vector &child = (*octree_)[level - 1]; + std::vector &coccupancy = (*occupancy_check_)[level - 1]; + OctreeLevelBoundaries cbounds = (*reserved_size_)[level - 1]; + + for (int i = cbounds.lower_x; i <= cbounds.upper_x; i++) { + for (int j = cbounds.lower_y; j <= cbounds.upper_y; j++) { + for (int k = cbounds.lower_z; k <= cbounds.upper_z; k++) { + int cid = index2id(i, j, k, level - 1); // Child id + int pidx = div(i, 2); + int pidy = div(j, 2); + int pidz = div(k, 2); + int pid = index2id(pidx, pidy, pidz, level); // Parent id + OctreeNode &cnode = child[cid]; + OctreeNode &pnode = parent[pid]; + + if (isOccupied(cid, level - 1)) { + if (isOccupied(pid, level)) { + if (pnode.lx > cnode.lx) { + pnode.lx = cnode.lx; + } + + if (pnode.ly > cnode.ly) { + pnode.ly = cnode.ly; + } + + if (pnode.lz > cnode.lz) { + pnode.lz = cnode.lz; + } + + if (pnode.ux < cnode.ux) { + pnode.ux = cnode.ux; + } + + if (pnode.uy < cnode.uy) { + pnode.uy = cnode.uy; + } + + if (pnode.uz < cnode.uz) { + pnode.uz = cnode.uz; + } + + // If the parent node is already occupied, update its centroid + pnode.centroid = pnode.centroid * pnode.point_num + cnode.centroid * cnode.point_num; + pnode.point_num += cnode.point_num; + pnode.centroid /= pnode.point_num; + } else { + // Otherwise, set cnode to pnode and mark the pnode as occupied + pnode = cnode; + + setOccupied(pid, level); + } + } + } + } + } } template void Octree::update(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud) { - // First, update boundaries - updateBoundaries(new_voxels); + // First, update boundaries + updateBoundaries(new_voxels); - updateOctreeContent(new_voxels, new_cloud); + updateOctreeContent(new_voxels, new_cloud); } template void Octree::updateBoundaries(std::vector new_voxels) { - int new_min_bx, new_min_by, new_min_bz; - int new_max_bx, new_max_by, new_max_bz; + int new_min_bx, new_min_by, new_min_bz; + int new_max_bx, new_max_by, new_max_bz; - new_min_bx = new_min_by = new_min_bz = INT_MAX; - new_max_bx = new_max_by = new_max_bz = INT_MIN; + new_min_bx = new_min_by = new_min_bz = INT_MAX; + new_max_bx = new_max_by = new_max_bz = INT_MIN; - for (int i = 0; i < new_voxels.size(); i++) { - Eigen::Vector3i vid = new_voxels[i]; - - if (new_min_bx > vid(0)) { - new_min_bx = vid(0); - } - - if (new_max_bx < vid(0)) { - new_max_bx = vid(0); - } - - if (new_min_by > vid(1)) { - new_min_by = vid(1); - } - - if (new_max_by < vid(1)) { - new_max_by = vid(1); - } - - if (new_min_bz > vid(2)) { - new_min_bz = vid(2); - } + for (int i = 0; i < new_voxels.size(); i++) { + Eigen::Vector3i vid = new_voxels[i]; + + if (new_min_bx > vid(0)) { + new_min_bx = vid(0); + } + + if (new_max_bx < vid(0)) { + new_max_bx = vid(0); + } + + if (new_min_by > vid(1)) { + new_min_by = vid(1); + } + + if (new_max_by < vid(1)) { + new_max_by = vid(1); + } + + if (new_min_bz > vid(2)) { + new_min_bz = vid(2); + } - if (new_max_bz < vid(2)) { - new_max_bz = vid(2); - } - } + if (new_max_bz < vid(2)) { + new_max_bz = vid(2); + } + } - OctreeLevelBoundaries dst_bounds; - - dst_bounds.lower_x = roundDown(div(new_min_bx, leaf_x_), MAX_BX_); - dst_bounds.lower_y = roundDown(div(new_min_by, leaf_y_), MAX_BY_); - dst_bounds.lower_z = roundDown(div(new_min_bz, leaf_z_), MAX_BZ_); + OctreeLevelBoundaries dst_bounds; + + dst_bounds.lower_x = roundDown(div(new_min_bx, leaf_x_), MAX_BX_); + dst_bounds.lower_y = roundDown(div(new_min_by, leaf_y_), MAX_BY_); + dst_bounds.lower_z = roundDown(div(new_min_bz, leaf_z_), MAX_BZ_); - dst_bounds.upper_x = roundUp(div(new_max_bx, leaf_x_), MAX_BX_); - dst_bounds.upper_y = roundUp(div(new_max_by, leaf_y_), MAX_BY_); - dst_bounds.upper_z = roundUp(div(new_max_bz, leaf_z_), MAX_BZ_); + dst_bounds.upper_x = roundUp(div(new_max_bx, leaf_x_), MAX_BX_); + dst_bounds.upper_y = roundUp(div(new_max_by, leaf_y_), MAX_BY_); + dst_bounds.upper_z = roundUp(div(new_max_bz, leaf_z_), MAX_BZ_); - /* Compare dst_bounds with boundaries of the lowest level - * of the octree to check if we need to reallocate the octree - */ - OctreeLevelBoundaries src_bounds = (*reserved_size_)[0]; + /* Compare dst_bounds with boundaries of the lowest level + * of the octree to check if we need to reallocate the octree + */ + OctreeLevelBoundaries src_bounds = (*reserved_size_)[0]; - if (dst_bounds.lower_x < src_bounds.lower_x || dst_bounds.lower_y < src_bounds.lower_y || dst_bounds.lower_z < src_bounds.lower_z || - dst_bounds.upper_x > src_bounds.upper_x || dst_bounds.upper_y > src_bounds.upper_y || dst_bounds.upper_z > src_bounds.upper_z) { - // If the base voxel grid expanded, then we need expand the octree as well - if (dst_bounds.lower_x > src_bounds.lower_x) { - dst_bounds.lower_x = src_bounds.lower_x; - } - - if (dst_bounds.lower_y > src_bounds.lower_y) { - dst_bounds.lower_y = src_bounds.lower_y; - } - - if (dst_bounds.lower_z > src_bounds.lower_z) { - dst_bounds.lower_z = src_bounds.lower_z; - } - - if (dst_bounds.upper_x < src_bounds.upper_x) { - dst_bounds.upper_x = src_bounds.upper_x; - } - - if (dst_bounds.upper_y < src_bounds.upper_y) { - dst_bounds.upper_y = src_bounds.upper_y; - } - - if (dst_bounds.upper_z < src_bounds.upper_z) { - dst_bounds.upper_z = src_bounds.upper_z; - } - - OctreeLevelDim dst_dim; - - dst_dim.x = dst_bounds.upper_x - dst_bounds.lower_x + 1; - dst_dim.y = dst_bounds.upper_y - dst_bounds.lower_y + 1; - dst_dim.z = dst_bounds.upper_z - dst_bounds.lower_z + 1; - int node_number = dst_dim.x * dst_dim.y * dst_dim.z; - - // Backup old octree - boost::shared_ptr > > old_octree = octree_; - boost::shared_ptr > > old_occupancy_check = occupancy_check_; - boost::shared_ptr > old_reserved_size = reserved_size_; - boost::shared_ptr > old_dimension = dimension_; - - // Reserve space for the new octree - octree_ = boost::make_shared > >(); - occupancy_check_ = boost::make_shared > >(); - reserved_size_ = boost::make_shared >(); - dimension_ = boost::make_shared >(); - - //Setup level0 - - std::vector new_level0(node_number); - std::vector new_occupy0((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8), 0); - - (*octree_).push_back(new_level0); - (*occupancy_check_).push_back(new_occupy0); - (*reserved_size_).push_back(dst_bounds); - (*dimension_).push_back(dst_dim); - - while (node_number > 8) { - dst_bounds.lower_x = div(dst_bounds.lower_x, 2); - dst_bounds.lower_y = div(dst_bounds.lower_y, 2); - dst_bounds.lower_z = div(dst_bounds.lower_z, 2); - dst_bounds.upper_x = div(dst_bounds.upper_x, 2); - dst_bounds.upper_y = div(dst_bounds.upper_y, 2); - dst_bounds.upper_z = div(dst_bounds.upper_z, 2); - - dst_dim.x = dst_bounds.upper_x - dst_bounds.lower_x + 1; - dst_dim.y = dst_bounds.upper_y - dst_bounds.lower_y + 1; - dst_dim.z = dst_bounds.upper_z - dst_bounds.lower_z + 1; - - node_number = dst_dim.x * dst_dim.y * dst_dim.z; - - std::vector new_level(node_number); - std::vector new_occupancy(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); - - (*octree_).push_back(new_level); - (*occupancy_check_).push_back(new_occupancy); - (*reserved_size_).push_back(dst_bounds); - (*dimension_).push_back(dst_dim); - } - - - // Copy the old octree to the new one - int level = 0; - - for (; level < (*old_octree).size(); level++) { - std::vector &dst_occupancy = (*occupancy_check_)[level]; - std::vector &dst_level = (*octree_)[level]; - OctreeLevelBoundaries dst_bounds = (*reserved_size_)[level]; - OctreeLevelDim dst_dim = (*dimension_)[level]; - - - std::vector &src_occupancy = (*old_occupancy_check)[level]; - std::vector &src_level = (*old_octree)[level]; - OctreeLevelBoundaries src_bounds = (*old_reserved_size)[level]; - OctreeLevelDim src_dim = (*old_dimension)[level]; - - for (int i = 0; i < src_occupancy.size(); i++) { - unsigned int stat32 = src_occupancy[i]; - - if (stat32 != 0) { - for (int j = 0; j < sizeof(unsigned int) * 8; j++) { - if ((stat32 & (1 << j)) == (1 << j)) { - int src_id = j + i * sizeof(unsigned int) * 8; - Eigen::Vector3i vid = id2index(src_id, src_bounds, src_dim); - int dst_id = index2id(vid(0), vid(1), vid(2), dst_bounds, dst_dim); - - dst_level[dst_id] = src_level[src_id]; - setOccupied(dst_occupancy, dst_id); - } - } - } - } - } - - // Build upper levels - for (; level < (*octree_).size(); level++) { - buildLevel(level); - } - } + if (dst_bounds.lower_x < src_bounds.lower_x || dst_bounds.lower_y < src_bounds.lower_y || dst_bounds.lower_z < src_bounds.lower_z || + dst_bounds.upper_x > src_bounds.upper_x || dst_bounds.upper_y > src_bounds.upper_y || dst_bounds.upper_z > src_bounds.upper_z) { + // If the base voxel grid expanded, then we need expand the octree as well + if (dst_bounds.lower_x > src_bounds.lower_x) { + dst_bounds.lower_x = src_bounds.lower_x; + } + + if (dst_bounds.lower_y > src_bounds.lower_y) { + dst_bounds.lower_y = src_bounds.lower_y; + } + + if (dst_bounds.lower_z > src_bounds.lower_z) { + dst_bounds.lower_z = src_bounds.lower_z; + } + + if (dst_bounds.upper_x < src_bounds.upper_x) { + dst_bounds.upper_x = src_bounds.upper_x; + } + + if (dst_bounds.upper_y < src_bounds.upper_y) { + dst_bounds.upper_y = src_bounds.upper_y; + } + + if (dst_bounds.upper_z < src_bounds.upper_z) { + dst_bounds.upper_z = src_bounds.upper_z; + } + + OctreeLevelDim dst_dim; + + dst_dim.x = dst_bounds.upper_x - dst_bounds.lower_x + 1; + dst_dim.y = dst_bounds.upper_y - dst_bounds.lower_y + 1; + dst_dim.z = dst_bounds.upper_z - dst_bounds.lower_z + 1; + int node_number = dst_dim.x * dst_dim.y * dst_dim.z; + + // Backup old octree + boost::shared_ptr > > old_octree = octree_; + boost::shared_ptr > > old_occupancy_check = occupancy_check_; + boost::shared_ptr > old_reserved_size = reserved_size_; + boost::shared_ptr > old_dimension = dimension_; + + // Reserve space for the new octree + octree_ = boost::make_shared > >(); + occupancy_check_ = boost::make_shared > >(); + reserved_size_ = boost::make_shared >(); + dimension_ = boost::make_shared >(); + + //Setup level0 + + std::vector new_level0(node_number); + std::vector new_occupy0((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8), 0); + + (*octree_).push_back(new_level0); + (*occupancy_check_).push_back(new_occupy0); + (*reserved_size_).push_back(dst_bounds); + (*dimension_).push_back(dst_dim); + + while (node_number > 8) { + dst_bounds.lower_x = div(dst_bounds.lower_x, 2); + dst_bounds.lower_y = div(dst_bounds.lower_y, 2); + dst_bounds.lower_z = div(dst_bounds.lower_z, 2); + dst_bounds.upper_x = div(dst_bounds.upper_x, 2); + dst_bounds.upper_y = div(dst_bounds.upper_y, 2); + dst_bounds.upper_z = div(dst_bounds.upper_z, 2); + + dst_dim.x = dst_bounds.upper_x - dst_bounds.lower_x + 1; + dst_dim.y = dst_bounds.upper_y - dst_bounds.lower_y + 1; + dst_dim.z = dst_bounds.upper_z - dst_bounds.lower_z + 1; + + node_number = dst_dim.x * dst_dim.y * dst_dim.z; + + std::vector new_level(node_number); + std::vector new_occupancy(static_cast((node_number + sizeof(unsigned int) * 8 - 1) / (sizeof(unsigned int) * 8)), 0); + + (*octree_).push_back(new_level); + (*occupancy_check_).push_back(new_occupancy); + (*reserved_size_).push_back(dst_bounds); + (*dimension_).push_back(dst_dim); + } + + + // Copy the old octree to the new one + int level = 0; + + for (; level < (*old_octree).size(); level++) { + std::vector &dst_occupancy = (*occupancy_check_)[level]; + std::vector &dst_level = (*octree_)[level]; + OctreeLevelBoundaries dst_bounds = (*reserved_size_)[level]; + OctreeLevelDim dst_dim = (*dimension_)[level]; + + + std::vector &src_occupancy = (*old_occupancy_check)[level]; + std::vector &src_level = (*old_octree)[level]; + OctreeLevelBoundaries src_bounds = (*old_reserved_size)[level]; + OctreeLevelDim src_dim = (*old_dimension)[level]; + + for (int i = 0; i < src_occupancy.size(); i++) { + unsigned int stat32 = src_occupancy[i]; + + if (stat32 != 0) { + for (int j = 0; j < sizeof(unsigned int) * 8; j++) { + if ((stat32 & (1 << j)) == (1 << j)) { + int src_id = j + i * sizeof(unsigned int) * 8; + Eigen::Vector3i vid = id2index(src_id, src_bounds, src_dim); + int dst_id = index2id(vid(0), vid(1), vid(2), dst_bounds, dst_dim); + + dst_level[dst_id] = src_level[src_id]; + setOccupied(dst_occupancy, dst_id); + } + } + } + } + } + + // Build upper levels + for (; level < (*octree_).size(); level++) { + buildLevel(level); + } + } } template int Octree::index2id(int idx, int idy, int idz, int level) { - OctreeLevelBoundaries bound = (*reserved_size_)[level]; - OctreeLevelDim dim = (*dimension_)[level]; + OctreeLevelBoundaries bound = (*reserved_size_)[level]; + OctreeLevelDim dim = (*dimension_)[level]; - return ((idx - bound.lower_x) + (idy - bound.lower_y) * dim.x + (idz - bound.lower_z) * dim.x * dim.y); + return ((idx - bound.lower_x) + (idy - bound.lower_y) * dim.x + (idz - bound.lower_z) * dim.x * dim.y); } template int Octree::index2id(int idx, int idy, int idz, OctreeLevelBoundaries bounds, OctreeLevelDim dim) { - return ((idx - bounds.lower_x) + (idy - bounds.lower_y) * dim.x + (idz - bounds.lower_z) * dim.x * dim.y); + return ((idx - bounds.lower_x) + (idy - bounds.lower_y) * dim.x + (idz - bounds.lower_z) * dim.x * dim.y); } template Eigen::Vector3i Octree::id2index(int id, int level) { - Eigen::Vector3i output; + Eigen::Vector3i output; - OctreeLevelBoundaries bound = (*reserved_size_)[level]; - OctreeLevelDim dim = (*dimension_)[level]; + OctreeLevelBoundaries bound = (*reserved_size_)[level]; + OctreeLevelDim dim = (*dimension_)[level]; - output(2) = id / (dim.x * dim.y); - id -= output(2) * dim.x * dim.y; - output(1) = id / dim.x; - output(0) = id - output(1) * dim.x; + output(2) = id / (dim.x * dim.y); + id -= output(2) * dim.x * dim.y; + output(1) = id / dim.x; + output(0) = id - output(1) * dim.x; - output(0) += bound.lower_x; - output(1) += bound.lower_y; - output(2) += bound.lower_z; + output(0) += bound.lower_x; + output(1) += bound.lower_y; + output(2) += bound.lower_z; - return output; + return output; } template Eigen::Vector3i Octree::id2index(int id, OctreeLevelBoundaries bounds, OctreeLevelDim dims) { - Eigen::Vector3i output; + Eigen::Vector3i output; - output(2) = id / (dims.x * dims.y); - id -= output(2) * dims.x * dims.y; - output(1) = id / dims.x; - output(0) = id - output(1) * dims.x; + output(2) = id / (dims.x * dims.y); + id -= output(2) * dims.x * dims.y; + output(1) = id / dims.x; + output(0) = id - output(1) * dims.x; - output(0) += bounds.lower_x; - output(1) += bounds.lower_y; - output(2) += bounds.lower_z; + output(0) += bounds.lower_x; + output(1) += bounds.lower_y; + output(2) += bounds.lower_z; - return output; + return output; } template void Octree::updateOctreeContent(std::vector new_voxels, typename pcl::PointCloud::Ptr new_cloud) { - for (int i = 0; i < new_voxels.size(); i++) { - Eigen::Vector3i vid = new_voxels[i]; - int node_idx = div(vid(0), leaf_x_); - int node_idy = div(vid(1), leaf_y_); - int node_idz = div(vid(2), leaf_z_); - PointSourceType p = new_cloud->points[i]; - Eigen::Vector3d point(p.x, p.y, p.z); - - // Go from bottom to top to update tree nodes - for (int level = 0; level < (*octree_).size(); level++) { - int nid = index2id(node_idx, node_idy, node_idz, level); - std::vector &cur_level = (*octree_)[level]; - OctreeNode &node = cur_level[nid]; - - if (isOccupied(nid, level)) { - // If the node is occupied, update the current content - if (p.x < node.lx) { - node.lx = p.x; - } - - if (p.y < node.ly) { - node.ly = p.y; - } - - if (p.z < node.lz) { - node.lz = p.z; - } - - if (p.x > node.ux) { - node.ux = p.x; - } - - if (p.y > node.uy) { - node.uy = p.y; - } - - if (p.z > node.uz) { - node.uz = p.z; - } - - - node.centroid = node.centroid * node.point_num + point; - node.point_num++; - node.centroid /= node.point_num; - - } else { - node.lx = node.ux = p.x; - node.ly = node.uy = p.y; - node.lz = node.uz = p.z; - - node.centroid = point; - node.point_num = 1; - - setOccupied(nid, level); - } - - node_idx = div(node_idx, 2); - node_idy = div(node_idy, 2); - node_idz = div(node_idz, 2); - } - } + for (int i = 0; i < new_voxels.size(); i++) { + Eigen::Vector3i vid = new_voxels[i]; + int node_idx = div(vid(0), leaf_x_); + int node_idy = div(vid(1), leaf_y_); + int node_idz = div(vid(2), leaf_z_); + PointSourceType p = new_cloud->points[i]; + Eigen::Vector3d point(p.x, p.y, p.z); + + // Go from bottom to top to update tree nodes + for (int level = 0; level < (*octree_).size(); level++) { + int nid = index2id(node_idx, node_idy, node_idz, level); + std::vector &cur_level = (*octree_)[level]; + OctreeNode &node = cur_level[nid]; + + if (isOccupied(nid, level)) { + // If the node is occupied, update the current content + if (p.x < node.lx) { + node.lx = p.x; + } + + if (p.y < node.ly) { + node.ly = p.y; + } + + if (p.z < node.lz) { + node.lz = p.z; + } + + if (p.x > node.ux) { + node.ux = p.x; + } + + if (p.y > node.uy) { + node.uy = p.y; + } + + if (p.z > node.uz) { + node.uz = p.z; + } + + + node.centroid = node.centroid * node.point_num + point; + node.point_num++; + node.centroid /= node.point_num; + + } else { + node.lx = node.ux = p.x; + node.ly = node.uy = p.y; + node.lz = node.uz = p.z; + + node.centroid = point; + node.point_num = 1; + + setOccupied(nid, level); + } + + node_idx = div(node_idx, 2); + node_idy = div(node_idy, 2); + node_idz = div(node_idz, 2); + } + } } template Eigen::Matrix Octree::nearestOctreeNode(PointSourceType q) { - double min_range = DBL_MAX; - int current_nn_vid = -1; + double min_range = DBL_MAX; + int current_nn_vid = -1; - initRange(q, min_range, current_nn_vid); + initRange(q, min_range, current_nn_vid); - Eigen::Vector3i cur_vid = id2index(current_nn_vid, 0); - Eigen::Matrix cur_nn_node(cur_vid(0), cur_vid(1), cur_vid(2), 0); + Eigen::Vector3i cur_vid = id2index(current_nn_vid, 0); + Eigen::Matrix cur_nn_node(cur_vid(0), cur_vid(1), cur_vid(2), 0); - goUp(cur_nn_node, q, min_range, current_nn_vid); + goUp(cur_nn_node, q, min_range, current_nn_vid); - std::vector &bottom = (*octree_)[0]; + std::vector &bottom = (*octree_)[0]; - OctreeNode out_node = bottom[current_nn_vid]; + OctreeNode out_node = bottom[current_nn_vid]; - Eigen::Matrix output; + Eigen::Matrix output; - output(0) = out_node.lx; - output(1) = out_node.ly; - output(2) = out_node.lz; + output(0) = out_node.lx; + output(1) = out_node.ly; + output(2) = out_node.lz; - output(3) = out_node.ux; - output(4) = out_node.uy; - output(5) = out_node.uz; + output(3) = out_node.ux; + output(4) = out_node.uy; + output(5) = out_node.uz; - return output; + return output; } template double Octree::dist(OctreeNode node, PointSourceType p) { - double dx, dy, dz; - - - if (p.x < node.lx) { - dx = node.lx - p.x; - } else if (p.x > node.ux) { - dx = p.x - node.ux; - } else { - dx = 0; - } - - if (p.y < node.ly) { - dy = node.ly - p.y; - } else if (p.y > node.uy) { - dy = p.y - node.uy; - } else { - dy = 0; - } - - if (p.z < node.lz) { - dz = node.lz - p.z; - } else if (p.z > node.uz) { - dz = p.z - node.uz; - } else { - dz = 0; - } - - return sqrt(dx * dx + dy * dy + dz * dz); + double dx, dy, dz; + + + if (p.x < node.lx) { + dx = node.lx - p.x; + } else if (p.x > node.ux) { + dx = p.x - node.ux; + } else { + dx = 0; + } + + if (p.y < node.ly) { + dy = node.ly - p.y; + } else if (p.y > node.uy) { + dy = p.y - node.uy; + } else { + dy = 0; + } + + if (p.z < node.lz) { + dz = node.lz - p.z; + } else if (p.z > node.uz) { + dz = p.z - node.uz; + } else { + dz = 0; + } + + return sqrt(dx * dx + dy * dy + dz * dz); } template void Octree::initRange(PointSourceType q, double &min_range, int &nn_id) { - // Init min_range at maximum double value - min_range = DBL_MAX; - - // Check top - int top_id; - int top_lv = (*octree_).size() - 1; - std::vector &top = (*octree_)[top_lv]; - - for (int i = 0; i < top.size(); i++) { - if (isOccupied(i, top_lv)) { - OctreeNode node = top[i]; - - double cur_dist = dist(node, q); - - if (cur_dist < min_range) { - min_range = cur_dist; - top_id = i; - } - } - } - - - Eigen::Vector3i top_indexes = id2index(top_id, top_lv); - int nidx = top_indexes(0); - int nidy = top_indexes(1); - int nidz = top_indexes(2); - int lower_x, upper_x, lower_y, upper_y, lower_z, upper_z; - - // Go down to leaf - for (int level = (*octree_).size() - 2; level >= 1; level--) { - OctreeLevelBoundaries bounds = (*reserved_size_)[level]; - std::vector &cur_level = (*octree_)[level]; - - lower_x = (nidx * 2 < bounds.lower_x) ? bounds.lower_x : nidx * 2; - upper_x = (nidx * 2 + 1 > bounds.upper_x) ? bounds.upper_x : nidx * 2 + 1; - - lower_y = (nidy * 2 < bounds.lower_y) ? bounds.lower_y : nidy * 2; - upper_y = (nidy * 2 + 1 > bounds.upper_y) ? bounds.upper_y : nidy * 2 + 1; - - lower_z = (nidz * 2 < bounds.lower_z) ? bounds.lower_z : nidz * 2; - upper_z = (nidz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : nidz * 2 + 1; - - min_range = DBL_MAX; - - for (int i = lower_x; i <= upper_x; i++) { - for (int j = lower_y; j <= upper_y; j++) { - for (int k = lower_z; k <= upper_z; k++) { - int node_id = index2id(i, j, k, level); - - if (isOccupied(node_id, level)) { - OctreeNode node = cur_level[node_id]; - double cur_dist = dist(node, q); - - if (cur_dist < min_range) { - min_range = cur_dist; - nidx = i; - nidy = j; - nidz = k; - } - } - } - } - } - } - - // Inspect leaves - OctreeLevelBoundaries bounds = (*reserved_size_)[0]; - std::vector &bottom = (*octree_)[0]; - - lower_x = (nidx * 2 < bounds.lower_x) ? bounds.lower_x : nidx * 2; - upper_x = (nidx * 2 + 1 > bounds.upper_x) ? bounds.upper_x : nidx * 2 + 1; - - lower_y = (nidy * 2 < bounds.lower_y) ? bounds.lower_y : nidy * 2; - upper_y = (nidy * 2 + 1 > bounds.upper_y) ? bounds.upper_y : nidy * 2 + 1; - - lower_z = (nidz * 2 < bounds.lower_z) ? bounds.lower_z : nidz * 2; - upper_z = (nidz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : nidz * 2 + 1; - - min_range = DBL_MAX; - - for (int i = lower_x; i <= upper_x; i++) { - for (int j = lower_y; j <= upper_y; j++) { - for (int k = lower_z; k <= upper_z; k++) { - int node_id = index2id(i, j, k, 0); - - if (isOccupied(node_id, 0)) { - OctreeNode node = bottom[node_id]; - Eigen::Vector3d c = node.centroid; - double cur_dist = sqrt((c(0) - q.x) * (c(0) - q.x) + (c(1) - q.y) * (c(1) - q.y) + (c(2) - q.z) * (c(2) - q.z)); - - if (cur_dist < min_range) { - min_range = cur_dist; - nidx = i; - nidy = j; - nidz = k; - } - } - } - } - } - - nn_id = index2id(nidx, nidy, nidz, 0); + // Init min_range at maximum double value + min_range = DBL_MAX; + + // Check top + int top_id; + int top_lv = (*octree_).size() - 1; + std::vector &top = (*octree_)[top_lv]; + + for (int i = 0; i < top.size(); i++) { + if (isOccupied(i, top_lv)) { + OctreeNode node = top[i]; + + double cur_dist = dist(node, q); + + if (cur_dist < min_range) { + min_range = cur_dist; + top_id = i; + } + } + } + + + Eigen::Vector3i top_indexes = id2index(top_id, top_lv); + int nidx = top_indexes(0); + int nidy = top_indexes(1); + int nidz = top_indexes(2); + int lower_x, upper_x, lower_y, upper_y, lower_z, upper_z; + + // Go down to leaf + for (int level = (*octree_).size() - 2; level >= 1; level--) { + OctreeLevelBoundaries bounds = (*reserved_size_)[level]; + std::vector &cur_level = (*octree_)[level]; + + lower_x = (nidx * 2 < bounds.lower_x) ? bounds.lower_x : nidx * 2; + upper_x = (nidx * 2 + 1 > bounds.upper_x) ? bounds.upper_x : nidx * 2 + 1; + + lower_y = (nidy * 2 < bounds.lower_y) ? bounds.lower_y : nidy * 2; + upper_y = (nidy * 2 + 1 > bounds.upper_y) ? bounds.upper_y : nidy * 2 + 1; + + lower_z = (nidz * 2 < bounds.lower_z) ? bounds.lower_z : nidz * 2; + upper_z = (nidz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : nidz * 2 + 1; + + min_range = DBL_MAX; + + for (int i = lower_x; i <= upper_x; i++) { + for (int j = lower_y; j <= upper_y; j++) { + for (int k = lower_z; k <= upper_z; k++) { + int node_id = index2id(i, j, k, level); + + if (isOccupied(node_id, level)) { + OctreeNode node = cur_level[node_id]; + double cur_dist = dist(node, q); + + if (cur_dist < min_range) { + min_range = cur_dist; + nidx = i; + nidy = j; + nidz = k; + } + } + } + } + } + } + + // Inspect leaves + OctreeLevelBoundaries bounds = (*reserved_size_)[0]; + std::vector &bottom = (*octree_)[0]; + + lower_x = (nidx * 2 < bounds.lower_x) ? bounds.lower_x : nidx * 2; + upper_x = (nidx * 2 + 1 > bounds.upper_x) ? bounds.upper_x : nidx * 2 + 1; + + lower_y = (nidy * 2 < bounds.lower_y) ? bounds.lower_y : nidy * 2; + upper_y = (nidy * 2 + 1 > bounds.upper_y) ? bounds.upper_y : nidy * 2 + 1; + + lower_z = (nidz * 2 < bounds.lower_z) ? bounds.lower_z : nidz * 2; + upper_z = (nidz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : nidz * 2 + 1; + + min_range = DBL_MAX; + + for (int i = lower_x; i <= upper_x; i++) { + for (int j = lower_y; j <= upper_y; j++) { + for (int k = lower_z; k <= upper_z; k++) { + int node_id = index2id(i, j, k, 0); + + if (isOccupied(node_id, 0)) { + OctreeNode node = bottom[node_id]; + Eigen::Vector3d c = node.centroid; + double cur_dist = sqrt((c(0) - q.x) * (c(0) - q.x) + (c(1) - q.y) * (c(1) - q.y) + (c(2) - q.z) * (c(2) - q.z)); + + if (cur_dist < min_range) { + min_range = cur_dist; + nidx = i; + nidy = j; + nidz = k; + } + } + } + } + } + + nn_id = index2id(nidx, nidy, nidz, 0); } // Check all childrens template void Octree::goDown(Eigen::Matrix node, PointSourceType q, double &min_range, int ¤t_nn_voxel) { - int id = index2id(node(0), node(1), node(2), node(3)); + int id = index2id(node(0), node(1), node(2), node(3)); - if (!isOccupied(id, node(3))) { - return; - } + if (!isOccupied(id, node(3))) { + return; + } - std::vector &cur_level = (*octree_)[node(3)]; - OctreeNode cur_node = cur_level[id]; + std::vector &cur_level = (*octree_)[node(3)]; + OctreeNode cur_node = cur_level[id]; - if (node(3) == 0) { - Eigen::Vector3d c = cur_node.centroid; - double cur_dist = sqrt((c(0) - q.x) * (c(0) - q.x) + (c(1) - q.y) * (c(1) - q.y) + (c(2) - q.z) * (c(2) - q.z)); + if (node(3) == 0) { + Eigen::Vector3d c = cur_node.centroid; + double cur_dist = sqrt((c(0) - q.x) * (c(0) - q.x) + (c(1) - q.y) * (c(1) - q.y) + (c(2) - q.z) * (c(2) - q.z)); - if (cur_dist < min_range) { - min_range = cur_dist; - current_nn_voxel = id; - } - } + if (cur_dist < min_range) { + min_range = cur_dist; + current_nn_voxel = id; + } + } - double cur_dist = dist(cur_node, q); + double cur_dist = dist(cur_node, q); - if (cur_dist > min_range) { - return; - } + if (cur_dist > min_range) { + return; + } - // Check children - int level = node(3) - 1; - OctreeLevelBoundaries bounds = (*reserved_size_)[level]; + // Check children + int level = node(3) - 1; + OctreeLevelBoundaries bounds = (*reserved_size_)[level]; - int lower_x = (node(0) * 2 < bounds.lower_x) ? bounds.lower_x : node(0) * 2; - int upper_x = (node(0) * 2 + 1 > bounds.upper_x) ? bounds.upper_x : node(0) * 2 + 1; + int lower_x = (node(0) * 2 < bounds.lower_x) ? bounds.lower_x : node(0) * 2; + int upper_x = (node(0) * 2 + 1 > bounds.upper_x) ? bounds.upper_x : node(0) * 2 + 1; - int lower_y = (node(1) * 2 < bounds.lower_y) ? bounds.lower_y : node(1) * 2; - int upper_y = (node(1) * 2 + 1 > bounds.upper_y) ? bounds.upper_y : node(1) * 2 + 1; + int lower_y = (node(1) * 2 < bounds.lower_y) ? bounds.lower_y : node(1) * 2; + int upper_y = (node(1) * 2 + 1 > bounds.upper_y) ? bounds.upper_y : node(1) * 2 + 1; - int lower_z = (node(2) * 2 < bounds.lower_z) ? bounds.lower_z : node(2) * 2; - int upper_z = (node(2) * 2 + 1 > bounds.upper_z) ? bounds.upper_z : node(2) * 2 + 1; + int lower_z = (node(2) * 2 < bounds.lower_z) ? bounds.lower_z : node(2) * 2; + int upper_z = (node(2) * 2 + 1 > bounds.upper_z) ? bounds.upper_z : node(2) * 2 + 1; - for (int i = lower_x; i <= upper_x; i++) { - for (int j = lower_y; j <= upper_y; j++) { - for (int k = lower_z; k <= upper_z; k++) { - Eigen::Matrix child(i, j, k, level); + for (int i = lower_x; i <= upper_x; i++) { + for (int j = lower_y; j <= upper_y; j++) { + for (int k = lower_z; k <= upper_z; k++) { + Eigen::Matrix child(i, j, k, level); - goDown(child, q, min_range, current_nn_voxel); - } - } - } + goDown(child, q, min_range, current_nn_voxel); + } + } + } } // Check siblings then go up to parent template void Octree::goUp(Eigen::Matrix node, PointSourceType q, double &min_range, int ¤t_nn_voxel) { - if (node(3) == (*octree_).size() - 1) { - // If reaching top - int top_lv = (*octree_).size() - 1; - OctreeLevelBoundaries top_bound = (*reserved_size_)[top_lv]; - - for (int i = top_bound.lower_x; i <= top_bound.upper_x; i++) { - for (int j = top_bound.lower_y; j <= top_bound.upper_y; j++) { - for (int k = top_bound.lower_z; k <= top_bound.upper_z; k++) { - Eigen::Matrix sib(i, j, k, top_lv); - - if (sib != node) { - goDown(sib, q, min_range, current_nn_voxel); - } - } - } - } - - return; - } - - int px = div(node(0), 2); - int py = div(node(1), 2); - int pz = div(node(2), 2); - int level = node(3); - OctreeLevelBoundaries bounds = (*reserved_size_)[level]; - int lower_x = (px * 2 < bounds.lower_x) ? bounds.lower_x : px * 2; - int upper_x = (px * 2 + 1 > bounds.upper_x) ? bounds.upper_x : px * 2 + 1; - int lower_y = (py * 2 < bounds.lower_y) ? bounds.lower_y : py * 2; - int upper_y = (py * 2 + 1 > bounds.upper_y) ? bounds.upper_y : py * 2 + 1; - int lower_z = (pz * 2 < bounds.lower_z) ? bounds.lower_z : pz * 2; - int upper_z = (pz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : pz * 2 + 1; - - for (int i = lower_x; i <= upper_x; i++) { - for (int j = lower_y; j <= upper_y; j++) { - for (int k = lower_z; k <= upper_z; k++) { - Eigen::Matrix sib(i, j, k, level); - - if (sib != node) { - goDown(sib, q, min_range, current_nn_voxel); - } - } - } - } - - - Eigen::Matrix parent(px, py, pz, level + 1); - - goUp(parent, q, min_range, current_nn_voxel); + if (node(3) == (*octree_).size() - 1) { + // If reaching top + int top_lv = (*octree_).size() - 1; + OctreeLevelBoundaries top_bound = (*reserved_size_)[top_lv]; + + for (int i = top_bound.lower_x; i <= top_bound.upper_x; i++) { + for (int j = top_bound.lower_y; j <= top_bound.upper_y; j++) { + for (int k = top_bound.lower_z; k <= top_bound.upper_z; k++) { + Eigen::Matrix sib(i, j, k, top_lv); + + if (sib != node) { + goDown(sib, q, min_range, current_nn_voxel); + } + } + } + } + + return; + } + + int px = div(node(0), 2); + int py = div(node(1), 2); + int pz = div(node(2), 2); + int level = node(3); + OctreeLevelBoundaries bounds = (*reserved_size_)[level]; + int lower_x = (px * 2 < bounds.lower_x) ? bounds.lower_x : px * 2; + int upper_x = (px * 2 + 1 > bounds.upper_x) ? bounds.upper_x : px * 2 + 1; + int lower_y = (py * 2 < bounds.lower_y) ? bounds.lower_y : py * 2; + int upper_y = (py * 2 + 1 > bounds.upper_y) ? bounds.upper_y : py * 2 + 1; + int lower_z = (pz * 2 < bounds.lower_z) ? bounds.lower_z : pz * 2; + int upper_z = (pz * 2 + 1 > bounds.upper_z) ? bounds.upper_z : pz * 2 + 1; + + for (int i = lower_x; i <= upper_x; i++) { + for (int j = lower_y; j <= upper_y; j++) { + for (int k = lower_z; k <= upper_z; k++) { + Eigen::Matrix sib(i, j, k, level); + + if (sib != node) { + goDown(sib, q, min_range, current_nn_voxel); + } + } + } + } + + + Eigen::Matrix parent(px, py, pz, level + 1); + + goUp(parent, q, min_range, current_nn_voxel); } template class Octree; diff --git a/core_perception/ndt_cpu/src/Registration.cpp b/core_perception/ndt_cpu/src/Registration.cpp index e091267be44..5fc2651c075 100644 --- a/core_perception/ndt_cpu/src/Registration.cpp +++ b/core_perception/ndt_cpu/src/Registration.cpp @@ -7,69 +7,69 @@ namespace cpu { template Registration::Registration() { - max_iterations_ = 0; + max_iterations_ = 0; - converged_ = false; - nr_iterations_ = 0; + converged_ = false; + nr_iterations_ = 0; - transformation_epsilon_ = 0; - target_cloud_updated_ = true; + transformation_epsilon_ = 0; + target_cloud_updated_ = true; - trans_cloud_.points.clear(); + trans_cloud_.points.clear(); } template Registration::~Registration() { - return; + return; } template void Registration::setTransformationEpsilon(double trans_eps) { - transformation_epsilon_ = trans_eps; + transformation_epsilon_ = trans_eps; } template double Registration::getTransformationEpsilon() const { - return transformation_epsilon_; + return transformation_epsilon_; } template void Registration::setMaximumIterations(int max_itr) { - max_iterations_ = max_itr; + max_iterations_ = max_itr; } template int Registration::getMaximumIterations() const { - return max_iterations_; + return max_iterations_; } template Eigen::Matrix Registration::getFinalTransformation() const { - return final_transformation_; + return final_transformation_; } template int Registration::getFinalNumIteration() const { - return nr_iterations_; + return nr_iterations_; } template bool Registration::hasConverged() const { - return converged_; + return converged_; } template void Registration::setInputSource(typename pcl::PointCloud::Ptr input) { - source_cloud_ = input; + source_cloud_ = input; } @@ -77,34 +77,34 @@ void Registration::setInputSource(typename pcl template void Registration::setInputTarget(typename pcl::PointCloud::Ptr input) { - target_cloud_ = input; + target_cloud_ = input; } template void Registration::align(const Eigen::Matrix &guess) { - converged_ = false; + converged_ = false; - final_transformation_ = transformation_ = previous_transformation_ = Eigen::Matrix::Identity(); + final_transformation_ = transformation_ = previous_transformation_ = Eigen::Matrix::Identity(); - trans_cloud_.points.resize(source_cloud_->points.size()); + trans_cloud_.points.resize(source_cloud_->points.size()); - for (int i = 0; i < trans_cloud_.points.size(); i++) { - trans_cloud_.points[i] = source_cloud_->points[i]; - } + for (int i = 0; i < trans_cloud_.points.size(); i++) { + trans_cloud_.points[i] = source_cloud_->points[i]; + } - computeTransformation(guess); + computeTransformation(guess); } template void Registration::align(typename pcl::PointCloud &output, const Eigen::Matrix &guess) { - align(guess); + align(guess); } template void Registration::computeTransformation(const Eigen::Matrix &guess) { - printf("Unsupported by Registration\n"); + printf("Unsupported by Registration\n"); } template class Registration; diff --git a/core_perception/ndt_cpu/src/VoxelGrid.cpp b/core_perception/ndt_cpu/src/VoxelGrid.cpp index 8de9c55e727..be369d25e6b 100644 --- a/core_perception/ndt_cpu/src/VoxelGrid.cpp +++ b/core_perception/ndt_cpu/src/VoxelGrid.cpp @@ -16,773 +16,773 @@ namespace cpu { template VoxelGrid::VoxelGrid(): - voxel_num_(0), - max_x_(FLT_MIN), - max_y_(FLT_MIN), - max_z_(FLT_MIN), - min_x_(FLT_MAX), - min_y_(FLT_MAX), - min_z_(FLT_MAX), - voxel_x_(0), - voxel_y_(0), - voxel_z_(0), - max_b_x_(0), - max_b_y_(0), - max_b_z_(0), - min_b_x_(0), - min_b_y_(0), - min_b_z_(0), - vgrid_x_(0), - vgrid_y_(0), - vgrid_z_(0), - min_points_per_voxel_(6), - real_max_bx_(INT_MIN), - real_max_by_(INT_MIN), - real_max_bz_(INT_MIN), - real_min_bx_(INT_MAX), - real_min_by_(INT_MAX), - real_min_bz_(INT_MAX) -{ - centroid_.reset(); - icovariance_.reset(); - points_id_.reset(); - points_per_voxel_.reset(); - tmp_centroid_.reset(); - tmp_cov_.reset(); + voxel_num_(0), + max_x_(FLT_MIN), + max_y_(FLT_MIN), + max_z_(FLT_MIN), + min_x_(FLT_MAX), + min_y_(FLT_MAX), + min_z_(FLT_MAX), + voxel_x_(0), + voxel_y_(0), + voxel_z_(0), + max_b_x_(0), + max_b_y_(0), + max_b_z_(0), + min_b_x_(0), + min_b_y_(0), + min_b_z_(0), + vgrid_x_(0), + vgrid_y_(0), + vgrid_z_(0), + min_points_per_voxel_(6), + real_max_bx_(INT_MIN), + real_max_by_(INT_MIN), + real_max_bz_(INT_MIN), + real_min_bx_(INT_MAX), + real_min_by_(INT_MAX), + real_min_bz_(INT_MAX) +{ + centroid_.reset(); + icovariance_.reset(); + points_id_.reset(); + points_per_voxel_.reset(); + tmp_centroid_.reset(); + tmp_cov_.reset(); }; template int VoxelGrid::roundUp(int input, int factor) { - return (input < 0) ? -((-input) / factor) * factor : ((input + factor - 1) / factor) * factor; + return (input < 0) ? -((-input) / factor) * factor : ((input + factor - 1) / factor) * factor; } template int VoxelGrid::roundDown(int input, int factor) { - return (input < 0) ? -((-input + factor - 1) / factor) * factor : (input / factor) * factor; + return (input < 0) ? -((-input + factor - 1) / factor) * factor : (input / factor) * factor; } template int VoxelGrid::div(int input, int divisor) { - return (input < 0) ? -((-input + divisor - 1) / divisor) : input / divisor; + return (input < 0) ? -((-input + divisor - 1) / divisor) : input / divisor; } template void VoxelGrid::initialize() { - centroid_.reset(); - centroid_ = boost::make_shared >(voxel_num_); + centroid_.reset(); + centroid_ = boost::make_shared >(voxel_num_); - icovariance_.reset(); - icovariance_ = boost::make_shared >(voxel_num_); + icovariance_.reset(); + icovariance_ = boost::make_shared >(voxel_num_); - points_id_.reset(); - points_id_ = boost::make_shared > >(voxel_num_); + points_id_.reset(); + points_id_ = boost::make_shared > >(voxel_num_); - points_per_voxel_.reset(); - points_per_voxel_ = boost::make_shared >(voxel_num_, 0); + points_per_voxel_.reset(); + points_per_voxel_ = boost::make_shared >(voxel_num_, 0); - tmp_centroid_.reset(); - tmp_centroid_ = boost::make_shared >(voxel_num_); + tmp_centroid_.reset(); + tmp_centroid_ = boost::make_shared >(voxel_num_); - tmp_cov_.reset(); - tmp_cov_ = boost::make_shared >(voxel_num_); + tmp_cov_.reset(); + tmp_cov_ = boost::make_shared >(voxel_num_); } template int VoxelGrid::getVoxelNum() const { - return voxel_num_; + return voxel_num_; } template float VoxelGrid::getMaxX() const { - return max_x_; + return max_x_; } template float VoxelGrid::getMaxY() const { - return max_y_; + return max_y_; } template float VoxelGrid::getMaxZ() const { - return max_z_; + return max_z_; } template float VoxelGrid::getMinX() const { - return min_x_; + return min_x_; } template float VoxelGrid::getMinY() const { - return min_y_; + return min_y_; } template float VoxelGrid::getMinZ() const { - return min_z_; + return min_z_; } template float VoxelGrid::getVoxelX() const { - return voxel_x_; + return voxel_x_; } template float VoxelGrid::getVoxelY() const { - return voxel_y_; + return voxel_y_; } template float VoxelGrid::getVoxelZ() const { - return voxel_z_; + return voxel_z_; } template int VoxelGrid::getMaxBX() const { - return max_b_x_; + return max_b_x_; } template int VoxelGrid::getMaxBY() const { - return max_b_y_; + return max_b_y_; } template int VoxelGrid::getMaxBZ() const { - return max_b_z_; + return max_b_z_; } template int VoxelGrid::getMinBX() const { - return min_b_x_; + return min_b_x_; } template int VoxelGrid::getMinBY() const { - return min_b_y_; + return min_b_y_; } template int VoxelGrid::getMinBZ() const { - return min_b_z_; + return min_b_z_; } template int VoxelGrid::getVgridX() const { - return vgrid_x_; + return vgrid_x_; } template int VoxelGrid::getVgridY() const { - return vgrid_y_; + return vgrid_y_; } template int VoxelGrid::getVgridZ() const { - return vgrid_z_; + return vgrid_z_; } template Eigen::Vector3d VoxelGrid::getCentroid(int voxel_id) const { - return (*centroid_)[voxel_id]; + return (*centroid_)[voxel_id]; } template Eigen::Matrix3d VoxelGrid::getInverseCovariance(int voxel_id) const { - return (*icovariance_)[voxel_id]; + return (*icovariance_)[voxel_id]; } template void VoxelGrid::setLeafSize(float voxel_x, float voxel_y, float voxel_z) { - voxel_x_ = voxel_x; - voxel_y_ = voxel_y; - voxel_z_ = voxel_z; + voxel_x_ = voxel_x; + voxel_y_ = voxel_y; + voxel_z_ = voxel_z; } template int VoxelGrid::voxelId(PointSourceType p) { - int idx = static_cast(floor(p.x / voxel_x_)) - min_b_x_; - int idy = static_cast(floor(p.y / voxel_y_)) - min_b_y_; - int idz = static_cast(floor(p.z / voxel_z_)) - min_b_z_; + int idx = static_cast(floor(p.x / voxel_x_)) - min_b_x_; + int idy = static_cast(floor(p.y / voxel_y_)) - min_b_y_; + int idz = static_cast(floor(p.z / voxel_z_)) - min_b_z_; - return (idx + idy * vgrid_x_ + idz * vgrid_x_ * vgrid_y_); + return (idx + idy * vgrid_x_ + idz * vgrid_x_ * vgrid_y_); } template int VoxelGrid::voxelId(PointSourceType p, - float voxel_x, float voxel_y, float voxel_z, - int min_b_x, int min_b_y, int min_b_z, - int vgrid_x, int vgrid_y, int vgrid_z) + float voxel_x, float voxel_y, float voxel_z, + int min_b_x, int min_b_y, int min_b_z, + int vgrid_x, int vgrid_y, int vgrid_z) { - int idx = static_cast(floor(p.x / voxel_x)) - min_b_x; - int idy = static_cast(floor(p.y / voxel_y)) - min_b_y; - int idz = static_cast(floor(p.z / voxel_z)) - min_b_z; + int idx = static_cast(floor(p.x / voxel_x)) - min_b_x; + int idy = static_cast(floor(p.y / voxel_y)) - min_b_y; + int idz = static_cast(floor(p.z / voxel_z)) - min_b_z; - return (idx + idy * vgrid_x + idz * vgrid_x * vgrid_y); + return (idx + idy * vgrid_x + idz * vgrid_x * vgrid_y); } template int VoxelGrid::voxelId(int idx, int idy, int idz, - int min_b_x, int min_b_y, int min_b_z, - int size_x, int size_y, int size_z) + int min_b_x, int min_b_y, int min_b_z, + int size_x, int size_y, int size_z) { - return (idx - min_b_x) + (idy - min_b_y) * size_x + (idz - min_b_z) * size_x * size_y; + return (idx - min_b_x) + (idy - min_b_y) * size_x + (idz - min_b_z) * size_x * size_y; } template void VoxelGrid::computeCentroidAndCovariance() { - for (int idx = real_min_bx_; idx <= real_max_bx_; idx++) - for (int idy = real_min_by_; idy <= real_max_by_; idy++) - for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) { - int i = voxelId(idx, idy, idz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); - int ipoint_num = (*points_id_)[i].size(); - double point_num = static_cast(ipoint_num); - Eigen::Vector3d pt_sum = (*tmp_centroid_)[i]; + for (int idx = real_min_bx_; idx <= real_max_bx_; idx++) + for (int idy = real_min_by_; idy <= real_max_by_; idy++) + for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) { + int i = voxelId(idx, idy, idz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); + int ipoint_num = (*points_id_)[i].size(); + double point_num = static_cast(ipoint_num); + Eigen::Vector3d pt_sum = (*tmp_centroid_)[i]; - if (ipoint_num > 0) { - (*centroid_)[i] = pt_sum / point_num; - } + if (ipoint_num > 0) { + (*centroid_)[i] = pt_sum / point_num; + } - Eigen::Matrix3d covariance; + Eigen::Matrix3d covariance; - if (ipoint_num >= min_points_per_voxel_) { - covariance = ((*tmp_cov_)[i] - 2.0 * (pt_sum * (*centroid_)[i].transpose())) / point_num + (*centroid_)[i] * (*centroid_)[i].transpose(); - covariance *= (point_num - 1.0) / point_num; + if (ipoint_num >= min_points_per_voxel_) { + covariance = ((*tmp_cov_)[i] - 2.0 * (pt_sum * (*centroid_)[i].transpose())) / point_num + (*centroid_)[i] * (*centroid_)[i].transpose(); + covariance *= (point_num - 1.0) / point_num; - SymmetricEigensolver3x3 sv(covariance); + SymmetricEigensolver3x3 sv(covariance); - sv.compute(); - Eigen::Matrix3d evecs = sv.eigenvectors(); - Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal(); + sv.compute(); + Eigen::Matrix3d evecs = sv.eigenvectors(); + Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal(); - if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) { - (*points_per_voxel_)[i] = -1; - continue; - } + if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) { + (*points_per_voxel_)[i] = -1; + continue; + } - double min_cov_eigvalue = evals(2, 2) * 0.01; + double min_cov_eigvalue = evals(2, 2) * 0.01; - if (evals(0, 0) < min_cov_eigvalue) { - evals(0, 0) = min_cov_eigvalue; + if (evals(0, 0) < min_cov_eigvalue) { + evals(0, 0) = min_cov_eigvalue; - if (evals(1, 1) < min_cov_eigvalue) { - evals(1, 1) = min_cov_eigvalue; - } + if (evals(1, 1) < min_cov_eigvalue) { + evals(1, 1) = min_cov_eigvalue; + } - covariance = evecs * evals * evecs.inverse(); - } + covariance = evecs * evals * evecs.inverse(); + } - (*icovariance_)[i] = covariance.inverse(); - } - } + (*icovariance_)[i] = covariance.inverse(); + } + } } //Input are supposed to be in device memory template void VoxelGrid::setInput(typename pcl::PointCloud::Ptr input_cloud) { - if (input_cloud->points.size() > 0) { - /* If no voxel grid was created, then - * build the initial voxel grid and octree - */ - source_cloud_ = input_cloud; + if (input_cloud->points.size() > 0) { + /* If no voxel grid was created, then + * build the initial voxel grid and octree + */ + source_cloud_ = input_cloud; - findBoundaries(); + findBoundaries(); - std::vector voxel_ids(input_cloud->points.size()); + std::vector voxel_ids(input_cloud->points.size()); - for (int i = 0; i < input_cloud->points.size(); i++) { - Eigen::Vector3i &vid = voxel_ids[i]; - PointSourceType p = input_cloud->points[i]; + for (int i = 0; i < input_cloud->points.size(); i++) { + Eigen::Vector3i &vid = voxel_ids[i]; + PointSourceType p = input_cloud->points[i]; - vid(0) = static_cast(floor(p.x / voxel_x_)); - vid(1) = static_cast(floor(p.y / voxel_y_)); - vid(2) = static_cast(floor(p.z / voxel_z_)); - } + vid(0) = static_cast(floor(p.x / voxel_x_)); + vid(1) = static_cast(floor(p.y / voxel_y_)); + vid(2) = static_cast(floor(p.z / voxel_z_)); + } - octree_.setInput(voxel_ids, input_cloud); + octree_.setInput(voxel_ids, input_cloud); - voxel_ids.clear(); + voxel_ids.clear(); - initialize(); + initialize(); - scatterPointsToVoxelGrid(); + scatterPointsToVoxelGrid(); - computeCentroidAndCovariance(); - } + computeCentroidAndCovariance(); + } } template void VoxelGrid::findBoundaries() { - findBoundaries(source_cloud_, max_x_, max_y_, max_z_, min_x_, min_y_, min_z_); + findBoundaries(source_cloud_, max_x_, max_y_, max_z_, min_x_, min_y_, min_z_); - real_max_bx_ = max_b_x_ = static_cast (floor(max_x_ / voxel_x_)); - real_max_by_ = max_b_y_ = static_cast (floor(max_y_ / voxel_y_)); - real_max_bz_ = max_b_z_ = static_cast (floor(max_z_ / voxel_z_)); + real_max_bx_ = max_b_x_ = static_cast (floor(max_x_ / voxel_x_)); + real_max_by_ = max_b_y_ = static_cast (floor(max_y_ / voxel_y_)); + real_max_bz_ = max_b_z_ = static_cast (floor(max_z_ / voxel_z_)); - real_min_bx_ = min_b_x_ = static_cast (floor(min_x_ / voxel_x_)); - real_min_by_ = min_b_y_ = static_cast (floor(min_y_ / voxel_y_)); - real_min_bz_ = min_b_z_ = static_cast (floor(min_z_ / voxel_z_)); + real_min_bx_ = min_b_x_ = static_cast (floor(min_x_ / voxel_x_)); + real_min_by_ = min_b_y_ = static_cast (floor(min_y_ / voxel_y_)); + real_min_bz_ = min_b_z_ = static_cast (floor(min_z_ / voxel_z_)); - /* Allocate a poll of memory that is larger than the requested memory so - * we do not have to reallocate buffers when the target cloud is set - */ - /* Max bounds round toward plus infinity */ - max_b_x_ = roundUp(max_b_x_, MAX_BX_); - max_b_y_ = roundUp(max_b_y_, MAX_BY_); - max_b_z_ = roundUp(max_b_z_, MAX_BZ_); + /* Allocate a poll of memory that is larger than the requested memory so + * we do not have to reallocate buffers when the target cloud is set + */ + /* Max bounds round toward plus infinity */ + max_b_x_ = roundUp(max_b_x_, MAX_BX_); + max_b_y_ = roundUp(max_b_y_, MAX_BY_); + max_b_z_ = roundUp(max_b_z_, MAX_BZ_); - /* Min bounds round toward minus infinity */ - min_b_x_ = roundDown(min_b_x_, MAX_BX_); - min_b_y_ = roundDown(min_b_y_, MAX_BY_); - min_b_z_ = roundDown(min_b_z_, MAX_BZ_); + /* Min bounds round toward minus infinity */ + min_b_x_ = roundDown(min_b_x_, MAX_BX_); + min_b_y_ = roundDown(min_b_y_, MAX_BY_); + min_b_z_ = roundDown(min_b_z_, MAX_BZ_); - vgrid_x_ = max_b_x_ - min_b_x_ + 1; - vgrid_y_ = max_b_y_ - min_b_y_ + 1; - vgrid_z_ = max_b_z_ - min_b_z_ + 1; + vgrid_x_ = max_b_x_ - min_b_x_ + 1; + vgrid_y_ = max_b_y_ - min_b_y_ + 1; + vgrid_z_ = max_b_z_ - min_b_z_ + 1; - if (vgrid_x_ > 0 && vgrid_y_ > 0 && vgrid_z_ > 0) { - voxel_num_ = vgrid_x_ * vgrid_y_ * vgrid_z_; - } else { - voxel_num_ = 0; - } + if (vgrid_x_ > 0 && vgrid_y_ > 0 && vgrid_z_ > 0) { + voxel_num_ = vgrid_x_ * vgrid_y_ * vgrid_z_; + } else { + voxel_num_ = 0; + } } template void VoxelGrid::findBoundaries(typename pcl::PointCloud::Ptr input_cloud, - float &max_x, float &max_y, float &max_z, - float &min_x, float &min_y, float &min_z) + float &max_x, float &max_y, float &max_z, + float &min_x, float &min_y, float &min_z) { - max_x = max_y = max_z = -FLT_MAX; - min_x = min_y = min_z = FLT_MAX; + max_x = max_y = max_z = -FLT_MAX; + min_x = min_y = min_z = FLT_MAX; - for (int i = 0; i < input_cloud->points.size(); i++) { - float x = input_cloud->points[i].x; - float y = input_cloud->points[i].y; - float z = input_cloud->points[i].z; + for (int i = 0; i < input_cloud->points.size(); i++) { + float x = input_cloud->points[i].x; + float y = input_cloud->points[i].y; + float z = input_cloud->points[i].z; - max_x = (max_x > x) ? max_x : x; - max_y = (max_y > y) ? max_y : y; - max_z = (max_z > z) ? max_z : z; + max_x = (max_x > x) ? max_x : x; + max_y = (max_y > y) ? max_y : y; + max_z = (max_z > z) ? max_z : z; - min_x = (min_x < x) ? min_x : x; - min_y = (min_y < y) ? min_y : y; - min_z = (min_z < z) ? min_z : z; - } + min_x = (min_x < x) ? min_x : x; + min_y = (min_y < y) ? min_y : y; + min_z = (min_z < z) ? min_z : z; + } } template void VoxelGrid::radiusSearch(PointSourceType p, float radius, std::vector &voxel_ids, int max_nn) { - float t_x = p.x; - float t_y = p.y; - float t_z = p.z; + float t_x = p.x; + float t_y = p.y; + float t_z = p.z; - int max_id_x = static_cast(floor((t_x + radius) / voxel_x_)); - int max_id_y = static_cast(floor((t_y + radius) / voxel_y_)); - int max_id_z = static_cast(floor((t_z + radius) / voxel_z_)); + int max_id_x = static_cast(floor((t_x + radius) / voxel_x_)); + int max_id_y = static_cast(floor((t_y + radius) / voxel_y_)); + int max_id_z = static_cast(floor((t_z + radius) / voxel_z_)); - int min_id_x = static_cast(floor((t_x - radius) / voxel_x_)); - int min_id_y = static_cast(floor((t_y - radius) / voxel_y_)); - int min_id_z = static_cast(floor((t_z - radius) / voxel_z_)); + int min_id_x = static_cast(floor((t_x - radius) / voxel_x_)); + int min_id_y = static_cast(floor((t_y - radius) / voxel_y_)); + int min_id_z = static_cast(floor((t_z - radius) / voxel_z_)); - /* Find intersection of the cube containing - * the NN sphere of the point and the voxel grid - */ - max_id_x = (max_id_x > real_max_bx_) ? real_max_bx_ : max_id_x; - max_id_y = (max_id_y > real_max_by_) ? real_max_by_ : max_id_y; - max_id_z = (max_id_z > real_max_bz_) ? real_max_bz_ : max_id_z; + /* Find intersection of the cube containing + * the NN sphere of the point and the voxel grid + */ + max_id_x = (max_id_x > real_max_bx_) ? real_max_bx_ : max_id_x; + max_id_y = (max_id_y > real_max_by_) ? real_max_by_ : max_id_y; + max_id_z = (max_id_z > real_max_bz_) ? real_max_bz_ : max_id_z; - min_id_x = (min_id_x < real_min_bx_) ? real_min_bx_ : min_id_x; - min_id_y = (min_id_y < real_min_by_) ? real_min_by_ : min_id_y; - min_id_z = (min_id_z < real_min_bz_) ? real_min_bz_ : min_id_z; - int nn = 0; + min_id_x = (min_id_x < real_min_bx_) ? real_min_bx_ : min_id_x; + min_id_y = (min_id_y < real_min_by_) ? real_min_by_ : min_id_y; + min_id_z = (min_id_z < real_min_bz_) ? real_min_bz_ : min_id_z; + int nn = 0; - for (int idx = min_id_x; idx <= max_id_x && nn < max_nn; idx++) { - for (int idy = min_id_y; idy <= max_id_y && nn < max_nn; idy++) { - for (int idz = min_id_z; idz <= max_id_z && nn < max_nn; idz++) { - int vid = voxelId(idx, idy, idz, - min_b_x_, min_b_y_, min_b_z_, - vgrid_x_, vgrid_y_, vgrid_z_); + for (int idx = min_id_x; idx <= max_id_x && nn < max_nn; idx++) { + for (int idy = min_id_y; idy <= max_id_y && nn < max_nn; idy++) { + for (int idz = min_id_z; idz <= max_id_z && nn < max_nn; idz++) { + int vid = voxelId(idx, idy, idz, + min_b_x_, min_b_y_, min_b_z_, + vgrid_x_, vgrid_y_, vgrid_z_); - if ((*points_per_voxel_)[vid] >= min_points_per_voxel_) { - double cx = (*centroid_)[vid](0) - static_cast(t_x); - double cy = (*centroid_)[vid](1) - static_cast(t_y); - double cz = (*centroid_)[vid](2) - static_cast(t_z); + if ((*points_per_voxel_)[vid] >= min_points_per_voxel_) { + double cx = (*centroid_)[vid](0) - static_cast(t_x); + double cy = (*centroid_)[vid](1) - static_cast(t_y); + double cz = (*centroid_)[vid](2) - static_cast(t_z); - double distance = sqrt(cx * cx + cy * cy + cz * cz); + double distance = sqrt(cx * cx + cy * cy + cz * cz); - if (distance < radius) { - nn++; - voxel_ids.push_back(vid); - } - } - } - } - } + if (distance < radius) { + nn++; + voxel_ids.push_back(vid); + } + } + } + } + } } template void VoxelGrid::scatterPointsToVoxelGrid() { - for (int pid = 0; pid < source_cloud_->points.size(); pid++) { - int vid = voxelId(source_cloud_->points[pid]); - PointSourceType p = source_cloud_->points[pid]; + for (int pid = 0; pid < source_cloud_->points.size(); pid++) { + int vid = voxelId(source_cloud_->points[pid]); + PointSourceType p = source_cloud_->points[pid]; - Eigen::Vector3d p3d(p.x, p.y, p.z); + Eigen::Vector3d p3d(p.x, p.y, p.z); - if ((*points_id_)[vid].size() == 0) { - (*centroid_)[vid].setZero(); - (*points_per_voxel_)[vid] = 0; - (*tmp_centroid_)[vid].setZero(); - (*tmp_cov_)[vid].setIdentity(); - } + if ((*points_id_)[vid].size() == 0) { + (*centroid_)[vid].setZero(); + (*points_per_voxel_)[vid] = 0; + (*tmp_centroid_)[vid].setZero(); + (*tmp_cov_)[vid].setIdentity(); + } - (*tmp_centroid_)[vid] += p3d; - (*tmp_cov_)[vid] += p3d * p3d.transpose(); - (*points_id_)[vid].push_back(pid); - (*points_per_voxel_)[vid]++; - } + (*tmp_centroid_)[vid] += p3d; + (*tmp_cov_)[vid] += p3d * p3d.transpose(); + (*points_id_)[vid].push_back(pid); + (*points_per_voxel_)[vid]++; + } } template int VoxelGrid::nearestVoxel(PointSourceType query_point, Eigen::Matrix boundaries, float max_range) { - // Index of the origin of the circle (query point) - float qx = query_point.x; - float qy = query_point.y; - float qz = query_point.z; + // Index of the origin of the circle (query point) + float qx = query_point.x; + float qy = query_point.y; + float qz = query_point.z; - int lower_x = static_cast(floor(boundaries(0) / voxel_x_)); - int lower_y = static_cast(floor(boundaries(1) / voxel_y_)); - int lower_z = static_cast(floor(boundaries(2) / voxel_z_)); + int lower_x = static_cast(floor(boundaries(0) / voxel_x_)); + int lower_y = static_cast(floor(boundaries(1) / voxel_y_)); + int lower_z = static_cast(floor(boundaries(2) / voxel_z_)); - int upper_x = static_cast(floor(boundaries(3) / voxel_x_)); - int upper_y = static_cast(floor(boundaries(4) / voxel_y_)); - int upper_z = static_cast(floor(boundaries(5) / voxel_z_)); + int upper_x = static_cast(floor(boundaries(3) / voxel_x_)); + int upper_y = static_cast(floor(boundaries(4) / voxel_y_)); + int upper_z = static_cast(floor(boundaries(5) / voxel_z_)); - double min_dist = DBL_MAX; - int nn_vid = -1; + double min_dist = DBL_MAX; + int nn_vid = -1; - for (int i = lower_x; i <= upper_x; i++) { - for (int j = lower_y; j <= upper_y; j++) { - for (int k = lower_z; k <= upper_z; k++) { - int vid = voxelId(i, j, k, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); - Eigen::Vector3d c = (*centroid_)[vid]; + for (int i = lower_x; i <= upper_x; i++) { + for (int j = lower_y; j <= upper_y; j++) { + for (int k = lower_z; k <= upper_z; k++) { + int vid = voxelId(i, j, k, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); + Eigen::Vector3d c = (*centroid_)[vid]; - if ((*points_id_)[vid].size() > 0) { - double cur_dist = sqrt((qx - c(0)) * (qx - c(0)) + (qy - c(1)) * (qy - c(1)) + (qz - c(2)) * (qz - c(2))); + if ((*points_id_)[vid].size() > 0) { + double cur_dist = sqrt((qx - c(0)) * (qx - c(0)) + (qy - c(1)) * (qy - c(1)) + (qz - c(2)) * (qz - c(2))); - if (cur_dist < min_dist) { - min_dist = cur_dist; - nn_vid = vid; - } - } - } - } - } + if (cur_dist < min_dist) { + min_dist = cur_dist; + nn_vid = vid; + } + } + } + } + } - return nn_vid; + return nn_vid; } template double VoxelGrid::nearestNeighborDistance(PointSourceType q, float max_range) { - Eigen::Matrix nn_node_bounds; + Eigen::Matrix nn_node_bounds; - nn_node_bounds = octree_.nearestOctreeNode(q); + nn_node_bounds = octree_.nearestOctreeNode(q); - int nn_vid = nearestVoxel(q, nn_node_bounds, max_range); + int nn_vid = nearestVoxel(q, nn_node_bounds, max_range); - Eigen::Vector3d c = (*centroid_)[nn_vid]; - double min_dist = sqrt((q.x - c(0)) * (q.x - c(0)) + (q.y - c(1)) * (q.y - c(1)) + (q.z - c(2)) * (q.z - c(2))); + Eigen::Vector3d c = (*centroid_)[nn_vid]; + double min_dist = sqrt((q.x - c(0)) * (q.x - c(0)) + (q.y - c(1)) * (q.y - c(1)) + (q.z - c(2)) * (q.z - c(2))); - if (min_dist >= max_range) { - return DBL_MAX; - } + if (min_dist >= max_range) { + return DBL_MAX; + } - return min_dist; + return min_dist; } template void VoxelGrid::updateBoundaries(float max_x, float max_y, float max_z, - float min_x, float min_y, float min_z) -{ - - float new_max_x, new_max_y, new_max_z; - float new_min_x, new_min_y, new_min_z; - - new_max_x = (max_x_ >= max_x) ? max_x_ : max_x; - new_max_y = (max_y_ >= max_y) ? max_y_ : max_y; - new_max_z = (max_z_ >= max_z) ? max_z_ : max_z; - - new_min_x = (min_x_ <= min_x) ? min_x_ : min_x; - new_min_y = (min_y_ <= min_y) ? min_y_ : min_y; - new_min_z = (min_z_ <= min_z) ? min_z_ : min_z; - - /* If the boundaries change, then we need to extend the list of voxels */ - if (new_max_x > max_x_ || new_max_y > max_y_ || new_max_z > max_z_ || - new_min_x < min_x_ || new_min_y < min_y_ || new_min_z < min_z_) { - - int max_b_x = static_cast (floor(new_max_x / voxel_x_)); - int max_b_y = static_cast (floor(new_max_y / voxel_y_)); - int max_b_z = static_cast (floor(new_max_z / voxel_z_)); - - int min_b_x = static_cast (floor(new_min_x / voxel_x_)); - int min_b_y = static_cast (floor(new_min_y / voxel_y_)); - int min_b_z = static_cast (floor(new_min_z / voxel_z_)); - - int real_max_bx = max_b_x; - int real_max_by = max_b_y; - int real_max_bz = max_b_z; - - int real_min_bx = min_b_x; - int real_min_by = min_b_y; - int real_min_bz = min_b_z; + float min_x, float min_y, float min_z) +{ + + float new_max_x, new_max_y, new_max_z; + float new_min_x, new_min_y, new_min_z; + + new_max_x = (max_x_ >= max_x) ? max_x_ : max_x; + new_max_y = (max_y_ >= max_y) ? max_y_ : max_y; + new_max_z = (max_z_ >= max_z) ? max_z_ : max_z; + + new_min_x = (min_x_ <= min_x) ? min_x_ : min_x; + new_min_y = (min_y_ <= min_y) ? min_y_ : min_y; + new_min_z = (min_z_ <= min_z) ? min_z_ : min_z; + + /* If the boundaries change, then we need to extend the list of voxels */ + if (new_max_x > max_x_ || new_max_y > max_y_ || new_max_z > max_z_ || + new_min_x < min_x_ || new_min_y < min_y_ || new_min_z < min_z_) { + + int max_b_x = static_cast (floor(new_max_x / voxel_x_)); + int max_b_y = static_cast (floor(new_max_y / voxel_y_)); + int max_b_z = static_cast (floor(new_max_z / voxel_z_)); + + int min_b_x = static_cast (floor(new_min_x / voxel_x_)); + int min_b_y = static_cast (floor(new_min_y / voxel_y_)); + int min_b_z = static_cast (floor(new_min_z / voxel_z_)); + + int real_max_bx = max_b_x; + int real_max_by = max_b_y; + int real_max_bz = max_b_z; + + int real_min_bx = min_b_x; + int real_min_by = min_b_y; + int real_min_bz = min_b_z; - /* Max bounds round toward plus infinity */ - max_b_x = roundUp(max_b_x, MAX_BX_); - max_b_y = roundUp(max_b_y, MAX_BY_); - max_b_z = roundUp(max_b_z, MAX_BZ_); + /* Max bounds round toward plus infinity */ + max_b_x = roundUp(max_b_x, MAX_BX_); + max_b_y = roundUp(max_b_y, MAX_BY_); + max_b_z = roundUp(max_b_z, MAX_BZ_); - /* Min bounds round toward minus infinity */ - min_b_x = roundDown(min_b_x, MAX_BX_); - min_b_y = roundDown(min_b_y, MAX_BY_); - min_b_z = roundDown(min_b_z, MAX_BZ_); + /* Min bounds round toward minus infinity */ + min_b_x = roundDown(min_b_x, MAX_BX_); + min_b_y = roundDown(min_b_y, MAX_BY_); + min_b_z = roundDown(min_b_z, MAX_BZ_); - if (max_b_x > max_b_x_ || max_b_y > max_b_y_ || max_b_z > max_b_z_ || - min_b_x < min_b_x_ || min_b_y < min_b_y_ || min_b_z < min_b_z_) { - int vgrid_x = max_b_x - min_b_x + 1; - int vgrid_y = max_b_y - min_b_y + 1; - int vgrid_z = max_b_z - min_b_z + 1; + if (max_b_x > max_b_x_ || max_b_y > max_b_y_ || max_b_z > max_b_z_ || + min_b_x < min_b_x_ || min_b_y < min_b_y_ || min_b_z < min_b_z_) { + int vgrid_x = max_b_x - min_b_x + 1; + int vgrid_y = max_b_y - min_b_y + 1; + int vgrid_z = max_b_z - min_b_z + 1; - int voxel_num = vgrid_x * vgrid_y * vgrid_z; + int voxel_num = vgrid_x * vgrid_y * vgrid_z; - boost::shared_ptr > old_centroid = centroid_; - boost::shared_ptr > old_icovariance = icovariance_; - boost::shared_ptr > > old_points_id = points_id_; - boost::shared_ptr > old_points_per_voxel = points_per_voxel_; + boost::shared_ptr > old_centroid = centroid_; + boost::shared_ptr > old_icovariance = icovariance_; + boost::shared_ptr > > old_points_id = points_id_; + boost::shared_ptr > old_points_per_voxel = points_per_voxel_; - boost::shared_ptr > old_tmp_centroid = tmp_centroid_; - boost::shared_ptr > old_tmp_cov = tmp_cov_; + boost::shared_ptr > old_tmp_centroid = tmp_centroid_; + boost::shared_ptr > old_tmp_cov = tmp_cov_; - centroid_ = boost::make_shared >(voxel_num); - icovariance_ = boost::make_shared >(voxel_num); - points_id_ = boost::make_shared > >(voxel_num); - points_per_voxel_ = boost::make_shared >(voxel_num, 0); - tmp_centroid_ = boost::make_shared >(voxel_num); - tmp_cov_ = boost::make_shared >(voxel_num); + centroid_ = boost::make_shared >(voxel_num); + icovariance_ = boost::make_shared >(voxel_num); + points_id_ = boost::make_shared > >(voxel_num); + points_per_voxel_ = boost::make_shared >(voxel_num, 0); + tmp_centroid_ = boost::make_shared >(voxel_num); + tmp_cov_ = boost::make_shared >(voxel_num); - // Move the old non-empty voxels to the new list of voxels + // Move the old non-empty voxels to the new list of voxels - int idx, idy, idz; - int old_id, new_id; + int idx, idy, idz; + int old_id, new_id; - for (int idx = real_min_bx_; idx <= real_max_bx_; idx++) { - for (int idy = real_min_by_; idy <= real_max_by_; idy++) { - for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) { - old_id = voxelId(idx, idy, idz, - min_b_x_, min_b_y_, min_b_z_, - vgrid_x_, vgrid_y_, vgrid_z_); - new_id = voxelId(idx, idy, idz, - min_b_x, min_b_y, min_b_z, - vgrid_x, vgrid_y, vgrid_z); + for (int idx = real_min_bx_; idx <= real_max_bx_; idx++) { + for (int idy = real_min_by_; idy <= real_max_by_; idy++) { + for (int idz = real_min_bz_; idz <= real_max_bz_; idz++) { + old_id = voxelId(idx, idy, idz, + min_b_x_, min_b_y_, min_b_z_, + vgrid_x_, vgrid_y_, vgrid_z_); + new_id = voxelId(idx, idy, idz, + min_b_x, min_b_y, min_b_z, + vgrid_x, vgrid_y, vgrid_z); - if ((*old_points_id)[old_id].size() > 0) { - (*points_per_voxel_)[new_id] = (*old_points_per_voxel)[old_id]; - (*centroid_)[new_id] = (*old_centroid)[old_id]; - (*icovariance_)[new_id] = (*old_icovariance)[old_id]; - (*points_id_)[new_id] = (*old_points_id)[old_id]; + if ((*old_points_id)[old_id].size() > 0) { + (*points_per_voxel_)[new_id] = (*old_points_per_voxel)[old_id]; + (*centroid_)[new_id] = (*old_centroid)[old_id]; + (*icovariance_)[new_id] = (*old_icovariance)[old_id]; + (*points_id_)[new_id] = (*old_points_id)[old_id]; - (*tmp_centroid_)[new_id] = (*old_tmp_centroid)[old_id]; - (*tmp_cov_)[new_id] = (*old_tmp_cov)[old_id]; - } - } - } - } + (*tmp_centroid_)[new_id] = (*old_tmp_centroid)[old_id]; + (*tmp_cov_)[new_id] = (*old_tmp_cov)[old_id]; + } + } + } + } - // Update boundaries of voxels - max_b_x_ = max_b_x; - max_b_y_ = max_b_y; - max_b_z_ = max_b_z; + // Update boundaries of voxels + max_b_x_ = max_b_x; + max_b_y_ = max_b_y; + max_b_z_ = max_b_z; - min_b_x_ = min_b_x; - min_b_y_ = min_b_y; - min_b_z_ = min_b_z; + min_b_x_ = min_b_x; + min_b_y_ = min_b_y; + min_b_z_ = min_b_z; - vgrid_x_ = vgrid_x; - vgrid_y_ = vgrid_y; - vgrid_z_ = vgrid_z; + vgrid_x_ = vgrid_x; + vgrid_y_ = vgrid_y; + vgrid_z_ = vgrid_z; - voxel_num_ = voxel_num; + voxel_num_ = voxel_num; - } - // Update actual voxel boundaries - real_min_bx_ = real_min_bx; - real_min_by_ = real_min_by; - real_min_bz_ = real_min_bz; + } + // Update actual voxel boundaries + real_min_bx_ = real_min_bx; + real_min_by_ = real_min_by; + real_min_bz_ = real_min_bz; - real_max_bx_ = real_max_bx; - real_max_by_ = real_max_by; - real_max_bz_ = real_max_bz; + real_max_bx_ = real_max_bx; + real_max_by_ = real_max_by; + real_max_bz_ = real_max_bz; - //Update boundaries of points - max_x_ = new_max_x; - max_y_ = new_max_y; - max_z_ = new_max_z; + //Update boundaries of points + max_x_ = new_max_x; + max_y_ = new_max_y; + max_z_ = new_max_z; - min_x_ = new_min_x; - min_y_ = new_min_y; - min_z_ = new_min_z; + min_x_ = new_min_x; + min_y_ = new_min_y; + min_z_ = new_min_z; - } + } } template void VoxelGrid::update(typename pcl::PointCloud::Ptr new_cloud) { - if (new_cloud->points.size() <= 0) { - return; - } + if (new_cloud->points.size() <= 0) { + return; + } - float new_max_x, new_max_y, new_max_z; - float new_min_x, new_min_y, new_min_z; + float new_max_x, new_max_y, new_max_z; + float new_min_x, new_min_y, new_min_z; - // Find boundaries of the new point cloud - findBoundaries(new_cloud, new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z); + // Find boundaries of the new point cloud + findBoundaries(new_cloud, new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z); - /* Update current boundaries of the voxel grid - * Also allocate buffer for new voxel grid and - * octree and move the current voxel grid and - * octree to the new buffer if necessary - */ - updateBoundaries(new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z); + /* Update current boundaries of the voxel grid + * Also allocate buffer for new voxel grid and + * octree and move the current voxel grid and + * octree to the new buffer if necessary + */ + updateBoundaries(new_max_x, new_max_y, new_max_z, new_min_x, new_min_y, new_min_z); - /* Update changed voxels (voxels that contains new points). - * Update centroids of voxels and their covariance matrixes - * as well as inverse covariance matrixes */ - updateVoxelContent(new_cloud); + /* Update changed voxels (voxels that contains new points). + * Update centroids of voxels and their covariance matrixes + * as well as inverse covariance matrixes */ + updateVoxelContent(new_cloud); - /* Update octree */ - std::vector new_voxel_id(new_cloud->points.size()); + /* Update octree */ + std::vector new_voxel_id(new_cloud->points.size()); - for (int i = 0; i < new_cloud->points.size(); i++) { - Eigen::Vector3i &vid = new_voxel_id[i]; - PointSourceType p = new_cloud->points[i]; + for (int i = 0; i < new_cloud->points.size(); i++) { + Eigen::Vector3i &vid = new_voxel_id[i]; + PointSourceType p = new_cloud->points[i]; - vid(0) = static_cast(floor(p.x / voxel_x_)); - vid(1) = static_cast(floor(p.y / voxel_y_)); - vid(2) = static_cast(floor(p.z / voxel_z_)); - } + vid(0) = static_cast(floor(p.x / voxel_x_)); + vid(1) = static_cast(floor(p.y / voxel_y_)); + vid(2) = static_cast(floor(p.z / voxel_z_)); + } - octree_.update(new_voxel_id, new_cloud); + octree_.update(new_voxel_id, new_cloud); - *source_cloud_ += *new_cloud; + *source_cloud_ += *new_cloud; } template void VoxelGrid::updateVoxelContent(typename pcl::PointCloud::Ptr new_cloud) { - int total_points_num = source_cloud_->points.size(); + int total_points_num = source_cloud_->points.size(); - for (int i = 0; i < new_cloud->points.size(); i++) { - PointSourceType p = new_cloud->points[i]; - Eigen::Vector3d p3d(p.x, p.y, p.z); - int vx = static_cast(floor(p.x / voxel_x_)); - int vy = static_cast(floor(p.y / voxel_y_)); - int vz = static_cast(floor(p.z / voxel_z_)); - int vid = voxelId(vx, vy, vz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); - std::vector &tmp_pid = (*points_id_)[vid]; + for (int i = 0; i < new_cloud->points.size(); i++) { + PointSourceType p = new_cloud->points[i]; + Eigen::Vector3d p3d(p.x, p.y, p.z); + int vx = static_cast(floor(p.x / voxel_x_)); + int vy = static_cast(floor(p.y / voxel_y_)); + int vz = static_cast(floor(p.z / voxel_z_)); + int vid = voxelId(vx, vy, vz, min_b_x_, min_b_y_, min_b_z_, vgrid_x_, vgrid_y_, vgrid_z_); + std::vector &tmp_pid = (*points_id_)[vid]; - if (tmp_pid.size() == 0) { - (*centroid_)[vid].setZero(); - (*tmp_cov_)[vid].setIdentity(); - (*tmp_centroid_)[vid].setZero(); - } + if (tmp_pid.size() == 0) { + (*centroid_)[vid].setZero(); + (*tmp_cov_)[vid].setIdentity(); + (*tmp_centroid_)[vid].setZero(); + } - (*tmp_centroid_)[vid] += p3d; - (*tmp_cov_)[vid] += p3d * p3d.transpose(); - (*points_id_)[vid].push_back(total_points_num + i); + (*tmp_centroid_)[vid] += p3d; + (*tmp_cov_)[vid] += p3d * p3d.transpose(); + (*points_id_)[vid].push_back(total_points_num + i); - // Update centroids - int ipoint_num = (*points_id_)[vid].size(); - (*centroid_)[vid] = (*tmp_centroid_)[vid] / static_cast(ipoint_num); - (*points_per_voxel_)[vid] = ipoint_num; + // Update centroids + int ipoint_num = (*points_id_)[vid].size(); + (*centroid_)[vid] = (*tmp_centroid_)[vid] / static_cast(ipoint_num); + (*points_per_voxel_)[vid] = ipoint_num; - // Update covariance - double point_num = static_cast(ipoint_num); - Eigen::Vector3d pt_sum = (*tmp_centroid_)[vid]; + // Update covariance + double point_num = static_cast(ipoint_num); + Eigen::Vector3d pt_sum = (*tmp_centroid_)[vid]; - // Update centroids - (*centroid_)[vid] = (*tmp_centroid_)[vid] / point_num; + // Update centroids + (*centroid_)[vid] = (*tmp_centroid_)[vid] / point_num; - if (ipoint_num >= min_points_per_voxel_) { - Eigen::Matrix3d covariance; - covariance = ((*tmp_cov_)[vid] - 2.0 * (pt_sum * (*centroid_)[vid].transpose())) / point_num + (*centroid_)[vid] * (*centroid_)[vid].transpose(); - covariance *= (point_num - 1.0) / point_num; + if (ipoint_num >= min_points_per_voxel_) { + Eigen::Matrix3d covariance; + covariance = ((*tmp_cov_)[vid] - 2.0 * (pt_sum * (*centroid_)[vid].transpose())) / point_num + (*centroid_)[vid] * (*centroid_)[vid].transpose(); + covariance *= (point_num - 1.0) / point_num; - SymmetricEigensolver3x3 sv(covariance); + SymmetricEigensolver3x3 sv(covariance); - sv.compute(); - Eigen::Matrix3d evecs = sv.eigenvectors(); - Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal(); + sv.compute(); + Eigen::Matrix3d evecs = sv.eigenvectors(); + Eigen::Matrix3d evals = sv.eigenvalues().asDiagonal(); - if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) { - (*points_per_voxel_)[vid] = -1; - continue; - } + if (evals(0, 0) < 0 || evals(1, 1) < 0 || evals(2, 2) <= 0) { + (*points_per_voxel_)[vid] = -1; + continue; + } - double min_cov_eigvalue = evals(2, 2) * 0.01; + double min_cov_eigvalue = evals(2, 2) * 0.01; - if (evals(0, 0) < min_cov_eigvalue) { - evals(0, 0) = min_cov_eigvalue; + if (evals(0, 0) < min_cov_eigvalue) { + evals(0, 0) = min_cov_eigvalue; - if (evals(1, 1) < min_cov_eigvalue) { - evals(1, 1) = min_cov_eigvalue; - } + if (evals(1, 1) < min_cov_eigvalue) { + evals(1, 1) = min_cov_eigvalue; + } - covariance = evecs * evals * evecs.inverse(); - } + covariance = evecs * evals * evecs.inverse(); + } - (*icovariance_)[vid] = covariance.inverse(); - } - } + (*icovariance_)[vid] = covariance.inverse(); + } + } } template class VoxelGrid; diff --git a/core_perception/points_preprocessor/CMakeLists.txt b/core_perception/points_preprocessor/CMakeLists.txt index 78242dec367..75ede64fad8 100644 --- a/core_perception/points_preprocessor/CMakeLists.txt +++ b/core_perception/points_preprocessor/CMakeLists.txt @@ -1,43 +1,27 @@ cmake_minimum_required(VERSION 2.8.3) project(points_preprocessor) - find_package(autoware_build_flags REQUIRED) -find_package(autoware_config_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS - roscpp - roslint - std_msgs - sensor_msgs - pcl_ros - pcl_conversions - cv_bridge - velodyne_pointcloud - velodyne_pcl - autoware_config_msgs - tf - tf2 - tf2_ros - tf2_eigen - autoware_health_checker - ) - -catkin_package(CATKIN_DEPENDS - std_msgs - sensor_msgs - pcl_ros - pcl_conversions - cv_bridge - velodyne_pointcloud - velodyne_pcl - autoware_config_msgs - tf - tf2 - tf2_ros - tf2_eigen - autoware_health_checker - ) + autoware_config_msgs + autoware_health_checker + cv_bridge + pcl_conversions + pcl_ros + roscpp + roslint + sensor_msgs + std_msgs + tf + tf2 + tf2_eigen + tf2_ros + velodyne_pointcloud + velodyne_pcl +) + +catkin_package() set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp( @@ -59,13 +43,9 @@ find_path(YAML_CPP_INCLUDE_DIR NAMES yaml_cpp.h PATHS ${YAML_CPP_INCLUDE_DIRS}) find_library(YAML_CPP_LIBRARY NAMES YAML_CPP PATHS ${YAML_CPP_LIBRARY_DIRS}) link_directories(${YAML_CPP_LIBRARY_DIRS}) -########### -## Build ## -########### - include_directories( - ${catkin_INCLUDE_DIRS} - include + include + ${catkin_INCLUDE_DIRS} ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") @@ -74,12 +54,12 @@ link_directories(${PCL_LIBRARY_DIRS}) # Space Filter add_executable(space_filter - nodes/space_filter/space_filter.cpp - ) + nodes/space_filter/space_filter.cpp +) target_link_libraries(space_filter - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ) + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} +) add_dependencies(space_filter ${catkin_EXPORTED_TARGETS}) @@ -87,140 +67,139 @@ add_dependencies(space_filter ${catkin_EXPORTED_TARGETS}) add_definitions(${PCL_DEFINITIONS}) add_executable(ring_ground_filter - nodes/ring_ground_filter/ring_ground_filter.cpp - ) + nodes/ring_ground_filter/ring_ground_filter.cpp +) target_include_directories(ring_ground_filter PRIVATE - ${PCL_INCLUDE_DIRS} - ) + ${PCL_INCLUDE_DIRS} +) target_link_libraries(ring_ground_filter - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${Qt5Core_LIBRARIES} - ) + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} + ${Qt5Core_LIBRARIES} +) add_dependencies(ring_ground_filter ${catkin_EXPORTED_TARGETS}) # Ray Ground Filter add_library(ray_ground_filter_lib SHARED - nodes/ray_ground_filter/ray_ground_filter.cpp) + nodes/ray_ground_filter/ray_ground_filter.cpp +) -if (OPENMP_FOUND) - set_target_properties(ray_ground_filter_lib PROPERTIES - COMPILE_FLAGS ${OpenMP_CXX_FLAGS} - LINK_FLAGS ${OpenMP_CXX_FLAGS} - ) -endif () +if(OPENMP_FOUND) + set_target_properties(ray_ground_filter_lib PROPERTIES + COMPILE_FLAGS ${OpenMP_CXX_FLAGS} + LINK_FLAGS ${OpenMP_CXX_FLAGS} + ) +endif() target_include_directories(ray_ground_filter_lib PRIVATE - ${OpenCV_INCLUDE_DIRS} - ${PCL_INCLUDE_DIRS} - ) + ${OpenCV_INCLUDE_DIRS} +) target_link_libraries(ray_ground_filter_lib - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${OpenCV_LIBRARIES} - ${Qt5Core_LIBRARIES} - ) - -add_executable(ray_ground_filter - nodes/ray_ground_filter/ray_ground_filter_main.cpp - ) + ${catkin_LIBRARIES} + ${OpenCV_LIBRARIES} + ${Qt5Core_LIBRARIES} +) -target_link_libraries(ray_ground_filter - ray_ground_filter_lib) +add_dependencies(ray_ground_filter_lib ${catkin_EXPORTED_TARGETS}) +add_executable(ray_ground_filter + nodes/ray_ground_filter/ray_ground_filter_main.cpp +) +target_link_libraries(ray_ground_filter ray_ground_filter_lib) add_dependencies(ray_ground_filter ${catkin_EXPORTED_TARGETS}) - # Points Concat filter add_executable(points_concat_filter - nodes/points_concat_filter/points_concat_filter.cpp - ) + nodes/points_concat_filter/points_concat_filter.cpp +) target_include_directories(points_concat_filter PRIVATE - ${PCL_INCLUDE_DIRS} - ) + ${PCL_INCLUDE_DIRS} +) target_link_libraries(points_concat_filter - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${YAML_CPP_LIBRARIES} - ) + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} + ${YAML_CPP_LIBRARIES} +) add_dependencies(points_concat_filter ${catkin_EXPORTED_TARGETS}) #Cloud Transformer add_executable(cloud_transformer - nodes/cloud_transformer/cloud_transformer_node.cpp - ) + nodes/cloud_transformer/cloud_transformer_node.cpp +) target_include_directories(cloud_transformer PRIVATE - ${PCL_INCLUDE_DIRS} - ) + ${PCL_INCLUDE_DIRS} +) target_link_libraries(cloud_transformer - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${Qt5Core_LIBRARIES} - ) + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} + ${Qt5Core_LIBRARIES} +) add_dependencies(cloud_transformer ${catkin_EXPORTED_TARGETS}) #Compare Map Filter add_executable(compare_map_filter - nodes/compare_map_filter/compare_map_filter.cpp - ) + nodes/compare_map_filter/compare_map_filter.cpp +) target_include_directories(compare_map_filter PRIVATE - ${PCL_INCLUDE_DIRS} - ) + ${PCL_INCLUDE_DIRS} +) target_link_libraries(compare_map_filter - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${Qt5Core_LIBRARIES} - ) + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} + ${Qt5Core_LIBRARIES} +) add_dependencies(compare_map_filter ${catkin_EXPORTED_TARGETS}) ### Unit Tests ### -#if (CATKIN_ENABLE_TESTING) -# find_package(rostest REQUIRED) -# find_package(roslaunch REQUIRED) - -# add_rostest_gtest(test_points_preprocessor -# test/test_points_preprocessor.test -# test/src/test_points_preprocessor.cpp) -# target_include_directories(test_points_preprocessor PRIVATE -# nodes/ray_ground_filter/include -# test/include) -# target_link_libraries(test_points_preprocessor -# ray_ground_filter_lib -# ${catkin_LIBRARIES}) -#endif () - if (CATKIN_ENABLE_TESTING) - roslint_add_test() -endif() + find_package(rostest REQUIRED) + find_package(roslaunch REQUIRED) + + add_rostest_gtest(test_points_preprocessor + test/test_points_preprocessor.test + test/src/test_points_preprocessor.cpp) + target_include_directories(test_points_preprocessor PRIVATE + nodes/ray_ground_filter/include + test/include) + target_link_libraries(test_points_preprocessor + ray_ground_filter_lib + ${catkin_LIBRARIES}) +endif () -install(TARGETS - cloud_transformer - points_concat_filter - ray_ground_filter_lib - ray_ground_filter - ring_ground_filter - space_filter - compare_map_filter - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) +install( + TARGETS + cloud_transformer + points_concat_filter + ray_ground_filter_lib + ray_ground_filter + ring_ground_filter + space_filter + compare_map_filter + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(DIRECTORY include/ - DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} - PATTERN ".svn" EXCLUDE - ) + DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE +) + +if (CATKIN_ENABLE_TESTING) + roslint_add_test() +endif() diff --git a/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/atan2_utils.h b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/atan2_utils.h new file mode 100644 index 00000000000..d688403b44a --- /dev/null +++ b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/atan2_utils.h @@ -0,0 +1,83 @@ +/* + * Copyright 2017-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +/// \file +/// \brief This file provides a fast but approximate atan2 function +#ifndef POINTS_PREPROCESSOR_RAY_GROUND_FILTER__ATAN2_UTILS_H +#define POINTS_PREPROCESSOR_RAY_GROUND_FILTER__ATAN2_UTILS_H + +#include + +/// pi +constexpr float PI = 3.14159265359F; +/// pi/2 +constexpr float PI_2 = 1.5707963267948966F; + +/// +/// Approximation was taken from: +/// http://www-labs.iro.umontreal.ca/~mignotte/IFT2425/Documents/EfficientApproximationArctgFunction.pdf +/// +/// |Error = fast_atan2(y, x) - atan2f(y, x)| < 0.00468 rad +/// +/// Octants: +/// pi/2 +/// ` 3 | 2 / +/// ` | / +/// 4 ` | / 1 +/// pi -----+----- 0 +/// 5 / | ` 8 +/// / | ` +/// / 6 | 7 ` +/// 3pi/2 +/// +/// +float fast_atan2(float y, float x) +{ + constexpr float scaling_constant = 0.28086f; + + if (x == 0.0f) { + // Special case atan2(0.0, 0.0) = 0.0 + if (y == 0.0f) { + return 0.0f; + } + + // x is zero so we are either at pi/2 for (y > 0) or -pi/2 for (y < 0) + return ::std::copysign(PI_2, y); + } + + // Calculate quotient of y and x + float div = y / x; + + // Determine in which octants we can be, if |y| is smaller than |x| (|div|<1) + // then we are either in 1,4,5 or 8 else we are in 2,3,6 or 7. + if (fabsf(div) < 1.0f) { + // We are in 1,4,5 or 8 + + float atan = div / (1.0f + scaling_constant * div * div); + + // If we are in 4 or 5 we need to add pi or -pi respectively + if (x < 0.0f) { + return ::std::copysign(PI, y) + atan; + } + return atan; + } + + // We are in 2,3,6 or 7 + return ::std::copysign(PI_2, y) - div / (div * div + scaling_constant); +} + + + +#endif // POINTS_PREPROCESSOR_RAY_GROUND_FILTER__ATAN2_UTILS_H diff --git a/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h index c3595c660bf..7bc7a4cfbf0 100644 --- a/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h +++ b/core_perception/points_preprocessor/include/points_preprocessor/ray_ground_filter/ray_ground_filter.h @@ -1,5 +1,5 @@ /* - * Copyright 2017-2019 Autoware Foundation. All rights reserved. + * Copyright 2017-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -25,12 +25,6 @@ #include #include #include -#include -#include -#include -#include -#include -#include #include #include "autoware_config_msgs/ConfigRayGroundFilter.h" @@ -41,18 +35,15 @@ // headers in Autoware Health Checker #include -#include -#if (CV_MAJOR_VERSION >= 3) -#include "gencolors.cpp" -#else -#include -#endif +#define USE_ATAN_APPROXIMATION + class RayGroundFilter { private: std::shared_ptr health_checker_ptr_; - ros::NodeHandle node_handle_; + ros::NodeHandle nh_; + ros::NodeHandle pnh_; ros::Subscriber points_node_sub_; ros::Subscriber config_node_sub_; ros::Publisher groundless_points_pub_; @@ -76,100 +67,81 @@ class RayGroundFilter size_t radial_dividers_num_; size_t concentric_dividers_num_; - std::vector colors_; - const size_t color_num_ = 60; // different number of color to generate - struct PointXYZIRTColor + struct PointRH { - pcl::PointXYZI point; - + float height; float radius; // cylindric coords on XY Plane - float theta; // angle deg on XY plane - - size_t radial_div; // index of the radial divsion to which this point belongs to - size_t concentric_div; // index of the concentric division to which this points belongs to + void* original_data_pointer; - size_t red; // Red component [0-255] - size_t green; // Green Component[0-255] - size_t blue; // Blue component [0-255] - - size_t original_index; // index of this point in the source pointcloud + PointRH(float height, float radius, void* original_data_pointer) + : height(height), radius(radius), original_data_pointer(original_data_pointer) + {} }; - typedef std::vector PointCloudXYZIRTColor; + typedef std::vector PointCloudRH; void update_config_params(const autoware_config_msgs::ConfigRayGroundFilter::ConstPtr& param); /*! * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame - * @param[in] in_target_frame Coordinate system to perform transform - * @param[in] in_cloud_ptr PointCloud to perform transform - * @param[out] out_cloud_ptr Resulting transformed PointCloud + * @param in_target_frame Coordinate system to perform transform + * @param in_cloud_ptr PointCloud to perform transform + * @param out_cloud_ptr Resulting transformed PointCloud * @retval true transform successed * @retval false transform faild */ bool TransformPointCloud(const std::string& in_target_frame, const sensor_msgs::PointCloud2::ConstPtr& in_cloud_ptr, const sensor_msgs::PointCloud2::Ptr& out_cloud_ptr); - void publish_cloud(const ros::Publisher& in_publisher, - const pcl::PointCloud::Ptr in_cloud_to_publish_ptr, - const std_msgs::Header& in_header); + /*! + * Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs + * @param pub The ROS publisher on which to output the point cloud + * @param in_sensor_cloud The input point cloud from which to select the points to publish + * @param in_selector The pointers to the input cloud's binary blob. No checks are done so be carefull + */ + void publish(ros::Publisher pub, + const sensor_msgs::PointCloud2ConstPtr in_sensor_cloud, + const std::vector& in_selector); /*! - * - * @param[in] in_cloud Input Point Cloud to be organized in radial segments - * @param[out] out_organized_points Custom Point Cloud filled with XYZRTZColor data - * @param[out] out_radial_divided_indices Indices of the points in the original cloud for each radial segment - * @param[out] out_radial_ordered_clouds Vector of Points Clouds, each element will contain the points ordered + * Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs + * @param in_origin_cloud The original cloud from which we want to copy the points + * @param in_selector The pointers to the input cloud's binary blob. No checks are done so be carefull + * @param out_filtered_msg Returns a cloud comprised of the selected points from the origin cloud */ - void ConvertXYZIToRTZColor(const pcl::PointCloud::Ptr in_cloud, - const std::shared_ptr& out_organized_points, - const std::shared_ptr >& out_radial_divided_indices, - const std::shared_ptr >& out_radial_ordered_clouds); + void filterROSMsg(const sensor_msgs::PointCloud2ConstPtr in_origin_cloud, + const std::vector& in_selector, + const sensor_msgs::PointCloud2::Ptr out_filtered_msg); /*! * Classifies Points in the PointCoud as Ground and Not Ground * @param in_radial_ordered_clouds Vector of an Ordered PointsCloud ordered by radial distance from the origin + * @param in_point_count Total number of lidar point. This is used to reserve the output's vector memory * @param out_ground_indices Returns the indices of the points classified as ground in the original PointCloud * @param out_no_ground_indices Returns the indices of the points classified as not ground in the original PointCloud */ - void ClassifyPointCloud(const std::vector& in_radial_ordered_clouds, - const pcl::PointIndices::Ptr& out_ground_indices, - const pcl::PointIndices::Ptr& out_no_ground_indices); + void ClassifyPointCloud(const std::vector& in_radial_ordered_clouds, + const size_t in_point_count, + std::vector* out_ground_ptrs, + std::vector* out_no_ground_ptrs); /*! - * Removes the points higher than a threshold - * @param in_cloud_ptr PointCloud to perform Clipping + * Convert the sensor_msgs::PointCloud2 into PointCloudRH and filter out the points too high or too close + * @param in_transformed_cloud Input Point Cloud to be organized in radial segments * @param in_clip_height Maximum allowed height in the cloud - * @param out_clipped_cloud_ptr Resultung PointCloud with the points removed - */ - void ClipCloud(const pcl::PointCloud::Ptr in_cloud_ptr, const double in_clip_height, - pcl::PointCloud::Ptr out_clipped_cloud_ptr); - - /*! - * Returns the resulting complementary PointCloud, one with the points kept and the other removed as indicated - * in the indices - * @param in_cloud_ptr Input PointCloud to which the extraction will be performed - * @param in_indices Indices of the points to be both removed and kept - * @param out_only_indices_cloud_ptr Resulting PointCloud with the indices kept - * @param out_removed_indices_cloud_ptr Resulting PointCloud with the indices removed - */ - void ExtractPointsIndices(const pcl::PointCloud::Ptr in_cloud_ptr, - const pcl::PointIndices& in_indices, - pcl::PointCloud::Ptr out_only_indices_cloud_ptr, - pcl::PointCloud::Ptr out_removed_indices_cloud_ptr); - - /*! - * Removes points up to a certain distance in the XY Plane - * @param in_cloud_ptr Input PointCloud * @param in_min_distance Minimum valid distance, points closer than this will be removed. - * @param out_filtered_cloud_ptr Resulting PointCloud with the invalid points removed. + * @param out_radial_ordered_clouds Vector of Points Clouds, each element will contain the points ordered + * @param out_no_ground_ptrs Returns the pointers to the points filtered out as no ground */ - void RemovePointsUpTo(const pcl::PointCloud::Ptr in_cloud_ptr, double in_min_distance, - pcl::PointCloud::Ptr out_filtered_cloud_ptr); + void ConvertAndTrim(const sensor_msgs::PointCloud2::Ptr in_transformed_cloud, + const double in_clip_height, + double in_min_distance, + std::vector* out_radial_ordered_clouds, + std::vector* out_no_ground_ptrs); void CloudCallback(const sensor_msgs::PointCloud2ConstPtr& in_sensor_cloud); - friend class RayGroundFilter_clipCloud_Test; + friend class RayGroundFilter_callback_Test; public: RayGroundFilter(); diff --git a/core_perception/points_preprocessor/launch/compare_map_filter.launch b/core_perception/points_preprocessor/launch/compare_map_filter.launch index 70aa66f9d4f..763fdd31ebc 100644 --- a/core_perception/points_preprocessor/launch/compare_map_filter.launch +++ b/core_perception/points_preprocessor/launch/compare_map_filter.launch @@ -1,22 +1,22 @@ - - - - + + + + - - - + + + - - - - - + + + + + - - - - + + + + diff --git a/core_perception/points_preprocessor/launch/ray_ground_filter.launch b/core_perception/points_preprocessor/launch/ray_ground_filter.launch index f2717794417..fb6cffdaa90 100644 --- a/core_perception/points_preprocessor/launch/ray_ground_filter.launch +++ b/core_perception/points_preprocessor/launch/ray_ground_filter.launch @@ -1,6 +1,6 @@ - + @@ -10,8 +10,8 @@ - - + + diff --git a/core_perception/points_preprocessor/launch/space_filter.launch b/core_perception/points_preprocessor/launch/space_filter.launch index 3a80ae5ae71..40de8fcef80 100644 --- a/core_perception/points_preprocessor/launch/space_filter.launch +++ b/core_perception/points_preprocessor/launch/space_filter.launch @@ -1,24 +1,24 @@ - - - - - - - - + + + + + + + + - - - - - - + + + + + + - - - - + + + + diff --git a/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp b/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp index a12ccd47577..4f07f2f3154 100644 --- a/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp +++ b/core_perception/points_preprocessor/nodes/cloud_transformer/cloud_transformer_node.cpp @@ -29,159 +29,159 @@ class CloudTransformerNode { private: - ros::NodeHandle node_handle_; - ros::Subscriber points_node_sub_; - ros::Publisher transformed_points_pub_; - - std::string input_point_topic_; - std::string target_frame_; - std::string output_point_topic_; - - tf::TransformListener *tf_listener_ptr_; - - bool transform_ok_; - - void publish_cloud(const ros::Publisher& in_publisher, - const pcl::PointCloud::ConstPtr &in_cloud_msg) - { - in_publisher.publish(in_cloud_msg); - } - - void transformXYZIRCloud(const pcl::PointCloud& in_cloud, - pcl::PointCloud& out_cloud, - const tf::StampedTransform& in_tf_stamped_transform) - { - Eigen::Matrix4f transform; - pcl_ros::transformAsMatrix(in_tf_stamped_transform, transform); - - if (&in_cloud != &out_cloud) - { - out_cloud.header = in_cloud.header; - out_cloud.is_dense = in_cloud.is_dense; - out_cloud.width = in_cloud.width; - out_cloud.height = in_cloud.height; - out_cloud.points.reserve (out_cloud.points.size ()); - out_cloud.points.assign (in_cloud.points.begin (), in_cloud.points.end ()); - out_cloud.sensor_orientation_ = in_cloud.sensor_orientation_; - out_cloud.sensor_origin_ = in_cloud.sensor_origin_; - } - if (in_cloud.is_dense) - { - for (size_t i = 0; i < out_cloud.points.size (); ++i) - { - //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap (); - Eigen::Matrix pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z); - out_cloud[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + - transform (0, 1) * pt.coeffRef (1) + - transform (0, 2) * pt.coeffRef (2) + - transform (0, 3)); - out_cloud[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + - transform (1, 1) * pt.coeffRef (1) + - transform (1, 2) * pt.coeffRef (2) + - transform (1, 3)); - out_cloud[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + - transform (2, 1) * pt.coeffRef (1) + - transform (2, 2) * pt.coeffRef (2) + - transform (2, 3)); - } - } - else - { - // Dataset might contain NaNs and Infs, so check for them first, - for (size_t i = 0; i < out_cloud.points.size (); ++i) - { - if (!pcl_isfinite (in_cloud.points[i].x) || - !pcl_isfinite (in_cloud.points[i].y) || - !pcl_isfinite (in_cloud.points[i].z)) - {continue;} - //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap (); - Eigen::Matrix pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z); - out_cloud[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + - transform (0, 1) * pt.coeffRef (1) + - transform (0, 2) * pt.coeffRef (2) + - transform (0, 3)); - out_cloud[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + - transform (1, 1) * pt.coeffRef (1) + - transform (1, 2) * pt.coeffRef (2) + - transform (1, 3)); - out_cloud[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + - transform (2, 1) * pt.coeffRef (1) + - transform (2, 2) * pt.coeffRef (2) + - transform (2, 3)); - } - } - } - - void CloudCallback(const pcl::PointCloud::ConstPtr &in_sensor_cloud) - { - pcl::PointCloud::Ptr transformed_cloud_ptr (new pcl::PointCloud); - - bool do_transform = false; - tf::StampedTransform transform; - if (target_frame_ != in_sensor_cloud->header.frame_id) - { - try { - tf_listener_ptr_->lookupTransform(target_frame_, in_sensor_cloud->header.frame_id, ros::Time(0), - transform); - do_transform = true; - } - catch (tf::TransformException ex) { - ROS_ERROR("cloud_transformer: %s NOT Transforming.", ex.what()); - do_transform = false; - transform_ok_ = false; - } - } - if (do_transform) - { - transformXYZIRCloud(*in_sensor_cloud, *transformed_cloud_ptr, transform); - transformed_cloud_ptr->header.frame_id = target_frame_; - if (!transform_ok_) - {ROS_INFO("cloud_transformer: Correctly Transformed"); transform_ok_=true;} - } - else - { pcl::copyPointCloud(*in_sensor_cloud, *transformed_cloud_ptr);} - - publish_cloud(transformed_points_pub_, transformed_cloud_ptr); - } + ros::NodeHandle node_handle_; + ros::Subscriber points_node_sub_; + ros::Publisher transformed_points_pub_; + + std::string input_point_topic_; + std::string target_frame_; + std::string output_point_topic_; + + tf::TransformListener *tf_listener_ptr_; + + bool transform_ok_; + + void publish_cloud(const ros::Publisher& in_publisher, + const pcl::PointCloud::ConstPtr &in_cloud_msg) + { + in_publisher.publish(in_cloud_msg); + } + + void transformXYZIRCloud(const pcl::PointCloud& in_cloud, + pcl::PointCloud& out_cloud, + const tf::StampedTransform& in_tf_stamped_transform) + { + Eigen::Matrix4f transform; + pcl_ros::transformAsMatrix(in_tf_stamped_transform, transform); + + if (&in_cloud != &out_cloud) + { + out_cloud.header = in_cloud.header; + out_cloud.is_dense = in_cloud.is_dense; + out_cloud.width = in_cloud.width; + out_cloud.height = in_cloud.height; + out_cloud.points.reserve (out_cloud.points.size ()); + out_cloud.points.assign (in_cloud.points.begin (), in_cloud.points.end ()); + out_cloud.sensor_orientation_ = in_cloud.sensor_orientation_; + out_cloud.sensor_origin_ = in_cloud.sensor_origin_; + } + if (in_cloud.is_dense) + { + for (size_t i = 0; i < out_cloud.points.size (); ++i) + { + //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap (); + Eigen::Matrix pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z); + out_cloud[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + + transform (0, 1) * pt.coeffRef (1) + + transform (0, 2) * pt.coeffRef (2) + + transform (0, 3)); + out_cloud[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + + transform (1, 1) * pt.coeffRef (1) + + transform (1, 2) * pt.coeffRef (2) + + transform (1, 3)); + out_cloud[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + + transform (2, 1) * pt.coeffRef (1) + + transform (2, 2) * pt.coeffRef (2) + + transform (2, 3)); + } + } + else + { + // Dataset might contain NaNs and Infs, so check for them first, + for (size_t i = 0; i < out_cloud.points.size (); ++i) + { + if (!pcl_isfinite (in_cloud.points[i].x) || + !pcl_isfinite (in_cloud.points[i].y) || + !pcl_isfinite (in_cloud.points[i].z)) + {continue;} + //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap (); + Eigen::Matrix pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z); + out_cloud[i].x = static_cast (transform (0, 0) * pt.coeffRef (0) + + transform (0, 1) * pt.coeffRef (1) + + transform (0, 2) * pt.coeffRef (2) + + transform (0, 3)); + out_cloud[i].y = static_cast (transform (1, 0) * pt.coeffRef (0) + + transform (1, 1) * pt.coeffRef (1) + + transform (1, 2) * pt.coeffRef (2) + + transform (1, 3)); + out_cloud[i].z = static_cast (transform (2, 0) * pt.coeffRef (0) + + transform (2, 1) * pt.coeffRef (1) + + transform (2, 2) * pt.coeffRef (2) + + transform (2, 3)); + } + } + } + + void CloudCallback(const pcl::PointCloud::ConstPtr &in_sensor_cloud) + { + pcl::PointCloud::Ptr transformed_cloud_ptr (new pcl::PointCloud); + + bool do_transform = false; + tf::StampedTransform transform; + if (target_frame_ != in_sensor_cloud->header.frame_id) + { + try { + tf_listener_ptr_->lookupTransform(target_frame_, in_sensor_cloud->header.frame_id, ros::Time(0), + transform); + do_transform = true; + } + catch (tf::TransformException ex) { + ROS_ERROR("cloud_transformer: %s NOT Transforming.", ex.what()); + do_transform = false; + transform_ok_ = false; + } + } + if (do_transform) + { + transformXYZIRCloud(*in_sensor_cloud, *transformed_cloud_ptr, transform); + transformed_cloud_ptr->header.frame_id = target_frame_; + if (!transform_ok_) + {ROS_INFO("cloud_transformer: Correctly Transformed"); transform_ok_=true;} + } + else + { pcl::copyPointCloud(*in_sensor_cloud, *transformed_cloud_ptr);} + + publish_cloud(transformed_points_pub_, transformed_cloud_ptr); + } public: - CloudTransformerNode(tf::TransformListener* in_tf_listener_ptr):node_handle_("~"), transform_ok_(false) - { - tf_listener_ptr_ = in_tf_listener_ptr; - } - void Run() - { - ROS_INFO("Initializing Cloud Transformer, please wait..."); - node_handle_.param("input_point_topic", input_point_topic_, "/points_raw"); - ROS_INFO("Input point_topic: %s", input_point_topic_.c_str()); + CloudTransformerNode(tf::TransformListener* in_tf_listener_ptr):node_handle_("~"), transform_ok_(false) + { + tf_listener_ptr_ = in_tf_listener_ptr; + } + void Run() + { + ROS_INFO("Initializing Cloud Transformer, please wait..."); + node_handle_.param("input_point_topic", input_point_topic_, "/points_raw"); + ROS_INFO("Input point_topic: %s", input_point_topic_.c_str()); - node_handle_.param("target_frame", target_frame_, "velodyne"); - ROS_INFO("Target Frame in TF (target_frame) : %s", target_frame_.c_str()); + node_handle_.param("target_frame", target_frame_, "velodyne"); + ROS_INFO("Target Frame in TF (target_frame) : %s", target_frame_.c_str()); - node_handle_.param("output_point_topic", output_point_topic_, "/points_transformed"); - ROS_INFO("output_point_topic: %s", output_point_topic_.c_str()); + node_handle_.param("output_point_topic", output_point_topic_, "/points_transformed"); + ROS_INFO("output_point_topic: %s", output_point_topic_.c_str()); - ROS_INFO("Subscribing to... %s", input_point_topic_.c_str()); - points_node_sub_ = node_handle_.subscribe(input_point_topic_, 1, &CloudTransformerNode::CloudCallback, this); + ROS_INFO("Subscribing to... %s", input_point_topic_.c_str()); + points_node_sub_ = node_handle_.subscribe(input_point_topic_, 1, &CloudTransformerNode::CloudCallback, this); - transformed_points_pub_ = node_handle_.advertise(output_point_topic_, 2); + transformed_points_pub_ = node_handle_.advertise(output_point_topic_, 2); - ROS_INFO("Ready"); + ROS_INFO("Ready"); - ros::spin(); + ros::spin(); - } + } }; int main(int argc, char **argv) { - ros::init(argc, argv, "cloud_transformer"); - tf::TransformListener tf_listener; - CloudTransformerNode app(&tf_listener); + ros::init(argc, argv, "cloud_transformer"); + tf::TransformListener tf_listener; + CloudTransformerNode app(&tf_listener); - app.Run(); + app.Run(); - return 0; + return 0; } diff --git a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp index d06faf6e99a..33b05cf947a 100644 --- a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp +++ b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2017-2019 Autoware Foundation. All rights reserved. + * Copyright 2017-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -21,23 +21,14 @@ #include #include #include -#include +#include #include -#include -#include -#include -#include -#include #include -#include "autoware_config_msgs/ConfigRayGroundFilter.h" #include -#include -#if (CV_MAJOR_VERSION == 3) -#include "gencolors.cpp" -#endif - +#include "autoware_config_msgs/ConfigRayGroundFilter.h" #include "points_preprocessor/ray_ground_filter/ray_ground_filter.h" +#include "points_preprocessor/ray_ground_filter/atan2_utils.h" void RayGroundFilter::update_config_params(const autoware_config_msgs::ConfigRayGroundFilter::ConstPtr& param) { @@ -49,8 +40,17 @@ void RayGroundFilter::update_config_params(const autoware_config_msgs::ConfigRay clipping_height_ = param->clipping_height; min_point_distance_ = param->min_point_distance; reclass_distance_threshold_ = param->reclass_distance_threshold; + radial_dividers_num_ = ceil(360.0 / radial_divider_angle_); } +/*! + * Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame + * @param in_target_frame Coordinate system to perform transform + * @param in_cloud_ptr PointCloud to perform transform + * @param out_cloud_ptr Resulting transformed PointCloud + * @retval true transform successed + * @retval false transform faild + */ bool RayGroundFilter::TransformPointCloud(const std::string& in_target_frame, const sensor_msgs::PointCloud2::ConstPtr& in_cloud_ptr, const sensor_msgs::PointCloud2::Ptr& out_cloud_ptr) @@ -79,102 +79,79 @@ bool RayGroundFilter::TransformPointCloud(const std::string& in_target_frame, return true; } -void RayGroundFilter::publish_cloud(const ros::Publisher& in_publisher, - const pcl::PointCloud::Ptr in_cloud_to_publish_ptr, - const std_msgs::Header& in_header) +/*! + * Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs + * @param pub The ROS publisher on which to output the point cloud + * @param in_sensor_cloud The input point cloud from which to select the points to publish + * @param in_selector The pointers to the input cloud's binary blob. No checks are done so be carefull + */ +void RayGroundFilter::publish(ros::Publisher pub, + const sensor_msgs::PointCloud2ConstPtr in_sensor_cloud, + const std::vector& in_selector) { - sensor_msgs::PointCloud2::Ptr cloud_msg_ptr(new sensor_msgs::PointCloud2); - sensor_msgs::PointCloud2::Ptr trans_cloud_msg_ptr(new sensor_msgs::PointCloud2); - pcl::toROSMsg(*in_cloud_to_publish_ptr, *cloud_msg_ptr); - cloud_msg_ptr->header.frame_id = base_frame_; - cloud_msg_ptr->header.stamp = in_header.stamp; - const bool succeeded = TransformPointCloud(in_header.frame_id, cloud_msg_ptr, trans_cloud_msg_ptr); - if (!succeeded) - { - ROS_ERROR_STREAM_THROTTLE(10, "Failed transform from " << cloud_msg_ptr->header.frame_id << " to " - << in_header.frame_id); - return; - } - in_publisher.publish(*trans_cloud_msg_ptr); + sensor_msgs::PointCloud2::Ptr output_cloud(new sensor_msgs::PointCloud2); + filterROSMsg(in_sensor_cloud, in_selector, output_cloud); + pub.publish(*output_cloud); } /*! - * - * @param[in] in_cloud Input Point Cloud to be organized in radial segments - * @param[out] out_organized_points Custom Point Cloud filled with XYZRTZColor data - * @param[out] out_radial_divided_indices Indices of the points in the original cloud for each radial segment - * @param[out] out_radial_ordered_clouds Vector of Points Clouds, each element will contain the points ordered + * Extract the points pointed by in_selector from in_radial_ordered_clouds to copy them in out_no_ground_ptrs + * @param in_origin_cloud The original cloud from which we want to copy the points + * @param in_selector The pointers to the input cloud's binary blob. No checks are done so be carefull + * @param out_filtered_msg Returns a cloud comprised of the selected points from the origin cloud */ -void RayGroundFilter::ConvertXYZIToRTZColor( - const pcl::PointCloud::Ptr in_cloud, - const std::shared_ptr& out_organized_points, - const std::shared_ptr >& out_radial_divided_indices, - const std::shared_ptr >& out_radial_ordered_clouds) +void RayGroundFilter::filterROSMsg(const sensor_msgs::PointCloud2ConstPtr in_origin_cloud, + const std::vector& in_selector, + const sensor_msgs::PointCloud2::Ptr out_filtered_msg) { - out_organized_points->resize(in_cloud->points.size()); - out_radial_divided_indices->clear(); - out_radial_divided_indices->resize(radial_dividers_num_); - out_radial_ordered_clouds->resize(radial_dividers_num_); - - for (size_t i = 0; i < in_cloud->points.size(); i++) - { - PointXYZIRTColor new_point; - auto radius = static_cast( - sqrt(in_cloud->points[i].x * in_cloud->points[i].x + in_cloud->points[i].y * in_cloud->points[i].y)); - auto theta = static_cast(atan2(in_cloud->points[i].y, in_cloud->points[i].x) * 180 / M_PI); - if (theta < 0) - { - theta += 360; - } - if (theta >= 360) - { - theta -= 360; - } - - auto radial_div = (size_t)floor(theta / radial_divider_angle_); - - auto concentric_div = (size_t)floor(fabs(radius / concentric_divider_distance_)); - - new_point.point = in_cloud->points[i]; - new_point.radius = radius; - new_point.theta = theta; - new_point.radial_div = radial_div; - new_point.concentric_div = concentric_div; - new_point.red = (size_t)colors_[new_point.radial_div % color_num_].val[0]; - new_point.green = (size_t)colors_[new_point.radial_div % color_num_].val[1]; - new_point.blue = (size_t)colors_[new_point.radial_div % color_num_].val[2]; - new_point.original_index = i; + size_t point_size = in_origin_cloud->row_step/in_origin_cloud->width; // in Byte - out_organized_points->at(i) = new_point; + // TODO(yoan picchi) I fear this may do a lot of cache miss because it is sorted in the radius + // and no longer sorted in the original pointer. One thing to try is that, given + // that we know the value possibles, we can make a rather large vector and insert + // all the point in, then move things around to remove the "blank" space. This + // would be a linear sort to allow cache prediction to work better. To be tested. - // radial divisions - out_radial_divided_indices->at(radial_div).indices.push_back(i); + size_t data_size = point_size * in_selector.size(); + out_filtered_msg->data.resize(data_size); // TODO(yoan picchi) a fair amount of time (5-10%) is wasted on this resize - out_radial_ordered_clouds->at(radial_div).push_back(new_point); - } // end for - -// order radial points on each division -#pragma omp for - for (size_t i = 0; i < radial_dividers_num_; i++) + size_t offset = 0; + for ( auto it = in_selector.cbegin(); it != in_selector.cend(); it++ ) { - std::sort(out_radial_ordered_clouds->at(i).begin(), out_radial_ordered_clouds->at(i).end(), - [](const PointXYZIRTColor& a, const PointXYZIRTColor& b) { return a.radius < b.radius; }); // NOLINT + memcpy(out_filtered_msg->data.data()+offset, *it, point_size); + offset += point_size; } + + out_filtered_msg->width = (uint32_t) in_selector.size(); + out_filtered_msg->height = 1; + + out_filtered_msg->fields = in_origin_cloud->fields; + out_filtered_msg->header.frame_id = base_frame_; + out_filtered_msg->header.stamp = in_origin_cloud->header.stamp; + out_filtered_msg->point_step = in_origin_cloud->point_step; + out_filtered_msg->row_step = point_size * in_selector.size(); + out_filtered_msg->is_dense = in_origin_cloud->is_dense + && in_origin_cloud->data.size() == in_selector.size(); } /*! * Classifies Points in the PointCoud as Ground and Not Ground * @param in_radial_ordered_clouds Vector of an Ordered PointsCloud ordered by radial distance from the origin - * @param out_ground_indices Returns the indices of the points classified as ground in the original PointCloud - * @param out_no_ground_indices Returns the indices of the points classified as not ground in the original PointCloud + * @param in_point_count Total number of lidar point. This is used to reserve the output's vector memory + * @param out_ground_ptrs Returns the original adress of the points classified as ground in the original PointCloud + * @param out_no_ground_ptrs Returns the original adress of the points classified as not ground in the original PointCloud */ -void RayGroundFilter::ClassifyPointCloud(const std::vector& in_radial_ordered_clouds, - const pcl::PointIndices::Ptr& out_ground_indices, - const pcl::PointIndices::Ptr& out_no_ground_indices) +void RayGroundFilter::ClassifyPointCloud(const std::vector& in_radial_ordered_clouds, + const size_t in_point_count, + std::vector* out_ground_ptrs, + std::vector* out_no_ground_ptrs) { - out_ground_indices->indices.clear(); - out_no_ground_indices->indices.clear(); -#pragma omp for + double expected_ground_no_ground_ratio = 0.1; + out_ground_ptrs->reserve(in_point_count * expected_ground_no_ground_ratio); + out_no_ground_ptrs->reserve(in_point_count); + + const float local_slope_ratio = tan(DEG2RAD(local_max_slope_)); + const float general_slope_ratio = tan(DEG2RAD(general_max_slope_)); for (size_t i = 0; i < in_radial_ordered_clouds.size(); i++) // sweep through each radial division { float prev_radius = 0.f; @@ -184,9 +161,9 @@ void RayGroundFilter::ClassifyPointCloud(const std::vector concentric_divider_distance_ && height_threshold < min_height_threshold_) @@ -230,96 +207,183 @@ void RayGroundFilter::ClassifyPointCloud(const std::vectorindices.push_back(in_radial_ordered_clouds[i][j].original_index); + out_ground_ptrs->push_back(in_radial_ordered_clouds[i][j].original_data_pointer); prev_ground = true; } else { - out_no_ground_indices->indices.push_back(in_radial_ordered_clouds[i][j].original_index); + out_no_ground_ptrs->push_back(in_radial_ordered_clouds[i][j].original_data_pointer); prev_ground = false; } prev_radius = in_radial_ordered_clouds[i][j].radius; - prev_height = in_radial_ordered_clouds[i][j].point.z; + prev_height = in_radial_ordered_clouds[i][j].height; } } } +float ReverseFloat(float inFloat) // Swap endianness +{ + float retVal; + char *floatToConvert = reinterpret_cast(& inFloat); + char *returnFloat = reinterpret_cast(& retVal); + + // swap the bytes into a temporary buffer + returnFloat[0] = floatToConvert[3]; + returnFloat[1] = floatToConvert[2]; + returnFloat[2] = floatToConvert[1]; + returnFloat[3] = floatToConvert[0]; + + return retVal; +} + +bool is_big_endian(void) +{ + union + { + uint32_t i; + char c[4]; + } bint = {0x01020304}; + + return bint.c[0] == 1; +} + /*! - * Removes the points higher than a threshold - * @param in_cloud_ptr PointCloud to perform Clipping + * Convert the sensor_msgs::PointCloud2 into PointCloudRH and filter out the points too high or too close + * @param in_transformed_cloud Input Point Cloud to be organized in radial segments * @param in_clip_height Maximum allowed height in the cloud - * @param out_clipped_cloud_ptr Resultung PointCloud with the points removed + * @param in_min_distance Minimum valid distance, points closer than this will be removed. + * @param out_radial_ordered_clouds Vector of Points Clouds, each element will contain the points ordered + * @param out_no_ground_ptrs Returns the pointers to the points filtered out as no ground */ -void RayGroundFilter::ClipCloud(const pcl::PointCloud::Ptr in_cloud_ptr, const double in_clip_height, - pcl::PointCloud::Ptr out_clipped_cloud_ptr) +void RayGroundFilter::ConvertAndTrim(const sensor_msgs::PointCloud2::Ptr in_transformed_cloud, + const double in_clip_height, + double in_min_distance, + std::vector* out_radial_ordered_clouds, + std::vector* out_no_ground_ptrs) { - pcl::ExtractIndices extractor; - extractor.setInputCloud(in_cloud_ptr); - pcl::PointIndices indices; + // --- Clarify some of the values used to access the binary blob + size_t point_size = in_transformed_cloud->row_step/in_transformed_cloud->width; // in Byte + size_t cloud_count = in_transformed_cloud->width*in_transformed_cloud->height; + + const uint offset_not_set = ~0; + uint x_offset = offset_not_set; // in Byte from the point's start + uint y_offset = offset_not_set; // in Byte from the point's start + uint z_offset = offset_not_set; // in Byte from the point's start + + if (in_transformed_cloud->fields.size() < 3) + { + ROS_ERROR_STREAM_THROTTLE(10, "Failed to decode the pointcloud message : not enough fields found : " + << in_transformed_cloud->fields.size() << " (needs at least 3 : x,y,z)"); + return; + } -#pragma omp for - for (size_t i = 0; i < in_cloud_ptr->points.size(); i++) + for ( uint i = 0; i < in_transformed_cloud->fields.size(); i++ ) { - if (in_cloud_ptr->points[i].z > in_clip_height) + sensor_msgs::PointField field = in_transformed_cloud->fields[i]; + if ("x" == field.name) { - indices.indices.push_back(i); + x_offset = field.offset; + } + else if ("y" == field.name) + { + y_offset = field.offset; + } + else if ("z" == field.name) + { + z_offset = field.offset; } } - extractor.setIndices(boost::make_shared(indices)); - extractor.setNegative(true); // true removes the indices, false leaves only the indices - extractor.filter(*out_clipped_cloud_ptr); -} -/*! - * Returns the resulting complementary PointCloud, one with the points kept and the other removed as indicated - * in the indices - * @param in_cloud_ptr Input PointCloud to which the extraction will be performed - * @param in_indices Indices of the points to be both removed and kept - * @param out_only_indices_cloud_ptr Resulting PointCloud with the indices kept - * @param out_removed_indices_cloud_ptr Resulting PointCloud with the indices removed - */ -void RayGroundFilter::ExtractPointsIndices(const pcl::PointCloud::Ptr in_cloud_ptr, - const pcl::PointIndices& in_indices, - pcl::PointCloud::Ptr out_only_indices_cloud_ptr, - pcl::PointCloud::Ptr out_removed_indices_cloud_ptr) -{ - pcl::ExtractIndices extract_ground; - extract_ground.setInputCloud(in_cloud_ptr); - extract_ground.setIndices(boost::make_shared(in_indices)); + if (offset_not_set == x_offset || offset_not_set == y_offset || offset_not_set == z_offset) + { + ROS_ERROR_STREAM_THROTTLE(10, "Failed to decode the pointcloud message : bad coordinate field name"); + return; + } + // --- - extract_ground.setNegative(false); // true removes the indices, false leaves only the indices - extract_ground.filter(*out_only_indices_cloud_ptr); + out_radial_ordered_clouds->resize(radial_dividers_num_); - extract_ground.setNegative(true); // true removes the indices, false leaves only the indices - extract_ground.filter(*out_removed_indices_cloud_ptr); -} + const int mean_ray_count = cloud_count/radial_dividers_num_; + // In theory reserving more than the average memory would reduce even more the number of realloc + // but it would also make the reserving takes longer. One or two times the average are pretty + // much identical in term of speedup. Three seems a bit worse. + const int reserve_count = mean_ray_count; + for (auto it = out_radial_ordered_clouds->begin(); it != out_radial_ordered_clouds->end(); it++) + { + it->reserve(reserve_count); + } -/*! - * Removes points up to a certain distance in the XY Plane - * @param in_cloud_ptr Input PointCloud - * @param in_min_distance Minimum valid distance, points closer than this will be removed. - * @param out_filtered_cloud_ptr Resulting PointCloud with the invalid points removed. - */ -void RayGroundFilter::RemovePointsUpTo(const pcl::PointCloud::Ptr in_cloud_ptr, double in_min_distance, - pcl::PointCloud::Ptr out_filtered_cloud_ptr) -{ - pcl::ExtractIndices extractor; - extractor.setInputCloud(in_cloud_ptr); - pcl::PointIndices indices; + for ( size_t i = 0; i < cloud_count; i++ ) + { + // --- access the binary blob fields + uint8_t* point_start_ptr = reinterpret_cast(in_transformed_cloud->data.data()) + (i*point_size); + float x = *(reinterpret_cast(point_start_ptr+x_offset)); + float y = *(reinterpret_cast(point_start_ptr+y_offset)); + float z = *(reinterpret_cast(point_start_ptr+z_offset)); + if (is_big_endian() != in_transformed_cloud->is_bigendian) + { + x = ReverseFloat(x); + y = ReverseFloat(y); + z = ReverseFloat(z); + } + // --- -#pragma omp for - for (size_t i = 0; i < in_cloud_ptr->points.size(); i++) + if (z > in_clip_height) + { + out_no_ground_ptrs->push_back(point_start_ptr); + continue; + } + auto radius = static_cast(sqrt(x*x + y*y)); + if (radius < in_min_distance) + { + out_no_ground_ptrs->push_back(point_start_ptr); + continue; + } +#ifdef USE_ATAN_APPROXIMATION + auto theta = static_cast(fast_atan2(y, x) * 180 / M_PI); +#else + auto theta = static_cast(atan2(y, x) * 180 / M_PI); +#endif // USE_ATAN_APPROXIMATION + if (theta < 0) + { + theta += 360; + } + else if (theta >= 360) + { + theta -= 360; + } + + // radial_divider_angle_ is computed so that + // 360 / radial_divider_angle_ = radial_dividers_num_ + // Even though theta < 360, rounding error may make it so that + // theta / radial_divider_angle_ >= radial_dividers_num_ + // which gives a radial_div one past the end. The modulo is here to fix + // this rare case, wrapping the bad radial_div back to the first one. + auto radial_div = (size_t)floor(theta / radial_divider_angle_) % radial_dividers_num_; + out_radial_ordered_clouds->at(radial_div).emplace_back(z, radius, point_start_ptr); + } // end for + + // order radial points on each division + auto strick_weak_radius_ordering = [](const PointRH& a, const PointRH& b) { - if (sqrt(in_cloud_ptr->points[i].x * in_cloud_ptr->points[i].x + - in_cloud_ptr->points[i].y * in_cloud_ptr->points[i].y) < in_min_distance) + if (a.radius < b.radius) { - indices.indices.push_back(i); + return true; } + if (a.radius > b.radius) + { + return false; + } + // then the radius are equals. We add a secondary condition to keep the sort stable + return a.original_data_pointer < b.original_data_pointer; + }; + for (size_t i = 0; i < radial_dividers_num_; i++) + { + std::sort(out_radial_ordered_clouds->at(i).begin(), + out_radial_ordered_clouds->at(i).end(), + strick_weak_radius_ordering); } - extractor.setIndices(boost::make_shared(indices)); - extractor.setNegative(true); // true removes the indices, false leaves only the indices - extractor.filter(*out_filtered_cloud_ptr); } void RayGroundFilter::CloudCallback(const sensor_msgs::PointCloud2ConstPtr& in_sensor_cloud) @@ -336,49 +400,21 @@ void RayGroundFilter::CloudCallback(const sensor_msgs::PointCloud2ConstPtr& in_s return; } - pcl::PointCloud::Ptr current_sensor_cloud_ptr(new pcl::PointCloud); - pcl::fromROSMsg(*trans_sensor_cloud, *current_sensor_cloud_ptr); - - pcl::PointCloud::Ptr clipped_cloud_ptr(new pcl::PointCloud); - - // remove points above certain point - ClipCloud(current_sensor_cloud_ptr, clipping_height_, clipped_cloud_ptr); - - // remove closer points than a threshold - pcl::PointCloud::Ptr filtered_cloud_ptr(new pcl::PointCloud); - RemovePointsUpTo(clipped_cloud_ptr, min_point_distance_, filtered_cloud_ptr); - - // GetCloud Normals - // pcl::PointCloud::Ptr cloud_with_normals_ptr (new pcl::PointCloud); - // GetCloudNormals(current_sensor_cloud_ptr, cloud_with_normals_ptr, 5.0); - - std::shared_ptr organized_points(new PointCloudXYZIRTColor); - std::shared_ptr > radial_division_indices(new std::vector); - std::shared_ptr > radial_ordered_clouds(new std::vector); + std::vector radial_ordered_clouds; + std::vector ground_ptrs, no_ground_ptrs; + ConvertAndTrim(trans_sensor_cloud, clipping_height_, min_point_distance_, &radial_ordered_clouds, &no_ground_ptrs); + const size_t point_count = in_sensor_cloud->width*in_sensor_cloud->height; - radial_dividers_num_ = ceil(360 / radial_divider_angle_); + ClassifyPointCloud(radial_ordered_clouds, point_count, &ground_ptrs, &no_ground_ptrs); - ConvertXYZIToRTZColor(filtered_cloud_ptr, organized_points, radial_division_indices, radial_ordered_clouds); - - pcl::PointIndices::Ptr ground_indices(new pcl::PointIndices), no_ground_indices(new pcl::PointIndices); - - ClassifyPointCloud(*radial_ordered_clouds, ground_indices, no_ground_indices); - - pcl::PointCloud::Ptr ground_cloud_ptr(new pcl::PointCloud); - pcl::PointCloud::Ptr no_ground_cloud_ptr(new pcl::PointCloud); - - ExtractPointsIndices(filtered_cloud_ptr, *ground_indices, ground_cloud_ptr, no_ground_cloud_ptr); - - publish_cloud(ground_points_pub_, ground_cloud_ptr, in_sensor_cloud->header); - publish_cloud(groundless_points_pub_, no_ground_cloud_ptr, in_sensor_cloud->header); + publish(ground_points_pub_, in_sensor_cloud, ground_ptrs); + publish(groundless_points_pub_, in_sensor_cloud, no_ground_ptrs); } -RayGroundFilter::RayGroundFilter() : node_handle_("~"), tf_listener_(tf_buffer_) +RayGroundFilter::RayGroundFilter() : nh_(), pnh_("~"), tf_listener_(tf_buffer_) { - ros::NodeHandle nh; - ros::NodeHandle pnh("~"); - health_checker_ptr_ = std::make_shared(nh, pnh); + health_checker_ptr_ = std::make_shared(nh_, pnh_); health_checker_ptr_->ENABLE(); } @@ -391,54 +427,49 @@ void RayGroundFilter::Run() // VLP-16 | 0.1-0.4 | 2.0 | -15.0<=x<=15.0 (30 / 0.52) // VLP-16HD| 0.1-0.4 | 1.33 | -10.0<=x<=10.0 (20 / 0.35) ROS_INFO("Initializing Ground Filter, please wait..."); - node_handle_.param("input_point_topic", input_point_topic_, "/points_raw"); + pnh_.param("input_point_topic", input_point_topic_, "points_raw"); ROS_INFO("Input point_topic: %s", input_point_topic_.c_str()); - node_handle_.param("base_frame", base_frame_, "base_link"); + pnh_.param("base_frame", base_frame_, "base_link"); ROS_INFO("base_frame: %s", base_frame_.c_str()); - node_handle_.param("general_max_slope", general_max_slope_, 3.0); + pnh_.param("general_max_slope", general_max_slope_, 3.0); ROS_INFO("general_max_slope[deg]: %f", general_max_slope_); - node_handle_.param("local_max_slope", local_max_slope_, 5.0); + pnh_.param("local_max_slope", local_max_slope_, 5.0); ROS_INFO("local_max_slope[deg]: %f", local_max_slope_); - node_handle_.param("radial_divider_angle", radial_divider_angle_, 0.1); // 1 degree default + pnh_.param("radial_divider_angle", radial_divider_angle_, 0.1); // 0.1 degree default ROS_INFO("radial_divider_angle[deg]: %f", radial_divider_angle_); - node_handle_.param("concentric_divider_distance", concentric_divider_distance_, 0.0); // 0.0 meters default + pnh_.param("concentric_divider_distance", concentric_divider_distance_, 0.0); // 0.0 meters default ROS_INFO("concentric_divider_distance[meters]: %f", concentric_divider_distance_); - node_handle_.param("min_height_threshold", min_height_threshold_, 0.05); // 0.05 meters default + pnh_.param("min_height_threshold", min_height_threshold_, 0.05); // 0.05 meters default ROS_INFO("min_height_threshold[meters]: %f", min_height_threshold_); - node_handle_.param("clipping_height", clipping_height_, 2.0); // 2.0 meters default above the car + pnh_.param("clipping_height", clipping_height_, 2.0); // 2.0 meters default above the car ROS_INFO("clipping_height[meters]: %f", clipping_height_); - node_handle_.param("min_point_distance", min_point_distance_, 1.85); // 1.85 meters default + pnh_.param("min_point_distance", min_point_distance_, 1.85); // 1.85 meters default ROS_INFO("min_point_distance[meters]: %f", min_point_distance_); - node_handle_.param("reclass_distance_threshold", reclass_distance_threshold_, 0.2); // 0.5 meters default + pnh_.param("reclass_distance_threshold", reclass_distance_threshold_, 0.2); // 0.2 meters default ROS_INFO("reclass_distance_threshold[meters]: %f", reclass_distance_threshold_); -#if (CV_MAJOR_VERSION >= 3) - generateColors(colors_, color_num_); -#else - cv::generateColors(colors_, color_num_); -#endif - radial_dividers_num_ = ceil(360 / radial_divider_angle_); + radial_dividers_num_ = ceil(360.0 / radial_divider_angle_); ROS_INFO("Radial Divisions: %d", (int)radial_dividers_num_); std::string no_ground_topic, ground_topic; - node_handle_.param("no_ground_point_topic", no_ground_topic, "/points_no_ground"); + pnh_.param("no_ground_point_topic", no_ground_topic, "points_no_ground"); ROS_INFO("No Ground Output Point Cloud no_ground_point_topic: %s", no_ground_topic.c_str()); - node_handle_.param("ground_point_topic", ground_topic, "/points_ground"); + pnh_.param("ground_point_topic", ground_topic, "points_ground"); ROS_INFO("Only Ground Output Point Cloud ground_topic: %s", ground_topic.c_str()); ROS_INFO("Subscribing to... %s", input_point_topic_.c_str()); - points_node_sub_ = node_handle_.subscribe(input_point_topic_, 1, &RayGroundFilter::CloudCallback, this); + points_node_sub_ = nh_.subscribe(input_point_topic_, 1, &RayGroundFilter::CloudCallback, this); config_node_sub_ = - node_handle_.subscribe("/config/ray_ground_filter", 1, &RayGroundFilter::update_config_params, this); + nh_.subscribe("config/ray_ground_filter", 1, &RayGroundFilter::update_config_params, this); - groundless_points_pub_ = node_handle_.advertise(no_ground_topic, 2); - ground_points_pub_ = node_handle_.advertise(ground_topic, 2); + groundless_points_pub_ = nh_.advertise(no_ground_topic, 2); + ground_points_pub_ = nh_.advertise(ground_topic, 2); ROS_INFO("Ready"); diff --git a/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp b/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp index 3ef120ff91f..b32b1ff2edd 100644 --- a/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp +++ b/core_perception/points_preprocessor/nodes/ring_ground_filter/ring_ground_filter.cpp @@ -1,8 +1,8 @@ /* * ring_ground_filter.cpp * - * Created on : June 5, 2018 - * Author : Patiphon Narksri + * Created on : June 5, 2018 + * Author : Patiphon Narksri * */ #include @@ -15,338 +15,338 @@ enum Label { - GROUND, - VERTICAL, - UNKNOWN //Initial state, not classified + GROUND, + VERTICAL, + UNKNOWN //Initial state, not classified }; class GroundFilter { public: - GroundFilter(); + GroundFilter(); private: - ros::NodeHandle node_handle_; - ros::Subscriber points_node_sub_; - ros::Publisher groundless_points_pub_; - ros::Publisher ground_points_pub_; - - std::string point_topic_; - std::string no_ground_topic, ground_topic; - int sensor_model_; - double sensor_height_; - double max_slope_; - double vertical_thres_; - bool floor_removal_; - - int vertical_res_; - int horizontal_res_; - cv::Mat index_map_; - Label class_label_[64]; - double radius_table_[64]; - - //boost::chrono::high_resolution_clock::time_point t1_; - //boost::chrono::high_resolution_clock::time_point t2_; - //boost::chrono::nanoseconds elap_time_; - ros::Time t1_; - ros::Time t2_; - ros::Duration elap_time_; - - const int DEFAULT_HOR_RES = 2000; - - void InitLabelArray(int in_model); - void InitRadiusTable(int in_model); - void InitDepthMap(int in_width); - void VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg); - void FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, - pcl::PointCloud &out_groundless_points, - pcl::PointCloud &out_ground_points); + ros::NodeHandle node_handle_; + ros::Subscriber points_node_sub_; + ros::Publisher groundless_points_pub_; + ros::Publisher ground_points_pub_; + + std::string point_topic_; + std::string no_ground_topic, ground_topic; + int sensor_model_; + double sensor_height_; + double max_slope_; + double vertical_thres_; + bool floor_removal_; + + int vertical_res_; + int horizontal_res_; + cv::Mat index_map_; + Label class_label_[64]; + double radius_table_[64]; + + //boost::chrono::high_resolution_clock::time_point t1_; + //boost::chrono::high_resolution_clock::time_point t2_; + //boost::chrono::nanoseconds elap_time_; + ros::Time t1_; + ros::Time t2_; + ros::Duration elap_time_; + + const int DEFAULT_HOR_RES = 2000; + + void InitLabelArray(int in_model); + void InitRadiusTable(int in_model); + void InitDepthMap(int in_width); + void VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg); + void FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, + pcl::PointCloud &out_groundless_points, + pcl::PointCloud &out_ground_points); }; GroundFilter::GroundFilter() : node_handle_("~") { - ROS_INFO("Inititalizing Ground Filter..."); - node_handle_.param("point_topic", point_topic_, "/points_raw"); - ROS_INFO("Input Point Cloud: %s", point_topic_.c_str()); - node_handle_.param("remove_floor", floor_removal_, true); - ROS_INFO("Floor Removal: %d", floor_removal_); - node_handle_.param("sensor_model", sensor_model_, 64); - ROS_INFO("Sensor Model: %d", sensor_model_); - node_handle_.param("sensor_height", sensor_height_, 1.80); - ROS_INFO("Sensor Height: %f", sensor_height_); - node_handle_.param("max_slope", max_slope_, 10.0); - ROS_INFO("Max Slope: %f", max_slope_); - node_handle_.param("vertical_thres", vertical_thres_, 0.08); - ROS_INFO("Vertical Threshold: %f", vertical_thres_); - - node_handle_.param("no_ground_point_topic", no_ground_topic, "/points_no_ground"); - ROS_INFO("No Ground Output Point Cloud: %s", no_ground_topic.c_str()); - node_handle_.param("ground_point_topic", ground_topic, "/points_ground"); - ROS_INFO("Only Ground Output Point Cloud: %s", ground_topic.c_str()); - - - int default_horizontal_res; - switch(sensor_model_) - { - case 64: - default_horizontal_res = 2083; - break; - case 32: - default_horizontal_res = 2250; - break; - case 16: - default_horizontal_res = 1800; - break; - default: - default_horizontal_res = DEFAULT_HOR_RES; - break; - } - node_handle_.param("horizontal_res", horizontal_res_, default_horizontal_res); - - points_node_sub_ = node_handle_.subscribe(point_topic_, 10000, &GroundFilter::VelodyneCallback, this); - groundless_points_pub_ = node_handle_.advertise(no_ground_topic, 10000); - ground_points_pub_ = node_handle_.advertise(ground_topic, 10000); - - vertical_res_ = sensor_model_; - InitLabelArray(sensor_model_); - InitRadiusTable(sensor_model_); + ROS_INFO("Inititalizing Ground Filter..."); + node_handle_.param("point_topic", point_topic_, "/points_raw"); + ROS_INFO("Input Point Cloud: %s", point_topic_.c_str()); + node_handle_.param("remove_floor", floor_removal_, true); + ROS_INFO("Floor Removal: %d", floor_removal_); + node_handle_.param("sensor_model", sensor_model_, 64); + ROS_INFO("Sensor Model: %d", sensor_model_); + node_handle_.param("sensor_height", sensor_height_, 1.80); + ROS_INFO("Sensor Height: %f", sensor_height_); + node_handle_.param("max_slope", max_slope_, 10.0); + ROS_INFO("Max Slope: %f", max_slope_); + node_handle_.param("vertical_thres", vertical_thres_, 0.08); + ROS_INFO("Vertical Threshold: %f", vertical_thres_); + + node_handle_.param("no_ground_point_topic", no_ground_topic, "/points_no_ground"); + ROS_INFO("No Ground Output Point Cloud: %s", no_ground_topic.c_str()); + node_handle_.param("ground_point_topic", ground_topic, "/points_ground"); + ROS_INFO("Only Ground Output Point Cloud: %s", ground_topic.c_str()); + + + int default_horizontal_res; + switch(sensor_model_) + { + case 64: + default_horizontal_res = 2083; + break; + case 32: + default_horizontal_res = 2250; + break; + case 16: + default_horizontal_res = 1800; + break; + default: + default_horizontal_res = DEFAULT_HOR_RES; + break; + } + node_handle_.param("horizontal_res", horizontal_res_, default_horizontal_res); + + points_node_sub_ = node_handle_.subscribe(point_topic_, 10000, &GroundFilter::VelodyneCallback, this); + groundless_points_pub_ = node_handle_.advertise(no_ground_topic, 10000); + ground_points_pub_ = node_handle_.advertise(ground_topic, 10000); + + vertical_res_ = sensor_model_; + InitLabelArray(sensor_model_); + InitRadiusTable(sensor_model_); } void GroundFilter::InitLabelArray(int in_model) { - for(int a = 0; a < vertical_res_; a++) - { - class_label_[a] = UNKNOWN; - } + for(int a = 0; a < vertical_res_; a++) + { + class_label_[a] = UNKNOWN; + } } void GroundFilter::InitRadiusTable(int in_model) { - double a; - double b; - double theta; - switch (in_model) - { - case 64: - a = 1.0/3*M_PI/180; - b = max_slope_*M_PI/180; - for (int i = 0; i < 64; i++) - { - if (i <= 31) - { - if (i == 31) a = -a; - theta = (1.0/3*i - 2.0)*M_PI/180; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - else - { - a = 0.5*M_PI/180; - theta = (8.83 + (0.5)*(i - 32.0))*M_PI/180; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - } - break; - case 32: - a = 4.0/3*M_PI/180; - b = max_slope_*M_PI/180; - for (int i = 0; i < 32; i++) - { - theta = (-31.0/3 + (4.0/3)*i)*180/M_PI; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - break; - case 16: - a = 2.0*M_PI/180; - b = max_slope_*M_PI/180; - for (int i = 0; i < 16; i++) - { - theta = (-30.0/2 + (2.0)*i)*180/M_PI; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - break; - default: - a = 1.0/3*M_PI/180; - b = max_slope_*M_PI/180; - for (int i = 0; i < 64; i++) - { - if (i <= 31) - { - if (i == 31) a = -a; - theta = (1.0/3*i - 2.0)*M_PI/180; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - else - { - a = 0.5*M_PI/180; - theta = (8.83 + (0.5)*(i - 32.0))*M_PI/180; - radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); - } - } - break; - } + double a; + double b; + double theta; + switch (in_model) + { + case 64: + a = 1.0/3*M_PI/180; + b = max_slope_*M_PI/180; + for (int i = 0; i < 64; i++) + { + if (i <= 31) + { + if (i == 31) a = -a; + theta = (1.0/3*i - 2.0)*M_PI/180; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + else + { + a = 0.5*M_PI/180; + theta = (8.83 + (0.5)*(i - 32.0))*M_PI/180; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + } + break; + case 32: + a = 4.0/3*M_PI/180; + b = max_slope_*M_PI/180; + for (int i = 0; i < 32; i++) + { + theta = (-31.0/3 + (4.0/3)*i)*180/M_PI; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + break; + case 16: + a = 2.0*M_PI/180; + b = max_slope_*M_PI/180; + for (int i = 0; i < 16; i++) + { + theta = (-30.0/2 + (2.0)*i)*180/M_PI; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + break; + default: + a = 1.0/3*M_PI/180; + b = max_slope_*M_PI/180; + for (int i = 0; i < 64; i++) + { + if (i <= 31) + { + if (i == 31) a = -a; + theta = (1.0/3*i - 2.0)*M_PI/180; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + else + { + a = 0.5*M_PI/180; + theta = (8.83 + (0.5)*(i - 32.0))*M_PI/180; + radius_table_[i] = fabs(sensor_height_*(1.0/(tan(theta)+tan(b)) - 1.0/(tan(a+theta)+tan(b)))); + } + } + break; + } } void GroundFilter::InitDepthMap(int in_width) { - const int mOne = -1; - index_map_ = cv::Mat_(vertical_res_, in_width, mOne); + const int mOne = -1; + index_map_ = cv::Mat_(vertical_res_, in_width, mOne); } void GroundFilter::FilterGround(const pcl::PointCloud::ConstPtr &in_cloud_msg, - pcl::PointCloud &out_groundless_points, - pcl::PointCloud &out_ground_points) + pcl::PointCloud &out_groundless_points, + pcl::PointCloud &out_ground_points) { - velodyne_pcl::PointXYZIRT point; - InitDepthMap(horizontal_res_); - - for (size_t i = 0; i < in_cloud_msg->points.size(); i++) - { - double u = atan2(in_cloud_msg->points[i].y,in_cloud_msg->points[i].x) * 180/M_PI; - if (u < 0) { u = 360 + u; } - int column = horizontal_res_ - (int)((double)horizontal_res_ * u / 360.0) - 1; - int row = vertical_res_ - 1 - in_cloud_msg->points[i].ring; - index_map_.at(row, column) = i; - } - - for (int i = 0; i < horizontal_res_; i++) - { - Label point_class[vertical_res_]; - int point_index[vertical_res_]; - int point_index_size = 0; - double z_max = 0; - double z_min = 0; - double r_ref = 0; - std::copy(class_label_, class_label_ + vertical_res_, point_class); - for (int j = 0; j < vertical_res_; j++) - { - if (index_map_.at(j,i) > -1 && point_class[j] == UNKNOWN) - { - double x0 = in_cloud_msg->points[index_map_.at(j, i)].x; - double y0 = in_cloud_msg->points[index_map_.at(j, i)].y; - double z0 = in_cloud_msg->points[index_map_.at(j, i)].z; - double r0 = sqrt(x0*x0 + y0*y0); - double r_diff = fabs(r0 - r_ref); - if (r_diff < radius_table_[j] || r_ref == 0) - { - r_ref = r0; - if (z0 > z_max || r_ref == 0) z_max = z0; - if (z0 < z_min || r_ref == 0) z_min = z0; - point_index[point_index_size] = j; - point_index_size++; - } - else - { - if (point_index_size > 1 && (z_max - z_min) > vertical_thres_) - { - for (int m = 0; m < point_index_size; m++) - { - int index = index_map_.at(point_index[m],i); - point.x = in_cloud_msg->points[index].x; - point.y = in_cloud_msg->points[index].y; - point.z = in_cloud_msg->points[index].z; - point.intensity = in_cloud_msg->points[index].intensity; - point.ring = in_cloud_msg->points[index].ring; - out_groundless_points.push_back(point); - point_class[point_index[m]] = VERTICAL; - } - point_index_size = 0; - } - else - { - for (int m = 0; m < point_index_size; m++) - { - int index = index_map_.at(point_index[m],i); - point.x = in_cloud_msg->points[index].x; - point.y = in_cloud_msg->points[index].y; - point.z = in_cloud_msg->points[index].z; - point.intensity = in_cloud_msg->points[index].intensity; - point.ring = in_cloud_msg->points[index].ring; - out_ground_points.push_back(point); - point_class[point_index[m]] = GROUND; - } - point_index_size = 0; - } - r_ref = r0; - z_max = z0; - z_min = z0; - point_index[point_index_size] = j; - point_index_size++; - } - } - if (j == vertical_res_ - 1 && point_index_size != 0) - { - if (point_index_size > 1 && (z_max - z_min) > vertical_thres_) - { - for (int m = 0; m < point_index_size; m++) - { - int index = index_map_.at(point_index[m],i); - point.x = in_cloud_msg->points[index].x; - point.y = in_cloud_msg->points[index].y; - point.z = in_cloud_msg->points[index].z; - point.intensity = in_cloud_msg->points[index].intensity; - point.ring = in_cloud_msg->points[index].ring; - out_groundless_points.push_back(point); - point_class[point_index[m]] = VERTICAL; - } - point_index_size = 0; - } - else - { - for (int m = 0; m < point_index_size; m++) - { - int index = index_map_.at(point_index[m],i); - point.x = in_cloud_msg->points[index].x; - point.y = in_cloud_msg->points[index].y; - point.z = in_cloud_msg->points[index].z; - point.intensity = in_cloud_msg->points[index].intensity; - point.ring = in_cloud_msg->points[index].ring; - out_ground_points.push_back(point); - point_class[point_index[m]] = GROUND; - } - point_index_size = 0; - } - } - } - } + velodyne_pcl::PointXYZIRT point; + InitDepthMap(horizontal_res_); + + for (size_t i = 0; i < in_cloud_msg->points.size(); i++) + { + double u = atan2(in_cloud_msg->points[i].y,in_cloud_msg->points[i].x) * 180/M_PI; + if (u < 0) { u = 360 + u; } + int column = horizontal_res_ - (int)((double)horizontal_res_ * u / 360.0) - 1; + int row = vertical_res_ - 1 - in_cloud_msg->points[i].ring; + index_map_.at(row, column) = i; + } + + for (int i = 0; i < horizontal_res_; i++) + { + Label point_class[vertical_res_]; + int point_index[vertical_res_]; + int point_index_size = 0; + double z_max = 0; + double z_min = 0; + double r_ref = 0; + std::copy(class_label_, class_label_ + vertical_res_, point_class); + for (int j = 0; j < vertical_res_; j++) + { + if (index_map_.at(j,i) > -1 && point_class[j] == UNKNOWN) + { + double x0 = in_cloud_msg->points[index_map_.at(j, i)].x; + double y0 = in_cloud_msg->points[index_map_.at(j, i)].y; + double z0 = in_cloud_msg->points[index_map_.at(j, i)].z; + double r0 = sqrt(x0*x0 + y0*y0); + double r_diff = fabs(r0 - r_ref); + if (r_diff < radius_table_[j] || r_ref == 0) + { + r_ref = r0; + if (z0 > z_max || r_ref == 0) z_max = z0; + if (z0 < z_min || r_ref == 0) z_min = z0; + point_index[point_index_size] = j; + point_index_size++; + } + else + { + if (point_index_size > 1 && (z_max - z_min) > vertical_thres_) + { + for (int m = 0; m < point_index_size; m++) + { + int index = index_map_.at(point_index[m],i); + point.x = in_cloud_msg->points[index].x; + point.y = in_cloud_msg->points[index].y; + point.z = in_cloud_msg->points[index].z; + point.intensity = in_cloud_msg->points[index].intensity; + point.ring = in_cloud_msg->points[index].ring; + out_groundless_points.push_back(point); + point_class[point_index[m]] = VERTICAL; + } + point_index_size = 0; + } + else + { + for (int m = 0; m < point_index_size; m++) + { + int index = index_map_.at(point_index[m],i); + point.x = in_cloud_msg->points[index].x; + point.y = in_cloud_msg->points[index].y; + point.z = in_cloud_msg->points[index].z; + point.intensity = in_cloud_msg->points[index].intensity; + point.ring = in_cloud_msg->points[index].ring; + out_ground_points.push_back(point); + point_class[point_index[m]] = GROUND; + } + point_index_size = 0; + } + r_ref = r0; + z_max = z0; + z_min = z0; + point_index[point_index_size] = j; + point_index_size++; + } + } + if (j == vertical_res_ - 1 && point_index_size != 0) + { + if (point_index_size > 1 && (z_max - z_min) > vertical_thres_) + { + for (int m = 0; m < point_index_size; m++) + { + int index = index_map_.at(point_index[m],i); + point.x = in_cloud_msg->points[index].x; + point.y = in_cloud_msg->points[index].y; + point.z = in_cloud_msg->points[index].z; + point.intensity = in_cloud_msg->points[index].intensity; + point.ring = in_cloud_msg->points[index].ring; + out_groundless_points.push_back(point); + point_class[point_index[m]] = VERTICAL; + } + point_index_size = 0; + } + else + { + for (int m = 0; m < point_index_size; m++) + { + int index = index_map_.at(point_index[m],i); + point.x = in_cloud_msg->points[index].x; + point.y = in_cloud_msg->points[index].y; + point.z = in_cloud_msg->points[index].z; + point.intensity = in_cloud_msg->points[index].intensity; + point.ring = in_cloud_msg->points[index].ring; + out_ground_points.push_back(point); + point_class[point_index[m]] = GROUND; + } + point_index_size = 0; + } + } + } + } } void GroundFilter::VelodyneCallback(const pcl::PointCloud::ConstPtr &in_cloud_msg) { - //t1_ = ros::Time().now(); - pcl::PointCloud vertical_points; - pcl::PointCloud ground_points; - vertical_points.header = in_cloud_msg->header; - ground_points.header = in_cloud_msg->header; - vertical_points.clear(); - ground_points.clear(); - - FilterGround(in_cloud_msg, vertical_points, ground_points); - - if (!floor_removal_) - { - vertical_points = *in_cloud_msg; - } - - groundless_points_pub_.publish(vertical_points); - ground_points_pub_.publish(ground_points); - //t2_ = boost::chrono::high_resolution_clock::now(); - //t2_ = ros::Time().now(); - //elap_time_ = t2_ - t1_;//boost::chrono::duration_cast(t2_-t1_); - //std::cout << "Computational Time for one frame: " << elap_time_ << '\n'; + //t1_ = ros::Time().now(); + pcl::PointCloud vertical_points; + pcl::PointCloud ground_points; + vertical_points.header = in_cloud_msg->header; + ground_points.header = in_cloud_msg->header; + vertical_points.clear(); + ground_points.clear(); + + FilterGround(in_cloud_msg, vertical_points, ground_points); + + if (!floor_removal_) + { + vertical_points = *in_cloud_msg; + } + + groundless_points_pub_.publish(vertical_points); + ground_points_pub_.publish(ground_points); + //t2_ = boost::chrono::high_resolution_clock::now(); + //t2_ = ros::Time().now(); + //elap_time_ = t2_ - t1_;//boost::chrono::duration_cast(t2_-t1_); + //std::cout << "Computational Time for one frame: " << elap_time_ << '\n'; } int main(int argc, char **argv) { - ros::init(argc, argv, "ring_ground_filter"); - GroundFilter node; - ros::spin(); + ros::init(argc, argv, "ring_ground_filter"); + GroundFilter node; + ros::spin(); - return 0; + return 0; } diff --git a/core_perception/points_preprocessor/nodes/space_filter/space_filter.cpp b/core_perception/points_preprocessor/nodes/space_filter/space_filter.cpp index 14cb88fcc76..f82a374d3a7 100644 --- a/core_perception/points_preprocessor/nodes/space_filter/space_filter.cpp +++ b/core_perception/points_preprocessor/nodes/space_filter/space_filter.cpp @@ -15,138 +15,138 @@ class SpaceFilter { public: - SpaceFilter(); + SpaceFilter(); private: - ros::NodeHandle node_handle_; - ros::Subscriber cloud_sub_; - ros::Publisher cloud_pub_; - - std::string subscribe_topic_; - - bool lateral_removal_; - bool vertical_removal_; - - double left_distance_; - double right_distance_; - double below_distance_; - double above_distance_; - - void VelodyneCallback(const sensor_msgs::PointCloud2::Ptr& in_sensor_cloud_ptr); - void KeepLanes(const pcl::PointCloud::Ptr in_cloud_ptr, - pcl::PointCloud::Ptr out_cloud_ptr, - float in_left_lane_threshold, - float in_right_lane_threshold); - void ClipCloud(const pcl::PointCloud::Ptr in_cloud_ptr, - pcl::PointCloud::Ptr out_cloud_ptr, - float in_min_height, - float in_max_height); + ros::NodeHandle node_handle_; + ros::Subscriber cloud_sub_; + ros::Publisher cloud_pub_; + + std::string subscribe_topic_; + + bool lateral_removal_; + bool vertical_removal_; + + double left_distance_; + double right_distance_; + double below_distance_; + double above_distance_; + + void VelodyneCallback(const sensor_msgs::PointCloud2::Ptr& in_sensor_cloud_ptr); + void KeepLanes(const pcl::PointCloud::Ptr in_cloud_ptr, + pcl::PointCloud::Ptr out_cloud_ptr, + float in_left_lane_threshold, + float in_right_lane_threshold); + void ClipCloud(const pcl::PointCloud::Ptr in_cloud_ptr, + pcl::PointCloud::Ptr out_cloud_ptr, + float in_min_height, + float in_max_height); }; SpaceFilter::SpaceFilter() : - node_handle_("~") + node_handle_("~") { - node_handle_.param("subscribe_topic", subscribe_topic_, "/points_raw"); + node_handle_.param("subscribe_topic", subscribe_topic_, "/points_raw"); - node_handle_.param("lateral_removal", lateral_removal_, true); - node_handle_.param("left_distance", left_distance_, 5.0); - node_handle_.param("right_distance", right_distance_, 5.0); + node_handle_.param("lateral_removal", lateral_removal_, true); + node_handle_.param("left_distance", left_distance_, 5.0); + node_handle_.param("right_distance", right_distance_, 5.0); - node_handle_.param("vertical_removal", vertical_removal_, true); - node_handle_.param("below_distance", below_distance_, -1.5); - node_handle_.param("above_distance", above_distance_, 0.5); + node_handle_.param("vertical_removal", vertical_removal_, true); + node_handle_.param("below_distance", below_distance_, -1.5); + node_handle_.param("above_distance", above_distance_, 0.5); - cloud_sub_ = node_handle_.subscribe(subscribe_topic_, 10, &SpaceFilter::VelodyneCallback, this); - cloud_pub_ = node_handle_.advertise( "/points_clipped", 10); + cloud_sub_ = node_handle_.subscribe(subscribe_topic_, 10, &SpaceFilter::VelodyneCallback, this); + cloud_pub_ = node_handle_.advertise( "/points_clipped", 10); } void SpaceFilter::KeepLanes(const pcl::PointCloud::Ptr in_cloud_ptr, - pcl::PointCloud::Ptr out_cloud_ptr, - float in_left_lane_threshold, - float in_right_lane_threshold) + pcl::PointCloud::Ptr out_cloud_ptr, + float in_left_lane_threshold, + float in_right_lane_threshold) { - pcl::PointIndices::Ptr far_indices (new pcl::PointIndices); - for(unsigned int i=0; i< in_cloud_ptr->points.size(); i++) - { - pcl::PointXYZ current_point; - current_point.x=in_cloud_ptr->points[i].x; - current_point.y=in_cloud_ptr->points[i].y; - current_point.z=in_cloud_ptr->points[i].z; - - if ( - current_point.y > (in_left_lane_threshold) || current_point.y < -1.0*in_right_lane_threshold - ) - { - far_indices->indices.push_back(i); - } - } - out_cloud_ptr->points.clear(); - pcl::ExtractIndices extract; - extract.setInputCloud (in_cloud_ptr); - extract.setIndices(far_indices); - extract.setNegative(true);//true removes the indices, false leaves only the indices - extract.filter(*out_cloud_ptr); + pcl::PointIndices::Ptr far_indices (new pcl::PointIndices); + for(unsigned int i=0; i< in_cloud_ptr->points.size(); i++) + { + pcl::PointXYZ current_point; + current_point.x=in_cloud_ptr->points[i].x; + current_point.y=in_cloud_ptr->points[i].y; + current_point.z=in_cloud_ptr->points[i].z; + + if ( + current_point.y > (in_left_lane_threshold) || current_point.y < -1.0*in_right_lane_threshold + ) + { + far_indices->indices.push_back(i); + } + } + out_cloud_ptr->points.clear(); + pcl::ExtractIndices extract; + extract.setInputCloud (in_cloud_ptr); + extract.setIndices(far_indices); + extract.setNegative(true);//true removes the indices, false leaves only the indices + extract.filter(*out_cloud_ptr); } void SpaceFilter::ClipCloud(const pcl::PointCloud::Ptr in_cloud_ptr, - pcl::PointCloud::Ptr out_cloud_ptr, - float in_min_height, - float in_max_height) + pcl::PointCloud::Ptr out_cloud_ptr, + float in_min_height, + float in_max_height) { - out_cloud_ptr->points.clear(); - for (unsigned int i=0; ipoints.size(); i++) - { - if (in_cloud_ptr->points[i].z >= in_min_height && - in_cloud_ptr->points[i].z <= in_max_height) - { - out_cloud_ptr->points.push_back(in_cloud_ptr->points[i]); - } - } + out_cloud_ptr->points.clear(); + for (unsigned int i=0; ipoints.size(); i++) + { + if (in_cloud_ptr->points[i].z >= in_min_height && + in_cloud_ptr->points[i].z <= in_max_height) + { + out_cloud_ptr->points.push_back(in_cloud_ptr->points[i]); + } + } } void SpaceFilter::VelodyneCallback(const sensor_msgs::PointCloud2::Ptr& in_sensor_cloud_ptr) { - pcl::PointCloud::Ptr current_sensor_cloud_ptr (new pcl::PointCloud); - pcl::PointCloud::Ptr inlanes_cloud_ptr (new pcl::PointCloud); - pcl::PointCloud::Ptr clipped_cloud_ptr (new pcl::PointCloud); - - pcl::fromROSMsg(*in_sensor_cloud_ptr, *current_sensor_cloud_ptr); - - if (lateral_removal_) - { - KeepLanes(current_sensor_cloud_ptr, inlanes_cloud_ptr, left_distance_, right_distance_); - } - else - { - inlanes_cloud_ptr = current_sensor_cloud_ptr; - } - if (vertical_removal_) - { - ClipCloud(inlanes_cloud_ptr, clipped_cloud_ptr, below_distance_, above_distance_); - } - else - { - clipped_cloud_ptr = inlanes_cloud_ptr; - } - - sensor_msgs::PointCloud2 cloud_msg; - - pcl::toROSMsg(*clipped_cloud_ptr, cloud_msg); - - cloud_msg.header=in_sensor_cloud_ptr->header; - cloud_pub_.publish(cloud_msg); + pcl::PointCloud::Ptr current_sensor_cloud_ptr (new pcl::PointCloud); + pcl::PointCloud::Ptr inlanes_cloud_ptr (new pcl::PointCloud); + pcl::PointCloud::Ptr clipped_cloud_ptr (new pcl::PointCloud); + + pcl::fromROSMsg(*in_sensor_cloud_ptr, *current_sensor_cloud_ptr); + + if (lateral_removal_) + { + KeepLanes(current_sensor_cloud_ptr, inlanes_cloud_ptr, left_distance_, right_distance_); + } + else + { + inlanes_cloud_ptr = current_sensor_cloud_ptr; + } + if (vertical_removal_) + { + ClipCloud(inlanes_cloud_ptr, clipped_cloud_ptr, below_distance_, above_distance_); + } + else + { + clipped_cloud_ptr = inlanes_cloud_ptr; + } + + sensor_msgs::PointCloud2 cloud_msg; + + pcl::toROSMsg(*clipped_cloud_ptr, cloud_msg); + + cloud_msg.header=in_sensor_cloud_ptr->header; + cloud_pub_.publish(cloud_msg); } int main(int argc, char **argv) { - ros::init(argc, argv, "space_filter"); - SpaceFilter node; - ros::spin(); + ros::init(argc, argv, "space_filter"); + SpaceFilter node; + ros::spin(); - return 0; + return 0; } diff --git a/core_perception/points_preprocessor/test/data/input_blob.bin b/core_perception/points_preprocessor/test/data/input_blob.bin new file mode 100644 index 0000000000000000000000000000000000000000..c3a15f0c6c2637ed15ca52950fe2768b35962d88 GIT binary patch literal 1780192 zcmaI9WmHzp`~HoEA_j_ziP(Wksx;>i5;h_rAR%@DiXtW`-5{+RTYtOT09^c$+-Lr;$!Sy+gGbVQbf1}Wq_Z`WZdRctHSE}WoAISaRe_H>o ztDOS77xc#c!#fD$hV6vGmjCvPRYTu3dyu$O|Bn4{K0q(gc=KvQu$(mj`!8+ZIv=3D zXuQ$M5Op;kK%AYM+UEBbjh{-gfSc=v;n+|cPy#=cBXBwGyhKs5eNWgon-48YUmJGOnlT}9*j57GEcw;pInuV=XH7MZs3o}%%Uhex53MV-j&tq10&3jpNy-OCw>@91ubrA3AlT8At1s8~$*9|*_2kxfxwhx`6aD>7E&ZX;ZXWKK zF5zFSzf_ZKv}lDtSAXS4Bj9Z0B7AzMFrU_++uvk#*xZ|_ycG23XDHU+rRF5a3tEpu zP6_jA{cV|?jAnP*Kz5%M^oK#Lzn=GVV0al{fATXb(DeUe$yZgj{)lZkSbvr)??dX8GW?)KGA`CvvE2{2U3vx& z?#(_D}Bu>HL$-smFX zPaL1_OXVVqH9@4fOtJ0ri}kbO+)j|aHV@l+Nal<6^Ws-F%0Cyt)sNrO2(Wf@Yk_;TK9E?N>d zp1h1c+sc;|i1neiXg;jDJ&~Kg?Nwikw(l?@Yq}P-&ZqUEadi=NKCgv?jD*im=Wi*x z@n~bnT2hzK)`t=Cf?J8x@XdJ=zQp=yKAnv^c?6P;p9VAa@w0p~!XQNuV zK(0RSjfnu{ycnyc2+ybE%VEtd6h1nD3|KpesSm3@Nzkb5jiXA1`E-0)pOB08Rs|FJ zc^R$qX?-**=D@uQzCPl&o*Idpdc6$ua+X;h-K}d5OAL9B(VXHYzG#!a`R0Tfi__6ET9JE49 znJ8xo`tUOp>%#`khsQ@I;Zk2=KAnH5E%ZQ3l}t$a;DfEtr}go!-WA6E(!x<6CBL6I z|GJ$XkH$rLk^2kT`Im>K7xc6<}ql)RR z^J#rF?9PU{-GeaxC()NUew^%j2F-hsO?(fq^%2_X5DY8k>qE2iDR_#q@aC=({>Ay# z?9KP!L2fzjD=+X5AkMGsUwnm{S?6#~nJ`Y*CpCS#qjMvFAcc*J#N+#mHa^Ar_$X}-r`wIf z?+paLAAz|3fAf0|8nJW&G1ENP#+O(hWe2R`fTs#qAAfgwAe&56QgM{651ABKxG+Em zt4|i5Psfk%ZxhhZg&WCK>Dboi)Aj$(hIMdphB>!B+25RnHn|27^o$)p%)ah`Yb$N= zfH(K%Nz z`fxDJLD#kglZ*#xt@CMpynt+YQy9eU4?Nj$8Vw1{A=&%b`sk5a1|RI>xcODmn3JHK zorT>lOZo?5ePlmsgfp%cTzx!K`3iUXp2x2W+4^Xx>xQOHet`$=VCy3*as(P%!q>-~ zb86^`uRQU+&(?=_z8>TS493H31-@u~c-=8XSH}${){|eh^5q9&eY|;P21^=8;gg$$ z`LsS(D$Yf_woN3PF0l1s+TR*7zNm2Pk8=ywprn^3flTC5yl}O^ zKT!R#nXl53Uts{TbQbvcqvC^R??eb}w~1Sy*YCf0s9P{MKCD=O z8ui|^k4*i^=6|Jf8LYh=$F0wm4xNBcD%o8ASGwGTsOy#ZXsN(A9Ur{YzCg}NKK~Ea zc0(~;UUKV;;iE^O>GEAj@?Lg)=xVKw9FF!O=fea(>HJCViZ0B|9n7sSe!C;IXZ|n} zuWk&!^B~7l74LTw=F|Dp zw;!v}j4LMOR+CVF)BP*|FV5h2UI#zFCDFGye=2($3geNsln*&`y=Uuup!6}*bq934%GXEyuynM#ny-(2DPiEKu?&xOW$PnEvjDyO z5=ma>k2L&W{f#MoRF)+`T;(P#dsH%CTz}h~K8B1xrxTC)HLdggsQSCoA`846g0asN z$$WAC6lr}9>5x3)>?Yq@e*;y2tDh-_YO{E*K1{t&fd0K~9RGnGAM{ci;oA5rygY!d zkH5pdfZh5F-27>gUN>~_%}cyCogE)C(}$ye8@dn~f3`l_H>jg?GW|$DEy?dM&Yv7o zbs=u`5K(`Zjt|d&8lq7O!-&j=R{~#DeE9o&8pM7dEs76*ls>ei<{~F&6%vuj)<=l? zJkXq~#?7C?9&bnYAIvAt!)k=*8;aw@faA`fU9XF$beHH$tdGPC5$K=AYGO2!t&jSl zYoT_YB{zQ>XA+O3uKJL?^MXF)kT`w}`OgowIM{LPi=D>l$RV4bKXu6ngFo5J@#Pxf z`=Rrv5UT?8;8heksWPgKZ*hIGuv-HB9JUz`+9u4W>+jF{$54t-22q~I)<>Rn7F2)c z$B(@+=h1+ zm^JAlS0AoVWl?7RE3Q7g<_t%-zjq(-et&WQ$+Uhy>J}SGEc%WR z^hd>q@3;M+llKB{|H=g!u(kr<2b;P}VWNsTxqLl>x>G-htW;{Go z--6>(C7)j$9|Bh%Lq~!$$%Dsi{-@MtLh{xSZv9~Q>>PSDrI0N0XY>DBt`tgFCE%M6 z*!`!jD#szeA_s4)V)MUP{w~OLKFsAGDnEg4{zY66Bj|&!udSnH(ekj@T>hJ+h9lPm z84_}k&Htk_>gfCp1!8m+s`MCu7}&^i{r!gt4`2E zPai)RBj}f|uLoI1qMN@wi0AAufp02*>f_@9M$Xf5oQ~x0Bi0A0%|a(9hmkcIifzvq z$A=>u{6JsLp1c01_aYZ+6w^Z$oF*!+76KNqo&!H*I`~ z>x-QWOkrK*SZwbo;Zxjy8l-zR>!~Qo0R_Nr$=XSt)=LOA7Uz^y+%Cx)VDo~wzKeQ?|J#r3&Vj5{R%oWZTn ze^~BE9qOWq`~$Xry3O!~Czv3|JRFOtrmRB(KQ|6Nav5!Nszl?+rv3@+e)}ezI*<|AQ zZms;&>*JRai{ajbL~ecVaRDQXynRIDFk3&h6$G$nt|89=jJyy^89Rp9tGsLFkJitWMq{|CHx3W%D9oqxvnQEz(BEmAB;@?XHh#tN zXMxXbXfoBnYtIV(sYjH4x)yIi(>5<4dGbR2PWQKz-#Wt5=LX#RMQK|o>au4InHMkU z$B)X-Ha4t*#oK0LO*09<;`lRad@i~cA5Fr>u=OKfi{_nuIIq0Z=6w&!Gtd)N$D*jw_h=auZ?cDeiPHNH0Z`tIH;t{5P zvYOMuKsk)t-*VBeLtmV7h*dUQKaGmT@NRArH~#G0Sch`sbI8(1x~=+CqT)}C0Rg#R zeEsYlbPLuztj4Pkv-NXhzz3K%|1wuUKjgcjn)J8a{;>P<7X5h2a`iJcMice_I+$qs zN}eyy-=-*NLvoXnX#J4Z&xk7s1#THj7NPg8{L||rwW-D+D?47azE0~W?UDnUDQ`%o zxv=xMp5C+Jfvu(}{>UNm{zk{fO~_Au0okun-TM3tYJcN^Fh`hHX~^B*sNXpZz4-1y z47}O(f4$2Z*tB34H~usq-G?6cj^XNOP5n0bk?4pMrnB`k)b$Wbf6I?QS~Ejn_4n1H z^+Q@e_l$GU(DPBmwOr7TAElqk?{>k(^}e{DsDB}@|J9@GP(toLlCb0`Q$IVlr9*fQ zUq4Fm$I$Z7T+*#w4`%#X)KCOxz9iv`Hze^(yg#e|)>^c-Du?WLW9uhrKZXZB`*BmQ z#NWmB&-;lt;oYPf{CkUpUvd3owdFlb>~@8#pH=5&(2JON*d>J>fBgOqMZfOLa@XG< z8%##u*D8{T`9gf7d{y-pc`91^0SS>q;@bCq5$fgvS3hH{LQoew zcQR$55P#_Y*)@X}{Vbi0_loxSisO&Q+IlqeS3aqIWZ32(;{Jer(Ka}AVj*|^@mg6h zY(#6YwWdU0;`~hUd^R#rjV4N2fm%CV2nH%C*JN) zY8ZNBHn%@e?Mu*3-2yUu6I&m*FKz|JRRIqy+5UBR~m%x2*;l;3Ew|} zxW3t5bQDGZ-A7Ur*!meAdJsGc`TF_UP>0q(*iU*F3-wI~i1*J=E~F19kr7(LfnAME?V~|NOJ#P-I-vjVuUZ_n*ffn}VQd7%^2A z;uEc({L@-+Z1V{0J4yKa(fS!Z0ioFE<4MEx4{iP`?yq%`F@iq@eEs}=V2@;S5cxOw zZtHw{{r>y8nee&S6dc-9(2o?ApN-M?L1F0*#D67QKi7)vVf7}&t#5ja4MzROco2=; zptk3W`vU{>R>6gBbGZ8H_-YG$eCUMzY=yrMfVh4sy?YoXg!A>0q7)3z26%|-e_9{@ zvrAC$?>%I0)1+3uA5r<&tWU9Eth9r>f6Hoj9om(dN7SFzw$7*fXYb~w!M$D)-2QUr zn1gUiEd|FXvg3#AraH7bAdf^|X7gV;;us7al#f%=*!k7b;_G0ke3V%-IyF*(%8nIxV|r4Jrg`{Ou=!= zZ2rGQZ$v9?9J%o${PqG!d5XCER~~!|LNmaVe7MZ!fA+nVVBcjfcYplZHAhkViv8sF za^2R???{?j8#r zJa=&GlQ+#ZX!wF$(y5faK53e{7hn%_ z7=3D(M0RU^Y31h;rJsly2;Q}y$gNLIIxj?fubYxVOYSrElT$kbQemnne$e@s{hk1H z-(?MH9(=lWK3$(=#w>s?M~t}fP7aG6-Dg+nER@|aHA=LTfbOnAAmQbc5~~KVbXQr-=~1f|BlFO zux>#uRtRU;=a2N?K#J{kJkFlYe^93`sA}6M?)j1RwL{STpWVrFA2$CL|4l`%5u=F1 zV9B_+zZG$QDulR?!mHZ)n>7Esn-LluJc-ow{M^c)6cXo8BliKESTd2@-B8z2|}p3lmco3Re+|nLH2Po~=`dB*@PF~2=3g1dz-5b_-2QNc^j^@l ziRAK~))6D~8wW^sAUi(1I#&oy8GQanB-g_E+yX2W#rFSqovyW<@8t6@+v^Q%cD;c& zCkg!1^~18%&M0%}XYTs^mWe~qm$^MisGWpw@%<5N_GqC|E$bUDQr(#OlU?_zP zHksM>_ow!+yw)^AHg{CW=z)U&)BMZ&00c~%gymKV`43%x4;Zl!UDq`y_4^+%`L9|% z9eS&4;Vo_a()Gh7=@6uA<4tsDOV(G!{D(fYgZ0iP-1CKp<^>^hBQH`iS>T`UPhF{8 z4oj=7@Z4d-?@!+kp|kloYWi0~6ki*+>0jKRT9Uj8Hc2hw=1+<-fuQhcEmj;S{Ct}4 z2}cg0C$(AR+i=ZRzUlh9lS&M{kKBpV)(P|J{fkbH$IyP$gJf13Zk z|G@Cr4gAAJ;GeD^c4>D;F;6~o^Pk;hFseJ+gJ{oV^MB}&7LrjJORleB^WT7`g7$;a zc>WpT?@Rmt#O20l&0961W$>-_`=|4t*wFwBzfHoML)iTPXXu2|oGr<3+efYQ>H7J` z3rm=DT+Bc1|D#&YN12bZCpM^}ZN8ZQe^s_Hb&Uzv|DO#BLgfbQiK#7{|C;FKV0U~T zcYR~lyyIwfV<}l+Y|{FCDQbUjhetjzJZ%woeSP|zKrlbE4u`hI2b%wJ-qmQ(qdd~b zUdQl%{!a5BekB^7e&+Lk(&8wR@+u_N?S%dkT|et~PKB=WQQZ3AtV112n}3jGbz<{> z^FslQ$lJrMucrkZg=u+(cNU7*yUES}|J{&AzaqbI?_XFq ze=yP<)04cM$>zV0zZS~=d%kI?b`Y9! zc>^&!FYui~?cbeTu?&E&)KTppWgOF}PPp-cw=xL$pC&!Vhn{2+_V@=Ss;gg9|ub-`a zW>EF($&&^!=)4NIeqBD)2_+WIAe}u0zG?ry@Y4eBE9&5Yc7p%Yd|S`2K+F2?CmlaX zem}8)7eBLsiJhi#*VpDM2B9YtHj;=w?DgrLO3R@1r!{wfhsBsI^mJ7Md2xlkzat}P zBTQ0Q%=PbVzW~^#zFw5S09BtJ@jrs1&K)4~YxS9YhyRTNbiyAiEf?Y|oxeo)szF{G z3W@bOHs5L^_Q2K8QQZ8+SGE>KYZQ@FmwGbSpQV4~!}^R=ZvN6`&JlRE`v9Ko$oB8t zvzOuFV$7{y@2I?jpbNLS`OA4FY2>B$jeEY^cEcbP)kBV?n6v$Rc-2(Ypg*1@Uu5&W z>bNPgHJVDg>HlW(?Y7VWw3exI`GQdKFL;!RdbUd>E5EY& zesjSa#vWRXSGh^}6ZiiY{isAgBlEfSX@g+^L=V^?%3o;yFUwaUpWJ+M%|pAD{|u`C zpI8_L&6)w+{5{^F3JtiFPw+CKzbQrC?{@auZn)zUjn^EJe15UNf4x|RzF8FzJc+$N zHgtAAm_JL!i(J_Lu2EY9gJcil)ah*guMWNp9(OQyU(fdU8{1yOhlRJX-8^>wzO=p* zl4<_N&0iWv4MItAa^%iJHveCLO+h0A#uJY{0{>D}|FU$;G!*zni)^|4r90SyNqKYg8%t7&HqI;{&Pf9Qk0|~v?4rPKUjVm1`SfQc z8sT3+%G22VPqNt!a#y3d{(t^K9*kSKm&HfX}zMUZ4{ohsa61qFy z;qL!F;noTD-2ENjS}uw2;{3&R_dt~SMvhn*v-z&EnS%Dc8Bcoq34GJ*TNY+!==voc z@;mfj+xIK(KX&e*53(w1-2D%sf1HupkGbUVsHV30;`J+cS97qsr7Ox`XudZ-cR^dP zTajol;r;=7|HHr{Yxv}3hIgG4@_V}f7WL_@?Vma%}@7tX<08A7o=(iF_LQe0R+Bhx9XizQb2nq5|J`+rOJ!UciK#cktO|Z2zu!(-AGy`hj=NVe{>#HV{2t--}y+X5>#sMNZ13 zVlkWVvRE_J$ykr1%@^)J^P}?f5(_=pm!`(uf4!v15xKg~A%3}R|L&A-2FbJaMEQ#n zwLigWQ3mQUBZ-6-v;Es?vo&n+H0S0oDnByNyt_%nR&igezND!7^R44zNL_8q<=g5` z1~NUGM54^ueD^P057RC!<*qMH9pewD*KQQ$Cv<;h=F&)Ta0|rQ3nlr3cz>I>OC=g3 zdw^8-7S@O8{NuH63V2_P;r351|J@IRHm6~)b!&fvASE`BWHbf%-NWknhEUztMc6 zu6hvUs?J^iS@7B!U0P{P)Et|c{+r`(2GS<_qWuH(`e%(?2D*PMi4@&t^O-1R4P>wd zw|?wpoq>)iBomuwIc?7u@1NQA)(woc?YRAsL3tU-XIU~?7AWvZ_eVNZt%r7_mgB}s z318y;+UNLAxU1m9UEjPU9SO6}@cFDBSczJ`8B$=u<}uId{`Do7 z0jPdXZ?1nnIi!h>xK7~ur`8KgG&cs3*a^b#PxHA~Nf)Yjs*CPNrPpUXt~jA9QP#xd zrjQ>8*v@P2|M=MW9R?SA_jA(z3IDei0MF*BG(BS5;-5)z6&l5HzA>w(Pe~I(gyE10b ztGE@BhcKb5T_U`%Qdx4(9HT?NvR zD+1&9WoI7xW>z`wqo8U^= zJrSSu`nQW`2h=d}H}*7P^SLggKboZ{&+Q*{EY(0G?Iw~$2R5IV_0&M==Xm_>z3~0f z>wn63Ez!MVV{+@3;6GASe)@L34m^Iq=huFb6Iv5&L&l}I#eeGl&_J7M&}F`%=>9jF zUlYT0WR#vl!lT*zcFdj&4!V~3bz6Qy*Izn2(^2EY6yoK?=2xo36*Q{&{JuDwj@pgd zP2PMI_@(PF4f%C2HE0DlKOK;@1IVDw_~j7c???NqS7SJwe#Q6K@nb8HOnnjg+rZ{` z*~290yK@&eKh2cM1+57g-1^D1e-)%I;;b_ z^Y1see(Kt}KkAntPk!jL`vWecG?2#&KEGCJsxV`{GER8R=6Arb8EEvlX{1hGlHZ8^ zSGqwPrnqQ|-akO+2VXiZL{ZT;B$dJDzqWGto!|=LiT1dpkAyGr`J(Rb>8RwyZnC(~sJ8ea?vFj) zxfYbXR&xEM5cwbzOHY_V93!B*dzOzaK!{%Mw z{PlUkp5pSWpz{n)MBc{(+U}R4_g|bl z(jKk5`iIMJ)glEHb3>kt>%r#NCqW(kTs(6hm%R%pC^&HQ2jh|HC}jB_B5fq_OZ%@=vnOO5 zuHx=LdUDziegtg6zMUm}iqFR-eh7oH#lcwFKr$}o*JeREGE^)flluwlb98^;;)O&| zHjcyTVUqdc`YW@p9F5;mLagU?XRgnUQ{4xOb29O&73}}ZhZ-urF^Omc zo9|TtDiFD90{47^XXI?u_;fm1*k5u!PRzI2ek~ZeWHPt^)fnK24rSO8|0;HV;csUG zQIA1XztMc}Mro+Rdk<06Wb-}2Wj44~O~=#LNctb*`vWr*(h!{8Lk>J(^ZojPGo-(E z;QI6FdueD?&s1_~oxnHUUr_ky0TU}%aq|n6?Jf5UdTkZu7qmaGO$dXPBSN_Ttn>R2 zn%Gc6J^`EW(~gM{Ucu*kQCd0jaW5tFv)O!`Zp#6!#7vCz*nAgwR)DO28D2G>?cW83 z=U{mM)7<=7?bH)EbMgVs8^Pw=^JzQeqV^BZ(qi-NP|^>*Z0ti8Xt4Qih*U#&mZ*^D zGueD^jhqCH?i28{4eb1*o8}zUa9}2R*2L!f_^+vO`PgKxe=nG@0&TTjN*XhS{nzyR zoOzBh^fy7G{u#}8rgR!|8I($v2eJ9id^!s@xy-h)HoScTL3scGb3^v~{hj_rQDXY2ri@vsRS?_zbRn(uL`QGq;jFDUO zsQT`UiVgp_e@+#N@4x(|5eD`_eEvU`A3`&NO3CNVZ2r4^N`R+I@mzmbdT|KdJzPqj zZ)EeYshk6MCuDK+m+^`fp!B+oyZ-Dm_8dr;pXRP#RE&NC2bVqM@_#w99UA%dAJ^aC z`1eEcyZVv=UTpqvT~bB!52=tDN&^4%`ZKvO5qein;NH))Ce{j_F`P>*?g{5_fT|z6 z?wJZ%>!)!2z4)FxIdhiNZk*m9fC|AxbRQPhzZ{!g*_?-@E1wi?dB z``femuS{`*)0zvp{{7h39lYAD;ofgiSLO>x`)}v=FDyolF)|%6y57APn_oo|3cAli zxcSNFWrvWNc^T<&n9Xl?b^??his!B$kM_@ouUoUY{f+)B%AvvR5Z9lhW6py8%rjg* zW3(Q_>V}8-^iLswrSogqVeQcGxl%-5o$b%2qxvD4KYc~#Tj=~lPfr!K@2*OGW!QYm zJeUBL#S`$_*TVNp=hvPQ^AMglkMw^i@K5vkM0P4%zdJ?r{vf(O3{z@(zucoWWZYCX zpZ}g1!O0>cZhrl#whVQTDkFR6cW*tPK<^*Yi=PQ27tX|=oQ2OXg~a}xKhOzAK3vFM zU%UQj4fM(6^O<{ZJJ=_0=jIR3e~dO7dvSFA8#^|idY+-MYT(X!fNB$`NQPSPK*O z>m$6p3p;;!drk_i%;WQ!@~tmAaHt;{dsyIy<`YG!pw%l?N!&|eoc7O|2PQycz(o9W zEIWV5i?T+#Df7wu&l0}H`SBUQDUiQpDwoeD&DBV$#XncS{lWB4#ZgAEyT36vKYm|c zhI%9%BC0iPKHGnv0lj|k`Fyl?AtVPoarxZ%dNm~XamUxjNWOpZ`dO*!cG&FU%iVu@ z>vss`olo4@+_ zL-1omIX8YUGC2d`hG)6!6ZzjBLb%*xu0NJ7ltM*+rO3e1Y=1QK?TZSADv;Y{0$((L z`X44C-`lEW{w-mg=CA$S3Gi8U5;uO^Ew)B45806WCc^jcXDH_HMb>0!NS!KrKQ8T$ z>i^u){p7VoF-O>+M(3|iH3&Z4Fy{KB7nGqls^vuWobY_wAKg4>z{UJoqWX;XN21{f z@+nUEPz-0=@VJNYrTZDz;s>#zU8T>ExJMv2X5IO&5ztQ17~B~b4->pEi+x-nCYD4b;T z`Rlead~TQ|x<8kW--c`Ep-%F)WRbkU2hC^5h{+IUtc6Y6?jNN2Tx=PLdJ-VLr|0e`lw|*O{|Le9BSrTNXP&e3&!7@RrSI zrpqc&@$|qi21)o4`(vQuR%oy1haWXb=8OAVMLHp17azu5zpXw|itgMfCzB=%{L$x! zIvtLKH71GN_hzYfCDdg!oMJH@rj>D$4o%nGW_w#tB=Mi$A3FCD9wqG(HwwSBnYd?kWm-fe~ ziB{;WrX4vYEAT<{nP{g8rvtRP`Qwj40qA#AFzK^FGGFYESqd%n(r#1H`Yr8`4xT0G zo^J(F-7Uw;B^XSMZ$-e&kGM$z@Ioz+^eHxTOS-+e9Fxqui5e_>1JqE4xH#Oe*( zANv++z{*B#{Il(R0Ue)9Yy8o4lMpU{lfn!^W5hHrf1mVAQ13aFMC~q{zh{pvVDQa3 zTz@R>Vh=Xqu3Y{+gI7THuC=&Ml;4T@yFPt0Y~8Q}m-iOFf4YBJ^fL%PWQ23;m%h(S zP?vv|WadjYf0yU&f{{*1I9_zVM_j-3is)nXJ%2#`mZ2W4>raP~`2EpuCS-tf={|1! zj@ncLHIbFr`n{z75%X!Ad;;DtJkRBmB;Nxm^=I7p-TC})P{8fUjqYrJoEp~~P20rh zbM|LtbmO5qQQFG($4_V+l=f1^J?^pn@%5oONM_&yGT;H5&#^DnVZmS>e6LWLPxETerXfTK2ebF}w75O74oL{H!ZuzfZ#R>G)qWv=|Ms zsv`5R3G?arzwEF%Y#(C9jsL6G*}=!SMOgWXz-P;Pkd)+KbMi9y=CO{;@AX6%$~tGMmr#KC#f#ESbw^?Z9-H5SfdI^_TdkIQ}nkF9xri zDxC3MGA{O4_rAyB*OUwR)D1R&UDO-FcYPDLJ|89b3v`zA`7?Lzg;pyJAe-yh{2A1Y zM~P=N$Z;1of2P%AVd()iZhhn;I~zTewkPfPvH3gJP95H_(-p;kKkEHwqg;2Qxc#HG_lsK2M;s={d-P!T*X`e#!R#&D z>5d<;wP#1-{*ukFot7M$5I=wnT+imWSKT=Dm}nBKC2W34?ijcptj^s(c)f5Y^6Th8 z7KX9;?fgX*$~^T%{!8=gwQdKxe>;>k4QKOf*Iy50W}1ucucY~P8CQgMdsh>id2D{a zY%+uDRo2*`mhHbX2{ur>V=V=!*3aXF26fV1K{q=NUZx$;G3@h z)zpj8?wA_#`3sv*1?w27Dox?8AKj9XGs;~wp#JenHlN*-_QLPW`?>yVQG5^*KOe^K zw++Tg}xW`xa&(l3;a;wjZm`eh-ALF zKPB6w3vbOVxc>TaZy;(O9!;LhH@2;hiubn$7f%D7Th=%+i_NFb^ZDR2atW8uur5pB z$bt>r{J^w!1H`5KbNd5JJOkjt!$@v_>e#g+G|T)5X&iT~)qm;wX_#*`m>y2y#{Xps zdttkI9+$sW6A!{O|7u+Gkj>xNEDW0*E^*`gEQPITihXj4o@!f0c3^cj7BdPX~@FQN|>|U<| z8q4&#_0e4=KjbVQMjjY(i z{)|V|{=9~s^TBcV5>fx2u8%Gqmp0PY=~a)_;#&EBLET^XX69m8)!CcN=j6)u(0tb) z_x;fJ_oMDVieJ^!s8iIy`ltI+TlqUf#s4=y{NX>XC~kj$xN8x5^6Cg#WX|UIgl05+ zw%X0@Z~fkp3ZZ#<-1z>(_W(FOtHw7@vH6vi!(i~^5;wj_9KHpgHooBU+waF$Xz1OE zjJv}2&sz_BpnKN`a^riS^JCDD8- zOA3ko)9J1$n60o8@#{zNyCL2ho;oe%`e&uH8}wi1&CO2>8@yo8pa5=sH(A)j$iZx2 z{g_ILNA6ML8^Y$ZZ)p^$X6?p3=ScEPaeY<$K+Y)O@8J65 z?L3(M*U2yUK**Oo{9N>YP;q{`qN(NnQS%zCU&-dTqwX<~)oZ}dGT8ZP`yscWa>z?= ze`?vBuW;786Pa zZRvS~Z|niocvY!LVb>il*}KOIOqZ^`vv8HWJWLqA63zcjxe-kE?! znhp1SVf4Fsknxqz@2a(n;Ppvwyh*hGMBHC>8si1uw*`pS@9F+PuL1rr=|L2?{E!Qc10x$%E>qMT8D>=17MG$wElbl#fJUBB|%Pzc6%Yq%iqK-(Mf@-3ix5M&sJgLViHkPyIp;qVfrK@MSVd2IiD zpmP(dPx1N8y7w6@CrFcpPuc!C%(pv==r)*~cNh4SqV_+@cOQ*@DNQ90ze&c$_w(P> z90?QqPv-jPkXaUJN_!_Ft-|IrJZ2)8t~BKOXPC@3bSpTV+=vtA(|i^`)&l3I>0JMG zKkJV)Y-36K4mO`1^NnHq8C$M@_QO#zT;SqhAFhAO_^yS#@qwcF4^)2I zZe(YpK3)6P+xaB4^7o#~Pc5x?LdlV6Zhrc_<3VJ4xsEJXW%H|pB3t$k?&11t^D;T3 zS7>Pcf*{Y<_)qhz=e`?M=M-?`f4p%4EI)OG8~;yQ*Fx&W%lLFGn_m_E8?aURHFtl? zqqmKcTxy9ypcgOB1WXWJMezCwOy+38yic!eHYbx-2UnP ziUTMy{1^%FWb+B9BVhZmRD4=p;*a9|)cSJ@tg7Sl7gLrG%9=;X+W=QXu6AAw#!w9_Y+KKv4bbR0bVGcB?uMqJ^*Z;k)ID^}TO?dQoNqiRPpI*H^ zTi&l5$gS^{&UY}XR*2Qk{oM+(9;!PVQha4nQ$E%Fa9SwA5G_< z^EZ41tC^j-{d?Db-B5SkAzXjFEIShQ9;!vOGueE)ts4RN*G=WVA2+U(8H#jqCQ2XK zd{%r_hW70dw|_rk&K8v0C6dhhCGl5reSg1V3f$;5Q*{3&-M^Q9u@lL^*+ou_7vA6F zNAdafHiDb63%L2`#dULFz?T)=_4|~7f9Tlap7k2VQOEvwe)9~~pYqIcf~8M4;p`GN zzsGO6!!Vg3eCwcOT)aLNH+l!8e~#g<@Avy$h~)lZvg!ew&l^v}!K(dUZhSx0lnf{K z6yk>sY(6JA=fQ^`d_KF{9Dz4RS8=o#o6n;YuR%u&&d)h`h3pQ8O!EqXTm zGF^$yj|%)`Q2R?vp8ZC4hkMk==0~>ji77tM+BiY@=gr*szBBVTISEOQBxWk5sAW{BG*Z;W*eqcR3mRtWXOejPb3J5XjNm~7xuCHvZ!=bzJUW|rH z_!P%~KbK?}^rsNtIwctw`|I2P_QS2vS}dEu_SdBaHE^QjD)th+|3Khi zyZ_H_?R&UT+L>fzu=!Q(CX24VA42w62z=7{XHevDRG+Oy;w>fP;`*sDWEgmFnaZu7 ztQ<_y#0f4$w}S1ji)zQilJ|Um-zslH(f*Od@i3d;^XDgno9`@ceV=8#6V-ilvy+JEnQzXMgNE@X8S zo8RQRuIQh$BDw1%;ZwZ7I4e*x83>i zp#8;&dq1mJpbrYT6-n0BvH5N9G#PX|x4ggJOu~ow{7L=PoyaODo^0!Xzttb<{*>og zL+JINJvK^^tUrj)FE2Bk1r2LfasBtM`Y%-O)U*E49)Vxle>FNRgeB%%x%sV|_AlhI zs3+Hd_qeWs+gpOU=ljO&l`=|i=w1K4U2Lnr-lpRG?%0Gn^s&W`Y|U@O<3@rPCL z%_kV66T;7@^M~*PDWhXpzTP96&2RgZ?Qmw&F7E!9E(ryw^V8!brGd?_S*8M#pTt&W>t9O+pNiT>BQ^;^}b%U~w`4sWa#_7~9pe7yDzDD3D$ zI;~{$yW*n^y6HHSyMAD@au{;kq(jc`6Zob33rif8ARTFQ_rLb8HbNgixsWLn1b*rJ zGwZvIgW_q%-2E-@oxRbe*-@hP1A71K38Dda@@I4FH?8CysH`%9oC;&}yJEQkocrd$ z&5u#(46yTAjis|Ce2Mp8mpFb$2R8JqPx=i=|p@ix%``W9{Dp3jmp`-A*u^cMNE z5|tnSnZ63jUIugX<7dHAMhaW|)aO4J_zVoU z#)wdmd!B|niq40L{n^tl5z>ke;)YtbKd;E$2e%g<Fc;j^!_Dr{=9Kc z1JwJz!=3X5zNM)BvBTf~2ilE%zWY?jpy=O2$@pr4Upjw&eO(ESzNz z;P5aVoFCuz{ZsEpy#A$v2q4TZ(AekPtg8c8EX$_Z?|#%cTMO@ zDAW((@_8$1D_p4Ag-u20YsLFtlb+_IPtGUFmDz0mg5^TNO+TGmzwJ7m0NpzjarwNxFGOJ*i?G0}IroH77jC}eIpNeGjr*ZQ&{P^32Y}ID_t7caj^i5ldyFYtv zMHB+j8jOXz6(-#Kr8YiY zk7kUECa+W2{23fmhn;`saQn9wAN-yLX$@YS zDExjje_ixGp?b9*^}{=axB6=yRlk*nE`ZT?+qwO*PB&M;L1a6ngIxson5!hD+Fy0kHnp>(SB@xiPS5&wo8VL8N}xI+{MmFAw-GDsz~?}^PAUqC>q;c zk4*9r#%X^4d>#UCs&u&h-=%(r=)2P*vZ_p&PxHHD;21a`%;)#2vKLxc9Zh0)u=)KF zss^R^`TU;!p$k%)P9i>m+Fz(T+7kMFap(3Iis!#YdH1{3pXd|X%4agg=S)32XxQV6 zquTnzbbqW^eK`!%59P-H$ZzjZ*7ff7gF1z^`YU}tc98C7$ZU$k@JjH1djHJMGkK_g zz-e;*51Y^QvX=WZmSu4B15Jx~u(2rS=Lc@t5Iur$`(yJ{DqvQ@O|HLU*9%aU{DJGQ z;Z`rf5(grl5ufS`;lzn=f01Nt6L zqVuh^e=btCfLC)pxbZ*t_iJ?AsaySVJ>mUvG@lAPZNWv=kGnr+MEZN=uO#k&b)@Pm z&4J6{yLTv-trqyB`v>iIy+vbQbgz%C31#woXZwJ2B zV$P6Y_}X&6`%zhTelTqGcXVX8e0`@{+t&Rvx2gSKm2cx<|L(x%>^_dVKBFXq1s#s419r7*QQRJ49U^Z)wn8zeoWM}66G zHvbD&`9OSLJlDUGTps!`@+?^s$L4=nRS>MuZMh$tvpzRX`#VYv>+}EkI`eQUzpwur zGlys}B&0#1K^Y2XZDTZuG?3<`NK_(~q9jFyOp!=Mb7}6A>fR@56wRWUN`oS$H2Hb1 zr`y^4x$gb@{`I{s*Zv$juk~Kz<3KW z(|_m=I0;+xA8|7Mh5bj|uNzSM`3skkChR}%FMkU@amu(^QCQzE^zMZITW5qnvuLVSmfOO_vuyr9UUY-dwPA$*$58vv zMZ4dkli@02+avM+{7C}Ee?L4CT#m(XXZG;=P5YCxUX3W~hz8-GY5t$=41jI+o0$Ah zo6&$K)OQxA%L@CKF1e9V+$Ehk|2wI$2z7dT9nZQU%>Rb|@esXn7gPVWSEoYAoMTMB zcdp$9o0p5ZuYSV%{`ANRu<@&6`fIz%H^94~nX@Y3`KJ5FH92pf_JJ~fB_quD^6m1d znTy4Zsa8{CZm7Z|^pN(_wB* zec$J@2!(qk<28r){xj`gj8WChYzm@tIuqH>l;#FYS}Sv^D<$5uK1A; zc5Pw~<_Pnv&~hA}U$5eNSqtm)fST*@di__f`%Phfk6wEXUgj!HeqHV4(Q`**rar6a z>!ZmA4orRSUZo3_+w3@xj`Q2JK6~Zcp{{2G@HZu%Kbl{MH@)F^wi{EQ2Mq~9mlh@C zn=ASCG{3t`EZ|1D5A%F)?ya5Z<6Mj*e)H>TeJ-A7(_TN%WcqWB39fK*!(#68Mq$2h zJbQ)C^-&gYDv$fecNoR@ja(nN6dB9xAM3Qufl&`OG57Cc@eZA`BmM6WM9!bJ z$<2XktwdselJ>vK_g|r>-;~9N9M}KTzZgnCU4}1%c{Ul$`LrZlh@8A`;VV~#`OLi% z2gQdAnE8MIlVqriX7h=T=E3ly_V;ORh4~D-UJN51JZAPUf{tE;?AmY4`JP+XYauvE z1^3~E`P5XDL&LE#9{8UypLd>gfu%~rxq_d(e#D5RiTu;`jV@Z${6hfl9WBgn<7#7gJZ==Xcnj~J>GQu!wH6}R*c7baaX)xIb$+tZ+#Fn2 zOl10lU&nJ%zW_0=>+sLCz8Y0o!O*$0xbN2d=hOWUKP4A<@@fguKL*PG{!D&`3eA`?9eZBtJ8+5<1`LA)F4bPV)GW#1_Wy0Ivm&)KSKj*(6y8re?RESo7zJRFoD6Rc{qxT{FdRl+KNgG4X<5A4>l?9K2(Bsq; zJUElrUz*=7Yt5kI*+k-gni%SRyBX5C=+9m;&UwwRr}-TkY6aG}dx0F%tgB^BE(fXF+Zmo8Mz)FHxVbD&mP5 z!unk1uoOmL%V7H3Y`H=daJL+HA9v-SzSI4=`ors>3+(2O)k%IolJCh6x59bv<4pgc znza)K?qu`5Wa2Rh*ip^B=^^ZI&xVyjoLmdnZ9304J^!$K^efovs)~K@3iEy4Q5G3q z>y1Z$=J}@QACAOoLh6>`+@k;ZzmL{u(M27U^gx8mEO|a@eV&%p18U|u5dK#RWC(p9 z^`9-WyBJ8!N6>taHZ=mB?(STt#k@Y!`aG+20owg21wUNP^GWl4=kh=p=sk%!|1+;{ z2U>LbGOp`*pPJ_Tf98{CJ)BL{ceFmQ$#jBlYT<-F)Ba;rziRYZM^W50J@y~pK=Hjt z+6xo|*nH2u{Q@lqRiZy}jq)eY6J|n>u1QRPl4<-Lr4CmS=WdGo$8Q+rPu%}5hRD{8 z_7^Jo@0Zs1$_;zbg-y3{(`sSY5r|odceG92j+Zo<6Rrntt=2%9N^c}=j(F94MEe|oqOXf z%zp%)k188eu!R@TKVAQI8$S@T?@uE1o$gPcZ_PnZvMytbFrreC0;WKmG?({D)ZYqr~Ri6>4C$!XG$IazLdYYJGTc)pA7g@GoL?b{&#wH2m9X+ zM1Pvr|DUbaXyCB<_(#Y5GtIx+TtkQo^lT=hdV=X+f*$OEUSHV!R@)wdGp}nn!)A$pC+9cgWJ@6?;5(t;G{48PpM$Qx z8vb%vm|wppX*9gq1dnXv`J?&WWTOs!Z?pOJ{M#KhHL~@)@NYMme@MjiFDv_6qtDUv z@tMVZ{LuVbIrf5grXEcFKK)-Ha?{?1#TSM7{hMtH9%CkR3(xcVPy6%xD|67G_W4L| zi}3!6?jcJ!sx_CmznAtet3(L=JeP5?VLYES-=$qE4{CbY!d(Zr8^g2(O@Gr+G|Dx|R9d7AwX7=}H;ZT@mmc``zMbI8J{d6UE6$$hG z^W288+xV?_iHj2LA-B4o}ZdqFcdoXolCqwO7p90aUI=QE+zgF-TaSF4#@X+ zZ4Usf)Qlkf3C;J%cXv>VYA3OA>#Be2H7LH%Mva3N?f3gh?x&*lTSmPabpsV9-#dQz zgH1c%w}xi2hUz3%>NXp zSUA>wFZZdVKS95b=HG2ITo`ha$$zh+98kSg#w{Bn%zxe2LvZjln|~>LF}&6K(LP@* z@$a39`mf>6Q)nw>^DlEp3i)RCVfJ5=^g07NY{m2^e-Cv-b;l6XpBN=}1y?)Z#A|qd zX@8=zV>mh;z5u`S6V~?;V+|mD^=Pi7V?E9P4F3QW9J~!j&lBeV=+yr3Ja`JXxa0jb zTHhb$Y)9Q9t}y-i9iyS(^?NS2djS9Y)A4b;^EFhHE+t0#!tpWtkO<=EMlk)&^wn=s9~jGeDn($3&WJ+2>(v&|G`^TXv-9KeAF%VhyBHynf2?Kx)3mU%hvyzeY;W7 zth-q2r7-{VFUCOF8aDsivy$M^`IFp2FJb*J)5wA7iS6&JGy3PYwuj*DoTpss2T6R8 z{ziKZhNUGxxVrDc{GZ;obql`mby%g?vu*!FC6D{iglRLZk+Vc3E+`=Q_TB z%Ac?A+znlnal}Vo^6P1Te(^tTSUegy8%KUU&Htpm!;sI`1^9PQVg8To?+K`CG_yYw zuxu{!J+=*d`U&$NXWk#Sh50i3=j-CPqerXDu+l7He*?)wKyOVB;jx9 z`c$F!Z6tD(7oYTA@sDpQO8;+qj{%czaa^wjyuW!t`5W1ZkI|piWPN&;@;Aw0Q{h_8 zX3o09|I_tpZpD3cHC0J`#VYon{sX1|5tR#JK=ScYZBt>5A*A3{x#Kxp^V-^IM7s>|7Q7~uzAQBrvC}| zo`Z~UZ^JuGh54^u(+~9T_%i!5K6=~HMV+fysbl_|?$4ZlJQ%wF3}EWNWtanO*c(ag zkJA3Pb7he94{}<4W;Ky_HXehLZG}xCK4$Ct&ozE_%fEPC;4C3paqUA z5!3%D+FGKz1wpv4f-wK_&-7t{`B-LurXpcBI@>1=A0H&le`{@D*fq+J$^QfQEaW@r zD)x2~*8l40!4UXp9&`W6KHDB<{)uGz8&7ltH9O0R$IgosbnMVo)i-2b7Fwhf5q?Z=hMZfnEKCIZilh6t}*q0=!651 zQ}&FLs}tt`&hLxRr@WPGKE(4+?@xW{Uk$|vJ7Z~IhW}m zI4B5OdSo;G%Mz0U)HLe>u4@tIcf^foP;V<_?ysJ7-30SmPjN##-j9?5vcE33EDOFD zT;sZYmgqa_Ut%)$gRjMNuKvC-zfT-4w!h!_lgaN&yT_2y)EPe;Bh0T|>n~6(?TeHA zc>ZYr-p5k~R?V|v`WKh;S|}!o&9BPKE>IBc$n3B8EE|H3jSt2K9p@|P{!MYN9@zaJ z%Y47lWXnvHxHAoRl^5o>@2EbIch!%mU+Mj&S3usFXWcv5( z1MT3IRuogeV;sxSC~H}9)YR~Q{N_{qE^I$PG}dH2H_D6Wb1=p4$Td@7g!@+J{L8&t zHR#21O>yf|VSO%y1zIJSt{pJ{5|2ye1a zGy5|=WU}D+@axmX2K-^0<-zhH# zBhQ1u_|OA>J{=VH*raq_k zPe&=|%Wx-YVZKMoSU}pNK<<}%$KOxsbIHC^v|C12Y`)~{KYm|O{mYrlMnbpCQAGVp z`}fGp?$B>RJa<6Szoz)EJXDQb50mGEUr_aF_wJLSzMX%Ge$)PBNI*48j@A^`m?S;jKYIu#7YnO_jl?3 z{FY-QVCUc!OnuM3DMlsnGGg_=i~q$(45ja@7rTMVp7lh1O6$9f$0R7sVDp_5U5#c2 zb`ifhEzEbQOCbFBJ)0YUP{Jp9Kgq$j`DlH?BRrcE=DTam3b3y(;%YnISEBpx2XF#h zb2-E0`%*;)oYK3&)OVj#MUcV0VEXUI#`Ey==`U_w7SA{BzeD#ugpUu@aR~_P`{ctv z;A?h2ys!_?7tJ>pq69`@%dOkqp>LGF@42suqP98XvswIlnr|h2O(@7_^L-$45Xy{S zi1^)%o6a&*8;-IM6Q)B3J(a2mQfFCB+;+<#5a2WZ9ihB5Q}ne*qhSIuD6+xbj? zz4$AKGF4^77xy%E_z!abDPDa9=-*z!)bEo{Zh*$d6Z@xzlzu>@ZSz|HvS39u$P;F#Y$_2l>diyb4bVzAorb9&U|-9hUo;{MNc9fXvA=%>GH6 zR|Z_ozrmdEivCmxit;bHn^%POIn(q!_;~#0YCG-IZLf2d{s0|9n%lE5z)NC-#5n{^0fY_p7ehBs2ZR^uG_0xJFYPog4p; zzXYoP(PwG^SZ3#N_XvML>hDSaeDo^gF^)YV%b<$yEU{1zP804KH2GW9nkA|0OG zy1|vbk@yeNUyrvf1nERJzuyD@gT)QMxf31lPtg1x7vG2XlQr->V`2S;EiKSGxIccP z%=1I*Z}ApI=;1kn+5fw_TLX2Pp% z*#kByjwjAf(EPfOn2OSp(y@4sFuyau8NtgIe=e}2|4!GB-}?`Q!*L6^wzpE;|K1Nx z?{7lj1!O-=TI|yK^FMxp^3NKHHt@G>CDUKrIqd=&&q@8I_b-oqp8%(`l9}^`t;?!V zzye0am=*QF&7CEHiyWv_+#8HdYqq_gl_4SX5pTS6yfSUw*ETSt0P?Cf)9uC{L%V*ceFaZyXnl$2;=<+y?@hH%N+R^hv3Z{`Smov zs>R(QWx{x7eb_a}4`u3S;FwHdey>CtK`}Rts1Ip>-1*7?P~H&4^v4zv=h4-3QsNJJ z4TAhm;jE#@)KyG=cRh86j}{vU{{YnfWafKscz&O)zhkC7L^76I;u<$$|EnB52fA48 z;3jt5zed-0X1gNbrQd$8@PaU(?{>$-k@~Yte_&vf)_#A$P0swGFrOZe_rTPESKLwJ zeLu2(+jH(LEH7sBDXzZ@JMU>=O*vsci{idQV_kooB+v69Ma@@j_ELc0&m*|x{Sv-N ze;_+p9gV*2f(u+F>&gD|w~Ee?uPxVFhMj3dMk1(I7uNuNTz3GHMp!w|i(-dY`1`+*>t_bZV5AM-DFg0_hxnS4G^>x^KSEAHaR z^F`~YifL!?-|0f=C(Wlp#6Wb!cM;Z_!mp?Kw2$rvQ-*pm^>e}eDabD<1J55V%x5q% zgy&bLGwZKjTBa~jF_@YE<3F82D~`6|NwOaV`81wp1u?PF%=*j6&Ix*)*uY8VvuQpP z;=SO~t`u%zCa-UFf9%-3S>WBWgV`Ujy|)wHz4ipFe-`Gma85W_KHbmd5c*2?zw{&5 zgJuGo&-Bl!a1Y($MiKYxlKymg>~4tjsO5}~3iBC1@eJIo{>v?m;Q6Hczkw-tVBCI9 zd~k%Yeh#tz0%I1KVznBcPuiabMRo!`9Xn!wj;^mv|Ei%0`D{L~rmBH~vMZC%BgY4z z>sJ@yqA|jJnv{2itRydDK7-cJ1qqW;@udvBbeu4sow9nt6wwSOpYvz-hv)=0pYI({ zqZ42M;{H|d1o^zNX*l$5j%McfmJmni_J_@9uKjqBDNNxke1!SDdt@dk^vz}VXKRM- zMC->r#V)^u`E)B;3Sm(PnErD}a~vrDJjadDljLu*KWh?|3RmlHG5zPB`vtJHjLoNU zz-dS|Y2#-5@O;ws)6L9E==xd{NA?%ya{y|BK8Hf4drvWM+ z4H;O+N|;aGCIk49GK1+qjdc1$ucZqK|4HZfxhqei$Y+1>?FIFMe12&f1|!z5X6k3k zM+9MW5{Ua1@~Ql;w`Ux5o0!5Cm-GL=w0{1qnE@7y*?e-}a#7IWXV`qfO~L#gc4Z0J zw7<{C@}G^_ao`jGA9Me#_;U)Bx|TEf)OIO=Sy0FHpYw}O!Sc8^PTX-nDa~g9u7HxB zUGT(?_j~F4I|e8;Ldy$Ny!n_gpUMjIuw#rJlg|}rRMC42H>{w;^F{Ni8L0{v?y>cA z{Ww$fwJ;RhA$~p0=lVKr*p9uK{i(ub6OoNpCf?9ln9olp2B1+rgL!`CSLc4<-hO{R ztG*Z2A4iYv|6pCew}N~os11WZPgZlH$-Ms2{_~0jf`D@g#Qmf+pA%1wh5H#P+$ym! zpM}-aVamB&ZfeK*Lc0EG3eQE&FP>qoTwy+s<}QXqQU^K11Crm5%Qfw%eW$d1n2d5Sa|)PL*@r zcL?)2v?3o?{H)_5vxNPpuJuV6I8F+ujup=D0~g(fem}Y}=fn2PeS+VSY(DoW$-yck zdnTWGQ7Y)tH8-r=%IhzEKgZ1=6^K3I#;o6Gr}slGDq+~ONwS`N-@*EC7udMjoAduA z>0grb2M%@m;C6l{Qy-(B^#PCe`|pcn`0tSJKTR+w&jo13#on7{5i`Jgf3H8*vmFn@+2Ct!T66#gO- z=FcLg9R8SV;c{1Df2nryBMcJ{z|#}?@1NGk*Yjn;Glk8c`eYK2uv9fL-0xGZ}B__ z2$;B$sgGLwMnh9wD%VF}m`_JNf0!@c$*h02JMTbqLtf(l_6zg5<-{WRJn#_HUp}9* z7Tze9Fz09O+wZ>^f8jRwi+G=m%-=d=^B}4GHCG-h%;)IHuEk?!@Gd?G9SWU(tJ+b=Y_^}$->vFCHbG^Gk&2SJdB*h z&CcWFgYIuWLM8yC7Pa3$FU;q>RfmwN%};zm{OTW{Qq=yDgZ&UVz9ojp-!z{C?%0FX zk&Q(Eo%WZ~wH}~ux{b-_tu{ZXuiDAX-+`ZU+WU8}@bETaKF4Q)ix>Z!Mhl zSeVbV*WN>%*FYwp+m6e?;t~gD|0r~)5^{Jr3SWH6^F{MH_Mj5TzZ=EO-^G*qAWx6Q z_{m*kJ zFrQXzzy75lpS3U;ly}5%zdQ0Xo!@n@+Cj>tjl}si+F#x>@&M!2+c@8Tyneo*{H1@Z zF9fUQarI;PpVRe^enAeJZCHy3hLwx{cYl`dzo%O*gq8k>xbgtWdb0jGry2_tJ|$ci z;(R{Ir?b-*7@S+dtbc5}?}X^nZvlj4tB@t9sMVo&(l?k@SnOnGrwo#nxK#; zi*Zyn|M@hZ>t}0%ZO%mE{!LmxSG0Pfh-+E6d!w*^wl?cP^N`uxly$=Tx#(09npbk0 zdH-9*4`Z-g63R{ZCakZAt@oozc|Wl8ycdG}R-YOK7qw%V`dX-B2OCW`G4ubpVeT-Z zg5;O>r$h98VdLsNroN6JoP*BG)M4(XFu&n}!SLhLA+D<9{3gBs{w+ENW?U~}`qOWR zH^XMrO6LA%vSTiktG(rlmk8@?tIaXcTqcc+O@#Rk{eBJB6=>ln8N&QVOl%Q3^|Ind zcidkSBO=D1rNW}>LFdIlym>0m7wr!U`$q?&{Cb-2Wnqfo zd&!-tzv1_Kqmd3vu;?bgp60vTA`R%BJdv31qxqiUHxBhl&cc%-g!!)Ms{`AX&E`A< zdA{?3ykFvQNg~>xcN?2+5}w~~9byb0?}sw`Q=7LGp*7;~_|CxRf_xvXumE?5Sf;;i zjUEZpc5Wj2r$F^j-8PJZ5|qZZj^g!`)@RgX3N&BNW7c2q_GhE-#dWx_O_=Yu1A}0^ z(P1t*l>hJ3d~Z6p1`cXm;FMoWeopH1{OTm=?^?;Mzb@|C0rT?SGW~78*+(JufHdyX zU6}7@zplc8YAw7kPMGflaz8}pqHH+1d%VA)`3{`_7Ty?`;hm#-zG%KbACZD%!JSI@^)%nvuhn6N`Xr+NPxF00 zWGu3}m4*8U3G>}Uvj<$Un$4NZ^L%p@-=BgK(XoIE9C1sSZ~u5BC>RyS~HxM%03?CWE^F{Oh z=zN>VBTU43`tp3xd=G8wgp_)E;AI8;dYbRH*PX!gyE_-&Te4n;NFYgbjnN3BrFi#c zem%{%dKYzwwwy%lztViGxsE|;@3U~CNSN>NjPCHhc{Vq45dZlah}7@VFAU*JO&HUE z?AyKvjSg+W=L|aDpQQM`<7EyzE|UDx^<7f2Ei_0cGWkuEa|7RBX~g^rNBL)Q&S*!S z;4JYCGsS=J)5HMzzCyUyBv>7q&-5qWkG7+<32*R@1Hycl*v|*+>cgCO6we2(-yb(c zL%=PzejDOMh_<`KFyA#5 zO(JDgEAC7-|NYW@7r49z`y4ZTaUjnZ&39h)Us3K;5$C^vUr+PhZG9)SBhdr*?$}?W z`A*!~37U#MxIZ%`>q)-D5{=M0yQTPhI{*1J-)X6xA?@HKV*Z8ZJF8?gs+qMN4+|0I z+ot_~IZxj?OumbjZ$wUiZZpr9op&&VEpCgM{0~vtjeJ&r!>)BTg8oFj+YHivko?p7 zZT7|nyetz5|4r-nrRlDaJUN}1kEQiH#A3AL{gy28k%hwi7rRb`S;_fau%m=uvVR=4 ze>>8i{ucMMuMpJt7@t6>?RSL9|GC^%;AwG@SznHKO@vt|?{F{5dH(=F_U8^pXG3~! zJ-6IPn15IM!_aS`3{hXw^D~uwufTr`wecS}Vg5UvZxkI2WbBZ2q5~{v#UX z08IXOzL7`Q-h1G*gFL@9|6A+i;lNuDX8-Qk-uCk-OPAueq5OK9|5a^jpgDLl)1SXP z;ekeGZpW`D3-j;q)eSD(Wb;4rdM{`)S;CxO7`bT|nqK}D?|f7($ah5fK$vO1mN}oe zri%^Cj$-p&Y3%|&q3OhYO+KaXnWsG*owjcmmz)*m`@e7>(ECODmlz=V9%#QE{jsUX z7qW!;e(OIEvXhQ5{mb*sE5SVHBGbQAwV#h)kaUO3S|ZGM-?!T#eZ)J?n0Wt>oUh$I z;Si{7lfk<>?)RbR8}=BL!j>J{`0OBIzDF4~iUt^2bK9Qs`bz72jY=)t?rV-MGeCPbT)4 zX?>r1!yT#AvHAYEtt-4Tnaf!j@qfP*uD39Xvi+6J{LU9LW&0O z@X9|tzf#owQ=JS0ps3^sv;TM5Zw2@?u=P2JW zkIUfX7yQp@etq>X!Ht zPq!4-=WpG*Lh*~aoXcooet%gTKycj>=KT1<{GG^feKWrHxJr=U0d1y`yJ{`hqlbjQ zPDFk2Zh;k~$R#oT$EjE+n5vn<g^fN#)tHbd~M}9r6zwX~v zz*27tQ-6o=bVEmVvoTf_=C`q28%}cp-1HRw?|(t{M_MNIgbVMM5c`9){w}x3Mb$^Y z;Aa;e3G!Q=VhT3(r2f+NW7YHFAT>XUn6IGybLrMRlSQd}meehkZR{vEeQL=QQ6_j$$y1?}|Sn zVSOGXZV+v}W5aFh`2A_VrR840f5sL}e=#VzRaE#F5&gdyYX4?wj4To@9)snIcs^-; zemX%G8U~Kxx@hx!(eoKc*7Zadufnm6CBL5LJJMDKo-Ua}+#f~ziyeusXwal=yt+lQ zp4|VguhW7V4FN=do8~((Ssz*gmooX@$K{~kCSUN4yAK8VK6j))Z0NO)*k7diKAAlX zzRXGDhE3!7iJ|<(@b>-d^58E_zSWl^(3_b->_5_cUu?`l7el|`PNtJO^qK6RCiqEU z*ZSyN$TFtBzbjXUp@zOpfAV#&3+k1TjRPC`&!_Ki=##7kyY9^+_Sb3t?O*A^-bZZy zl^nBC)|e(-dhCH9|2JRtgKy*3aZ`uze9->-@E1$azL>-*ciity>-)pRY^1_9G5K#C z1t6N6!Hxgi@%>T$yE-=;**zZ$|0G^FZLsDT70Kt zJ$XN@<=vT3{_rR#c95(m^?!+U1gxCTG3!f9{|(Sua*w;dO%fku|D-uA11x+#F#Cs{ z=k9~fCuIqL13=!7x%$c_Sp0|0zh%P*k?#Rpraw2n{1mRlS>PEjh50w@_g$nO)cd89w)i|9o2iFE%TIZ#(}(toZMr z*8huposl-q#%fjk=hOV}*42X78v=>>WqSW7Js=MKnpKIH==1X_^!;mRdh0=&c{n$v zoZr8v{m;wl_WS758?o!*`-1VYtW!VmTD*?w-*?+uf{Dszrhk`>&PK!gH8bO5RH+Ec z-?8(|)v5w6qNBc`<0I;J20Amf0Tuk9rXttA6~q6+Co z+~?9g!T7M5(-#i5zaPPx&kEcy6mZmLW_|F^Bn!D4v-5{^z60!6&*c7-=k=TRPjTb6 zqi?NWaP$)4_^9<73uPzC{6W{pqKO%3q0=WkVfbCa{2|{k9hU7o#wq*rpHKTIpY=;& z-A{IWY?X?K&{_AH@nQcW4eY;uVAc*fZ|VbYRpXfc z>bAoWcrkl3aepV>zx=#76UFUd$Hxsb2N-rDljz^m@v-S(7P_C@jNc~<$H&*iG0sdA352?1uJtbe->3UWpF-Ee! zqMs3XS`U6b9Us2$72u4EACW&asQBo59HF5JIrzjS$$BzAHgX!UKVm*HUryH-3huG! zLtX_QeUD#H=MRIMJs@x9GU9v$?XSF7rJ<~4pK$*6JA(1?3Y$RwXfi(N`n&dNIto18 zh}Z4${Lrj*9#nnf`0;Bzy2t%wqOeZ)B&VLez*YUA;T< z16iL}p!W9zhVSNLK1sfRa{nu7Q98>0`5ABiEF3?Fclm>T^?g6k`(AF27v zL8*^n*Udp#{RtmGQq+9$`+_eb4^?Moecoq88|<O?T}i;?d(bU^ z=o0lqf9)`UU+nnmZ5{{1vK}z^Hzww$!r+FF+y_NIe(3t<=#)L+dxP!Y%4+|ENz&c% z>HEU<&BWl>qE{P6F!NJMcoiJ^GYD67yzfreH*3c=iA;w&GyR+Li$5?lXdF(lmGDW% z*N5AGML}ks%=j8Nya)Oj8;OhG^YKl`*YxmC5V)HiUnPDb^fN67_wwdHpRWIP)~UmX zX$y${7wz9d{MVr6?fI#%AHSZCuS3DzL3cz1k)L9y`=17%N=3HGpYYx9!tteT-5c6Y z#Bt|Lc>hB8$8PmaL-4K<7a0iWr%qi4LE7Xk%>KYLi!?N&g&kk^-XkGqY!FT(OZX$>M=$7)=-ot5?%`0$dUF0QWP5i6n#-B}v*j)F;5>XPr>V@Zr}NX31P8Rg zHV31Q^9^+T9J|#SWDhPN{2d)XtGlj7Mz7lA$3yb_YZLldcd#2ICq*#(10O3>QIdTl zzNjT!|9nj_Zl4cg`@3K(3;3I`h1p-uII#^aJ;ttov}{Izcxo1Le*m3-QjVsg)=rJM z;LrFDzDfVKdCn-<+f3%47gT(_w8%ix+&8TMS~xyb-}yp<`*G&{N8!~F7?CLE>N(-~ zkkeiV^{XB-_g9)`r@)an4b1-8!MXzI<0?<=FVg+xdjrnF@-^M@-rK_Q;dQQ7v^{ww z7i!4=esq5zFZv-&I4~G5y2I-`9UtxupG4(1oQeH&IzHqBe!(GiPh8tE-%8g%?}L7e zX1`_Um$jF>p#Z<-xVB?|ht4m%Kprl|P9^RipyMNKtvzb!wgdke#q&+a$03!@@cPdJ zX8%llU={kISBa&E@ayUPvR=I#yd4tB$#T4Zr1OhHQVLoo{){c%gzF!v7$f*Ax1M|S zmyd5czZ{=t4u5a3>c2bv_{ehX*YhhOGL#}O>aD9`In+zGY zpSTso`+a2o(3UO$&ro@0f1uRzEYzIoj@OEXap>YR0K4PzLMU_)OVVjc`m;QG?gg&4Cviua`!BV}%;1~xR*rT4 z#&>TjlGb7Gzbt%U18Xd|6X$d2{4qBw6&Y84!MhI&`zr%aSE!i2hwxW)eEeOLj)vcF zKR@^NQAd1{^~;<6lL7E?=KR%y`N44B;4)Wrgx6=ff428xEF@_^V%8_uRFdK7^-r8h zKjHdB&S)3x-Yk#9cJM!^`)BeVXW;UO?s(>D;rQ^jc`54uc_il{>3>l5|JCRB;qk5^ zcy%|PFS0E7?R}{&e z*u>`#x_@@ZdkcE9z5)B@+!l-v<8Fo!lFp8gn5=;yH+U;i-_!f|8Wkz1VG=t&1|7DB zV(0B#qXy3(9UsAWQ;}HV8}4oE)4@0CuMC#CKx*k8PO*a5KRP~E;WYFU{lKM7!trs= zeG)vcIL@8v&VN2#e|+)`f`#iZb1%+FeoodO#(J?(9l?$dH}kEq^vfr1nl#TpUBA~y ziLUpq#O~|(^>lnRG-`q2^5ulTqT?g;U=sR`KH_H6 za>4jew&?|%PO|;ggZBdet@|{F2+>@3!Xo<*54O|NC_Qz+o|P^2{UV`HAssw?N92&&>FU4atMhm-2YV3O;`5{PAtqDQJuDfzz%D z$Hzdm=c2i3cFg?oC*dy4ZyQ3)chU972B-I;KI*Q_{TI(|E$|?6Jf6^xk1slZ$glY> z>M8PK#z#rL7Q#9!nDL=?Mh3ohnnuJ2y+4_|%@(bCy#wnL`D~-A(7$4&g7{FVTc;^1(kwF6>{1w|@ zm6dKo%}-jH@ex`-9G2c>=Z^xT6yz894WGC(K`?(dZZ9kddFp^jF1xHfYVq z9eBb6{`aTzhtVEonBHk2(_blk3P+Kv+Vh7Kzn;z?C(>Wh`}Y^y>j%!C9Un8yhrM-@c zS8=td_bEHBX0ovUPoH@k3blvgHYEA}N&cVbz7b7qb7l6QHl%!kRi0jW)L+SZlK)1l zuOfr<-o*Vzbp6nMmnJfqu#(BYTB;PJyqd<@SMdDN{3oPXp@@ySII)iZd|LnKYbb$o z;zH*6kBPT6AowktZ|{d2P}{=yIKTf5L46-$r4M#Dy62% zcNkmWr~euXgBQ2IugREy|9X83LJM1PU8XSK&lC`(B^MI&y)@s2@?Owo+DT@8d}iES z7$JRy>Hq(mz7p`;Dy|$P{F3wS+hY;|agAJ7jpXMf-?Dvnz=D!a_;Y|T-?5L1VbU@k zroR7*e=I6~Z%3T(p!I#4dwKi&)kCqyP@WIk|C^b;5$V5iBhEMFQ}b7kCN{x`OfPKu zO|qWkTQ%y7=w6yPbARr4l?J+yxe|+R@#|@Q|L!3L>mN=h=C5eJBT9#(kxz2*UCX^?|zf@proFy-!GT;1<$P{ z-?V>`p0pKh`~HKe-$R3k!kK2aeg{6=jLd>t@IjF<-_q^pLrVX!_4|9XC#YqgWa@Y8 zoH>xb@(R@u7xsU~^F`OU zzb%?XW_P`b^Qp9c*YwapkKe7t_c?w&&9`xQn`qJK8N~Swns1jI!_aMoop?=0|DV?H z{TJHjtHy;e^*h5?9hT>;VD>*POxL4%H|ue{-ZeqKdtcUt)ovS@_3NIOeW0i*EjGW!hEee3 z@?)m|zT0mTT#9dE>T{zw8@${U2>(I%FXdkxg>UC|@Tn+a|6N`3P!z9i&!seX7+=b_d=GR)TPIUGPo8K3CpWv;&H@5Gn|7d<+jBOOfXHH=HZxvT{ zCOVw&l*IlBYqg(F*wP@?Gw>Z6fnINAjmO3DNj;*i0iYBnsD}^|}K{ zSj6KoRB_AP4ZUR2rvHwr&=MJtxlw{$<+#d}qS3|zK(RltT318&<9>MMRy9C^wNt|D% z`P{r?2=ZII6G!Jr){}h7ACZS!*=#=jMyNrh)+*+F*#gU0WV7Q9zB=-XAfImS^V8@Z zsh6yknxnoomh3wU!jhgqLh``f`D-F?jd!cz0mFnPi$PVY1ye^Q9l z&n|J(Auhd)JG)6(Kg9;i;2~z~r>0Z_=wJH6%FrOJ8 z?}@x;I&dK!=W_u%l6(9A*}3~F7*4jtGhYewIe+R4(fUMpX8rZt?gNy1O<>kvGASQL zUhCL=eiEsnJBFI3C#YP&NyS3Q_j{;%W8A@Xtsly->s*O z1iSJ3i2EVv{y>P|yiiJ^!v~bg%T~RYk=MR%87Z311YS?|z8xJIx~eC(UQl z&OvC)=bhLhUb3F#Gi!z%6lIZo((}7_b5)??_XI=Yz;t{ghq51Qb`+F#TuomU!5i#O5 zvx{alO7we!Ih|6${9aYp6&{7L_4DFlLzt+N%H?#NPoVSrdtEa~-^bQZgH5*3vzE;7 z^#1a5qfwAH@HCO%f#UOP&{Wub?kcnYH1_CXaQ|Dw^q(o8) z!Pr?5FB&Aw=Y*gGP-&pY%>*wBYmqD$-5*sZS=5v6|Q_;9A58{45 zn$LR8dgxWc=CdN=oyc8w67l{aT_0Jis34OMt8vXe316gsF1*zuT5UI*=|3MFH%H1N z^6-x7lJ%s1s>;hkkKtj={;HJGeDv-5eO!~tuc!CV+=7&$YiTr*|7m`wc&tF5Lto=s zsmp@=zUbW*YELIH=T{Ri^@1^Bsl@&Q&F^`$fpFy=o8L?RHn3J|KT$u?{FcpggVO7# zxkHV@`a0aq4<7uz%2nU?emrETPyiFS>IbeNQ2Tv ziuksXFu!X@?T0#ZJ^aH;SYIzZtPs6@F5*(>cl`d8KlNQ8hD|Hl`Ry&t@Az3YqJ#|| z#QYr1@5-n*kaWcd2P*LTNY_uHL+VARrn33fuu?|FgV!+or)g8ZiELtKGyUoBvu3C$ zJP*fD;rXNcr(6AHVD9lS!k^OlKXSl4l)dUcK5fCTr}-^7qXfupHFN%<=bz=M*VETn zM@^XDd>3ude#O?`#h(qp=D$>C{cql70Q`~8WuDKuJ=Gc}x|00T{xz%K1>{ei=6nzF z-~V7re@(Vcf%wL&T*f?MewDT_g6S?#xcYt)K1qI)SH{7w9bcLH+vo2#=$@~L|LO|! z`yqHAn6A>px=zCUPV>DjI$Orp-=Sd`ew10_#r=7HW2p1d_V*r(dM@^0o z<>9@0lJ%tidZbB%+5fy>!01nHZkdZTZr;ZsX8d}Z-`DC&aQE_R!avaaUnVw@C{z3z z&p#*@)ZehB?f0iCZDgLWQBpU6C9g^SjR6Is0RCib3K~Olnf-xM3oB6c+E4WVY5mo< za{=pdXNdkPU4OkvoeV2{uW?1oh53EIDFnusK4I=(Nncq9^BcZ$D{o2oCiS6Y# zq=-cw_fyjSt3j)aK=A-ue+P@oMP5UJ*&i@-<6xfJFhYN6ey41%5-q*P=2v<{EkvkK z#9OXPzJHQmgT1dsdMcBd{$XjNBKq$fo8NPZUqt76&0+ReHP#J4X$SLgb`SpZY5fhp z+kPI!sr~%{2EPeC6k+YF)kOb__6No-;izKvYn;?cn9uPixoQ)<^0 zP?|;zQ(qsAZ4!m2&tdw5*Hxw{Z*V>i_2xgH=CjmF3Zxz{Cj0^2|4&qzjhu!&z#+f+ zzn|9E$|VXAy?PDd4`_Z*H7rF2>TmEFcVT`<-`9lvjT@Q$t)yZ4@Ys7Bx5Sp`i}ttT zS^Z$fQ#QZbmJWmF!3T)`7Dvr@Ew*ujhX!Yf`2ddEA3(h(g0}Q^roMVU3WC3@o-*}y zbC0!fJ>VPHH&2+~HR&lZZ=4d--xhiA1^bVBc)FA@zyFV~^N#204gbI09#&InNK1Pv zxv$fp5=}{{wD-~;vdJhCrDR4%gAf&UZizINl2nvRn%X=4{2t%W@xJfx<6Pgr&*S#S z`*~jX>v~<+xzEVwSIN?SApT>{*JZXJrIn!<;O6teG{`~v{&;Pgwka3 z`h!;=Yl+n_TwgaWaTHuX+@t%(NuSU2o8hVfku!FQ^L9%8X`WxJjP*i8hbo$2CeLqH zGfnt+9QOwc{Mtjym|)c3s_Zd@X}S@p{_Y$;2%fe}Lj6Ja2BRUTM;7A``1!rRqan|4T2Ud%F2nh4R+R(0HxHr82c_?y?{9_7zDG7cwLqWW7~@s}nIYEHka<3c z^#>ZobUC6-|JQC5cFynGoQ=z`|jR4p=H~b)F51*-^>v$ zVRG?qamXjd{>ApcRFc|3?KRdv@cL`Ew;L=Q5`ord&eI2i=h7tc?+@wc^ZqtjPk`v% zS>ozn(sh1*pycv2XuiBq+~Xk6@8sW0V8hAB;__O>b(Y_tYc4RL`!_KoUY=i#PJwXq zY$F=cL-G&&e2ZR8EOeWrhw5*?n^(y3y7yNo`d=M?~muVSz<8> zy=@^jYoz%5l^FqVtX>Y&uUS*ul@dR^fB16z328ce7V2*sZB-XKd*k}sIO`o*^=cvW zenoyhYfyoquske^ZfPNXKJOol#{VH}Yt}RVfzKB-Z#xL)VfUzctn~Nu{0nS{%~9?nR&jA z&%YMBnSyh9mKas2;Fp~*_@+Mv0=^ZB&K45Cyg%@@Uj#<`%Eig8CBFFgzx6!q44X8+ zqyC`(@I5eIr7_Cq1^;NU&eNl9tL6EeYm`s?{Bb_l&OHb1G=|cr^QG^H*VmbEZj+hn zmS}$4#qc30HJV9XnEZ(K2R)M>6D8+asK1?8sw!O0bD^VWD)?gk?c|@YN!-pwX#Umw zhk>xaV>Fr{YT2j2%Iqx=8*OQYbS^;xFB!0V?~p%rM<@oC*rp3jcD3n3!6 zT+Gyv=kxO9ov?Q?&ga&(0kEfQW7^@9w4T>br#(?%eM^s?z9i45*~-hLmC0yy|35SF zES#9c@~On-vzNk(h{H%rMnC!dptNZjIC{^dkIf~%c>OFgdqfPfW}(j?ziX)~Xnl5} zPE7sJ^7-Y=D{}6`B4+>R{p&%ot8l1&G%b26-Cw+Zu6y^LY<%m4_Q&4snk|I=D4{_w zr1kv%zouFRMqb1Dv{q^cOV0YD`D?dst-(B<-QPtn->NF@422^j(euA+=Jf@&Kvq9_ zf7&451j5dqMfdlOD=cA1yQ`uJ^L`2T{D^)P^MMShK=pG-;dU68^<5luQsR&A-~Ku7 z4~v)J`Z@bpBv@&8pqC2e`FuY(kK|g6X7T}kf1d$a@NL6T`f-}{{qXwvbJ{JUYh{T( z|Mfk#6du&^Ii{UFpA%+1B&&wlqWk-#6)J*(p(|}!|9m=MUv*hp*FQ5@jOypr2VI1M zG0`;Up7i_kd)lp_kIy~`Tc#w zW*cGn=Mq}$BK`e5pN}GyVf_?WroYAW`NyUS98vKT_rH*SKL7mf(N((8Mk|EzpFE%E zALzsN%{ZSbrbe*iZZcCJ@%pK^as*WUJS#3NR(w9|KOJi)f~wn9v1_$-o##_!-aPOt z!S(Z3=@#&WAL79S^7`4Ki66YnXiP2NNZ0xOeP;O)h}enqd9Rj|Za+se^Dn%9&iau7 z2G54l)KSv+!}ICxc!PK>w?gN$93S6<86RiTg0Is0|FysGEhVPMY|;IFaFLR*Y?CW( zSnm&bKFg9{kU@8G{fzqCNtk^D-{0?l{!EVa-H4vQlQnFn&}q_r8tAF`{n`5HV6_sw z+k@+8Xk=s9FwGC$-&Or|;KW3hPriQN|DYrI#Yc*%Hza=e^QFSgdP8{E<7j?rHP;xN zt?`GIni0fyY0lu*G zS!25Mxjdh{Gr}QfR|nc7Sbl%snj;eHo@3Dc-99rN0{#r8w>wDR56|bw#A{^ea4Tki z=j(S(*SoO8$cDD5me%up2F$rn`fJZd^)p0CNiYp}r4b|L^|O5ObFyOG64Za@zSb9- zzl)}u3Z>8I_4Db%Ph{2FjZFT;*GGqRtc54^K3y3ut>^V~K`SMgb{f~u!fTD-qZiI+ zP=+=f4h&)PC0;+DRCR#VN}SJC-FiXf_~Xp^n7n@Kj2#ZA_TzkRnlc_v-n}aRu0Nld z=QGyK0me0dBEG#V&*#eVn_%0#pJ@NzU}fF&SB6c{`l#Z=VVGalf$nAApTXu!Jr-Of zr^y&JUowhLgI_QVGOF$lka^Xhf_DA`}?xA=|aVi`*elBw4Ucv z%cqt&-g8Cs(S7mHh5cie`;#Q!;8tiPbk7%02f4Z-(>ADTbWJT16)4%gSA^E!Y| zKot7?YVSTh;ZNvsbpK!3V;F2GWBHBZ^tE`HITV>(6PwiQH_vb0FnbuD_yqN*+AB7I zm+en<|9AHFfeRK*P<k!<1-+{Ickk{93?Jf}Gsbj>hcjW!)k6*c9cbrcL@7a*z`9##nme<$m8cuLD1?RKpNpHBexCw1mB)|W!Yjg;{ zjqXV8IcE8*U77L+huQu1`qc_qe`xSlB^GeH4S{_f1c|Bb`5OWZu8d z@Bf#!O%)#HmeQ5S6~900PlM0>CR0bbq4iV7h6d2Omp?k6a=x)9EY}TX>U-XwzHZ+h z`ng1jJ8~ue$otdZw%uVs?-NWu>ca8qUp*KW4?NF2-@^0Rdh9rG)xVDBPvr+~VQ|l< z;_Y|xd~V#l4hBB@Db~11{PFqIu`gZ_64!*Dcr0D#>!(`HFwkGv5%s6GgR@D9!B}R# zim#sncBO#h$6?HT6|bLeJMzh;hgRa}YK8u?{n6wtx8T$8S=8dT;`?Ry|0$F2kWqc@ znEjvUbAHcXFvSkn&#oWqp8uM)6xGiM?ezq=)EKIHQu=&;|4+<#OX5>Eq5FSCiz&kB zl2Y2$S6a{S|IR0VkseWQ;xQG89{_b`e{UVB0ojxM(fTQ@ZA&=NCsa()mA-#oKRtrm zL3EpFbpAwF-w+;mIwAVzNuSUA(*d^zLH@$?sD2tP91Ay(Ul$kkmp-50-`6di1x-Dl zqV?0>K5Ic~@-MMTpu``~=R+eeIC&4})2Z`8=;7ayYB1*~vi?-7=XvrfW-MCYSL&at zJHK%lO|6#ZS9m^KkH1VhjGHVf|CHzR>y;ZYXz(l=bV%|2vV59$x=jkt*fII2$mwTF z^bhD7?uO>~2HPK#JE=IIYR2t_mpZZ3^}6)=JfC9jYZ4H*3DwVaK32lKzoj%|wX~k+ zvw6%9VjYg_r+KJ4Z%n1dsPk=&D@lIZDJ{X zzW^+sv-FCH(+qoN{-4*+OFzEBu54C60oeZ1yta?XN%du@etxoVCm5}Yr4OG=pU?9- z`syoU>#-TF@5LXJgcHgS=wFc5^L!52{+;+LyEFP3#p&nKmufI01J}<{Q<{Tqawz(I zV1r3*V9=;&G=FL}#sJz^v->-*pP@kmAfguMGy0wYhQn@%4&CMT)2Z(K=DsSG;_%0c z>ummXY4|EwYxoj-@q6rO)U2T>tJR30b!p?a$BOY$53AJfJJ|r1dh=ly4)No)8yI~tvD8l>G7I{i6;=1&_g z^@rP`+01+%U%!8F15jOfL$s{-7ySNS*?9)kPQ&?}v3Uh(4gW1VZk71s_xI#o?r`0r zDLryty3Xt8SG^Fp)JmVGES2XoIV+PiTR#rn-+fb);g!d5I`D!#pM6D2?2V_O^LbN+ zLQtMKi#};5eZM@Pl~vct1;fuUH38@Iz?27MvHvnOe{!#FE%daFrRJNZ z&*%AEezc0TuGoy$?>E{{5K=mq(oVCbzn|yx-{>!-h2Sp!d#Ug@tpDt+s|rsl{Kcu) zrTdTXFAa%m3L85gKsC+^i1RtVT^BGNdJ^Sx%i?};)+HOQk6Jkph)BTs{E;yY zb~sgv)AQu@bA!rq@Z9-Zyt7W?kLPo9o*VSv-IR_hl&t0cicS|7jDLu;u`h@ALW^=A#QsD)Iea zb7W^2hd4>0Vl8&$g?t>^cD%j+d%t*{*Rrv-KI zkNdmgD4IWMlUibbF?ERkSwesO-rY&u?N#c*^_d=&a z5}@sX`h!`U-a|lhcN%tDv7Xi6z76gXgC5J7^Hurzy&ea2h54(F(t~%T^}PPhpHxXE zUcmW{88lX~PrOg{eWm-~1z3K~F4YjP%eX)I)7(NR8dyO$f0gIAZJrVY?+!rcQ(XQu zg4V|mp!L^`*V>>F8iUUFB@EMtX)32s{S8(#0zoGS<@a-A6YxmADXyx2{*d>#flsZ# zY4I~L>bkst7%wh@vfY1Be_Lr+*Dq<^4D}CJCkMg2v-)(nsr3Kn=l8XHrjd}HW~jft zM~;E5g)vnLljpZgKZoq|#`#?wp9jAl+tTrKC4P8*w^tXCX4@Q?^RIb-t33T3sBU(r z&Nb3{zCY#qrkIpoS&sVKEKeQbuisHRAxE*EeSYe%%2V=w!d7&?Z*q?@LgLU;IyO!E z|MC1TR(?++?z^M;fA#VSLT|$gI`FtWzoWI3AmJISzr6pw`==qewn=`EorU4hdDoh=Qq)$AsA^MWb~Kk_rzaKnDHeB&1WsG zZVS_*mgQdPe}Vk>eomnclg|t@>;Q#JPcicYBG>=AUibc}zTa|~=UaJyywJ`VG+x|9 z{qd1_3s^Dbnb>%lJl`&-=7WpIU-8U*dA`TiJwKo~w;Ae>53Jh@TlG58?!zU0;q`f} za|&s@!wj7ts8WxEvXDA|Tz`Hx?=LKS|o)*7j5aHZxSEC`QviW%f!9Q z9F%W*;Waq?bEgFc@_diCxJ{PM#rZzjUrTtgatCQW-~TE(ZYG$luAl?f%j>h+k3S^NbPwZ?dA_T*H-N(q z2buhg=ezb^OHi$hLHoDm$8QOC0n2hvKF^WmyOEY2tnfI+yuXsy@BZ(4K*G-)G{2bR zG#nbNxrO%6s`pQXH+P8y1=9D+^SyuFS+Z-yG*rL;H4&loj4d6Jr&!PSC$5)VB8yb# zh$(6kAH0664}Jyi{XA%B4|%@z|K1`i3Rj@@-)cQg!O`_79Xmjt?|b7Ok(Fn*iX;0; zpRXjSG5QvL7X*t#Wwi8|^!xLC>t23Ea$G%_`j6*3^2JzT`Ope#(?Fi@K=a?kYcHo+3lg3ZSgU-2UqQMkNzj?kBljg$Qy?@0+)8+O1(2K3`JgynFkCLwQ z`P@v;09e1K6aCyxUcaLzpCr|T&Cz`BOKc2yl^fH~)1~j1=lk{eEb{0OtKaJ-=o@9lQB^qOn%Jsof$JmI2l|)54V!% z+b{Gd(TTwMPWD!Z%CLiIzOkjMIZT`!i|ThwOgFx9 z{}DIB9BNNK6Yc7sUyS1P`O4@ybz5UC>OYFc)IHzus2MdnCeLr&W`A(=?nF;A=O3~8 z#!CMaWM!E-+CN@V77Y>eM^NqE()Y*n+xq<(qL(lY?SDk=&4G^-XVa_o?`P%xhf^#i zzy9F-YBZ<Tj`YH@JD=0$Lw_+BO(o-NW_Q%+d@*yXWHiS(5&? z6j*<8;HW)((5)4n$4Y$i_2HcTo1odRX4F4Sy3Xrwbh00`xsU6w<-=s+8DTD#RVw;V z%)ei$g-;Z`-86y@S|-nL$*K(UE_)g}KQ{G9HU#O~(W$MZ@1N(l?$xOzaN=ClKgZiY zhnZ0fYhkpI-=$Bv8dOqLKdv$?K3qyrUA1MR?H4`tyZ&e&gF;B{NcReya~R6QWAu zXl96X|M2;;+l&&jTWLGvA9(%!IAD~Z8uXY3U6$7K{JOSzMoNErp!vqTPeh2g`h-52 zE6;D(lrKcN#a?uNqPR*0{3eAl{b?8O`SA}rO(D1GQB;2o#8zPDhx0qkxGSU>US#GY zd47B84g}`_oL|!iW8k9Q3vu^8d469++rqx`TGaoZ?Cu2J9Gj#5*ZkOSI6t^Ez1>!x z-|J3^^!ePRX%TSt(g+%BCGp4mhu^Mg#F9>Do-gC)%iEQog(|_09;lGk^Zb&W z9MY~B=lAyYC$Rf~2OWA&;)myVcEJ_$qI4zNAK8)9RH#vpNBM0%@E$qtydBlwPSZ?; z3x?&i>o4i^d4Bs`drJ29@nrI4UVlGLC4x)JQ#zhygZD_ z=XicUO=$wJY>uMm$B+VDusxL`2A-1Y13sTetG@9(sra^=wD7(HI@7~ z&u?4(CuHYDPgH+bwl)`Z84 z`A@7dQTPM)e8lP#YoNDZbGm)Abe;FVQ_{WR`?Ah-`B%ktwtmywcZ?KQjz{~`otuV( zt=34YJy@RK8(AsD{NZ$TKHX$NCj2P1qi5>p+j)NTV$P8}IdjFgFC_mha`Qpg`#gs2 z!5;MZdJsRLlC4ll0IuL@yYvx&gV~&<9;(xe{irm1J^ zdY(@@uoJaactzzE4%;#f0;~ELww#UC_uCwr z^^V-|!S&U$sFpNsdx+te&lk)|Lzr+C=lAO^EeHupW#%vW{#=_|9ig3$i2B<$MtxwJ z6VC6508@zAQpNaNp5N|n(_z!?f8yOf5}$m&P(5=ce0_`a+x3zsJh{@D+SW+x`TpGI z2S>@XA2`2RAz?6T)JXcdR`M4-zeycWl8$CG(E6;}Cmn{hv8V0N%k!((GK1iO5uKjzBwS(EdIXs6+PnkxMzQ-&X6>MxP2zsk%T!2Y*K(fqbYz9x8PrZW9C zp3n6u9bky5$mCzVe~mBd4Mm%7qx*k|-6$x2P$hPbmDkt#M$@2s2PKN_|C36V!_#gp z=vzMpf2_W$zxRNO=3P+#`sr*e2_G~8)z?O$2jQLDNE+No;)~}qxZerlRXhXrult6i z!R8V6^l|-s8?Ub&O)|*~BS$p<`sefjUWI#7%g+kF*!|z;1tqu4R-^S-ZCL}s_j5dT z_EM~8_4QJVo22!Koy>eNudmzHhYCGTRnUj6<@I&?)H3qYzzglKb?;&(yxsnpzUm^+ zZ@;gvNOQVZTph32pEa2L=V!m)WR%SzwEpVgqyZC+$`^Ro6 zEg|)0DwB`#d`AZ9!LubI<8S%*FX)B!f>m+1(eo8n{TvCe|Ka+Z7d8df7%5RRLy2Er ze`ESDg9+nXP(4q@b(U|_rXFx|To=?o3_BG=G<_zZ^;wSl0VqrzNyn&3d@FJ1C!T+m zOwN6qf%Ye?s#76nfj#YaSh1e%uhss{AiY-OeBaEv53i4SGV|}e{$3w0lCk=$Mf=~9 z|KRa%xz3%LI|70nm! zk7*CxY((+OI_du6`P~=T6I7euLC*(s-8BMq8@^=nT^BB2=&L;$ZjM%>y_oZB+4?Ni zc?o=--vX`AG_>4d+MF(EeO7H9O*Bv8`h2i$D6EJbNxR;X_YaG5lE~4u*64iCwpA%m z;crhr`pEM;&^VohTR5Wm!iT;kP*CAXwVx~aWA%Bg;YBjw%W5=V_%l>PxK?nC=9Mef zv--Tb*)_8H91UA%;q-n3@`Tn&jk-XezjrxyYy-z{kJbOCd zL!R$_ozuuc>WI$AS6AGHz6M^@OGVO0UY}PK<&g2i*Pwi7e^L`R1stQkyXE;-y;(>e z%&2>RSpE5oygv6De~&y}o_#ueYCh4ln=)F99q)`PUMK9dj0zm`S*+cQtu8UcHI%%S4h7f zKcAB&4uiD)xc*v-7O;Gw6213I;h$Ok)qJ@C)`qvBCie1tuF!CW?89BC&V9vomd}Ab zBgvhS6H)(=@;(@rd>=^%UzGUd{X=B?1k&b^HJXoEJU;DW z_3z)|=g(r=6hoq(7cILh@x|x6%60j0!e`t+B-*P9iG35$=i}#GEg&}@?nLw5RgLbF zqZwZ4{LN&;(ZZ*cZ*Jc}99}4HR3ZN#8%ur(5M`vhd>}rvJ+{kBvXK4?6WWq0i6C^EvfU zJQo?u6D#EFcxPBJd=M&Wh&glH_kDUI(r-VxSsI}t#sqFJbH=?PxU`xSV7ZL`iq zs7?Gx9d}dN{=>=8rz9;N=l4R*M`F_DFv{=h7-d*M;!%Il*R=`czdX&%-|+RBRZ1)H zBb4#CJiqD*2GFx-F`Dn*X)*-<^{Hm^-6+oAo?A5@5 z&-c$-i=*B^!EWfkTDoF1P z+#mE9`+;m-d6>x`c>OI&QG%<^@u)wjE=?5gt5F?9Th>+^|BU8p`y znf`^yo$olIZ&y(2Sd8WmE%pzBw==3yeRiokA2Om`i7xmk>9ff3?NE3A?s$WiwCMtQ zzC8!;fZ%Rjsp@U%I-mbO@jFbW-kyl&Yx!paVPmQZQ@`>4;qcs}+K4%y6{9F{*zZf{MuMphj84cEz=X<>NEpk`MoAJMV{xJT^Fkwqf4V}5`qAcHo z`jr!}GL~-uHeZ|9I7JYA7v(-XD$Pe^39Xp??Y_l(a?tLu_`ZIAoX?N1bo@s=rpJp~ z_3wY?&)@qSo+7N8usBy~lsx~NCNzTSDrsnaw>|WjaKU4Cu5)Bx_@C#St_W?J->)i7 z2VOmA?+-qIHq`C{E;I1^BY)gLuym?s<}Z2wqEavpls+m^^GfOdh~n;#$|epFrq`18 z9--i$&F6lEY=f*hUD5jQ(#}JqMOO>dUu&P+3(3Dts7{5X|9t*DPc4?bn>7>lFJ;jQ z(D1wiwXu`GKgjvxp3OJ9yXKOzi@VVJFScVJ!8iIDU1K7De@u$MK~e{KGxICST7P^aat90e>kMrl=lD#pwzv;QgSg`KYn}HAAZJGqtADUE60L7%JS_^og#TCeQce;xe+>1m}Bdz;R)0 z(?z*H_oe4odHuij;WhDmkNY3pmA^@4c|1Cwkv*dURK=z-{S_DP`O|RSqr#n=wz)Zp zeg4z;B2M4i+i8KVS+3Y}uXO+L{5u`ihlP)e(f*?U=6+E88t30ky>9+Z@54f8qqUT>U>~xWcnl5O6@#3%ULPE!I3()?1-?IhaTJ1#*_e*^8`@_x^r-@CYb?E(Z+4>ha zv`IwYPqZ{LhdkAFLF?bU=M4o)p3)We(&zK{hjr2wve=KkKluE{lnfIJ_k5>&zsmP_ zZZEt~#yaEoM?s&Lq@;T|n%~SE^_{d)J|;enlI{=Q-~6;u2X%vVhHpN99Nj-gC~j|; zYcyT*_q_gxc4!GJQgOaD^*g|VF?Z4W_uFG5c<=K{yf9DVoA>uww+UnfvHpkWySl?n zSRak+|E`SnaO`7OT696;pXd9IYY6Fe59izVhc9?;9z|zFO8$qhe<$BRLY@w=5g%NU z*Z&XSVnDC&918XGDg1m%S2#xgsV_wPJ7&G|;jOMW%{wgd#q)j0IF(pLu0#7fL(_i1 z4WC4G{^{=MY!YD2>c0zD|JD?A6I!cRqUXoI=u$wITx9(Z&v%o1Lj=p0-_ib0@4NTN zqDw(&zTVXI1sORmTzv3X;+M~NY71h7_U|2X|G(t_PyIPhXwB&VgPC8+WYc44{kvtP z8ay*kNAt_4ubTsTkSkhxN}tc?J1@?+ht1ROil0)Y>wJGmXKim-d;S$#zg~4Pg)e!^ zbeEFEC(rk|bu(bg?UwX>H|aXxzZ`gTE$DSOK=pgu+Wkbg!6a0_$Nt(4Z{t|LdHpVY z98S!_asB>#JsP|g;(X6;9#8I%V)^F%&Ej);(07nG{dz#2Z@(L-$oklIsJ}0G_zjBV z6VdaL^tI2EqCnQ)^L$tObralupV0|UQva0KZ}V%HN#=XDe&zX&Z8KCTpYV$=Jex0{ z@3go}wqys1MgbBZeE+DKS6zR}Aso$b`mOv-W=uSW)~DL%B86+dcDefl<^4-VPgO7< zpN{sILS8h3?+q_8eDnU@E+$%d*Kv17|5p;)G56Qzi|yd?XUzy2oc>asNPlL^W*!q^w@1GX0hPRy!=(Z@u{lWG}?MDQY5d`NyCd~() z9vwvunDfWk=U+bA9VUOgY*2r{(Ju-jvgXkDt>pd7>a?RIeh1F~=YE%!=F>7kMjIKcyx(ef9TE3 zr||r5nlVy1@-W}4Do~Z1&dg`? z{^deJQ?RqVgx04YcOMaS17_!Xe|7zj@BSR$54_sK&_8$4`c>%HM}-Y7a`xxBwg9dU?M>CQs^`-jgF&^dh$efCbVo}Dku7!ykl zT)_EnK7>MNTW|Veoy0$%@5jD9PG*>|NBghB(@y~1lF;`z&5y_={?WL9H^}HJcsRU3 z^ULd#bIBlmAEv(L`QLKRSa{K1CD*3AJpW-r5&8BkNF2XJUjOYPD#+jXaHf9c^LyRw z8ZzkPF*Ls!-B=lhUQ1{48=n7XtD4lkAM6s-e|6#dQ|Hy&fNd@AU$*z_4j)ZkGxaC$ z&(-%E!#5=r+Phf6H`{-mIdd{}Cz?z?!|QjmqUGS`jO+KsPl3ej*(5Z7Z)@oVZY87W zml+a&yni{}JB*xgn}yEDo{c;LU2e{yaSx^SygwiGDw?c)ypYK!dH-V6>mnR&?@cdi z$@BYpOfuQpYCSq1JALR!xUww?&ELC@K0^i-;reYesf!T2>;+ZsET6wSTouVxf#uf) z*z-GdpNtR!wAFG=Ti%w{@61Ox$+bcIQ2$b;QBH#2;QFmo@Qye%OF-viYc=covkfvB z|IPDjwW2W`OJMy8&+n%&353Xi9&p#ItEhy}bf)1-%3{+9`fHS*KxV5rq5k3Xl6Q6Imn6~ojU@le&%b z>fVow%)hDycN9)ddrtQak=FC|4SjVZ#bdy8EKUKhN)rW(#0W<8E|F{rl7Sd^$_ppV-Z}MEjF9k6dBbQd6osM4sQn zWIyqCutoiE%D98@aLinKReWN;#gpYPY`!C9V zufTt3GPO{Z=l73)3R$z-m6^}t{lT9L=g7mCKFoXx&##?(kZ^Ohb?)B*Jw$0fiG4qG zWs581YtlaPm6Npp^7)+p>Js8P=!iJ;jN&@mUrb4UL2k@V5KVU}uCwpoJ?QbBOxuX_ zdt5~WM(xZ)^9ctHEqLCp1nmz7x^{vsGjTp+$Ux9J!TML8&#%E|uzJ5Hwau63Q+Kc< zENk11s%(<)gPh^88-;dzok?>=QMt6#TLCgBS1JB{}g&n0%SxMkv-Dk{&BP+Y1^;v4*Zc=p<*WXrmok2g+ln&8V=qH;WXU_{F z`nzn=`M=|fL*TFbT>50YVm<4B@4g5lLrfQ={$cE<3^5VNV<O)MeUISL%R1L0t^0raTO_dh zyK`&Z`#FE$`dfVK4ry@uh}gPJ;+xOMEXY&h=$s%fpC(=B``ag!J`G43v#T35aFf^HH7PzM&BqEofBabB4w!U{<&*cfZ`K5o)1zkN&)@zGh94nwsrDjy zJ~KBSB=7APqw`Dc-lxH=8eD(VcSMtXr46V*i1&B~?Vlyn?9TFhCSOh_doR19^Gkn* zv=)lDKBu)&QhmtlZ^GgXa<|EDMt^yJt6BsIeGRO0f4a-_o89&jaaU= zd+3q=M(oM-*V*&EMqBoQ#qU(;=X3?%Y`$ynDZtY~T69E>be;FN3kKQ2wnMmocqDj} z1}m-5`O~e#x523zQyS7(;*aNdnbuy?!*(|MeC_toeQ@o}T)N0cTF?92n7Ic?fZ7st zzG(3B(~xT5LuWLQ_~HG77eo=upbhB!#g*qz!FBF&n&2qUuhGaP(y)r^ZYH6RilGZ{~Foy7I9RLVDyvU|JS8HCZBrY{LRRHPqO;s{4KRo26dauXg<)j zrYY3u-bd$uk_+2`(}=fdzNPWFH&hy^(j(U-zIgq7SVdsU8Z9&*_&d%Pg06L=+B@X+ zGp@ZCad5Um^R1NzTcBlQLcjh~tY`Q42FC)3vEFQSf8Vtx2v*n3rC;pi`MY>Lgsk7R z81=6?=To3pOCMTxPkw*jUKK$;C2c_St(~o&z+g|DziZ_QWSxo|s-H1SPZRsuEPpOs z|Dd#Bx6s6JMsAPQhX3vFPq_Vk|JsWrWqoXBx=7EAAOPh2cK`{ z&Fuxny;K?fjN?fZ>z*N{-_`tuce{q%M5C-;`kM*F+tI|V|+rt_$ol{~+2a6hrF#rOZcT~0x# zPChg$U!LEPO-D#n!3MPcs&FcYsV|SyDSPGh(`oQAGVmLoZyhq%7BoITr(Jy|{pR=o z2A@)hy$|bOdA>ii-z@}pwa#7BT-yIjIli4$E|90Eg381`tOLiD?;MKg*)GC zRJ$^g?U{(qXSQnehBP_F@-1@n`L7z)60;3B->%+`L7a6T%@0C4v;pVMZyEo}^E>id z512Plm5z^)_~iBXK(Gm|I`&|u@dlGjr-TODvx0KdfL72m^eyT?KO1z1ZZlZ^c>TO{egv$}!uk6+VLAk=8q(bs5 zzs37ck3}cQy`bG2ao0)=bXNTT z+5P>h`WjGmA#~$Cc|NC$KIFB&9XcN{tGhph1<#`gKwcl!>;lQK$xBdw`lDYGT(&;(^Z6n@ zi=6%)Ec&@feDV4IYRD%=_ac~ll-I{`eeROyfARhK@#^P9TP>5R&-wlN?B8!>PUU5B z^c?B)d3_8&rvbK=xW5ektqpDU-!c0$pD&$nV*tKeRB42_JbykrhruWnZL~h$?lKvg z5<|L#Nc`~n7`M)a%qW|T=1Y?;&()B-m{K4tt0{u*)+RGcCc+3E#gn<93ps%O<1!r#`z1Bra5i-wjry+meAZtcP4_2r_Af=} z`&xZF3I;QM=yE}x&pt2qllvVuq4oLLTX!IK#7VmBp}c-J`FVu+?R8_$XA`;psA-2| zB%y;ZGk?PS%a1NQg^TV}bDvI==QDLt8rd>-KRVyn(OD$DTStmUHzj^}KBxA&Nt6~Q zq51ouM&+c!71z(8t2M;6Z@xHenBwQN?=Lv}MFny;{U7?7+5(n(vV4l1ztq~S59ZfY zX-gM*KCez02oZB}K40yh0D})1(n0m-$Mby7eY}MfT*mctmfm96*#S`fbartkXMCUm9n)3T69eK@3PI=WZ~FIW`B3#_-ypPkZ8o={UBCnrWL4Dzcr#3ntl0AGJ zY)UeuNq?mEJf9}!8_2kQQ_%dfPu=^+ci8|9$&mQs>m%h<7m}E3ht59@yYCJQyE@Y1 z`uvIKQ+byU+0$wn>OZY&Bf;vh58dBOp3k6lfuu44*UzvnH^9;G6g@XodcK684~aV( zM$G!Tqy3}1`Z1){Dqki)0ud|$pk8nAwY@cGP?+}Hb}$^Xm;CUEC}On1IdcGcqhzxB0h(k_qn zr!L&{Rmp$;lEsfo#Rs91Kj8cCADo-O+aWB!yg%)i*AA{2s4@FLudioX^nvtC`2OE_ z_ZaB?h1FLVPG8f`t|PaWO+oWd2m86;upiL+K3-=RIrxs{m#?3O?Qw(XPL6a_eLleR z`{b(^F+95z&6m`|BH&hz4;@f{eiWa--!|M!v>xF6ULA7{F2N}p+h3kv8|{N+L`QeD ze)@PLic}u;W#&V8f2x0Ez3{xx)ZAQGd44Yk94CYGaek-ho+X*Vk!b$8uwg#=l!Nmd zw(B0*t(}GDpKF7w$cyXw;>JD_e>|Ulalc9IcU)f|^=S+$X79x@&!zP|p9A-_g(nNu zXi1!;k9__avaUDuy^YuRLmQ5U>WST%`ibZBbi`_s-=|JrS4sJy3$XcT@jZLUO2qZ` z=9C@eP$zpvUq!CI->C0e_x?IZS|v*Q%=6j*lqU%qy$s#||J)3R${RlPM;Cd0%}5L& zTl;QC>!<6LS77kyQ*@A)JfFvQhLR@}-O>J#@xKUi>?=fBSz+ zPG3hCC6NO45Y)eV8)TBj1+2dE_0#uLmq@p>N#bC0i4R_1y|3IMY0opoWHaeHU*AtM ze@^sz6o@$!71!DN$td#&@%vLMo?S0p=k>GlVnYxQv--*J|6jz`P*caJA|K`TvyVql zXz?81|LrCNl;n43=JWae|KjzPJG^Go5qmI*dambp2zd>ZNBCLv?8#Hh8>b)HYl(UoL`Ljm*t z3O;|*JoAl2&wqgK@AJnrfap2z#r$)MpU>u_Zj)NU%hjwu<@pS~+Z}d2)uyjfC4J@l z>!OhU%!FAL1AWE3f!a%_=Eh<@fg?MZV-w2(F)t`d@~oWv8glWO+W*7Y7p` zCwzaOlzo^8m8?JI_xJcQiv?X<%iJ-YBtCUG{Zy(uzp2(R1kIlg=d2QHRA=OdgvS0? z|Ce(0|6Z*$()@I!nCK<(!RzaMZIPUqn2hG9b8>Ey4Rf-@u8XDhJiq?}D#*k-eiiu? z&+m#~pUKx?oL}4P>hLG_y{L6b@$*@J%XaC&=sJEU&X)M(`TbM(egd1{+O%!5be-on z`Ta<^aIia?Pc_t8N{ol%{OTyp1mQK%MS&8(O5F1$uHhSr%`yjOK9twj!in2pZ?q%* zRj<#yzIKduCHK!PL;Fv+FCKut*L|o-{rio0esAmVCI%xmi=Q4#{)O*Ha2`{ni3s{Kl#^8Sq6#chxN$8QnGug&sQGNmSxnQ!9x&7OUM*n}mc`PHl=*U9J& zSz?@>^!Yr$Nz)&bCY~(6B3EDi@%u<-UBvm_x=Ri2SH2hLTvPmfmf!7vwBWak8qJ<2 z@yYYM&B*{Z5*;)j7~Wz8^gM_2>mIm>+}t%4oo_zjI~_^Cc@{ zD4fhlp=lT8`F%GtkPJSH``6?(2T8u3ADRz*A23f?95yMp;RK1_Hk|%e<;9W}8$!_j zl!N&xGV3d@uli5VlkOXn(R{!<;3{eMfUU1YZvO6DWEpAfQ6Sc|mA)TdU;k`>Pf}tZ zh^fn@>%4zm-#``GcdrqXilys(eRX-bCRll^QB4zx&nRwww86?QkZP=h>g)U8!=Tg4 z?sVKB1s`m_+H=POGJ#G-^DEU2Q{iVnMZSO9j6NS-=x`ANol@vwCwV@T zO7@VH^#8-Zz78c~cRwco=ku%GnsbEnxs!5rC&}}9SS^NpSrCFgpEv#73DU5C6r-QK ze~le?j2gbkhd|KPAhi&cW(}xG7^*o=WTW=?JO+$j%JVt!tq0lKXbYPEZylEd=?8E=?aTs5(k-0NpJPG@jK%qU`Q1)9 zGtx4*+irSd0p3l(>l%Pv+jrjecw4Ud)*0?$RK8^F)ukQKM z4U=?equmm}yg&Wec`!U{*@J3!R`9{{`NV7vF@1vjQ=7w+Kzo2dzgbJ`c|IFoSx$;h zIxx?V@O)m4Tmy@Q`P3p*j!FLPEIL_|xJfDwm2ZBpoe!A9Lo=@W_cXA+b3z|>; zOFR#m15)YRoAUZunde82{b2nm-`{WK986rs_@VxE#Ee;j@90Unxd|Qq^QZj&u5%!Q zG`@h>S0fX*2$u_&=W4D`|IeTD=i@hTpG5qRM4|a=x$+s}ScdQaDvk0;ueN8I`ikeb zpxs@vYTOkxzY2X>Mb4?0iBUEZpFF?oPW&a-UNvYw;2O~sy5y_TuSOD|yuQW_>j1;n z>(B>#rRzMuFYxh~VZt_ndaae#^Zbs4Wn{^L zIjBE9-eMJu88M&MY?jvZ{C3FMNcy`i7vH}4e|)`nTu=Z1|DR}>p+&N3$=0Ih`kO4-?=$o@S)mv<-U@x46nzrWArJgaBd zb9>zGxBLC^IREMwY5(7)XFT1xJ%*oPsGQ#+7OUXS>Luv<-&VJfYH!Zt52!Y+=Zo!M zeRPP0kzZD$^C@wfn?Qfk{|~=~p7N4f7vaokkzYf`pH`gM0h8jBxNaum|DUa|rn+W> z&yG~dd_KGWZ~R&S#-|T(e~0|LUwXbox9>dM>Tr@X87*EJZ@O9Ib^QqmpAAQo* zMABbXVfs@Q?&Cp4Zw%U>YG&+24~63T+V_$_wCyqlUH^|k09`TPhhHJtA1Ixla_zbR zJTzuY>L*rT6K8FpP6aXix^~L>+`lCPVp8z+-|yCOIwdcU-~3CtzFrKBfe+7CbH?Aq z=cAIDpHdCk2xl^-^%GnFr<9D5`(1Pqv|1|Xv!+Q3Y<-BY|BIdWf?6@o=OnXy*f97Y znor$NIs@?oPonw%O>oQC;scKv@C z-jsfS-GndgDDubhIViL}{i@*ego}8c)z4vr`%tYpCX)FSmQVOJ7Q7~mLG#s`{X^-} zU`2gzDe51qpXrl*;pVC-lKH;YO#KuTJ%g4f;ri+KJP-`d2T1y-ET0w+*HNxKhCgqt zoX?Xs;h=X7=X1izqg3rd9>4pqaz3q1qG8_9HE93z-03)o%#-?4me1%VqvU^^j1WpY zD(BNbAQ?)!Z;{mZlzBf|dC$@Ew44#b;x9Yu*Z)c;pL(r$KV3jM&TqFqxzJ(uLA1Vl zFz7VwG&{)+G#2?|^|f31H5k1d*H`#MP~n>^&Iv!G?YgZ^*+pfz)Ta6okp z#2&@aDGY`h%El`t<2U9e!~?<$Uk@(Tm27G~pM$5wEj+zm4>OHI8G@{#I*O zdul0@^I1Q|`&quL-+4om4O1lhPgsB3Sks^W+2Okl5EoeM-hThf1J`S$A- zOKXnC@D*>w``P^U&HYf2^<9egx8{`e?ZSBk4`Sg<3n?m>+jkQYan-#RDV+$ ze=ut1I*7O=<&({?yj5M~!Er8vU5sJ9KkmZ#SAzpdFtzO#?%W_z|5*R(IMYSGyT(O0 zWG3ow6{Ej?fvKSPIF&12Cf?8H2iG+YLPYpMG=FVjeiCjTkn+pwug&aBu&VYFx<4R! zpG-AHLf(kv~>n zGyG=4!P~PX^MkCu@&?h=vi(}r-)`6z0!yuzqWyv4qYl&kFZ0m;Kx*nLFpIQK*b4~AdfV6)==8C%f&bx-*&sI*9v)L$&0{Xgu3!9fSn z`4+uq$06%9?r+2Xo`;0DxIb7>b|2JRJVN<&D18Ur##Kx5SB}{qaCTB-s^hAL`rB9A z+bZTiboeRH6c_Sl{FLwR+cN+(5 z6#n+#`F^aw{hBn1hE)0R=Oz1Rr1h8Y7=QTj9IwBsj3a4PT@1glLj3vc`X9L{7}n0h z`E)yekZ#(ahxT7vKUDP3)~!MF0nH!LP*|~!o7r2e&scw3FvUT>`tNWdu!G2_3BzYQ zt4;7`2F_>iojbtAAPv<|yR%tfz6s}Z+>s+-{S@c3bHG`6-}o}R{zrDW2R*HDK8ruS z2D-PJGnbq%Ak7Czb|boJsv7U2C-TLv|0m;G(`f~`ey(WLgO(n_^)n^P8H`@w{xn&4 zFtxZK=e;E7t4Q|;^quJm4{WAz>t>4ozb;JuHMe3s^{DjWXPSw8vHF?z!Uz5iorCtT zRz$9*PikWLn+@;RWBHtG5Cp5#m!bLVouB(@PK$irf4}ne|8naUu(@Q7WIm8x|H~qy z;IGblG=KF8vy)duIt#)Kkxy1X>$Yr!WIk0s-=ZUI2Pfk+?#?`M z{blvFqt;%ic#Hejj+^qq_RC30e~VrJkJ#|=$l@}ZZ;c7N4cdJlaT|wo7Gp@qpo!AIukxSO}x(P>(r@E@Dtq8{9yE3 zD?0QQ&hO44?qF0fh0EV2^2_RLn4=e!fAisoOZpd5ebq7c2GcQf(DlF9<(2f#-55S9 zUgV$Ux8tQbit|I3qW;xY$fld#=J9z;mGfKhI~4BT!`J^Gs*$j0$a>DtQ~di_eVyBe z%2UIgg(Hs2`SrdQ2anfpLFZfg=DNr$ipL5czbWT;Qs-pw2uwrg3mw{Kg5M9^zslTm zA^XKi?wFy-AIq=Nk7DRIPRcLa|N1)UCd^-j>#zNS=g{UM&hNO^zaeG18Xs9L{(Q>J z4;&xTk}iCS>u=}povBMU&Tr)Lp`bDo=Xa351@)_u^V467{ImYx&Ad_IRW9Y1%?E-O zdQc-XU%s@b$RDe}J#c^7X6sRZaQ=X;{B6;2!7$07-oLW`Aft9Y z7@olWfyS>b&_4+G2O$Y*V8tKgl6s2&e|G+rw9kR|#)VvNfAKn-57Z5Jl#kZ)6#6@L zug|BdnD;*iJD!5Qqb_r^)W!SR{=$9F5}35%5!%1KPoKc_(rQV5%lg|hx4*-Tcr`xl zulV__e>l3dIj!ufi{=M8S3A;#6DE9AlE@#czct&z%}9{(Y?e_Fp(yz9MP3U^z`Wzi;!` zL9OOibbkR!NP^)<($M*rMMkMGzULus*W`cye`)_~>bRlu_Y*yZS^4Skzx*_n*}pZl z*FpHyy%5#kyvc=NzWg%RyS4cFEWak*u0rij+&{E<`51zJ;ru2ze1qiuYJ6V}kw2E- z&99o$aqV=`{Gj&`L%O%hgfGkz?`Qd4)m;t;58(RyyJdgcwz(aDzv28$R)06lbb;^h zrf^%Ai2q;K|DK!dMrYak@?p(H{#gCB7Q8@p(HzNqOa!xkyW{4ibc|xY@Y)dZepY{v zboGPTYRk~`f#U9_(L)pSc!LYd`7KNeh9Mu;aQ(H#{~yQXUlUCtVB$il|7G(pI^9a% z_pg&c@3gPiUvs8DJGpi(bU(EP?cat3Cc^K{xW9eXa~C9zIfUk0`v&g^y^V#E{w=G& z?(b~m^sI}}<5P!v{jFp4ciP+IpqGH_@7^Vs;Qf(DTy(>H80&vu4lIL*9-q*BVX#pR zO9YVEKk2>a=jEE^np#k3VUDBKfyIU8!cuhcwLJu=;#|kS!!>d7%D6$IqN*%W%G( zW(!(WcGnVg*PlwZKOMUs0hW+WRKD##`1DX4Ae{6anm_{9o;g6^)=ew8R6zI5l z8Jh2w9@|MRkL01}zjWL*2iiK~eDBCy3jUc=eP;Q#2pS+)Z8cnIwqH5lA%;;<*I_G~ z@0#t62jfRL-&!$)>rQbh3r2eDP+C9*1jnrSTeE(-# z00}jCz9#6Oh0nJhae-aM&u8_ybk`vHg4Hg{ImUGk9Plo?vPL1@~PteEZ=9- z-h*MK8n0a^UT66py0HmOn2hsntgS~g+nMry4fByK-(8DsAXL`_%`c90H={`ocD$ox z|C%&^>)zi1N*jBl{fpeTj`WYKFF){x`24YaPq^#`D)PB#e$hQ9kQ#9@{P1t${jC3R z@}CI)t8o8O{vn0_Y@W}zZK}Nf+vPF~a{5I|{0HlwcO)-@ewU^B1?xXNO8UyL6gdeR z?jqm)82{08=^BW)+luywTmG?MC z9j~!Nyr1Q7V{{k~Y41ZTD#Li=|^ zZPQ>9C)Mv%W`6Q=bPj|YT|w)^34Mye(6J2l*Yh(J?|;tv#OVbo=htlJD_GxHU6RkS z`mENj5&agai{{JC+qR`=`rW99yN zyRk1APQ>-M&6_|F9^ml1Z-M$FTpNIYKE1!`&T8J(0 zT+eqklYd-$ybr$l<9u)aasrx8DMS7B(NYV!(ZO-T1KU0IpC81`UwT_#g=yVBqxGY@ z`V*MbN}V5ZTjZP7?@f9?VSSP=Z~R5P&ho!a@qVUfez<-QZqW~B9>eR$)qlIt5z%(M z{(ABGVfokCVxxFJus2#ij$hl6CXOS#^SXyh`BzDB0Hc*s{bu=ZbjA%V8;7F(6Bw6B z^)>VPYq`q#PisFJUT?zr|Fn7*G}YdK_OFvXdder9brg~;l=J<0^fG8Ncq<30;`h($ zcl_!o7!{5CR}%bSJuU zw;g{eO1z)t`g(sC{ll;4M?mxGp=f`*ch7D# zqO~KRynAcI^P?>}plZw9ETf{Jk0Cd_Jr1Z7Tg?e}@fd|D{Ry zZt~KWj)HuXe!ae1Gy0x4bTO>FycIp4oZm1bvH;@zaXzDlo(HdfpSjC3#OH_Q(>v}Vyf;zj`!$?T!s>7B zlP^$uM3;|xA>PmOd9htH>J@9s|MnC4V)+a|Xa-*d+<%ms8Pb?TcD!+zct6W$xWOQ> zU4!edcTzig!-DYtbyUvh9DzXjHL3ox_1}lf!(q>QoX;*Aov8e;1HZ5~NhzQ0xv>!Q zP|7FA^iO677ShU@Rea~|%K3c1(+5z{)X2lKvp;um7Z^!}z0D z(EfJwgT3UDjm8RkgBI57Zz`j|e2Y9dd9;k1-tHfN%_aJIdce}ZqO0sxA>o2+!NBDLHuMfW!7|>-a z?fDCOsqlCV&bQO~4)UiD9fYJp-Fm($ z!*>Z62*KgF|F{#Us4o|%bHB!le6ap{&#SdiGYr??c6W^AT6e|>Y5SGekFPB@gO;mQ zpIN@Q3`~Vd3vqo`Tb~2|NoCxy8u9GXn*Cv6@9v=Ows>dq+Fj5Z|Va}I(TzI4d*AZ{C1zHLpLnI`F*+5 z23|PLlk5*=`F%zmU`;j7?+#CWI(3*GZ*ekFDZj6`i~_f3Qh&_q^N!%7^!$e^{wJqg zpN&H&fk)&9N&k@5=b{how$e{(Ck|Kn=Va9M$(0uu>=|MsHXUj$ru4VPQ$q4`EZ=O$ErrzsyfSmck@UyqFL z5HQ~p&6oSk)TQ&D;QG5w#~eZzdQ0Y)*?jJyM;jWqQO4^xE^XjTnlEn*wgjsmbJ6{y zw&UesHy{knH++t2(-HeA?;WtI;q#^b*LQ_0tWt}T=r8Mk{WZtKjCFW^abu&Ne4L+y zARnZh&si$7Ai5UMm;Zz<1;b5D{%cR?0p?97vuWbx$R3B)ItySx1J`7_fMQR<+Fw< z=kG^q7qIK@iSF;zXrxU$YT5JA4f!(bZ{Ke*1$~WaXufcIe=Az)D&zMgJ!s%V%3sr? z1L4Jjd6ImM^|#Kd1nfG8q4ihTxz==+KIMa-Cp3J%l)o=E!{PZaX+F&AXYG^2^sM)5 zzVk!n`uWPz6W%V|AerA}_4CduZTZ+Dd!hSI9i{94j6VJ#wAhCBKfZMhf!}HATu)HW z=R3dEkUtLRv#3>P`I?sQ0>q2@d4kE0vu11n^E7<@AH;8iwYgU~j}yxIy>o0YOtvgX z{i`ppBX8z2RB(EoB>G?4LE>)>ULS*IM{s@Z@Zbt0C#v(sSH!=c)z{(Uo`PC0Jv3h! zS@suNaHhOZALV?%aqk3+Cwij&537>alytS{t>=jMvwXW~8$<7&Qoh;w&h%3)=%2kZ ze#c|wd>_2p59X11sJ@!^9|B(~&UeJDR`g93@Y#oy^Icv!42Vh;*IVu1_t!-7{SS5< z13wC+`pWX_k=0t>?}MF?{9e1BU$#EmerX!$b;bGZ^ifZK)z3wkl$%`t{IUB#UnI?k z(-+dYHZJ1t$NJkZi7O#sC+-h&wK~ez?R6L8--~>+{gHk4iucFtFXBi;zQyKi1-rMv z`R`Y_9ru*;-GOAnM|Yg>Eh>8QiQS!rQS+1Q`Bq`_;qk^tpz0j1-$hv$K^CRXM;#RZ zewJ_g`!TcwoNxa7PpG1D?dVuROZ!UbC z`2DbaYfWiJ&1cGZ$7Ra-ZfeyB?3T?#^Rw)!*3iob=X;@Z3p%hF<;1dwAML z$~WsDs@LqJXIfP8>uSaMB{o0nI@k>++{69v%(|BHGh^+9p)*AO+5Aj*$rSiyzYU!) zN}Z`A|7_$U%$=*8|3jMdpwC-reaHF_HTepdaRldo{^R!Ysi}(oU|W%YR^JE6*MjV+ z)Ss~YmxXPHOuMV7Kbf7A2D)R)xv>rN`)qypJtz;#pW}S@-+K-|Z^ilUH}esMDD-<+ zgTAx*+xyMq1 zn$fk@luz_m-v66u(+fKK%;StNiq8k@Pa?Znz`Ql_L8RblP~ZYU6u1~ z{h5N+DBK?#z1vHF_*L=ib(Q;*@(V7|{UNUJ5uwfHE&JOEb1aqf-T(XqXz7gWdxB>G zWOU9z`+wI6AHLdhH^cNKdi;M!MSW)ZT+qJ;HYoTUZ6fl;>hB7>PY;>oJ=Q3DZ%>_A1s^7_k58HqrSGS_ZMvc zdF~1?nC!X@%@@wTnGRhB;{18_UkvvPaQ?cqiiGuTPoeoi$6N7m#OW&P5Be|L0iSx8 zb3Jd0{IdGk^8EoYX!3>oYa#N(<_E9RiXpBL=g(;4U6?)?=WjqnHRygfHyX zXuk0CS}-iRhVxnWy{-JjZg=5EqPV`Z{%9SDhh63L1o8W0 z^M^*4lEGw7IcM=yyw37F;BGb)>wV$!8{Q9;%A7CZpjiY?d)0X^O5~gMudbJG!e%#| zU+1Ck;72<%zOSLkAIon?^|oMe70(|k=cv(UUw5lnxrZnk^zD&0KEj$gX!-{(vFV^;6f1$`hK6`S-;`DgN!dfEAmMheYLRc z0>=7*XnnOmRF$TmwBy?zQ_g3xyD22*;r=wG`ykK@!0W61V+l-Ck3;7VZck_=PiiI? zWX(lB+4=SHt407#mg;9JbAI2vFb#QKKWAZ~n{qx~izk4cb%rD#WAlTmu>mmWQ4ZHj zOZ@)X{mmXxVPG=%6x!dN=@tXGW?x0~uaMBqps@w#v%GNzbRYJGo8GX$n&mTc+YxZ* z)%pG_{{4O}CC}%}$jfkl3eKl-o97_!ZN~p55pY$z|Xx=lKEYBeeax} zM2}m);_qlE_owG9t--`24(-oI{H>$kr%@qrmdG!=Kl$8_q2Q2%*H6Z;Rpk?%orRM` zIltk_?r<+G1D!w6-`+^R-N8vR-#dtzudzR*IRB{IVYGiXhpNg`hYlCQmu-dr%^z1X z{fSdo766%a3iY>p&Z){jwQ&|+7qzR;U)lZ7p=Vb^VG6F_*$MG*wiNfjn!9#_PCV{^ zgE!?s>nFH=n`a8J!$*(r+2D`a=fl;m47Mxu8+$%U{kIEzP&^;98{+TJ=3kaAd%^nHD9QdJ_W3X|Or$}xU-7ZJ%Ab$^HwQsi zYpK4o{flQcUue`*5JKx(*Xuibe#(S_c5vYg{(RVdc7x6FIRCBQOo4FE!|49z!#4uq z?ruC^*gJJ4oLY00Yn~#0KM_p6^{2}Q;8h=Uha5rKz0HSGJwNXF0Cl ztzQ{KU|1B_>5=&TvwU8T*+|!}Rp__Aaz6K^_lKTNQa;&yA!5Quy5Kkn=@*srXB*r5IGx8?Kvfx-(~%W zQ$#o{F2(bOq)oAq{tNfV#Bv*S_z%y=Lg!|Kfr8)YnIeBIzecr1aALh4U%Ots&g$#e z9e2TVgc+aIFyG7ayIZv}G;$t`_Qx`uUqPUWjIUU!oL_^eX3$5$Z|NnG54L~Me^pyZ z&5-&Fme02iuYm6^lWQab^sSLpFa=Zp8Vd{(r+371XHc*BPIF_zCRF)9!lJ{Fz7 zX}j|&Sm??4Gb5Dqc`jW8mX7z4od3u28R+#4j^)Yth-^_`N6Dr2Tgf&ph))kh=M%1^ zK7~>3WxV0j{09FaUH>aPv;&peWlQCE0%5?}v|s$=Qka)rJcE7#ZShs>Z~fK*@E z^?$DB3#!rqgx`Hce%bRYpNz7C*jjx3&z$4{oUqpm_q$_pt8QV2Gy~KdMChe3ozX`M=1I#kl^q z&3X(Pra0feQEJfgiPS%^d>c2dfQex;e%4r#Z*PY0h=7(5GdxJrpJ4Nellvb-S96^2 z7JYTWJ8U`H-<^@!3EVD9`DXRG&FC09WA`imcEkA-?0muj0~4^k6~`6C{?m79e_~{I zCDke?!iP^<_5POSyK(bDa9zPS_I{xuWfT^aO8qT6e;|(;3BMK{=DZEW{~w#54VwCd z1}_0&=cV|1es41M+eNP_um z-{di8*wBAx{c-jBcu;*K<(t*-soJ|?YflZ-AD{HdgPJToKCXovGXzkgd$`GotASEDui{BiStdnMnKla$7nuh z7`Yzo^lDK5VG)r6Ut4PMk4OJ|KBf6_#`Hr_o~*|^G@Osf@~cG^@2?9s|^5^nvOmAE^sC$PBP!i`r{O<|LCjhGNDXe z2PkyHMGAGs}lqEEbyN5D?S5eNdmxU>;woFFnZ$h3vrUz~g7urtRTL1mB z`NO4A7Vy<$Sw1pMt~7&G_aG^JT35 z=IyN_8B@K`{XbDtuYvXe8Q9&RchD1yD|FHSmAWZ|frSJzjUBv$%tG{oa zUZckj$b@OvTh;qtR)5Vl^@N$jaDKnq^oO0TGbQ;L%jeDU*XcQRTz{_?%Ah#oFgpLR z;lG>I+CwfJ|G2T}DH*Gat2>bIBM z32@(S#`osM>nz`-<{2^B=*1;`5r03nzmZ2SLH|iI{%;HA{-XHPM{?sOo^O0fx(ruS z2|ud8*q@F7X})o8*B`RuB3}Qw@{04F4^jTe9kD;n>i3UWb%+QFN9TJ!RJMYnhS8G! z7py6c8{N#z95^{(Kl8m<=Z$;r*4c z*SG10U`HXxcuW1~v-#lqNh{$&b`3h;dHqKm^s&(3`3C)GpPv!acEiHs`1-J5-VxZZ zcz&?;A#lZGQZU*J?Y}HvauI4Y<@|%&f0g>5!I$3<6-!_A{HyH1voOD_j2}Adzxw-A znf2jMlka5EuORgOHZ!MQftUB~`NOAAH2i#NK6rRWV>sv$j`s({n?vhA(*6tk{Mc;P zhT)2Q5s3vWdY~E;Q8RlhZpIN8FE4Wsq*I|t;im}2AoFc zmxqsXhY#U6|Fv4v;Y`M3PN!JZUv_;+xf}-hX*KBlQpKrtP%v17A1HbMw6y+gc|HXe z7whpB4cFQA;lrq0$VfHgtFo1^4=(DZWShd@WBqS=w+pbKg#&-NOuV0+Uw+{5k}P`Q zE16$n`->$t#o+nbmUrzU@~y(~y{XR^;=emcGC$AuZ#rE#4^DaZ{PY-+Z+3myyHW+p zMuwyFOCMr1LAQOh#NV_2XX47%p!o~ef8Bk>bXJzFaOp|QdjG@f|Akru819jb&VPoi zI76dDWy1648|t4=j?w=Cl|5lZ*Gz8kK=J!!`7X9QLl=USZykp3{df8+&Ns&Of1ukr z>PGB@#E=B|-~0#bk5-NbXgw15_b%5*LgzHReswXL1_c*!f1lfJF_g#P{@(X^477B_ z`Mxq`8#tZQyeKOUWbTK(iC)i$yfDi?_S z>oDh2+_t3T)yhj4~>LuSgr6knH&H8 z|FtCfsc+L8q@*MMd~7T_1%~Y%_y^a-``PEi?#)9oJ_PqSnKsA3e5};pu=PRMo>%1D zVLabi7IhTVcG&W=lggiu;O4a?DFuH%f;y?fi~-W;gVq1@%bSAlBfS0%Q#(rk=-LYJ z$1CSw`;<0lMBw?j#fzgf_>Zk{VvflF2}b{I=X8R)?V0HOYG}q$YFub5@i(mg2QD#% zb-KA||0vDoI5qYr!t{{1di}q|)W@O5mN3#D=YOHzP*{2q=lf#9SXl50*MB;0HiSmk za48M-C!1d$b6y2Aym7vJ_DO)v5A^uW4f|tQ{hvNI6KptK|7|_55SE_5P+cqwn|ow}uvh z$>{mZCnF8OQ=#Ag&KF?o*Dh`IXmWs*-`0$O*}1hRlnli6TlZoCt#JY2aC@=;$?`j; z-2lj3iTf8%FA9$Puc7mQT9u<==a>q#KUCdvI)q=v{YzayIA~AO;PuT#e%ShR)Qt@= z;|0#|_Ti~;G0u#a%@OZs{YydQdGdKO&Tre-1@PC@fwvLF`&oTHbmk^WNRjF@>tCvV zmys_uQvc2NFFn5;1eZixzIUQ>KCSk@CX+AV`dhcDj(l4kEt$_|{mFkOjlo_u9_{~( zes_SbSvW*^b4fX$Co5XO?POekmm3$*_hapa3)-9N{Z%ESzpqvGVR4o;KWF{-s~rbv zD+`?8t$|&EsO55eo#-Ff{{4y9Ikfe0A}raZTz@B(^@gblIKNA~6wwiyBZO|Y?d$Uq zcK&+j?;#NI9q)g77ZuU|c_V~htEboBU&-|MSFaxd4jL6`ed-n94GFopeusoE0i(sZ zewzlx!uwA+|Czx%;KOD!zSne-UzY!KJ2*1c9rq`vJPyO2Mh<+_o#Op0|C`FLlJhTp z(fQZvmG{Zfw^IMX)}Q8Av*A>}Ek7e&IsY1t&&h}ZxIQ1Z_)ISQL`&wcS^j%8QGsKI zQhjFgcN&mI2bv5K2CotMZ^7vE=J2NAcvPCdv-wI=Ru0vs_Cm$i1f~3cx6y`0Tcr64 ztKZShvuSwQ5Q+a_&-c8yuOs-&asRP>)&Xjh3c?V%a{YdI$P{|!;`yV=jY7Klzfr=R ztIG37Z&xdL{|3)rZXR@mH0ugq!v_zlZ0Gi;DI`k8Te9zN~+rFYT{B`gWdF%*Opm z>egFi%7q}w`57$Vd7U1UO=c_5eBJxi9x&OW*uS6`U(b((6EFSGI1)fi*uYL^{YQ2>6?f*axOa&?5Y<=0xObbpglIABYzmwNy&|l>^zs_^p zLmACQ=d)wK?WH%aD~=Ewr<~usCOzSdLcg*3m72f-(EbgTb4-r`)vQSINKH+0Oxn@osn?7xQ09SQ1nM^zF~dS4-QPz;76&8{IL9v zGg$#O-}HEohVw^RetTGLgfm%Ye4V>^KdZ0r?&pzSk8pl3Zb^fkU2uL^h7}RNcwAq5 z-aJr^>eSOFJhr45b6N6KDejR^N1B^?g`5fzy^Ez** zE!s%=WZyp$wV(}n#^$2)e`^$c%Lo--Y!>-s^SS%W458!u)9C(~@Gkr5s^uev+NTCe z{juk76Xv>f8{D(XZZ~}caYRh8i)4p<>@;h!Nh@Yzd^j8)!*YwkC91{ zevqGw}h@-ihmLoAeYo^~#R#XEaeMzy9hk z$l96lX#f4jlFhX8qmA%%j>xYj<9{KymgL;W>%U%y8^gudxV{R$Nz_me=Qm%gCA7@W zMfV@x*qcn3&7s1v1IqdRu}B}L9mexDW7kZ2NpKZLIV7)AHh{ix%ni*fv(7$B)PjJp6uYTeBt^Z>ySX<%z7X;@L-y6Q@{+t)Bi^#1t zQvbp7-{Z=8(t9$_zg73!WKb5)|FLOFu%MhO&Q~3$lz;OskI8tyc*%S=+h4Ew5>JgD z*$5xUDCd7r_6IVm^>%drWN7eTQuPwoZ;SMewDYOKlKPI-?_=qjkUBFLoxdu4vzgwt zr$Xi`<@|S1)drOksXu1-H%6&;hSM%M->uv9h70p?ewP->K>w@MU$A_Bc{v(JMBw`T z`pzsE@>!3!uNL*4)#pT`HQ>0*j8Et*>MP6Vh{NgRzy~jM|5)QW z_%vbik{$#VEse+q+C+wiu;GCy@kYe z8eX668+n0r-;eVdaP=1X9Etk_PwQyx5ZBTSX^ z{VHi2IqfhGozL4bB^EYxa^RDF#QRyk-{+^2v~xJ$#a8>t61(|mes;?32zj#+_XpWw zXUN9_obPu&QQ*9k@Gc)c>-CY!rS;vA6<5ggl~RAe=EIi$tElNMYau*P9)kb(REw=vWXEXgftAI)}y%z63&l(&?d(W_u=rj9% z>dTv|iN=3;K5;&{5i}WDjLv^*A8QWF{G|HIG5cSJ8McEDyKsNd^sEu6n$}A41(wh3 z1=cW1QD0d!acI%V*)bIP%CI_Xjy1E5SxlUt#*$ zM0G1!Y~YWcuV`bwo9taK^#?4U&vUX#;9H!}b$9Z~az%ZGoe%Tc;WSy8DAh-nzt{~6 z>EzWof0^H|kgeZveH@rnO3GXAk<90_`sj6k0X6<^jq6t}C3F64 z(-#APKZ5(y>W+@^sJT9W=aHyytUuM)od$NrxIPL)*OJfe#-Z~$mu!}TK`%xBYmCS* zyMF&wNg&4^{LuPoXI3(4@=RLav;66=O(%5Jn~tLXvFr2PqO+v4qJGEDkL3^CB3Cu{NakxInECeyF{oS)oEvcBE@J`T7`IA7@&YsdrnIJ7?BP!R~(eH{1+4f!j}SKZ}xBqs}B ze-9iF)fxtB?o8ma%|7{2D-nMT*r1}>RO<(1i(>u6&aW_laH?AE zCS3ctyf1Wat>ki*pXK^}ihN({@7Vfd^1<=6$lF?Q|J;=OU;SDq*Ol-Q{QM|++h#jDKN!^YEQxX2 zgYI8;*)X0448!^Bee)(+UV-!Huq1@`dFLh=y-?2I$kmmkw3n2>|EIpr|4h0jO8p(X zzB+tw3@tcxR zExiA!c5WlFN?aj1zlY_|Uv)bP`Hbi1>&nu}T|t`vu>57r7)4{hS_z|5l=Jr~Ge`0I zb9{aMv2PrGP2vCQ*ZTT`%_r~Z6p`xg()E}1e*p=j=kn2Rf7YdtMMcv3gXQyJ2S*wg zY9+L{7Wu4Z^wD8W7P&iRJNkaYZX*jw*$}+`i12cxx%pO-`lFgzpI7wch^$Q>+JE09 zzfMZq6mzZ(`xDuGrg8HM(kvF|im-WcfOOeGN%bjX?Y7uI)FF#VRrA{`KGLN#wswe7?iuxr`3e zv=V+l)U02BS-$qSP9=d(c)rqq>;Y2Pa}U~ou?!|uBLU~jzT`NGGR;H#x*GW?cl4i18-)cT)!^P@+C!z{G`!$@$X~T z*F;xaXmdoyKg_>Zzdos`NY7U|)hmd6uff;f&(p(6X3q$8|HvGxAyBH=f3mKbxIc-V z@7!1#MO+@@`gd@D92s6H^@nW!l4GSf-|^5;KJcP;!|yNkhZlw?lO1z${X2FsgGBz# zxtE0h`W0&XWdZWvFq!vXmv1*QSezHemU;?%1A5_n-oHEmG%|5MS3Zj%+;3@q&92V}M#PXsH>B$`%jZjX8yFjF&l8ij zO8NY4x`}+U!t0lxX*W~?q)-eCc>gRiRJ0d()%=Zit?~kC8@=>Mfync|V;=un<6`y~0eIB)9B;jZH za|Z3j>#TmhtTh9}_cA`DQaPX5=f;zM@A3TR^QP%!vo^kd2Y)t&%4@d#i*CyG^Ng^N zyswewhb*6}_AANnpn4;$&P0gTurk0{jl}*%Qod?z&6}p3KMI{$s(LzzOyFmw!!r^wzxgqx`yj( z+ey}>4;_d0_u92JhAnmW{DiuHzrR#p2ad5PCp!3}`A+bRuAt&B|9>o>rNzbM%xT=8E?abqkbK;q-V1m|0#0i1^KOZs&*newp8R&%bDYNVZ8!PO2gJ&_C#$kULQ@b7)hFGMWFjPzT{6NX@7D3+|hF;AxH3hJcKSK51jG! zd*p^lQsIU3W!XoYI$PmU;AI$6}4jGT`175t|a?6_gemq*@hSpTH;&)ua~WP?4<*R;QKqOBw4 zi_Lci{GWc(7<7MfRsMML;-r)>)<14j>~9#?it^5jv>JXtX?^pcQ2?ki&ww}`{Qu#1M{_vx9@odl?%jzn z2w%USol=KAiuXs{y{??!;N|8dzfG`Y{{@>LbxOA+RYv&wo!3nrD6!>RW~^`EPr5%d z^@yB2QmpUoO2qGv^`Aj%t|YQdTEDaT<;E$RP~r{z*N?5l&!AGHI*GUorkoem^5|3V%CE5btOCPtedHmM3xkbq3WC|L?edYu|50 zg6wepPCWFMd{CUviRri1BR$fy3$EWnQfK1YCPH#PA?rW(g_@FcsxgxJHddd_nhYe4 z`{KDdYU1C|>hr|~AIRg0z;n+;eU1RBK5IHtqB{!L=gOJS;phk};e(TMzTez;C5IIL z(j!Xqca; zOg{UOoFcQ@=<{tQ?~jq@Up-IVCCg6W{BE7_U1pJi_oqI&J|SMk_Wbq}|9*dIe(9<4FIWkt!pTP9{vDY(Mc@UmYq-K|p|E}8eZ%-@d-`et% ztTq$pe~ZdRvL-~vzwM$tpV;mFM^@Au*YBz@b@H&Olz-O0G}paAh9=qa{2k@~MgLwa zvhAnTzp(lqJ3^lrG~X!M|IF(9*@{c#m<)L9^U9x(%cL9mwg}JH+ygl1)Xz%LG#8%_ zHeZWf-(39ZoXGP< zxW6%Y=0#4&;QnTRZ2&RJtKbSJ{NqE~-!QlnL3+B>a&uRR*IB;rM#hnDxr+I}1LAeo zpS(M?i#$>2yL`2Ho%QEGCl(MbMLvS@?Pz&Z);0&%_qu+k$mj?5{NS_yK3}Tuzc!c2 z5;oxZNSi%JiCk004^C6A?}1vcWgpk#{(Sbpud*o}r2d5Ed-3xlWvl{;WU$EpJ9bp5Xc)sBwZUSPgueugdxM8LC4J6#b1|wf{a}U9vtoZpnxA zQX3(&y@27fL+U;k^~P-1rq_c!Ub zo8hm$fpFxYdHwwn)Ijq4Z5ZT5jBD}r!KZLG$sUD2A61iA5vv1I|HD2Xt&9?gLrZ;r zewg_Eu+K+Un@sXhq5m$Y#Otho*S%XL>+}|%PYhhWkBmNN&pS){e%2a@l*u`7OT}HT?ea#**)M?fP`$d~yiyV%qS0 zP-*^B81q(^+$aXkU*TYHtO(E|s)4xw znOK(s!@A)7m&|NW`t`!|Mb9rii0cYmzxSs`f$y>oLZCra{qqq4QocX596*B8@cD}8 z{;4ooW+U8kcdO?+m#JT~tK~%X2hMlIHV?8YvX&dOP5l3{`fpRGSU+;4e6#-E^ZF_h ztJwdC@f~m>k<3z@pVe-^`1vf~F+;Lso*!|(Ro`zRoiE{hSHH}a1uw(-wtt*JHYwi! zjn$_kmKDk-y_EX<2xfoa41@Es7dbfJFV1Wv?amM3eflcrJ1*#!?B4xou33io_p|zc zWo5Z+&4GBXU$yvt4A$S=O-dvegYo(`^W%G2usg2*R=@wqzWMBtoS)C?d-8!;uzNaC z;_ojp{v{z+lgK*b{yq*i!Adf9vnEwxrQ&od4GcI+5{rasNIm)%^eC>$~G> ze&7EK4Jp!IXwV`eM5l8)m1JgyP{}E6n!YIu+bu{ zXhn?d^Ar2`I-i|_fC+Sc13zBpPgA7t-ygGX^5Z4>t(GzK`ec0fD&8&FecK7&H|F*q zZ(2U#e_TTMXKaSO<~z=!>lcxDgOlM=dVK#m+`=yu(*5&s`g@$BB=cKd)^W$T-n%Y> z4`KB9#=dHT>f3aE()dVUF#c5?Dp}3^KBWJmalle=+Jhdyeb+b$-efA_gNe*~GJdlU zPZ1PL^hYYo-(mYNyASvYJag##^Lp1%{xZq=oI|qy(oi9b-sN6iST4vq?TQO!{6WU= zy>9#XQP=7Dr*Qg0!9RaKj#A*(AAP1o^D|U}(9J8I-;eFT=;PTm>;&6?yvvc zIn$|kFg^ZXy?@AG?Mjb-i*Jjaz&4?{MVXloL(Uhs+wzisV7mr~xplTY!4Y>yd~rW_{M-A4^TihXSoi;s{!3%MqhP>qNq_ZG?)WeN9mUU< z^pDc&ODPZUKX*?Y-+3i_e@_vz^Vgfd44wYIG!jRdamW9+S?T=biFAKP zyGt(LR5=gLmYt6!=X1Q(baGm3D-@@cbMNnSr;GTbSJUJB-L^8mcQ#v}lm7aa$Xfo> z3VM8p?9p;Mu}E92(RG1TzbqvD$CRoTex6$!dg9OEgVZnIY7_;cGfMccjK9hKKh!`+ z(EdvY4_m~nC-cvMXe+_11J+o4fO$^pm+|t0_;Pjh`jMfIp`f>5j|0n&K?UvetICV#?vyeOf z2PDnr_iALHFDCW*?58?{DK-Lpxr96Z`e;^(6mO80*uvH!m`*v;QOnI8YUrXA#ae)8SAc)YIeJSM3*n&rw%gy07!~+5Sqs zy#{~4X}bTob!8JjQgVNl!dUM3{_SVL{}e{=&uVfr<6GI&`vX*jU-`f4c{rNK9p7&T z+3+7q`u{ui4Y|Ju?)%1XIM2tcM{&n@%tU*>V-ww3qMfZ2yI8)`2MO<$*w4xqo|xl{?P(L)R~tL>c`0$MpUe)zk{dgMM`Xuzmg;M>kKpeyO~FmS1p} z@DB<7zQMJ{af%VWKfve9IexB%03X5J@jWe7j&Jpi9p6GB`+Px4$a((XmvsGdv7tNv zu?O8>d=VHfa5|(bo;z|8=l=cdl_r17HhTQWPw&g0An_Mz_oqZou;%}Wrsto<5AFH> z7wP)s+qV6JDZdTGl}owf+j`VEew?H~k#@eY@&f`{kXzs=_m3X` z=bw(_4_f1jc`|)P#{bASs~o!>p!+WYJze;jPw4S~S+L1*+dlgKe&fV$$2iqc)JNw3 zko_;S$2s%gYtr?LZ_@$CoPlipPU@F*V|V_?8_ulxy5#+a5nqlv-uRFB*SIu>-*bf% z4tOZ5KgqHCXYA9H98XBjXVdCWmC!(-c1%ZXffjJa|B&Kyjx|G1qsXpI{!99k(Jcjz zd^P(1Z?y4-W2zlMRS``5kox38@MFiXH_DN~uk*PID}Vml^v3ZntV8+JnCE2vxo)YM zpvS+y;+9!!IOF@6&L77clj!<9#i0lP@n$7_Zh7bHv(GQi(lq2xc&mf4Oh1wOe4gzP z{@D=v{=RfWI4?7b-XHMc@OsCBZLau5Nay>r^^1H)G_OkrUB9$gu68UbcEoQTx%CS# z{RFS;YWDt4>hq*wDZFR@5#M9YRyn4$@Nkhkw|+6~pUK-TIp5H!UAe>2GOv6>53 z?&BqmFLM6>j*^Q!tIKqMJ@I0I&|4{#hx1m2k-m>~U8Q-~Ca*h`+(f9Wg7OIY|J?Z;*>I{9y^L^<0 zBxt>rqrp15{%!=0j?uL`_?ug2e6jUO&|*)=zK7}h+n@j!cHE-Z|GUR$7x^uf^tY_& ze0_HO7EUcM+*eHZ7hBe46jkqb#9vz;OXGt)AHFKNqVW4FcKnk5%9@IX!UshBlKJJp znzKdyUhwdy5!~^6ctcC!Rfm1l`zw~EUMRAj;(~3KamR05m|T(i6MBAWKlpsngu_Jt zIT61W&$<^S3gglIYUcMN^UFrpaM8a7y5d=1xZ~IRt7cI_B;8;1HRxL;`j7Y(m1T)+ z7CBSr|1aZN7ez_V|IqZg?*sdywEu|jq3a_=?T_@ueg@q2{RvI(MV5%ZzgK9_D+;lp z>yvKAK}D)t==*o^^}R(qZt38iLz&-~+`n(mi!J&SYK>E5_$Bp;Z(Mkh-+#ov?Y8xz z->d2Rr1DsFQOSO~J}GQlCCZb`FPPYid;eCve4Gl0EmjF?VzzM(0=hhz)t8mf#czXY%+mCxi z(4SuaoElnFr2ZfJ;@ix|B2^+j$^EyrYA9&3>M3qEf8r#q4+z=yd+lgB(ZH~BG|aX0 z`?K|j-RB;nhdFg9a~$)W)E~2!4gw`*-Nl11GX3dff4QT#zUbk9=xeR*R-)Yh&>ve; z97THn5x<2Fo+AH1YrJh8^ZCg5H3}^)y7`jspTyZ;5j}Ku#phZ64152cweWe-hX{K7 z{_B$`3co?uA6L)6E^N&2@s=MR$c z8!WFRGI&L=Z_avpQFJ1MUjGTWt1i0!ANiwa?LlzfL`QsAn_EBcFftUKm_qme=!w~KN%@bIe72W0w(-GBAC=Sb1; zhwS}XNSq(?t`UkfB>joB`u#t3Inb!-gcrnc@6W@;9->_Wy8h7Hco!U>s3XquuPn!SIM{$T8~HKN@H^#0ljbL64xAE7wkm%D!XZubt+zmxRyacc{`>VY z=l;G;6e0Ssi@m>-{-Kh}aZ!9Vz5Y{s@*$YL&`2B|$lOn~kBEQsY3U+kYq~zMi7F5| ztflMor)DLhb!9qu+NjR>Wb5Ok z*JtnV-qkLm>3iw%FDGvdj&5|s4?c3o|DxBEMd7>Y{>k?|FVWi(bboyCxPGAiBoDt( z;ojeC-YgSs{=?2M$@te?vR?GCk?jwX{VRKant-f30=(LrJO10g?GoAX>G7{S>!3*f zKk7Fn!;Xs{f28l<@Mfy0`XJr^vkJ==-9N;x&x8{5nSS>GqDxiu_!JCNf?7`f#LEl0 z{g3sv_eJFutw=PS`TxoNIl<o*lAo{P#Q^T$38==^+aeXUmgQB;~i*Vnng9LkmU6*sGM z$9GDM9Jv0b6?Nw`uTRFeWV$j4*g($@o6P!xNpU(juottQ%nu{(4g*hJ=<%B`*emkb zL-+T-{9X(8nMwLjWcdXdzcELmM3$&EgrMQxJ# zjx>GU3UmYe{QLA0ONCXaJ^aQdbYkeVL1aF8E1`0 z&10UE`|~^)Ct52xpX?sZJSX*aZP0#j#ge{1|7c4S4Z2LHl?c2?G(&>Gk))ACRcyJ6&JQ8dE0WCwhEODhvm_ znNE0SDR+D?d|f5dk<6E%op0#VI1lP{F%+Xk%Q)kEz>be1&$0CUQTt&y{2JsW{{JEK zKYv4yxWB98^>5L{C%Nb<>iqxM=YM?uC;~lq`u=_9LT?c7RgNwUVb+uS`NRY-_-lZ^ zICAkoCVq+YJ0W>}flWRgAIr*ZK=9vIls1`peRBVv>Ny*pFV+?JR^Y~mWIQ1_7R27) zN&T|*j3?-JjK05Hu3QT$23X@(7v}xR_|I9HExP`Y?w`!Rl?b96T=0Ru%zAQvpPqeH zwCxzZesgB+3DA9vBOW2*j{lx7#G-vXdVZN(RW8Es=>1jj!*QUKz{AbzjJ^(aV&|9L z4pfPnp3%=gi2UA(f}hj#%l#E`z+dQu`#|pakJkAq8a|w^ugh&W!X>Bm#qkT4aK?WU z>;`5jo<^5HF~2XVPqaf~;n@9rR{X0I@!w}rPcY$MF15c9$ms*C;Q-B%_2-fL#c!oA zR4P;z1I5t_0zdsk+fx!WF=&%j5p7dXa z){Ft!*IUurLCkX!AKv+1VC+;SyjG@<$@s545Cj&A>H0kF)jsgd+8Qg!)|2tSbORL4 z_(<31*Y&c%iC->w>tN>dk@3G_Ux{eIf1Gbq{C66RmGu8@*~`SgoRGc$tL8ryB}wjw zu(-{i4wyu2*WW z0^HRR&)>!!|I3scMc*XzF=_EX<#W5}ya8SRcu&0w+JksF_NUBWB+hrHTu}fYB>jh- z^R>wMPYzK7S@m>(rS?n_SXk|Zd84`e3yU&zfrZ3hq3NIS@?)^tOHW+C#aFujll`;8 zO{U<6BVGS&>M|INlH5;0>mPUj>i`Z7qVMmEJH~_GtLgFEOJ_b<_k@1_N9eu}=EbUr zKec;EG5ep+UC7QF3YjUSF= zo|EyL;`mXt#y}Fkl=;Midp-usuDIZd-I?{|{{7|LPtpCAbbqkmVktP+$iw|samR0j zM^~_I9KC-3`I!osqf3w9*)uf3amoC*&i)e8{}Ut`g8oOMQTWq;()c0$KfU7nU}v`E z3OEDq_?+I|0(>!`@6Q^Isjz;Dws@M64`+NHZ5;-F=(GDrNPSXT<^+;k=062;s-y<4o!TuTn?zM|sf46iU4wjqK z_4khhIk059j@V;2w?DY}t`KPGu;UvM_p1$mSPISe4QA=@6ykhx#Yzt_5!3U}bR!>d zW*A+6>{2L#A@U~TxoeuF@hwNx?{hB&fCyK5d>@*W2OA$r^v7>*{jocG7w9k1AGH3$ zNkh}1=W7*lRxopZpWNS3MHIN5PS@vWs!oD2gOu>?VN86G@vkn*0Z+Hm<6mv(E#Tj7 zg^?|@p4{K}@wkLcZN4e+jG+AhXaIcf(C=?uH2g0}`@v)9w{qr8KS-9` z-%j&C!y>N3h{o>X%fSYm`1xmb0$4@T`NhiPGHc}h5vlg-B@GA#CYyk+gpy#)RBc4HnKbm6uKJz*G zL-(aWkXNGXtD#*(!DPw(ptSsUKy)>fTc9WQKjkZpU!hQswLc6DivZ)g(D`FQWDHm% zEJuN(JL8Y-U#{off!Z@w#794K$M@5mRN%IZ-al43>;s%HR*{BOtKjK5%sUgq)MPQn~sm|MQz~H4J+&?yT69S$Cj=Z z;No6-{mZsp8{Sw;$H$3ETQJ?7oNcZCK-_xbo=;!Nr1Bj;;$ znd=Rrx6<>II8{w}HeG zK$sPqKgj&Md-iAOuv%ZdvWmNYHf2~As29-nSJRd%csWH)Y@IPf8vnLLf7*qFB5*T| zo}YX_{240E)fX$IMN8L{`m1=x12Ce863%4#o9y#Zehu#cm`2Cf=r3Jhwup`|gI%`Z z`dE7Y^5jrocw~YL{+Z9sKiB1W;G8Lae!=$&L-@H(fQPp~lf^Gvf8AK_2J&96rTVL} zpY-6>1(Nz%7`OiFDw+!7i|P8y;k_O_F^`9Dc4PR7yr0lgG_1W?|}#vfUq>*seC zIGM8XMb@VekGc%<#@3-YnLkR_*BZyXhqaS>iraH%a^h$GzS}^58y!F2wpW8WI&6Ll zCFW}@&1eHFC(-e7AXo*)oVCK^6dC>{`RCPl2e4!VoqwL)wSZ4t==j)k#|_AJEJ1H8 znAa!u*~6)(@Wy8ztN((mznPRw1y+Uh{6uf8H^`Rwx6L)3ug~V6QGZRKX(YWr&UAtw zh?3|t+WC`d~+`%^$YpYo)87;sgh=l>PK zUD19!dVL})H3|fp();Ju#l?cQEP8+Fp9DSBkYg*p5zO$(=p>#c&|EFF?V0Pa+6w#mge@Xn* z{cVM&kJZFmyK>{_miA*1wzw7bm#ruBn|l%6kjgrJ@z`Q+{?Rb}0Q!DY#8FzE@6YC+ zVOQkg>cKiV6n63hyS}$vtFx4w&YDLXmI{#l) zmOpafj~pz2L+6*1>Am2i(RBURp=Aogc3I(xtxSBA_~`L|4j7a}zrWf^)deo7bjH`l zG3!ZuEFZNLc>GyHycr-c6u1K%*-Gyp{1M56 zCG+Y0;r}2UJj$Z;$J{_6e9IT&6FX;1@kh>o&tC2F+yB}A+AJLa zb~K2n{evTalz|Y;<_9uA$$DA<|D7(tJ5x)guOI5fo`1j6u@1bFr|Ykgb1uOzmX|R9 zx}r4x>xuZ^u%{JxjbZDrdLcXhJ-RBv_jUC6&zi0ST?W$mVRg6_{56-(4=*Zwfy-1n zKOFt;24~)M#5dA^GW)ZT?Ju894gh95==GJh8QZ|oL-hP)m#Z5*YT$^q=jAf5Pt;HL z*z5&e-|V2?-x_yv4D{Jb?;m$u7zJ+Lpw}la=efhzs|5JyPVW8xR?u-UcLRO@pFA-Y zw3O5L|4Baj$jV7W{OTq%pMuQaV;Zx->$mj%-`&6(*$+2m?f;0#-?MbCfspO={5?{~ z0M#^Vh{H;`@u6aH8@Rln<72eAH#*p%B7XPcz6@V%eKq#MGjR18oj>NU0I=~;0WLYp zjh|gDAHW73dj3BzwFs)!UBvq%82p41_!;r(A5iSxikx~d`wyAFXl_x1!Vij6e@w8d z4{S5k!TriR_jk6wTADT#miyB4lWtenfS56K`~){lhPd4?|0n%1JH>P0 z%uPCe?DLF~*-#BJF5g zkJ4)c1;1;l{ps!_Z^4imm+;$n-1r%3tOzrEw4#HW-1y0~)Pj9V==qDnoBpt-tK|Gr z9yfl*_i%uRoUL%m73Mjqzt%3=2*7AMexCQ41!K*5*dmb|KZSR80k0G`en|f;GGi8e zmds=I@76oB@pDvtKR7a%et*T3-m~CoLmr;Bof|*OE=R!N3v~PxswV)?2zvdduihNk z=cOa=sOH8`b>k^;Xgpni9af(UmE#4}`2jDja)ImbIO=>kz0c-o_1oTJ?>XG~TCt}H zgx+G~i_~Xt`jmk1bGg*}xeQv&(ZSEX#oHEn$>N`lpNst}LFjEd|3uBRLOx1bV&{!D zvh{5IbanX%mP_;-?R*Dze*iD2UdE+%WzzMee!KbSFL+W{OZCsz@4pAvhqLn+Qop@8 z-2dh&;l56jE$cM1b*5}qJiyXI)2jh7r<*n zdH7BuH-37$#DcP&bbrj_a4I-{h@QV(%v=Ojy!d!r0C)W}t}YXVNce|#zv&Uz#n32M zfXlMD>oeV5uYeuJ^!m&U9UIi)&|BQTWDaEdzuET-WX~!FJ|a4Pju{U{B}rN=eMi=3 zR@y%T(|zgsF0{i2wf*TW{ujoLFX8Z4V11d0bw3zcpSfZ+6s@N_>qe!e7zf!i^&sr~m4|1F2HRy?d&#EqZ)v`DaJ zFC9O2nJb{$MIQc<`B)ksR|))l%QyzwLg@ao(dFgPw9x_YSk8@~2}Vg^qaoWLBlX*o zFU#R|1NQks(q9g0JPZD9V)GMO-wa5|17pXr^&9CgPh7DIuK&Qt-p1VcIW-%ABfxPB8y}=TJ1Q3lADm<3gX9<6Me#sG;vdt_ zS4HRtK+84w+9 zewjHc2%@EYe7jgpihuI{Y<^uanAH@AoVqamd8B`KWz8Jam1iZ6bJ;3guTI=Qxi0Jx z*q@k=(ta@UPwKO7D_#O4A>BVaaNsk%+jbT2uIlc@@E2R34cOca?Bm$^4T+D+$3xKl zE#1Y{56fli+4`(sUKd!th|M2lepB$`J-n@X8GoJ6taHE1|Ot8i%^*Z zH-4ex$8|$A@OUsARjpxOKUBy{@8xb^2!ZOVJiI)Q8$X#NV?q4yCDikY?>sg^=P(|Q zk7oE~4B-!W1*HHdZ#sT_l0%?_yu?3?%#EM>3(A1nwK(d0)~`c-QK6}|I3;VF6hFoU zerj8)z`$I(|7Kw9ip+~OsQS!&&PVXhm9Ediy1a$%@)z)zUvg4>ggUYDwXLEZRIL%A z`t?kFkodYdQi!%3RTtZBuaK_)Kj&-SE5Vp`Z2y|nXIjopu&&?|4t-f7dw;fnjo)g* zwr#a2kafP0eZO%^P7_q@UVxV$`6egO3j?;tQXd=Vbo# zrfMwoIHHaD_RMnzx6gY}x)BS>NoN6AIr{)A?yeOAg51!S=UF zetJClIuMMZ_n)l@x(R&dvCqGg`t0!7T`+nOAJ5HV@FOQ=&z~3WdJI$#)BQKY+*iQ& zI6HqK{k6Jh<59^0IzCc1G=oDbbbYp9`WM*Xk%fnDli`D?|E~+}0uw{&{Bx^vI6CFg zRXic9SQ_6#;`~|37gcyOy^MN3KAke%mnc z7u5Q22@l@OjgP4*7I5@RIzAkyj)wgt_@L>xMgJzl>_ghPW(*VmBtGm9u7C%g)A`49 zNgOD3osBwV=jTcOX?6*Nm%Gya>G&IIpwf@tpVlim47TrK>o-e+e`Y;859*ES_!!7U*6>kEfWqvJyv%b~fsmvH_PZhU;* zX9Jh)YoXTv8^WBR-(p2Po7F$Y&TstGJR#an=Z^^!1L3elOWe(z!4JtFuho;mx?i)Y z{4w=x1cYxT{+Udl$r1HWcdrbf9J2(;|6=wBGQSCx+Yc)w{mC?a)=f1JtX>?5LS*y3 zNdB0W905PQaG>flMXMq(cJmHuf2YON+aPcXJ-`3*;}Osp9ZkJ|@R!d4Sis}sS0&u| zFcQ54J%w@T*dgZolle=M-dyy!mzLP{D|i2k*63#NDUgmIxOq0}HJ*+ii{p~>ZOu8< z{9nAk9quX4#JLat3jUYhgcAJne0vZ0YZ;qgQiR=E0^;wP9%%bX5w_4`?sp^gSK&?_ z=rfm&AD@8V(70PBZdZVu`pf!>8T=MV_XoZWQ$+0}F5@0YnEZzH&$4Xn;KXrsesTWm z27CA^;%L_SFgAYL2F!;c>*@G0oD>4%4$<+`Dt`)uS?#vKB!2GKN5Y@3Z2x&G!7mLvFN38Gfyg(5Sx@3;+pS2*Gm)IHspQUY zW?N&B)3%*@{yEE{9IRhLuYayDsQ?}tbbhJX8x2*~^6~X{20vu}AF=yAI3GmUU$+x{ zknINz@d!8W{+Z#=e*)Ff>8SoO^Zm*Ef8kFbG|60(n!l`dQ-DS9==f=$Cy(BVGV#r4 z-1zZ#?**s!5urB=nD;01m!3vl(3-;YxVj*elYe%K3}6=lJAWbl0pVVGl-HJtSD7GA z{AhYv!asI&{<+sx1;tpi@k7>cY*a?UK_8n@znu&}kon7!fQhidSrHqjGS5kWV9|VE zXtr1zpS0?H&i0?R>~}zUe@mPw&papjN4!4+^h%#iy&qb6(h=Bf!^3ZFx$zS`DIbXX z(fzfWIY*$kfPKE1#LqX=A|QV`klLRq;va$MB>0{9k{dts?Qer#uj%-yJO3C=T1ofM z8e{6f3ne;!48|OTt9}cp_uuN5eFeeG>G&~-U5Y~MHN?*2xbgF2y&O!MOXnZnh^0uF zO6Q-EbGt)+Q4Y%9$HYJBKMQk}kW<11Y#b{ui(hvBpZZ=CR`A*VnIwL?+bN@?F4@>W zeHXKy$ZvXX?+06Z(fzgH9|~yf^7Gg%M}{9_e!$H0HgJsuKeYUR!|}f`wt%^IxBZ3x z;|~%)bB|mAH#gG#wP9{?u>TlIeSCJibUoR>Ik^1_c(j-pQ!iWnw-$o&6wS|#w;rsw}*S7YI>V|+Y* z2zUQlThv=nV?ft;-`l@~>Pc}Z%n|=di^FdUKKU%&&K;3 zxbf5A*&iO0qvPkef(n{2>pVV`$&H_X9mC+fVRV0bXPZ3wGb0s`@7^rM4rFG7n#SOR#82hIIWT`RUBCJ44}`xa(fP;nW;f*ZFdfgn<|XUD?#t4*I-%jPeYhpo zddQ8h+C%xkC}lQvzHr=QswTiP2OfT&%J|p0 zM19nBzr9t->>Id{jNp3mVbTe~4E|lP> z@aLA$^i?Uk^o;p^NPQR8Y7fm!>G*NzqKM2MrQ)#_-1xcDF%GW0MAvWE25KRV&-r-e zI7?alv*&l4^z(sEMvA!G5$5xe{PeJ80~~FjjkmsG;+yo}Ch!ixd}B-8T+BQt`3Y{i z0)C#S`wNFooq}0&h1kG}Sx@4}<1GgFJ};*Bhd%B|f|d;q7*ApFL(V5i$twfOC+Yc7 ztPtd#yP(FP->e#^S&t!i=*Q8_^EScYmA9L4#dX&Eb*6M70k@E}Y zH>5xfV?OnMc(cl8Ft#uXjY?tu9}-`_{4UT)FAj}7$$UPNzp5)XqcVR@@$1Rl_)0s_ z11?jh=T9#+!;r2&oxgq@(T0LYIn?Qx%cK(v| zw=e8bM(Z}EV2w9Tocy(Nj|VKoZ2qbz&M(Z2*F|7>K90_?km4^?$i`oT{Sw&2l&%lK z&26yRTpN4$Wd45=fA89&pq8p7zIT{n~l>jcKH8J$pWzUiZ&ngc;o*zpQf_`gZ42@AqCi;}@`m zQPlZTp9&P<97B44&z6m$Xpn)X*r%RbKUTW*f=w#y`D|o;DPgHT)H_4xuQT7Z(Wxuv zak{6RG(JgxuS-pTIOTQ`S|PjNhQ!xVzCLmZ$-!oq7<`fZg`N+EYU!mYBZrAUlD|%v z_CUeYl5zJb48F+vk^4<&*!yJ-wSIJwuZm6`OTjHB%=uMP9~Qrw0o{|?`4x#Thv|mM zrYa8$7INe3s;eJ7)sOCFhY8AqVWR|~v9g?Uc$+wTGlEcVg) zZBI!CRKLf=U6(TFhe&+2bS($QMs$6c&?f_4P-E*u@_hE8sTJT@b|AGs=xSjDsM*2x zC&>ItHzot_Jj}z5b=>@Q<8d<>q)W%oua_2G8S3_3kPU0y$^Q8EcBm9Sh6Wrk$Q4NBP%zBc4c9yH7 z@qJS9u&&(tZ|N5=_-PYc|B?9EbfO&VRLVpB4rmBtH!o9fvkoEpY8(<~fOzIA-U;ER|aYNq`f>=;7# z2OYhdK%_n0pQy9?2ljlUXmddWT?yZ^^OQXS?s z#8UI8xYlq~Th>c_%yPDLJ$Zh$|6c=`{Ph%dzFX5xKlE#)&f+eHTjbSKqPIpr2O_+J1(cziiF*(D^SZ_(lUa{zToE!au@h zv^S7hPx9B|`~j%LIR}5%A0Ul?GJo=&vv|V>;Mrc*d@PdRx{XkQj*;~I$-??NoZ3x@^`@(H z;?r-U7JSeeOZDdsU-gAo>)H4t_2FgnmFVB*CMy0OKCy!P2IinKLCo(<)~|jiIG`(= z5I)dDU5Xze!G9APMna=>I{&TnFhuUQDfn+GH~w75xxt1lY=7|o;BUS@+B`T3zjn)K z@Jry&=h7@Vd_CR2c)H&J?Ov9Q*Q*or7hSIVL7rhV`n-S}e~VlPqNLNgSS!Sw z6MsricEU&R>G%usibC>_HN@k_bMxP!Z_%)2qZUq>(uprNKHY0mV9nCF_KeKMA!QEL=)bo2WM7T7!Osex>4TvEg7?JetmL z=f3wtw>nbrRkd#nzY+c6{Y-f9)662YM#%iWB)?rY>xV+DQtz%(Dy0#@9$Io?;@elj{tXHm~@%z2BUYELKZXxt%N&z|p4^6D)(x??eG zz9Y$B_woRYe8a<2Te$JX|K0-LFA78v&pQ8qHojWA%fkZ`==`-PPZ_r6>}Ac@CeQb& zr>Vn-yXg6q$*7yqXNC(FSZYYWpPU?9Kh8HcgcmF6{B)$hISjvaigo`2iJ#3)%hBYB z1}c7T+!_j%B>Y6{ub8#N6m=M-;OP&)GWa3*Nvz=nwcP0Vc^umhEpR@Gts+-T<2QxC z&xk1=aPqiPG*~uYjpV1p9fs)K#W-v>hZ{fH`xe6Kd^&!Rz6m;0l!U`88T^p^baHbr zJYN3|&78vEkJN{8uT4!q5EJ9H2Zow7UnVdK|(fu z#v~kvF-z(C(LLE51=^%z`#s$Cg_?%^}6u&7#wtl=i ztq$BeMd!D^b8o{_@lLp~l^cIU;y(k;6>R*G_2&oPZy{Xijdylu_?4W0zgzA%&>Bz2 zUqYX5(C+&-YX4xIvntfTx0iMPiNxQiv0Ct(1b?*rExLO-+}+y^XSi!|;%`w!U-;!b zo!{;xM4~4K%HqtXiPH5Xzx6e>hI7MCp;p=bjVZ+aK~{%0pl`oFQ}MaqW+eQoN5|*q zRpv;iH5ot5;>PFmFRsvUD%+nY{lx=oP0@IhM6B8B$BEDUxiesy89RTgC+^RR7n-19 zf8z1gYHt7Jq3$vmVot}WvSWYLT6q$GPy8Z%f0EyJMs0x!x9Rv?7v+H5Juc!OmYw$- zvFl&gD)+;Y>lLtxJ~uw+xD7-uC)4raQ{4Exs2LA)b+oWU6BGZW|Cs#35*?hFhT9Ei z%lMI<-^u;Rg1rRhSS5!WpPT12fX%mOQTr2NYAH~El8IvszyL7$*uus8l= z!{CpsU+**d2L}8KVD*2H`J1U^KHB{DZRk-R!;hrCJhQkLyj#1Mb$=q6pDB&hg?0|~ z{*AkWb!bp&1HL~pi@_gpe#&`~DU2$l^I!jtAhag30q>kRP`W;pxF0>V`(PNFe~NW} zm*mILCV&llj}m^;XDgaWXdi*vQF`3th*-?cVhK?c8n) zR2zK~D-2sBjek;K0_{0)loMTF-Y+vpuU;qO6Pk?wPx>cIl~=*s-gNvO%`r#5cM|a& z-Orr(d$ckXZaDl6nGR;~L-M1>CO(>MpO23YW%@rz|KxdQB(xSP;N#_tK1?CzgWn1t zjK*4}3}0esurRWZXAs@y;8o+-2}b*4LH{>;iwT zq33t!6jfm0OE&&U|75;}2K4aTi@wX|E0FxR;IaXnGoJ2`T*=sol8RsByj|xx@z)JW z{KLRl)UvxX{@M5U4w|_R8QrbJN+lN3^(6jWGl#;-OX>W#y7wwH!nT5nztyS&Sa~NK z^;+Kf{_Ot6(}!%(pX6kG#haV|5+Wu+VqmGN*?nQd&d;0#NqY=T!WSc6EW(H?yh!rTi{ibfzo`XN>0Nza71&!CGCq{tWtTg@)C~ z;>a1xoc>q8AoIh7bBo{|1-gG3pgIU8+>OTrDj58w5dLLHSTIy?sHXZWpL}eQ_Jt&T z%#`sjN&T6vxfhNQena0>x$)=la;T)Xn1bsp82kx|`kjwrjO2W{0?x1I=D!z1Mj^L? z(|E7GqZA*Z1pl31n+`3SHE~r3H~vnQ*&&fQ6&szM#pq9Gw*DMeoDC22`e1FhuhRG- z>vwBXTY$?Ry8cucS_!iy_uJ9HPTM;!3pO zRyn?>nZSv^`+aQS!!`8$@ZQ$|l+b6-`~BJT%RIM^hE3Dx{^yV_>(O6VIzD@i z7z?+BWuwzmJMquvN2RRc=#5q~-UAtYlJ)gxGd$s?r-jt|o?W^P8qg4nwS&0v>9=wj zOs_AY`Zp794n}#e;_!<%-2RP2{$}{Th|Z6N`oocSOcGw9!;R0-rhRaeIUS$v@x#$; z1-kzkp>+aYP*lM4bGY$YZtI9LE=ua-0~vhE5%}ELdKNBtMaSps9;47+wKP1@M3x^C z`0OFfhjJ}OctBI5EI!!vha0bWsM-HC&ac|S;G6JoCMW#>+H$j~^VMwBYTz^#C)|FC z**{4Ax~orD*p$NNPZGa=)8vqCDI33}eoZ{60)00Ju+E2){F!k{1MWUb$FKEDLs&3n zFKQ3zjNfi7{%gGT0(v*`ao|;M{QeE>53~Bv@oO97kNVr*!$Cm|enW};a>gKAD0HUl z+neuJqXtnKewn8)`+wN@eOK%VRr{Yp-HVvdPv)1e!+lWVG{oXpa{l0$#_{mS?rc=W zI-kzQ@62UhaPg}`YX9<&!*=MgZ33?Nx6+A=KZ|PpV5~&Hf{sr9V&89=cw{Jgvmp)_ zY-R9C@@L%Q9dObWI)4UR+as?@N!SK6{wm3zgA)$GULJJ+=2WCTQcsicZ;Q4xzDfR^ z))Wix4C;nM&6)Tm^T*|TGSKQ%y~W>xxckR0f6Igmi!|}iC(L?Mzm9G=gCI{`Tyg-) z-k;5%e@|Y9Esy$O>-kNx|DTOdC+!Z<&ZE~a9vpiK`$+Czqv7waiy}NZc`o5 zzhw_B;9E61{%%>VM~XT3@bcFT{>b?_o`3D&Xzy6+{RUfmk4GbiXW}!b|AGI-H<@2v zxh;fdwsihn9xxNFe|(XOza1kzV6SMpzSUYj0>wqe;q3IcQh$f!&#zy+VMBExtN)qI zFZDJBz%!TW{Mf5yBr2_m$29|Tr1&NM8`r73;JqX|{z|=g=*WpAJZv&IKlYyy1rN10 zQT3~3&`fma=|ybX+gcj`q<`}wE)Kp_=z^8ZnErhde?gJ6(1fG{oW9aS#!u|}#=zOx zaCnR+*306?--H|IQPR@h;`@WR{Tu%9oA6(@gu3Me>^&3~kR{bD7#U(_;ydcJ$vSv`1>&#qsP{^{~66X+IJAV?UoF()qu{5B zICdT5uaf-8f3yec%&tajVijpZ=@6LfFkn33Vjs_&Ef zR8LPC6;AQSpCQAKq&~H)(SU--{?z`Nlng`YZ_LIg>92O!41gVz>HVP_R6oOMUz~8f zvzPSuC-G^UG8o$aiKL!SurHa0jvmd##y3M{>)G}H5_2B(8%WPDom!@%l7@4*d5znf{9yDe*&pDh6$5q4n@~ib&i7~EA2edXSaj1c75i=1 zlj4KauiBnTu&785S2lc?{=XzXr^{!dD^)$jbvnt?_3Fg^-KHJ|aJQc(-ju}PgVe9r zD&0~3_B4D>dyaH{3ejI0qFN3wUNy%XW#?Z>{){*^2HCz!#;p(6$?(nY59pVm0L>?P zqC>Lzm1KXn@1I8KP)x_~>q}~|(t({{lKnZ&*(%6=Ih|kSCH^YDO2_Xo$$T{bcUxKW z9Z38p8d|~)wrqcvtdD$O(+nGTJ7Zh(c{2R5{h_XBhr-%>k<|0C+G0=iHzgAvl+3~W zpFR~5`K9tr0rYZ@Mfx|G_$SZL{(dwQnZ7!Q`|o7%OY&=Yw@EOnDvg?79zHe|UE6Vn zh2Iones|w#b7Axtdi`X_5*L&+Faa-L$c^7Y=ltNxsdW5i%p8M?t|a2OSGfCol22}f zZurfO-`{Chp_VV5U)?Wx zp#A^SvE452`bl-(1L$$w9NSrN^Xr=}%J8DdlY0IlYHkZ$5-Gri$;|#i@~h4gb(qtS zjZczaOKsIqiV>Y(mj>v;^Ada}MRdkDyMON0RulO9%~opv&h`NVpW;JVRZd_BYhGo=BMCU_qppU zKZ?^}@w>k$>rAWk{~`G`{hKH1xmR+&tVkf`H?qE>(ya)lkJ7~UyBU0t{K_A_0F5Zg z#*OJKr0dE40{iPvpxqHVzsm3SM(XP>;NuJSaPsS$Y85!HR>H5_JMqJ^Kjm~c{(!d* z32*{rJ|BtS#XU5kPKYnHzg%HsFC=cAk1t%{*2f-NhES=(pX%Svf8PeLd-GZMXUY-t zUkXh7!~7CDzCXLWqi4Z!c#p<=27f~K`T6IHgW(tn{^i1%?@!`?S?_V^k9s^FpPDUO z&&GfM5BBg@awK&=%z-g(u=PD1-#;R}(e=1Y{AM|WZ&E*-hs}VeUZqj{YX{w$ja;qR z_$K*xyp1pHF^I08PtKo=V*4lI-o2Rmj2waQ^)BmR?uSdl$^wF2&(L(gxg z{9Gh4bh7b}7u@*X<*5cQ_^|PJHA9#HMouBm|YC|;vJ^%gbqJh%u=Hv3q z-1y$C)fXO+@H1_Gr?E;q>=MbxFTh3V?@QwQq@xAgc95>GgYQg0!~4Wxh4b&E>q7~A zj|>?KN64}DH;HeZrQ=b(dMu7!$MpY&3fcJ1J-~zYk{(;yd>XkM3y?=^1`dg4_?^_> zL002o#p@H)^OpxQ7NO6+nK*h1H~zZ?&xUF_X{`QTGJoDAnul6Go@VK9lHXD4GB~zB zy?-#KcnT8NC*o^kKXc~K?fpVvvKQT7w*52&`9Il%`+XWG#h)C3|6fotfBg4dbaEeq zUlRX`=SQQ(Ll5HkKS|Q{LLz^*Uw;^`I{N}S`Y`KB{7)`7LK{m~;{j%!=Qr8&3-3iG zLHD&^QA~dZ|8mak{Q1C|QOLph05(?ZCgVqT|L#8Lv+(25Kj>?EvoyZco!Rqsk92sW zrjuuJfP#~BJ&FJ2Sz>smLj%vA%kU@3?;m!pKrzudIP3LFPJU0AR}H;<&9SE)^ZCjA zIof6!I#6~2=ilJQf7X>=aJVNO|3wmCL~p17zu3WiK9b)Xhw8!09~V*Q_Z}_LLgQ-Y zW2;9D{z-rO>Um=rzQdpDPdje4LR!bR;N}ZV{h7QU+q~ThhD_Vax*wj*uj5lEqd7^j z_>3Yq{(UzLhxScj)bpEVw0z2g@WwJkEV*@JHg?B6$F6s0hZnubJ1EBl<6jmuf)XT2JcvHI?aI&>1-a{tK|?7GnksEV(w-`*RA$*lq>wVs{n)Z+#tYedXRqJ$ zb9q0`)4BgHkMn)~`?{PS>G`}qZnyh9?B`>?ubt~cJodP9{fjvM4s+@VXG$D}`R%=# znnZu8Sl@?fjDr@n@wB27^B*ece&V$6TIBgqG2bQ%eVP`UL-Xc5QS!l2KtfHP(@_ZkDu17{Xi1{AS(i=7_^4kIH-g0n08QEAIznhMWfDTp_v~_7SC13o0;(#8J z#NuKlgmqw_502kUHgYKUHW7^d4DHP zxL>FRwS@UG+4S3mLg_pp|6ZMKNY=)P>tFWo0i1pi~ zz90D0LYmT$`F9mmpPv0_4zZ0C=jZ+#J`1`U^L%6fo?aS6>Rv4t_CFu1nhl?Ct*7a$ zmGcK^zI^=rXkvf85`qV^&j<6Z)`rhv!@EcP?4h`wlegC(rkV8cirUGLL%QmgoC~!A7z;;5jU7%lO9ed+H@U z(7TjOn_R0W=`ZFxJ)(qkzWfWCXtVeo>-YX&hG2R=m4;ULkj_Wy@ckoSZ=EHvDs5B&Z#xM|_p9rsu=Dk40@JJy$&gn`x|m zh57wEvmZSAbX*j=%rzensq`i22P@^xbypF80?SA2bH9i(-D=clIP_R=Nu36FxsuheuZ8 z{Mp{hfh4jA&oAz89~hf;VZ^Roox8eeEPL>8JSnDgI;rg^!=T z)E5)$dBwv1FwJ0ZD7{la(_L$&_!-~-X?{7LIDV`Y-k(!DxF_6r>_T;-<^A=@(HW$t z;~8Q9i3zMD0pvE^`tUD5#NY3E=9^-FOA808*@N+^i}K@jzHT8SG@ruo`>cM2{qyiX zQ=t8cWP1N4(^niH$0Z#h^}E)mZ-UtKaedmzYbH#!&!%L9JfGbIu9Bmx=m-)zpDg=FuE~SU>Mhh#+%ki1{09-~h!-vT5|?2eSMf z{+LMWR#tNJ3xN8+UT*FM_Dfyp)T#3P6&}naOXlY7vL|~#_jmC5>rHOspz2gOZMH~Nd7jtL@275%`@U`H4b6Xi@&5N$ z^G{@RX>XeF^56gG`5V%40cf4rMvtb*^QXTDqbh=i~g9 znWDd{ZGfw=Kl9o2E=(u|NJ6 zKZ6wZ=lRC@X|0W}q|8*z@2l)U^6poGus?H!gFYPn&GV^(`n$eQjv`ie;{0-^uMuc8 zkE3aw&&cwbqMkyMR#bBJ82!Oi`^x!)XWwT=1Pe3XC6YP^aBkKp|+=CfNy9|(4K zriaExNPO0y`ciOiJ_(v#4KYS6|Bu19oh2%7S1k+Zt{I4piAGs#?hHign(@pwU zrJs-eYr7rCN#(tIG{;b0A7=$?WSC1Ex^Ni#{$u|-S#=qNG~7XJ zx4TLFVtriw^9ylZBj(e*Z!{z-?oZlsAx>5wlN@@Gb`PwD{UK{Mwt}c-VtqVbI)Gds z!RsTAUq|Zpf=Q)zRP8&9?=hc`yNx8*^ZkVNqwktV(0Ok(jd;%T`}xTK=53lpwnU5h ztXE+Tc{7&Nt3z4*iupV+#+0mai{tu3u>ZXqITN({rP1LJ7@yexI&0dJje4oV{f0X~ zyOET}Ik1P@pTW=1?~V;67i$ZI{g>N&7(!VSo=>cw;nQQtDjhMOM{*p1++IPKw!Xvo zMDgcwmsHX(POP8F=Lf=*?Q>{g4=tts@%wj6eR9dc4q`s_)(?c3d2?u|mu!D_KH~GF z$tKdnuNwA-Gd=ilK>oB2pTHR5-WV$+8(V9*EY{fqsrr%_+nvfGim z^t>X=Z=Z9g$n&#eeoxKT0mHCxx+FxN->n<(lHDW3@#lbSTPR(wc)vSLRPx8?hqqPy zAYI&g)8E|w8D3vkrNqF*<;Ap2o$-tJtHqRSlAFn5eI4L)3bxNlIN=j*#;EbR$t#mA>uKO=MJz=RH&)GNVRIvj4BrH zr+F6O2;m*mX;A!4iEmxRcV;+~G`JjffG+&9KzW|$_ifc5 za&2yJ>VEH^e)IggM8`ppRWbE%$oQ>6^vy{SmVx#u2TCesG)9Cq6zc0b^J(X&IeAo#odt->UNs z$i}~mh4+gY&$osr2NLKr{|idK`25q*P)pKwh&aA&Z(s)lwUX(A$M}+QuT}~9{uZzR)&#Gkx^8bJzVlK1>!!ApEZHyi z*BVQv!N$#EzWbXdkk$8h!uaw3K7W2bzuVaH5ckQCe(kwe;v4sGzRbuV3+nRqUF@$v zxDADk?yj_@lRV!~ny({Iicdp=vcDSpYlD&jFu3b1>a{gY=YQ`vK>B^_I90+;-4zz0UW$EYR{L>+o3nX=2J-TGHyuYUX4Pe%G zo^M>=aVmdI5;Vko$3BgPW>*Sng8y7uzF$Pvfjf(P3+E#S*(X5N$DQ=r#aQV)*5}nD z`;p{dRzkkbf47IQMic2lQ}+JA@voZ2aAI^o%=f6O!SHa3BMn`~{{GlsuQ@k?XzcQZ z_FR7`&-daBCSYq5LAz(N_(ucjx2v`>`Ph-yZ=9d%`N<02ro~ZB-Ln#3*k8BoXGOlW zMBs8d+ zOJj`&DZl@`zdqV$1M$q{`Bc&4_iI#t(}KBw>^VMF^mzTPX}p8jq>B0UUOf(VM=f7S2Fv!UC( zB-+{dlEgQz-)4V~B0YS?e3$4=f2-|D2l$j^INN6qd^B@4K9A z;&`!w>#xH8deG)EaIUi({kw+ojq_W*-3rLD1w7waf2Wy@fVz8}Xiy)P-_k|;8@aTY z{9alOQ@S%gYEb;FU1um{teZuR1DLshVZT4le{FS1ftTvV^kNtJ`Ka#i z>O)g?G2f4m&x6h9Gw5tB_I|+nT)AuzNogsLpRJs`z|UfBD!LzFcjXw8nC>F1{}zuM z4WAD<(Qml|zVGUhg`a%6{1@hX=zUXA`@E2zJo#GU6Z`MOoy|z-uEoOs>7*b#@HC30 zSCY=i^4%lMo){=R(7*kzSf2yq?I2@DEM2aaBb~?o+u)izc^kYO^eoxG59{}}mH{w$ z?@HPsR6f3ba$o_eI=MV;ShQM9blvfF5`Wvw`Q3v|9wyA5WkoTP*L80i1~lqdpy|3^7@YXxBt9} zxVoQ)=H~402WbC!6Q@xSwR1KN=(AMkfBqZu|JSXAq~=z0^(PfQKEEBGISeeC+S5sP zTcqg2zmeml^MLey%;$z+^{E%_ev;`g?yoL& zm;=wPlj+1O*2?z}ukVi@40w(u?f##s2(7wE-D=PRxJ)m1z*?zJN{$c%|fz&#xJ7up~KO7YqA8G&egyj9M&p z^^xa4Ki-iX*&GYcl=su%{P#cy2iWjFhVDMGO8I;~zt-)rH_^`#`*;20f#B_vL7Q!v zEuD`<{g=t!m8pS3&&Ssl}7`)?)tk!e>G9Jh8u@ z8Uq5^;Hwqxp1yu z0yWe=FX?|I%CB#2v6hsW^7@bYzgjv0_TP1)``-1}VbAB|`?F!&$&w~w{&j*z!{`D# znzDPL@;o2kZ@jdROn*=f>P?ycVf`OGatwqg*i*ZgjDJA&v+;hX$+{nJz@bo{|Akp2 z;ib1Njre^|dcF$k-+a~lE;%+q?EkZ71_10%qpLn>D)pE5|INC6CeLGA)BX3EzGD5? zv-N_m?~>?w19|4 zdmGZ#mXGi8{AAgexlrUBN1d}-eh$~yMjW0)CT$n{|AX5dVQuFq>ROg5@r&!<#`Ocp z8(&`kbF!&RW_#Qr{bf6?RRiv22M!|A1UM3(=G z!X)C~zCgGiuvfGbWDgem|9t~8$;^>r{{JQ#L+BE3+ShfDtp8uqXFUmTSpiLt|I_a# zT>i%7Y!Uf>>l7?)`|tnr`hIKlNVt4|20f)0DDj2$-E&q28S>~R*t#-4^HF@iFLoT1 zw6mvS#qxZg9)6abIsS&zcbtEp`eHOxHnOF;AkX*t+WRE1Q9au92YbI@eSdqwAIi;^ z(=FyKe~0y5CF2`eA%|D0Fu3;7YrwD|%X<@<&A z_s5ng;`7Z`!uiQxXS&0csblG5<$Reg()U3clgZ$x&cgbdb1OYa-r+<;+OzL3*7r%( z)5vE%G2gyd?O=bq#dMR~zx)fY?~Tgs$d^xxg!Q!^zuZZ)0fY6_3SZPDeD0>=vy|=_) z4eCFuGAJewt50$DF&v+FnJ^aChFjCKdcm^%e&2S8jL*5n?Kg--{9d~?0Tve8(c%U2 z{KkAePXg24K>tL>KlbO9oyUR8QX9HyHse

    GL7gM~eCExz}_D?KA(GMKHNN#LvQi(<4En#8DOl`Ph20bYtjSKO2^QrL%&MjPs}e}VL%)oI1BT0$#Ih*AXRaHQX}?$ z#{6DUw;<0I?xoyYpEQE`Mk8Fx!KUsVu05fX3DR3zb8{SEu` z5h0gIg^!s3wtMxV-cu)<9C2NGKKAF|;0ftkU6;O9_HY0H^!wf{XlSyC7A}(SkNI)v z4~cHwnto1|=YRg;DUh_$jb>cyEWJPQ{Bs9KRY>p=$LGCT2ZGO(BpQCpik(OP{AHOo z+4f2ipVNQucg|j^OuW%ckq{h5H4Rw*Hz5749BWKY9~AT7!%-hn-5uxbIgC+0%v&DYY9E|HeEW8`Hx<=h`jC3`*WP1pSvd!UPtHA=Oy!$=Xre}yFZTH z=`XI&IsJ5pZJJRuBKx@H&oTdYW7El^YBB%n%Y327IX*te{5!VDBZD9A;PUhNx_p1k zy4i*>X6tNfvUj^I|JqrbNdDe(aCiQvpS(Xe7^x4Z$2w5$%)Syos(O5UzV`GU;cH$*S*)fLg0f%bn`HIzNC{yawx9j|u)f>vnG0cq!l_Sdkob;7`S`rtFyhF(+uB7Oh!k-l4Bnn^T|`Ed1j%s&j816SKGq}_YIkR?YexICP?Sm;T=Kd!%JStXHP4aEMw>v&JtoEJ_T#mV!3`OQkQIyzt2U$^mA7<7D- z!10gccU#kS#QfS0uKxz>`%gc82#Bzu-}i5n_#cY+@Be%=ap?vHU7mlhah8xDHkZzsCC`6eZF^9;tVz#s^WA*^`|S&!&{KOUZE%|De{9^!s_%zYd812b#0U zDPwVbKTvUZmVN(FuKteuZ|*lk=6 zoSnz~|5+79%1)#R`{#6T`GA9K1nqNUvcxyeuOI)IOv>+O3;XLl4*SC+lPJ1-#0gn_ zkBQ16w9A( z1DM=&I<1-aLHhpJAif(GIg+{ceISgx|B&y0|F6?L@@$4!zk7G|flAlKG`N;XKR*)X z=jxnZNNPXE2=zPI#1GaS2&ZqxWGK(`{(aKO81n5|RRk=gafG@Wyho z_HVY(zpEtsfy3```c0KeeB=0BH*^(QH7Oq)m$UZ|=KID61DHssb9}3)@cUDSf5|8F z=ZpRO>l{PS2%15I^YSIWYf$~XU*GLSvtt?D-pJxJtlxTv?cwE9Pde?;Fo_S$HyOT% z*i{^YGoRV#uYve>N-&0VQPy<(So!{$stISwbH)A!k$&erG6I*Yiu|6tJl{@j?-A{| z*Iay#`7ZOYhl9zU^mpVv>G#Kc>zt}3EA8vj@^dVH#`(FKT6XYyf(H%$SYH`G^ZEIl zgN@)|x|r|nm9yY{trzX8*G+kzpI`Io)ERcP(4uzZ3a-MwXuGJfFw z`vvd+o{l*#I*4d z-oMr2#SAFiF`Hf(a9!dL*U!%!@+JE(g$e6x!)oTi`8x~fw>gKE=lTAb7xkBr-7jLe z{SH{af0lSbs}&)%X~A;od=1)vcJ@LnvCS6idt1!_@R%D;lUFkTj^p=c(P?DLscdfl zIF8>}RJp^6m_TY6a6sZ;MTMVFy=0b4ez(boz(~e_jcy|@!P>{p7|LQ0|EPb);o(M7 zK1{6dx1Slo&KA>Y>#ZAP`9F1{kaY1cg{Dtg{RZ>zW?o7LdLD#X{%pPh^F3Z`Dx6BP zp`EirCBCpfw|jY>9Pqix?I*bId$%5LgUN6gU(DEImd+i<=;Kld_wBIE!K_9}enbP2$T_rwLkUy`T zwwFw4d=LzKFuqlherKAP!NE_~v{O6AcRtF$4a>Vk{>-__-5-MaF1}$3zTPwF@ML+u zYcd{@x~*TsN#*_)tlviV4sbPTF75aAw)FdB{WksbgG3Dw>-UjnVHot&{-;m;eza3oiv8A6F>tRJ`~R3<{rFHgp{UQbey~FN`M5r|q(LI7 znk&}drB5>y^BvjTdQ?fxwuq~L1FC-&eKvvLpUr81LwP<;p6w*wL-v4s6w7~NeXXox1b?2J(qYw%&qy7< z{?%j5eqy57ueSFo>rcY-r>EOn!50fVYS3+w#77O{^G59zGJNn&?*1;!=ftbdFxbhR z+K-ms@3L>?Q_|)6D~?aBzf0R^fNpUXZLG!W*Z6*)PhI|yHwyjj*Mxn)^U?i2p7m!# z%F;QsS*vMIGV{gd&YX?IM(zR^5u>Zw+%UBq7alCLorSQE2@s1VqyTR5BGLKl$PI>J8 zi~V&o@FZgw&J*^(yl!j@Uy|+UoML%?|HOroa1XKmUfW>@Cr3F@mBj55pDHT6zs~s^ zMV80K2G{}Sw_cw~?%VPC zGtB=O%@9cayMX34JS?lvM<1>uvlaY{{Pl-U<}ffu%zxO1?ZhOn2-2!q{Dk?>*lY&# zTUgSRvGV>pd-g7p?^Oc%t3ONsKCI87U8g{Kuqo}an(>e0>v5I`NY_P`P^fTG|Lc#z z{6AZ717+Rqs75=+KOp|KJg<}K&#Jlp7tFt1b64=$J(spdD-}n4XxSchV zhCRC|eLrfDey8Y!kyC#b3iIO)Y8Qe{*+S}&c|zT(F=fedPJ?Ii-a3>QVwF z4vhbNS+=UrD+`C0I^j`hfZ0RXPLqFPTBl(jbXnyno{H zmuixFM9lw&b#Cy()s05)XZ%N^`4qcdugHG^uekfYus?4<*#$BixlpYZH>Ky}`dHfr zb)oO0I>P+gvVP8B{MLz%7+ObG{~HWf1&`)pe}0t&0*wr$C9Bzd3(lXP?$;eA|5c~$ znlb;5`ET?-0JQc5P|e?re_S8Sv9u z61EuPj2F_vIr97u{T55gjl}gaW1CQj8WluWpGZ-@fB5`*_rJ@@k`XD~ewlnUpW@@Y z8tR7Ta{X^u|5v_WMPln`bNd^y{}${bGv>dqwBxFZcx(vpkxHydV%p($?kvhD;x6zL$r|a?h zo{#PyxYu(5_zw=C7G=rOdF=0lUDC*wx5+|%4-Q-l3EOjNqk%rk=kxiugp^!DZf9}x zXP9qyqeT!uDVUy5t(4XGm2sQM#T6Tb^DDNhHgNd41sC6AeP4NT7kQLb#Pzq$nRnpR)a3*x#QnbA%elnY8i&n{UB<-+EU?zBN24oIk(% z+8WxQw4epw{3ZUdzUvcLq8-y1|5)E$TYVsN$BX0pKXrY<(9DDO zo2RUw>G1yE?Nxo~zgNtE%6G-?q=}w%*RY0+Kg56bu(t5ApcVb7A_Cl!94WtD{ zN_|K1z1N{WaHy;&b?wLU`+(wm{kyT?yfup6sx(nPpRb?2)3hh%W@3HMYd8V)jYiU< z(`-LH)^}4=57O($Y%af!`9HZeh`2xY7Us_r4%oq|CziDOi9FvObt1`=2@Bz_sXX86 zg&wfnMls(!e}}{uj^AC6CXfqvqGA1K7QbS?*V!(D0NVhX_k{5cD8Fw1Je@4wpA31U z*m>N)es$_v2-~)bcAxCU_(uC%Cl6aq?DDhVf&u&eG2f|C5wKx;DE)47NS5y>T3bl? z=nW7b!p>v=9x~P%Ow*@ve5>g3_3`c3OGsoe&o|a@m-rd*@Uv_P11QBpI^B3iP$yg`NjTx)wO8QP|W|WIrd39kMrj z!G~&=u=*H|&rjZM2kjzS(HU*!`90FLKm1nF=>pwG%(BtG+zK9{99 zkh?D}h55I&Q?;Sh;1P7{GUl%^pO4+W$SK7gqB&vzzCXPG*4$?S^|l#OhvQGA@9%a! zzCXQ_V<@p(!s|1hKk-m^fIHEaG_6FQ-`l&Qi1Wn-5Il%IAM5kkT|qGRod>NLRVqDS z1@*W57?4C-Bt*kPZhnftzhHJvI4sy0Ko1X=_utP{SCXM7u>O9$AL4dp1pIIhqB?tfDfN}_Z@KimKXl*SgEs!o&SQPH^jZc@ zn+4MsuK)J4^ZHy?KTMe&vsha!hy{u9G|L4 zU+2BwOM)jAar=|=k$?8rnhE|Pru1ZiyuLQtv7bD>w*zV&o>?wV} zYf$|<|Mq2~9?bKJ^>=y`cSu<_la_|b^I4_)nA|@q=5ub~9Qd!L4b@9x^CMV)duo3t z<&iJpXWM`J-<-?u+>coTwOf3tUfU~F{5$o@Z^jP>DxqzPCEMNbc__T<`JXz1xzp#H^>S+hLBYD2_k^TmMR`A(X%y-ZI zc5q;+3C*m>_{RCKV_64Cv-LaR?=bfHWBna)&=s<3rqgl#<@rvSe2w&-bwaqmr7Fi0 zE?SBC-f`$DX_t5d4xDFvV*PCoo?y6WCM`(Zsv}qbs%rO(_`AFm=D$a;jDl_-0_eJV zFQoIB@8r(SV1;!ZdgTs_PqDx5Rof9-PH90CPyWj<@%b-xtvK-8w2&T%>&N&<_gfbm z4g%9IVtxzO!~$8hfMx{fD$n!!+VJBX;+146+>hR-zYe5q8$vVnS$-Pxdnz=5#Me4< z`E5M^W&6zvN={Cu7e6t6S0H}Zd|yiTIeQD|zv}BMYG-4o(L$Az5+6g+eupdL;z^I< z1>*YF1#kFz!0r<55<=kfek=ClIRbBvhp8;{~Zt{+_#>YR`Rg&|I#eDbl^ni-} zRW9WLUykJl~1uW_=R%51L^mq z>@Hx?tR>w!o#}U^F3A$gmKDaUg{`6Tyi*hH+@(q*RiA#i~uzuxo zP8ag*hS00^uaUmrx`^*<9U@8J-(JG}*Z$c~0NSRC z{VB(#^LW0?%sqiDFkT?cf2rtt!!PO@jBv7|*Vo9$&t0~wfO`Y6en;<$g`$~(^kqNB zH;$hVy=noU+lc#D)VoAOz*b+n^ji}pe|-PijYKu@p52oAt1^F$`EKZx0OQ6lpj|Ha zRi5YL=lupl;g^L5)y!k>2h6{5>=HPq*x>&5%y8+v3d*1L(eWg|pIE@256r*f{Y`T! z^%UAan66sQ=Bsi1TwV}L4qtQR{5j5VPu@8bwmi|JF-A<^0}%f`y`zYeVg^IFzbVWa zyq-^?#T|}G{NVca;r>bFO8x@w{sf#q%Z~MhL7S}qZ@ynTkM-TWRR+1|9nJNps-XDV zZf63t_!LanZAq2RnHtF=jl zMnxgiYKJ`k!FD@HPP5ezcbM^y{kxC)Y-oDch|_n>|A)PYi0!sQuD*r&e`4hXh7XKs zV9(XE`hM`_Y0@uhFO-a9{uT2dUf~T>G{o_FcI!K2_^0E-`c~p|e^|PECfygt_{aJ2 z39a9fQ;o#>Zn1A36xX$)77H2wfa=?kFY3VHoEI?c;lJOXkIx5G#X-vz0n{Xy`F9mG z|9K?175w*AMcltOFB#~AFq%EKwUR%cf4@H6AY9?^=Q*;^PeqT{_u9L|AmMp;`gWi^ z-`l6Gf}v^&w2zDYex~^S-sEP5nD6^N4d9B^V0yhit3PAD=l2LB_Q{UI`LA=8(L`;o zm#{uPL2EWdXBp6dW<=u01^M%$fMoJWaYymL`D{S2g~YNQf=b`#;*!rpVswR zNxU`r`W5E4?)YS=+#gDZSEWhku|J=0vxZ!2CFa*ydn<7Ou|7vUiid-z{ApOr3Ms#h z^||wzo#f!kJct;~K3~k|C?gjbX)D&}W!sLBr6Gk}e;MY}IC(BuOf;pg?d9{^sd$HMBfxq^clzfB`}}KA{W(x08BCHw>F06s@pr@wUy_q7=J)DeBPfX)O!qEg{NngK z)L;o&Q{*VjZ|~37hxGFU>9`v#|D}uOv%fgUl7mrR!u)oc;(p8PIeN5*#Ub*)?~exJ zJ3wnW@fgYLGv<5l*bQKHEroure@i-#`%hdZWs$_8ygp-p?wpn{(!5C?TKI0er>u$yONx1)U2z>oV z`upPg)V6V-NYd)-u>BzW|2Y4(Gu#hCS6EWpTWmfH>u2b(`ml5;ub-Gt_eS&VP;Rl?`)#MAKVpY`+PvKjq%)rPwc_O8+YR7qEX`q?!%Q zUPRMpPniGBM|_eQqhRI4?sRCHJf9CHu7V>UVyNaRbLPL1e^&c%K54txLYN;rZea{I zmV;<@19|`4Zq!opX^>c7$J-jg%!OLi=@_dYVLqc0;)ugIar|sToWNv{9&Nas@o9

    (Q(B0ujxUcwTeh zRfigi^WA(}sjB73b_#9h2W_m@$!~afn94s?obSW?DpY14Ix0feiPs0cvI;o^djnN+ zXL0}H+PGjS9eqTre_<0Uhh?6p6#1uUej4X5=EUT4+iuoV*{l=yFJ3lV4rPnaD(c$P z_ze5E<;iPc^dL~Q^1jHwf2^N7XU2ek%o&Br3Cgz-@^721kA|&PS&HroalU;=M#F{R zEX5re<$F8g`%(XBsIwqT(P`Q${{F6r?~YBQA%e+LTsj@ZkK_KJTWz<(x;?iPTd!09 z1D|j8Y)b%)nwO>+F?E_|zL5U_r@e4;U8&+wv<*w;N63G6LmwD@>!4!AyMg@tGL*k_ zw|0OmzwL^X3EedFh4J0{#KmBjm!KGVxg$Rx^WP}Z39^h!bc7t98w|4RzJ^%f_|)mk9l9&nG3SOZW8@rB&kf$IcDv=HF@4 zQPudMIR6iAD^;w@Kx=-lcTNF!ru!SEHvgpGuV8R=OH@djQ~w3~C*yk+aFt7{mER7E z$A3-Jqo9|0l0w`086%$-a+a&!D%V(w`!5;#%VCY>UPa&0;_{LG<~%pG&U@wmN)rG0 z!1c+Mz0~V_+NCLCT3_YgKlaa`ILE?+WqTCQw`6L@h3o6bl|;jxttGbS41M(Vb6soY?7UQd9LqxMQg4vl#lf}PgI@fm*t%Xu>pyGM{*UhmT~)kPTs|Jz zSE|l;d6lQFzS*{Y5x2zkqS7v2+&=8^P_OTohbziv&~fblBuWZ7Ms`7&J$4iSd^rET zeo!O?o|LQYlemBX`gJVqZ?jSn)s*s&<4?BwJU4OpWv%=-j9CYNZmm~*>U@R2KjuHe ze<>W=5TS6WO5w+`{kX1 zk$QjQtZy-jmr`m!HlqIOe%*ZGV9NkSk4in3>VKjCWXuFYukj&@uzS>g;QbvOO144n z+$6=9WDCuFq5UZHkAgY(qZRj7%lO|9$bNX_IKhv3u8J!zru=*?AB}9}kf<|T@hZJ1 zKVOFOF9FM1aF>?-Q1od{`N#fI)pK7cFrBDqWc-JpkNdONg+EmVN^|qH<*y$X>Ew?v zd8}M9Qk?JKCY7q6CaOGb{ZT<9FK`L34=XQMmGbw;@o6v55Qv{>CEy$9{}%ly;ARXw zsNBVf^L^AW9Nwi&SJdYJGEn~Is=;#5W1R*19rIl?dcAu8EFZ;xN3QYDhy9;BrM__6 zWTHZ{xYoZB>hI@|^f{|<&lLHydh+oL-k)_)!x#v7X|G7_L-W&kedv}M(QxsUoj`x% z^);dG)c*4WONCFkJO6xV5x;$u-k={dUJ<`Wmlfl88yg5WuT0j;@5sYR&@mxe@y=p0 zKOgs>Y#1eniYK;;|13vq-j8to+T=QND9!1qNRv@Mv42zjdm;3UZ=={!rK5R2!ua(H zX~9|N6e1mW z{QV`U|HN@erRrDO);w+bl}S@WVB7C5is2)v{>6NDOpbu7QKpK%ji`Rb{m~yRmcs?- z{)&~!;`;TtdVjznHH;$o(k=e?;q@<(xBMYByQ3l#Owad_ePl zh3o%gzsJD71AP^HM{VV=FG2mG_p5?njCW^+0VAj5$bYaj@q_M39TeRU&*R7O`mU!t z17X<)6UDmE^;zm43H9g7m|!r!(OFRktoix4e*WuaGLSYi75k!Q@bhv0#J8OsY)X16 z7Pl4WuhTeJsJh-vF-@QLr(*p%;y@HwZ~2l}C82yKBmLRtz&tQJSDa^mqETfy1Y&f;`;OY z5;>IrNXmQTN8|r8lpp!)?hJF|R^)YBEY9cBoKM_l-Db*qdTzY_zg z63RcH z1o7E>MKFwQlbBblA2ELqRwuzS-<&+(4%9wNQ2cf2UL=g}up`fIDy#YZLi@aUm@RO_ zqVsC^cfk3%!TLe))3Px4tFs9|-vsRsXta0%yzG;cTWTQA--Q-(Fg3cK8>%DD-`BHF z5Eqx3yW(sWe|@YUckcPbrFz5m1M;knx4uST+^Fe39pZb;)2{`oL}y*d|hT{m@9xU{781sq?EN{EJ? z0XK8K!ziCOk^dPnIRZ>RUd|n6P^7uOP(Q{k*5_VW+U32@73Z_vF;8gpJvX{0&uSU+z362~n#U!J$>80~+ZjBSI?1^q5NV0(!XC3H#D&$v#OIge}^Z;K(Dx4=Bv_*>GwhW?cxGpg0#TA&sGIL?vM22 zr~STQ{6=NI@60iN9P7tNdEUTmQ<$%{+DosG^kbj+819DTwlwm~eo_DPfBcc$a;Y}{ zhCf`WK7Tyd+~d+QzJC*+zx{f-H^{sc<~DmNpJj;8*)|Qhwc#$(AGQ7$;&W%a2-weE zHh+7pJNu6>>|Y*s_66H4mAU=F!SwebKF?gWf}!P zzViG?WCHg`5)!ur!W<)|pY+A~EnOW2S(9U>V^b)m*$w;Z8+#a!v!{MYpPP=0s9 z#3)$aJ65W5w}$rjApi2rNS%DA+j=CxO`Ok_YCin~si$pN5O``N<##Chl7yT{e#L>5uqqq3(|~Y!EAr=tu20?mu?l?G5ca1xVvZQT`-| zKh8UbyQH_0Nw_4=-+^aw+@7M1%;&A*`tQm*U@eXUiBdi_u{Kk3NS zVhx|d_4{UP8gN^k8Z(ZYsegsnA4P?R!;zuU(&J;r`TK6O0H&W_B%Lvj4~ReL6rk>Zd?+2!sgvgV!v4q*13OhhBhLJA z5uK0os~ev$gDDp(q>ZOgKK+q?y-_$vHS6mIbLQJy${*shCUzM#@~@EEbfA3V{Xu{G zIjeM@6`2nWF6HOTWWxOFlx|Vr^tVEK&sWKhWBZ=aty1;1bh1>Ne%&``2}JdJBKtp!mPe%IH zL%sjY+l1%Rh4*^0|E`bi|BmbKknVU*+HO!kem<_BW%aR9?dh*4ecSFk|9#64ziZU- zoz9ik%#YI@H1mc0ehHqbdOo3^T0c_0Br;+AK29AU6tC{WT#TXorXqg7mfNc)=Qfbq zX20a`kNwl3qnE+hiq4F88Rgp*o&Pgqxs$5?LPP1ZH6{Ff%#b?wTOw!6q*|0c5UZ&SP=V_^&C zoAR>eFSD6PI*shKaVPwh)y25-ZrGX>_9Z+w2p z^>5HM#;myVQyZ<8+o_(-kj%`-(*T?IV9Gogu(S>iz*nz@Hq|cV2(7SG}y`D($8|W1i|qp?{dZ$q!6N zEMd%-Q2mDMJ3a}sRX%afQf9okeO?f`47|?AFtb`vzGO(hwfSbJ(*5Nk9n8HD<*TE5 z{&@BLTKkOoGG0Abb??#wY5(nXeH`AOB>7AvjCYM;zR#n48KM2Vs}d_!v)@!nwdL3M zE{%d1i&&;ey~h*(e$e^`>CONcYa7b^XiVelji~>&=OXp_T`&BY>(kHh@7ERSzXP%3G?qgj%Rbn&*zb3vt5*Lq(9@-_4m3H!x?q`T{B-;zf84o2ZMv&O#NF_ zze*6_uUvy6c|Zg+=hFzyd|~{);^-Vz%XcfK(~jzD-j9&~0R>*LZtr>qrnTkAG5^21 z%~4I?y;9o$>JQ2X>JJ-e?Fo6RIObdby8L{+e#h;zoyy}`jDUY^-#0y82A`EXnDnJo zzhe9TzPqbx)`(To0mJF~ILv>`yOB`GWCt@Nobr#)r}$rg%x0AVqfNiEZzG}qfE~=N zW|aSA#Q)P`cW9ipmWe!lmH&NZi2pYyZK3{(Xoh6b`WeoDGFCnivS9; z$nIyj|Jv~HSAzV9sGt6-`BjIdV|?rJ<2e3WROtcIw|g1ayBhm}^7~6%eN=hp4oKDe z>uTgf=s(nVP}jdoGnk-{ly7U~zdjq}rCK$7zx2|KYR!CM{8j%$B#f&(A@CpY`AJXJ z{f`5VbYQggKdxLA31&M_FriP@^Vcs!e6PFj4pRs174VJgQ~lNPr|bF*CfA&3o=>=b z?Uz&z+@VaScKtq%->O^J>6MZ2;c8ICXf8qM;u4dj~c4t3x=*1rT z{g8c_Y3UEg{0=ks{?Piq9La~@o;c3sYCah@Lp**n8@d!WRUcu>CZ8k!_{Hm&_0{$x zKI=9aXeBN`LmQoe#{+*ci?>kumLdDlW^Oijs{S7`?bA*Tze4|Ib44NdXik0hw-;Ss zoQ(8)cEKXh`*@B~Olhy-Qy71(`|S?fOHMJzXHq_KeKgD?SjAPTq!uf5H1mag4m}}< znhBSfgNzd*-+1`wRKpbtDo(=bab$AFjy%_@nMWzm_|Qsr5hP zsQzRh8wtP1oEPwEjm`%ev&Ip&W*lLP))ny2kNw+AwthhR`K`vO5fHhp zi0M$6%kPgakqGOjUBhR=)X#^RCq;+(>tp?W|BxRv_0DCS<+T2U`%_-0d&974XPMgk ztOW7tbuR+G<`gksvZOp;a#nagWLhIXX#6>c*<()mO-B6wJst{E#uYFX+3WcE5?Nb; z0eAi!4Y6adFx%VE`B?v(_gDh*Xkf;i&!+cB=WBC+w{c#|w`9sNalUt(2EoqvN~Ugj zB|qN`ozG>uDVuA%u?f4alem7L)WZ+j)X!zYhjn28$yWy2AHCbqmRze3UZiwsxrR@n zejj_x1J2dE#MJH|i~W<*Tk~P&+VjljjuL)8=KqyZBhL0|Fp1S$t{E5Bw|c#bgy|DX z1p3ts@jLjpdi`3w1yj3!Ip+7svPhU;^+dq04DtKyqaElpRWP$hbNu}=zs6f4q3ZV& zCdz_Q{(C8`HrY-L?Zm*v6&*zW$%^Vv5uT1VRCZs+~`4sx^Ctb3+UDrCX*0l4=saM7v-Yu^G`)3()O)sn_7c*n|`EsP+CzPxASGf9BEB{6fD^(4S zJ2TqyyNc-%Fk#{s=EZR8U$`RvN0it@)x|r^)|UDF{aum&tUoaV9y4E$~DfmC|HXH#dMlqk)ixbO4$-<_4^&;Y?YSvTWnU;_`FgvI}(C z{E%_@*+Vm582{cp>IIP<{}aTwc>QTn$49Ci>lQHaj3dtnjxXzXlSAuz^@-g)70)Nm zuS|+i*YDy2wE8#47OB@K|I{M`EUA2KNAmI7+!?MHS24TV)%GU{&oA{;g+r6QdSvql zbN>EvBp)|Nhe7mRT_Wp8`xn0>`|z@HxVpbgk2FfA@*zRz!vxN?1*gpwOu};U_;t_= zFIeFCA2YBe_1|&-*o^8R82Yykx!L3lZ$Dho{`tOhm%#ZV9dhm6aGp;SwEy>99Z$Gn z|BW$=m>^IcszXY$S8L`A{hzPu_5WY{H6X=vHU1Bh55Jrxp!-FK)Rl?L zN7S-d@Yvdr+$dbb-yhqLflk5D!CZ&b%7-DyN2X{F8jalkI$!Q)N2uZh^S9$^P^b45|cyW zWLgt4EAbpJUos?LE&Y6;x@mplUQX>(8S>9Ojt0VVsUfMV8OqBKKA)m_`yjX+VMr1W ziOX02_R)~JvpLD{Pwh`KlCPE1m%yd`M&#>P8eagiKbLfmz>0_Ci2a~b{QJT7C%G&H zo~JY>!G^E+=aZxSQ%yn)luv3&EYdchzP8y?ox5t<}hX z>vuH;TwB?Y>1U{X;rOMw#WRj`jAJK;X_2ps?>I;IE$rWAt{VF*j9p)dj33FPlAlE20`ZDGfK zJyKmk?H886w}xS$d!?N~{_y!s_T?V%r??4;8ASa<+<&#MWhlf9Y)5_!qVi{r!sX#Wo&`RsBs1OjKYCAW2Gek&Qt=fa!maIknLiI-6M#P-i% zcPt!~bR)V)Xn%v870O@WIUk6LY)10>>GAS|_g8Ip?i?g6T0l%ackuTnKmcZXK_DO5#5S+Cxtw!VP#0}Z47 zzHe^+A0}?fUeM$p72YHXQQj_auV& z2+7a!qpq+qy(L+?=LCO$oS*&EJq#489s>C>LgxcMjGPaBH?$@%l+^y={Mhrxp^&KC zLm)pHNPb!$4uqQdT}k(A2l@NUQ2wlF$`WYQr@O#^Oh)oEDbE9pa@&$)oi_6GO_2ON z8nFa2J9H-jPu6JUPv}3|w2XpnP5O`?-ZVZdL-M1X7y^2CyOW}G)PIyC`7!lLhw=nB z^53qL{QZ+re`KP5Fj!f4BRhO)d?i8lO<#5zVp;_f={t>ojpXa~Szj2?(u5@0=(GRq z8{S_kpji$CZ44zLcH;6C9K9T@vj>u=R{i<;xc~BG4|RX*u;uLCGve}h`TIQhIHWZR z9YXUHGGyOe#-zfz-2uef)tUeOxW3Z;X&D#aX+Qh9g}D43x?6`^IV6|3^acOf@!5xy4LRa>iFhfkHTM_pKh;&;fBxg}K|y?m`+pv_UIqyRhm(Pp z;`KknLknPkogU;s*meH;IDfZtUpOrE8Y+m-ZX)^ovMUi&;w#r?@FBXRlMNP;2#h8gkhOXItZNIrel^*8%xJ;}9M zRKD>3Yh7(a;Ihpiq90B3A98g5*GwtJk7rB^gU7)`$RM3uUcO~W zKAoB$f%C_gkhL?YeZ&5zkvteG{+N;4{2-Rk2~ioaec3YdEP(nKcz?q1#=g*CUmxQB zmD)cnpBD|!!2{0~Bxo6}?@G}6ri+JHgLQ-P#P;%F_Md#?{=EZ|BJOFu4Q%`#arsd% z?NUkp`04`o!WNmvKNZTKV<+|bI17$xwU3DvUa&B35UJx%{YNZcdL1HQ&_R~e<_B^7 zW|tZTm9xeWpPSTvW+40by<#E6)Eh_~M;sHCuhuq!;Qe_7F<_KDU%39WWOf+%P9_5R zT8+*ZEI;B39WM4J&bbHp`8a-ac3cWWE=kFxb7%SZZ99^$c}0sM`ND7#yot`o_D`

    6}e?8%>N=K<-=+H2>Xv#&H>QQd<2OzUB^E^ zULXB=UMM6aFhnt%_QzoRw`NNgydJlPEVEMZ^RaxjapZxd{2pfV&60j2QueocR1*F9qvQoZ-zyE3^UnQ?IVI;GPJThOY`98w@ zh|eQiSY^|d2=;$Q_O0*5RFGa|`djUd z7r{qU8Cg2#4t;*)U*6dg0dLMtA?o_1l7D_=zbyQhLD;BiQnP)ghOK1WPyBHBl)tbo(Ilvh7-n}+Al!sR}+VY z0`q4QNtsXWmmJC0%+k4FZ#%*uUIh6$;_TmL%yAl`j)yzigtHfbCTak`qVcJDk6_xf~6i?$gPn7BoLEkqGx6 ztz+&AValOoZNu9d`zBofFfINRB(6yyt{(LL;`ppIPTfDdZ5(O6ist9>{!H=lC&4mj zBdJrDz8@?KRle>fctJ-L#8`Z z`H`Xh2m0QwP+f^C(3*dYdEy3kZsW-M7FT(G495ub^B=4tA$N{Fsjc7Q{Cx8C5cp(1 zlUTl@{v%%B-6Y!q7M?ICo{g#h4>F;D=knDRZZ;fEcK)IE!4<7ewfS<@Lz`NSHV-3!ffMNWODzV{Co+D zuXJm|z;@PZ`@k@!J58PNkWo%{IuX=24tVwMj}>F`NsPrv`bh4 zx>9%IbbSCz^?OJ9a@GGkR26Uu9aCAaC!2XbasN*LI$kjR`b1K&(~O@lLH%hLBFngM z#+SA7KgFbmtFgP!J}?pIzwNlks#2FCM%(_p-xC^eBSZcp$$csRxc}TpR;lV4d`)Y7 z^z4f|{+m37H1WR7e?RP>HJP#uroMC|%V~fv!DH) zA*Z#4TK^p5uaEi9ndAaYtBE9{>3)73=NH<3c7@PLOEPmT)nD5Y-@jHZhE1OKWRrXd z&zBL>?~l#GA*S6tazlsu=VhoqTN)DvmCNRm5GTsF9QEJ4dK(C4n;gj>JIb#d@td$> z2_(LBCfg=N^Up6w{Eq194>f)5h;IF7{PVe@`ck$u5HdbGklOt{aDJ_#a|TRXw}*`S zP3vEH{rYPoXGr@!fmp>fW&iOjLHX?`j|#XpQ!-fl`{MleQ}++;+T=_wUK`2J$Lrs| z|1IWLkG#Q7Umnl%kMrBbmSx=KA@|t1d&Tv8X!jbfgKIh4)J&Z3ymn7jsm<>)+V)3E z)oaLYFx6#8S5UsOem7H9sJtT|YSr%%0~&LVJ?pVMojUQ~M~3<%qf!@v&Fi_ut>M)x2S$ML;Ah`=>Yh8 z+JlU@qVcyJ@ogFt0NYo1kk4ajeMg4$x1Dh)DD!>D$1_xa&y5q8!bwXXqI8Yne;;07^wnfBln!+#>hn!R`Tmw33-@ip$T7Vz zIv?rp@VAS>;=4Pk?a#sdA1Tg&s&=VFkxccsHTM4v3%FYg&#_sf#rdALYY9B`_9Bn_ zk7B8Q7v`6H1|NcMrw)<_754n|;ry2A_%f~!dCGoJ??X=K3-?d5{m_8(oYsK7ET!)U z*GCPEpQ=I(OSSSnVu~a`-uo|WR?cetAEEz0>2!t4BE4KI--iw~=H~xu#KLoNzDIfc zgSCwx=^k~T|9!ZAdZ_L!C^48xdQPVKO@G9<+YJ{mx$I0fL{t5Y{qv&M4p6_1Jy~{i zv*!B>_wPEw`orh$e#Ctw{eD>gg6~pTJUN8iQf<(@e_?;vgk=#h*fyM$-lYBOWhno% zby6mr3e6x5>(Kle=F@kA`g|VKAVK~I_lNzs8w+luVu`J*hEJ5AO*RaMiEjf*AN>X_ z)vv<-v6~-G!mmyziH<+DPZtrNdawLp%{4!AZf{3^KF-fBYhS=+4bNv^&7l02q5j}y zg-AA0|-T_mKqcK8#;X=$~5-l;rnnrY}56hJqI ze5}y$EfMl9QJ+6uSrthJY(35EPn>@tL0h>!j=R~$<-0ZdM;JeLXs{TzwTTeu-_^*! zn6~gVOv+UdgM=jh{pgMn*2mfKx$y0dH<=XGoaOZ!@*h0@>|qN!XFK|))+S>3WA(*D@bzZYy5nyU#+`2!?^AKJd_{>A+vt1kz^%3dqT@J=*;hV^eF_4$0Z4za@gJBr_? zy;n4x z@cz>S{ZE6TM-fTiL-|cb`qfjd9|wC!5!HdVJilhB|9s`Oe9rFu9d?1KIKRJI9RQ0F z=g5;6w*2?O{%zxmr(E`!KkR=F;{1g^ug|>+X~#ZvlWXP+_2aJPk5y}?{HHa45w2{= z-9Oclz1>OEzabIY|Cs9)DpSWgMBDndx`Uf?cb<1+_dn^v-yidt{KFqU-CIqXb$Y;$ zV?Jm72?W!)wPeF=n*YH0i)4K#7+4lcrj4WiZ8Gw2Cm-;IebK8(mg#YNeU!hOLKZ@+ zvRKlca&Kau>(6Z+m>PU?N{Px(OWCx)umPtLrzmh|~f^=mSU-^_N-2OSbk^e0DY z<_qh;```FOo$IT~w^&+V!uh%0>iY6s-B>c<&{2Lq?mu_yvXx7cr?V?|it}AODFjTs z5x2;UQS|));`>|caJZYef%Nz7&i>PX zCW!C)>+-ox@1C$VKR5CE5Bm>Z@&iz&&yk(s;{HL?Q%||UhPtwvf#Q5eO?tz*gf)~I zri$DD)nAT*@0@F7ocRE%eK_=5(HG=*X54fF6T2AF zr<(F@g!}_$sV|rn#*s-z;(V7Z@`3yD>xk8`Wd8pCD1Muy@(0KE8_2VcG(UmY2kqSx z0MmxY6Z<>c=<_4KJqNkLol`5xM~R&BiSiRq*93#d`;BDbAo2Llp@$C)_gF_P@-nD= zApN~c&398alf897obS(@BVp``EkwOP2R~ni`Wu>F^HZ-MTu#_g%bVYpMyLtxv zZ#*E4AJX_#j`%KLn9rFlf6nH<7U#FO>k_E+O%TLycz?%sXAb}zxJZ(2*775)-yHR> z$L;yjo&9=>>JJH8-+92knwvVzNcQ@+6Xh56xAtCk94&R&Erq6f+euJaLspExtLgsWv~;r|{?bM3cUaSWF0JM*J61*c!};B;_yCC9 zmq^t6>+#o@qxwhr=z84z5q;TETN*#({pe@tlFU+z>v7g?CMIDbvm_4%&mO^LSiFAF;vbJ2}Qu|w-n z{&4*D-EcbmJhy^W@5`mnkLrs9?47})I*u4eo#V&N5Py^A%!h{DM$)E>=KUc5A@R{X z*x<8~M5NOCAI|?O4Cg`2>v+c=~>j{(S1KUY~I)nHY_r zeBsxVQ)Vz#oZsK~DpZ4(wIsFc zi?M$Y=-8Ayr!Qlx`*+nmpD;di|Lg=iKPHew?;?I2=MN4R&V_X*TSygA@Z>&?w6l zB7G7`T8j+L^@a7jUC&%$%i2UzJeuZj@%|_4NBe`v$vtFm70sVv|G>U~6!hGXO4dHu z#9trl&%^*dkgpXa1ncHusEL$!cK#c@*SyNzmDt21A8w6oAMMg z#ia==%HPy1?)bnO*5dXKjeQj64^)prU~KjQGSHv)C*k#7?bZBwejLa~oTdCp5PuH$ zL%>Nbdv;#t{QWl~{W|Aj3P=Y(Cj)0P{QF5pe4U?P%^6%Uk+|LHKPyh!yY?k`%t z-w&*g9UxVKgDF2KzA6S!c#*o7O!uVx;r_kN2SZ>(_cXG14b5NS_(}h>`uwto`$)^E zOnQCfU*3${!nK`zm5uBp&ZqVFsZe}8j$C%*sQyL%rBz}$l-xT)mV9W$^C3s)uiE@P z#o3j7VZSAc^VvBu0(LA{$9CIH`S}}>empae;}*8mmAx5H?LUs6K2=44TJsY1{?D5E z!u(e9+H|np`GHKXNA)A1{s+&{!$2NZ6UUe4{P!(G{MMOS#qIvpUAD8ixPEl+U#a@I zuQRD#pN{ok%qKOUMbp?fHR60e`_BUkb{){#-x^!t3}th^#$= z{x@u&&DH(oIo8Y!NCI<(RsVqMdT zpOVHm$%wy;_fK)w7yhv7{xpsL5$eaz%Ojz4;wf@ubPvie;!oM*2)qgXNc@*Y^L$|Y zJm6de%+WnXnh&M?r6T>97L^WnNB$?^59hDEuWbc8zb9mE@810L;r(y6o29`1`Jc&{ ze5vOC!ur``Nm*s|Yp9Qo_x z{A=Oh3Y9}+Q=)DC`P3EeUu*TsON-?$GXQ3UT|ilYf2_ z#|+YMIF0Xd{F#UFx=pR*R^kX|g{$jSItOaZQpuyE&-m|$y z@6p^}SYK`1ZGrmy^JAp4oW|ccKl;2y2pqkBj`+=>`Vsq=?pv*(r0p(Zw`V8imlg8$ ztfd=dtvEuC&A3nbL;SQ=_a`>1SC4h6q5X+CzOg>C7{2G8CXa&Zv;X`{ygqu?tfSCm zdmXlEAIcw~_$IcldjFKMN>W`%oWJTQ6?eIgk!t7NxcyK-l@C`TOJi z(dPLnVAx5AwQ1OWz9YPdlP+;~`r)yoj)(<;A;`xH4$ z)-X++Pi1@)E^*Kt_TaSI{FN|2s;^!@{X#lWtNrhDrUmDczmT18*^_^M3CfR#_Hcw% zPU)mk(?Wi{KFW{!6Gxcqn@$Gko~84V{Wosx3fKA^C#Kg=@ZnEfBLX$6tVCgSi_U>?MU$Osr>epd7enU?ypQC3q;pUujXK!<~{}=bKteE$Q z^L{v4CcQ~C@+IW6Noa-YjKwgm@p)-Q3-0C!e|G*_4WB5#*?#XVVEZ2-Bm1iO-;etb z=QeQ$vu>GW=5}h|jS!#x+=HOUg90+?Hk~g=@zbM3d)Vr5oLuX-m%l#d^Huv0NYgz} zT<_8K2@+)AJ>nKX;kt9A?f!l|Kgp>7D)p@TT$QjhtF^MQxc-# zPw2lMeDAOBU+0KrDXmYHq5P@5g%x!DaEMHvMfEf0_wGwy&{?b^(caYO^xiJ zUDsn|UH2;*`4Hx(?*17IevNmNK_MmlIF7G$r21S^=h^H94|Nn2^*_f0^DC>j2wuHY zkchbU?7#8V$iJPoHWT8;HD*^XrF`N2E1cE-=jxvZ?62?Q`m;z<#eMEHT5EhXYnvnJ zo1Z493rjT5C#*k(KQ!dR!xyqmon~m>kC0!xk_uIWCQ_~XHQd4;5~iObL!)W^=pnNI zZ)?=?Q?G2|F^|SiCWy}ypS-~L6-SzfQ2mPQr@HZWFf->Qi3p?i9miL%J_W;xUzbUI zYsx3?Klzg30j!&n6z7WD|LX4!FzIX-`D(dDl)rOpec^3sAu(P>_ea6}o$NRjHcUz* z`mc6q<_rCUs?WZ#aaa*K8AtiU{jV*a+r$35r^vXPtD5;j{{GI~&$;}kCrdn%q=`?2 z>(3YMv4pN8Q^;-I+V!=<{;L@iR^|u^< zlm;pN4cT59a-I(yf35E@i+fmpf_=55vyAdDjQ_tsJp+HO+p&IU7W4Cs(D^xkP8@>f zXARj!v&{K%?7uc2@|s)OWP)t9yQ4etZ&%KQt6uF-Y={;7!Hs>So5)pQ`y=1P7%8S&d#?H{xrl0)>CQTvYh{E|K&zB+Ow z>ueG~-xcZ4oS$>x=_n<6QYV7{{&;`GwDaCjLN1cj|5owyaek>;PyigOx<+PNMQO%` z{Z9ij=7WbTM@9{$_8HeFyNuh<4ZUd~yPhJ>mr;NhZ0~S^)SmB&*U$J5h=FlkN=R4Z zzU;s6kNN4kJ`H+HjM(HT$`8&TrQDB&?jN3#hOLe&-!P9S=$cmmyy2w?^})d z*<5rOjxB7;p5HC5A636!akkwj%PhuHe(?TpH;aCA)nlDy16GOK@1)Nasu|n_Qm47S z=KTuKkGr7W->m-ID|!s_DZEOChEu+9 z{Bt#VDx92jO5h*j{=4^$LtvEW1LD{*hW>tZzCzA`{oG*BMlv>8oUh__C*j`Fc5JsS zs-H|y{X3>*ENt9XNy@D0`YPNX+TS%D+OBWT%6rlHIvM$g`N96*;_imrwR2(YEBSPKeWZVOmshA%4<~Eo zXY)xwm40{weYBfx01g$mQ(w^!iBu%pNiiN@ias%KS`z9Ir3Tf9MJyO)il) znY8|b{kx{~oZ)i4^Q3Ss?LWr)>BhlD;IsKIsokFy`)|`*&4y1NKpag2c>RUz-(Gs& zP(123vE57gk|Y1^o4X}A7@j6|>TIX;QGVQ;EP*TIo{;l7^!v(?|JJF^LWtabgE&V% z(&$g2{cPE6KR5q}k*sTiIDen|o`S#$Caj+24*Gske9h%VgI=pw_7d6`BUi} zf!yz{*&oO0^I`qg^rRfZnHOZX*;vhdp?$RLdjd>fnXpl?fZiYRIi$rwFhARpEzP8S z;{D}+q?`rgJ-yh875(`6n9ug9zqwt17s_llitD$j_7$qh_pG(rNAn#Xu=Lg)^63P% zk2wB#zSs-i+dm)&yB6{HmmxmuI=I5J=GRGIXIdY``JLMq^Fdm4Q&7Lb^}!>H7C=(s zU81*Wx90r_^E+H!Z+P?c0ZHFS^;6+H{t5`?6J(&%r56AbVpu>Ghj_f6S-F+DI5u`HDoBQU3?m7xgP$;A`GhvYY)y zug?now~+W~h|#SfT^CaRB*;Je8+ZhqB0I2+jHv#_`p;{e(?~{8;SNZRc`O99v06M=f7Obzs{5_BLgbNoRleNj&n)$-| z^okktA>qqCVz`&~x0@mRnm*eNysGY#wXW2@;`$BK(G%KwJ|+($Xnhd#_wl1GSXo`x zsvig6_JQfoONIGuw7*BoCl;`^T^^Y=i1LTy+h?i zu5pK8ri3(R`m=m|i{cY$bP4CW!a>$ey$+loNBe_@?s&=F2y>HVT2cP6er&nym1?$= zJGnH&o4-G(D@ zB}achvfnH2xInu*kI5HXn&0+E@yW?gv*CAxd&Jm{=4UW}AFCbU@An6!ThlH4^|AhZ zmgWd^vL2FvZr$nkL;V*@+b{_F_LZzpp?qTgUM#f$y-S5;UmeOH){hI$2Ee?)cZ6+7 z<4-x_uS5L>u&}y<96evm-yg@vhCUInN$)@M&5+t}3F@!>Jk|lm&3Hggj`^l}exd!= z>zD-<83WnZQ>gsm{L8lNaEP1noxC|}%JWr*?E9TNXCcsb7~9jH%AZ6c)W5{>_15zX zASa=U1ox(VFYe#aX*37S70<{HEBgIh(f$!{=S~2F^B2h-vW4eIg5sa?OdwqB z^OZLR=xLt@N=&P{7R7i9Ca%KCYSsr4_8or@%|7xZPoonn{E(qf6e~0$p4(L z42NzP{*XTTluumW{+6EwS?`Cjo2+SmREFYj&p&SP9bOXIXBxlD5uY=e5^f@KmtD9m z&fg84m)sZ^KUv-zdksIr{9m@^FE06XjI8LXIA7%pD%AZ!-dgqJ6bfc z^slf#^4)h=2yXwH_(?AFUwlT~TG09!&Tl8Jb%n0!uZZhZ+TUP;_*$py4+~Fy7p`AJ z{-yW(3GkrHb&_~ioIhnr5X7AOE!e-oWHibz=BW3-Y4(oPo==SR=WVBOa2=(?`i`vC zKf?UAUi2gwbmb-~51{9(NRWTIrs@=2^clrYVyXT#L;0bd_0{>WiEoIjr8r-?{W4+Z zZgcj>OE3QYo} z6`psg5%7!s&po~#Fr?0BQreIDmso$!zU%<=j=dz^oR0F>$NE$C*AeP|c}4!N-KQC^ zFX+FSYG(`9-^)p52O1wqQ2u*_nKSqduOf58OnLo>>xb_NoTK@o_zdgWX0od33LaJP7 zehKsat#}#CtrnkFLwvW^ISGT8N!fS*N7q@0Rq?!k z|A?)Cpx6b1UD$nQFi=#wyGue;5K+(rh=L-Z2#BHrf?!~Qgv6OKu$xdZP%*IcgUxe( z&v)mr_jN7);~#U)o@Mv7?>lG4gykRL`P;D%3rUKhF8Z)#C40XhKNQg~i_|ntK=Bi1 z%735VpLV^MAF+uSAzS}{+&Dacuvhy7lpa2kDob^q@vHf{!O@k*gM~b z>>2xBJZKoR|8V`!##%elPV!M4rN{V{fcp22yVj&`<~#AU@xuHrZD&NhQ=W=PK3c}{ zi$QJw7BlV5k-(L^>+w<{WL^|b<*gd{Zetmv^)Y-+D zbno$8d}ljbzXt0&8)^@e?YcA2_$2oIVxYe&gYwB>JQsz|h~|D@q{H`5|LB|1+Bq+I z^+A|_`qh|E0;eoQfhDZI1LJpxUk8X;!W3jYnDLzs^!eAF402=aB=ohq5BK{R@O!e! zgp{Q;iv7P;bK@|+n)3TMJs{bN&pZ^?-yO;g(rb~SVxw=u{3dSbLPa*I=&?WJmjHfm z=Gc)c<8R`%wk&@S`!n74Tar1_58`$APILDM*B96RkdTt=%4mYaRc;){|Iyf9c7E$O z@z0b@ZXDJhJHB!x6W=t6CsS5mF#`JgUl%(vD(kCQJ(KlUKz*Iv#eg&qX%HtCdvW~0 z`sD7uLB#Q7N7UN>Il8_Q(sQCR(m%`e4emd3K*f#p-1LXne+l(<%wGwKx}%ILs#kM= zAJo^ClPt)*G4I8B>R;vh&yT+fC!8i0>5Gv5CYHa0{=+KU0@62sAu^cGzE8;S+XOTE z!0s(NSR$N1J+d{6is5iY8R}QS={yxa3 z@6F#dw@)07xGv1+w4bu`FS8}B@@b>kmHv63hLQ&iwh+j){)l-l+dmw7M~>meSP!Gmb{(+LwvW0`3D57uiSdah1~et zEIxjn`FD`dCPx>tKD1eU{%9O`|B%o9GY!eT`bP26VN5?^{mD4XjFkWRD2`p2F6V>a zpAn)VAt&~zpf?*BpRhkTE7X*9KK?^jDVn-AAlM9KDN@LQUJ zI{aXKVW58la;->H_g~`bw=Mo9e|_!&2OFZH^hf;Nu$WyR#7}BIW+ZXkcd=($j(nUS zKPj)ZBqoJFTI~<&Gt!wn`rHP6D@&En=hu&(X1b7us|v{M72^x;PZRcVDM<->C;pe{ zDS!Wb|MJ@v+5W?lj;N$-i~ZyGrz>h16Ah2gV%5UE+epeQsB=s8l zt@@u|N@VNX{kx;n6Lk>F-}CE7haz%GhLtY5_Q+BG`~3BfJq|vkS#{w!h6u;^W_L2l z%7X|^ZDRTe`R$^6Upl{HgSfT*9cvta(?_2YaYLpszaQH)NUgOuwaRZk5@ z#_TubH~6n5iJJ9K9OuFKt;c+RZI)P(i7B%2%tG$(hw=Z^T@K`?s4X%qWcep(zxNc| zkQpT+)aQe6{=RpHBgvPY?bBkvq5s*vqboU`)*ksxiRXS_8^r%h{0)igh;QO{JB9VJ zy@MOs>d^tYIJNkXe17$(`4A8PF6h>`HQe=K{{YQh&Ws`RU=Aq0j z^7;bM*HCnb^e|b1x_n{!DgyD-(&->#|(zhxi&y&nP z)`R-{S$9uz{BIW&mvxNeM;oj^U+~d( zX6+fWr@a$;T6{|W{Q3DQ?Qe!8@%B&gH@|m+{C4rnA_F%sK#%Mhzc9b=^)Zx0yzh-h z_8Niy$1kkk-&e>YTRSd5?!QCW?*o1pD6A)YcJx7)5{30wJmx5QdENxI`@rg#^&r2m zd^wNkRG6WV!wcB;f&Z{3w}IMx--@HWg!%TH_CPv)dz7qy*q)mY{fC`qziCr-Dt0!Hi`a3wlbk=k|DcrXM*4j3in4N<{;Gidl&6*}xzn*L z`YAag=a28dK3(TQR`yUr86yJO-w*gdyTzS6+@OfAZc#vtKfe8c*guPuzgUFqhckW& z(BC}S{@USAeNoH$U;^q>bGsiPsp$*RfgENZVEM(X-m zBT=%a{Qmj=!^;bKW;r z+Zi4Hn#_$u{nksfB^e(&q3qL4zhQsh{3KoCmenNg{YaSKdt1Co@IF=4TK`lRUstl} zx)SPeMVQ~5J)R`rTLtY13}W{W`bU?Ivm^&bcR-iRVAj3ijqaJ~0B1@j9V7uk~j?p;xXBI6(G_tB9KEu!*muA%hZ43eve!P_1osX6WRV-8C^ZY$(R||$i0d2zYFj`=-WPWqSs<{td_;6 zkna-vAX4zNKRUTU6aDY|fP8P-l})0fP0*N9=3hg;$4QTp;wncpSHXk(`_qB{;XL~| zu~v3P&B+V7aSZfZQSFg*#>{xJ?H}f!Lwzo>%OelcozVFnZMpd(z~>V02I;b2iLLt2 zZC^N$AWsz(t-|<&{R2ViR^+3lB62Wg`b&WR-mkMH@%Or-7nLl&Rss6kAoIUtW4fZD zRjmI7)(>8fb|5hyyCKKEEdQzw@~@*d*^FI!|o6A zv;6luavW)*QFJ&G;zzt8mvl3=K^?Os^6T^K1Io6C$gUfXs7so&e4KCp&lc9v^s(FV zc_-og!GqkR#C(h!`mc!TUpmPDzkFOHb^NtW+}ioD60@V^QJE{!w3q82=ErA_vi0xM zt;wzGpSHUb*|0zj6-Hg*?jP2t-u)ucCu;oq6Q1pxkb zyt5%4a#c{&;yiA?6X36x)RIKRDWjJ4n~*_~(x)tcN`QW4m3fhyK>`V3iq8+AeZTr1`J$+zErZh2&y zmOGl2!1`}tfApQ1cI5d+RW!Hh7dIc)r_67iCQB9spyqnUC+t7@eJGc7T;zhbUX<$# z(5Hr!I{HRG5ogQJIr|^K@cgP@g-3~Qktg!5VSGXVvWMn9sneeX@$(UO-1CL{^?Xtu zsdMn+=@&eoq0z5Fx_DNq_`-bQ_&?%=1KH!;lc!%W{#jQ+=)@)A_}m>~zPcZ>B6BTN zQ9~5dH+8_5^pG*h$WlZjI`+^-A+eZ!UT$sZB{Q*GVE(bf4 zGI4LzlD|&}_BBq=lc){rj||suV$Toox4wQUDe>=&<|wlDy%NCR=gB@~#KnQ=cPWdX zVSiL(J5v&|O$k|!xg=;m8xP3Nr)Z;wCdLT&j}|6nleNPf&=As+ALi%xZ`vLskKcNu z&U2!;`-l8_Ov)wW6+DpQB4PeS%j)Rt_Q}|5fiQos+U_C7zf94I*~8_0^7~Kp;-1mP zuXf}34wi!XsY6?;r8ctjr^+&{+4BYYseg4xNn2-Mr23rcALR4ke%bzVnR{B*zYaHS z$$q_F=t@E*`}=`^mtkW@LMEu9gdh3bxC-F!Wta(xdfN>>yukQ_@lBhmt>=uNi17xL$-?@M&IYoK=>ng0*-qX$NsleSV-mxrt=`iL5Ir2IHIe%y07d)Tr>)sr4*uWbp?_=>T^uK0=)KPK|7H6&9HsG!-krQG{50(|vIB=m9nP5ALWVf}lv*qroPp@tgjn0%;u$;=V5Aq|HDys2dxXfc(%enLh9S-H(@_hy1tYY7^N093r598bkcatusSW$Npj5{fj{Sa8}up z#2x90c1{ysUw-0AHi>xZfd*Hy`2_TD?(dvShD7=C^b7K}VOkws_+dBxPfwVy)t~FB z)vtZ{PQEZdbH?3~x^3Ml?!C-{eSbioR;cEY)fs_k@R+vTI05{uFlvxuyNp)(QQoRg zZ04(?3lB@U`H-KI-h^H`yBTkd73N2@!-bTptD_T>2{#}5XP=%LkmFOkqxkMjpP>D$ zY_caE>Ib0qJ=r*nPfg?9$jN98H1YwDUl-q@LZM1n{%!<4Tftax^-; zmgVm-&@ZF;k!0Q08EA77>mP!Agd9yLVFO%Ihb*R_(I9>t^D~!}*ZL!+2KM_-p#Nv# zs~nPI=Eqy#4g1%w(HyckWCdE!|O!y|}?!m>(InT<-p0fBESs7xKBICfcxN4>u0= zW8pa`a_*c4Dv4tL2h@+_vh^_z?WZ8Uc-EgK67lPIOS(srw})pV^Fa3gG0+FAi5aA} zqZd-2#eN^=5Ayu7$@IbgsBI(r{S)B*r>s0kE+sEVR*mb~^9S{d7t2iPml1vNpa$Xo znakS_lB%Rty!Bg9UoyJZQR}hkc#54cALDjDrJmoi@b_rOhXllbb~kQFwPvP>S57qL z?hgY#a)RRd7d5z1XZ0PxdYw!d0ztR_11 zv78&%2K#I{i{;l~e~n{*Tk>$aI-2i%i}~juzk6OOgQRZpLG8vc zK4E`@f`ujdw0a<_8uXw1_xb+Qn8tL{)7%IB*Msp7_t!TakxS-$2to-}67KoK{8pN2 z4zX7WLHha3zmfp`TJ+4AhE5)UM|S+g&4=-$^l&{@o|1zPT@ki_K6W>yH%xbnKR;u9 zLj8K+Bc+d4$6-qoRk?r0&rf{c{6c!|?qRWOdwV%Q{QW8VO|&8X+=ig%=@+I zMHgataRmB(is>5$eA4B%WTTNLDmOaD&4>JbQ?MtyLbcGBtOMLQ%s(s}Z9~)@hoHu$ zByJq$AM^%TQoTOvxYt~ke}sHyc5x+ZevUwSgA=&<1lT`~&TC0H1=`my8aX7Oat(?d#Q22! zL%9T-(%;SlvF!YA%)W1af6l==S$|oZ4d_Z8%dbIxk6(O16DDTkUZ%qOy5?6sEv`S* zs{L*E@uu{1o4u{tU&nJls9jAdw*E3(Zom2bzSDjo?bMPos1>@$EbX;rA{4^6kIw4O#s+YAl)@%lao^{P6I41hI@+fXZFj zeAu6RPnKUSdp!ho^AhI2&4F}sCV3@~e+gKhJ9M4_c~sFKMTms^C&sqhPv&a{pnzn? zKkP3*);*hC(F;KvC$snj=2t!*F{K--24go%Vg6rF%q6!bgrhA382=dPciaJU`nHc2 z&Pe{oy}d&s~a^krfN{*oZfe}VQ(>4uvp z#3x<|>vvQeMLJ%s7L5%b%-tXCkGQO4K{hVaLdm_(%K7B?r&X?TAQzvGLM{9E!}wR* zz@GU38Hw)xW%Xsq_pH;l#Ng}*UVRPf`?y4F@@&v>^sAWh?F9H9TWmqy-fQ7_O<}%6 zLY&ET?Xl?7BE~oLKVl{a67$4a=;WT3@0ZW_=7@0O_D$A**t;eF%U_>%WRMl1qG9O4 zQ^qf>pCy%>lB@$m(A;HT1oc^?V>+2q6NC!3wp^c||2s52n`GY#Ln%p&PZ5ZpHQJlf z|9TF=_>-{zTYTgOUHdm3KXBM0*GGQ+L#=})ov>jz_FMWN_kLmjZ)cx+nsnA#dLu@qa$=kw#EsL$oJ@_Qmy^j8t|FY3F$lzL9jZ`B!9F{u828F&AX-*;(cboIL( z_}5uwZX9F2|J)0=hT+`P!v6KZ1Uqu==4hlgoB6+xZ(a8gS^a1(iY#RQ3-qsp$9j-~`jZgvd?4Uo zTc$=3wcsU4%arLi^k0Vf%qMNy^hKdlN;$qoz`xdY-Aj!p1!4UkDf0Kvum2r>wx6u% z9fH)>GyWx@KVsj59CC?7pi}kCKY{DhOXE!`y{3h8mkaCj&Pf%theI;He|Nng|2MD& zz2ZC)H^hGD-XG+@mvT3{TXr~bUtd<=hW!sQq)OU6Ay>TPA8HrA0#?@$?z?|E$~WOkOXUh{8@^OXilm%Mxp}4!)zSzJ-9};bGp-b6tRcppVYzr zHpj-=kg1_#P}LIF9|8I9BDSEr9Y^BAFT#AE$#W!*)!Jyp5~k0PZ{Ka}NakZ*RI0@C zpOEjd*WF3%(J5$dHSHzDcf!_aGu&)ocU(4Ra$B%LUihVkM@4ER5AIh%A-jYKz!S^fk1 zCr&n|^j@#wILKa@f1UOfRPFRGyt_h}f35s-+I!V5{CX=}{|@8J8?T~BF2tBh%t?>%1b#Mf>*D(uMY6YTGN6&*~X-|M2h zt1Lc+`8VTE9;EW&bYwJ0_`cHH=tF%54_qh>yMS7 zw>yR7PotMcr0>(=C?(+|$9Fy8J95YY^003t8Wh6v$57v=rt zzux_&G~oIk9I%PmZ|J|+-t;8P|H#&NXE6R@eEG}FoP2mY7ES0R%y(0S9dW9hgf89| zjxVic>-Y8tPe4yJn0`aPPd1p-zRu&Yd%duJFF)!@nx4$&)u*(<`jMf@LFCl5MX0!p z`R6ddQrW?iytbN+LVgPKeGEy+ivh++tjzSg9`M~GX)Ym|gHZoVC4%}r@1-$`9XuL+ zx+lE;uHa}Uao)d?*S`$;H6Kzy4C;2EZn0aq_Y3P2X|mm212e|pM-PShw!L|cJ`O*G z16Rff@_kt00X^YgfHxTk=TCkqD$`7jx5(=><6DCG`e@jRPm4tgGj_=L7SD)!|ZVwP7C~ z|5li99ppt+r(rZpy~V%hpYL&ahYflBVlpp(C;|S-AKCdJ>w_mDiwPO*`vd-o=Xp!w zoj4JVd$p4rC!oIXRA)}}{%N-)} zELAo`*?;B!CD{MuT(Ax~J4hXEtSV;n!TE+e)DI9Bh0W++2GdvQKOD<1Ab+ zzr*#%BR-qZo=M|c&2NnVa*YOzIEvHu3-fvHbT`^1;4^C1FPlAI(0^G}sYDlRe?VoM z8K1DfX?5CtspwjvINHgPn-Bemg~c*H`+PuGM>78z?!O%~w?X=~T-s`WuVa`p-RbfX zRlXR)T_5s!xZ0KsJv<%#Y=4OxR{`~vm6}pIIX)d*oDt@;b7T;CI?Dj*?YPa&&jtR4 zXSnQq!sOY=ctk!oZUp#T-_4wO|D1?g_MeCGVY@mzax7{FnjgXXJL>_T;Th&sC2&%! z`uk$46KS@bjUN1Be8T)*P)B#-;EIvb)J@#|!T!(fk35Otg}ErRit!8cdk1~PN#k;B zuT=$&_AwzcZ7!dBw%&>B)R_a^B<316p)VJQ_y4s#xK;@ zlh$VRl+#39u}KpP<);siEu)v`r{l2tQ11FLKRru&pB`OR(yG3GJFZOkD}F^L>)7`R z`PKYzU%G!!NvrEW){mCbPPa3$=TqVON>}v;X~5#Mt@2x8sYI8a{e&8iF@1&p!;f2* zr0B-9R@X1dj@6~2wplpwHS;f_|6n|FnQZ;SLNr3e_!oiwO}d(RkX|F_BjwkuzYpf` zvh~b~XU-IKrhK2AAO89f(J%*MI%y7Sw?0)q&R-vmFPqbzYE!XwZ%xGBAHRN>x!aMP z3=s4B`(XTM8{|PoE}V~^tGDP2KY#bS*^H)oO~KD%GP&!+`r+`dk!0#LN7QF2%b%nJ z|6#^aH&R9CqPb_-{yZ?hq3D@Lb07bc$%g#-;3=E2ue#u^MA7M z2kLXK)P&v+n}j#H3i}Tu^sdn}jwf(~rLaDKO1e*t>PlPf|BEm&p!YQ<;;dliKf?3l zqK@5@M)oLe)jy6H*+d=Os`18R;rw$_-7{&{!*k+y1uQ;<^_O0Am8jpFudVZ4Xhbq5 zPDY0{DmZ?i|FCkbKiQtCk3zRy<;Fh&{hb@_L9TXMh_;U}=Eg4p{q@zgCWn$|p*c5% z{ezBYWc&9l!KmT4Fu&`I&8c$K^j7oF?dCa?m+R)Dmh+Kee78Ntg}lv}hhBc#$lV{* z-;{&qG&N{CRvU5v{qOsL{64XhkbVd4dHD-iUl|_nMAGVY(3`h4g8r{0Z9mDo9)r+X z7T-aAc5pdD&o(9E@!f^_eWzVO=I_{phP)T%_u!jCa&Tfg${o<6|NQ*(GOR-P9QniR z4~F@-ioIskXUa@$v7fzP$Y=8M`_i`l6|L@n)=jG$-CXhuEiAQR&sW5c-^MLzkUD+3 zC=QwzpL%?7)Y z^NqTw-_FzA{XzfWV39rfJa#Vfp3eNMde9$uZI=^?$)Ar}_K$|~+3YZLI_&36ELIiP zSDzp^;?Q#u(*DN$8w}#JV6ihvpT7X<%w~MT{mu5yGN;F+Gx6fL!ul#*9Z0VBwLnE3 zBDud01AWyV?m||m=%NY9Y=2(3KTkyEdU8_35qW9{bMqmefA^dq(MNZqjz#SIg#Pc` zs(j+NelOZpCd}t13sqV?sSVz9{G6N*KA%;?RA|Le5pL;UhxvuNQVW{bAja*kUT5<` ze^BJ!d(wvqq}BM#$48kCp7s}=yV#OH=JVNAw!hhR&nrCtK!o}I7lRs==qkfMs4`p5 zr-;A5WRKa#WI~&nNarErQyciV>tywVaDS-2(`EVPsf$qbxB~9)QwRE4 z>f%6poLYd4s)hN?zvMuQ6?IY7Or|f8Pfuh{gLllq@BR%zLiXS0p=|&B%SNbvD9b-U z{XCGkjD$uTA=8^I{>NZ_GnJhmv@LKBcKR&Lr${S^q`tF84Qm;nBEaXLZsBBeusgb# zwwC+*A%C*{pGi))eJEf)`+ex2=B298PGSWdc8k?dMW8<1cB&igvP~Z=hqq<^DcIln z#usavZ!jMZYQy3SsDIDa-jnwGbGB8!Y-5#ay_*O(50L90=xF^`QT!Lzx*3Ohfo65$3CD-3pQ#ZjBOC!x=w-FRH(Xc7C=M zpRZ4rzkhyxtZ2gtGVABQ|2zMko38@;Bj2|@NsI#aqyH*cd;0sk#?h<7PQ4ZerO5u7k0vuT>Ni7`YK}nE9}o%w%CGP zIX({!-Ou6|nExO7)0s5b7@!{Qnf-p^587Xg#d~P;jcs^&lQ4fKk53Tq$PC{8xFS%W8h1)|{;R=BY@;vC z*8-hx^suBIt}tTu0ou=N-IeJJueP|QzA6Fs)3n!psnXR;t;W|{Zr^F!pU?2s-?QX= z^X;eit_Eq_fV<)g10C4=0rqomR(JY3vm?IcK7t#E{V!|Mjmg#q9ds{Q%8g@SKdt@D z$li7H(LAj}Zae_^cSbI5kgv%mK4g2YHEN0!=1Xs<8O_)~A9uVj z%$GuP9MyRii5*bO`Rn}tm^@bxa-)wqIy!@$Zwce)l>c_qw&wBpLWMAY#-opuu=bg# z-6NL&g8BC&`&DV|$qqPD?t{QGd`n%eN`*;AR7i) zp}V1szjP2^80UDBHUF&8sLSc>`GEebSDnr2zPN?0_Se>pbRl2wo1&KUKOleYbG*pk z_tt2CC+0uF{b>f)o6)tN3$f0)14tM*jQ!_`%|z1%0Eo6dzyy zgFQcxANOgaOwF%#z+1O4`wi`@>(zVGge%uu)xUZJ75e0NC*0qi@dfkaN4;N2U!K1& z9zK=XXJ}t7*4PqaW`w5KF}{icU-y+ANp_hjs*hy)2lZ`gp%aNRFh^4ynEwXP|J^yo zjjT+!LeXW1<7B;^lmk=A3z7wiui;c8BI$1TQ}4hZX8gv5<(e`SU26Igx| z<_ERj%g&EiazJiR8DG$Ui(G3)&!5z5)qaMb3M5(!z0mQaEIxpIX(@V>q0{Y=pISYa zUxD%K>AcE{{J+QYPf0(bX(Ig7K?|Rtc@CIF4_4GX9{xtvgdlPCY%2 zJUTFagZXXO!OFDXwN7}gO_m^k?-jbyK{=iA&NTLXAb;1r?nyr`y~WF~!2YHa3EQ?8TQCVk@05)^etGyoKEYg zkGq5j^Vh$pH!-w!LNoTV{#01s4(#MjH1wTNn;`alq5n1|#*9jKEXAWo2^x3a-IDC`0?q~na$Rsx{`-7=Taw^J+TXB2<`dJ{{R6%dUYOBm z%MJ0c4Z?hllbz3NaK;^#uSntML;JbE!iRi5<&I*9vHF-1$bT#fG@}u146)^8VZLh4 z`x5_C9%#roVZJ({-PCE}}R}lHZl~h(2ce593pl z1@7ecR!_9-`hM>Eus>$yTQjGp0TpEU=k2;}7P4jrUp6oWu6G(Cs(({9yg{y1fDYImQ(K zS}4q)H=$HFq=ld*w3-#~W!KL)Bk1=jI#QX!;|DB-oMmo6Yqj=cs7XOd0e}CWE z&|V##@bD@YAHe=C^kN{@u`1wKRS46MRA< z+~1nnsg6#TKEv*ZP38K_?{8gha8)`Z_>OpQlL_~JA%9z|zR&~CzwzfO!uq$(|E=_E z@mKNg=^pa=eEu%!_>#Sef#`w3eK|k;^^X-zHl!%e1!;aQAh@VuYGe3jG&ke4PQ=$6hN z?)ODteS2&>A2M~xD%5g*nF#3H(1m977O}+&xx##P%=REMhEYmL2zPzRSBh0C{adjQ z4^kKA%gHR4KF~SVDqrtaOzDvgHu$?i%l=XP_(4yvoMum{#66OQ`C7NKmd5RVip|`G z`C3!xDJ(mW%((QsEceD4)$+5@g&RgR-(@?EWZK$v&lb9 zso{V2ct?ydKZA6=$h;Y=P`HoWzXkdtj>Q}S7`IF)5p~zT| zjYGa%d~C=}Q%_!h2h88Dy(^0^lUAd%eHdR*pEmw=BGN_v$jJAQ{P+3srFXFtiEs8p z{rWO}g8rAA%s+3w>Vz|@g!w8}@gsY?uS2K0GW#b%e7>%$%kpQhR<~OJeDu+j<^(yl zYX2JNd6I4)0+CkaTK0YbU!u>usQ0f7eEEwoUj;XFXy-F0agSZXeBJgaru~+l!?(^d zzF>Wzp|Ff@_q>AVc?k2hz@wH%b$Eq;l?wCKzG^YOvBer!2g>;Z^-;?}A`Mw~LmV|~ zksx13628*ry$U+%Q-u37m)~SmqVZMGXE~Z-!UBHc3 z8DB8}e_^jN-EZ!SSDg{|?{$aP(hFvdI4xb6FUO?CwCibG{Lfy_7tk-Wfo0OyZLf)o zuFYf5AJ{+V@Gmq_(pE=3T3Ejpt#l@Nl0f9E@rXTt9ln2+dBmEYSM|li%tGbQj~`zK zjdvyMTvsEb-K_uV6NoSCG8~BAsujHbg(Sd!K3L>L`ioZ~)se#bWoPI}HjQ727TYnt z(g9!5&SrFqxd)!6EzDQy&HyqeC<48T-y^?&zJ5&@=uN_Jhw|#{kT3h;W^`~b4=m}H zg@o#xU&7r;(w$&5_iZqDedu2m?b$_tg=e?Q*Gl6Y+HUn}{L4+4ueQ^Q>6FVCvEn^p zz9#H1r5j7H;~%Hk`pb0CzqX*chN_Uacucl1Uuz`u=tf5id^DTIUobx#QC2SPrF2W| za9{!Z`v716c7CD7&FyralnV28MRxw$wHK?AYkS5Q)Gu9PO$S}@$4mAK^EKj)D;fSK z1SKrL!~Oniz}G7cM|$Q+AU>2aMt*-ine!w2|MuTiB=$lS`f7ET8;A9$f)`dau-XsD z^vbDV@0Y)SM3sw#I9-fIIv;Lw^8-Nq=_$*vSvRdh^FQWr<4_-yOg%|MP8h1{lgaK6 z@cU8bzwf!=h5cp=^ZV4&ix^#4kFrM!_kSdq$@<&wdf{LbVLq4FdXTe&!;nQ5v#*fP zxnpWi;f}E!=;GuzfYDtD*jq z54i4>FrOrbNPC{C7Vii(W6uxq_doW2Fpm!Lvc_t|E4XpU@4bRE(x>>QIPTzF`F#HV zCrfvHq5U#D=&X1y%J*5d>9G0?%>M>e`H<-i5$K9+ z9n$~!g8QE+K5`^4H>^QvYG=7|0`#$|!HTXu7l6CYVtk6g{w7{Z{zRm{5m|g9+F07xuRg39alWW-dKVd#4m8CSX_71)~n(+zsb6I%}4IK0t_q`y@XJGLescr6U z@zL2W@h6|p8|xR*hQZEw%pLZA;ridh7tTn>7u^=SJ{9Kk?1j%Xu&kp_sjo1fIy0R~ z{}-VsCWz^)2-xo#ZpO6xKp(7Twu<8e*1y6#1Q1)g2|4^@^P&IfYG_Sxn?Rob2;-Ak zIaYMV{8hMqoSaV)Uq25o3MB4BW6=EJmE7;c{>^88P9&pw9f~_H%%`D?4gESL2=CBi zd}5%Vj@!*>|6~66V3{zVQxEu%qQx80o^s}2LOx$@_a!B_Hlkr~g#F9kf0h%4vQ6k? zcm#L1g@y^X-3!ZZ>3}VK5qN#rzw{?|P5rq|MpQsL`B# zpGH7GEsr~r;U~k8>>Nq<_XGVr-_C~qnHP-fw1oNGqO^<@lx#%ScUk=m@>k#NPi}7B zjN*ftKBj~Gp5`xq61Qx+c>Q?x!vFC8kw+6uz_6_ggyFy~u% z(R;=pjE@&RFQvaEwRr0)VgAZrEueP)T=0msujJ34U!Q%qq)RBO*2@s0*0pU>y7P4h>3Dzmdrx#diG{+Zt&(DtAc39Oc& zpgBz6Ab+Rc8B*g=e|)*kO8NEq@lBm^0GWCx1})vk_=Ear6lzBj8$!{Ly;5#I!TkC~ zdf^(pR9{#h^~?Rqq&Lwh{y$cKgY}KmKC=Fl0tveQMVPnC7;KzPtr`u*E}Jos(P`dNPb{LU?f250Bt z_6vmhoA*1L9(St1eQxfMzaM^mcHfyIT2*=n@9ml(ALr+fQ%9T9rSAf_eXkIa9a9JdPlrMTbRE_i(+ZT^=k3Un^^w-`Fy>|_(WA>yXp*Y z7Urue(1|3EifEOuF;YW%OxFMS5D%#n z)}K1_8hX&?H#Sfge*bpP`O^J%cf@@!>&ow+Z~ye&FnzSo8CNBga^o<5cz5o!^uUN} zFXJV(ZX1ir6PZ3ied&A0 zn@sB$!&^TM?bm{~)^z3i^|-oiE*HOwfd6%;$c-!*unCRQI>X&R)R!On&g5x-+5S1L z|CN!u;`UBM18VawPsS|EM5;Q;lW$pY2g7Ke~v! zf0#eX*zQdJ6h)!-^Vs?=7@u~qaw7xmH>1H{)7kR@{=b2qKl!1vjTe7HeXHNLnw%K1 z0}Wc6$ethI@6z)v)cr^n?sQU^zbiMAY2md~_)QOCeLHNJO)LJL!zsIj`CH*yL^t@| z$8U!T>)UUWGPCKE+6ux9yzt*+0upV`2hbauUMBB zj`7EjdoceN@^^4cq15uy1979juzyuQ@FSHh>87*CK-m8M{OKg~k2dk@6DlD7d{k{f zm%I$dsykP3_Xqn!YIiLs+DY-~dokn72>AD(SNoC!1>4ZtX*am}2_QeBo#;$Dj@#Vo z{wG_1yO3Y)qj~FRAYW-ReO_+58ErA#&z>LPs}ovI93A7)-$yLJ0r@IAwvue|-;UH5 zZ|CNV0AJJMx6laHgZT4mVZPMkl4-w{1^CqWopS$$zrJ*_PBwK@scco>jtncJ7Lj$B z^cLnT=uj!`qw*ZDy~p$o@@3vwP5r#v=vRfKK6^fZuVKx#)aj^# zPU1jQx&OwmuZ}D%k_In&+^T6S|-ewvYjI-P~VKK8y~Xg3;6Q+q)(TR z4Z)ek0c;%X-`Dkz3mIq{DWMm0~_`Yot$%g4JBHN`FHdQ2XBejt9F{MVU$E{aBL*a2nruCd_Z3S~fK+zld*U3hSe$s?0u19^q%2!u;C4DWy&~Uf>5q zg!S=fO*NfC6?AmHh53zkIU$WIs1;Aw66SYE7N)gHK3F@bjPV2NYkjINNjs;0Z?%7E z#cWG@eNQC*Ek8dDt{=QH-;rp`@)s@j5160({7RqZ+*pULUkdXZx@XA>^6wE_C@U;}_DanA<>e$PL)q{_{a_-yPh?)!)FXTFIa88vV_no_@8&Og8Y)@xM|nbR{FJ(|Gm zGY0yZU|mEz&Zx(leY$?sk%P8`Cjkhlo=CkCB5na_K9RGg&UH<&|`H?=WPDnp} zy5Fk4+7lgGX1E-`C}8<3XuqfJyDhZ~Y=eqj?c~pw?>`>fZb_$VMBxzETy7ltkFTTc zh~C6#6fSwdjcWsa4d0_rlfH%FO3L_z_IsJaDkABTjCQPf#?6QJd&G|rQs=lEJ&I-5 zhx?b9y&XiK>&?fGn!$qly7;9#x%X=u>ea~NGnhX_>*4*@2df6V}h|%dM#Ra1_>j&E7BMvwOEK^jXwlyh>k~zksSFTGOor z-`Xe4-}bO9Dj9thA9E1qukeZ)9kMJEf30Es$-ZS?ebaZW2@OG!SUq1w{{8X$H@ycK z(s}0LIPl9?_WnWt`haD}rH*QK;=MjC{R8~?<&hVrS_T0)D^XY<`;WXU+dr%=a+>MD zU0(vu*IH!!o(`X=rc)a?gS$Vdk1>O-$gl64kfLP`H{S{Hw{)2v4cxX4cTn?X*GK&P z-0s+wBw}?6nmbRJzbW}vbb`rdtm`^b{`d3q!|T3=kSjgYkdu`0c>?&CF24rRIoot` z+#1HG1o7(|8>(E$p6qQ%GpU5TKD7TEJ&WlfgO~XKUfKWbs|5Aty+6agU@Ph|l=;u_`?72*ri&Lg;!b~Af4&6x&&y5xNoT!elpQJTf9O^g zQ_s$gczC@0{e$z(FNBAXgBE*R)&HWOHuO=?E%?XI!-D?FWDO_s-h5lD`2!`tVp_lJ zHU2*&+4sT!zLq*Iq6Z5@@!3!E?*sAsBU2TM>Avo-v7#0GzS1%O``S0!lBOQtj4uYu z=L7p;|GS8;@BA8jeiHt^BuRes#qA_42^Rjo;$9X}osX|@`*QYuVa)%&q#aj~+5b|| z&5te5m%o2zhrLCz^(C*c*-7?&)dT;1M@0<%Q=EtEW((V=(N;w?Z`La;xi9>E&G$*7 z#w*M4?NH(GYxkdgx~usao;Kc0{(bV#-+Oe;oG!bw2_Hxmv+o0Ze+O5Z(@m+H@RB1V zxN-RXZ4408{kK+PUE7xZxA^vL(~Cv)V|NMG=>DG5U${PIP_N_C1#_OXYTuq87gHaN zRk-gQ;qPzPq`T6xtPZGU|9SZR>G+h;XWs9y8W!F^R=LuFShkNt5^I*9gWuojp8jOi zrIc2`uf4h@bkwYOIHpfaet~bldi#cvMe!ME0! z@{h!!M*+h5xjADO(N{A!wEF#ImRQhh&!h1jefE7o|NoJvAGNSf!Slj}`S(m)L9#pU zMsxk;f1ilY_vRbs^o@Qr*7~!I@q_sFhs^Kh^qxmF_Ng&r{{Db{7>*qU= z_!n`!_!IIMZ|O%2l6SS*|FMCX)2lu)xWne*?D|08b7MovSo=)Wu!r%T4*aL7zf5V_ z!f3qDSI!^kU+UxLNT%+KN8@!Ee-aRXs&?2%ZjZl;TysCmf1j`43luDE-!gvtRf7(C%G?l)8-Rk}!jrYswu$ABO&Gn2wn7`ZK z+mc39ZpD&?|G4J^_wTA4cSzdnS)I6O^c-$n0`hl*jOS1_rPWw(<{9>ULH?shLY4Hi zMi+E)lM^=%`AaW$r7M0X;)K(u_A9wy3!ZgEn7@5d7Bt;+D?W3c@s|$juY0DL zQ{8P_@H_eXJIG%f+5Vd@iCeJE6=D8}?E5_RY6~W9&ECd39XcHCY@9{`;`mAOvZd%U#U%0>0%6d0a zIW!s7bZp@Gg#3l|Uq+_wOy$+zVSmx)I0<=rBo}Q{Wbq~B>#J=2>-K%|SZ(YPLI1U_ zz9X>-+rjf+Vf_^kTSzUlBk+dpj4uiBPybVut)CdY6;G^^ug?Se)?21ucNJst#A(8O zb&oWsUaGP9ibq~G0=zEHxb{yruI5O-G5c%1s}Gvap1q*9+E{3 zZEEqZF2a0uSYJSU-g<}ojS%KbZ&oSAKbvspy)3^1^=*E@e7dq{1Rk36TCOkr{Mq*0 zT&c+EiFn+H+1xnPH`CrGv{Cl_O1iNAZ5UtmaI2DD$yRKYuk8!WX!7=0{P{UszX#*1 zxE>Cqv|A#t|1uZoo07;p{KIH}4dV;eAMCW<$oKv!$h(C3 zr!fDOq_&V6R!8E-9ASQ@>@uT9mtwJzrLaDw$C}g8%eLV`u8bcT|7&arqYEDA;0v0p zzYX%U=1Vl4>U0`U>n6WG@XwU`?4o%g7&jqxqvpT`G6&#mr<|hzwvZmVg1smTR?R@H{v6SZ#aIS{WP7Q zEzQw>BpzuxLy#|xrW$JapqtJ}Rpx&}{d#!2N?N{58MR;O%*}`K!>UPUv`iF-T@;vp zLB84sJCn9glhO6=Pr3O}zt+4qp-6KZ9$eM3zKNe78+Xo=JnX#(-Pybf7_9tM+x$%Y3R*`3Y}t66VwK9-{BF!|^1w_8h+w z#E);!JlCb^UYl@w=Xc!mh4Jl(pd4wU`7?3XAG5e|sDIa9*3h#vRdr@e6Xr8|PnGm} zUN;_}5)fbP*lkU9loRo3|0DA2^ZmQ8+r3HHy}hW&y^$M-@rC^rW4gI=8?K_k^84rW znP+K7R9^2yiT#*9tAYBge)n*4eAO|OpZ=WvK8P=pIt-?&pDb{gPY8=|0iV+0>&Z2G z1W6)qbMqme>pt63(Se=3{E`7Lh~O}O6JDnd(-6l2kdjF zMLu+^Xg?17yIcN#`SHg;`%t+9nS zx^!FEX8gFnoL>>&ek%kXl%~CXCVt&UnBUT5yI!U$%eK zwS-pV56>?qwBd3*j?x>3xcs?@pZ~Y|vy7&Xk)1#NL72}Q(N^@;u0(uuLZqBuKA)2f zEve?Y9XNji;}e7Ucu965eYo)Q|D)^7!*clk|9>aDN{iAa+4p_lI%gtFNF-88krtE? zMWjd@MH^aWUqhD2cAq0lS<_xpktIrzB>V4ve?N0>^ZH#=f4tw><0=nR+2DfREIGzwF~wy00J@_g}n{=M%0! zyLiBz9PfDqt+>eeh4cT~k-o&G^ej3R@$a~>e_gH7mM-|S4_}T=5#_h5PXIY%oQBMD zS^W&gH`X&x6Sou9Xmu&e-@^J<)${o@YGou&G?42b(9ecHR#a_D3|={k#SgIm>U`-! z>byA`hregf*AMg${Olb}&(67y1Mi5>|A#h4(XEvau<}!JKF`mZN6Sv^!3OPri1K;5 z^dNOVTh=U}#W@$~z?O~JG(eosq?I@5oVpg=7%euwDnNgGgRkuER;M($_ch{tdKe#- z_CEW@=uU_6^5-v%uYZLWP**KY?wXG{pP%pKO8@rNKtskbe+u~=y<{PMeKH2C3>4?{ z{b*OxO7#%RPiK4v1O2>vXBzFA6N(2VvidFTAL!U-HR+{$3|U(+e+$<~zLxrtfuAm* zhIBUn!}{#xZ#J~Y^Zj_gf;gYO?`%f0l~#Iof?5%^M$yBfP}<>}zz8w$Z7;ueyor=StcBGTUhsRyxA+-+o9KKkZv} zo!abCwonGOlIu9h~2Xcb!gqZQ6z3 zn7YZYPv}p-X1J5JamNLG!u_}VPW2-#v@Rj1?u<{E|6VxDmX;ol!z0!+K4JbbvTg@? z(e?(Kmd5-g%s(z|XFxN`77P3-#zKGkSI>k#v<=0Hs*GQ#uNooqs83cDzLX{B3+U^* ztv+;P=y|;DIXfT5_pb3lG{E5&{=G$hK8T+@i{mlpe^odObK5=y&|NA7Mes4H;HR$&91{kDlU$NOAogm6uHao~^`dmBslTd|kG`L-bx* zQmH@B7v$IAAf|^7hhTrV*7D=R_7UH#(ic(qMvOSWqL>Y{oaSuCy4XCl>S?PBGl)s@42+;r8Z}4Ew0aJM#=UM@zv$R+Oql=%)eI5 z$(9CA(h~GfVUXX7$}*?3V)o*t$JzQ>n14M}<4lH|92exbVEk3>X-ZeOjKtLs7{4(7 zx?$%|rc|Fs^A0oqpns5bF{gRjdjQc1$^K+h0=r0^DPoZ7Q!*Jo4e|!n`*Tltww%WKKpDh>HUoO&u&fd2l z&&=+FSpStUzYwbAN}qK)(JbH74L8w(<(Kf8&Huh%sLxw0g6OFc8QAi$INvX{JR9yx28L%(k*ZP;vt6O@tbUG z6*_DDPQ0{IobSxvNz%Bn?~Ly18Zmu9LcV8x%B9}=x?JEcalRGR3h3?=dfffa;(W(A zKaBel8SQvIOKajqt? zn=ZEJ3#`d!<33Ati^ z6zM21zM(&PP;W`!ge2jursDZGEXxlU6`Vn9H&yd|LB4yK&!Z+q@i?MxlblZ>-zSvZ zNy+l_&GKE*ZYs@|M&kF;jBg3>*G5BqhF#l#d zFp~T_ScKB++57?dtr=)e?;FSAqiy8;0Dgz%*px5~TJ^J{a}T`Iny%>Tgu5T-rCS3)f}3 zIG-&Z<}>Q+4+Fa_$eF7`I*z|`m7g>J<RAU`}k%$ug%PRC0Ji1RrwERdENWMLy$`R4;ZcY5q2-)vu@W#eM` z-{%MT91ygRWcj{A*});~IM7F%L5MDT8II9Y9eMssnE$OfifCKUJy>DCIDe5TiPCKs zJ{tA2o+ST#A%F2SN0y&A;5^2Q^Ea}{idL^Vj5o>NqsZ!$!u~(5+hUS^<`^ zhs2k%_frjy$NK$y%CBGOZ!Mw5o_6=;LS zJO1-!UO|vw?{Q6!9-u35#WXJ?{{DgWD;vhlr79N^o2_5yJanS#zoy`!HLN}X`MhQC zO+!at$8}@H`7AMsB7a(xp@)x;$bY}Ef6&ouE;V|Uh*MI;=Wn%-NwimV9S(95_op=j z&r{zAExCY7aea&}o=eI81GqX=L(Z=-e>Q4GytKvg8Y6?EfAujTpZ#a$(3f>xxi*dB z^);J=`ILHh=S*_M^|92-mTZnbj)v#3{szeBV2gM3>Bk}5wKQ=)PmXXVh56^uuYN4Q z3-xhG$63^JSUi5rdGhxcuFpC+b`6R2yn@0X%kxj5zpKOD*>r(#0uDA7=QFdlFS#&` zqMq#--*EmuWe`9N8#B?{`%E9<{5_-BUNY9oTk1$i(^8?`AkXoqOY88;BkNC@f*mG#pXv4&zu+Nr2S$3 z{=xnPtG#>4P~|tsDV6OHNq~MPjF?Ne>mI=2N5uKfR69Ub8$M(2RB?X4C(omvAqR0N z>csPjLH?`n`gm!Zb+tzGw8j19mWF3^K&x)t&S&C$p7hVB9=CdMA8N$;Y-Mai4)!^L z%HJ}7SON62%{Vja)Hew)FJj{t#!n-cIg?K7Q&G>jX86>fMH533aOY@oKA)dfV$wb`@#j1ADL_7dBVl}>^kgnItV+h85C1|ezb4FIt;l zXP|zLj-S$+D>oC@&kR|A!>ucaaNH2aryt-m_vSw7lxH7|it|P@{Q>zar{rhUVR(0L zNSZjGT<=@b<%Sw)c(#@Nd|~}zpld#D?AnX_uD(D%e+%b-iH0r7n4}oGh-dgYBG1rqKmdme2GF>g&l}GwBiEL>w?goZp-I?xgDBRpiq4HGln( zUkz?E`93HE&HTdng!P53pSF|T10SL2Z%jX7e#*8qnkd=6Meg>jza92>^_-+f$#~iR z&+{3-81SodUx9Ybn~o=HOqAb0;r@SSD+&4jvJ=+2Es-A=_8;b~_M&v16qog8e8c*$ z!{kV!u<#XHHJ0gv1oU_Hl-13a#8;thgy|>rpBW31=!@20@jEMVJ|8)qrCOg`bB{i< z{&Sdry0dB?z2E-`wqDKng!<{J9w$w5{$w<}aGabk;rw1c_8E;B--BDfRh&<=>*>;O zZ&i_>!hHUG2^R9%?w}QYt8fzE4`KNgn4d~}YfJhpJcEXgVDS;;^RUxf>P<#)Mls@i zrq?=>VeuExx`XoP5Bg`uhMUsPZIbXqj@5TzeZlISJNYsC8dB@Q_=NpkH&$*YwzYTA zd@B}TLw(JP3?$V*o}o<#7{5?oFO=)j7suBK`VSAn^-d{2L5(+A2{K5W$^>L;&Joo?}mnhC(RIWQ& zqH+VB4`ckn_*_S_nKZcFL+Xg}2mPhuxghdBB_ELtHvgN0{;V&u_bS#ayhk(q#OL?h zOZDi_OP;uh4f%?9uxNWAmzkGam z4;lNX5^buHKOfMa?X`0+nXUN|#V>4Teos%NT8>T4^4D$ESz5NR9e3A6eE!z3xJK>& zXmF#6c>Z#Ar&y`(pf5(}wZ!$&VsADbkkX4=u|S;9*Kt>*uK8+coaQ{HuYk{@h27}= z-ZIZ6>oX9G-;*xek*lxIBg<=__~Ras&u~L(qr4TD*ZHyYu`qsj(RCt*chZpRQl>AE z&yN~2Y4xmw_@uXd{s#NQ)ZAQ6TCKW;-d$kv5!6S0*Y-55+yO>TmUqxeb7=N(-fBdB>9lrh$e(cZqgZ(S_t5%bPdISY_dCPu3 zh|e#5ZAZO6+v2E<7mPnF%pYY>Ur)BU-a)&sGXDtcM|~>-iGo5A8ugLs>rlX7rGXlq z>*^wyzhVF2^)pdqonH;Qw3q3tAt%f)d9_!d#V5>gR@nre-((P<-(B8^avcKkwb0gx zjelYNe*o1nO(`6OX#V`paSce|Yy4s(ZLScWswA z|1mSJ(ZtzWTw)7ZAN8rS~|Z+ozd{f5&ZQ*{)=8crO&SQ;VRpT>+kNH zm!)eCsUsgJbN+k+`2TPtk2W3|!2OOFkDsiY?8u6@7m-mg+dm-~@ZaO-Yx-3>mg_Y` z+@HFoEhp*=(~*v^IRB&C&!E>v9>R5@;`JGIN#r0*VDl*?%{w8alQ?21d%^& zo}=xP<$Qzqs>_{l5^et$(RUI2?~{Q1RL|hK^t#GPe7wyc^gsR}-^IlVw1eJnJn6AG z-){aXH1Kx^?(bi5zQ5MW_P?_4%q{-N^d0hTwqu_(`f8)m>3nhjtFrbfo$|Ub*DuG1 zA0Kdkl;s;PNtf5Cqo>2?i1MA6pGV`T4dQzK6z98JUpwMjb_osmDz5JvhAf~GhqJgv z>=}0d!1^zxpylL9*)>6a3;K)QLk+3+%5B)qpOc?2te++faU=Pw8 zdta9IzdAf;`VRR1>g!1yRqmq>fsF5DkpFVc@*$1CAEBdWdHnZ7zFlg=NtYW{=*wxg zeh2d1@qsQ??XVfgSulU>hlKlE4T;)B92Fj+h`coZ^ZkIne+%wS<70wwyMBy+30OZC zZM>Nz*grclxw8G;k7=NrSIpS+1N!}Lp*ek|dKxQS%;As2{>8{%i-}_NWn|n( zobS*E+5RAB&S9Mc;(WLAb0kL-uM6^DejvZ_?UVxTQ8yp2$<=4iANXg-E^cJy`P=B~ zB&Odm|Fy`ZJsyX1n~dd zwl_VsKN$BMBF_KJ1|Je%{zSmPAMiJ=l!J)=y%%WO+T-l`g8i-1>mtbPV|B=W80%kB z<%Iq{{cSj1bm{{h<{~~mvNRK@OUUzcA6YXmAL+L|%YQxr{KZFyk{!Np(7Lw& z^g-Bvs2CGQT6=v!57sC1=R^MHrG?XO3u^ERM{)jE=fu-rtrWN;%f$IRbmj~l`$L7> zQzXvc=)84u$d`lBDiW@GSGEZRd;YM$U}Zyls*&T2H=U^v)z{gBJ&E7BhiE}dw*Cg{>%>N7 zx};zgo*3rH&X)-Huf5e~BT>En6fI9@^G`6~Q|+rZbsoG`sJ{~7`m@kgQDo?suV``@ z%O7IEuPW|AM-2+b`(3y5{7NK3evcUYkm>uLp{YNv@b|w0=&$LsZG;+?pxXE6+4BMK zAJ;#zla&6hLethI@y9)Ye!koqPFvjgh|Mg;`Q4cwPlvo!XjVUi@13UCXLRIhCX4g? zL?fNfjMd{>$?80O{0scUtm?2|9qg2o9#%k(sdNIj`0igYkEZn6z|-DkHoS38q9B0EL}#%4Uh`fmqY*idLNlLF@FH#JO7k*B;v&*l=Fq5f)4*h2;e z)T6?@!=n7&I~7C5o%o4j%m2lP!urMhZ>Q<1C{->uMx4*`(Pnhd)3Z2XsCa+Ow#|=e z^svEP&)Q9*@!6i2bBS4XDmv)O_=5Y(cpufL(GLRf+yMvp>xb_*{ruUMSkJnSV${X+ z4=u`G(jaft?ELM#VJW%tT`H(g!20dD%9TXt+kHX(3(n8hd)v^eisd-sSo{O$_xL{+^n>1IJoZ!}|NCHl_WoI0 zq7-~Xz#p97OR8VeTM8VPZX@m=H-pO5>-(c9fyai`me^E+SVG@a$5!HruYuAfDh0;OA2KNyt_ zA1wcT0lt#ht5@i$#ID@$Lrh;GzaO&osL7HbTrQEa^TGQ+=J%XU-j2I~yo*?Wl^^h* zR=0BLpvEy=uOH(6bB?Ypu^T59=qs!*sG4h2?fC)tTtM4jyM~ufV)_a7+2q1b((Oh) z%HPcR^#lA~sf#6}Z??iFYVzZtzL0r5j&@z#n#;2l=eNC%KCMd(!VSj%^ijBe;8_1) zsne`lqZ>2C^>@oK+4~b_8FJw+;{0|E)1$un!Fb!7Tm0{b`*YThnN4OyUKHpr0sPLk zm+}8K2!A-q;zQ_9-4t!e$|F)ieiib&wu1#-dip93t3A!`KhR%;#HFO(^j@?5+Z_{~ z$;VRa)XC6{_%C$S2(YaJFU$QF&K~;tR$3ED4)W{eGw8Ee}}# z0OaqW<~9;?yb|e^9^$Xxo)gADdop$s<^2t4oK(&q;IqS?{iMy-R=6>j=`-vv)O!+3 z7sj;auHE>zK3nKdFFEPa@*hEX%jv)J=O^UzQd6L`6LYK>E$w%f7AfJ!ywCQ5+K-~9fy!?D&d|zW~O=^x3 zv_F-t4}|gk@C;e~&mbK~b`|HdpVu-n^HwHuwPXGj>TAXX11dSXv)TIAmQK#(L+wL! zy^8S%`Hl2hOVt17BYRh-f6%{%jOakkF098MotBF7+5VLusrRWA_y=$co`c>n$r|5ANEzVk1+#f_e50kFz_sht?>%ab*|K=L@r_=Td{duN4w;)-Z-;6@p z{$Y;S@w!V2EWQK$PD5s7=$tEp_zUvuGFXT9?-h){J!AeJ#$Q|RT9aoUw~_x=7Qeyx zt9_|9ZFnAp!%{cO`4{?w-M^QTSGTf|WpBnWjQ@vbI+AS*9tz%%SOofOI;M7}<7Mxk zIi2>6@dxTtKL)KPQ=;=w*JCC8_d|Ux)YwQY>|dbMFU0Gwop0|X?cJM@>xnY{e0vbz z&v(_M`wT;I|BIWASbk8L|E#O@Cel$a5bk)DKOgdU>Z}j>b-o;Jd&$N(0r~xrm)%KC z-#j$&3G<&rfxcdr?j(<0o6wW)$^7RN&|eUAa6f4{-Ub)WVtm5>f>8zu#G1Cpp_uWB z!TMDz+5F%3W+qai5MAm&A{5&-iR)|4 zD>HI_bvhc-nZ-|roUnhpDJ+-fCr#q!yt0z>E!5ZNy{$=NaE4(1hkTm6(V@YgLa_Et zAO8Nq`cm*Bdy=V@)vSLV(5(yIU$6`RIm+^<7{p)6hnADQxsTCi`TP#`RpFpJ!Ik+a zcAYq%bIN`bwOz}w`#Cc?-@^QUMb%c~Y5xZOXu;-xSbv%ns!U&B+k*eoi~sQn_vfmx z4keRXH6hdMEPo60`zvu*y5nXzUU1xBl<(w_jl}X)IZ}JX_{KnAf0nEzN-4#tLX+*U zUjg_&xY3RHm*mOn&x~(F!1qayon-X4?##YyDUEo`CnAJh&;}{ zBj6kQhlLi}G&m^)7x{_n?~jp7$gC4tXz&Zx9|--!%7tol{G9E$?dsw3>lemno_Cj$ zl!`~_W)z#BVSQlGQcbGa7>GY4G%$Wae@ww^52ARuxY_!FvBGbn8|{dzIL1E)@mbC5 zt;BZdJLGH1_}>Hkg-uNmc^Uf^&FIPetq0KWA@B96QbriIDA>yL4gJGXB{ve^uK?L* zp5uSNJ>Yx(?A4@rco8DyEWZ!=9;o6@{M8Eu`mGB1Hm=%29y`84Ys;Db8UnswO1jYX zMPayhBjZ;B^0SRIb?IuSow)aKaejZ41xpW@d^bw4|M&cuclhuBL(iwtP@CR@{s5@Y zsDsS6=c=NLB~$p{FTp~7J8#makBUNZ?cy8qn`^dL~>AyY5pWXTXf_Cg~%9XSmEgyeEf1#_mgrsOZL}R~; z^ZhwPlU}qB###FR{FRXJx?BgMapW<2`i1FZCh#A1joQ@5bSGYw{e$Nl#&?D7*OB&f zU!Y8_a{l-20r@pe{m!&goNRnv-oT#^`JPzdPdaU=K@0Mj|A6(|Mnz@X;Npk>dzQ?9 z2=fo!4g5(~?`mYQ>k0q;et>`d`A&qp`3&u8!~6%-@2-z@>9w!Bu=Lq)etf|GuvWKa z`=6~SMwhNK{tY={{bGWX8;KZHggWdO*LS6!t4VN1F=`dX_AihC{%>vEL3V3>k-fhu zl)wH8kiYn~t23>X$oxaJGJF1Dd`v3Up{9DfaHnT~*zX7X-x`U>_-0jV1K0U_qpU(5fubrw#!2{#f)#L-)*$@ z=!dD{*y`XPQNCw*t|Fh`7omBJSbk$D;QLk=5AxBZ6y4jpkNNMkk9B~ z`TZ64e=SoBAWzKd(KdCKKlKCtd;20CIxA%tj-4saZ_9Zh($vSljXJFQ*MI(>7O+3v zLzgKo>BBwQBF^v1gam2CHC0sbg7v>beygwIOUZiFn_$*LVaV(7 z-Kd>%K7{!@W6NM^?dRXk>T_KBCE8(bU+#dSINvG1*e#JTBpv5NQ{GP4Sp&J&;-Vb8J z@+WZrhVcr^$k>&+sMUDZf1V8d_fTIw+U?mMJms4>|F;J_5~YAVWT}~s z*rga5Y>MKKCxiT6P{bM%`m+Mn1?=RHLw{~O&WG&&{vO3yZ0CVx>do^1 ztqGFDOaJB>O^kySRV<)Y_i>oSY-5e?$H^ZPBDB%y!|$RNTKWnYxTDG|xvP!JADh1t`3!;=HgT7i;HwchyL8Z_me`tkL-?sa8@4wfcKYPY%zyaU&=s1zF+v?2l@WFKZkbIna16y5$Ai% zlm$c~;sLs&Db9DR%^K9&eJ8%YZ5{vl(7&uVUqbE~dW;Y$9*Gsx^WkbaIACa{~ zs#W#JsMVbz{QdI-{YzgHF48Uf1DfUkYJHrvTcQT~_x=kE;!o!{vuNb-47_82xPKq) zX-+2Yy@w)0#N*HEZ@uUP{UqGw7mJ@@{ipHu0@8H#5!!B0$6r6xchh3o`k|=-cvjSM z{y5}+`WxB%qpk9qeSg649A%oK7ldb0`TYU;^@3#%3)h39=P zVEPUG&#-$QBwm(3mpo+S2iAw)$F-pQi@foRh6SSI=k?2FWQTS!QtHP1(RtvH6jWQ# zx~EbW9|A+a@MK|x$@(9Gu>L~92U7F0u82@|7PP>8s z{-L1$6cm_4^*_wudbnH5;}>Cko7rw5>0zyAc_|CNUwxwtSNxkiig-KW13(I%y6s6Si3 zhj8$+Bg|NT=T(`STI>pG@2AM)usTL<(=k`CV$Vm8{Nd zKoxxh`SXJTzj}t-$>6}BNO1_`7$2jn*LUS6G=|Ebzc79sFf3Twa7Ga|m!Ii7 z;Ue8VV-WW=SDfFpxUhmJY ze<&x+zhs_tB!Qh?2;MIM^Dhn?+EAOOZMZl{zCH@*ci^yfDCYjcG4Qwi`t7enmGn!bfdt(Nf(^D~>` zbm-b`(YW2VExdli`ckx)J*jV1j7Du?{(cYOzeLMk_I|}8w9rx($8G&DO9bmnRU?)W zrPI$*Vmjj=)=yD4cXD9DTjb!w^5?LA+9a!=1-X1fW#<|HP`^7h`4h*vKhcei%-={r zezO1eqqJ>nL$2d4asJQA_*YM9iQb(ZA?NqMU%~!njJQZ=L=NWW{1NB>UHfUW{rM>h zd(b35U+C{W9^RubPH^0eL~nll!TdT`W=2c{v(ShOjDM)#M^0IhS8BNe{$c+7_B|Wo zp;Lg`xQW+~4)p9s+x$$x2STUw*GGUq>9J-hxw)^j+4svDWUe98L#oloQx*LApMZZK z@VX;CF>n_io8!jw3;p|`k4s6E>I;GYfccr7>sr#3Hvag(`_1A*VSOmH+LoLcU5Glr zyug1y^zVmGJCKEi&r$UumVbeKc6qXzEJ}Efe7wZ#`&(bx%lfCEqxGJ<`Ok-ZMs(Um zxD9QwN=g)ed=Jpyy~aoB-QR{>>kx6idac_bol({THP?UoxX(ozcYX+0Ak%T)KY{*} zi(1pjgNYgFdH?VH_e1~OIQ$-6zu1^77$VNs)SNk_%j1X0wFk=&LcV?u>qK?tM_@tcc`-IE=L=dJW$=Y#%K*H|0!agj`aLd5xOlhT#W+?#+c znx?Yzf&Sjw;XrEpzCh1Uu>1$~&ujJ7XyNQ|d~VQZoQMFkO8)a9 zzxGd*sFr3Z?$OFslwTF|<;1(90!h~2=g)`ynwr}Z6XhaQlF0Zx0sOJ<>1E{P&aM|2dRP!{Yq* z|2dT`J$DCnT*>%_^_$+V-KkSZGJbRJA$$IyzXT7TLq%CG3x-n zJBZCsu)q36w}oWMu{^>00H~jmL<8!TnSkw-1LWT?%x}-WZ$q?QYpy)!TnoO=BiK=S^e&x{+{QA`fD<33Hf-i zwAuVgiH0NTx>nZTE$>fV|Nsvdti>3{_FmCG5jBm zwkOuVU!Y^B*!Y0?k=|#>dkqN9d1t-39&uj*kdg-L!0P8`=Cal7Id%KhpQ}1!~)MxM2Mu%nxRcoJyQ$ z-4*%=kRQn(beXPLG?Ft5UB>(a7$1lA=a6Upo}i;G#r2(p>C=$~@i-v%u$*sU{8#K} zNrD6OnvMSszmoNz4T{5&hW_&3CmbKQEv?CY%VLyY@s=G2_03Mz9ca60JMq=h!TfO; z|4ElRkge7gsOMnjFQC4E7`dLfX*Qt8Pha!r!~G9WTB%aEbGxxm^lDN5gCg8X?#7R( zu1hw5K8*jmTDGC<(}erGV8H(@tEJ?l*-I4O;VOSV^v@T^Xwm4P7~IEVqtXBP#bEum z>6PW=+sW6c(V6Yv0PFjOxy#AYd#}-z(X4+E#*dNh9mus76@vH?)<2Jxdy#fG8p!-~&Xegy7+JosRcbVEa%X7%6y-37YX zas=09ySV)t~~E9Cwd@LfIrE^TwkgtP7-?qABUnvthto}!93;`*O)=b7yN zH1oJ0+im3jNyv9}$vmQBn~M_aYUICPxPQ0bvJx8i-kPhLCtlxi__&A+UsobqU(NW2 z`u}%Ic<}rZpx>8UI*^y)FHx&V z7XQKgcVU;dbk&+*{GVL@kG~UuU+p>eB)_NveLRxJ|9;qCwX~}ijqurvbGM80+kT`Y z89-hO@*mJ&f9SY`RPHZF^=T~r!yy0hcyoW*`wLHDg~gUgOy5(Imyo~xDg^!;@_oN@ zHPQ6?gete};;+Axv9Ld7rMVBe_2DP#I!2uD$-M)~Vei&BvENqy{A8f-j~~aAjf3>@ znT3ph`2O)De?p}DO*^2E3&ybf2l9J+USFVZBS&&3=f(MV>^p@ROYWgo@0mUm!2isx zX>|7Jv0QAya;EQ~{(}#hk$F+s&HDFK-P7pfqA}c^7e=D|JK}ky|M)y)yN~e?>-+Ba zOK4iYEvHf?&cB;v5n0{-If~F{{QCiY_l;jd9525_AKNni_kjB4$X6<|{M{ZruaNm0 zdrs)jH~v{iR?KKb+vhTUhxL80f$eFD_fBm7gROsr?_Vq}UP7!IUZT0V8T|8U0{Oib zr`yw*rk#TEF%*oCp0Rc$;d})O@xRQU5B1$8SBs7_+K(r-^WpVf0`z^3{wgwKel3c> z&iubB@b_2r)aekPC_HXLgZzA9{j=vtJ95gjLXba!u<`FgQTrLv=jIn$^YHU|Mcd+zcJ(j zU6C=088 zAJ#t$)jHF}#8{l0Fo{1O`Wx>bw&eN63bgeW>(7P$|LL4{B+T_2y55TM59>Q)RNB(f zi$d|w2WVf@HOw!c|9`n!eY2Vs8YR)H!# zG%X5itX?DMS6Cm7a$ZFOmVH7#S`f%TADBNh zvW})ROSHJ!t^f9C6!w3iUx(=}X>V@+5f&dqe^e#QA0CV7fU38RV*KF$8yNh5R1aOC z^(tdHp#zm>a6^l|MCXTd4`!1ml{wA&qc)44 z(M!P#xW}rtqT@r|cn*XLzNcjL}Qh6;^X5{up{X+ z`~&(pndK*8{^e0YHIv3|%#l48Aghak97k>qz<9VNUam|Psw0>)Wlw(n`VsV!qnOR)i6Fb>o@$oU)aTbxh%|RYfEWZxxOTRpyQHh}yH)yN)_|S};L#_=f zK&FTP^`8sl2gh1%dh<~tZtcP54>&%wG_1*jma_cFY&L&D|1|c(0#X$D zf4vJj)2h=6IJfZ+&$k5lr*kpxL~C#(dS$}mXE;7iUs*+-;|8SDn#I4FV1DS<+J+eX zeTkx-nSMjQ7w=Z5S>yKMj~&)C{RjI)Y1~>$zI}ax>%a2n zL;f=s*$`LDS4j4LO8)ml{`Iv~sr{K~{C>GO|CM)^kzTE;(dnO&{P{3{|44NOu?zSt zsINl))qDDq8&df(gnbhdccg};(})9hZU-t)bei}-kY_F|9n_~ zomak){M}H2j?QQE!yXVnsO4Fb4+~`Pr;RP(&p!e5f6Y8i`g?Lbe%I?K&wmBT?`z$6 zBTbXO3EpoF`Jcb84Gk{bg?kq=|0DtNb@iVS!GmZW~&HA7J zhW#=3r`Qs%-5d1y$|e5#p??Zl*@ecPJB-^tlkXn{_Ps>&*NW z96wdJSCQ328c}-MPX717_+i5UUy|ChB`zjx{J{PM-w%F7U#T^2ZvDuPltZ*%pMG4+ z!Q$iRTy&81$*1PWk5ZVdKO`U?TR1R(4d;&u%2P-HdW_bdV&lgij32A(m*~k+lQ?f1 z7JtC{>|f)Vr1W7Piu=yS53E0gf7hVfKE&Y#9P_srtRHc0JBRGPRfH}PHh;kWGYx-r zYG)sd6$>|rj-TpY3rXOlm&o_^8~!-VKP`E?kSMfyg67)bSp8iiKYrl)lUd!Z$?e6j(Tn4;{P{5czG&HtcI})Zs82{F!uaG* zwjDV;<-H(2f#YYXrz^>EZa}e(%zwf0Gi8Ynsf$*`?w%|@F$DhWSf(H8o!c7U9weWC zK>li^(;>Q~Wq+=^r}+4}GcHitd!@1nFCIs0UT60Y)F-MPOv&8w`AEWvkDtX!>h$);IBe98>(!{SKY+QvD!9zR!Q{KNSpFk~)Su&zw-emz*fj;JZ5y(TQ@mU)WjZ_E2zlCQI0p}$@%zXbc= zq?X^v=Na4awWIp%{($)W$;tVo?#@fJ*^&9POyJL)tv-`h`hIv)#Y5hoNq|4oS>!|} z?QB5GrEGjae|Dq4D_Ios4O#YM{;MVE@9%fai735jK>f9D@z-Yv`YTkut;ocuZ_uYC zrvDi5uRK_dZa0jRy`Nm1f2$QXMB!5v!fn|7hxIoLhsETlEWWsUgVmRzzK^b6NhYoT zfj$&6e+1);E8{&$?O_G1+?LfBV0>X13Miqg+`vJb+O_SB1y^J`|JaNA3H%uXsub-iNGk@^k5Ba{`?KX{cn!}ZPipSSu z)n*Wfrv-xjnV~=0AD2xJmfCSMxW%IRr*0kQl9Ku5g7qmF+^?#{-R-j+{k+4KS69xW6A`!;N z*Sk$8jc$dgb?RsS`(b{ld~G%@cChCnH;D7AUp|{0kAHy-%b351{Pxi+q)xk>o2@U~ zKATVSG~Xb-N8K2919+B_g2;$=--(5&}<_|%94D+YI5*o>}>j6UkLH}`nYfstxn-#J7 z^(_AS&4GUFEK`&1@1KA_&u951*gvu1tu<*lSS?sTavtcrNsTTo%s7T8OjShx8z0c$ z7(TNhyOU~=*8`^S`+>h%7~Y*u`*{|h4mIP?_d`N|e^E*He%rDdL4O_`KW1&*Nw~fQ zuL)w~2i70@JYGqb1 z9(K_|`R|SR&xid-t^7&m#Q~zCgR;Sp5O|n`7k# zv}L^uXS`Be|0iV5ClM)c(O5&~@1ei>o%)SzpB#wyC3KO0zp%gmaFDFOBexn=Sg`y- z74SD5y44c{v>m%|eJnb@0#%n2_xVk-{maGu%`8JT`gMLHzBhfn+#d=1`=?EECW_~O zpo1$|d;tAV>pvc3$-x%5KJ-3+{X@a{sr+tDVjMprY{B{;;rc2CBP&wi_5tPi#q#Gv zf3H(%OFnO?6Xbu)!Tg{%#Fbor_zN|bh4SYogZjbt;FaXU!oR5Y1LGU|_wWfVX@d1` z9CDeh&w>3F6Bf3lo_2e%SND7T=fnI>PX1)#bSPh-@6exQXA!z}&OC1OyA3?wFn_b7 zb}H$mSd3OSiSv1AR5ms2zKrYfQe5BttY#7I>N4bz&-jG#XU1DglDhCc$~eLDoByBx z`0EeghSO}nz+ClT_OXt9{gS@Rj``?CB!_vTHfH>G}iR7|Hwx%>O&DQlMl=ShMNm?iW6z`?FVY5oywoz1oZnra3`AB_7KkX`DG-g-(?94Nz$ll#7$-V z!u*WdBrSUF^*I8m#T=L3WF1r|dlkWX4qkz@LAIX@D?-@BKJRHZ5c7j|azgC7$5mkV=^$&Q}| zsQ=FI{P{4y|2kHYF54f0!#azPuL-B8k<_=P&F&vEv+5~r-O`DBH%)weHh;kS@EPwVr1QjY$lHb8KiEI? zF~@-{EBKB&?_>32m|xjeuRwoh?8bdh+OqKh{C%a73yJZTV8>}s`RjxAulJ9Cli=mT z@d4x8jHG)2(F^Ud0LZ%NR z+A#fx`N_@EE~NIj1pm|jp&&oG`NLjvudz3NdWhAZ{Xl-+F?|BLH2xVfe*1^NKQO-i z5|v6XSDSDxV#WRWR}EtlH>U_qJ}u6->c^?%RoV;Gd0;*N`7r;|yYVS)$aLm3WqDer z55oCDXVn~{IpiJk*jdY;5BdF_WI^;_RHIo|;{N)UPd(YxEeOvr)#J~H`roJLV&c8A z5h=Q}`qByDug9HhN88KlGn2+tGd?B4{!q7VE6AI3E%3kohD@OUAy*aXljuFo@@-hZ zl$`ne3n{#Nz+WHq*Xl?@bv}g){14QB^Kv(GY z_v(+{B>QT6+&PBu-!B3F=W1Ff`b&BgKT#3i-|yj^MdZoIdX&w@%g-0?UwLMKC%QH1 zC{DF7LhShp`8Qi^BYXd51Nz>Q<>#UQnX_z=8;Ojs!rn~FaAHezB?|*|NH-Lr$T#6AuE!y*L`k@(B8wyeA`0yDkDWv zW_BrLMA@>=W$&4-Y$c(Tne@B9AFo%g^LyO+#~;_@b*;|xem>9hoY%RO<441_C#IJ^ zmiU{L9~v5-5n2rhQdIdU&mX?5?}Lt?p4Zwxalv0(NH0qPqi+29sDIze*$3CId@onM z^_e{%&2KMG*AnjiS_j9Ta()1!ziycNzXlKhtTpLUsjSg5z5zhc6zBL4o!{UY#F{3Hd^`B;8U7kjH#R??my82?ftxd zM&}!M?5!fGY9~wZMfszDw+X0`t^sKemE+5?unG&uEr<1eLm0kfL|^@mkHGMvO8KKb zsqFr#|9Nv=7-n?)D)H~5iT=O)X&^qY{2^ECx|pq}{*C^RjoZF+Y>Md)3LzJdR}3l6cZ?m0qNXLrS{Ys%x-ds0u#Sou`mw}j^p zH2;13{-{tO&L^8TZM@R_ci*KxxN-f^Fb~= z%^8W`8>zxS|GkL(z6V9v z3W=77;YD5?k3XVcTxHX-_cUGD7@N<|Pvh^$V{!iVI4xKZqg=ml+xrJcURwc8`-Uow zuS)}G;lTlQVTb2gcK!(R`@J~cLWmlY1<@;%>-QE1Lh(u7SGkr3?+>B=OV}zSL3hWF z|LY%@EBpOU&l-qk0l(xI{_y-YmBjDZDGh{&*K@$ABDQ9|^!Iyg+YlVqs6yVNitpc} z`X;*12s{?00@o9i$9LAoIGpcl393VD@FAD_`>_+|v{Jhx)i;hF*bu!T8_o{p*wb`SmVs;pT{q5RcjHxQyh_ z5fA!ckFKxfd!s7Yaq8~}Z_pO(0yaXG3eVqZ|G}i=Uihc}2YJ?Ou8(N^_t(l3D$OR< zI^TQt;y_$+^^0Wx0QHAb+tw4d>`#MGm5%KGsD5gm=ZB|rKg<0qxW1?O8M|pDZn9Q` zHye5UQ+=eZ{vBP#@7FcA@@M#=`v+nzhGAj@70}n<{*W!HZ++Jk=f}FPll*>DeN=R8 zDykgPg<)s8e;G;if4)W)u6eQoCUjT+`#mcy2(|SK%;8IlexcxZ(=O z=km>o9AC74)y&XS}NcBnB#}) zpPT*uLkCZF_&1-B*2mi1m?(aqx(@6>zMlF=4JQr9D|=L-)2cJ<`l%%T``G`+ye>)b z{#G!HUpimVs97j_jQ=6m*XRBOjsLufR>JnXIk0|{hWu~*(*EgPRYBOM;;YcOdHh%R3&x!u z-{jw)^7yCo3169wz*f3ylK77%@vqt3LO9o9Kj^5N^7tX~Ki^@CU|il#vC&_7{p;BG zPFT`ZoUiVpJpKnOG=&jjfAsR5*VyyPWK#cV!pELypY}q2`-bxPU$?F|DxSQN8=U0* zYm`4ax4tC^rza?8<|vQ<+kQT1Vo+M^eC5pedxF=6DT;+1mB)YDW`Fd3RxU4Z$MqGB z{~g_RghpOl!8eA-Kiz-U!8HIIZ4~?en>=C9Pvd{Ho4znmvE%>xiy1%A{x+kMQCQYa z6Lu&6t50Zh@hbj5IO7NAxUPT=&U}6q?GHVoF$vE+*Ma&y{^>vIeDS85;{5pFYze>6 z{NTdLA=tt|70h>>V)vg!@D*}$Bu@OI4*kC!WXGe4K07h&8%BOlgu1Qs82%`J2G0+| zSz`RJpU3e-`D3Q8jWE;p2wXMtkSpVlfggjgOV)S!AO*({&9CDJS__(O4}o&h@5{S4=kZVV*{o^}L2uSZ__RqmejHl4qUO|B@(Ig1{wROE zT&*qy++Pm~fqU8YBNWp9ixO3L3^FW|>|dk!axqjF4s~A-o{#wZrTMjCOCQvUE0Y_a z5JcQS*Z&D`bRxT|ESxm?^yrV3RwF- zpa!4P{M)$qP+a4t1}i9;ZFQp(w{NHYCJAjUPn@2jwbjzxV;jqs*=In zzDB>1{XYxMhhW-TRS3%8&z_I&f7Y7*4Fi5Jhl&jxf7IW7Bl5?<8$TucpXvO#viMM3 zH|n>fznb!sbC(7}<@h6Tc=rUZ>sVAD` ziu!Axa(soXR~I@KZGde%Ilf+y{3iW?jnVr#gLM$0>fE z4Z179xv2`P2g>pD)YK0fP5dg^-$V2N{Ue$Qy;huqR_{XC`DuRRv&|nHiu-r|?f<0t zjiY`Oq1Em)aOr$qwx0Hv2AK}Pjmu?V_A!qgr}dBSWy7$8y$1a2FQxiz`q>Kn`CaP& zQvPu-8H|qC#r}&6C;9n7Tf%>(8-AhL(3Q}2E7y0lfA7Mn|T64 z>g+VQc`b0!WGomonBIWql+B^{7E&3(NUno9a z=c@{rZ>)!<_gd7vA8CI`x0`67g z4WWg~zYma>ISAK0R2B6Jf4`Yze`xu~ujsQVNutka{y(H+6s9bw4^y3Qviqm}A=dST zyR+88e~kt){YB@CCU}J5$v$HJ*?JFK4@AF}1$@Q-S|-7MU(O%2zpq#|5Lbu%k}q=N z`iYzn(3T�f4NS;QNi(Jh$3X( zM5dpj3BMeZ_r(mmPx8gPl;aD|s|g;(8=+@c?yn&62TpAE#v!}E%3A~}=bxY(s)Fss z4bVS-D0_c&e^1rmV9b26`(-z~KPQ5pD(e7D{ryY+ z{^t6c=a<$GKh0JVUUygzOZ=P5|HeO%`5SqMgRx7GYDxWs>aR)0Ur~<+|P+KQ#XtHuk76W^9;Zy=o-K51H>Yyqh}~PWmKocK18Gf2z+$7XVs~050M(c)hrk@m2f35k}5M2IC26NUZufN~eT82sa zDG~<*Mo|EPQGVuEVFZ^{J$PCCfrxIPbL?&Ys}@6Xl;Tb}o2Ncpy(d%Hx;nH_cXA zLgXfIMX&wJ_iy0Eo@li2y`8Qru4+(oiLKH6&$0@~6cO!QU%>OLUuFv_0 z;^)NFo5IUQ(-kk<4ynoirTWgr!yBs?|B&CirksB=)~gD8R&Ijl{f4poizfbo;oT4n z{hbqB?RE3Tqn_!=HOSYc+bKSLrvFNP~y7hR@j#Gcm_H;3(97%v+Q1xF|@Q=lHWU#{N|2bIaZ%ahNx9Ga%KFJq7j4z z{bbO@lIw>QqTk$tEQDuyM`7v&uHR^Vrsb+IOw>?=o8x%>lIpjKorht5J8j4`na%E> z@=N)^`MA)?0v=K4~9Ek2_ULVl^dq?F^6 z=0EbmH-*f~84BlF%JFgLgg8Gu^_RTqQSN`!`lrfI8{yZrGcYE3DZ4(M|55!g6o-vg z1OG?=`Uj-??8)9x9O$hE?+3nO>uLNi5Bz}Rza_#F1HS)4M*71h-WrV8Rka{E>Is{wcR|x+zCZN^sc#<32|~4nD)8_7 zI21qbmF1Y%dKH`*QNuq(zm3@xge|72z`y;g)ITU`XD+yII|@7YERz3yKFU86#P9cJ zit{~ImvQ{i`sRTPmcsVjTsUp9i>;^m&$5$4G5ex6M1G&eo}c2Ybn`syo?-zecjxfq zgn#;Pi^Yo*8bQXNaqKw7SHmQswwsys;c)epneS?bWjg*U%B`FvG)P7KPyH#z6x7ai2Wz4 zVSelTOdqBae1#SSV)7>yFlx1louA@su1g4pg{r}4qhxlR;^(oxsZbbn1oqWkC|8D` zjdQ{=JVXNqOp9gfssFrVft4_|;v}ea-Obih{Pbu(3l&?1Z^fv zV&|7Br2PYDJG94(bMoaw-&V5YRG%d{>=iU8`YF^mD94AhyeA$W^HG8iI=}N`-9y3^ zg8_<@a^?8gJFPdGt^6W43097e^QBfoLCR_H`pNZqH1P*ath~{=QI$M7PdPpY_cRbL zEzN-!4Y?4jk$jyBl(f4${>8cM+*jK6|(n7 z>pPuV48yFuI`Cse0Xt6jXH9GL154A_0qXJZ8&dvx=pTR@XI0>R;90hw&d=%aqY{fM z*Gu>(n)m~szYo9{b+q8nf|G2$5Ag?1ss*4yvP!M|6O>hsD~nfyfeFV4<)2iQKK-J{6??Sb{%@IuU`44q z_(gO6p#GW7&{CZJY86Co_mltS4_d!58z;_39jpn-y_DmlYe|mqsyIy1ae^!G^-}-r zLc%cgtI~xn?Row}{egKVVt=fO5$xDCfxSP9pFi)^1^d`^NND?k9hVXRtW|z{e4uzK z>2Id|(zn?jA-Bq3@!LZ=ev)z(__h4AyqmU+;gjO$es^=hJozM)1akkH`p>ox+;F_k zSBd_j`G4%%212;gIhZ#(i`_rvmwSHR=siLPxxYAmsQwDJvK9`832;LEx_+$Es);IN?Lvg|aO&C6w`_JY?f4Lw3 zjKGBwHS4AN>&_H^EGkz8qaK`J==>>#dlhCr-6Y``8PQ(_7YAU6Ty1Du=M;N> z>OZH3sR;QUQz6oLXpO#-&WE1hz;pI)JOBvBLku2{*|I}v_4*{c*MU0)6JK5=}}{(ya5!|+p6EjTxV z6rz4zEq;`%sYl+&oNpceB}8N#pj2awn78b%W%hn=SOtD%FDN**!iIr zbdTZn8H&$@FC{qY=qhMDna`)D{nuB*{4lJs8nj!-^CP-HEqz}kPSG`mgHw5Z6^Xvn zdM6WJ9T7dfgF_hpXn$#HkRP74Rg>gL6n_IPOEBGO6`V@B#n#IR|8;CK80%Tw|1ECt8Wn33;rme&xiWlu4+z4nZ5nVUpX&vrY9R{vFkat5tJ^g$D;H{w!9Gzo8Ceu>NlYFxxVw=J}-g(~O_l zLi5Z4ip6!~Yw#t--}M%6FsA!*7@2mJt*8FP?CsgYB>4cvrx%-Q)=Tj@7u#d=25;m) zVwB_4G~_i_?_Lg8!<6H*`(!}Z_%iuZZ{_-PqpF+u{kiXw{EOmqQbSGQSzso}8?Uap zf2lta-O3j~xvD{hG1sRQpE^^lga(%9ApU0@TTk`nZ;N2;_*)ZNjpF#E{zMy>147}> z!HQEu{^<*8|AWJ}Ak@s!1i$o`?EH^N|HH%4Rzh;UbKqR4&96`DxBJZp<3^btoYCU- zE$R<8Fa3&5f;K?%(O|}(6rVd=iv5AF)g=A}oqv=eRAKWTTP6GnM4u)e6zfk_T2RuJ z>r){3-G8zYPygHudu|Ni_#^w<_9^`Ed6^oFK+d1Eel@<%05mqy0l|j*OSFF|qtYKc zX=y-gEcefo2>#;7hGTV39k3F=^Yju%JJ7(b1-Ur)va~^(6xuz z!n^W;ilZl$<4@Q-3WtjPw>oh&yFS&Q{Tt*6w*3bw=8RE}zq|ldA#+ta^eZW3>t7Ik zdLS!X&_6R!@xWO*KU&^wk1f}~m1k>l{7`^KsBY_rG*$M05y!zVevQhlm- zTSEw}%7lWhJpYX*-!JK!8id-hT43kF@kjGJgJMIWe*AGz8QGIvpZXs+b_L?NVoeyT z#_?A~@b}|zF`j6*8n)WpV)&u@)vaR?qN^6NgOq>2ewxQ1 z^dF=L*Zgj<^;Ey6y$!-AIa*+&dYm1n`m|{LFWh9e1-|NVe9`^c@7ns|`Qz#kRL${4 z{rR9z;{5UuZKxc)m7PD1@L%1hzwzF#tq{?#nfxz)UJ(DiTZum!-O-Tv?{Nfwqt59G zQRj1@Ma&Ggp5}jdOGCupPi<%!$n`1p-z(Avq4#RNTJdKn)`zd{s0Z^~4rBLE@%7>Q zLwxHR2mM31zlsDuHhtRT_Q-egyz|QW$uQSk7-@eNf}VV2=a-TGys$HJ6wZ`O_=)Pr zhi|T7uap?by3K!o==`SL!+Ya2=il=0mCEsx)>A{6I&v56JI3+zg5YOtsRsu4RE667 z^=fCaKl73{EE-0@HU};p{>u1)=1*T52IG%ab)b8AnAd+3yp65t&nEgxekuqb2h@Ro-(R5L zuRYr57p|zE3eEQ9GkioSr1MuTANym>Y%LMLynaOSktXi{b5W#0`2@}nNcbVb-4_== z)PNP!m$Un)`s~R>J;5*aAPj$?oF9gc48kbM7&`hSKm0&w0hZ753r%&t%Q!=tH& zP#CrcUf6T~p#Fo4Q4lu7I`A^<6cR=HeKq$d{l0=<`F9LY*b1ks zpE7(T5qxxA2{d2=l`eN8uO)%1~`TZpN>G%*`p+Uq! zXgGShoaHa1e{Qq5KX12(4h$3LWGl;Ww2X(Ljg28>mCR?yDL(Yxjl#FjOu%Xe_va!B zJ`Vhzj~$LR0msoJ`1y%`s`~AML&fi7EREp$iSo;|G+kj>=^;3r^@LwvF5REnV@(g# z{{BtUA4l==uxoEz5-Ed>HoSiI0;KsxV1l`@BI^PK)aCV6An`xvmM8WK)qtbnoIm17 z{b+y17o0w3GfXxJsd+vlPLAULVPE}GC9n=0F;gD@+q8qQYnBc~n{$6Hj^q#b<;56s zaUC3Vz0LR`l6>DP>ZBjKE!Bpb=kKuV)BV}5lYSxe+6FHU@%}a$ng5rQF$nuA^kI1$ z<@}){?k`jQq6hK&PqOn<{94epy9}L3pmLJ|w+8z}BY{ebsr< zS9CGj3U=;K*!pOKk9szKn9*1pQskUJB1wMHZB-#&)>#Y511#mr@(Yct{`jd=9oT$4 ziCv%eCoCzbBj{xw0KLvr*?QU^x4TXtYHRC&b`kF{rTuXpQNys;U?b=_k@ufae3+da zhwFw~!07uE+4U(tZn?(b-k4_at@$W+obpF~!3BE`D3jqvfm56Qs5QSB;Pw>r#ra-V_B=mGCHzr&vKPjH3?`iB`iuHwzP(L_FD2(-++Cg@ z%4AZ1Y+jrv%71G>qnXO_)3eDJ-12xcbUGQ#?_VaxPyPn+@87Qu1XT0B5!G9AC6Qq0F!Zwcf6WwY}~#eAyCw`G57r+yZU5Fqq?u z?r%t17K%@A*9C`L+~1`Bv}tZB#(tF6k0MC@=*DT$U;k1UG&=D55ye;d!I9X1xG9{p z;`vQ9!OzW6KXKmLZP3fUfZ>PguSK1G(POwaRON4E?U@WDwHa2U_|h4zm++%gwlt-lP#GG5=I_*n44 z1G~p)f@crq_=w2%#dX{2K$9uT5Myl( z;NSPB>3rppIX>8>Qd`o$<3sR~+^Z0mU0(-H1kNw1BtQA~+Z(Sf(gq=m=O>h3_RDmH zq85i?;^=8|W%?`jL;$L6(}jQY)hK>K3I=1RGDG+`AD{LooOwM8>*t$8#1o#sQvB#> zEx_YBEn(zD<@x=iJ}x+EV@a*~$)4;yObktctJC=JJIzlDCU?ghn!n_k^*Mg1{_5uX z6d&zRf)807KmT8TU+pH&4^@SPUcXshC_B z?2F&q>p<%j96z+bZMFFOJ7j--@T~d%XeQBLtuDXAD}7Ty%bVjPmDEr6i238qU?aFQ z`#HOQCh@O=3j#1_x*p7F&EucuA5V;mapANLlKg|#NAlBy@Y}Y!Fx#2umrf-9d)TQ6 zYsc<}pD#zS-+#J))NoEPZfjc)a%S-Sg!0Fa7awuwk4=*OJwW`evh{v=;D-*BPT$O) zkM{T2BzoiIuiB8ak;gyfk9wC%G5FOM$nXl5D~o@7zd*D)uP4brXnwx0_Yln4X$(_t z^8CYx%*UD0WHcr|vVd1}$FuvR@!z)hV=NuK0$Q{=&yLgiP@y}W@t5bvTJsOZft&cC zcRVEPr?d4m{@+%16Z-=yTPYpg;Rn^?T zG(TA}!d#d>{;H%ufaWK4%{_2Pf)>2C<@`bYtur9Qa$ypDul zC_cu_HWfy{x&$TG{rLMM`l{?uC_Y=O4<$#7*zstBpIshB__5Chcw)%&7h3QB^axAVuYknO=lJ_0`b^8y z8O;WMsuf?i7gV5EWI7D)!}~iZzN`*)!=7%xYvmU+(`R_idKFx`!~I{%FAuZbaG|(A zV@Lt#7wUhtztSHUbkvsc3#}g-1o>d&p1M%Kt8)H`|7IrmG`l9w&-AEyeyRTQe;tA` zKlN+nmwLi`+$7%wGq2vMiErurnjL)|FoS6Sp$iG({;=UvVGEqGZ^(`V;g17ieIsGFJ~Vj5^AoDS zCNFu97P_0kuTnWa9K`v$sbTdYdc%X7>r3aaDc&0jPu5-l^|*x$U(sZL=gAKN=+UM= z3>kKrtxqBKld#pr`00$)AEx@O|9`%C{*E5J%i;K<`FnhBF>Vt5jf>4VzNkO8re!$J z8EOQ3=Wu_F)*lm%d@*Xh9z=BK{6X=R6JLzyj%|h%Ya97re9`*)<(1xeXsr}qlt1R! zmZ5pGZ7}f##~0;~``3K1^JqPAKedp(ABwNMUZ1f`VJf)2h-KH0mP`Aq9p!_u!qybt z|C-0vQ-7@4oe`*)U@7sBeF(nleVT>2r<=p;H^bO^ApDXyzb!TmE0s5pbNxl}b)ruk zE{*R57CzjcjVAejKizIPFYQmQ{&CKeBAl^vGqg9^!mjT`^jlPLFD(9~4j1h?zfkbWd*TFUGrT$ox(|yrkoi@BVQ&IDN)Fi(@i{J|esb|3R&@gr!3I0+Kcw?un zdbR4epyThcLys+R@@)gQp5kwYPY7m5iT=!HuHPbwesfe2{jZq1u=5Ge|C0#+c=;Bh z-DZ)$mh%2hB>1wLGzd>_Fa`B%+&`oHr+Wmy$Lp0+d_|M|AD;SRgh@R}o6YqZ#h125 zF;1Jb1uVb&GXA3ZPm4i*s5+q@jM&fp7mBZGUS4RtPghcZk&*oW_03W=)=7ureU0RQ z@kR6h9;-!v?QLCeIV|uZwmAG&8@kXkQIcl;`JF?|L<8EgHGjbz;iM8 z4_**_dB-@RZ+xlTGO&uBU-rLTm51oq$4l_IU1tc>=lG)h)vl~7?yoO{fBS!^KVY}3 z6jLkH!Se{uuc*IfY~_lsW$I9%&;2#3-#*zi5RThC0MF-KpUX)7=AwOHY*D`s)L*O| zUj>bQu<)*!Ur*%xMf0CN;YDcazXiPdas1H!78i#Q9Mazix_;#Nq5YRlJqj^=!)EC5 zfagC*{DU1Gy|KJ)UC^4z@sUdKHQt~IFWGK^LEC&7f5`~G3{Hokzn%#UIChi$eSq-S z{^=#?Y@7DKzuDjTrTo>|&JTaKt`BkM$Ju&{uhK{#9II6ijzsNd$EknNXWK9IzO);% z`oCiMqy9m4l_z!`pa+F3xIU!&M>Qw=U<>VfkhoKMeMTp-1kX68!Muz>`QQ7e_%W>; zh|3)epiyNkyFcn5jLCb2+AB7|qv6qPJ;hJGnFG+Fiz$44GKa0F{#uyP2)try4IB4y z{7`@4k!&$Og!V9F?PRu|;wK@|37dT_lgyu@{M6^e67+ZL0*_a4{D@fL;1d6Dzp*RE zC)SRiF>hYuxaOPSvL}DPH2>*i=Zb-cHK1&na{Sb9c>&v4E`jt7oS&$_;9}Sp7hI|X zUir%L7SwdOGA2o z#DrDbB>18H^t#Ls6PD@20()Mcu_gJ{_yQk{Xjoq|zb%5)Z@Q0siFQ*qfcSlIrTA$d z>5UVc)RXkjQ2c!E;e`tSx-ep>^8D#(^8nlyVE|1tIX-BAWL8Q6PF#`#0h8x&e31EU znMvWee~KwQb>;Y=`t8lMA-Hs&CEOk|ioJiT-+DMM#^S|t<<32Aa75cL za=9Vr7m5!vjKimK-N4j~>mQ1b^q{VIy0HrUtKX!O{Wohq9>en$^I&xxzkiC4Z`!W- zZIUMRDB}2_`%6!(dVy}YHbA-~_aCDPzkIIW7gN@Y`amw7!|+_zoxU-2%BItl4p@-#YpGXHe~#u)$MT0_$6?m6we3T8 z{W!uupHz#ng^!efXn)PqzT>d^Wh3x;f4k=SrSq#i>lWdlZ(G4|1lM;!`U?(z_raZd z`VhI8>pP0Cf(N3$TT>5uT;9aaPx14xr8j=RSr58;D(9bByFcO5#TgJC79!{RPddL% zL&qOG&oY3YE*xL9Kj2YxD1QB90znb8*!5G0zgD6%2sQOBAhtj6kD>Tk7`;kZ5#C>6 zpuPnEUZ464ubkW9B8PJM?b6@u{1iVwd&J=*%kE(I^I!fhqj{V=PH3rHtH1F0bFRR6ZTx6QG84^3Pjm+Be?kGUCsNK&NuvZPhA)?;22o-F5~)& z;NzWhI9|6ghn{Z=*m`x+f4Oj}hHxVEIE+~`iLIykPuu##u>YzCFy|4+2hD$O_A5sB z6e+*RNd8mabt1ZHHif%C@3HGseP({!2h&7cf-_p8wbq|L*mZ_qe&= zHn5BeVC$*BU^c=Z!wwn3nPbZFbM<2gE?Q;^Ha$6h=>D~Q@w=1$JuSgqXC!++G{0$f zem;iIZwsYcxqnUZQ(5SUULz`M<)7ReM#93_o6w<>#~4tK&4u~*WnktKE;nk z{!u&?6%B)1&tb=D|Gw>U1=@#b!GB)L`6npXN-$af7`h)*diCMjH2!=PUpsys!t|GO;I7K|8hl9gTTjbiEbU_oc{|_p=Og~X zPxZH`p^^%TQ8oIFJ;QW~exvoD>e=C#9&7vTzfn~d;JK~rDc z+RzZ%kK4=E#}R$^JRtz5%r}NTx6{~hTjDSHwD-qxD~urG>?(Gg`UeNT_~S_mi! z2|EtN-;VVu!OIrgVb>$>ztQ9jvZ;%-z&Exn1!avnV2cgXdD@dqTj-NT#=3#v` zXUOlt@dLyksNU;{pTzm*|GqCm`DgkrBcW*4EeLYr^%EfZ&5@fOF`$tO{QG_tt)H%5 zeE}!jS_%_S*E~PzzbSN7;M!wa5`Td956sFK^AGh0u9OGk-lJv^uKI!f{iwgzu$_^h_24FicGYCZ zX?=96Rv5apwvg0EDL!sB(h%+#oPeI^IX-B9Gs0p3E=aS4C5Crvt}p$*$i|CBI5EC< zd`t{~hZ7&9LFeYm^;dba5B^wUDA^xC^_N4706bsUq}KSq75oMr$ECs=Yil{<7g8VU zQ|yZ`W*Wiuh8!P}gkP#l3Nf*C8(d8AXX~jykQ(5Nr^NZ{|K_tr68s!LS&Yub8PK*Z z#}APCx=(iv#3#8{U=_jZqm+NnH6MUpdo983+;H}ODgP84o{Q^xID;aK@86{OIiS@B zL*{<3)xZ9);t8(1z5zCM%4X-M^L20LbijfZDsW&N=MTz1KgTK19JOoBZvq~i!xd3W zAu)p2hiHCNXI&q>XjK<(B=Yx*0>BR0&rjYh;_WRl&2RZ9Y_=V;- z9|I2J^p$gA&oRFLh57?C#)PB3trhg>^O>EW;wM@C4SsBw1`P)&=a>6hAsBwb9D>yI z*?PJ^Anm-W@L%CEIR0%s=QqMHcZLMvpCmJI*S*2kQ-956qq=Z8`h22R4&`Pf%v|6!%U7z+3JV^=1 zr(gwYnH(QL>N^{L&cTw$&Tw=N#|ILAdH%LFUQm3mRiCx(t08n>cnao}@%kUtXNy{O zK$C?kFt-)Q2j!O;RTprrkN_Q%;@JI16Mi|>T!91q>VT>i&#!3y<95kX7-IMg)OT}z zM)M!D`tE4er5+@#RoXnvKQpXx8OBk%B(dPc4IIQVS{W@p$!?wu?A{S*Ie!SiBl^=pSXU!DK-eJ~_bV&SsS84vEwZjufx)@6O+o(QkwDkuLz-+j` zy`}swKSh)N&mXUSacoBu@X6-*qWjb8%ip5SuWhx?e>c?d!wN4GSX#{SMfF|!fFf+% zc01G?u$W!nRw1pghKT!{T<%)eI{&Tv!Eij|WDUKYl=};=x94D=6E3j$0>__BQD64& z-=@Q@vG1}UlKKzTcV>@`gsn^O!Rk-k|E2gF`J+81JF3>oPesQspnX&#tlq=%NBy~y z;R?JIrX%U!q4ibYJZoX#@E71e@(_z38S&?Iwfo}CJN4nR_YZcQ`g6$>`lD66L9PCq z{`z3-+}#q2_5S5YQvcw>jGy>x#sRQ={)Y1h@eh714;K3?EG6?n>HY!DXd|JG?md`z zisOs=2OEL{arjnq$^Nxe;;(&H6XQEkiZAM~IlT+Ukx`al)}8lPMH76DoK}cO)^3N; zNWOoE<~I)We6X^a3CMbId{KP|Ki^`V*bF#V$?-+&KjvFJP(IWUZmDi&@1Oc_>*~Hi z&!*|H_8HfIw0~jx7hm*qHia~u)oeY*SM}L9Xq=f|E534n_~5SjCQuQ}@kRY_C-M6# zI~}ay&aipx{8ZoBmqy^N54I52bZkxhNax>}ADN3|W7Ey zNcyWOe!9f<73ZTEK-tuvHP0vQKXA0q#uuCBLVlGUzdyoHWksI&va4~e^QGWuAVxj0 z0He9ZY(3?tG~G`qAG8PdK6%3NL;Qil{9r5?X$6yAxc^4;pQd7dZ=szD9(x1Xdg>1( zEeXQ0k(Tf{Qh9x}zo>5>$C`qD!U=YNkpv$*RNvsECK+%j*N5>3^`GI1H@;3Y0UcxI z_!#lD2&`e*(Wzv%vGg&)`ds+C_xL{GwgUmT(Grz<}{ z@efuF>VWRn>Y!1NAyy@KXjSj0ld&U20Ue6 z?D|fme{R=Zcbq2r{|6gz{Lucn4!V5k+_xpcXx7LYZvW=|MDru-gN8!R(ma^eLW^IY@KZ`kFg9_tmdxi( zA^OihyByyy$%dIL1~Yt7e)@7W0AtK8!KU#Ic7A=rPi@xM71EpDkmx_kPyH`=-scm*Z)IgpeQT`bl}wJu&@+b7t;^(~INffAOhL z@TIdh98C=yg8w{@FIr#C$rz5O)9j&GHhe_}QA{D}vxFpwJx~1{=bqY>qGL&&4|)LD`{2@T^mF zc6}$pPh*Gp;)8|e@T~Jc|3aES{W3(%ELsK!KB=?y)PI;Y(H}L{EG7Ltv_G|@SRZoQ z-4GrveZ|&O{QPeJ3VU44fV>a9KQ5a13q$((;S$l`TkLqP=KiJroL#672Ang472A~a z(}B#_*gJ1KBm?*7^hy7=@mXJ#Up0qmgZH!ZQ~hSO`z3}&WWamx+l-&+_kDIX^uonW zOks>Y$B#bouRS)s!J~_JfMzEf`QP}a{c$_H`{RiM3-EZchFzcfci%<+D$LmdZ@rb{ z%OTqj_fEHff*JhxoBDT;I(@)3L3`j=!#H+*8NrvPTR6Tt+7KcWIlhvJ|LvSQ0<~P5 z!NmAU?Ea{KmliVwwF^_}X* z_PDjVMy>pHuKQlRv}O*(HsbiF`fkuUIriPCC&`a!f84&`S?FLtA2vVe%kKXN!B^fb zcf8Ww2qK&E`W59b$B-PnuDt-x+cjb9BM81+O?}bC+X6}_aePt!(jDiIBQ>mG(d74R zJ?&4J!UmHP`mgkRkDyudFfr1=l^-+qexvLM7< zqVH(_Q?L0eY<6!ugoSc_mrDEvhi|^*e|M3?8-`(URPI{RI;fb7I zX#Css8HmH>ji8Md_vdJTTfxPlxV}$Q*l9YEouBp}7z~|*2K72izTcxy;{W5tRv7#A zk7WNfjsF#XzrJ|q z6WTP+hR!NYYwk~4A1xQZUo|?#29A|{WXCU)`lzK?zsv8t4^EgpW%??*r?fvu#U&JV z+uA~P)JwLW@=JMVAAGaY0;cJ6d{FtF^>laI6YNkm^oZF+$-Gq=O_P;d78 z|ANH-tp0~^cC;O05y_^24*g=Q}1 zaH1~PUlbpkI=sUUS9igW`GNAk{6h8D_;cd-Q$AS3r7=s{{n7mX?!)&OKYcIc6fa@x zss7r2EF8PkZ3I6fV%U0$k8xuEv{%O#lKBLY#J_%jdpe%I&;btUbAEV1{OgtbMSNJv z;NSdAijP%wCgafMF3_oNZ+87?f{z*BTySxW6dy?X+cH8UvBJ|Cc64jb*3JL=qzrdI~JHSDm^9S_@nnu0ELf8p^qBuTM$^Pp39X;^yd^6~q&GA9^AG|7l zi`$cSgJ5qf|9gM*`ymO9yztKlbI5PY@k9MF4S0t)Z|#O-Kb7O>W_Mrw+Sv-+M#ZuB zL;ZnSU5YXETozc2Q?9St4hl!xQ;onRlH-T=x9Rj8jxz&WKz0V#R}?>fFQc&6?)IR# z%Kd5DA3E}(1D5)V-#@OI4@L3Qwzmu3Ezpqo%M>5N;U4&TR6Pklq>}vp{kgrEpc(@$ zk8yo;nZ*C>E$--Y%LFDY;qeb7{wIj@RXTOEt~LHktdHQlswJS&pMU>@#=kJ%7f(c5 z!|J;{eyKj{eL4V(p4q_YoB8bT6HEHf&J8HTr(F+$-*uj!r;_|4S?r(dHN*lAxm;En z|0~a#2-vgh$l`C-SYH)ts0BR76AJ3p=ee?_tWY|#XaekhOcOI=3bf>sVNwfhuy{b<4u z``jIHiunDlf8TGX@e4i+aMe9mc-Ae5uP49%VWVB}`VCF+ZvF4~Tl)Ra-lulqA;bBQ zeVF@iwq$?W`Q<(Ethm3U(~N)lyQ<{K=fZKD6)re=N` zt)JXpyARttE`-FYMr?f%$q#(@`(l1V1NhwUU;RbO4@(_%1hs9q;K=|5TTk(kBlgb( z_iO|8Do5fO zzsLxFb~N(D3wD;0{h`q${}?pz1uk8kDZvl@KFE1d-(0P01vlRE{GH+_HCRXJ`Q{c( zUJ=dp6UpCa^zgys)2*SO7RQ%*PwD>aGj}V|vBN1Crul)br~cRNTu-!IZ3+GQ9gum?j^~HG4yC1BaHlQZ{r2Wyem$_j7Q{sI3j~sv0{~G*Y53YG1192{s+4=~A zzZRprqu^X0j2HY{FU6l%MJ75!$+={1fo%3ph`-k@E>EYNn3W$S5wz`=GwxV6j<>MWR7 zbA9Rl&~Y=~;^)~}5O*|D5#_nk9l)X|2`i5x#v-?^OJi+4j8!s<%S zzn2OA)~j|$&D`4YXVi5kt_zq4dzNwko8~_~yxj4nk2$DZ zvinaW_*?1ki=SIHgcju-e>6V|(k;S}DcKVIQT~e%zyEV@vkg28=Kh&}Pigv2=ER+MhF2yFla@vHq*0ynkSwqaV(`*AR}3U&q$d`3H*E@6qK+4h-?+ z_=_g^Q%7GMIlm#S|Hl0{ebPTFpZfv78ytjrLzl`~en$LfVVT%J*rYLBoid+YpVoKG z)c-?=J#9e1Y3z6^(T{~&=3>%QfcXt0*>Q@mYquRxF;xx5c__zM#J9HCsfD)0U!(Y$ z-zyWnPDev^d#)dm;HTTXZuq#PKKKmd@lXAO;&J;hGHNmOo$kr*Pn+3m8ieQ_py=aJL<0;YxWE$Ps)Vw`#0Ho8JUm!WP=wD zF|q-_&~5Dbfz)SSFUiL@^L9z_AtU@W{h}A1X=hWbKkc*i6Ruf#1k&XZ^1ty-@iDoz zFZR~8mH5-P1RudeUt`42EZASd^&iczzKi>NcK)=N_y@HAW>3{fym!J0)cQ_m&zC~* z5g0Nb>kM**J)T^D*%JNtSla=^SE@lynR5LX9G-xe%7S6u8Rh)*uAnV$$%ZI=r?<0% zU*kBwX#Vxu;WM87eH7L=eaY|xq<`nwKi`U$(hY@HXw5B29Jo%X`RIt?ZM zMI_;;h?S49@rE6e{n?bCnpS&a;&dD6?ac8<`wNn1d!oOg4YbeV`4tfTr~CdXZgkiM zZpPm7zxV>eKfPo9uxq&;2>Q#|^HKdbMB^2zJkNqX!#KWVWdFk5tWb1}Y6kz=FJS8_ z|CBBrj+<_^f#1!hvg2_CUpnOu_{LNNlFOCz%Pozz*hIY!Tub2j3B^a(>YaE-YXP)+ z!uchM;Nx|-uGqOmA7)*@ZTfyVpr$H`bQD&zc;Li~xXReiAWHA`4i?+?3wiVywR zZ0wa52X8j;`b;#z$KiZ$OnGe!why^JqxGH6>tExX7TMsWV#m&(O7PJyE(quAHHEC? zGIl(L_}BX;{J;%;5z_xFX854{d)C;6V86c2V4?3DetyDFo9)X`dq*xbTF&_?lJHaV zqd=Uq$R5@@-DB&M2!1+G`hfep9+BXO_TOZC`Jhf$JJ3arA6g%3Q|Bo@jN1hrFMBG* z&w^=Qxbj9rNqvaU*EyT`1if19f{h(Ge<9I#Mu8%JKH5N6U5+2hU&SW*SZTB8|MtJj znZA-q_n*EK{msxy8<_r;z(y8>>+-iCHFMP7v--^6CZq6&kk;#=lYKN7dC3I z(d+PjNq$B7>t;kK4ua<5@2hfr{r+zR?q1OrVzzUANAXqtV8Brm7OHNNh1EjR7D}~G&=+aKe)f(q>$D}4~gHmyi?g6cD>{N zLMFja`M^Sa*!mDmyUF`Q>G!kEs=`ozX-jxeP{{6&_E*Exhq%=u6Tr1U!yom>Gw+9B z+Oy`cZrcO4p3ZL%UF(ArA{)WLDcpac_~?D20=uj|4YH__3?He)e|Xc{3kM|GLemZ0 zzoYmVr1}(FE#Lir--l!CDZf1J;fd`ZG?eJOXrk}h4|<9R?(c?vORX3_fatplQD4d} z?cmHH?mtle$*TJlE7$IZ>zz10DF4{K^G4@FJ4yZ%N%Y;Y)30$}cn$<=E~&Y`bbmsN zv~av%#{mu%FJ$kR^3Mp_FpRt81i4$I*zs(_KLb5x;_fCr;aN?8X&k|a-wY@8cGCgN zkDNa!|12r$f+kZ8CHSEE%Z;tO(7tF999`d+UEiAEV^i}!=&NU4D?TO~ZO1#oF|cp3 zHCyjP@GH~Qai1Pea%{Dt<%TsaqlPad{_v=0CJXQcUkR!lI?c-kBij&OdkCiNdZ zv%$FGx+8oF;`t4Y-{wJ|@c!vs$?yLQQr|gb9Do6>n!-if^X&d3NdCTE^9knV?Uwxh z%Se1b6XSbHg2*4W%*S26{V@u0yZ>)~Hj8f=`ThU8$^*mu+e-9P3W@JIuHIO0WFzob zQJ%ja&UlPw;`!4DddV3-5dHLifj^q(+QYv63GDf3{H|~L8hic8fn$GS+4@wXpY$9D zVw7iVP;I`Lt@k1QW7u>!J~-zL)f4#dJFWjjT%CaDC1Y@7phVU{wgI%ZfnWe%|sej)bv^$Pv*D1g8-X4oVkNQCC&V$(Xd@_H}SYeEw z#|3A5P|X9}5RG zbZ;%wcPal_c4-6lh)IVt&$<5=ll?bm<$B`rj~D$lR!{BH8%G3Jck4P$P$W8>5P z0bZW>!HJu?!LI_IKhXWtZzMgyU59o;>C@}Xzl%wJeSC&5dVxOd&EffV9fFU2R*&$C z)StF)hZnO4f{(y1URXQ33v3;Boju<U7&aOQ|vm`cdO|a;+bPxAf~zt zo8MKWemQ=#3qFW#50R_6{!8)E@s=xw26TYwt=IAIL;OEiA=P(J`XMufFICBc{z}_SuBryxCNW&$SOg zcBAQR{4ApH7NrE>kfjE2`z7c9wEt!7jzPHVkttXea(+YcF`{k)P9AFwQ=fAGrt6+xA%dYio!rqs7qT+o({uORUw;GhQ{UDp|U&gcDObp6XiEpJ?G*G<+xN%Mp0 z`);Ad>MdZ}j>iw$pAU<@@JxAEs2#-j&rlJ3EdHXB_SfhFs@W&m^U?TVRPQ$KF5Loy zMmjTm(DP@rp1R`kK^;N6`EF)U_1_r_@1WiO?U0|x`I9cue>;OKLU9MEQj_C{*7qkg zdW->5eRjo4j-MP7Ke8`K{AzD!SQ*RlL;J@-`yLLszXLkxsg(cWkLJ%m_ITp-K3%~% zPBXt!ek;MeMF-&UFWx_vNbpl{Kma<7?E&4JrK`W6ygqq6H4J^@dqUz@&Yvj1+W9dN z#f|`$0{3s4KfAn4#ErcKc>mFv-CsfQ)8(Wgb`P!%1umNL^WAg}-VaWZ@h@5*d63c< z3(ho__21L@Q)6W=URyZ@LaqvIe5&vM9_@f5!leE#C!T*({c5*IE-o231y=aBWcGR_ zzi4;H9pB&T4EJC2=co9|2M^Tk(?y04s^8Y0T#k8TkHdtn&scn*`)f{I<%!MObc5)z z#cX_9KN))K7B-U3-?iM$@uMQ~#eb4JhOOva>Hf3}cHPGN;oD^V3rT%Nkk%g`?$xzY zd>Q!M##zm_!K?0?rW`AI6tPu5%w!VZ&+Vg75*&uIPR#_B<6_Q@PhJm>l@t)C>#jmCxSyjX>K|wh({TgZLT1^=Bf9KaY>+V*R;kaC5XR8=uza6HYteqP6Xyo7Z1`?jqxFG=JG}`XRQgvKLC?Ie#lA@n`=!56oWP6>w!a8$XNaSIw(=OY4KW z%hrb#6MZ+MxCl?dPKavb&hSU;^OGk;;mEs|aLv1n-G4KQKU(!) zp!)4L!w0zR&~ET>ZmZ<+L$2QzuXM-g0%?3lj*oDn-wyBc5C^C2f#SA4%w8qP*Ej!( zQQ<1fZjfrl;}6A;Q_nzLrZR?52hI4Xu`mj4%PnEC&LsB!*+hTZxGw?sO%!D3bB2@r zCG~@$)Sp;amcJ-S{*s-%0iT6Th1+ZS`kD&j{|(#pmHJPl^LG~iX5-WNVVb@f9q(p= zS5uBZx<0bYTnAJn>Ou5Y&Hi8XDHq3Oro)~Ct=Rpk{~sUZj%Jeow#(!Bdn(ay$7Gh^ zr-g^0d}k+SPxF`3(>~bpLJx>-!1dd3;{U^UOZh`f0|-6#l-X1NpE2?p+B$84XH)t! z|EKx;?u7w3>!~rkDdGK_)c;#a{Z$ob^dY3yX?B0A&xVin!0{8if!^wU{P{_KKIx}3 zjw$K{^-MT_qVs#G%L82ed=K;xx&PAhmzQ5qVVAl3&>xnw`&0j2wE6)Wbl)rUUnKfe z@>vxwnWYcK*SPNLQvdCl?um=)8Gy^DC+z!C{!{+_CeCWG z1L8b*eIbkRpME*M7!Yd&u7ir0Jzakiy6rZ`Cs*EIHP*=s$K)BntyO23eGbuQ^{=Tg zW@2|Z(>TPVBxSn0tBl-2k#DDs&lphspo_}jSxr=U6{&4xNr;^X# z^7%KTlL{T)>&x`jeB!^WuLWV*MpN*4n90Vc`cd4oD2(;ChE`K2v+I@!cm`>u8{ z|1jtGw7(w;}gGnjb%3xdP9uPl0bk`!Rd!zrEYrqnlKJDf`atssE-JtjE)Lr-J3Yw(94X z@1OTB-5pKW>cb)hj}Iy`KbHo1;mY$p;C19j_4xAo!7jsFSW{YGxU={Yn_ubq#wIh| z(RY(RxHvsl+gJZ5hO)mvpF#|-n+H}6I6pzsAMc|to&OhZ3I^lvGkYZb#B#%JOq;X| z{@w0B|DpAVrM_M$oaq4`oeG#e_3s+H@1pm$J#f^OuWzU4yNs=_!o82X!^LvW@2UT< zxKoIK#^p)-5A*t3HCs7ArvbPs#jWDd#U1cigaJ z6McAln&XGAZx1ZFixYlG&tJ*@EEcysF!n%q+5DeF@N@iK0M6}c3Kwc}{7`-AV2hy` zW!w+E8ck&1kMbACO>tOmVFx8=qu6yI^Z(AT@z^uk0gU%>evwM%|2D>kQhrlkwm)mC zQojDA)Bd%X88a2`4~S#;-%R+;j*>nYdaOB^>TrHS@iS-IO8ntI1ulNDX7*V`Upmy* z9+y|`0Doq2dy1dQ+c)9a^cm3Hy90keqR(C!>W*!vbcdsfmEdR7U95IxFFbwA<3~8D zPtWo4!Y(Ha!Tb%!7v=YLx?RPk?YBYiN#_{8km$4K37+U*)exS((7CbK3enY zZrT11Nc5$Oy^=oFQXlO1ZBYL{^8F>#jqc+<-TmNMOEW&ErMct%rQKogs%6Zc@}qTM z@8Qg+`yl9txAH%HQGWC}&;xHc8_4iM_1Wo@1M%)QGf?Dle9-l~Ig{b6{4=J=9y$`Jj==)%#r+`lM3+8tVpvz(@Z zPC3U1t>1M^?S*d-Hln%653OH(FTaeFEVhAgohd1mMVHW}r1+bNqRG_y$^= z$?*dOKWFwx>m#cfK{^2CPyxMjPdwgPX>jf6@BHNIN&wmH78wAC7OzzdEKA zVyl?F@F>1D8$XfYV~?bt*77lin|{2$P4f#yw=38;VLQZ4=kbH;uk%Lu;mJ@lu$lFe z-TytoN2k+;cysOEf9ucH@khSCW9LgB{NBVA9u?eS_B8+Kw)_TKbd~&1&CgN^KE7r8 z;|F_lSd?{%*`FivuVtM(>3o z8?M>>=l`_6;rP@8yF4+3qaC)WpI;t-3VmF0Tv>M+|DyYM1)4pO=C6Dxu;uvBCHT;h z^w&1mj3H>;Ty}q2|BkozMePt%7^pt~lExQ78IEtVt)ND>=J-;(Fb=oBb(HP@P3wEP zMTV$wY6$l|IKQFz$Y{M5-^FCf)@M+Dm3+h;`!;C~>(%RXDLy==&!kx|c!|ZR|e`$Zyu`Mq6E!+S+pKyItm-w&AXQ_WAXpgKuN9zYi zZQRj#wjqq`vspd9+<%SCT&48|24GT`^P?Oxzh@NO!?DftVO5l`lI0&nKbm~n6aS=} zz^Ccle`$ZyIiCP5uh|P`|K$9L<_~uc4#(|1`$OwYUVo$Y=|OelaO1fCvi-RgB!8H5 zCqNgusu)(HCP{I7ppoH|S9a_~U+Ea+gSdH#2Iu*Kx4PBMLz<_}#)ug8goGhzH??w_qdQIZ}Pqcphp>`3*{@VX9KW6rnAGthH;h57V&}-jq_Wgk5=ev#Wp}0=I zz9O8|54w#F!xZ~|u&E2jPa>KB+ehEPUiJ6D)^o0G{-*f(rsIZV(hX(xHw5|m_0GOG zu=C&DaDNG3f166`Z}n%n;>i| zgr5eIKK60joE8BRKKe9`)}PQy6NUo!x_ z>&5c#Pxc2o7?g`=yr#o<>zV9&Ho?ydJtN%OvoS0gs~JB-Zsnr);pq_jhWC$~lm3ne zCrwe=u{msA!~0Juem?tb#C~&ULv=r%-_ZCl$xJ}+xK5Soug3Q4vDf99VDyLMC!FZ7 z_|*li7aL0F3vm9VOYl>0)(gW1n?dU6uk8IPKMGlP8B>4kgrpJYnSY0q{T<9YOZ8P3 z6IuR1_1P}|cTjAb55Md2^{-2bKHKDk7ghvI`J*1^M~MU<5xWcV@Xa`463*UBz1Ec`$g_MTRdL zUv^w^MJ;zDS$;wFtJSI3@tx})*jL(u`#;gIhPk?-_8}u!zMSKSuAfMoQHc4A4?qoj z&G=cV?Tg1*8{A%8`9E=}29d69y z`S~3Ze?IA(qTQtCpckPTKVhL;(B(@uyq}}u&qw%GA3H(P$2wP4|+d9VxSG&ZV~UtJpf8o!S@582*^%%0ZgR^0Z)*-Oo!?*|@#D86FHy+q;GSx~r@ zGJK^HeC3CE;G&5=;fQt#yFU>ARUq|mtSC9~k3XsH<@rbZOi$eIZ6>RK(Dg}&W=Zx1 zmE&t;pI~&$wSs+hZm{twe~b8Z6>t394NHT0|3@mp*O5!E80%yV|ErHseBJDQ4I_K) zf!~uaF?{8a__OnzD}Hn^mhm^5zZYa&Lpy2z|Nb*H<7?YSH~di51PrZLsDEF1f1+{W zZJelm5PTYOe9`{Iwk1C3)~gp-9OU?-^=;>IzW8H*FIj&&t*`8@I|zHO0l4{Kf_i*; zeQ=O8IuBarjU%>-ZDoHt_sese)_YBallHxhqr(|bzw z)8??OlV<#+Oy7Vdi{=0fV~H5*!I@b!5}^sPnJB>X%w zg6o@k{Gs`K)8oacvq*#wZ#%Q+r~Chg{P4t(hvqQ0fX64ApTwG7#BbGi!PHhfe+Pn} z{ z`oi8(y#Jl@x0-9OqQjj%kg$~FhsLKL_U^cHTTgKO!Syc_lK*U9coWat9Qb$s62lLT zPov#k(5|g9*pA}-jpFCs`zv@zxd$9BG*@cUzuLc)_TNh}fx0a?erW&Hit0D;<%@kV z|Cu|pr}+7v<%Q+}7VvPwJofw2{Jzz0KfL&+547md^)HH_H!maba}h`UmpXh;451UEn@2*mhFOMJMBQNyc(hK@E;PHX-uU4KxxVg18ynCF* z?DGi!`c{4bBSx);Z>KM_>%}0C57%#`b>Q?mS*_}5GwZ@m1xH~gNK!|rcF^rww+&(PJR0KRt_q_&s$e>AP* zg_mmehNQ=u=T|G0KdzSeTVwxe?EZ9qJ$p_%KVGz#&9AA%|6;$UVG|evqhF<|?dAQc zy<1GftNVt-*an=x(E9bjb}P`ZbQ(;26vgamec@ zhfjB%0QWY5?Ech0ClBb4H5Wqm1Tvv^6wEa|H}OnNd2tGOsW6lgE_oTDrEMw{_N=S z8JpB7gnuFHKmVcivw7bBSbJSRxEaCcS0MhocglUtl9nipz8b*h#~i}Xdj$AM=UZFC zth2}2__V%uXVFcp5pw9?`X^=|PU>p|+Ph+nTc+R|%IgDEADYwr5=LCw19lfQ`+u-$ z0QQcwhO*o1+4#D||ErgH;D~m;DqSD9YrJ&+NheELe^VlvU+tq}F(%Lr29D2Q_ox27 zYfL)!2#AE^`Fwt*{iVO`R$$rrEa9~?};^-e{>d%e9r4*)V~c1`=f0=6L8e~#qLk_(QQ-S zU~b4YSnO@0e*eb*oQeINXsg1BLA~MJPd@)ree_(@LfpCXDD*Ai{;weZzue3Ny=L}; z!@IaXnnm){W*0u8@!3Mz`O&Gw|8*8f{RzJ<;Dc5Xdp??>YwnHvzxRcM?YRGE6Mj8o$}QZ|`v};0 z^7W$%lAmrF?S?*8E#Szrt?c>f{O|wU2al|`g4!3>vg_2pPu2CrdWL-}oxk;~OY!Gr zUul1w|LL1`*>CsnU(EJ2)KNx4l#=@|)n|0Rt-`-`Wa`ngw{tF!mtzEfAt9e9lYEIFaPQWR;8N#cmLMA81oY=ou6wvI^p&tQ|PwgkNW$_ z_ZJJ=Rf0Y60<^8@&aTt`|7t%y@a>R3P=5;Nztn#R_56Shi*CcAwD)ZOHX;7&lHMvC&>hb>^oEVd{WqNGm*2zRVEp{+@b9mD zIscIN-wg?H#XANTuq>YYZx-o~_>ka_1GSW(-*yALKka{5yCD!?eg&B8yp&z1`Q6tr zZyXV6C7Yjt%+KEa2jh=aC-~fM3bUv6uW=owVDXP3P*<1p588iPF0MmAt@+?-l+El1 z*vi*uhW=WEN$cl8-0wto{T$I3H})~X?rqyty8iNZ^>sKcXr4@;r~Pp|zF1>hB}xFH6?`!g0zcaC-Cv=Kl&Z zfBU!f!p{Cyka_n$v#0v~RgYI__VSv{|0#cI|92psKhPi2M&4ugRKMTV%mYWS?*oHU zxqpX~`Prdf74iMc7m!nh`!}7RtGso=>>C!)HjVo?-QVJrV>5APadlz47@_>_h8|dO zqc7CBuGv2~oOzDNe_eqRw-?O6Qc3^j*GqmlW(&aE+8@;4Pwt-+>%GF)Z?8l5B{AGT z6>|Oi%3P_x?W^2BY5&cWfxcKJLJ18wa{jC${8?|u8yqp<7K}9?&gNgL&qYe-gS9QT zgs&ZWen|O)VtGsP?$%m@l#9fRop+R zKC!NY4~}-Qfi=U|vF}6ub7ER3R_t(u%NJI#>vVqBS{sBzTG&HhLtek3{RzpgX`=42 z7@_J#d*)wsf8yFUA^2^E12mX9f!&|->x(xt(8DnvrjDJ;uB(Xu-c6s0UrtYeb&lTb zIuLzsYnU<4=+{=(Uqk(O-ML&;{g?;+9&rDq{G?;cemL)tJ}5IZ`>$3LNk8Z=f>SSl zHok(?Pt#iU$GlBu@T{2Yb98=QnNWmLgHOT)b^kN%KQq4Mjy0BAf`4_cFVg&ScJ>>5 zo_rgUk8^!QMfk~^rQUexjSc8GeaoINkML`|mSxyWIv+gVHk$cA9sIZcMk7A@Ui84O zldWXB` zgyoaV+5M}L{Z+cn@W&Mk>>%6q8M{vN$EG%|#ndx(h5z|C-G6bJR9`)%-w*6=Uu5D<35KY1}h>aS~T z172BqZ2TO;zn{Ey!&VP0q58Nr>^k+|6{~f`1#iEBLEdyF$B$ee-1x*D2j@%uk#=04 zzDCx!j2!EaGt=$hN-_6u6T(k=XQqmetzrb9wssol|8DwWxN4CTgw{)8&qw*ofy8u- z%!-G!lidF)f2o$4iT>M?!MiV?zjKKHUyn4#Zgur!`^QoLPt~g{<`*c0I!E`g@#*>V zkLO!qdN%{`YR2(F`OB)qH?gUi2(!w4)%NoBUpuecqlr|%_w2{{4fX$hKW?GE|4Hz5 z=Jij?&tF(c{rwJB5FM%6|34L#;-bUXVUKi^xNKjGV! zkD$rbk<6a*^Y|Oyczu8XLq9%d???4T)4wiaX(!7{@nIqD5Bej-3VH`zVD@zWce`^2 zZ%*3>I=>t>&i_8g-Es29ezN&Li}3gBGZo^6C9mLFk(QGCubdy{O!UHXT>#@-yV>}3 z{$F!8T}+>xDEKZttG1V~4@-RLhE8{_An+!~Pd3pP?>Xp*8+TX8@S`C8o%%gJaqLqY znBlOHjlY@TXUB*TEbZb1QNw1l>r`Jah)NL;*NqV_gxPAukB#{V3~3$$x311$_V%{& z`p@1L>0%opL2$K?VfFxR|4nA>FD)h&4FhB0NR@PEPx;mRdFfa*a|E=yJb+zKCHVT& z!x&#)(v$6f93qiFu?<3 zVr*bj#U=j!B)(|nUqlzh5ztB2yua^dBX{(+vzFl}mEb4y$WQFl=mp&T`iJ3j&O6$K{h_kfA_vh6R!m%3gXQIC4YW7enO@5hr3!>L-{D4|0WXr_;u6~54`;j zwaYcfpWjJd_{>m%3G)`Q@#*?8?OSQ0p>d)R(5Z_WAM*W654H}*)$N@i^W!XLpF`qP zf;dT>^EO(zzD`ivxB2&Du)le4CSm8MF)(KukAJkj8WE8u&IwBp)~tzU_7q<;(kJ5a z3sI1&&+~I2{LMux9e3AAf(g;F>hCMppT-YJNAsCUu;c^BAI)#Rb~na|tL%qf9AK0w@6Vz9Pp71*7!grh&{?%qV|;si$_;BavVk{ln)%;sX@7Co zjs0c#+f4Y~)%R0GC*4G0`KvQZP52v^rb4ZiAgdox{O#FTLu|3?2kg1U@kje_dMpUV z4Le+6%G*`!`_T0XJ8Gqg(&^Jehc%tm_>tqUd__1KOz?nb&$+%z^?`%s6U4O#qlNL8 zL2WO`-%b6&XjbG26UOlPq)YmD9&Vc=mSrahbG0?&uT8}Sv=*b`jKJ|n>vOHArQz|^ zBskJdGybARrsJ}{BSCrCiM>CKf0JB{(Yde#1jqCIhT<=!;diV#@C69koIfZOa{NV0 z`zO7sCGDT~;WxWKjeq?|Kf|9cH^KCv8h=FpJ$%C+@89kPwLJOw6o1L9+;ELTDZ>}d zpLCTk@Rg+Rrlr1S_@Mf(%b5U73w44&`ka3j6a65>rk!Y9-bh$5K35~YI&^i#vh~&w zv+6E;zcPX^#mPdvJz45smHs$CkjFpUBoAz}Px9Z^9AA__dYpE{{7y=^bdlqS)-MM2 z{(-F$%E0snk8iZUt?2^k{Lh`X@Fbn{|5So6i(d*+cilTsRoE*v;p?)sbUx(>0s1M{ zasMFkZP&sYqE5+AIMHSXv#0oq-|UTBR@sA=u!PxDd>w2wMLc#TL0ECUlNuj#eEI7P zLYrEi(0ukhwY|K)r!{H3cy3p;Fx*r#zFO6sBGx#PAS6zRV)v)qxJOsK^@zXYWO*$Ct;ioUnBKk~s?Yc6DagiwS=`USfn*5;{V=+1!6Aer$Yp zia%eh6?XO>h}=Kq`1$d^H;#K|Altu^;zvAj6E8kK1K#fH`iW8=zlPLuz^?84z+g9? z-%}mcrc|riTcXft@p)c6?)3ufBZ^F^PnEd0d3_nz#Xx`8hbqCr(jH_mSdQG)& zSo`*KK*I?(|9xMoPy62Yz^(mkp@)EMe5z0Tp8SplLtcWi{$I7dJpURRB<)|e)(*a1 z=lDt__?lWrOI&6A0iLaNP-?>0+O3lQSKn5KFB-oxZdVu6|Nex4qdb14lKjg%z#BWI zIKZVOjxU;jHJde7d|(?bJa5-dBfi9fK{)xR7o14o{Ex05niMit9Mm*g*xpR3wkPrH z_;Ad&3I)#-TptN1@oQd2s+iF;QE1RpGyYu1kHWb_hC+t zTHuxQ-63!C4?aHG-)Y-~Mq=mnwS)xYSqTUctge96vPw z`XikmnBCMK-fZRgq56eo=3iWB_8#<&d3>V#5A>RxDc}>TPEqliZUmZAp=>C>_yM$xv0WX+-p2sJuZ>;(; zTCCqAT6i$WMk9VUt{sj=Nny~i0oOOG5q;x&&lIsoX@YR7MVL)Dfq#8BuqLU!`_dskLbH@I{wm41JhSN>^hBKS%ZyGyx0l8cH#a@@pHZAH~f+G z5;pu^&Fm?D9!cxJk6q{vCRezBrxN`5*8YYuBVU4Z9>+h;zg&y#Fup_w`hTr1198n`FSu9mjy)f(|DW!o5S4x(W$}&nhqryN!fPWOpu$!& z{vO9&!y{i$LyLO8>i8r-zpr7I3MbWffRiO68=vYUD_>QhSKrqVHl5>>>hI5``qBqU zAF4laH?ybu$c>=C_{jYOES4~3u5f%( z{#bLaA1)M~VdUK9Y<#-@)#k%^F|K2r@G!N#8eek$I5uw}CPa9{hC3Xen~6RmP97z0 z_#Gw8dt$A&m&Z5ZV+h{8paKgkjxVY|&PkgjE|T)IA$^8w#Aorm(YRJC1}1GwVb4$X zkteUmqoJh#pUvR$Eu6%+&*fRz(I5?`#BzKpNPmu&hY{|R_Q$@6n(=vhWD{{kqk6*M zSA2e^`Pt2@X884OcW7h9@tH&Lx$aqg@yPYp+Ts}UHZwLNJ z`wtgN{kaK7?ER@e@>ky#J)77<-9jE;Y5aTC=nY;RRt)cIeq#92CHQR9)fcbjI76#l zJU&u#ao_0k#Dj_eEOtF=l^V0!PE?{kI?#>kr;+^%0IP(2P$A4@Re%DtNGn^B-LjKc7C+7QfE$7 zVR0AD_*}O%6jyHYf^XkBKI@S9IVE?3c-uTd7_C1^8TTbLE|xEasoK+;`pWeOKd)qiGlA^KudjoCJ_97x~VPR(N+lY zcKrL(_<6aN85a8)Kz{|tClY*~ZR04O&9oM*a=Cs^@j17a9qwOf31c!feEM-`Cv)7i;Tb0^(jNz zzru0fAH($gM2+~oyf+wI^zeeRq;mFrNc5GeHVW}^@E18g34aZn?TrTE&d{sPZDt=% z>I-B0d7zon5elyI_(=I{@zZu<^rz-Rzvi8lJU^G`f2m*H(f*eMBpuhxU%N*9LEpen zVDL^e{pu;{l!Jq0^*Oq~ z<2-S!*za4M5N#E~?2**x%wv<$_gG}-6G6T@rtmbzFUmIV%!;j~l!>^HJ)%J3I zPkEg};^7uT#oYnEY)3oIAtwce=l| zLrzmM=DDtLKkF15U!joW=fu?zydUcW38oxB`6PbjJxvrx9F7u#Us!3x&%_4<@l~Kd zgw^HiZ}N$L^7YJE@slb+kn~4pPxHSeI2vJK9JJ7$!oEMPZ;$&v3difjL#>bD>^jAd z!H_ik6fzNhYPquOdL%w=ySG)G<+nlj5*LPi{*&vIi-(zG)Kckuzuvq)P5I+7?^9xc z_A%k;BWGrxO7uzJCjvfSZ3V+)G{>jALNNwby9@IdaQ>Jh$or=pja~5l8hiMBhU1H_ zZzyQ#g9imSNSx30$!wzUM-G08ard6UJm(P_@spDqh|iXL$@n4dkF5rE#G?EfmFg$m zV+P~01|d)y@|=BNx_+VUq6>Jc)@iUF!S@fQ{4n{p2kves^$#VVV)hhY`&YIVPfuzg zB;<8cvfoD`k59KeJTPMQ0Pv`_kJ(fGKP&nNmUw-HuJ3G_J$R0+V{I-YPQVmq_f zBk`#?V2qd*k{~opR;c}3-d|PCDgf^*J>kuaRm`61EA~BGiuZdp5h{+JW8+hN-5DK> zU&4K0?jgX-wKr`7iI_3u`*M~P;S7ioRj zXcrjL;sCR!_&BChfy10Wz<~ty?J-e;&pb;t zKIQtx#DN2`%q38^{*&fUmrF*8L!|s^#t6;$Xqhqwr=3a!7^LX}#Y>to>=7C3uePg#El#n0V? zQh!B$G4#5dz{e-?Cu$F%=ahaB)Khc(@r-$j6DK}|>c%~peLlfY_vy~)+};taTzLGW z{BEuBSKN8)J=~w5VD@*2eqra}iz{L|;7cIs`|y z34j(MAK3kAe@FG1b;N-aYs%siU0<}jdI%1)_J>;aivRuG!{eE`;Y*HWl9sEt&Kdo|n)y?w8CU4!rci$FfPxV93 z-POd1D_VljOr9Un`q;M1{#e$^8}`=c`ZTRSzq4;4#=dJJlr7dAf5uu2#IZp^u%coC z8=tPvvkxCGez1xXbV~X%e5ESo_*$qPgk$>qLa)vLiy!j-#nsJ6if-rQh1XHxYJAH3 z7tb{tgXa#8fW^S^MdQzr#4#AVC>hQe4PnohMfAfiGg2|L;Up-&$niz@XFZ#mfsGQ= zAnl_ev#0sds*C2>=SNT3{(6+(b@tH~J400=bRAzGL-qT4EdlFD`+HP|uehtvaZImg zP}kT({rk%K-K)t?_&Uf@#_y;;c+^25-kA9dwz^ek_EdjZy~7KC4e@|+-#Gs(CiwE{ z^$DL0dk5xoCaLo;dH<9}`+-=pF&LIk<@p!QpYE0Z#1j?YWcd^ApDJ7sgu4vyuCqNSTlXL&42iz@$J!IY5#IPcbK1Dz}{~&>2K_9@DsI#Z(uU1s!|jF zCN}m*r^DXRHRvd_zeDh6ZSRH3-|q0lg5&G|>3^N8iA$SS5iUn^d?`r%x#8>p)H3u1 zp~V_@f6DJJJ2n?hUo;VJzc|aDkH)XHAA_-KW&p(6&S&T`B)-(CQv;D=UJZI}Mn<9*JMU1p{ycI>P#Fogx`ht$8m4hqEhp8hax*e*7HG0`V_ zKS>mukBk?#eE-GlDZai=55(${KA^DAQ9r+Y{Z-ZTlT@r3nF4hZ z`T7_d-@K>jV~zXWD(zqV2318ogdEqHBNnHA*u+JL>sj9Sj6;spuQlRIqVb&GAe6_dCo9L2-XDXsge+-%RvDpPPO-PvHm7M;`F^Bk{{U=_U4` zUG{H%jYj;f?&yW1d_AFA@;PRoL-6m2*Yt8lq7q>&|@#XuI z*WFV^yw$Uc&^*$e+0*sEbDt!LeZIyEdk$#ESI9SCOzP|lE_#~zp`Cd%@y(j1!n>_% ze1Tm5vuGcRb^}6S@=MMSY5sN2EL!~G5haX;O7L}Asy}`Sf=MOm?ER3$FEh6UF+L(* z2>%hP5no;FjK)(fM}f~HjxXB(Tl&gY+-hJeoCwg2uTgrVP2LmiL|-p4NJaCZsc<~12D?t{ zSM^rfpwkDNO7+1JN1vf%hZ0!rZLYq*oIgf29e|G$2EalSo}bb9HfZn{Y<2w$ z_Bo_})iuipjbBubukF#l@#o#&(8?y0;fuyM>!c98dMgC#2a6 zw`s6A&Vzkl8vm;9>WW3Ly2;Kjru|#?Q+r~Lv_F~9k>iubH-p?dV$H2}h5J7jvinnf zhBUIlka0>GK9Q_{UgU5e7d(9c2U>IeUPbt)GEUGcq|Nf;NL&YIsQNjjkk0}29a{N8%;Ezr61EA@3jz3yoUg|hpTv;_EnK z!27nzvh`^u1b-VQ+lm!$>;y@tQjag^p99+`<3#7tFfCy)dw$A4w`5PjB4s-G2W!S( z(_USr{j2mV#ox(6>G-Q@CU}0~_{b*vhfS0AU;3VA3eA6W|3?x(-*2rZju=v1=&4@+ zNAcNWjWu>`3YFHU*ByI;PqvqUk7&l*9kc_57hjpG(Z1^3$vi9(ezzC&X*< z_($_U=d-cm%3E>5)=!6(+<)cu>4OXXu}ee{)c(cs2LylfPU(pIX4DeEbsn>)_|qTn zjqm#ULFNixAE5Ya>D)woW7$kFzM_tQgrA;Y?2Ai610b*w&;Ke&{BwyPB2J2o5;89I zQv1Ige`ogjp>s+g_`l)!qxs*-tFfZV!#H8^reHPx<@)7`_#yZyG73i29mT${iqr?n ztZYTsllH>eP|f&z-7gsrogGuDzGFkFU8*~@fPkqd>nuCQg%AAWz*zr62xIsWzk2zLhmX7~#y^@YRzym7XXKO{Wo z&rkR7bJx}qo5fcZif?5xd%8YH>try_eJ~Kt{{GCyr|Y{*cS!vYm%`zVM=85b`>PsW z*A~yKbcFA(IR2=<88Tm5pEl7KHW^%C_Eg`*nm@4q{y(s!o3`>le9`r7-|wq1{-h72 z=^j>(FV7FHTomHWyedM|=bHIx)kofV=Y~HV9l`T|s?SUlbwp>6+QNywn(?Xi%?qc# z@PoG7IX;U?|5f3SCgP2=&4mljyuLv7&+Kl#Qh!aLOrI$x`1FeyEC%I932|dJ<8#L; zf9!NI7%boM{Eyze4+TYlh09$*F@fW&7_|SF z-YU8uc#r!Ezrv&(1$%y)AAXIK;@i~#81RcfKkYC1VEzrSr2K|zS$usC#n+~)!FXkH zxC~#kzA*evZP9FE{Yvx0TV(-gA0GyPyFF#kNBc|K)YTSSC+Y|n7HP)c?2(=rd)^Py zj%&u>J86GEGf6+xU&is3L-^;?W7WiYZFPjWd>`e1_*9Vm&v%axdbSRNX9sxxNBbLd z#_EV=A8HFpC7SWo=Z+5=*abn2)trCQ{;b_OO~ic(Erf=tn(-B5=Y#XN2Fl{!HG;1W zwIW2_i&4S@EzS5kksF*c1C4s z_e%NaXhTUq?VABs19~ufimy-)V?0u14n^8Leo}mW-dKzk$6i3gQvQB4{_U*jgRQRG zK+}ah{?PRSd700!WbZ3D`=FP4e7Sz}^sggs=)E%2igQdPyv7baFRcIz!yC6`xhL2mZmZO%`6W>52-h3!}>4m`Dp(5an5hVvsL8y zB>7|4KYrN$Y$z1mDQ5N*pXa82$3c4)!aajb8;&2jeskfu3TIFDhe?~wTDI(Vo!KWDg**R7>GzR2^({4HL1 zz#|Yk#_{|ymEgDgv%#Wg<6(kFJ1w&8r`Z+xxFDmgBe$)O0UrYNjd&*yvZ#ZJtmhRxB_{;B4@H_17 z8w^mQbNuwV>Wi7{ zLg7n4jz8M}Vrkq+ES=w680u5No{#cVv9}lYe-#KYk>ii9Z{4UpP&74(5~?pUSNp#_ ze{`zni_!N(VA)8HKU$x6JTyeKYY`{BObO74zbbpeaPr+qsDG66Q;NR?XIpVgl#_7f zxn}&8wT?ln9?75z4`tt%>ZfK^CSu1C=@6OE`6<;;ub%IOs^^vCuQbaD8#U+!O~cgq zB>IeX#v@E=TLwpetMNtFhX))p!|Ewk(CjIXFBD(*K7GXEgx{bYY0sXY)(4;ZI-;V~ z9hO;ed{O=y*8MwXe9;mLym@~N#n*xeFT6TB7#>&f=co9pfB7q3I;0RHCurVZsIEaE z_L&g@Ynt%qr|VlUrToBUo8-R{*BNUmvpKv6ko5;{F|;nXjv}xw>=MlVd+QM_YEifwwAJr_~Bs< zp=f~@v#0%^37vy5X6|5!I=4@4FJFH!;!1Tfe@z`>#So59THnaLL;WTUA3*dSWtJz_Ul1h2C*6PON=}Gq)+JI%uryQK%kg<6~{ZSj^uz z3fyWAWZzGZ@Y|aS<8a)qG}-=_6rUA^9nn?VU$1c*&%bDV4Ekt@W2D@9D{%h?g3l_2 zPjSVka##>Lij7bEYwEl+LkH{!iH|hLzm!!~#2VFV3i~g3tL^3dH6_RamDN4KGmpnF ziqGVIZ}6U51=xS%{1r+3GkxcYr~8D!5Cd*c@o72i3x3a62p#k|K52frUlEM8jt+%W z#oyTT(e-oLg$+dAU(GA!uN5Et@$a+r6T=D~}FRd!9Za9teS5ki*UCj#{ zd4#~J-Iv+;DpG&+Z&OSB^h8&P4Qis)#9xQSs_=bIkhFg;=dW~qYnSa+#gFZ32@9t9 zGW%4Le~9~`1If7h2ykCA-0&~llEu7>>DC3 zsTL))b>;Y^@$-B;FFZCZ1TJ`Fv+?Qr^Ejgrab`uNFkU)in7_XqpC@Mddj(lv*Qi<;T9nH1Sxoeusy4Rbk&`Y$NH-si_}tcUI6gNX z2enoXV&l{N(==*4E^V6u`Wt!tr01vHS=SNg?Cb%Ze{06)j0UOLtn)O8GUoM<98&-2 zXkdtIkM^o`|0CT99ntc2eWAxMUf-qbBid~?MVQvF()e2am_5E;A;+hJ@Y7xWrTtHe zd$`X8!r+dk}^__hdm*mN&@Kgv&Gj2C(}4}&PP9Cn??H?JQ9#mu1L z!f{n|wg1WUzax88c-b-pE}iB4ldcbc@GL}(XdWX3Ow-Ii`)~Ed6=Mg<*4NSameMm^ zJh5=NU~Q@yKf9#<_}@m+VAN1E|2%M95bcv)g*}d%@e^HT7+#7P2N!yB{LudF?nx8z z+J{UiDd+iLnIP9ktDWh9%?|ef)nLu|*`bwzKO4`2B@NBl_oelVKmI*X@vIk!N!*^s zzd`m2QLl}TV6tQ;|NTh+TFn)v*gDG^yk=;Qe>Epb`c zJq|p6QG8{(ea6FUw1l|QYRsO-zwy%faWQQqe)xsk)A-k5_Zz%o@DmKpHSfRDa%mu* zdJze)&++(2`%6!~uPW+Pts{?rWPgWaK0f%}a}d}Ke8QfO#=lMrRk+Ge$`7Y;{L%WM zcSLpZ;qrRINOO)qTEDpZ+#RdU4TiOjn&X?0?~Sjwg@ab@-E4fi{vonLTO8HBp3veF zk6%=O*|OUUZ5IuM@Vgv;R6l*Pv4QwxZcE|lF3tJhv%Avye>tJD_(l0;=E)H8q+P6V z@iWICfINQX=lkN(ixIN*MKpemJP<0bbQ~rqMsobn_*MUBFg8z&k>!6>Kb=@H8av)d zhoZ(V?E6rDIHE>J+^%C(>He{&rS%V!l4gUemj$z@`e#M!9%yu=w=Djo68^Yzi;n2@ ztbwq>bP=ULVO211txO_ZGf$n}vG zi&dz%Eexzm5U zjvtzz-5I9B@sq-2^@kjyU+!8PA`YH5Oc?UDshYpZ<5yl6FYN6XF56#$;%7~Kh_Wqs7{w6kqL&Pn1!-Nlad48o3bd05r=O|Cd=w~R3E9oWCHrsng%yhJlOcDBt8ur+yVD{8C6lI;?EZwGaNPyK>rixPgEbVEw;r=rk=9;0L`xoJ+#Ct*J=qjXV+!- z2a;cX-=@MwRl*@leLjdT!O!!pY{Pc%HVs92qiUI;A%n36F z%sF6<3A2J=4k(HlFk|GM|M_+EOuc8Jc$GQK3=U0vtdc#h!K4|}!^M%(p^l7dqgmyKjH>?}TmF0i8!xRvI za3r~ZmGg!7uUusG56*_@(u`yUi^u*)bU#1n@HCu6t>X0+?hll_RTHe@4X75)X7NdK z>H622qh4V8djyHe;`J5I58Hk-77nC0rVUqIth;_GUnBnbLh<5ok{rhKe@8T5CesKJ z;yZ}-(G<=XUY}<*-51_zgiGeHaeuGDpb+8Wj0x0av~qn~Ebb4M+i@Zp>@nr+fA=>D z)mLAZMnghT5=jxpu+R4+e`EZac<9z6l_c2n`U&e-+iT5W)A0@}{r}SwwS~!TO{q?! zy7_pt|9Q;MHn4AVccONU=YLqgYTk5$%+8by7{K)j^Cg?3BP4j6QFCkV&tQMwj`oG+ zmsIoTU;GxVlmC#Ia2dZpa_Rb^77fJx#gB%PYxlW+$q;`V?|uNQ^R?vctYp?7!2D&- z3xMf)V~OrE&L8fd$BFZ2Tbqw2#r~Wx1*)&UeA5)REH|b;;he7|xwQXQvqsE6gGLdf znYa1%Bmd%Jkh)-h(U88g=l&wj@3yV;2mQTcNLl9#EFSxd86W-Nb9DrXJHhLx8stwT zjZhO#95$eHtT;b1G@torh!+fhI+D1YRnAX?wL!vWvk7!;64xi}PvjmG{okx`a_YxY zc74ZDe{FL`kkD=P1bWw6IX?~8`a{T`F{H)zR2H9y{6qa+LBi$c6X>SII({{qSUh=}un?0Izw&2db zAI|Uer&GAw-ba$(Vg33w>^a8g^JUewH#v)^aL&$C5dU^6R>T$Q}PL%P1M_{%p4TBSwvp6z7uGUUI1`|1sL z4MvmPH=Lh0h@aH7VM0gm33S?GULRro*&xn$#+`{ENd?^BOGEsWbR8zd)EC1~_&TJMmZrRZ2gFZPVhcv5 z9aZ`d)pIn3F9jy_c1|5XXg;eN9N>DKi)20v>rYk}En)I}Q#x7B^&8huA-+x!bDR>R zI{ysw^)>JdTz{`g->*~7*NPVes*kDWtMZB`jCiA(pZw7}LjSkswBfHDrTSCS#uqB~ zk0BQFuk8Ng{Ugt>^oKry~;eY=`ax!H(L>d*BB z_piKS#Pxq|$CGw$7uoR%;^%q%SD2rsMYm)OlJojXS|2StGz8p^hf3zN@cMub7C+&N zkuI&jE1ktBA$~sgQ^45y;bdsyrn>JZ0P4ma?V)1x=s%4@NxPOZv4yXCw z9}qt!Ujl{J@1yAO>)ap5{49Fn2gM7=k$GCYK1xFT?9B@lj8{j|oC-c)h54CS8U~w> z#*@LOv)J|H^{GA2jsd6q*R%`5or((`SDnr%M#=*=M4h^CR^qT3qx87mXX`CEnf+tn;U z_&hF(YBpESpOsz&q+OdyzV=OG=g0FM?vrBRe(*f znCS?&tz0GfA+E0?d-W6Om!Y(9+ZJ|yoFC55l0(r&Ux|N?^TQd(ze8b|E?w4DkHzEn zyY+S-0$ab1B5vDxeTDPG0IlyJ{L`W5d-3^yoFC@u2Eh2-31m(Op5J2rZkknqPRKvW z`ng=>Z+z_N0~be*Bi0RGvg^Zqs`d8*HTwusb5l8gOD|{(q5mxCg9`2s;`ax%zaiFl zts}`g1FnDAzc^ee?hlhukDk&GlyiQi`nPS}U?}M_idcN){NeSfZSITn+cG_>YX9S# zXFcKU($U0z1m|xt@&|ie`37m?{K&KL-R%50e{5hVz8}8(I1)OF^N0OG`2v3-)N}%k z|I~^3gINEHvwdLi<#A+746ncTBmRyh`UyIfk#t9UzP<+QpL55N;93w*7M|hxV=T%a zhwqGnWwNwT7NUSd@yXd8cvKpE9dWhfU!^* z(v;@**~s)yhW2OJIoThcdrc&MZv6W9qx!7S`xTgdmGXz@7hjDW3c{jT60+cZ-QQ1F zvcBQ^PMMHzU`*FlXDijm?wOwObaMpxdxG~pMt4;#e6 zv55=Fk?zX>ipr=azqjy*h ztop1^hc#Tt;<5g<@O6Yn1NxK0Gk@{pBY&j##A?`>DCH09-{ZJGFw4SUvOWj%XZY?n zocmx%6Lq-1FGKmKr{7?3S~r@wo5@&yjrDJGqu20gfEo=gR^C6J_170BbeKr4#_;|F z*1t~8Uqa75wG#cq@9&uLItb3bn?gcts@V6(^Z&C3s0jnMn$UZ;JU_+$W8@kyc-4O# zS+JnEE?(L{vvv6bjZJjvdk0RQz4o7CU0Nb-VV4&x;IH<%!QUw^re&~j}Q&D!cz7ccEU8?N+*nmJ{)=S8B@`q0_P7YxECk{A=tC-(o-XT1RT zGg5uTd}hQCgJvtIkZye{+4W(6=H4U)#Kc9C)@mi}bKGB(d_TD|{z6xK!H+rP$$~%U zSiA!9m!kLwHJZj$-8!HyUdrF(j-K%H^;mNE+W{7j`3rKd0lQ5GbXVL$7Ecg=?z0u( zl^991-1+Z2*2jdLFOd0LmmZnH^%3_6W*d9K^YU?|UOv}HUBur5FK?m6gecmvp>qCS zczT18*ud@gj`N4}Q^#_J@cvUIeY@I|@r(8Gy@|O0{MH0Xev118d$LA@^{`~g`x)_k zRi#=q+!y_ssr3id-9M>6b9jX{c#Z6&a(&!+r_I8X<;Uo&_R9U4f;4*=k=To@%va9e zkNI!mq=P2Cx=}fQEw!DXdc;7o(TdL}6uyPO-ABZ43w3O>(3x|7rh~=LI&5vAfqJRe3QN$>c^M}{h)O6Mo z!Y(zC_P5dgMFVTS;MT+_Qet$0oge!%bkZN___Q89HppMj^H(Wk1J-@Jr|;Zd}4q;mc? zP8Q#<;5vsL4QQd$4$#*6*sXPVSWZ65pk;{3CJh9fNeGLYnTSI$>aMlblXEg}-NEDH7?u9Xx{7=7xyKK3=n>x^9s8Gu z#s1O=gGt2cBlk~2k$>``!B42ap`J?ql41fO`(QlLkK*|u_Aet+tD((NJ?dLpxBdm` zSN;B;u+4b_>F|N`hxNngVnkqshTx7uo&A^Z5_&KJ@61TO#dXx`~Gc6^*4Mw@y1Z$+>O+$Cq^fk(ks+pg8h} zoIlU`!1EvPY6n8isIe;bCwt;k_@OPM8~@ByT0cFH@P;2olStbUoDZx|c8h+(#jVo) zN3cE}64ytkADc@4ef+?_ALb*fb0r)Qf1j-?`FwCL;$y;WKWM*x3JI@y$l?i_4|&o^ z0p}ORNc;=zAA-kk*eCiY8pC=0g!jL*65sFCadxbP4}$y)=sX10^q4^Im2iE*^YLGz z41|(ITdMWylAPy<(&xWcoWC;L7ELs6@aG?|kFIBLD3}H`qv`{c>r2c2IqlM&S3}bd2Gn{(n$rBO`7nPV7GnI`$L#xK{qU*M7LN9_qSUCdT$z4E9q|IU%vdr# z@KRm8bbkK*Vjbaetre{`A6FMI&EI^&#rGq&k0nXJ`QIPsZ|%;%0o}{mbio^*zvUwT zVa~3>&{=z;B!9#Ef84bb{fqs^^y-=e{QM|?`!>uIp8t#{dpB~vu)Y}TxC+}IhtX7_ z71tN^{*AwPy`a^hSmN%qpzixi-@jofzW-I`Jcr1wX0y+6{uZ@20=ivKC5bSWeO^YS zd`&zt4m6f7Aj6&wtc#cW3q3wJ2Hp9cRpxIRI(-HIdZXxzVFti|U!?ONmy246`>*v; z=`ZvPD~63tzLCQEli2xj{qwPBd&n+vC#|pZ`UC6J>XWswr^bRhZ4c)0h_5Hpy1`HI zm%N`B^CgS82mQYMBC+SbGrq7s-B>sP0%naP7U*gCcWc{ z=io=|{^0s)G<CxNI=d*YdDxI%i{oDim(?x%@&VR@HHe8`AT)%BYN8C8i z;<5kt&}<0&{18pvcH#VC|Dht{13WvTM;jYl=hu(&yMxtU@YOYrWSrpq;r`ef`(Rk( zn@CnJ=ltRIUC%_{&BS#+k;}%N{qO!dqWsSO>o~BVo<`&+dH=Qy&3{ziYz#X_by1n$ z^>0E2hrXleYCFy!?tgV~ZvoT2jy+Z^8M)>s!XZas$vGuadvo ze1-V_t0{yS@ZSf_m)H4H(2M^i>2H-GzQ)Y-hr(tv$l5T@7uGk=1z(`a?t1jzu!T(D z@c!hh?G)f&Hks7yxzD~o_SXZF8wxMxI#J)|9pwD?QCc635!XLkY@9;29lp%s@%!of z$A1QUgL<@Ym4d~~(Eb3itrbx6ax&>zevHLqeUr7TfKT_dslS5jTN2{yjmZ!g-#?bL z4d2G%u|IL*y|xfh--dRJIahanY5o{6(G&8XOd>n?tzhwGsQ+v|)C6wYgz5q`I$C|9rP11ooOHlXK@2+3^YLFL!3$6qI633hIOdrco{&><%0SnttB@J3|{&4*@ z{(vvcoHU(WZ^iuw+@EsVt1eXjZbT~#R&c(Mer28Zh9NDck>N&MzmiaWb?yB-Xf{rt zo{iIyE8}bOO$8L_#}oh2SJ?f>{`sk__mEzwPtCS_uz0*a?5OyD?Ga8>hKWj26cizFykLRnZ+ZYJV{E8LFH=k7vU{ z=Xi?b{h^q@S6ZXtihKbnNK~$G1-Bv~*ei`xOj6EY^S_P6^*3FKk(u)O4&QXSVBRg9 z4pry+hW)`n{pOJBLL~JYLF=2xAD0W2(cv^)<0P`*v_hKA2>@rl&N1bEb z<^S=E`7-(-yZFN6%o(KDptbD!asGJ8PE&9@XGLGltzg%W`7;vVUtIlRDw%ki z^N0Px?j!pMlS;$rlP1df^ZPOs689#NNBKOz3`P3az;Yx!*GZN5hgkmxJsb_6v+Gv&Vzc>kL|qf4O2V8j>7FFy|UhZA9Q zNO;~Sc72$yxL|K6%AZcmow+}P^=(iaPZ;=YDw!+i{N$qfi?`2Tft`gOHMAedp1&lN zAAU_xz~PM|zvd^|`Eh=@JLD6jelVt^I%cwX?614HctXQZQ^|INJQk1niCLvCOgY@4%j~MM|9hgfT#&g%Q0L9c`I%8`3#1WMsb9;h`UnYX5!5GLIX};* zw}DC129w^J{Q1QE%oO)0j+mrNrwN=N8Ok5GZ*YQpy8h(yZ{_-RyHh{#_7>+CRLuWI z+m*uAEw!Xr?UltL*u~>z{)+ z4}n>m<4N`y<@{~G_6F*U>xU{sc>V~8zno}q$ab7bmSmq|*Pn#^kHkM8;m@&p^wGWy zcK#%!UwbQufX=^ovUvpO5BImOJya7u7Br!+4xeH1c>dzV2ye)+o=I}5l=IikCO;%!0a0G0S3Sf8G) ztN|mv2J}GW5_Wv7Pg=hn;8pt}5`RAz<%eS**Fa>a26S5YARdqSYJ1TMe&+;`TH6}- zIo7A?x9@}QBXxQphrj;<*Jo3Dy26*dD3$A9I_r3YzG4_kK(A zKivO1oEZR3XD1WIt*`9*u>Ub@@fR?anbR%BoG;w}a_#H~r_7Sbn=5539{c+?Ki)vx z8bjKvm#&=WcT)c&r|l4Uyi#F<-*L zk8pIVF>PzGkjEpwh8-CKojnuC?PAUs);E_Tneb&yf7++|LIa;fvdv~a zJ3rR9#hrD8@6Ih~?}3#(9@S?StvzA?{RC1yGM&Za`pmsdN9dzrN8kJ~sOt|%^)1U^ zTt8}`Bw0Vb3hCQRonYAfZyrgD9mS51`N}At0I7Euk(G12+2=_pKXhHu5VRU}SLr{t zSnwT6_t&S*#~)$wxISB^YYXoJ`%3oD!Tiye-y!sEeOg_;n8oAzY{NVUnEQB$#DB#4 z7U}#Pj-An^?K^UP!}EpJ^_(DIGmr#oE9Y-w&_nQCu1Q1fWp(G5&POfXMB$ZP6lpt+ z>lfbNV{WnndUlyj+STX&i3#Fww^(28O->?*f`qAy`TI) zK4nP1F4uU0>N`!}=m z6XZWGc-k74^zoF;e_+1K?l?l}_dv2?p>lpMc6bSA0uAV&k=pF|c>RicbRXEUY@Fo% zhqh>coY2NsVM6J55~wjzY5u6tRzR7_98%ex^Cd%kje1uKA)BQ8b0?wtt9PvrG9ja;1`NICj$@$(evLcbp*~9e<^VRQ52~5#fr&Z5q$hp5M?T=}`9t`~JkAeS{_}!3ojK&na^?QUHfhSmW~NqRFs_Br0ax53x?;6l5rd_U8s&gbFaqbjl`kLwTCuPe4qp~C`KmHTf` zj@~W!Y%8Ws4~uiOi8ApY&L54(wuVI?JXQJ|O~-8)AmKXgIm4XA=b`z-+FVC)(H%yz z+bW+A2@1Ijiw|nh|9gKL&L59IC7|(l0_jb8eu(vJfPojR96Lv)e$|}yg^vwW$hb~C zKXgR=c)P@x~kyF!pra-&eXnz4p!$uoCy@H<&V0&hNjJ51pT$(8hZXX^_90#pCr`<6ggj zVPg$wYkTEr24RaqZB{kcnU9DavBeXacYUOJ%_H2Uc&@gK@ieN>y#5oW6o zljsNT|7w)KfCIe^Y1Im@A9#NDP(2EMJEKYay5E27-<=)t40@XC(H zu7G>i$>iTuULPq?|0<+QIjo8`q*n@+`w!9M6tG9!e{c9rt}l3gcJJ6I$lgY@=d+VMr>Hatq zj+McH3UU2xiybT;*GIE*ykNIy67e0sj>Ths;yg42JFn)n)p4G`VSe^s_kwYgl1PvE zOcsyVKMHTOgzSu#bl^wj^-+&Gf#Uv}sbqw8GKb>g}+l;(M<`l>~mZn{cFwrc(wUQxiaf@Dd4hWUznrYkhFZbO~BZD#s{ z`C1{qpRZ^8dE~suD|Y=>eWmr$%yk-q!Lk(hJO+s@99=bH{1_(F{RTwmXH3?&Jdl>6&8 ztIJ@}1VgIl!1WK;PsfhSA^fyz{w_}c4V`;f(=JPwE3KcVRSkw#&BU6h8LywPKXK(t zC7g?>FVR04s-GMtdBe2NDdb-hu79CO|3;KH5H_ssMJG-;#QBs-_aC*%@rTT`RN~d> zHM>8!z8XJCQ&_jICB5ikBj@>>l+Pi(eW8`vJhIgM4vSZy{@0=QqW{u5h1_d(mVJ)v zr(H=3XdIG4&R*es;rR=7e*@u#O9v`Da=Y&QQvYF`I6o}xOeXb%xxa_^N0e!42-PJm zsMcfdpO+!Ne!2KTv;Ff(>nXgx!2PRaJp*CdqxQ7@U^B)SLH@amqXKR@q>$%bd47oJ z3#Vs}gd@8%$#HuX`sHW>uG6{@?H=lN^@-a5$`tl*?uqg6-E0|&=&YQ-S5X!KS9_?; zA9svfDRj#!pdJUp+3{t_pBOXNO58t1HGh}1bc81#9q5z4%IE73)U*VH=L(helmD`p zFr(C%=4A|Fe}By1(Uz#n}I|JO2_k6q-fZ;|hI!t#q*EgB8zua}a2hh_}{&0QgaMKSw_s%CF<=j8P{>4Z|IsABR zO!s!>{yW~kX8Ew8u=+z9Y4q?tyMD}H*Kg0D`xzri{f5^cf8VQs*`j`3tkp0z&-jpln z%lEN2bSs)iZcNCni#OupApT!{KtuR;z@D~y$op4V-=MJ%oT!;cE?IDW!~H9>5?x`a zQ+pa?#Pdh&|HW+{2B%J^lb}JIFYNzWdi(_KOV;#OT0@?H%9={9Z*a2_5H>oCboW-y z-*7WSIOE-kOuohYH<-VsM@K_Z&Jv<#r(oY->?KH!ukp@<+_q^$SH% zf4*w}r0-N;2w6R!7&!9t6O=!C9M%y=oNGs+>lUT?arbdH#4P(hEwp=aCj!MJyiIckSpU*c1MTBxE?tS^kOoU*#I!;9-zTrW>AP z@e0Ie3)7qMtc?bJ_bY+LV?Oo8`K}9nQ%R4w11uirpA&9*!DqL5q%w-vZ`dE1{779m zyuzNAwNuXD)U)2OFC~?{9?JR4L;j*!j;(;`+pF(&g90y6-3TCms9@VMM+&aku342j(y6?`W93 zda1-;!S&yVBr^zG-cwTlVg6o~H--^DZYujA!CErWv(7o<;`LA^UsGi;Iz{b@_ zqJNmL%G=w7gI*;x;!pz?kLM5P&2I-46(OYk3jTa!zGNP~z@_0NqM60@AN!YDjjq8T zEp^(@ZYt9^g8Y**>p{>tB3Whs%d!3qP>BA*|9+CVztK?g`?TV)4-~yr&EL6J;`=LK zI?^CvJLeDimvJ5eVD6Mo`V3I6f2+j(CER55NksROy5~pg-*3yk2p{$T5@8+ZD;M!K zCd3cyzAhkDkNExon6KE@#bCKmnhDjs7z*3{Gsv0id_Lc{uhgHs=kpj^ z8yV4QG0OePVt^6rf~9ZPf31>`Esw#0*%U}By!tO7LWC)S{3ZNjUaC6umF&R^+?wh+-{IC&b% z`NR3AJnAbniM6JSj#$)ve`$T!|6vcXIu~)*~IHG z_Jou_JYVk?F7}6?%_nxtcz%rQKZ7h?;qlv!^ibS3#vksV?P=r-pMEYN?{@I|FAwS8 z1M&CcS+P28X7{5mUh1FxSt0Ik5j>x~^Wc2q{(*4DA13Cflk2Yw+5K@u`gSL{2!w}H z{&0Ul{?8ZMWu*~Q4L+Z68|@$br1?`gRo|F4oXYc0Jm0Z#wl~bLo=-9>c>SM-_|r4+ z2d^IK#OKg5c70gi(q24|PGHndc zA8~&<^0GdRD|aT3y!h`o)~_*sqhZM})qH)Dn}S>aUMl&bNsYkehnvd$uuY>+phK-_ zt_T1AI6wULvN<@~`Kp|c`W^Qic37Fwumn%`{qg*7%cE_fV#x?{LGg=yj`v@Cc*zCo z--sp6>elCAK3)V5gqIJJRrc3bw)2L##S6&Py8VCg^B?l)8uYQzq{$a{D zA6R-kjhqx*>%fb=L|FwsgUbLU)Q@g|6m{C!0*_LUC3-Z+WH;OnKMBq6E*R1l_WF*LtgpoTtL;tg2KQ(TiK*cIH~juRr@{fS z$|Z%Ux99p%Msy_kS=!VqVC94K1NrY;Z+b(A^JyfYn)8Y4r`D<0;hjQ@2INg=&p-Ar zcB_g0*TQs?=<$wyKRln?cj5!sC$8VJ8K5Qq@A=33?=B$$P?aY>9|s<>`1^>T3padV z*7$U?bu;G!>j(U~2^&6W)8dlZ?D%+pwBFr^0{xUp4Af4tEx3y=L7o}Px}vr7QZsd z+X~JHu8-8Fj|7K}OGyWhIClM*kAjZ+FwL)v%KGQlxq0xi%UG zFOu1h=SMg{OW3^-3fzv7QOg2ZJVE^U>s!LmlmW!@FMmF9ezww~3KHH~N#0+C=L1JP zXa>W={8ai6^ZHdmi$7NM-5t(PF5>6O?l$o2>qruDia)=YpO*jb!R@0)bjv4Ae*I{D zr2Wh;(AzGWTxiPU@%*4X@H!kb)uvsh%_!i{uhbv>^TG`_&Q6i|7nr{$EfuhPaT>Yw zljo0kKJa&!C*az`ltwJ&{yfgl8eZ~-zMIp@>K9y}aDFy1b(pxnR5m&M{Tcgyd5E7g z&mID-F{ZQC2FdyLOZDe*FCXYoolYv=alUYW%WlU**dWfg-`_Bw#V4Wu^3oh%I8c;9 z9M5z8!Rz}APZz>GasTw^c58UNT&h2tw|T?&OetTuzdWO53G9ZB^%C9W$|`s z|G}V}#?a(OZ^{1Dn4cj{E5Xywnl7GnoW8JbNM8Tzr{*9*gp~@C!Gf_f;Lb%yW*M^C$HeBGbGf$}NNF?d0_h zp3f+_SO|%w8r1d-=LgR}{rjST=`Yhs#1F1d`*D3EzCXA7+l3^d&vJHs1o?NJ_lf(H zXk-yjf6fo~#~-SXf*j2iOl_H-tnI`H}y*Dv3+=0a&zKAC=Z3Om0h z;%9bMJ!k{HCG)eGpR|AsIJxZ@S<$FYe^CGTh;c(WmadwgnJpH=jU&g2`s#M<{J6g9 zz0wx?I{K^RCxE^HqYe$|?-0%p-k(tWq66fO3?q98*FVfp+ttP5`vDASo8`Pe6^h<} zlJK+>)SEJqG#RFxuZv6i!>$%{CH@@Nm-uo`;q-VZKX`rP(feNT=UY0t6VI;?^J99t z6y`oPq8Z=jvgaT7ho5fpho(2Oi1C*ycK7b}DX|b7P%-P%ywn$5*JhIGyEz{U#K+vG;`-kBEOKPJaz2_nhQhx+%Sm1# z*N0f-p9M|Tf!t@E$?3}fn~#<1OY)&)*wQhdIP~ZG)EV(naH}3PJd^o? z?;A+=KCAotqWvi%E@go4kQ3zS75@C={44KYQ+T{t_499b-~c%G`$$smv}E@W`_q?9 z9pC|k5iNUue*FBeJMj(v7}?Q*m6j|%3FTk&0-T{TK8BFG{b#Yh)Vtdc93oXe{|<&) zLdp&&mHM$g$P?aONGE$&aQ(1F{h_jM#SlEqkf!%fsr&tx`U92D{*VxuO}++Kv+LiF z{IL(uOW>GoJ-TVOrkwx2OP_!JPJy7eXA$Y4U&i9`{!2f9d&6+2Omgrg*AE5Kk2J@J zaB;Wk|Mt&i$H)1XZwGPxzi&3V+vy}bKJL$Yet8NB4=iZYU->K^`(sO5`@;*bZ1OmT z^Wlj2i0khQ{zh43SPADN7V)uX#!#5FU@@s*KdtWjN$dOmzed8o_!XpLKGzRh#7DJ} z4zv*8J+4YW&QD8%oon`xCGRG&<755EI&1`o!uv?xzl!-V`koFI!6!&=+o3ETufO;v z&eyj5JdoVq%Aa3czqs!y2j|b0w9}C6x_D{+l{Tm;glPt-?C-Q+S`ItQENOIie-;m@ ze%WNx8ori=sjOerTit?I4hFPAtQw2Q^Xu0No#6VTXku5OTt6&jm!PMH7Tp=j_jd`U z()#81Z&ygoo2$}4nEmq!bg@D6dopSNXO&_wIM8&G+lbdUSYH-rJ%r0eX0-ID^8Bo7 zpt!ztZ8rJk#`(hf;W=Et1pafpDpIkPuTsz`&VS!y@Y>#8_{Kg zzx+Qw36<)L(@1Z4usxHMH|F|+{e_AL;{I{|CUk?l^7?05fiK+XlTGUFJ;Bb8>z}42 z_o3%bQ_1_0F@K@w{9x?IY?Atf^N0O6&A=+yc-fYY9QK@Dzf30e-yW2D!=mq*WawDV zC$5h!E*%C#9F~%$igb2;*q?Tc9s!HTtsrk6bN#~g(dDz+Fs4^mmHnTbg~@Qd(?0U; z7tinBp!tTKy^Y|LhFoQSXL05^^xS6ozx_?w^L5QcaEeBs;Ts8R9b}vlXbX8buD*`D0k$9>(5))c5-I+*?`Q z`KA4z9ygre_0(AM_YUU+`*->s3gN&$ZJPTkfz?lV|1;Yjt`Myu_U|R@Q>6Z$^`_ro z*Q$*~{|NH;4xjOaRo54iL$*Bs!1GC!b05I*`sOs}wQ@e6H1QMP53-0{u>8cnAD&Oz znpp_DsaXzvC_wIWMRH>QJ_gOnwJm!~jXAogb~cCC=)kC?yGds;BX ztgFiW(Mw2z<@WoC_IS=8e!p_kPeb@~QLb{n!KLUGtWa3dn#3dQ`u{)v94uf@mOEKJ zSh+qPh^l}cC#+~u`z3YpQvUX9+Q8UvQvUG#Uyf!0&=Bu{JFL)=e5BZ;^&h!KEOS?re2p{Xw&sTYUm4xOW+V=8=-(r4vRfF@Di}Fihl(@dQ(IR4;&-uar zc-zrsaBZU{9Z=;f|L^*e(EP)J9^PdH(1S{Qypu zo6|MNcC+JSK4!ib_fKn-P5fGMKCu4~oO}<`bIjh6Nvm}{|0HOC>Y}@v zka(yI`S6kZ-`Ky94VeuSdgYVRZj;#c0n)c7Hx1xa4>{>mw>}EzpPTNQ!{Kg&ROXjn zM_<8=#@5t=DCZ~L+ZsGN2CD2Y-Twz*_)mkHRCQ(7hxMy7u?N$!;`>$a^7^L?y`Od7 zva2v{p+5a;q+GvzraOU5h$HK}aQ?AB-sakQ`0`qds!iv7Vg1V6K_O|NYifL*i&J*lyW#bf?PomarYOWCArF6R&L-)Tzy z;rIO|q;TzOc71^Aw}%^tf>Em+67H43KF54@IHw7JPIM((Zu0w&`AApHhE9Ha$)*0h zKUIzR*f+!gnx2*ubsf$Z=Hub7cVKX|8FiMOV&_jn{@#OL=1{mpH9uM6{@xjC&FT87 zJpaZ1#?jkWF!OGp%KEHbML8_HYem~t@cJ+b<$wK`wS>m6r2Jt08FI}D5{^zGN&D-* zAM(eO;?F|Rc@5fFElz2E_q!zpj}P<2`3T;>1=PO{JNN(`id5HM=TnD(e{2@rW zoZl@=z6rV3^=Md%a)0Cf8y}d`a*2cwtUqfK3qjXIk9Lv&Rmw+SGjaat`66Qfo9j~< z^2eVQJ%NlJmh_L6a(ybj762`amys1qi`d^E^Rw>ELoiKmK(os-HOHcG6*N>>|-%c2s4kKI&NV}w97H@+3w}CNc;Bb48%KUE5?spKA(wy3@ zQO;L&Zz~9j5Z527n6EqZ>%`8F^+{i^CD<(+t+M|V{^Su9QcF6ssUeGZ zME-eob0;|KKb4%j!uiAXm8VSsc;{)*C4>0;8L>V+2quu&B~`*7_SXe*f1%ywStREw z|NCJ5Y3q9fnmg8`8$CE*IKOM!N!)+s>0+`ondf(a@;j?ZmtopXecF0nS!^R>x>q zCHh2=K7HID1V<;WB;!|~XYol$pPChF3!1xo(4!Ie*!l7L;VG*E;r-y{#5`>;i^ux( zFQOD83(cu*mGb=X$_roUe`+at{fz4u=8Jy11A{J_(dAVi+4*HM>HbOs*ZG6`$7Q5R zGUpHbA9gm^;6a`t{dZQK{CEEdk>-ytkI#Uv$M%x0-dXJWvA-X(Rs+^Ybt4P*D%ZyY zZ<0WF=ON<0K7qyK{84?8KD=o{CHs3~eQfEN4sSc1C0kmBuy{Ow5!J{Hd^UKHe&=|8 zhW*Rd_C;`~z?9m);Qb4{K5NgeCUEb|P?hr+n*WMG?r%nCCA+iptUyTh-`fJLsANl`<0gf=~{8Wj4Vty+coCPZfEjn-hWTpBUe_sx@`%=lIB(9&B z-?E`)U>0B{$uGsVT$1^yftx(QwIYi&?8o`W^BIH1_kZ1aw}b?p=J_M`|NWy2q2o_| zYDwz&Mg6ZI;`)0{k0p})5%<6BEgr+#kVdqBN3M?w!VXUmXl`v?y&o3i|V(} zB>}MN@N!aF4eWCT;`4IPhY(|KNyD1#lXLx)&R>{B1;DMy$Jlc>ie)>tc8iX+{GdePHLu^XVVlZ$SHc#&pgBO{M%DElYrj zse4Jl<4pGbus_n#nkY@V)I^IPv`$*`YIs#pC&>t5@`(Zy&0%e{euM9k#Rs z()bqV&k^b8>JU>H`NV@nFHp{3!0t_g$LSZe{yi@?-;Mb@rqu*W#t&1;-|aE);M52^ zYWXCLT|drG>*u$Co0+QlYiD*Ay8h9k_DlHw@VI|K$94pH?No98mFp*-zkSuW03Jt* z>mz3<=Py{J4|w)TC5p9tei`%kBH;#1t}lK65cVe%uMC11=WLbyoeqBj&-yf>hIxE{ zP+KbP&+QoE4bB(E{T;S^VfP334^00k;P1kvWXyK1pO;a7+W7Z@0fG_G(r4% z_3(oZ#W`fhR^|EW&8zoesg@=63R)=tk1qv!Kf^ZNVNm6`imW-w^%M68vUWaz3!5xy z`AE(u*3TQg{h?*ra^hsn`Na8Ys!a(TEU=&lBW|$sSF((yGs4c@|p)Wr%saa9Z4)6?>|-fMHk!$QkDM8_@ikM{|U$*m*FfP z?~ikIqX}GYGFWB)+h*D(VNqE*Rm6$=Bqjb&I55AXLL0-dXHtH#ziImYClroyq+Op( zV&}*FmKe7HuV!OZ_Ro8ycYrdVc+$0#az2lxb%(5ODa5aC{vGenYu~U0(soMgM?4>* zxyv1lJhMskJD$Jb{I=DqTi`d_jIJM*%JNf!{7cgh3UHjbjQr~IweIgD-5+PwtwQKu zYe=6|$>dyrr2X+R*L|P`(b~*&)&wrgvOUjveKE zrXhV?w&|YOKeeO>J90kDP=4!jC=k|mSw*x1IiImeKaZE(fxH>@>9g?N{QA*+a7pi> z5V>*{X)Zs&u0M%L*Ehc$<^usSIb_ft?r&=LmF|DzU{nl_E*8|{f^zTRU- zE3YrB(fY}gmY3mqCnH)fN_qb3W;PSPw>n5ZyDZ|@hx+e}bk#vSL&~3ws7dmpQ_WMM z{-@LAbX78o$NL{vRp`QG_r8++m7w*@J^Sv0=DDAUK|k&UAxg1B{SId6XfsAacmAL?Z&9=zb`9p4{!F0 z@5iy^{NeocZhCjn5%;e-(wY0K1nnQX#`YYPpVgD(pE8tx-up99e7|xwxi3?mf41qa z0O9O1@@)|33+JE0xJz*GiXr`;%=yCm%cq_9gT6mkkVUB#?E7Q?^7)?oaQ$o}+AqdO z&iRzqkDI~+V4m$NVl$6+s__JaJAVnlKFlqJHI31 zD?DFK+#k+`+^xs|zS!RZAq8fgIY|z-;`+89`8(ZYx^SXLUvjA>fBrCEjWUhlwAv7& z8L2$~ObX72xj8>bRu0b}@%-Ze?MARKBS@t``g3S43=Zf@f9p?Y-w)S+HY1zCxcD(D z`*T;E3m~&dhmM)}gVk?%|IokU{#Cm>O_T72^H1~BT_J8(3bDIYQ+I!*{qHqh2142Q zY~tFG-(Rd>Wtm=3)H#Q|N>|QLzg^<`SG#qj<@=B9_{ULxXnA7<9Jky^R$O?>J~u(n z|G^){ki4w{UD=oW`}p}E7ZwRqhwmWapE*C+KWW&s7)taTP}dNyFWBEdBoBd>ZtKa% zA4mB8NAp?pif_TfF&6aIzH4%xpGf`5+TG&(a?5qZ)oe41$9!zN6%FAFc99?D>)7Xu z(eqzDDG~ZCK1SMo=g)T@dcOOasKI7&|4&u(jU%H{ATjn7i5j8&`CgT!14D}XO6o8C zd_QnChNBg#^&vbsSD@1>=$I^TrTN*{WJ_@G7_73s(%kkJwEK6ZnK9g-!O!=e?#*D( zk+H-#nDd4Gf48B3;JtqrYF28;?jL@>d$no@5mD1f+Z#L{>qp-0QmEM0h~6<-$oRnX z^Q+XlfR|Yc8K3-v9UtpUsNxP>eb7*)zMQ@|0G4GhBCuXLAE(sIAnB(qjXJo5<#)J$ zR&&!6KCjCm4-P5kXJz>-sOZ#^YPM-0=lUVd?=E-*LD#42i1&g@cKvvN8q25=u&iVw zY3$GYYk0n6OWFhY=WRuEnrE})W4^YzL_wzRPV#osJ$8KjeuYnp5^z{*Ne7m5eUTBV z|Dkg`7`lC1PY#A1W$~eiFWT=G^!#K&f2(o-1M5#&+D*ubw4hzLePq{%_2uvIiLi3% zF5&yO3R965`LbhYaMSU5JY( z&);$WR+W|vHUm$Qt{R*_oWC9YqzyeAyGr^8n7^|w^MRV2BhSx#IR=CGcWdBf9le2G=jNe@61m&XAFi zLf&6i&gbxxHPGv(vy@Mn)PEcrHUNs6EhfF}xPOBCck?$FLbbw#J{!*a3;6x8@%CN- zXP1*C%kS*_m7)H^8ixxIaMOsc+RpPsy#BJLC=hyUt|PveKCpPq=ap80&^3K6aed44 zw^*cqDZB2%whrP;g70L?|Kp#a{I8+cM380eCM%*Ivg70YZ7Xt z;AFgk(3YIfGE`p$YW#)Xue(wk{a@_-*#F3DI{|!7?jj{~`1+~EC_hZSc^&H2v!E;2 za(@!=KT+&^Dx)ey!#4OW>Srfz5oL*?UC&PU!;{DGB=y3xi?%K4jY+ZGP~O_2DHc>kJ7 z$2-I7>2t}P4nNuRgY{4USP6JQW0iarOmTyKp^Hhe5$DSm&HwLsc>y-`Hm1{?B{TiQ z>znsviv8W!tI4aeJpWEZd@Vc*(8Sr0etW|E{J!GfP;<11K*{u!eL{BFP9{l;tCE61Irme?q zuvuhD6}{4#ei5W!j?f8;-lq`xYUTPhF`@__4sRso3;7qL=tDLV;asDuS)EZK{onJrZE4sJ^_>|_C)4L9bX~DmI#=_2e`^gZ!tL*$Z|2!b-%d|ubdZ^Xa zx_D`QccW7r3>+^H2-skzdy^eqU(d~K8bzbMXpT~1u*L9TXBi$cL=~5O3 z{?g!nzkVawQ~xw`y&Dec83Xw#OyB7K12>AY@S&`~x@0WlljiqlE4X0p#!GPMn0!7D z2mj$WoF4*Bm+U~O@>u>c3 zF5%7X3S65n_QLgP{==wN3pMUb^ZVv^G!99the;gcm+nux#-j`NHg%ND-&cOl#o$ib z-1_#6U%Ef(z4QHWQIVKmB>Z}q-NG0Z4eosJ0J;2*@fe2Pbpk=rTfRQN89xzi$Ls== zy^K$FqJM8PZs4LNaAem~i5E;@WV1PMLa`*S1uH_H?;;cyGC#!Y_xTV?T5+-GnS zG_x3=bp4xyWjx-vuf+Yge;cj8P1#|E*!m3E8nXN)jSoLhcS6-o(eP)neExc#kHcM4 zl(=!>`x@rIIQ|>|$`iRc@sPRqzA!(^N&L6pEE~a4le72D7VN1$T77ZBfMJ&bTg40Z zbpNR7-QVEzGXuCCOOzY@Lveq~M!QvLoOT5Uzm>0##v|O&Pdyf{_Ga-DJwKu>`8Pjd z;aE}rh3a3E>8r6>%Or?CvPKvmZAPlZ}a52Xk306ymVN8 z$CB{5?)V}soO1%y%4>z+kMh^3cN`wQr^M-w8fN%UA1Qxdep%ymqbP{ael6IWkod0x zQ*qZIHST%1uVAl0{Lcr)F1XSp2I^y<3idQVlixTN1HLxq`n}mJ*i(J{{n-=s_a?xp zeYt}D3?p%UO>tcot~;v9o!%~=Pu(@E@Y&y3Xuc=0;r`6aVt^(7~Q{gf}slzu8x6Gf8@u1-CTe1pZ&**>fe;# z*Fhe*pVz)+qV35x+>v8%gz*8{fALS;N>slQ3x9^P`bIh7^ONamY~1lH%(r{m@OuyEs7VSIjuqSvbsdd&sPH^svKPb@z|^EZJyKlv89VmfEixbdcfHHTl`ICsFXh*+M+~ZRN}SDL zmxlX`_ZKQ}>4M+uufW3UXTtrJN&Wqj-xZuWxd|7P!~A2)Z$Pp;>cUmn9L)50Akkl| z@Z0#ROp813#^O_29|<{KhJ`D7b1&^!eZ!CNTbu5JPBOl%PRRFv+Zdh3*XO^1lG(F{ z=M(dL@n;#|2m8R@J=MbVQGQRBx#8y~S3zUtPT}v=f3CRkgCA5sR&!&a`X$ZMU!u*2b8N{9~G5 zTC4d3kFOcaJ@IGbqxH+vD?6go2Pf(J$e;xL{#KbgTrZzr+sNLS^;DW)|1mQEH%81S z&Cli@m`}EzNZ$4rGexB=@+d(jyP$8bIu=y4nfSm9K`))7y2q> zOpD{V<1+>c^Mm%k=%&uc^?@f~R4U_-);GHKy^PP6DRJR@h6whSL_h0vEiv5b98~_5 z&!1U93>w=u;Ra>63ieb#J*T>3W&1>!SXCvw|0I$h>el@tIu$hH+Gp-=7{53^-E(^t zreD1Z{AtFYGU2ao@hyB_rNwz^HSkCFhwyN8#@SJ^(5DB>55K*!_1;?uR1t zf2qFOu5d&fJ=i{LzS0 zDmZKU97+GTCRhXWa?K_6v)AY=xaV3^PHp9IVf@s;b${IfO+r^lu8+un6_2yFsc^f_ zvHolz>mzhO^}?w6>qPolPVz&MYBzA*blLi}GWq$TlC&Xswfkn+7{T;YhxotCH{8Z) z7sdSpz=`XVx_W?SU3ZK62g(V*XWnICpj#VmV+XeWmgbMHzL533w>$>wm*w+&{#gM& zHt)e{R<#!9KV5(8`ppze-%9JJ{m)ByK&1&+(TnLP<=4H9HIAu})gQmT6W)&{iC-1R zU&i`zO}MS9^7%b+-5t;DP6GS6uLOI#zgX7lXuQ#_F*oNi<2Qoz7Zlz0#sMc}{VxTN z1^b?a-=pW3W0K`%_~{)h{GG0E>NLI-^F8`-`w|-TlfMEbVr_;S~;?-2p>9|g~KJ8y? zzgrQv&zdC3pN5hOM#M?;w{XYkjA8XVI1fE`f0{pf`=>Q}xmk$nFEoGjFf0z;9aXpw zks}+PUwnSeeEklX(%4y&&r8Q*v3HE@e5t6=a^VvAj5H}_47WEHMeLZ;WI)+qh zax(`qeWmqHtGrq0ZG22pU+>IN$hfd{0%xE!*pTV7*uU*^WFdyvp9W`zZ^G|O)#2L-sHR*NLyMzQ=b zjZgJ{T*jKHrrg1G`vrR>d=BmJgR^_4Lt*y&=Xs^!`NjDqC&vP;Y}1n~$x)D-|Fs%qk27D#K(rC#H;crtc@LiOpE~!0lri%8 zjoB#6e>=v5*YX|0{b_s(55MqQi^stx7xw+9`gv=u7y6f`$yTqe7wqZ!M7^epIB@eM z$^L?aLxOR`+WRordbwanqx*z1~?eex2De7T5h&=H}$c=es_xCmOq~hhOX2_-Oo^ z=vsku>U6m%mBVuRt`FD4DP@}>rXAy(u8(@vI}`n>{*wCYg1_T&@h36gG=6O}a2B>W zCatg8U(-+4@*hZc~(ee$DQ<;QUWlq5JAe;r-F|`_@N1@swT~3`=7A`GeGF zoDPNIgN;w&@4)}!S8;u`o&9p0ZFB|d)8mBe)Abi4A7!WYg?eW`9 zvA)v&pPc&L*jD!iOqzbz@Za|_oD;{Vj+cu0`iQ-KO>mfsZYDZiUP zw@3RQVtymY{x!iW@fhQy#$C9|`pc>RyuYvq))%gq%pY5|Yo3v(wupQCo@e@QDAs2$ z1wC|J7y_z3j9(=Cb6nblZP4iDdWfxGpM-$Ft zn*8{8pY1Yi;eP?%>AV%*53T=9s))v?ADVDOYUSsj{syl^vmMEh%Q63%_8*O^yNjx5BhG0R=r{YCdCWm zr~Q9Abp=?xxi^=@vG|wfr?$?w!&hgoz^BDbpK1S6c3mhI29&|X*jvK*O$h(}?MwLa zOZ&sj#x=tIDgRx^IABW81WEnY8u*!?f5|{H{@onxjkVJew%Yp%*QfsX=b3-`zda|z zr)_NhQT~l}n_+Z?v_8*nb`VddRzugwdBXK+|HO=b>NxGCrDXjls^t|_?WD^2ZDsy9 z%`dxXw#Q^}5!HVv-*<1v%Jzp<;}+^MzG?k7xML4|90YC78gZNnuU zV)^BA!gr%iGf-i~aY?>k_ql*a{hM(6Bjxj5d)5@smPf*?_YL(6(qCxREgJPFH06|6 z4i)An)o9-P=I5)_u&e?8J{#irPbRO7k#?|_h&Ia^N9a^GdmQY zXFP=|4!4Ep4J_A`ldFZe=&RCNH zYw8%EwEsTGsGc|XmF81-&Q6?GUJhN?u=-3E*?&NDS5vg@HBYkt$?g3Cw6>~-^FQax z<@cz2E6mWel8m2Mor}Z7&&@e2#j%1t)#ugw+Tpt*7m^ThY-h{h( zZiQe^(A*`D2=Y>UnJ!p14#ADzWPYd#azEZaU*x*%!9p2CKieC-Lor zS-bGd-wN3Fhv}yq(a$4pHn?+TEIfNDpU6*#y3nDF~4 zll3ofVh4tfk@@cjnSQzvK0QK<_~Ke={Zu%#9Q&zUg?)$R^Eo@Enm6+p2b$48h5J)J zpZxN~gEkqkDTeVGLGs6@6aMh)KTMYNpT~ymKy8m_;P2rhT%Yo(c()1m8#_<3KHFu@ ze!Ly_0U}<^X&9f_e|~YLB`Qy~66K$1e(QaNEWdF|mCHK9^p)~C<6T=+o#-mbr}dgE zSk=BccVrFIS0wo@lk?qh&bW;terfzWsyrRFW$S;HAIQ%?=gZc2UOyQk%0E;8`E=kI z+%ayCX#Z52U$%`;M?ci!j>NM3G7|l?)0>8lhmVW;D`fQ+caXHza z$NTMU+5Y{fVdaKe;rFNctEg8OaAll~?PVSowG5(Bin!i#Gcfnzysqn^$=_ieUcPtCTvF|Iu^8(}7kMMg+%?5+V#DTvR z^M7f6dFZ8GnDn;_M!t(RWbuQzKk?cjOB^@z3hW=i_@(_%wez>*)}3WwayC=2r~F!d zDd11#^oKr68}b7r|2!S+Ft^`T&{`#*-)*H8eD_xRkYL07XUgx;I1l`OIs+ygWBk(i zcg@#deBJOVlK!vh3)%N)?QkH_253do&Ev%NcsFOY1x`nT8WQNdE;{-*)Tz z2rL@43u^Dx3C~CUFzLi)@My&HGkS#IV~x&X^7N)$pAu(bep7vp2y&FI zuT6%jyBWV!pW}WVK_}ljX#0E%vnS`DeXCu8)7GVea_s}*_o4k!P6I+Q;p1~?(t5vO zPxU!*uQi@hjfWnkjBn~c2OPIVt97xE_JQ$B^UJ;$x8ch=F~5F9f4?^`8rrallA}gujd3Wc%ak zpM}+ZSbmA>r~2Fr81hq@TaYnan7f1AdX+s zzQJDHzvw7i->S6QPqaTJ)z8d#G5FKAB{!?>8oBy;F1A13w3eNZ+t7bO`M&dbI7V*W z1=Bp_^XoY*5#PDD;a+_66Zob3-;GF|jK|WY^)p5x66fY9akpkM|JQ`@yWy+}F8Fv> zlpm)2x_F4^7M z9RK1e?B|((96|Wb$;;>S#}0yK9-oBqQ+@sT#2Sa?B*NaB9qjL9|A&z`%J|OF!=NuG zpYIk{EAh{#4A|3!@lE@qs&@b2HSMNK#MCgJ|WjWk643k5qGW7L58 zlJ(so)0?Bld>c`InDVQ<`T|D0SLNPCju5U7WPOiiS4}*pc6V)NJfYGviz_ii%)^Xrvpz;!spcy zlKI^mo{{L^qA7P+e$~HcNJ>|0~-yY}Xr@~PkR=)`+{fj*fLQv^ODeSr8 z&g_YQtGU!3quo$EWfIE!O2*M{^x4^#B62Mp|K^T7$(cixvw&MKk zXJGXpTDZSD;d5_4JFGsR4AWdr3-**x{YG1GL8GT&euU{SjbEFsdd%|^20?mD`F!5o zZi6!pB!fq*ox=5L{q~qz89#LDa7q7HL&*($UB4mP-+}7yDx>fGzVlNhtAn&;m`EllIKSzq))_U zlTS$YH%2x)gQK0Aag&>U5csC~r&KEwZ1?pXBtK+))A+U9k4?DtR6d|Cyff^TC=xO-x`#||V+SmadW&4Zlbbc+of9gN0uCT|tYiW@8 zh{dPPiM~F!TaR4yeSpa!!u9hAzm|ysBcD_U)`-PxV!8lq`Sj zp9EX9PYL6r{TFl9wb?#=X(>TAlUul%-;Q(=G$t3S~C>toYkytBU) zwjN(4j4z7#&vpG9VIaN+SL49IJu* zDy8-HmV0MhKFMDczf%AAlWt#p*mf(N3t@cG{BB)w+8O+7=|iy_CUYR z?DwJi+Fvymx9MtdZ%sA`{3sB8U7R!ln*^PZ)YsX~PGi8urd-r)rmt?q|E+5=8^zOYVLUf*Xkz<^ApJW*pxf= zm~V0o-kQD<-XHaUi;@mtXscRNZA^z{~%gfQsAsyD}vivahe>Lu{K|Adncv&AT z+@I!$!$U3b{fuf=W!{t_m|HftXD+es`--j8;zFxvG3FG(A&sNcs|PCATw2L7i=r( z|Nb6%4u4-)D?ss?Sh9brwXU-h!4~!dM?c zU;T(aYDf0LvEExH^|4)EEN;Cly*{@2x1m^he-9Y!VEoehDr`x_5&PS5ZfBT(O#6?& zMswKu+i}QCW#11SvOe}s>Iq!3w+ZLpgvGCv-$@3uv8LYz_?gDyXUgyD#{Ov1DIdI+ zstNPckMKKHcD_lxd2ShWQf2-z?LY4O%T2bv?>1cBR4U9LTHmQkT8-7tVtzx2zP>qOfhzGyqV?^R z-%|Y`R8=d55Y={d$!se?<9f-RLrE2e#&lZ2ky*(fvPX zKJSQ|kN8XGkNO2)zzxS*a^;g5pLBnwlIy+kT+~*{{P4(AmvEeZYmvUv{)fb>A=vTV z9?Aa0=!z8VY1ffklo%{mU(-i(_~cv!oUvj4zXIWN(Gowb^vH(^MahCa%?}?`osCy| zN5l0LR)2RR{SzA%{ZTKZ00ybb*Vnyji%@%YJVb3_@fYPYZ%+tr?OFk9_vPy={IbI< zqj`9FR=&QvUI<3Z&(C1GFY}M7zIK1(jFG=@!p)LmVSdu{Ez@FU>$|_?fN_V-hX4HQ zFv4f{cni!wo($D}lLUL3UkaGE8}lc9h5?}|f<5hTs<5-ctTyQoJn4*JPyOHbjRG-g z^AnielId?0$uGISd&ryb)Pup*^8H_jG&?*s8{xhFo`&nIi}5OZ3Dn=@;h6(%IQ2m{ILLL2kxQq0c#;*lE z?xXh3fn5JOE#dxjf40N{9dTEszvz52s?TTt_QKjPV*T|a_0_JbF&Mp6tiP0R{VF}w z(A+EOKfCxR;_)NeT%(VyznJEymOtW9A5MafoBaCE<9I)e_AP`XlTz9Df%wmpCz)Wd z*(KPrhJ7Dsek$URA8!9r2vv!UZ>qlvZx&)+T0DgN$mcuKaWj62e*q5d7~eF0y(Y`= zls)F5;wR&q=BH+UUXB&>G9bt$UwA*Xf7s`OH~Ou+56AW8^Q#zTj_a&b;Nw2VFU>z) zT(cYJjQI-Z5>pNT@vlJgPxJgNFsxlFWQ=3}Gp+yRw)V$`ZHpi~CS9=4BK&eKAMT2>JaJmg>FGw*NLs{Z93|gp1os^Ig724_7|h3$y<)|N8&y zkNT8|owYi0r@yfCS!jIRvk_CGu zBXRtkz5W63jYHtZRTe)hfSCW#;j;blw0LNFeV1^3n!nOoUdW%kF#Ax5% zTR(L2eJ%`%-YnRg5dLTFe9K>KG8xRGz6yV*{4X3^&tJW|P_n+eI=va1ELsl7JF)pg z{p%d9ix^z0!5Js9{wG?$EnL?M)i-*;^b2hMQ~e!u@gn|^>7(rYJ-Pn3ZG<)!EE4mJ zr2kmCC>lFQX>f`)tpAw$-(3Hm_+{EQQGSc+^XRmTnC2+v*N?2|0v4mukNz-4PRybO$qY-Yn$~2ymr5lFldu}KAU~Wo@_*2R8`c2io7*ET#u8zP$}f{<7z%{Ta&^ z3`WhAeK7J6`#a^grR8~?v%WQF9pEdMU!zy!Fk$uy(f-CXzqPFETAa430G2v2ev$Mi zJKmgyFT!GAj}`OJ)d|1F!#3a{jbf31twZ>IHGLtv7bn8#rA$94ze>eHXcS%vF$qk6 z)yesV_0=}m==62a8_e>rG(X+7`(Er?{~NNqZxQ$iBm5?oSfFuVUew=+Wc{8`XLD>G zEn9#8OuoLRuW`Yz*>@nq^^kCVB>P95+PDlS_DTo0!7P78{cGo5YtS&`F=XX1eceR# zwQJv8zJ=~kc;&%Ek!nzm#@uw)_FRGCruGTMw zD|)QHR8I7DSN1dh$6A1}8|?S>Bj=~-cG!$Z99~2EhPA@{FDLv)RsG`Eo->m?|2NNL z3x;{T2b*p)1baWiub*a9^g6R#vj1`S*g{!<#AvR?-j&SWP`rOepRyJ>Q`J+HAEWxr z^|^qqBie9E9qSwT6Zcmce{F|3akBl#8}?tN@$p^f^Vnj)2IpC`R*z%d@B&X?F!c6w$)<3>H4CN zJr-d0;3N^>CZvCI%ZW|6EwLQ_{^bOIs6JQix57;2>##~mzCPbi3q`eUU*T*?pkS{+ z_;$H%f!%x&8aH|*%n#~cS0#I($;k&`ZW1Echm-u+?4!$M=Z9W{Brm4VbbW5tJXwBt z;$0{YVEmU8{)4;8)+Z0U2D&+n|18pfHC=5L;=Ei~nHn$LKZfXcXPaC;*?JfZz0Ukw z%D?GQ3tZbu#{V|?{0Gj@=XY-&1%Eev6rP{@*Om7IaZGyE|Mn*k{vJ;FKal#AzZC^= z@3egW4Mql|hTd!Nf9WgO>k$6U3x4vQen|7*^~zRUUi}el3um$M8H(d;8@>sqS=vkX zcii2u8>hMc0sV{~f<5i;aFF$9stop&%#U^PIgd56{>3qU82_}tLvdp}^ivIxtS>)1 zB0ImpeK_~4i0z-FKIkq5YRHce|9qVNYV2HA0J8=$eW&?x(~=pu zWylq1?2e-G-d4-5CF{GX~^ijJ*$h?>jt?@Z`>jPXnRyKeeF<~{n1hM5(Nf7%}c z6J_;BFBuC-$O=TN>))w^Nm`P)VLGpg?`R}93s(fgrifBF3G zX|WeI|0-|`>z4}r()@StiKEbXM+A5cki)L zdtY=NSR(SzseVu1JP(J>OoB7XpN02F{qspi8_~f2DVSLs3iDTw_~##1+hU0NZLpuu z`cG(n?78nIEH$tAUw&4wr~GPfx4`<$>!SVXA_%`FSuS{FP%f;UBENs+qOt|9n|B>- zHe3_NPxZTWk{fPZ^Z=5N9~18HNAz2Nt~vV0XTUU*D8ZiQ$7U8fqT;o?@I(2EU|&S| zJ*9M?e|Ua443B2{ajM_yD$6lCB^!Di4i~OZ^W&$wKjw9m$H3cD?DwPmW<_no*xD~} zZqu;_dvSd_{Cp|DFhH8$@;@Q?c|r}SS+e+<`tNNlWc}BlKJ< z*k6+R&v%=6;~l;b(yLX4`9s(LaK!>+`rm|ON(I9Fq494U4OiTCD^FBEjv@MZs>U2|_}_r#X1rkU zM)FrhspjZ2?*;^ToNJh$twix>-%l$r{`GyR-54i4zXFMWjn3cWE$4BG`ivvO^=W@cs{JGWB#wc(J=yb9|5s`07JPiE7Se7od#ZmL9#8nkPo(*I*ViA1 z53K~(*y+rvd+8>gBCmT-~4du%6<=2YmsysxQ&}*2tr~aekm8SJGWR zztuLwF?q3U{r&py!tX=l-=Jfj_@Z4Aq)cS|0*QY$bEl&Bq*xKZG{4n8+6$XBErw?P zYKH&(S3TnY7AnujjziL5XR{x|{dEYxm#415iz7=xwQQVVuS579G~5Q=6U6)$5&t(T z!VkT;3W%7&`a>c}{QKg(B|i1JCG(Gqg!@yzm&{#(lb?(Alg7Ww{jE^%^(}ClcU`cz zBz#}=w8dR{+0b}-xG?@GQeRF{v&4z-GNF;(1;L)4-_=ZaIeIR*3)9-h2=+98-FWm} zzJ1(qI8o8?{R7eGLm^IW9zHso3JGg>2-lAx`LEURkni$&42)8e&%ed~5T%HJ@2n;Cn4lHdAO-Uuhk z&e!wLV){huPyT0*WoT=(Fgo5wU+Dip;{Qg^P{puMUXuRr3f0@#_m>`5v#}k!zo9t4 zbz!|GMkoiu7OnsMZ}Iwt#PeP7tL6?-|0U(u)lcTXsws*1RUq}Htxfx*zwQA^{mp%} z3+JC#6veMpe_xvpM<25YC^`8<7{4BgUw`~?M^3E>#@Dd?l^@~vI8MR4ezNtgM_Bwy z`Tbexj=pt;;CV#8{`NC7#Z|d!Q0u|&PuDM8z3+{Bo=+g;%~->K`~%_Fsfjh7{gDMb zRq`dD)?(AI&!E7v^O71%0OZ=^qa|<8WDa>A&^;l<$Zod$46iV-eppKix9CFD6y)hqI@ce^2#! zfYUB~)TR&H~ zRXF5*A$TlheADJ9!C(dSM6>#@?h5-QFz{f{F09M=5-zus{i^z2nD+@Hp`1zy3ZGN~38 z-#py#eB$^vE2xN{-P#yVj+d|Bg`d`;*YgS}c<3S6n-Kke­ z2H^ah4>0i0G&Vlczv&XAh!Zb5O6I3atajqnfr{L+X}tt{nxAgoUImMkeBg8#I# zGG*r%_sP)b-e`AZ_6lPCew3vlJO3(Bvc7yv>pV^xt1a@+6%@q#$4(mF83QABi0aFf zfB(8LtUKID#6Q*dieG*3@`3}B{<&f6VOTl$1YEFSd{g~i_HiZF_bq~M-b}wK-)YY# z;phHwpnHSqH|0BH)GE9-rx*sPGXL9+_}>pV&&5R-(qZC#rr$JwbygOCKRYekA9bjK z;Xl4<{polgE7UEz15-b+`APYnq`ndxTNZ-js^x-x2=Tv5Q|vL~W*)4Y{z70l!eD-!VkLuidalpXvAh z=U)rw}Khn>!dKum!049 zznJOY{HFXqGVg=_SqGqQ0gFGVezypW!-4m@bE`UU74#QLeaUv=Pz*>t0f&#t=UXeq z6}M~<^G)kZ8nF}c#*{e8`f`ei8=8D9h8H6l-&DUJB+f;Z_BL&{AvMm6`(zwv6v0!Z$xZ06Xhf z%X->!8pbcquT45=i^FE;La9TnaDU48huSPYK71rBHDKRI%D3X)HF&FOCD=YXFI-=b z@NMFn%ijw$fHRrw`$+lTbIK1BTD^nMCmG-6AlC17{)N0x)dVQKTrFIm#@|1W)$rE~ zmq_N%I-C#2B^uu#Zs{DsUV+5dj(Q3>!N5t0ov^TM4uh!wZ{9mr1?&}lZC%MMskJb^6N{7ygOo*N~k2?>$dGg z=q>ioDc>E&_r{JD2PFGP-WkSVe6w!cL@U zrl>-=HH`6{MDpW4{e01MXC({_E^GMx#C#|1vd4qFA3^cPW5WHL8;SSlnyKi3+kQNP zc^$6`f2aM|^FPb@ts4cJ7uoMa`R%*b2gB}HK#)1(7bw5y@AFpU#zV_V^7Xmdu^{yL z^A+xz9~H*0L-g6VTOn`MY!dv8{3!gL@_Sv|4?XkW!9dNm!rzrid~KXl&ChzU1P;z% z{x9{vhq?u$x!-pv897(5r}g7q0@1J)#YK(2w<0bv`(RuC|vFRBMnby*feLp(<&lwT^?VCLZb1xvouVe3@ z_J=rral=#h#C+5I8cw&srQ34g?nkEIw7#{tg%h@NF9Zt<`TE`Ij1xxJ7sBgr^7Z@s zMrV8yD|`Nl+l2Ag5WZKuT8&RTSAp7P`FszQ^@l=u2|VyUCD_yac<()a_%Z%HtZsBy zm|ryherG1@?>dkJ-{#8q&yTmu=I!;yfaNdd|4{x1+4$h`7FE!*4fD@w{QcJWKEM6v zc-Zw)KK~9IgV0d_J0#aI{%L>M?gIt<=$J{+yc?@eQ~sle2jacFFYvY3CgJ&X2>%ZK zs`(e2mP+b-re0vi?(8qz{8O@X`ZoS=($Mplnq2?GANnk<@9&-;%5bu8Wi;GOKK~{L zP4Ug%)spe|T!*_jX#O~EUVK+!{M3KX$!diqIzf`_ujVPs&R=}fgY#N0|NLOncx@bL zBF%qF?l~!5^`*FS`8}8jZ2o2ueXj|S>F1O}*jHsM*wg%5M_K-P^!Eao zu>FD@*ipIhx&7Pr zSa2XzGQaM!@d~yG>?Pux?(bK(w+Cu%mFD|}>jg9^?aBq-kk5BJH$7C|d>Y=(W%EOw z`0sr$IHSRpQn*@_BKQYD`p1;Fb2xjgZ2#tl`dK-siYC~QP#63hSOz{vnhWz22;Xn! znc#Kf>+sf?`i+b$N1a)f}LX_w`s%gNBABU zxe<@FuYp92ZFoL${p|LV9A5V+K-FeeKc{?Ggn8gHtb{(7cM10DM&kH9_hCM7|6mG) zRf;e)e+08XpU`}wjfig`_3>ZX-Enk9xMY85Pu~#K8l=Fb-B{Sbr+9tG zl@o*Ud+lj>vWv|RdcMTNkFj{7MPIIYOXh!5zK^T{Ja$u>?*V;H@b88jpwz5h`2A>o z>{6Vpete+_`V1dw_|HEpC;VoNUWAs7@4*M9TEU+7uV^VP$L&pv;Qkl+`n)H^3F9V| zf}cO@Kc@LL%PGt8@}wddp1wu6KixlURA)DI-}D?dj3^fFPx)QeZYeH{zYqSEOrL3f z&FRy6G}%}UBO{nTM-hHCax5`T=Ml6sif?#+@%rcz{oDK+w{c*T%ia&w=l$txv17Mt zSlj4|Fh06|%lGA7eo#5U{yy^gt&DZXBQKx9Tk}xCp03|o8~m8hQJxBSa^>?|rM(*O zTz(5>3s(#Fw7=z2m$$sO_cF=-O%8hP!(z)8+~0Ut!JfwFO}y&(-ao|p?FZuh{jQuj znDKsLYa@-1jBjXa!eat0%ZePd`|gZ;bn;PJ0^(w*QkDb2F%8u({Dof zIr)4Se{evYUkaNVjWPVkcNF2C0>!;hQJ!Ig&oUaHT@iN5%(t{V2n9}vdpO!T=!Nbl&+eGOYAjGy+uOxe{OoBS5X-+pBO1h)z2 zPe_wpM{@cilr;58vuu&4c}lh5DeKc|iZ?G^I*R=(|vtU}vyUBT1?5J7=-h-L{P4zp><`F-(Y#JzVEWbhd-m=~U?_PKVZ#R1L z|K5)+$*+CPdBqoanoIVlCU07YrSodxa?NzXp2pvo%f9j2Z=5C9cbvQto)L0L!|2Rs z#7_fPxagHml`f!5G>iBI_lS1RMPLpg*0b; z)B3p82`xMkF3orIh#IVTw_K9%%F3>&>wXZbUjAa^Bm1LV{Jsf?TKs~U`{v5k?><2T zv3*#iDE_AUebUPoTN^$R^}kU4p1*1=j(iaZ9s~Xe_ow}6i}3zavA)yz+tJP%drv5axFJm6 zY5Z-OZinG(N}=S~J7N5kZ)ZbmjOkhog(sN*u0Zl@FM8SGh}TcR;n73E-jC?JZTrRe zaK-~T-u|#K{&Et3k9zEmvsK=Jjq)wQK8E=3ds5A?O?@u(N0wiYA^k5(c{liO!wul; zMfv=1d*zAiPrZk0+LwjvQ~nh^vU#U7MzCp0!}pQwZ`5L#D^~Y?DT=>;koubQuZR5V z(&=E{{=fWOBhmZ2SL=(xzO@jtVxw^X=7j&OMK5{ZJ?4`6^^Pak;86Wf&^3OVU{BYd zyo&tFyDV`L#pl$2pSkfs#vE&zzB@4fslH!LQN*Kh()=4L-@uL@!|XXOAw%%rslGqU)I=BDDT>c&f7_oGWtd+(U(CNkJJIiZb68i@ ze|%6fK5u{I42JyH;dC#s{2Q&G$FCiLDzTC9wJ)1Ll>c$b@tAU4m%A9RVfc?<1(JVT z*=a1M-HnF?EvCYN7jxN(Ty1z(E|IQEtb`g4{$zd2 zHrTjTm}LKp`uNlMvQoT0l*Zqaw{*r%^A1VwkK+C^5KHtLad~(XIdYxKlg$!zGWd9pU>;$f!iC`fOd|2ehq9t@fven zCG|P^dp$oTX|3e?(B88B$K4G!L#rwO>8E)8XU&dRSbWHqbF#W7m)~3MHE_weFvy2WK9FwRwy`+J8RLG#*DQ59LCQ_X_+`es5msi&5Lo zNXFMQ$6UaVYW=vjHf(<)8ebdc499aDV@2n4P<~g+)<>1ZK7~V(EPqD*YuGat-znaP z%cYE8Kf>?v-sU)T?i0{oFQ4CX(*;<2@DaGl_SyLN`%r#Q9k4{h)G~lz2Z5g-gx{!b zR@g84sbv1F>DXm>(6K}mUnA*XYkb`a*W7#s=U$Ww_owl7N+&a{Uy=_`1{@XcPuG`l z#w)Se$oFt*JJVki!tb=21!y(wF-$U!6YRqYzoXAw5L`({jL>$uC9uwZ24uw=R;MAJSKml> zIml~08rJ=i4SZ6@Ub(Z{5RF#>uFoCW3@8pol@Drzu12s)_pjB zY7+;YhO+kuM1N0Kn&YVbWzaN3RhWO4#DDJneKPjAdkZ>_Vf+H&cc;%%%pUjzayl}8 zssDU2&lIh9Jrc#oQKbK@@%@!JW_dN-JF`Z(zXIX+*-tBce6}3k%&!*a2i0G%&5QAX zp)9`^&-9n(zZ(@f;CbIykTrwx8$%hN@u8D0ctrpJZ*Q~jOv$`uR!KESudS;GD4 z`5oQAnd0%QkHGFA(_gy&(=9ul-(7D2*0Oy*+4uc_-+K1%V^c>QIOPolE@S*!5`L4^ zviM}R2sj*p+Sz^nI?>1 zKf>=YpWpoR^mUT`D-ZgVV5RM1?pd!9!uV-^%yvaHoV9DSD1N4V4=yf2&$dfA+fNB{ z`ToYMJ6Di-SIk0p3%g#@z zfOdOpg!f1J9{6%09_?Nv+8?}}=<}?TD{xZfJMbD@F4%_?zJ1~r;**bsqW#Ngefz41 zGrmc94^teNKIajAR*qVT4wZ#)_GyAJe!4#FY(^S?$zr^ue?3#C&s$!<2h6-EjL(Gd z{W{|o|IBL%M0Px?+f`Rx5tzFUq! zJokj-TDW&J{KvPSp_uP(F+=c$ejIq6WAQW9@9f-VIOpm!;4d-0!-#&Xb()0x@85>w zcbI-t|66N@83y$(fvYL{?EZxBFg;WJqgVi8UD@}A=D${MT8f>PKZWjNnEwqRKHoj& zktG)33&?!>v0?tTVB#nHKWy4UyxYAPbjCCNrt!1WawiOPcn|Z<7~eGiH6&{uriACi z(&!_?_`^wkD-|4Y!1%YYTZOG3rTuA#FD*fzurjc-NNKPa_ovO>oXS7jF+*J5Ky3RYU$M5~)l@gUCt3*ontdE`1Iml{LDxxA}WzUSP zWF;~ql9g52sdTQ4&@e;Nk|>f@NW|~`eYj8V>-Tt{&p)3(Jg)Bhec$JKzpi;s_j>>M zRF(aHRsE?jIsF~^WfUseKS1%bL*+xZb({ZFn-=+_yRUXP7vm=JL(vM-Man4`E7$? zo4|674y}ms<@}=llkG9B;g;(Oq5u8<`ZYNJh|q5CT%U1$YDaGi2x@qdSOjo>aQu9> zzym7h6cF}-^NaoOxZ^{h{LyVB(H5asK-DD;MbL`kcJ##QDYb>G4^L^ZT~G zC8r#6rS*aRZ?6$fkajYY9K60?x;~!&DmmfcSY65fFWF_n`-Lh(`;(XCEVlsv6b0d`hG7h-O&JG?yiqF(MKUAO2+&CHhnw63~ zea>$j;&;`C2ki1L7ZT2t^ILLiGC1}xCAme)`JG+$f?ag*7V;Z6s#vi<_)KbjhwpEL z>r*+M-?4$&vxV~^%g+|Wc$-=D%N2hASikdbd}n)aiTOWo_6nvQ^QG51D(8RIb9Jbt zA0(?!WB%``JcG`?J?Mk_mpT7v{_|peUGQ1GUD#hb&}lV1oiEn!doP-T-KPCQ|9nwU zCIrT~Q?JSk68|`V_Bh52;!m6q)~9QYeGWelPN0vU^^w*e*6%;R%^_gKB~m|~uOB@W ze;cuJ@JatAS=5~8zwvx`#;w8dY~3Bj_d&USe`@IhXGUg|R(4#!asJ!C&1m>EIExgh z)T}=ge@B$NL5p5_GXEU&KlH=|Xj89<{9MQR$Ni`0#*KkS!7oUG+eYd4XCeRG&wL6r zyj4mZ8|1UU-5Dob!**2gyF>32z#_CWnkb zy1qHepEbU7mF-_*CG1a|*~f?FX|$&1`J?ke(o(XS$}(?ZeQJHiYv}xJCN){AobR^wZ`q*v zbA<8r+Dos&FKH(A>|Vn+imzwHe`7a>uN2m&H*^uW@5B1ux|=#I?kDDZ zyG1<+T(@25e?PNt3I?CW`V1zIplyg7b<8}kl+Uu3NiK5Lgy^9`QGP1j54@5qny>9v-xHjRAP@j!%kAi*uo)d$f zJtX_R$iMy&JqltJ{_ngie0|{laA@rcOBMNTkv_)`oB&M}^UKple3stNC)6Jv8RiD} z`{xsr<(sAJ&p~{~4Dy9A&yS>E&qB!__m7mEvxDH@k7fHG;`~^u;S8v<{X)ikOO@<# zeaiVv99x`YCG7wH(9IXt^!-fwe~6LnvHz^z?m7#*G(wpFs!+_Yn{_Og^?wt@->l;q zZ089VlG27hUmPDdzdaT9r+*@5YRjbS8=(HMg@c|mn=9VJ_;}>Fhv2o^otC!0$nPJW z&yiMC%;uHO5ysEPtVof+o<;j@;(V$gJ}t^B*rkOlh5q-zc}1{!%q$wUK{=leLABuH z@gU;l&Ha0^*Nt?7g4E|EeX?@C z+wXRQprq%-PpjtnBmK3jbb)cUc_cZV``?bp|MvPc9-fB2Ay)#wNb3vx-+N}bg5kY< zvOj|J9f0^w>8RL0w8v)>u;-OzkL%9|{}t}vfgM9BBv;K{Je@e^60&iTgquecY$++L3m=D#jFOoC(I%1E}=PU-r%|J(OW zI!hTmMyRiQlIB9Rel_tjUn|*1p!j&8V-_RxCkp2;JN8I}H&>nM#BzTBxIQ&+@Eev< zZ?3Sue5F~BH3)O%e~6ktOF~B^{LHfMKC?nj~4k`OZHfQ=Wkbo2Qfjy z`qhiWD`D7h4fQq*G~co7=T(S5KZt7mHnEcUR*~n&CimzH11DT2=2SV~ z>(e*FA*x3qhx3j1KRncuz-*JdWaV+?eD8@I4NJG?5@*s|y1oh0@8s2vU^Fb7JhJ6{ zWBs0AJ_efCen~poPLu4t5Z_6EJmA~dVzT!S=Q{-HcdebHq1Vb>qEpTNYdnA5%gh(* zsh5+RKZ>OFf$P%=t)1ZN=WNnv!6E7TI6s!z$`_8;DwpXuK7VKQYfrG5^p2D#-;nHa z{(DdHWw!GcAy)eQ_v8BX#~+hHW#Sjvd>8Hy`@WyCPG3d{>(i<}6JcwZV!mq;=O3Rx zaAZ&#V|~X6^?l5*nb7mr5Ax7)we);&{(G+GGuHU$D| z#QbJ@HiFMy2ZZtQ6g9>EAb}NRNkg9B#_{pbIwsKSbd<2aB>db{h!{GNKFm|D&%2v; z0X@IVB%)@1AJF~@f6{`WkHY_6xQX+N^JCuXR^U78uB<-{>+_>1XSilsK-}B)mDVpl ze_l;-KK7k0Vt!j~8w-K%Z;1X;?qBakd>S`%1{cNoTMme=1X)Yto&bwOo;n7^ee4e zel{}Q0IIv{(*>I>r1gdM({S$q=(*r7=|4fBpZ<=}B`}vviSNbNCpurc`#O8DoBe{M ze&PCo^V4Hp$3u3vQZk{_e91lv>E~TtcQ_aMhJ4$}`Na9Di&LCHB_L0>e+lOELg&eF zY)v_N{Xn^X#^1MtO)=RdEAyaqee55T+tZ+QN+ntP`X2l1pO_4i`^O!}Il;C0dBkD( zRmnaM<)F?w7uU14~W8Kwlg!!qxPsc-@*=6MN zD9$IIpL)FPF3UUWN=l7toG1kutmrUk0c#=>*{rxSHkA1yH zw=8ci^%tn1{_1?wLbh9Tp3r~(6J(LxTs?`}9q0Sg;Qo*?Iv-g;_9|g~eDO*S{OC86 z7Hr}5W$ZuS?5hIv2Z;H$i&+Zu4r)+l#`QM>`OiJ|>cW@vJB0b^*>N-A@nw=EtZ`%`(VR+C)I%k`5{&h7wflj?E@iCsSNHceXJ(G&bvwGZrEeAlr?9S-mrgnIZ2$w^V3+L5422Vi`8s|@pFSeyn`KbeN=8Ez^G-KifQM z082c>h3Egw%WVz@!%hnGUuUa2z|UD%g!wJMUZViA3dy1zZL7cfg#Bk<(hv4ENEPO< zb7t5<%d@%Uw;Sgd?;pG@$QIa@98#fpj(`6?=GXnP9b`1mBbw@b{y7Bc_t#VIU|aN# z{2s^m@4^1{@skeVXiz}PpK*S1eoOWHB>1HAjg+qA`w!#uXX`H+3F}s56GOuJ#rn-Q z%>vg>Ds=Tb&TlO8uW$M~!Go%or0oUHFZQo%tDk3EW>I1O%i!fiIK2LwZ2tp-`oD~= z5?KF*HnRFMLG|U}oC%=a{tL0m-X%R>y#Igp>lD`0*p0NQ{`dWr_lHdW?FVtsRO!?! z>m_^KpY3{I(O>dI>|c+peFqM@x>K#~=Oufr--{0Cv)|Qn{~OOgkMhZeB->fEk*RWi zuVs|7y3GTG=L0MsnFD`3X44=0l*iAtMpUz@`{n%N{PvS+bAhz4MaOIyBk@~+^!tvY zKXgEwP+|VdWy~Y6+#=s!R0a9(&FeQ%^k;{Y-eLcqzx@2^)k`nI`EJ(q;o!rP|E{7U z@Bf@zW(2;oPRjCM*nfXy+yN|ZTp`K+{O@CZ?yu(v*BTbe_Wvg+f4%)*{wla9~F+DeCHD^_PFF&;2so zz;{O}xp9m0jrTX8CmlgmF@Icaw?(oyLHX-*h7;l2nXjbIN3PE}e|`Mi2&iiJf-K#{ z`Ns9*Yi(vg;Oal*(f7yF`o(<5lsH1!??Uq0F;Tic&Ts8biDfo>sL(&ZGH^1qsP~gJ zoN!6{`?!7;b^WTMztV>6wdL_M=KHXdC&X>5AV*v6k?iZB`jz#pTP&xCo3MZ6*b86K zRQp5PnezO0YZO1PZTNuA%9|vtU)33q1fedDH21?Pe*dU`WniAij*glyjIR?;zhkDW z#QNKH!3${TJcrtu@ccE7uTLHS$z0RK{CZvUgOyj+=-mxme+l9@tEe_aUkxR3$N$AI z^7G?AY3M=YtKq`_&GwJI!P@>iiK$Ya-`b^b1gVe2{`D8zwJ{$9Hm$0ilo$m+|O&+Ktt&~(Fh(mjRu zci{Lr-Qgw+-Q_0i&+M!?zp2SMb!z`*gLHi$^7D6Ghu&wO&iarKz4`YY@9)2=M-n{A za-v5o_%nc4{}PF zU#iG!0}Us{$>LAUPlpC;z|IEGN$+Kx9~^%MHX97> za3BB&_e$4V(SGSSpkQ%b!mk;=OX~+e;@V8X6KhKkm(oZW9sh} z&}@V*-7%W$7v4YXztq>PPJDpue3}BH!9T8w|C|2#$ZpRKB!yM{{T877&f77H{e6tJ z>4NbSCH)Ga^79|N|EL8^b3$eLUCh_Y3H88v(m`SVX6~uOkYUo3x_X2v<*Q9E18BAJ z6nQpzbFim$eYUBPj({szp~ijx6wxvd^eIKcC>1*kvqZixlJ=-aaMTQOhvV{M_W z%WIM{oAU*TuSJ@}z^Pj9Kk6a>(X@0l^zkbrKW1?M5Z7PcnGJz!@PgzH+aRsqO2kit zlV0%r;!jfP&h=*wm7o8Voj(k&f6OPD?Ud`!qFTQ2p;DFVZFnm2_y78X(}qCN@*Gn7 zjq?+N@~^{ooMAs+i~UEn|E7RRwJP0|6)*jL9W)=1+4d5t9?0`6I6j+ePzz@2?iBK~ z;iEsi8>}nqFCr+vvaE>?*z`ImoR2^L9{7TTEp?-`NH^Z)t;GxPL#Ij)IK~%g9U<&L^I) z{q@2M)<$QM7rnT?Wg$L)8Y=d`ds;;@`|iul zXFrkF&nJ{$t?g+IMkRTq@Cx@2@&0n-MxSQ>^#%*~mxSpPq0TE6T2F)P8?KMs>T!`J zb+D7wN3nlc|Li!JXjnyZgZI_&E%y&Cr!%(qy}PhJdZULABp0jF9*OHDdmP_&R!wD9 zRg;OU3;(|3`0o5AKbTRdNe^!vFWH-*^OKKhJY$vV3xxf{(XIR-Ay|{99cv@mhoJps zKSUO?TD4Y_i=V2bf5-f9dsM`B(lx~79OpX%>Emf@Ul`Fxovsb#eB=EieR`{bHj(p< z=WDgjJqNXCi)DP{^O;UA*M{m0v3?dsjs^F3m9qQ{_D?4_X#!jGPYL@UE*Q;&QxEIX zArYK!6U6u8pjMEpbycRXnC~tAOTkfHm(JYO#pOu^e_iP**2QQ0_Ta6WN=(gPoFSmdTki>rBlm7x61 zFY7z3LC$2M|7&*g30v29p)h~CrBeZmJsLpTy!j#BALbJ>3fZ1^YslmOIG=#{EE+Hc z&X}mvUu`&_Dk%TbW1=cJui7cBZ}c1e41!yU`8+yL3qsx;6wc53#h-)1pElIO{utL^ z)W1KYQ)77CJZ8)F!e5IrNPO@%ohmehn z{yjfgc%>40%nNFls8Stu?jK|Qt=w^r>3Z4;^D~yQUeN7>Dt*%SkaU0Mh|g+|L^kKS zJ8_((oX_^vDQt$>6d`|FkvE}e+9bO4U7Ymy@%e~Z-kB^jVxiD~jz5ye3X=lJ$~5JC zy1jkL$dNU~JC(m5%;$@U$>4uio#s|3=kxb56_|5(rz}5;U^~W10 z>O$KdhlKIx!PHoATWm}7R@U%|>W`~>HG;}%Vm><@HG!DBS4ny#fBu-ijL%(Rt#hjU z{4&JXohM^qT+?b2lx8QbZ_L;EFBB^53&_PH<@(q7mIwUj{D-(1uaWF=ebMN;9UT2$ zMowJjeBt^;w>kr1&FvRtdl=^n?;o@FmHcwjvHSfKY-;FWVSUkNq!;*KP@}13oG+Ze zxvzDO8I7?gzIOcmVE>lZ^@J&k_;{=u=L?@N-ZeUb86=Js`nTKTroh8_wdt_DAnEt1 zApJ`{aEr}wm?E5CZ8_{bTu*VJsYy{a_6=npkY*N-*~eCkg!xe;MSVjnEr4{{t(?Cz z;|kdRYjXb;^S8kA84P*0jE3AzP5P_<*nb@v|A*OY>>?h+`1cL_uXn1`;YW#_KOCR7 z@~;E-dWVGl^Je-0n%SPT?EA$UeUsP!Z?ta+WX)-z|N8TN02mKyLOcF0m+bL;`Iv<* z;oh^Wq`xnJ|CrAY)&VeURb%R=%IkvxR`U7P-aER0|HxDlwv^jree}@rgq~HZ)V$?r zY5nS<`r^%11k&9Lg!PN#jy_PVtwG<+;r?d;+8<{0PkVT5shAJCQz@;F2vlDj88#4p zo8^(xLT-=w4Y=R|`Uh0#+DiWY#r*F1M&YP#A#pyz`7I#Evi0{PYbv~Krb+AV;r!zI z#q_X2up^_8jQV|5`u(_n*R13?yJ9j#=)VsA;taNyRm9*j@1Jo*`B$SC(d_GDJ2K*Z zmGt{Dzv0$iaOh?&YOH!#`gcd9j|nZ}8M!c4m_M4>coM8t%#Ux?G! zVn{^|zjFWdfW0x?(1;iMr$2($f@MfEYWT6A761Oo`Ab;a8ID~^C229r`TJPx0q&`) zwDHzal0DYX`@UANqqKn7epRlY0d?)+h0zzX)RTWdaej7G+kVjLouWQJmh0mul>c$~ znp*WXtw_LZ63 zbEz1(C7k~X|D%?Cu;+f6|A_N1R!3^X?DdC)^V$D3 zz5#>GrqZ61`1!X1D83u*&;S;6JR{`iVZsXVb8JGNF6R1$=d;yG3uxpRFVn98lwTcJ z@DRqGT0%Gf+AXbroL`M7>j>HFQpxa^%K2#?G7fs`EBc47Dd%T+)d0w7qS(K>CjU}E zbY%Ll<-I-RcKk|M5B~SDK1KHI4*|dPNT43izvBFgec?EGGf0iv%=jd&A1@TYeHb_p z%zR&xo_BcsHV4%QJCiBUXlfn0tX+PMy_~NgOGSR?QxW-Wogh6Q>|cJJdXycQK15hw zuQk{M@^;jsZx<&>e;>zhbJfo>$BXvD{AuH~>7Yw>=+n=`j2T@v!GTZT^d+2S-L-5UmuWhkLfm8Ec73Hob!VbyL4&wht4(j^7F5) zUp`}L3Vj;zjr$*%Ps?+Ak~>@W9MopFzBIqmW01T);yf#tHLzYsbhh*FBi66($(5}B z-koH4*uUQ|?@v3Fr~!LZ#QNmi={8*XGK;=B!X*8{`OkwEdhlS#8DV~9kNz?U^KMKt zPJC9XU)ko(p>|ljtp5f3j~y*t;YWyyqCe0`T3?tycC`a+z9r_b{rK_V+fSXw{cw@& zBT#;2bhIT5)XXOlHRpGkp!#CVbCbZJRvqg2X`^Icfc(ej`nC{zubhOeZiS;e8dtW#=D3`=XgiF`Q_4|$4li-O_9qKY!x&F~5 z{lTTl+0q|M@KR2rJjK7S`{7)%S(}?rPI9?^D=c{{i#qaq%?sePJ)G-`|`x z0m8p(P!s(llD#9UKfXS3ku^H%PBM1!=ZEz(^U)0GT2Gf=E!-yA>!JA%t3JS1?U*Xe zzj!yF3I2U`se2CR7uWx7+h?!??H3F4FAJ)lFt;}WMvt zZ)o{0hcsEl`2*x%Hpp^^qkU@8`g{2NCf3I_#eHDh^*r)?)j{d{xc<<^*aymd>(Y>c z1?(>$UZ}pPwz?P8%X>l2PQ4)6nTI^DsKb_iKT0bUe zzM@HJJE*rjjclsv-@*BlUMt+8kB+)xe?+c-IDhihq!)~BpG&sP z^dt+V>qj8{^U8Uis9e*S~WA)DiLLo7x>VI%SjfAJ5g;%lFs4)bcRP z>}4&i@0&gIfkQevw8=BhAD*9T<8zWZyEq8-PrLVcDEHQ+aWgr8CWybo4KJ|&%*T<^t0JPnq9)TNQjc>IX{*Yg#M z^KUH{lht?l`y=T5_k)+F!6ME2^kNR@&m7hFpTHybx+;MDG2!|MsQ)c?@-*1;RG0Rr zZzTPjgZg_W+rMCMdIb`#eqW^D7lG=FtkoM9@@xy)8L6C4wcWljPZ1ygFJ$`rd=zU% z7C$X7QG;sB2w{HI!n+={)j3O^9Ou6u=Up-#|XuF zWUSl2->)uv0C8@L^TmA?{5J0*+2j3n9lt(cZGR{<@8Ngp-!Z?*Y$}YCwUZ7Q);TNG=cP$a;kc8SZ>zU% zaPy@GJ#@g->hJeQ1@Rr#sts&{98@i`iS~4^&$z$5Pwu>XUl(d_LzJ5a0iOI?hIxI|%bfbsLO_Zn1Ug!~4gXq#uayc!yZ#6furmI`waT z$@SSq#S2=l)23?2l=Gc+FrK9?_7%=Qx+wN9I$mF!ZaC{HT_5|$d$LlP-}%L|{j;$? zFY)k%`ilN>gSd8*y^4xFzZCW69@~-|K$s2Z8~euxuTOz{SL;*l7R5F3sXV`Qv^tB8 zYP*3HIhNPlpZxr}_1mYyX-hqNu55~AAA$OR=G`u2npRtd{gWK)SyPyQf)M|;qI-eywpV0( z7SC@5kQOric%C^LVm{WQpO|v~%eM>!{qbd_Lz5`!`Zzw0|1<$Avb7ZRNy_=(J>DF4 zoqIuYe9uevu_!(cn;XvR#90gb6K0QJ1Oexo(Vkh^((l9ie(%LGW;?=>G%MrJ57%${ zbn%DJms?PuoFvJ94&uMXj2L!oq=#^SlGSe&`K|BT)bumwALpm~hhAkx+S7#o`5(XW z@TIOcUFM^l|B+s|800RNo&SpYx9;u%7YA!m%hheA`^Wneomq8{S)W`j%U@xAk2Cgw z^j=ytQYBB~7w=Cpa7Y%Ll(vEN?NK59ee9pdG@Gn=zxC;Hea=6@`riE|n=w_+e+0^J z9Z$Ikni`X2{Nwu27F8AK2@%5n`!U~q!1QK)+WG_MALqX;T4+J)T(Q1?-sl7R0b>5w z&T0&5ClZA5dAkpjA<~vC_H?)6@r!&u^S^Nx zaQJE-d9TUWFXsQ}u|e=)P6Y{V&Gnxk{_8~!1BVM$#FcUW3FhB$G;G+SPQUEq{u@F1 zUT|js{O9t4MD5~yV|}0Hx2JpYCJ`od5c=-3#6}(WO-%xV{D;|2jIs6waL#^L0ww1$w8~rU7H!r1gjQ4_Z9h92%SE zlgoYi?=wgGI(N%ZFeX3AJPm$6oeJV-{_yVbC$EsSZN>F70_C@|2aSTBbv5Y10o;Ew zM|`!qW(E3@U&xJlr=|N-A0+P&itpe74eYdK{xi-m+b!)0SC76XyPL#I_PD>j?DBp_ zZw)19yYu)S_c!!Wp9^l8hIDW1=hFJdeDyqcgbk>06!t%Cd9oPnyBgDc6(-qdA->vQ zI>W{;@(|{?z7;NnMxUC~E79SSeF5UjBjYkNbe|@Sk4x{4g_TFOY5zRVR{-K`?ThPd zZ{iZ!{(e|LRsG!|;hq-tOy&BC^IL1SWiX@eYi08*SU;;CxWc2Py0q1e97#U|P=3qw z$rBc{EQr*7&H2Rf@zC#MAg_B}s$V`vn%f@GnuP6ZLui8t;GI(6Srs zIh#+;Z{hqB#BWvp5Xg1-N#@`CQ?tJ0=f6$)X#t-tUJ>g~oZk?{@3Ov*;PpnG_PE6L zv4F_uLtk|00S~KQlhIC*((k*2^3!LNJwW}94xQDwNV+~j`RVs_EWzq`88JKzl0Dwv z>ymaDdoW}uIX&Xv^O3pdDjlo*V123~?VFud^ZVrat^UI!*@-+yVf;I^^-^f$VnQn? zB}?`OC_nwm;WR5-;Xyuc=Fb<`hkk9H3$5oH(YfjeYOXKuZ<>^OiA~g;F5F+_tIJsU zuv&-CSM!$aaek}BG?{G=73*WuIc`8lXw&kpJpMI7`RP2rbhd8WTG{^CnBVqm#(F3p%Y*mAe#3+XMcVquIf1(Sl9aWdUdBgcFLHrK;n#bn)ZzES`@%k|4 zcdyw`*6QG4VSM}0a}?Ms_OF9`Qr$&t7=pA(a$7% zK>QAwrVloA6NUYQQ8*R2mSO{ZTO~;@#iD&j~eu%6F6Gr zk_JzCe5*c4UVkcb-N)WEA13U-SaN(8To~DmHg(|ojN{u&FC*C1H)8*HTk&j|kZeTP zo=A}H5AWZ%wecyI_}oL7-!kkq2gX$x(avt1Zxxikz7=+nJzO(gSpSXE34rn;ZE0H7 zI_dhD@BY4wUEa8a3^n=peUs;}&1Sj6w;ToE(VTC*|H9&mRMzh1TG{@)nD4oZU0~oI zE&BN&=i3qK^U7YCEI(xv!5M-uGXFXQVzjgy-s2G?btY3X8rZE1_ zPtwzq^N;J#(Te@|>Hqlq$Ng7Zq9|xB`bmB@S#I^0FF^6_(&mF;yUs6i_b1nP zAaZ^0nqm%HHohk6LpMqGnE&2w?Lq&U2K`>Z{d3I!r?77DOTCCR3FZ9b{;LV$6X5a& zJ-TZSpI;buCz6#Y2yz{_LzStJkPGW zPZ#F5bhDQ$`XAa*7f0p%Z>p8VGRl?^r~dr?WB*#92t z=KukU`OH!S?thygel^ExK=OI9|GkgcD*QVQ`tZV&8vQqvIe?EJ)raKiiDZ+a5Bo14 znBSR8hJ%Y^E!u%{{~PD0La#Rmm+=|G{;iQtHgKbh26egXEUjOx->h9{SQ+$^Xw~!& z0P0_knQ99yi!>?YO)PoEZ9wEY3S5-9J8m<~|({f6DaeiHFMh?Rcy`*nP|)qx*3E?vM0) zYSL~tnTq+1ysqey(8j*hlyA zLj86RnGF-2<^1CKdfUo#Y;w4m-?ec|Aj-QnZQ1$X{JDI7&SGOCi|M&k$gfLjhh&4W z0vh5{yJr7=d3|bS)NOXGVy$d{7_8snXF4QX3@e};-<_9!KisT7iU6BObhBb{+hJDaen$s{o`yG884h)sJuE0-i|k>ZdS_m`Sajdb}CEE z_uz`+s9u8;k5?*<91>wu+XfI5HwSf6c=wojfCTR^Lca=vfHq%a*1v3~bo z+&_u8shsbasSlXnlTBo6GOu4_zMTWxCoc(7T)*>w(*5K5^E-nV>~+O<;u*m8 z0rPKL=QO0}%j-`#|GjKXIm>SrDa@}0U-p3cbsEx9W2e>Vvphcc>sAZm?#TJa`L&BF zHc%Th>1j`%Un3|!Uz$}9l71zUX64HD{Xy7ZSYoe6RpX2#esF$GKe`#%Hn}I{e`Yy> zf{iM4!Y5nFUIq1Mr~lUh2K&7v`mOl;$Nc{&8wtm{Y0}`vd_ETQpYAXK0xW-#9WKiG zUvt<7tWIcBFK_O@=^_2L&g~B7M?aD}y?Ffz>-S8>{whyx^y%`zQtAC;|GR3E8Q7hB zP733jU`*9#Dd*eta5NiVGF_M-KOMIM798(LSH0XIJs-^XqLet+ zKX?f#s;MtxzD<|6ORi)4l7=i)&iB_BH`%SJ>xAcDICW{4tX^0^zp7o3u8;M5*pdhA zeXlKql>LzY9mn6NXSYkX?)Q@RTCbe%;e)c-?DQSP?;y|LV7>=0J_&ukiTUo-`!nk} zAX3;Ly1(sMcz9KxhVSu}_{RSG5*0P*P!KK5zYUAhfvr8S3Hg29dJqiTsYZ9^aDMUm zHnXWAd~J767+)7Bwu6pGUXrB^l=C_NqbrQ--+(4pgh=Z@0O|AIBmKb7_ZJ!0TRETS zZW8c0p-R`R+h1cZ?+?kW90?=V)uBF7{QHdk@A(1Uq2Hpl=F-A z`R=PQX4!U>uz&kR)?^5LZ$uNHD370O7aw8aUK51p%azuj0q%=h(qq+}U);Z)v-K?d zzGQ}Q{&zq-f5`OeNV^6q=XcuTD=f2g3HhkVBma&6Fuy|&-Cz|L*O3DS{NHi>9M!Z8 zK0J+}8`4)v_5oJ%{;y4*517}ut>o~pd_uC1L;mybkTGy9SnfZop!`<$=r$1MP(U7axG332AU?0W+s?AmhY9Of z-QWAb{`ls!k=+aScm3l1WkS>Tv1Pl(`r7)@6tL4Yrn}p6|2YK3$3rV4*^0KF!u{3W z1p7jI@0PS-DCZOBw|=xc!w$rY`K-`d3aYC+Qnh8u`Rugz60_N~gk1FJ{TrCi@*dY& zgKz6dY2$z2Z~6Yg8iz{Zh~r^8+AKhNKA2DI)%RJdUN8xW<@N=LPdC4JpdAoFC%vjp z`ult_pQDFAW1lC5l0%Joe1-YEY49GZj~tf8$GAT$KCX=2f=J>1_>WRtVRL*#x;lpY z#{}iSdNfyo-_v7c{h2s_?O;3#o+|pw4sI-x^cVZb*OzL+oC9LMV^6uk)-jE!dW^ZW zKJompooZ8uj z{gGE9tsgzaZ}>Sgux?#I3NtTA_Hz)wUG9aj&Bnup{g(-f`3k6QOdl5HNPi#e>+6Gi z+1k=kqN;%^TpiMprnFYhZ_%TRZ1L-*q{&YH{l@&xIeY<}t(MSx(V_hJqw_5m-Uarh z*Lu>=hX4Km)W4;+uM|F{Mbfg)t0jBP_u8rqw$wS8)PBY7v48AgoC{H@duhYjpC!KW z{!$B8KV^A+c9JvQd3=TWK702f#AhuP@|{^;%3`&S2=iY{CjMpvZpX;xr!c=~etLrE zt!C6C{Hw&T3flklpg8IJ}-suixVI_GKv{T{-*O!)b z9}bHY{gD~%`S%~^uO7ea41Fsw9{>uHOH|*Kef;Rll^%wKotHB<2`syfQ{>r(-WSE=TlCF83 zB;8*W(%+3v5p2j|vHs59<^x94S_-%Sg*u{{Aq(mt*h1*UHWGgvW8|{_**a4hcytxAuBsbNZjXT%Yqsq_dg+Vm@!^ zyn{glj?fuTRHVO;_1Ct+6IL9ylhg@S&Zl1M9LU_bPsS%f`RV58-m)>(;{23p*M=&_iV-fP`3Jw=-Vb`?CR>u|6l%-OaQ#M+@WMpDsQS8frqz_A}}J0P%hP=0UdF z-cuO=b_kyYVGT^^%n#hZ#`+wn6~%_R&lJ{=M`zCg4et)LODE;|>F#moSc`8ty|51nIMlMG3qaafGh6SFX=<>!h(EcY;Yq*J}QJ zkpFG2`GlRnzl)T+^7squZ~Fnqz~0wa#y8GCr}iyj1rA4q@o(&|6qtKrGdrM*7hF@!=*T65 ztd#LxXLUn3zUV$Vy_sJh_jjfxn1fMhCAsv5^NsV*pSqaB@$-ek_}MwO4_texN|%0B z&bR7KbBH=vN$xiK$EUnMiv_8=q;&ioXx3AnD$IoB-Il-CM z4QbK0H$nBd)ekCdAck$`1Y+aiX!ujO{FK>wc(~{~|$Cdho$PVz z(L#M*eAfpC&S*u?hb8m%iTGW=E}T6%<|)iS4~&@z?aEB(s_;XSJVJP_-1 z%QJqEHoF7O)K|{$h3B#CzJb56zVza30-M}_y)3_s`P{eiF6*MbjW~I8{;+?%_g6M_ zT(qCgEUrlUyFPJ!sNaNVY(vpr;r_?pUDDv5dx(rr9RDT;zG3bsjtI|RwVLSz4LY=< zl?zsJ{Y3rOYr0pm&E4gE;`&haG%r}|*pj}l_e-+J=YzcNQX5{cNfP?c76-<_?Xd>b zBCdzDzOny2sGmNB9=b2A4|V;}176Qnp_W5!B>Mm>`Fzs7OD!S!dLdbn#Qh`eU&lst zg_2L-iKZFP?_>XY@+oU@8m&XWRq^iw_K#nEGltj;FNqQ5`iuK7jaxW^SyDr4Xu$nr z9N!+vFoJWva!E&smF^$sr!u~8X7?k83-ia_9Vfsp=aw`iHCI~y=4k%t(}qx{y+o{^ z7kxYdnwij3$GCrt^)qpdV*bg%OSr#y(O56ANHd|{PMkm7zoF)Ej4dypDa;?MzSs*{ zhT~`ti?h=GWB<63M+}P@C+2Tw=Xh4jPwfA`ymFhVm~E4t&xrX;TKNQ`)%MZUROS1p zmgYWTMML+If?&=sLH(1K_nyG9eq#T3w^0$h;(tU~pZ)gT6GpBxp^w6rE7eDh@~^C; zb*!*|vQ%;YOmvr)^j_#s$sXsQwAC~q@3`3ib@{3Xs&~Zx?dxTp5Y^FyZtAr{DPIu> zn!%`pxg_{D&(G86g3(hFzFG)R`{e0pt?4Me&HjXt| zE7rdeom1GD$=k?|W&HgGApcWuU?yx1-6zWrVf|Cn$z-Evi}|Y;ej7T^5$m7RkwVt) zw^;uYUnhgJ-4^;Ng!`v>KJd)>ayEKQtgwE1tHX1sXBJL943N~G>?7+se5iNVc{Y#u*noc@{_pl#i`#0tKm^q;}?94ACMa#BI*Pnyp&!vwBL1d+z zUmSl9S%gk$pF@B{?I6^9h@#kAsfAP3Y{M z%KcMwjqR-9j@Uo#5#j-R>zUH-lX-mUi2Tz(LHn3xA1`5i`R>;^(1|pmyPxs+66@oN ztC8&bky*m?ucoW-gi#&bsMiMN`J>yd&a$Ri%gHVk&KJ%feQXmAA){8(=H9#6U;h&C zuakG>GP9nso@lh?>jV3*`KAxy;l;hwA#aXkA3@~x*Bj|K*@g?-$k>#B*O%|V@ul8F z7;=0s)n^}*l=-)}d>^s3NA}6iC&&6~x3Ylse}6<+znNk_4ld~^;`a&ulK!b6|8?QF z&+Nw8SYiDp+#(AeF<~M!MU5MSflTK>N&%Y#S|D2^+4_MyoeZ=P}Uq6`N?_U!kdf;YZeA?z( z9!qI;RG2?{X#0spG(0EkpTPNFy*sL~%9;t|%l1D^=QBGzoqwwgfM@5LouIjq~JqmctOqIm(TZxxIZGSR|Gp@??<|XaQ_+a|GHU!I}Ez(N}Ik_ z&gYg|r`XoQ<-+}Kau?i#Q=9kEoBc0Izdr)iR~H*yWWT|5gyl3)3cFS)*6S#%q0-FDKsn@c2p#r0K}NB3Blhx>@uVs4M~yDbynL1bvO zkk6vWIqY%2qeA^X_-Z`7)o4QpxUH7-7m)sH*80FU*E%QE-{SINFhx;6^)h}Z+2j1t zWKe%a($FA3<)}Z> z`zI*At#iu&`uBe&(_cK_m$Kdl^u{-(&CY$2>~VeOoqG#-r1MV3_b0^nboW5k<)c`C z4HfmZ(8Z?oY!ugDoZsExw3Vg%It%l=8?)UYwz3sfG2;4*{paL2yO_I!w=ljv9pDa| z7n;%09S+z0KKcB9M@8RpWJ^C`d^`GWFkH(RLw9}U^%bnYcXFaw@B1rc=aXRnIsRZY zIQ3ggwzKY}HVXxBJ_9`*I zANQrhyc_cT6VCr8Kh0)`7m4+C>A7*BV$_EIv{ufq@qdl!`Jmj0xv=d!HK#9h?nl@`3JFQhb8;&+&e*1wHOR5Y}J!c69{T1QRuy2b}GN}cnK z<6rxz0pJ~^@E>L==lkQw5m0=+DebDy=Q}aKyMLR)*5&2IYErUve^H3vy|vb}3-?9{ z^TR(?UBGO&Db+p5`NjQ<_O4r4zI;n*=>*Je1-59a|ta7nA zY*9?0Y%u41s-XVGpiONd^2{%Cq>Xa@4c^)u`m8S_`MbAB*T?-&<4P3!zi-y118U|A zu>OA2HUO2FH{{B}Ly~R(K-Qp^|5G^FY)${AnZ^7#POEsfx$=S$iC8d!h53)iyS zMkC39_Wb_wd_an;GdNvrMYXAZ!?^>;4pXMg#Ax;pTpqs+*wp*dc5>}u>SVWJ;s)H zT`4=i9qaF?pXo43FP!$xQqJ#!Eivrfnm{u6r}F&OqTMdZYog2sU6{xBM+-vxYjil1 z$og*&A*T8~z9J|;?f)kYW;h(6_71#0i{syx%kQ!U6T@WrE6n$f+8Ll~7%t@dgYh%g z@5xbN|6&(^H_$I=L+N4VeD88BV)mb-N#+&azfpkp*O^yx9mc!uqHGrDCj#ZS`t7S? zQ`A8iKVS250N*#p)LXTmwEhXw=Vf#1Kx&hR!u(cim&Q<$CD-2wl)vh3U<7_=%ZP6g z_pcoh-`BpihM^h1$TUs9J|ocl{n4&Q@c4ci`F)7eFov3&@q@ynb{C>GNh-!xs3C6wVinZt4W3Pfck? z5Z7nCe@^t7jqFxS7h(U?L@Q?)KfE=a)a<%+e^{TLy?3y?`zDfT%YX5oe1B+-p)PQ| zVH>(@WMs|nll#{fT*6qJcVfQj%+(O>KAe6t3zzIM-v;_e+1y_%g!wHmk0a3P)p9!U z)K1AB>vOn6G;=HsB%1^H`^WjM%D_~xy?%f?WG<|+m*=N-yyDq?8X~LzV!oH}F-_KK zTSZH42XlLr-+K4?HjBI-MjF)q_kGZm^(Q^6_Yyu?h~wuTd6~@S#!+GY*ERJedwL_9 zRPJ#QS*+COr z7C#i`zqWO^g*v*%RQKaz$sYGNy8UPfz71Xr{p;E-nt|_*4WmW+f#!gY-7y;p>a>`H{_d;cEZr{34^ zai70?T%G%V-{<*$UF%%u18E$-N3zHIU3Scd9j&cLzqqL8+uKK*ZQ1rxRv%7Bd|T@V zL6Xlf;r*Nkokp=ynQf_i;Va<&fjmEU$t?tKJBs;sdohwlj&4ieU*`Ia0WRLl75PksQ%Uap_1I+iAqKnG@;+^zb8qbg6`qSw7C*XnkW@1}W z{eF<=$8wh%oxQLBm-aUu%-2VJx4)AEgVW^tjq}%aV^6YaAH#+E?OJpf)_xH4U7UKH z8OLm*UFzgX`7PZ47(L-7Y)wof+Ew>kVEsOO6WI9QQMB7H&JX5aV|5wK`2{2(oclkR z|LyIR^S3VFA=xq2&qqu4{uwE-}r{CXO}$kZi;Gs9(6VVwwVkQo<9g!F@kwzwWUSboL`3SZ|K-D z7+%_qB}eA)=a0`1ZD>4_)$P%a-bpwseLfSE-<}e<31aZ$bKy*kidBNMB> zpPb*~7tt_qzqc^I-PmXu^C%fiU!GIVZ*=5t$p0hex4v~OON7Pr`o;)pecYeyyLBJ9 z?pQ0EZ-@Dv^`Q0H4we-(ZcdJ5kI&aH`f?0nCW!gn6Pd$`3U|`Iic%@Rjr&99Z@d7t zo9`rVTUNjS<@#JF><+Y;kR-gHP}}@GORc+uj?@1t@rmol9aiT;?iDegA6|vCiaxIN zzn-e~`F7z4IMntexpa)jhlaGSjK7T0!`Le?LmFadY4vY^2O$6YzXA=`E9(wfGM4j! z`;({TDf@#f>d^T*6C``A&qmXASQk$@zc~M8+NT){+w)l#UvESDtiH*RHJkB={8z;H zH_m@WTAQ%mO|+azv2OUc!1{QOWP;&+Hre;243&>H)`OZ$VN^Fzsd z>az~3Uy|Axyg%|W(%;(CR>FwI!-W0GUWXjmjX?+E%PmODu3TID<`HgbUgl)l_ z$-1UIe!%{7kX8=sqllpuD|vj3>rZ3+&w*))SYH>%USJba#rd!DBe%e1xtQO%#@m>} zZ$5=9r#Qa~`T3#aHqSuoSQ;^2{zLlySYNleo@T$_ZKV%2=U7SpF^Z3!M!bQwEi=iK zPrQFH58c0gX1FEmQ%9Gof9WCF;EK)5&I>31>)OC&xSSDYDsJ9^7jMQ=bO9B6y!Ls?3SfBH?GvJ$cxUhd~ zMd$OZr$r2Pi{*Ud{MYA`3?2;HNi05BzaQlK8=HOuQZkc-=MN?}+sbku%%d|}bAGXZ z-0%5g@Xkyly$7h~ch$O+EMmx3>T`?xpV&WMSo;-J+R6E4h~Ii0l=IEYo6;JGIKS~o zf3=s?V73-weuIMtv)r$(>GofXt^VyltiRsL4cNxVV*TyWQkM;USxg>&zg9qm`PqlnJj1`s{)12=4@bCHI`m+79 zRWM3#oG}0OV4(y1(X1nlKFa;e|EJHn>mldNEHZy$_5PISzn-<8&s+>`XytnzUo)i7 z&SSPfeu1~JzU+C}myMY{m>zq}>%#=`n^!vqT#v34#>ZcVY-fkIE~eKSsP?ZrYbV1z z(_q1XFc-&&=#X@q~{xe;@`8)0cu9=Bxic7_MfjtUISf7 z66U8J8XaWq--Xf9HJ@?)Mg1Qv@gbaMX~e3DYJMv`H?V#~TxpNfrqcew{Jxz20-o2) zB*&e({^IzSmG@rg>{+H!tz|Chmt&TQu1x->9J zHNTU7>9YotD#-Mu2c^%C?>95uYR%@(X+@u3<^9`Of75?AWtDxtkq046vd8)B78Cv9 zi|a69eadZ+Jxl-Dfd-u|1XcWM*ad-st(f1qF`;lba2A>Ig6ku$KRut~%`zVjqIVW? zKC!;GdlnAEUV97YXXx(S3AP`^{G}UiV|o8Aq2_j~`8yk%2qUHi3+qd5uBJox8Q~=6 zW%c_-o`0I%cquebl0vCB(zX@_#IuMG8H&eTw_)$8vH`#U=OH)dagONh;X{iXG>zG^D! zF-8hy`6(RVHh!(cj(qw;n(yTP0p|1mLwy#o_b+)?)&GU#+rw`=vdIN?soHb?e6atU z@h=_-5q{R{T?3t)yE%Wjest1401`aLk~~koK8|lUd%CjiiB`1p-#qxoFCjWI|Fm~b z2xKeyd=#&mPb=Lyto`IcbkZG=>@lAYRBRFQ8{~Zn=DbWI?K)RKU-|vOO~_uh`pbH{vDFim z{N{hY0~>av5sx{1e`0>K=Z3O^fvz-TwrYKSI{q0LcpW2p7kK|Z=C|XlKah1s%;)?8 zI;`1_V)CUbe>EM&udnykWp>GhvilPVs{fwVX}|`I{z!g3bCvdgJjy@in(DD`kNyh# zueK?4SZ~u}Lbvk%D-CP;{KqyH9oRBmEo%LPKOfBRL(-Ia*p!nsQ};>h-$wl%<+haN zo;9Su)cO9v{GRcy%_2%)6PN8rB>RylKNYlhKJ-5;*3VAk?O1$aCpw_=owR>3zaLwy zfJ4go^*|TZ{EoA5W}TG$Zo19+4M6-JNDKzOYqLlURPQgj|C{&Jiyhr$OV8%;_!sk= z?Xd}3KJgLOhi+!iWht>k=t*Cmp9(?m>h3If`(mf8ev9?B%=jP+oh7dCxV_DRvaZQO|92frVbRaR zXx$l4B|dTg)r_vUVgB_r;u6UBALjE&aTu$0WDd2p=_~CYtgo5lo)ZP$ZJ_P9T*w!v>Gd?NOL*ZOL+8&M^sPZ7^QAoDufhCk zX4PX)mHaxSaejReznxw*V|H~bh5Xie+LVQ){3Zu?ZsFe_^>2(F(Vj&nY0<>tFK?XT18yJ1d>%>}#+F>@N*85w{|4um zI&EJH%YDX@2rbooKFpiRzWEc{XFIPSVSRnIX)VM#IFk=8s`sy)&$W3Q;MH*-Vf@+k zju(S%cJxL;~_m^BBUA82%CnGi}?>FQ8;rvm= z?wfGi?hvu5n^GA?=&Nr;h$oE27{ulFiZeBgMeduR$ zbGDnbKIYHCO_$Z`St-jO;r^)sdmFPwYk!fN_adt7<@))0rZHPRydHgbg6DtYQGF*z zyCG|Gs)P(1o-Em8{k&vt#jX(}x}=Qr7mxURGrk@>+VZpP{#|_kSO>?sV3|IQtl3jt zpOLwziixvqSxiM2syCm{x50eAD_RWZE5-@yI|uZqvw7nQtucV}iS;w;)@lg*IZKxR zB}C5W-nf}eJ(IpM!uS$wcdtYJQjcB(SN2!|3AXs{Pxemv4YcY&v_)%#yQAL`m~ZMNq{IT?H+T(Zag&6X$Ivi)o7(aW!@pP#%xDyUOERvi76d`U}` z?6H3CcImG?|7k?q|5ph-K9u)2|8B0yesnJ+!w+Rh_V|3l(@UQ4WtqM3eD5AQm?af= zp_Beo&F=u~MKE>5c;Wq^r@K#KH}6@|i3?QwzdN#4fypvwS$+xg>t!*El{K=VTk?4P ziupCn4+Y!zVtyCSc4u~T?dV8LuD=T8|F)PK3C0J-{AzTFWK)+1(2!lceuMe7b=Uczv?)eDC74bxi5Q&^jq6RQk^~Cf|U&dPm6gHQc|7 zNBX^V-Wq1&KUwEwYw$HdiSy)V5bWUFfad(&DhZ0CD&#nV}`$NWFCY0NtMRT77C z)%?%7qRnW#-(<#T)%xx3YQzpbuBW_Tjpu){ew&!oWnGSZA?aTdr1dYO`1izm3zm># zL^ay0=HIlS2D_m3hJ0*%M6$>AAFXZfaQLM-f90gS|M>R4uGGAO^N-`-7R?sGyKm#j z@~+k2UrnZe*(OfRx)r5&FRIq>O}7Fe?C31n{oa`Wduh{INdp`D?g-}}$G;7>u7jrI z=L!AqH47pj+c!XX{%BTe1navyfF4Lv&3Bm34v6p#CiNfk{f+tl^g5fFT}h-ZGFAeA z|H}D3b}$)M_lOXl4=&0*!kXpnq6=o0ocU*u`!kL>AAw5?#QJ_%kUrdZ+3XL#&VQlsNLGu2LhB?=vB>JfAd@%OULrm7P$1^->MVy(mzcAl@IzNEi zZzsu;q!Q`*V7{mKwPL3-JJ1&f10{PCM^x<--&q~*LR%XD($Ah z%%8m_4Hu~9dr4+3*1XC?pd+ECvC6Gyjqo#>qgu^$M+{(2{LDoj~dZkYO49RJW+!k8dgA-rXQ6)KjwRl z>uk`m9xm*^vT9|+?4ER|O)l{K1@_M`uA2|0ZO04we)?$=)BVqy&VT$``hBr~J}M&s zemOeJ=C5PE`%Re5X7wIUlNVf)>@nYshJ=9E`FXU-%**D2=hsV zu>NG*<`f%}mrTdrQb?a4=dU}gONYhLV*btTgPFUgkBonO|6q+?r{K-kWMO~h@26{+ zlmA?5W`CULuTg*2Amx18fz2~WP66i!^G_^Ru>-f#K+2pVr z@2|xCdu;8?aD?Y=xihIKT=;!HA~;6Q8tVesAkhw=b&w z``b=+SjY5I5;l|bkIz5c4C=$2FB#DZMLa$yC_X>2?+@73cttjLSKWW9Hpdy__t^{k zJC?p5#0tHYGbzvU_zUx|e$yMGa>tP-2e|&>`qZJ|Ni6loKx(y-_lIEqhu>HZecfh} z7uuX3%zx^O@ob?drKQiarTrg|`a8azUkf?`^Mvtv^7UzK+*(`eKVxT=y`2ARH8+EY zRv@{vS9N^;=guZp`CQ3=nri-|w@1U02f?!WTbTc=%@W{nn+Rci9v8Qkl?|9j4Vs*k z^j)FQmH9`W7t&yrl5bIe*4B5KY~!CjGQRQrfGe|3!hE$9VgCElmes6Zq|Naq#F&VxjT`K^s=G#2J!ke&W{^JErsk_ z&ZKyK_4@Ms+roz9nbRk0`l<`hzhQmfsk;UmThAjJ9@X~p{>z%(XRz6N_Oy3Ro_~u+ z@%x3j8(~88Kw<=-Fk-LeB?8lBT<{*ATV z9^G$N@6>Lke;gs~@7nNsH9Pjkhi*;I;{2ofbgfATVO8rGq8C;D`^)C~k zx2yO^@%swj+i>;EDN=X0YW}wwnzGc%MpR#xKbPO%u)f}VnA-NfFn;%GQHQlyUru^? z@%%m3_s{(mOk?po+5N&ef0t5OlZCu1A(KyW{;_|5a9(}(%v3?E=K~RRetBOrE#}%z zIbWm>uYX~Ee^S|k^>nFE>w56`9oN5N)@ic%*QMluwQBx7b4*!-Vk25|q5Aii=kMrazn0zKfcw8n4@`rU7Q==8U+<0$RL<`-rFJW-e;@hzioXUP@cQ65VSQ|Pkt0(Z zZB1MGasNIK)vr&jUIc+}W|71m)%?o&-(~5D%MbYLENoLFry z=U?~HWHu~%D2*uHDe;H--*+qwX4DQ8`uBy0oSA;cC>qqmSF&fQ|Ad-ELhCo;`2Ki~ zJ9|21936heSSA0j&cs3cWf8*q_S0+oU})?v*?bXPUweLjCp+!*qR`m(C$ zFV}a_?#aGQF_N8+!v1?d|FklkQ74y9?z9!qC zQ$~Ul=34!WKXCt8?T=b4+(FFuffY4b)V*)yRSG}9jP<>=gFaI@)u%`uCCZJx6@Of;J>yr1QR-Xu0Cz>cP^*;QpP_up%dT@RU4#Qyu(o^C8TYCNsDx>&Nu z`fipL0UP^;2=ntMk*=(P?l^jUF6SGce>C|K0|)m-2+v=zNh?{Y?p)f`^BC86+9U^J{zWjbetnc9`&Oz;K z8RTR`9{&WO{QQUL>#(a#&NoB-q522^V@?IebVy&WzX7N}^uxz|(B5!gcz){0ZcX-1 z@r(5AubOZ5zrUba-6AsoxN86XypbmB)$}Lvbet#gf%W@ax4I05DX1tvmqIjHNmLp6 z@ssn7`?qWTX~urEtWReLasM6b_q!+RtmC6^#C{Lg?{dWVq5pcYJ^PGk@O%DzaeO}Z zWf^oDnomr+a{nFI-*(W+5c7Pvuz%G4krmT!-HTrRqguc39Cd+(`^9`Wm^+$viLjx^ zUlvGwV7@=1+$^CZ)k?VKBmWk|& ztvwxcIi_lTIp4qC)`3DJkOW??{{7|k^JbQztk2azdeCO8WUoN_J!Et^M9d43oo~ke zdkdp*HhxeDb@U!B+2i?s1A}(Kwi2=bzFluQb4-{^^)giR9WyTlKAXh|>+h+9SF*`z z-ZH-N{Y>s^N1;e(FKN|>?;q^HlTM42=QrJ{d)uQ``Yg}SPflQv@*;zc^n7rBj@fo*Nw1XmV;Y!S{nJ-%l%I2(^BTrR zi}iihxtdI^+iy}?$@$kt`MEi2<#6|@IDRjCsljfp`bkD@=KKes{xyS3wVB2o1+6~+ zjQ#gI+tt~-mOseub3A^>{`)vhUDoJ%J(~Z5_pjml+oK_B?C<#!(p@h}`u^Jx|Ne`* zu$zAkX-unXe&qgpa%L%5+|4I{{W$+Pez$O$0Hc-;7v|^Q*0W;f9=&OBc=hii*Z1aY zX2Axn3Bvvv$5W%((iXPVIEDAGGUUI9XUv0_t6XH~qj7$&V7Kyqu0khz_viy@f8hFi z$=MZf^4&bL-JXAc%>Ui8Ny_}l2x_$`Ua}8B@p}v15NK>3D4dVqux$Wyoajq;<%CK0 z1o3b2Y!kfN9wM9XiTPhzypes#4yJ$oM)CDg{2p?12VAcd*XQavE@d5)z37Yy$GN_v z_}veZV8N^y;rT3kwZl->crO`RS2f=geRr{0n<8o7L8|rJ{l*#i+%1!&n^)V*`)mA< zcVP9bThq$3s_#ebvi7QSek&tkW?bJe-+nXxW0Pifq7LP}{)W$I&FGp3S}(-<{$#WU zyK4WN+%4sN=b`z5EB(vBQnyIhUvo9I21|SYgWP`TZT0W{@)+@L=u?aN?-cv*Ay+Cv z^G%6tem>UseFaUJ#jN@?Ifj3KtndH*sssz2QsUK}^Sv4I?dsQ&`IWV%t4CG)|8l+^ zHH*RXMLs#{#QDxc`MI{P<6x+c0|^eR);D>6u0ctEwrH~%HU7%qKR7?9(PcXP_8Twk zFCWo#1hc3!gpTOry~Vk18SAxRpv=EJ`&EB`xxVkKUox+LLwV>nr5-_ZxS&LE!5M;rS7_MvK@MFE46aM>XH}=MtcgON^{P z9mnrSe=cU9t;O}X*E)w_$e_LCs9`m~^88#%urE{7@t{tJs`MSz-?XAnL9ulv$!u3` zFX#W^8)LR{UTf<4l=B~e^nI<*H8>J-UU)x-Z9NlK(yJ4Fxr_5pkbl2pO)lgYiS@nx zN9Fv4=s)CYIJd|AmmevCt%Jn;5AsoGo~adNc7H!BRq^|PpEa5P1qFp()%!rT)XXPG-^zTE} z{4YuV3XARElJu6mzYgc;y4`Su$Ct$VzTs$pR&PXKO55`MGv>eJ=f15kW_cJVXVV);PWKl|6%n059uq&Xw~B|b6V^&5Q!g;kNTzJBqd z23xC8qvn>2C3`~T_a|3IYp^Ew6tsFiF!tXAR{VyM6TT7shpPGh^Q;l0hZ@lCA)FtA z`ri}g{D!i@-$=LfobNnzfASN(_R9H5Z76i+`iA58iF%*l!{kCTcp&eu!F=x;JqlLT zcM#^^yVvf|%$oG0Q^)b=kNKWAVlvEnJ)T?~R{iLTY>a@=Y}X)(`Sn?|MvO!d}eCmE%VO_ z^3UC-#6#2P;{4lv178+3Qq1q{M*G3qbuW2Y%6~r`pBwku#unU*qV|VX=ij$wo`9me znPkTX)%?yl-;Vj47|{*Ke@gK=LHZqIa0$jLE(rPEx3Gh9es4Rv-fn=zmk)~13zt8J zmIe>Vgr5BKdIi*3VY(V!I%SEp zz5?+*D_-wQ0*XgdpPah3l) z9?c(In=k>Id=>le-Iotz@%QcMGJ_A&{>OZu%65gA3Nhc$mP}{w*)%%j_M<9$`TW64 zNxo3_Y(DV{=Fbo7w?;irHhQQBojfE%vd8}W{%hctoos#)_RnAM zSjb{;E}$v8{iXkp^KZ55M1uRqEyTG?b$(nvpW(QRH}j11qLVK2{2S)`%d}VkCEud? zD4+9vm~%_9f4<%-6($`O>vP&fPnNw^?4Q40ehjh-GfDg+{`+HnUUt)n?H*!8$M5HS zV||YLegV84FOchdIGz=#Y_5 zo*X&MKR@C-H^Ck*MmPx1zeMQuV~Ni!=&z}Ke+D4F8=V*jlVJiG`cbuhw^!aDvii|5 z`l7{0Y5!xs?@ycs`&PP;E^|4bSijp=Ol9uPX3%xTkE`tEe4oOyfgOc?Rg!S{c%5xtTmlX6v-N9BoK9J8xdav;m zx;J@FLOl5V2+Vi-o}b|H_cyV6IbX8J{`oA0f|d4Gqd!LT&xif<-J5ECzv;(X)$+la}AthJKwp_8la<$Tv{{st`j z7m$?SoNqjTbjDRXP^&dUI6t_2L|=BklO@fHRn7Oa`D38%8!_K)_6%b8PTSIMQ+a+} zf#wq~?KA_<<%;9)wVS7~%{^z*pxh^%4=U%o>BPAZ>M)<^@8a(ltl#Bj&Mf?lJ1yL$ zn(rwmmc!v7G2fki*TNv{b!6Cn{(P~1=Zx}Ut;a8*Z~ayC`zUTROi9`zJl|rS=fn}3prRr5>p zkbZx!tbon!)M)kn9hmQ-arM~jO=5j6ZTkiO8hsPy&&^pYHeAPurmy7t3&+{cI!z)^4z-p_GY!;C$)w4_VcspdEOAI;fqn)cTf3ACU68qX^CVg~>^NZu_#*rRyOPN1glck#9+l^7Bl4ft&RNi*SRHN(D^s1I6Y5VpCP{A-2MrrUDbs3@!eZ%GkaQ}_Hj;->$9{Wy;Y-{U%7t&IQt%KE|rkm?GpL-NB+6pdjoc6uo2aj^>@nk`%T&husu~u za(~Z`(Q)4i^9x2xE+r_4=o{J^bk5tWns|h3EOp}Si{`R6CgPGro5p?4d9{*tf zeB+PF@M)Ns|C!AuvEE~yX>9B>_~(By)Ze;vmm53}@fF73zS%Qao3V4~h>4k!J?4L1 zw?(k_eW39C>N$N^rdH%bPi+j9>=jf#U$|?xRbVu3ov=Sv}_)Yvoh!Qh<|FZ z0TNG%`By7)X8C))>6C`5{qvh6qT!xLtg!zrwEk??0pMK}}p}%rDMA_Rr_|ra?^NF%o*c+FtITf4FDBNY8e3Xpw6EJL#PQ&(9agsAH=6 zKeMC_t8Caw7N08=a{h_lb$Fg8*7uoxTeBrc+S8u*S6Zp^-%Ix2gKfKV$&e_1J~I#H z-zGHt3WLVV`PWAE^Boo6q0mlES>LbbS6)9GQ&9vKKflT5vnkMgagtY?We;yC%&+_C zzk^IgDe>;1n*Xk!^jWg0kEPU#BZwge^8eN(6L0^|7NVL&;N1qqoaLQ>w6&tLPV(8e=kw;{VLFp zPMT+-lJ8F0>%q2lBuO5`pC6ttQ){9#Theeo^~*US`R@vpUr($T1saN2VSoE}Q&$$I z=_k{7%(nx?f${iMVf;P)_DMFX_C@-#Q!~zom0aJOyB~m^=jD83eJ^Ozg4J+oM?coD zko*Iz@8tzq@StIijBkSLW3jDSg0epD9mw|1re(ZH-S5PJWZ-fn47ei0@>_Z}4)ZIRBRSAs>wQmykJ~s^brN zd_Fn47JHc8kZQ~N*W~*CV0Ate^)Deho4J30^KWY!=&=ARBdR{I`u!r;_rk&NAz(r| z>15CO#_{=?d;$ZUM+p04Htg@gl3!ZV#V`2&#QC=_CUy`wQ>^c;6qFqZ96=WabA88r zH-9${+BcjnJfHrv)fncb?M(mHe7ttd=2$q(OdlojI4zI!edmO*-Fy8_*>|%-YL$0s5KPK7m1Y7zeN5(()?|Yn#0j(&pzI(i$ z#>|fS(2+a&`Bkj%ftOQZ%=%+wpE6JV@BNSY_b%6CHP#!`xAA{e@}KQ_9KQDw^Pg3# zCF}g4BQ^fQ``d7TjKlCt(8BhiFhA$#^ch^+D(J=OgZTRk@t-{MHsqDRBvDs5|M7_b zK*M6F6R$?A=O5$vT>W-Umi3|`P4808pPb(ov9Do8aw*y5tXiLSO`5Tm%K1^E{JGoY zLO8Sk2eI7)(&xwey!_(;_@gsYSRWhV+Ks(0x1>+*spfar%^@&>O%(R8UW@3@thPH) zr%~Mh!Te4==LiKC#roXIb0m9ZG>b;4Kb7_ej?Y(ro(2VV{e=Fx{iQL?`ps-QDO@$b z9|F9f(|2)x?N#l`>_CPWRaaXlt&jU#(uXaFtu;eQqzU&gasI98muYO3mLJ`5m-CD3 zXU__PVW57bu)k&K`>D+S%Y0hURW-i}n&I%SUMz7MQq7P2d`fA~6qb=L_s=oEwNrP( zwFGf|{{E>G+nnx0Z!YBg;`yueK?=NjE051{{VZ%tGv;ApOivc6*6)QZ1N18{$nMu< zNWYVoUVv|g4~6-)>#iT+%Wb8m+N##)!htuT<<&gWKA>3o{V<~Mz{n^>tlZJOkE7eLe>fALyY`7oy}^sh<>@(zsg?T zpVrKEEhJe*3iIcK?@nVcUoWI)jZdlczaLE91UklIejiSn%yyO`eihAR`PKHXw?o!x zIlly*AGhy5mBln(Kt~+m_Y+`#Z@f=}hw8_L`SWW{?AdOE88p|ttF-@c{yb;x5%B$Z zfy8T8z5metd;OafRp z549Vxr_F29>^h%M6@c{jV&4y-ovkM9PgBlbf}|D?1&?oYch!W<@Ak03J(s_kVz zzv7Tudsej1oT@eW1*+obeij2EWYQ$z{h5bWTCh;%`RXOx`1=v(&s+-}V4CY}VSm~d z-Qg^Ix(jXdMm67822X-phJM2HCF#i{S)P+SO<$xse_s684dR9c3D1|k3K+|JTvh7x zs}Sk?D^UKt%wZwSKP~pJcPyX68fW>_TCSXL+`krAvKrPNjwEw8^YoVFhJ*LjStX&S==PDOJ|LhWSofg=G(i7lsvq|0Jm&`1}Y3>Q5iDvmvv1 zE#^O?x&8{)a8? z%U1RuL+$_L&ll_e$dk5E`N@^ccHr-S+~1b`X9z28;!1S~KbO|W{{7ECju86BS6DxP ze87%{c5$b+%~bPW6f_fFDD_`-{%l4gH+Fc%8d~v4HUGKiy7*B`8d9}%&nuK%B^|1XcvHPt4t z)`5#;{Nwp>?bEivy24c1`7_M_Te~f6vR^9oe4w!6zrQ@c9%dH@U6lM+_qXEw+Uq%v zEY8xGp336<r^)$OApibCMnl$kj4=(h>o2X3_1`1+BpCh{=hvLmE`rsT zd~)pz-+x%&%U0B4wO+TN`Ib@A|Hu0Nx6Ny4)ue{7zwPWx1v@{m360;nPqJ5_`gkX0 z+&wc!n~qAZ-rsV*z2nQ^qFsHOSeM7&3gq8+I9i|esM%KN-~Zlz4+4Ek$xz^Y`yjqs zNBjrb9wUYQZCVbk*qZZwsk5?A{@?FQQ2%O+$riA4zc_xsQEtXgY#2-P!^$Lk%y;pI z!La@GY*M3E_4`piKVsIrAx!&{8y$S?MU}n0zpdfik)Suwm+boRQ~EpB_gN=~u+Mt# zbpJ=y@q6U1X<(w%_eBS)*O#9!3)OUGGcDKBztP*PzQ4RazT9~ZY$+A@$IMh;&E7TM zK|i!p&G+8I6%fb7d^f$npP7bTrah)NuUcQucYl55{cTTTW%mnW|6cP^3R{+cUdA`h zzm0MahnB}vW%J)K-(~f~SlGe@`qYK@pW^)a?ol!DVb^hCef(4EFxD$$E?qXWx0UpM zu#)S$p>`^K7?ne!Uh@5q`7R#Qfct9prn8Q`0$-?`0pO~1jnis~?KVN>pzuyn@n;SC_Jon8O_P5ot9n9?SdeB{K^CbIt z)Za4c?r@mMe97~Hs{M1nT{f&mEf1QzTD3lF_H%+8vx9`^Ll?JkX5~$TX{G;;s`cgk zo;Gubz~-UC`d4~v5GzXGLES%degjZ{OYqdCu=lZ;-!q5zv#hb#=yVr-X?+}@=XG8S z3-iVCxxW1-n4OU-o4<_tH0w2*m401Bw`rc{@i&^!8u(@hBzql~o&Uu8TXc3k>$56} z#&|EY`uF?d{Mx0}$*@&f-wFul`y2b;o!8W7ySI0s6-ic-J?3-#^Gx_M?UC?&$y;qr zmXXtn{x#?Q<9Po1$0g?=cT^!UT=89cewg2$%J@0TM>)S@{x)g-02F^e4SfcU6*YwO zof=M2um>8=>DohSl08BC{C@g3D9sS(-$uOu43`$k^%?V>cCii%>fBb?zw$2bI(UsO zA*OqI{%tza=e8HR!T$YXeIC$ApQ+U}r|K@8Z>-Ntx0*rHKr!F7C--I#E>EOW3^;$7 zZ=+fiI^2-+tw8r94K}l3e)s0ku_Inr{XTMiPMtms^85J-`_J_r4PqT<%%RPDXGr$A zzI{D!B22g|j=#qSyRl)h>uLVRxT^K#d|TFbg-xwOh5f6euLiOe&v(*eTjp|mG~Z=& z+eL8kkGQ|(+ve+R#NIMGc1}NTkNR8Y4_ghhUx@wh?!Ft~c7L-CCTth`*VBs!vSGtL>8!D)R;u{kvnmm0Z<6aT=KDyN7CU#f1NAto zn(qdIMFdb34y7B}0RCSKsr z2kW=n3scb7o-C}Nt(w@2)lQyF4O?*kmZ9_CZovcKf|eT@@Q%OVG2f@UTeG(-=Fs-J zucZA=kbaNWP(~Ja{Dl2053L5VVd~zrmBBH|UV-L2T)Qw1_FWd|*W3JGe`@P6>R2~k zvd8`DKBH$r?A%b{`IGOrRxqP3JE`Z)Iouxc{dcY(Y*OmC=zj0BEt6P4^DFf5>gHA7 zU+#Y&y%_{sN5l!|yENXN!-5Wf75d*V&#VWh|Mm&<>yei0Sc`Tkv~>vYKf(U@gv70| z-~YI5z6;j(<>7?w3ihC*692PO#ee(Bd*D-c4$&{=zdz>RtCuEwFuyHrcBr3ZkMnC? zo}|OHnU93$!^=mgu?5Rp(o=uDC3}2-lDf`W_-OQjyq(0?$NXPS{|*}F%KOC^asJ~` zef+e|9oYZ!FR|aQn*SK(xvyQ?dh}h|A!&UR#Q)5OpJCe%G5@pv`v`^)8q&%N-hYPq zf80-#B`s+y?0@0yI#QTFe|AWh)$Y`fo=f2IE9U#OXHTeOBIf&%sVNJZHHEsD z@%&Bz;(Nyz3yAI}<~t(aifQW1r6-1P{l`Z9{UOVPxsjjWI6rk(aNL8LE2vm z`Fw|Uj~(IUGcn(v7SCYDL)OzB6|s^%=DXN^I<$)mCA;$Y{=oe$e^#$%!;UA=^#d16 z_BekwHew!3=o>}eP5E2(clr77J`EFC&G}d8m?NtB{;nAaw_L@1Z(W+gzQ4OEWY9paKiGeNQmYhnTIzU@zah8O;g>D5lD()u`m zJ}~D!ywuPU#^(dK6oBKc`gBd_Gm^bF()a7rHCR+=TjBY$^p|hpdcTI$e&BP-J^<g7&a)J3)bUgPdu z@EIxQf9~zwte43(dgy~*)#sP%`^F2)A<;2Tm|tsnH=bSpdPT^8WlAuFkKZS|-x%{B zbYT@+zaWYJJjmy#WBwhQM?gp4h_K@xY&&9UfL|#6BNJa=3Rx2>@NxKp_+fIdY?hDpegM%PIdikt<76_VX8yJ z&+_*l&d-@TzX7ug4QP!qAgz!2A7o#H>BWfibGpa#;rF(NG$36y|KHZPg*aC+|I<4+ zX7ATp(7dkv^I`rC7k5?GC&lsmZOiVgndVfQJ5x3PhlYwSbXd+DC7%Dt})_IEuO!JE(UHq%Rzg*uBJ&k1ro>%E8s+#X^Tb6)!a-4Af z^30L(OxO0hkngK(4J3Gr`OZ%YWNUjRQG<@E`5roLGi3Y_>wE4&bGBf|9Qx_4>iB)D z>rQa2c~O=>$NE0ASxt5^x)Xis#QV>+QU6;pq=J#dW8wWt9^^OpG%=*vLB3Ud%Io8c zQ?uYjOF<$ z=K_%b{$4X5X4#7QZfy7p^t>C=S1q~!j`?<2q+oqB#C-pntDOJRtr49PoX5XE()acg z+Q2TIQNsH8*jL)h`_nBbRQ0!FzK6zlf*02(lWSp|f875%U``j7XE>FfnOMEQ<@#PL zz!ZjU6Z`k`)yWSPGrx*YIp1Zi`oo!q3xs^HZ|KM#o(ZA!&8;eXIp1dE?BGQ+ zG2bpJuIe;v64OZ?;ms;2YzS8@%x`C%h>P01llQJQPukL{#WmluJCc0Sl_4E zErjL~al-Q@N%dmcj_YE+onRI0JHAg?|E|$qpOwFX|4^|xZa@9V3xg|9m)^Ou}&g80trk^(bhACp#9^P_Qp zYyZ-(Fy6p`7CCbN9mnUL1CBxB(vPzFjF|5cYYHGKL(F$p!UcGA<1cAms+#Yx-d`Z{ zw>~Xhc-ZQn{!B-F=j?j{uLo*Vtw%gQ#`-@o+FqcLLr z?laLB`kWWX-`_9pVlhu|2=%#slOSk&UCeL$Q@fbQ^&9j~VhjHJqxjpPNf<6i!aLNCo|N)I^9K$T`ufI=LT|n6U6V@`bpq)Ld@^6 zy`P{`(}31)#`!fw_aoeP%z$GTKg#B(V}8w66++?IW;C`n_rFIXeQw&|95hn$`{KT8 ze*0Yh0(U%HQlqXJ((}Xlbzh@<&?u%Z-S_p2v_AsSeAVMOpF&b{L)yla>oe|e>3IAn z3@;Y*+wAreSX$YDzH)metv?d+`*?x@?0Gg)ct1jeL-kmzFJgV(oYxL66DOj$!THAe zoYJ&COUs=?Z(id0H-hqS@58#ou#qsyPib3!sVih^%Q~mkm{Vg^>hp|=tL+ISbJFD#F{N`$n zg#5Bl;e5vL;})>PFA}KN71jDY?fq1ko*zlpHRbCoh}=KViVI~2x@Xb4s=ie^$-p$e`J)%7>8cF*{f%q>gUI*(3 zpAgp1PZ^rCmJa?j?xclekMnPOv60{qa#7a5iur$e;15)KccM?86Up8X@xLZ$5A&eaHMax%UtXmMQsv!Sx&SueYrX zOzXB2=GU91Jc59_+O+N~9)Dx~?%!1(Zgw9f?2n1wRF}0@Skl(koNuh(K^{g>d#ad! z^G$78&ks{*cxLtQBlpiAwCD=QR*Uu9%&a$yezAbMEt8Vy z<9AD{KEK>QpL%XGylEOm8rt&pG5;5SN3zlFuF|QQ%_aLh#J|%4PdNHY%zyjhVCFwx z&Oe?HVR?BeOu8kG&xbe#vqgK4(?e(KTJilUudk1~9t_LK38DY~D!_~li1Vk`FIDsZ zWLX4woxLbKUmB0}zutr2Q15YPn(M^pL*$|PZr;!1Agb^&X;9AnKg_?4MFErswV++K zIR7J&{&#qt21{)}k;lo^_VWI9{aJ5e)K3GN?HI+sKhl4nL8oDqtAc)8`a}ACF#qe6 z=PJX^n#%fHvHs`xy$ew>N_~#z`8({t?_BW!@*il^GvQ~Y^|Ajx=w~s!?a+>Xi{^ad z`EQf2--jPg$~CRI|4vYR?%lpQG|d_%>~Fm_wKjWQZb9Rk@&Awc-@m6dxYczM*4M3U zl=D5-O{RsW&i|Dooc;B6CkVST;W!<7A2>PO3VAEf7t`Cpr30v4&h#4o2@`aAaD z|0}Rz5wk*QO3}?Kd%6Fp7q|MOt*G1XUu}Ak4NWMtXw`rui@>ec{=A4 z^KbUE33P2bN?2d}-AGe8U(u2V^x^iH?^-D>VbQ=TBxXbP^HG!4&wgFhXI}j#(#1_U zf0*xz0qsH8(OuTRj{W=XgL*QPYm2Ct=STRrzcAk(VcpPcAnr-pF;dh3(-;mDAtbl_5ceg)Up ztzO@P_*Xi#k!(Jk{QOF&*KKG#s1bFtIWMh``F7~`9t_5c^?gQ3Be?!(lyH8V*=u#y za;&8=ziz4D0_>MhA;*<{3jF;p=X>6PX6#z@1R7z^{Ts~pOP99F{D@e;&(R*t)Mg1~ zM?OjaAII;@dv}3Z%l%031l93-Sit}`VR#4~zfrY*$Mxt7*+Js`x_N~ab8NDX`W)qa z9) zJva~s?K~lz?=(%{pBZ?k({o8{toZ(r^PPHcJ$yWHiOkmE{tM=Nn$>6UHRw!j`*ObV ze5b}N8txx`ESv9y`CerB7@CgKr_Gr$=ZJbuUid&t7;(EN`MJyMhNgZ=lzvkR5+M?30t zit8)Z=k7nXVbj3T#Hta0e)#^A^N-b-v7@E1{$1eM9J+pXBKn`I|G%8y?t^rd{TCCd zTQb*A%x`|JHW0Z%tj}8`dawtHD`s(9~q)h&F>0JOExPogtp01 z&F`w9-jEQ#N;rSDQg;Ab{zRES58NfKkNMSmJOI|Xgp!3Vs{Aj+?^j1hM#*+MSjUZj ze$?LzogJV0A^!rkKd`wr>ON=`1L8I!E4?B)EX99{<(GA@zV zU-|wGK=HR%BP&^glk9onOKH)>-fXHeA!EGZu4w#`7ZYqvfBECLB^I<}h??7(t=Jf3t?thyg|9hEnCUl#kPUEZe3-kM-(`|VCO_%oQcR>37 zcz#T(vj4n!gGNGry%cYtZfrZc;&L@#^7&77mNbBL-;rl{2_K_ODN7 zHic)m<@GNGk@GuPdB5Uxt;y8pD(4IH+uEiTG@j=!J70$V>ty@x>_%t+wJqlJIk5iD z3NZ%v4t~P;Iia07s}mYR%TB1~*T(uk7_)Gd@cj3k&I4HZfG`TiaS}h6UuSzuIGroj z-=qQ4m`6e)?bma$WRLaN^`0GgMT+?y8#NIk7sdmS0`NAuBt_1yvojh~S07|s{wv)uDGe8|wFua3EKd!(-mI_`$eM?cB> zS1_MbXWWF0p%grwW^k_s& z4Eg8B`r5MpOBlLG9RI#d*Mfz0M+^H;G~WM$pae@gZT$cEdhd9yzyJSVW+{?UXpo(# zL?!cal+qw7+R;vFlhIPBgtk#4t2B_2%;z}=k!Wkv&@N?^QcC@Ne(&ew`Fx!3<#Aqr zKQG7Q@qD^p&+R_X;pcN)i!#dW*4OtL?B`^CYr;@vEK#%oY+29h56S1R)dP`!Cfz^& z>Sl_go%etxhOB>0^7%Jh2Tfez%RGC<>Ngqx-a;1G`}IEXDT%+otnkoC^zBawlQ&!J zUvTr=Zy#7=FfIzrGG^yT$n(tym2~^pjR%+&CG7Vj{p0iF=i{MDX`p%(fBgG*%VcE! zEt+%w8X5m)2Dl@$9rXA%W%VYkvNNBfpJe{(qQY{NxrMHuCY#sdK*=1i&{d?L1fK;L z{m_D3dVKrzuQzsWx&($RvHmZ~XRSdPavoF7?Bvv+$!;foSK`7Gv#&`*V4 z$jN}t=Y#=2PrG0iVEZCwhAI30|Brqy?u#`a()n!9R!0>>*HG)v4?KtC zhs#31@cyj+l6*$})WWZ8YcpZjw*Cg>GnBND_5^>#B?o z_HMt-;ghT{{e0_*uAQUjpPs)9$J2f5fR~Au&_2ohvclR;XzhR^>iH<;6INjPs!PE0 z6|0}YgnsUi+k=)e)yz*j@&3ocpU&qm zjd=93?hEs57Hgj*pFR_`@X0a0;QqGvET8t=`+FbAXP~xsQsCh%@%wZ6d^)rmjo7FG zUe)mPX>|o6t8vO;%O^2^-27A8iaMmL(tZ9>D62nYe7del7QLD~lbT<`reD#|YI=T2 zPFoQb9;fq}F;W3{4PFRL&anDI>gRab{%FHnx_-_ZYmC=i3I(AX*zZU3d2`GVbnx6( z>U@^rMho2UTqL-ib|10vEw?_jYS1v0Tu0|~v++2*y80mSs7V&CC;2oC8jYZK1n2%f zQa>k~xZ`+}v*5k{HsN~Gza6ujLH@s@IrsCDeBM`fK~GcZ`Z>LPH8$DA)lZU7UxS6H z^Aue_J>TuaS}*Is1Rs7rhbOK>x2%e&{_U&3UbuPLCGaSmpHH7-!RVK7H6yi>wQn;1 zJpOY4UfJve*4pe9@xiVCcy5nC9{zMbTYIbH=sxSf%#nHQdO|r*ClydgnopKeueF zLal|GV9_XXeT1u@qjRNETH{RW`QVy~Ur_aJdVMEqTyGR(w}|84lKOe^s60MoN$1mZ zpb84E_NLBHF$WFtJKZpFSESDjkv}S2r->}r`Z0@+@$2WxhSB(h)cW2BrLoX4Es;|3As6)3&K7;7tp`X?f+mTX6HKQoHUz;KFL!Md# zu!ZqP(4z+%f0Fm}#3+WNJGY-OU2j?aBje8kEp;4Iwh8E*yCQl%w?AuLXEZuHx0%|X zk(;B5nMZ!W^WFz`J;CRUk!O*-f;9NLl>PsZd=6NRQLoqPz)F&z&u?Q3QJNRszwP=_ zj(nOl!Fw-$KA(@1M2`FE`nfCbBihqM_ixQidZE-Rx_+8W>4{IwSqP?O@$09Ss}lO< z=FL1;V)c>C5BZ+e!?_w^KwpCW|B!s%xIO^2tny>p{P_7)v$wz#^N)bZ{TtB#^potb z1i`xK`S4KYoF)7FlYFMSTi{*Sj(~;oXN2o9G2c`=(gaO2i{Q*RlKQzJZW;#BX<))$ zHvS~f?>{taJc_(S@2?7fGYR#srt2rT6NwLW~LQEBN`0 z?^uo=cKf&adhG8*=7+Ln=HkyuS)l4MKcCkJcYp7r^!W4G5Oplk<_BJlixBcb@|k~r zFM3_@gfqWL@`)y^;WzU(fs#oqpAv+AHcvf$+M2 zeKhxGJnC3}Nj}eR8H#m>hJnwm?DI)J6{XbBa!8LqcitS2*Nr&=F3)%`TI$_JUG%&oKpU(`lvFL(z z4Cj0iQa`glZNR?wE5WyPRpIl=`b**Z323xIGWGt;IE4ckU!?OJy3!S$enj_wSFW6g z=TFE3GcJqxCGtlhN4=1zDV<*oXX3+EnIK({pWlJOTTp9tH4`2vwtsGXT0PMNFUZOU zqgt+s_~H7$RpUd^p1w~x{f{KSA65EcU$6nhoMPt>NPb6TA4Y#pH8YzF#QQ(DKcX%} z1^)}*0=zf96Fy&p$RDYWNkYDw(x7;v`2D&3w(M8O#ZlY9S-HN<|MY?6H#k2Beb`U; zfA4%2pv3q=ARaY~{{LM6_v406c&(7GuUlWfMAGAIL81@K56N%APbu_QZ85Xjnf?Bx z{~K;8g`@8+1WP5@^(4PJKjl%(GjGoQ@+7}cOo!m%>S4gXLcE?kU+7!c4;@_TN1Z>~ zwr(t5yz2yLPUGjdHFFTseZcK+BKhsT&m3P=j0HIj7lgkbsjma8_0hE*5uE;IlHcT{ z(WrJhozI$IYw-Llm0)EsKc8cfJu3G|W-70W=eM}$>)I@zjy82(q|Ofp^>@dq)AGQG zi!6T(!Jq2Zh3M@rx__%==8S93W`JayJuE+jfBVjJJqqg9&*lMQ`{nXC<%cSc$qWLC zl~Jty6ZcOxp4g3Q)SpuQ+thiASTAY=7+l8kN9J$u=SQKSz-DTFB}KO%&b0Fd@{(+R zh~%$bF9A7?r~9|-)~n+7>Odg-LxGpSQ(jrftwj6dEkSZ`27`xjt-Sm# z@Am^%EtthKk@7&fNXzr@Toc=k1!Gfb7gx`^$t^*T=i1ItUo^(0?o0(8)#C^}z-rc-gpxlDjt_lSO9ZvUX!=Mm_^X^jZCvfUM9)Z_;b!?Cp6R~gL6M5*?*8X&JAC^oCo?fvHX$eYfTwF z7tP5l;@nR|`mb=(6nykm1{k)0pTDA0-str?I)Cri^v4s-cY{SLqW&GCeqy1%6G4Wq ze`ZO2u;cMfz~6%PU&-_9*Z(=UoN23yUO7H6n_4eq9XJoLJMR`vGse>e|`6}6+Rw3 zi@77}-yr*ktlb}@%zbqJ5-)ebTt~Y8{T=@Y{rC7A1{gc^42yjLhHUmj$#Le*bl9-xWwDtD4jQN9Kom zwkTnf_8p+_Zgzf->>rXb2t=uq>H0Zfhb(?^b}hJkK1cNa-2BkaW&4rQ?`B56TFejE zf1R#48J8^20=I7JiS&rlt-t+{Hf<#O7$Iu17i|ELMR)5 zllL(`r*SCkg(7_(psr?6SJrwctaXUd%EI)sxIa^S=_ETzqkm+VQd?R2p zSXq39eSaeVvp+Np^_OX(#*g^vB;3)J1Lo@(@$%QV@)(*nQ5pmrh<`t>evZ29j8}~> z1j}^YMC-Zw>13UTmPx1p)fN2wP5D`fybtSxp1)XrNc~K9eh=3t(*4&3D{rGFMCVU- z`8T*dlg{7M8*Qk=auL|wOZi9_30c? zU0^8EKdyfI#vMkJr_%l3fB<2d?N7Mc zJ`Fd|fZ#;BqVV}7zYAMUQ2yd%Cfb=_UsbaUKt2L)d428w$4?TGKWdyX87*m{_b*Ix9*^I@&j4=5EWf1w-abADy*8rjulx)- zoEp;2Zx}znO}cB4anMuF`Eq3bR%e(Lepl%WCeJJszCW2iI;Izl^z~Y(^--f-JG{Cz z2V}ML^DF%(3aPH7`@hrOy5}R^^1=BmXA%Eg{nd?2K#mG3)cCa_B?nbteK5TrKffzC zJcDC1W>NbW3Z7J<^=fuN@PnUU$G0D#Ac@ZJti^9pcXkI%N%$$Uf3E(XTl5_+ja-5@)LWYu{!?Dq$T|Nn?KkP$Dq?7W(S);Bl-QXP98o zXN+fF1>PDeqTi33U;5T)gx+kR^ZR+)B>Xx`z~PtF-w{O?Xj>VbU$+jI5GtrF^*Qx!1#@3SfVrKw&;~yz{KDYjoSG63S z&!*>}9Pj)^i;iyrS#t~6^@RWISrmj$Uudm}wfb_fM}N1Fe}wxV-JJXwHvOE%gl`ppKhE|nG25dYX&BM@)?fM>e%Y~@bG|c~A6^vo0@=g)ocou^ z{M29FRv7k+o}a2qkj2{yL%@u!EZ-7Df70jk-6uC#(fQ77(#7q|lfeDOY<`R6`>2&1 zs&}LN*B8(TJfrJE_xVQrd{0;Hi{?p0Qu9-<3&vsHt9d|RxlhC=*S{XDp^3Iv)A^n! zy%YOI{RFFqSqaw%6aMv$TYAWBLNfJysS(cI_rpG;pYJ^Q^eD9X9-VJ}3k!^AWrNR3 z{PFSl>2}E0qL}JmJAO06Q?#oe3SJZhlqXXb`rfm zV$2vTjLfe9i7*#leg5blgB-2t@$t`d=TWMp0k{wN`E~eu4{lg7i`xI2eNTYgt?2x2 zNPiA{4E3bWmzSy5BhSbMpt6kRkL36Fp-)gjX)QIsJb$+oHoP7JKJQ@Hll-o=?|^Hn z=<#u)lP<1IP6dGmtbb1OTV^heTDFC9&S(CA{Oga#IAGF6@N^LCUz7Sg^-gb;JSdWL zegqjGuU~3`KVQ8J8a}i9lKo3He*IC~HF|!^XonL{`cw^=b^S&BbM<+H`%n~?naqG4 z{QmU>4<~%4qMD=6WdEVZN)zONHG^3wI=_O)nj0=2q6LVY9s>*rys03`W6V+D%cRuxW|0!r~=yhs;M89J{QH^FG!0TClgNgdk%VqP?kb1g4 z-w$j@uK#?2<|KZ8C3vO#|>#)W1OHx2|>Ff|5sOGt3`;{Y{)ygoaGC14Bgf zIb?p>e8Cg=b_|_gL;FX_rS~E*W}(>s<@(q1``*HH`D>}?v&Oo1*LN#JK#(Utzg~;l zV8SyxzjnIX*n3MF$eJpiU*PudhrgCUwhQU;@g!*@TzMb^ObsX(@xzUeKlJR0UggsJ zn{G-vVoSFg5TqO@TrWY~f2eX*8TBrt*KfO8m*EW6Pr%D;q;Nf{zhjmRMhg?^{xxiI z#0MtUQu!S_-3X=Kr}MkicMJ-jL)X{fzs7j)iA!L07hC_4Ao9=4wI`zd)pY-PLRuU0 zHV6Q(A4LfHAo~v=GVaLk-&4-{%Vhlfc0~(1`q&SQdCc-j#=p+1y-`LEU0;K5OiDqi;oYeU18QiZ##Wf`)lhdG&SGnnTEOGClrPD@aD#$_C)@Fn)c# zYJMHAjiBqRfBa>n`NozypL(ja4!%xY%sKyo^pAU*)}b$Qi@}xU;`o-!r?zAxlt1Rf zY@WyN4`lpn^`;ZOcoPB+gz@tk6ZjdfNDiRhfAX*AV7z(Y86Z8HUC$8t=Y~;#px_u? zUmvxZ<8m_rC@_8?;)BcQ$(z#1G&zDh z`^T028NBPqb#PvDfbjV*3IBM@Uk%jwfu4V!8n1^u`(-lm0`~VM^)sq|4OVUb0X&f< z%LkF4IzGe<%^Y7$oqsb|9*O_-D+C*791yMN>gTc~dn6Y`=kwdPFQ`{eAQ*9h)lbs@ z-Jb7?K5eLHc8lUSlFy=oPiS@ZR&acKk?{E>pKjgrxl^j>e5S`6<9x3?p!tuj50U*9 z8cVmM)0y=6HnX2GPQ9HAto-=-Jh(6t#T`=t53Y#$8>=MyJF9VQrK>Rs3znrq9 z5-LrcO^shS`evio<+jxG5%0y^hOTy=)cz)k?)mwlZHvG_(fMl<#QDgp1ohB=h7Y6P z#l9cOXMxLiG~zuye!c$YEqvY`zsmMv`5^l%ynbom2hnH1@`o&+!S-DJtbXzXo+_cw z*Ep{nji)_Dz*qgTkdI&@KP71(i9&wR=ihRdPr?`GKLB?oBnj7(d~ROV2eo$5`5ar~ ziD#c|1+%}K3)d$ReE!Pab?~NL3|3rT3@-9=-MW#kx@21zZ{-yfZa#ufq(b;`Awc4jz*-b0KcoO{gd?}nY@!I zXpsR}%;~@2@;l%Of=ODlsrhBMqZg6GWm};Ah2?|ve{EH+!!@%OGr6MvVNzdD{;WnF zV-|x4>-hDxrusg->bRDAK1<`7X5`!w0`k_g{E_kNT;msTB;HD$zZri~4Ikfr285ho z*OUBiKi2{schdde<1MCmhZ_ch1N{8@AM1khqar!?1C#nHSO)O#x(7h#Fh9Se@AX9O zlVdse3zGHSPjU0`z_?bR`kJ5LJ+J$rSeInxa=H$l^*9eaoHvFa~itO(%NC-pa zr7A$}9zVZ7kH(<8+v)myv#=NjW4eFb!zCRpF6o}ndBxA~Hs`DGN5W$2d}~_YtLVX; z#Xu#PpWh0%J21h{he<%}`;+=xpZWov{}=**E6X3r?-u+7{%ze#oo}tzQpQWJoB@Fi z?0S;lFP}fa0V<(P|KsBKH538<_VhkXDg8H!SYMSx7}CIB84e*eg$8K;Pcj(!8Ug}5r15M=iQuz3e8%X z^_=^OxcqjX41vOaZ3fe`-w3}y8Q-?2uR+d=GJqR@aQmwy_iE$w@>jsOk8FJ?n5YlM z&Dn#(?x=t(FIf90^>=yYQKY%q0NAV)f6mq4=(qXs+vQo*^Oq!~QjtQjE%koSrMd|E zZ>8(+=K%-}^``T?PrerZb*1y0)c6YN_Y9@he+Cxahn3O()c)i`M@4)whOWQw5?;f6 zzfi_aG+#mHkJVNhW5rojpvL%xh#zizn+;pxPK`+F`4O58<8WQq17I7&&+oDN9wafbB_Gi4Q zFvCr6Zvpian!NmO^4CTM6?FgEsY44#jVK0L1tR_k|Jg9s6v@fgFvpYF_b2Caoj=ac=(wJtVDdw4yyKch586MKKo0|9;c`PGkeL0MZ`8A}`S^SS))wb8_D zL-N4H5B%}(L67BVcq2W3d~VMm{LSbJF#E&Lue0h-B-23W*J+#%{&u4j+&dO1+<(aW zuC&e}q!dfn=Uv7*@ZVKB-=*z|C||;k8XsHzE`q@>iGARWRYtgY+I1kmxWAAu za(*babs)OEqL|vh(KTBGmrpJLk9YC=*Rwwxq0CQo|9Zq=HQdKG7i`;IEqp%7_ojq# zXhje`J`M}g#HY^|f;C6vg?zju`ZrEnPC*~S=zK4W>yOOv?r1M?;y318+c|7-T(ga-W1P}dpN7K7t1Uk&em_q__=h01&-_e97x^O zXWyU5e`TzfLdgPd{|3o-=es`W_i}oEy4Q?zaKQ_)q!%XS^wL*>xu1EPG zcLmEY*?*-ueIt7Pl+JJ1ObuL;SqgL~^6RtL!F{OejsY+!;pewCDINZdnoXV0Js%Z= z4By)UyP@oQGXJ&F;}Tptdoi=D55GQxt!GfuEjJ+9>x>rFPJ=oa6H}rzU66z|L&s4&$q5O!-LD|{60?xSbE=gFn0Pl(et_e8-jwr z@XrpqKASytz`a#EsQIs9f}ZHnQo8^B>6tEmQhgh=4;g6B&WCX0=M#rjP@lmijGs2U z|B&;&drkV{f{1*OKX|`zJ(<6bn4*Oyb<+EztquC%_xU*>v4-WF%wLzPn|9w{Tu(jU z;;G|RH2h@%Xgpgid_I}K_QJNvA)cQ9D%MxT+wCp`r%n9%ugafpXuB3&pO2sIi-QcV z0J$1|zWYq}Mnm7x`EFdTil>b%1?C3=g!>C7`YWA}hM>(441oM4mQS+3BjiU4yirK6 zPYqaj6dmeg4+e|+yGXtT`4?dHgT9O`TtAiRivR$=4qI$rrCz;>5=bw9i1}d7jk%Xd|sel=s3N4B5fN@D*$ncv=AT!93OLqT0JKfk8i3!wUl0P6h15a+Mx_p?-xe3s>x^sjFoy9!I& z=>D~GmpXQ8z6A<)e-QD*)o1mh+i=x3di?BfsfYJyJqKeqofYxV?T=3U^8%V|qwDhy zV2L{|e}S~G<3-Qs>T{uH3*3E~p5Jcv*Tn+{KBMyMu|fisT*zeBe-hglcYf)6xC)+l z=o+YfqblNytIv>OM<78JgMhT3F=RxU-EOo*q7gg z_DAZk=l654>Iz+dlj;S?Z$l{PQ^U`%{FWT(aEKlstL$w;L#L*J5=&8kG|?Y2)&;_4 zD3o)5CaJ&Xjsx)CUUgt=Up77<I=?!q+IY#V7eLxMUHJXU{*VQIp1@Bl z>G|!bN^^YvMkhG0Vl7-x>hFu1_pt5~U4PqrEbyo+zp4CIwf%&7XX*Jb|8afs=$qGo zb1(k>kh}V_Xre(0wZ7~;R0{8Fy#gNeX5(klzc&7(gvut;<7c%VJ@C|Dc_78OM#wK2 zKYLysjP7VOQ2V>QhxEi&?*w49v!YO6Nq$#dH$l>hZH&}~SbbeK@%ivdO#lV01R^fUwzpdf9 z0a^c|``63X9)n@;XHoCR-ab4GwXU@XJ0tk{PTU_4mmKk=-cPXI`UHw{SO|=dvwV_# ze=kadL#yfe?Mw3u(aK$+!0`#Yp3HxxO~`=n6X<-WMZG~MCZvI-+AQB>e`fCcLWthb z=a+zm3Z4{K2XHb!-xfg?@aqn`e;pe&2#54+1Yrlx@$xOWd=I|ZK6@7ekl>3=tt8luUA=zQN+lEmrXi^1X}BSn02^J7{*T`V7YQ$I@f=(&+`;q$mZ2v(Rn>d?#zh2FP zV5AmE=hsdt23~mL$?RFj@=eCaa=y_ht#vUN9WKs~ar>*+%}j)=hWk+OzdfFlgLdtw z^SjOLEOh+n&zx#v&yOYZUri|u=-r_-aD6w+FX>G5&RXG0vdvlE1s@%NAH z{XczwMd$b01Vg-W51rr2`Va6>COyBsq(&M?sa1jPSuDR~eQKTdZ+OnRgbC`+pa0tD z^&LHwDgf7dvieNM&z`5{klc(K>iHhC9ox{2Z{7MV&+?nZaQ$o5U={RCwt?zjOYHiF zvQOm$S=pXKen@@?g$zaMU+DgIt?6%+G^YeiYh?K)>r*?kMk5_Z88B?Om@jVp{KMmS z_x*1rplLThzq5)bp`z~i+2f0tA8!A3xwRL%VrSTW{|fs#$!~paIP4rho7z7j*A{@J zF53f}TJd_We=Xbp2sH5Zq|Qg^eK?G^nRYqv zufGc8li_}s0H$FAfBssn=R@@IZW@q!#Lw@&;~8-4J9__S<70U|<8gO>N?v@v0GHq6 zC$B)KM7n=Hf3Y&Yx2_QcmhtmDb7&>}b2FA1?$6pkS%3N`ITSnn?f_RFS&H@#ZhTzO zco*I}oy;tp%-RpBzxQm1;+O6}sroy2cO$%;PS@X`-V(T=suD!4<>z#y*fdX$^H?^zb&Zzb|JXC<+f1&Nq+Y*@Vp`*Xgc$#05*%UXVZoh(g}$8s64D@*+T zTz=0U`G%e!F6s6^`T1>0WzdVcs$gt?c0H-TN0sKG217$?{n+G0D6H5;&u?wg-+=lg z*#m(n|HKgI^Q6CufF7n^)cN5Q(+FhO+moulEd|G5dojI!+!zp#x(oxs(VHKI_A4R5 zJ>Nq%=_K^KLHD1Ne&0ll!Wqy{yMwiVB0e_geHQNO6GlBhw(k)+d;mNFA-CE1p3F~= zx4Q)6)<#nAKY0JV4~{Ks1dG4(^V@f_0PeUz&u>}m9f;?2_ir|q@aMNSXxBjNA9VdS zDj0}sBIx=n`1crgzNF{3Iv#c)_t+{B-NnzZ!}X7F|7^PdysYPYRIF9heLnvIA%7CY z{BUjDA85RauD|A%jmW|OGU&IL)n76`e!8L;x;Ki>??UreD1^xeH?sNtXOGSOk-26Y zwf}2E*GFW&vjl{;^79)KXn>l#`K9Hz&>u_WV@3CmP4Zk(j1@h9DWc13{SY3I`X}gJpYJeJ1%Vopc^b z_KIRoy=46d(m!5wRRIsM{tSMUWwZMWF(173Sw2+ROZShPM#S<&#nWn71lk*Wz+drfIK9yi`e||o#1~tN` zQ6y{%WtJ=SXdP5jc3A<&%tW3nzbrZaH*)y|ds6+M}M&$v>0&nqnu7bDAorznaw7f^sM1GLg=2FKIvcCzh_SAAc`I?E-tS z=pxG(sjuIicf+O2yqG&T+0V)N)-g92jdiE{$J^rf!*hMtF|_%JQGXAk)>GR+gM_%h zi_7n)k%yoli0&UJEP=>l)EVGo$9J4QK%O8u|G}UMW!X4L!as zh>*m$54-|r0?zaDTlyjkUMr#NYZUB@9X9_0y0`fC^;Kgr)HO`uoUcRr$JT@XB8}}0 zRDM0TSHqj_bbXzd{01%dsshy&{QOFNc?4I@FQLvSrncWlX;p=wpA|p94~srRn;SJu z;x#cp-1`$um)=EYnfc&M4O>4V^)28bM9}NQYqFoB(O3Xv-n#ShJMOD7a+^ix_ZMVPoUI|J zKTCok<|7{Y!1Af?Oh>Hv_v4gzC364FMw++j`YY8x5Qe$Y{o@$r0Q6>+Cy>9+>JzEI zF3UsU=5%_0meu+wG_G_fuzuYvw10*;AFIkJ99GEtQ}2&|onC-GFFym8ZR6+H=JGMP zPCATwex=H%c2sq!0Wgc$^`!nD8g~jRT%zZf*SbsL0Pbahf2hm@-y*v-*cIT&P{nIapmci^V^!m`v+BWnOKLK*Xb?k-b zyAtzYukI~H6!M=f>)cM1>MeESe1)d-?lb_G4*SEo?U+D4cpPL6z;i)|! z=(DK*(VnZXLxV!#unqo9-eCUx@t7l*&^C)Rz{r5*i_9PQ2#JCZjp*^~<|m)fzdsG& zXAQfa`6BDPBfOGf;}bfcOJ?=Ox1Py5 zBtLZG<#Tdq2268LVcriG^Ud{-r+yua`x%&U?pN3kxc4i_yex$0e$e@SoAwU}%b8*75Th67va4!3L%rvV4*Gr7erg zQR>?(;PWk(PYEKwx)I(RP4|Cg+xMcjZ=vAf1TlYHJ`Y80gK~BL z)cJmNC>?!KIRhqtWc^o?&*d)rV8`?@>is9DT3(=+2@PP-Y<@mx)gOe6fUcib^_^(0 zZU@+1S;)(0aqpARtb#s&v{t1Tp4?l`VZG86UOp#mPJgR(e=7{|=xKT!J|ze~ zdt_$AlZsi?{;4SS2DI$KW3Xr~Kc7}k5SneJ`@h;#s!-9~3UIa0Q6b-$m@iyqcnj)l z)G{L_+5Lsg4?B!3L7l4$L3=4XUr5$x_td_CGlJ;;Z`#*#^g$7WK`DKO{E_vY@x#Bv zru}q&S0`2@!!wm2Z_;>Pej_f(A)HR<_v*9$XnL|L7+}xxO~$96pAJK-Jh=WXS-;t{ z$ORrBFq^q8%jzq`aQ)lJS}PRO$>o!bPhBU?hh4Mje3s|WLq6COyza^VeUi^Bg)8A5 zt##D?#^9N|k%{^!|y--cq<;QO;qR0zaSq zz9m4@ZvE^h%i1>?pYB?E9zIc{^XHaZha8SR0ak7N{7t%W1^z0b=Z|ug5K>-zwYz_f zpFgLVO4!w}mbuW(+9%21qffc$V`BmMHi(};4Z%a0p4-4ApJdmQ`uS=}2~v;7AW%Yy zm%mF>n;^JH_itx@?SXbi(fwD)5+xLbR6)lo@$N%z(D}Ud(4seYOV&(8#$iDEopZSoMZq|IX#kht`VgsPlO) zlq?`ycZG;OO)vPH$I_1E(5w8{d>u9{nNIvB)Iw?y}!Zp<~8*0=wlExoaHZ= zh%X-v&V--O(EA&PWaXpr%~wI~h-3Eui%%Is|8i!QK*c__j6TQz{Og7>RxqxPo_`%6XN11=W~luMjs_E<`6w@H|L^Z>6VS%1p5Tn= z{sU6q=IYOYS!MM4$-3m#$h0jKT;s%lT>tap#`$o@g+ONHNHO119RB>H0SN z*J|jkOV8g#1tE0k$y0E_lI54=&o+N6JpYG&KC<8C4@lvUw8Kus&);svFc_~AN9|8| zb~g&189?W2=a@L?*Fo_D}M&%^?l07trIo);Sp{zw;`1Y{v3K z`j1R$4s_R}>(@}zi)hrD3J_#jFXE5eACxLl2EAkH{^PJU>FCH@1YXGU`;QZz*TL0> zUzwV(to@Vqk6eXMa9)`VXy(i(aQg@HbtKWJQdLkeon24*hqjr@s4UG83|3-4C-v*> zQZqQOgI<5k{jG&=DAV~VX|sY(o9O;w=5{Lt-*^H^WwAbR`}3}zbcBVrbpNo$dl7=& z{$Z;uzkUTxbcH|VgQ(}9s=Mz-QzpfO6Y3v?`#%}KITtO0%QWczq3hu*sA)t!*n5bd zpHI8jz)zKt)cd#GOFEHhNPmX|A72WePv%#8sP2GeP4xPO^3Z+oi**XMe>P)qPds`p zU7zk)9)ZpC==H@u)AP}(^H0FYW>%lb`SQ)vPC@-{eWIPemhe3ly?uNYxT^5;^;G#h zM1Sb{l_tkj^j)Ugzf9ogOTVH3I-jQVrEudkI`IU7QA=6Al8F3DWYKk~Jc`cOo!aNn z6w>3bO6i}__LV9a7sB#G^3`;?H>xW(1WSzA&q=<fTt<;1IgFcE9>CBS9Jeym0}wzlF@W<(ODtlliNRMe{lz_R!yPS7Z#q`55p3( z825c_d`8yqqlR8Ya@kM8tqc71g_?$=up)!bSN5`#NN-vt$X?3wMf!hTpAuobYAv! zt5CH}0{ELM?!V#AU&kj*gzuOz>ivMOnARJAzj`J$_3-k^$bO^4>^{CqKv8({b_x_@}$STHnk%3>Z%@bfjN zG8rXJss~flbXof*;;Yu&1Mq@GDYL>;yq?=1vp6unJ3jvo-j@`J)^qE3PMy)vYbrgz zxGbavotdTMpm=+XFh7Bb{_&f=QlZaZdVS!1Q7+VRp!4%-VvT2U71}-O*zK>T*5}{G{3X zIqCno=#GOg$I|1cyw5S{I>$&{o2cJhNu|L4=VTHW>d@hTC=iKQ0ocIz8J!GFz z>t~zG&%!?^zA{yg;^%Yg*9ZR;!1wp*d_>>A0kb<*!4uK>UZlQ6_IwX>6pVmhIBS0- zALD!Uf(y*(`8`#O4yfV5fQ1s`^;~_avsHp4eZ8pjOHcbMp|d7lAis#*H!;wrkAAM)>^WpzS3x2p2Ks`Ux!Eh$pyeAceJF@vXGQa2JHyn;%6-K>(DSvPj z(vGF`;hQ`LPI066XI_RA;L+)E%%$_}|Cj9l7#rmZy(gql&#%?i@q)jXW-${6u3_iMc@B5>fSI;JASPjq&IA;lp4vVC&u`xg9JFBZNP7JL-6#b8@T>>63H{iBJukD)Hh?)jov{{7uva|^ueOwXUWs2xCa z+TQ_J$^s-yhG5b;6(_aptIX-ia)yJZ-7=grSY`J`Sj!6bm%-!S?4IP}!~EHJZU z=jTZO$mEs^#3#d;(}Tp%=bnEq>$C+;`cMz{jb!^H$o%rQ4TE6qswif{Z#KV8_8)15 z|TN z*D_Ya*zZTyPs6TvXWm`j0rgK3y!_mY^MwWKbpL6W&R&?Z^DFaPMf~@<`toYharjJ* zt}m}z(%^srYCxT%U)=bj&(vb5vfK!q=iJZ0?cek1_e7u<RaD8$GY+X+GpS--^ z2ozK3`Q?79Z=jKj7kKK%&(BEhuY&7C)>H4-DhroGWz)F&LZ07nYGjwd^B=uGe&pI= zC^z9O_5L1-5IH#5kseY7S;pJc7A>77u*-l>y9t}`0?}OP^<~NjOp=r$6kH- z<9Z6Sb_M(YC;JCRCz`>oOnQ9KPhuC+ukHlXysd=#LE680e|y;enO=XlGpx?`Y(Y^3!gF4a^mmDJ>RVE+*W9H{3~-@ zkNupiuPE8c?isi*WEpBT&ofKjPZ|jel1K zs|)D;amAZ+;Hll+{*^Ynzmoai1l8LDt8}{kKgqrY|5?%XqpkX>pl%-BzbbwC9jbeV zfg5L8{UGf>cJ^Dr;Tn2>K&+uA+H8{!iUsU?Qa^TG`7RjYM7RIu9#hdAgL=?DmEZm^ zJ4nLqu2D>TCBOaO-Ps4WuA%EgU`#eTf7ISVf7wByK6K9_aO$glkEucLiFAFidZrB@ zhS2LLnF_0r>iJIa(V3r*?A505o)%pnB$Ae)&#gZ|c3 z;Z+zr9~DgGpPql42KPHWV_v^v?Td^*Mj!En9pQ9+Sf}d`hbq$b!Q?4>rJtC3HSMt-C4s=pR5m-@0|SJR0ws4pbiU^AUKWK@hc?-rrqp zJQgXrH-OAIe*emK%tyh=o>A2Mq0;?-3)Xel=V|9x>)uL4J5?Bm7R2&VP4E%wCJQ6| zQkdlr+25bkk3f4R*e`${f2&KmqJ-GrVCHXrK4Q-fgcS~@%z|+7{>#lT$$guSCco|g z2{J{Z_=TIF?ZFtq&%0`wd^PcUZvTt&;Se-KTg$;jeY8+NNIo9D9SfI?d&by6H21DuoQ~rzyxPO-s_@XFY&*j5j>XhL9 zXm{%Qc7uOJLhtVDr3Z=5|0DU>u{KT6JDaW_0rF{Z>u@?B5tp+Bc5pp2<(v5Tk>u>3 z)oK;+bGQGb70B8*nV+qCkT2M?oz926!gpA|Asu8(u;+7-`tf~0g}~dHt{;CS2B75m zx4@c~cf$Rhj6XE9ZV5Cj>G|0O&CdlnGvm7JC+zP}#uv>v3LUuu9E#fy3IF~bf)6~j zSrDC{!a&jdEy>5u@P7i8ll1sPBCQw9?v5X5`Bh!hF-S3{101U6*N50fRjA-g&##8} zS%cOzX*rnw$ zd@HK1usOar2;H6QJvZ+O>ml+&C{_ zug9+sZkn+I<*Dl!*Ja|*x%NM(>OAc4!nJ?We^Sg!6qt_+q@K@uw&w#_>`3>Y)~j3) z+&Dm=FYsyViAwiol>U(Dnw+Nsnou8?rhM>!9egd$ZUq3=m_JDu)()Huq{pslbeQk%pPIIAt zBoY4ApdJd)c|AS;s2r_`X1Kfnc6kP(_=S7F*pq{rP^;i8GeWd~knzdZ$Hs8CKAo>L zWjnaYj?S0V1rN9($_OY8TX#I8Ep4sl!%5O$&W~y(Y>JuAWMd zPewcL5ma}sW10rC{F3>t=lzeu6&u5V%oSE&NWKpB+Ap{tLf4nvl?6~UEFH*e@axMo zwWEUe^>qL1rehOyfA#K5|3~V}2vZ~&f10i@XB%${3KUAI=R-73Fh@THx(*+fwhQ?RCi;ul zJa{h14yW^xU@d{#!6)!jNlIkj-2ASj^H+hujUInYcrOi2Yv}piGdGptoB{OsV{m{j zT;!?-tXjqP!_7~vMwajgG6K&z{ux(aT74!6uFj#?_j2M!!RYG@IJJiT`=q`+{^l$w zdqA&$wC-?*z1->bkFne532yq(guKl!FelserkQcXu+6L zy8o2*29J9He(12&25ms{WH@X8Q88$pl1`|VRkV}EElJSu5s*V}XB z3$;DPf>ZJI_&a)aKjbeM;vjdLKmK0PQ6m_4>=~m!T+A;wzJRNr3*O(L+yAxd?}D1{ z_=4tNd428)HG|Z^JPYyP=i2{}08My4nd@Ik5a%D9{Gcg#JdbYwPrvtuUKI@ZBf5W( zwEufwbOc!|==~oRwK}kJEIq#H|I7wEH3NjYxui-SeASkNM;8s6ozx@%Hri!pU%vz+oD_ zKfcArN3cJOJ|C^#utT7Hm)>94w6qyc9H!^+w{?rqelg)6ov++4aPTZ;+!I;*An%Vc z?Drlv57Bb44*0@r|Jk+21np7u{lD&2lE5>XZr>$Lw!jC`{hO*!u+htEPDJ<(5?uN%?Ja# zH;L_+J0DVxWd! z==r7CxB&vo#dQDX<|tjk@DX(X=9ljX0lq}HZ_fa0!P0wl`&Mt8A~1BL=ZBIrvf$a* zIu82%zX|P^?2j#SSRKxr^*zhwSLIwzxa_`E>s{b9?EJ_wZJ z)4_5xe*3k3QdqiW3*A4Dzo8B%Ceioj4)2Q6A*%HJXn4vrR{tLT#jio2E>Gm7+ zp{;b_8M=Sc4kQH%s&xN*&;u_x#!bh;!|E%q{ce+05R6Qs`yZ>;X$Us$f5xbC_D8ON z(J&!ocb* z)_%$O^1zsZrF8=WsPpG5p1KJJ6{Z8ph5Yv0)W@*&+#Y)WoN;HkU}t3a`DkVQ{zYL= zv(gzm==~F6hwVz!o$3BXz4x@z!$;}on~mB$ztkp%o`12}wzf3gobErDw$uoIjM8z~ z*^A$Pdo=7U-H=_&U>nwc$o>Y!lmn&parFInw_IFls^mB3i0J%dGC!i&m|kjOLidlQ zv`b1`qSQeA4EFh?{eJp&uk?Kaw?0Ms$3bJ`tP(%d`+s6O!mV}w(f8j=zmu%ynJr;t z6j}Qw{fFy^ldNyYdx7Ko`Td9U!RM{42Cbu>&*_~Dt$TOZr+ysbw_kaaT&p@8dj2tS zM631Tu5_@og5Q287D6lC74-P9(|U-_kGapl%CjAaJwJn4Aw*0hk^in!osEb?_>^f8p*TS?m1o^!aKRxz#o)Q*<1(NATP4$>sg5mo25w zS5FBZVjWuejB(`H7kB@)$TYS7`SmOFb0uqkr2W?FG1eN(WkCQGf6n!PFPw03&3lHPKd*EeXsb5>0P7moK1u(fpvl6fxr3hH z>%44X`#jGJw59UfuWyx|&2!6j)cZ%X(mia)`_c1z4#S*mF1(@VH$sQ)vqk;RftE&o z`z`YGurcLN z?q}DN`*Zrdbel~w9!%X+vHf!6yI<`wwo4TO=ssm!`1_Ogt*n-9GkFw!f4-k_$+qKy z7r1+p-@ZGfi)~K7UB~Emi9hGohZKL`vE7{<25>LdK1u(AsV%ozFeH$AKSBISDZAM& z=K!!3_rGxGzk);W*yOs??R&#(6T3vsXP|Bg|NgA^x54Jo40?TN_TMiyxBnx)n{?{0 z&G%a=OtiE3|HD1sZAV^D+aY!I_%3XaitQ3zdi_Rs;!e90F?9R&FwwI0I82Z4bjF+7 zj{6V${q@P#_Iu-3#?ym+e{z5RGBl?>213pK@HTeVLvDLXS)HR zwnblzz=0(8bF#lU)Z&|smp{G!vhHiW?OX-A{q8o9uxUJjE!+>2Szkl(2i-N6!D?R`AI>+A544ea9#{BkMqp5DYYB$|K z&S=oKH87*+mzSj!+Feo9aX9ms%}{oZG*0S#h=P-YmNR8}GN>wkn41|N5*uV7owq z?*DF7K4DuqpKhP?eJ|KXoub>PQ!2JqRvQM!J`=w`;XkzN+3u92@2_4>s&+aS0F<=z z@2}25rnd1)OQ`1?&0BA3r`}@;F!;yXCqvwCth0HX?c{&-`rx?7&UVbcFre1JZ=c74 z>}~DV{(pRZd0b6V7j{y~EEO3-qB4fex_j+?&2z| z@hF^M+r(s$_yG^t?s)C|dUeNm)mK{_zqZ+Ks++xV{jliKQq{uaxc>ccB1CoY8qTlB zTdq-!ACBkGZnfL2n)JGW-i}b-Ki@w!`+bJW=IjGH##LSy`v*Oy9aB|m@`;{_m)Ax9 zyk%3UN^r&XZQb?HRRdy8S+7a*evv=(d+3q{pKMrWro1llXKJN>s=ur8{=t_jJMv&8 zV?CQH`}zEC&{+r7ur|2=-<#n;ylT6$X+{dZdH(D?b&~4p1-w6M=2CA`D(Tx4O@FMI zA1mrIL-k@X&Y$_liKJ*u8Vee(9iQ7Hy;W^j;QZNU`W0dk_JG}btR0{KJ_V@qRJgt^ zw~SWB{EzzGK$|$#OvA18z2^Oh_36VeQ&e^TNByowShlJ!$)zq{%KPE@^URZ6Ro>A8 z+Rs5*=ke(A@aJ2 zPs?46iP=vZb~Q&{7x8KH(Nkp~jpNg>y%Py{Va!)kzZ3PTf0&=D#4t-l(leW zr`u}BXO2sV%Cs|HUt3tQfvmk4%zP)w`qW>TUmQ0wN>zB=2mSut&j-iJ`~kQ=?VGhh z#iH>3rPfwI$&f=2*d8!qz@cswi z>)B-U$zY})rX8Q#_NS_Te8$f=SF0!{R{d~%t|8f~Zo_f^-o1$tSl4{Wdi!a|XX~IG zRgE^de}AgJp!&4{&u{J7yACRXr>f)Y%HOvT`>)qo-Byh;-b&A%mEWJpuiqn{s`QGo z>8Z`~x`^K|?Y^ppkHhl=mi6^X&URd%KDkwgd`x^myQt*ri}-Eupb3dI#r=PWo3HQ#3w^RqW+r;*e@F08L+KB1^jCsx^~YIp~a|IdBCKz7Civ(TT~^{Kz< zQB|dlKD5JCWu2e@mt6lh`93v`eVMD>|NpvvK{a~`?*HL&OK6=S`Tt7V@q66t_?^ni0oT9KR&LB{{nUua6b}=|aX?e4-Q5W&DZy_1nmSWbIM|_Ufmy z&g+AAZ=K0TNxx$8f3&_Id9K@vnOv9m>j?cfH|!3oM$EwD|2gK{$hLmCerRNa1!^RM%RTJQsK{;fH& zOf_;4&cDa(?V-o+2duZbcKq7feNbh3;`On4{VS206t9o1o>7gM{Y^#n>$$-u#9gZI zV)~$pZZqQHnM()f%kNk0ubEP_9kIGnKpnXH6|WDfF?%xP03KiU4K@%hz1i9c1PQvEjKshpn>=hv;7=>RusJY+v2wBz$+kRH+PgvVD? z|JEY*6Y&0njmOQ%4JrP|@~aN27Nq~*Z2Iq!f)9Sa&%)cLv|?Mb`i+C!-zE0X$FJ@{ z>i>`PiMK}pIdl)t4>WA*KoUq%` zFOzuS9IiST@7hgZ< z7;6Y;)&;Z4M%wXR*5j|L`%XMQ>tNg#B8H~1y_|pN@$J#ckTjM0ADzZ2_vhz3OfZ-V zVF1{V+t$pU=&mXGM1nvkr%++REXO#>)7I}q2$eXK0$fwjr%PSoSS_+6&v`-2U~IFP4j zaelYiI)#kbh4cFe>H4Ro>l=^MZXapeeaO&GIR8(Z6iz~={4Z8t^R2m&tlwwKerL=0 z742hjdL{{e#OK#U{&$amuX-)@$7k6o_~qoGPC?iE#Mq6opOfY5i}tak=^s_tR9EWg zA@3LUwf(-|M6HX*ht~7;iSstxK904j2d54Ov(nMp?PCqCL9C_uisy`Eei!>EYo4%& zkG0d7w}HGa_D{yz*CV0lgK4g(^80!Fh;dvBpPoNtzatd=&i6lfEonl=Hpb(_n9|lH z(+bc3{;T>AhMP@QAG{&k$N#6V-*+YVpWx?1(pU8%P@lx{%c>S7=M1G z<{uwod=U39j~m)iGv8#jO&9I<^Ext&oM?mFkH2mlIky;(Pq(PjNbFTpw(Obw{6za< z2al85Z){iv7oYR>6OYhJe{myHvIh(SCYd7!0YB{Y2G}*G2oOzS@Em zt8jgvR}unG7d&LqwYA&N@kwonpCg|CE6DCn4F1RbtmMS1^zpAL>Yt}&``IM;mu1cR zl5w$kesIByQ3TH5@o7a5MsG|=R`2}s2DF_|Jjx_}4!D2W-;2?{lakd{|IF3uUz!?t zlX_DA8;c*zdNVqCYO?yImv;NP5)eWHrTk;OCcYK**<;FRgsbG=OtsrjQE)6Ncl<=h z{#NkG#~%-BZzVl^aebzfagb!+FlFYS!#H*^4<LX$)Ah;qt+c85txM6 z#}DST2c4u~Hm93*|I=`rC0RIdDZRH%whz&M3_~YC$>W_Yt5DuA+D}P(d$N5kK7VV= z_%)C|T(Y0{+VxpVNq5ps>c7M0Z>|5+kEq+>@$o(%6MEBhs(M6`Y(Jv^X}`^p9NUc7 zC!=Dgkr`L;`gx0y4)odZWOb$2+U@6K$YQcTG?(_OqUe9VKJ?zwfv#$ste$a9yZsF6 z5ll9p!Q&VGaSn8vW3qb0Z0+__)^rUS_w51A(ey8g_LJS$fllg|tUmPVt=9O)|8Elc z)(($vo}b)J`pv}iOXr`QA$F4g!R*K3YYEAf>Q733RJ5P3!KNg&8lK-DVOIr8!Wlcl zoe$#k`wGLJ!;W_SqY9H+ht#;u4XW;tw z#G-r&-8e+M{akG}2MPwIvFcv(x@bSQvwD(QoALScy737>jy+_n=4tmo^Je!Ye+T3K zXXHvpvbq7T-)8P;LRF2Xs^>q^Za;_TOeL$&r%D3^W&RTL`?LCc5q~K^x=xe75%c># zUX$sr?#b%pLhbf5DkzZr=#BTM+#{3ez`DumaS5{h_z3aMePN-&0CGAU_dm|bJK*0E$^Y1Dx1aLOqexLd+G7JU?Jkxiwv@ zGgW=+ws!k*NLWa$Qt|v);@bdXDV?9h>}S7|2VK%ESq%rY+mCukG)Yg-rEU6Y_dn0o z9&|&UWc7j+?eE})P1%J>)U$9<6pb?B6=HXN?qej>hYCoeYQ@lWb(skYxb zS$+4ucKazGeu%tx|3sU&SAIXQ-?q=XNV-Y!50*b3wdN5aZ%mo0o4jAtZx8vOYB8^Dn$#(r@9bG-lgVAP2;YJumEPxR^p-^RJJ1)BMkVtsDN zAbVn52cIuLJ8cx4x)RJbrE9mJOE!JUseVgn@DXL5ug^K?2gB#~cz&&F*HL6aFm6A= z+xNi4v88Oat#W-ne^5BVnK;?u`L*F@^U2}acz@%)a63BX-xO58y{@{F)VJD7o3&8h zFWY{`YRc=P|Jk$Em)e?0`Ga)r_H*&eI#PQ~F75k3!9TCx8qV{jA1ad6 z*OqCwpIr@7$kN@oej7f2H_5vGfTkUjuP^!+uT{P@&mdXdK2y7WoHjp2=0C4M>wlif zw@CSHJibYJ`-V)vV9Ji`$j?W#kAK_s!Cca3iItRfK0i=#zY{4Kg!c!%AkPdea)?M8RX7++`oK>V0!swlG>rFcK@>R`Vmqt`4_A|>5eqJ z)A>`9dV0Ke`$@S{KtgNa@y&sKkIB+?2JF&88UJGc$6mW%WYa}cHmR1pF51tWxSFt7 zs^2L6$)bPJU92MKuHxVSsl2QWObcdg6L-Ff_b&%4`jNGP`1#U%Uj4zN9&SIy7e^BN zM|08n!nyV4LhB2`tovT=_Vax1Br>{e3Dt9x?L*8D#G9^%x+IMa3z65w_{Ly@yOf{6 z?I-`hIk?ogl-;YO+@JR^x1KB|IWf^R(qGQ6i1WE)zJ`$H!|?vPpUno+^*^Sd@y&XN z7-C(LiuNzvdmcqCb(7Wqx2EtPe2d>#9rkP!`F0tvZ#rF%qK{uCsh9a_x37phJBU$# z+`h`UMA07mlhn&QXt%HOz6Z!0PdtC!CO3-yyq=`4@@?;b?Nf|@9!xz;Vz=P&&(BLy zbWd55x?Q+-`%3V?OX^7VpN}GfAJ^op^VS*^*Z7y9Q@rQAJH)&ohjlGwot{14?eq2%?lfPzo z{<`7SALRNP1NJ;X`G0(W*MSDr;lcw`_MnfvF8ZfExs9QVbUqQYpSHC|kiJ_+qvsQk zda9t>dfa}d44OzLH^S?u(LEZ8O)ydTG=@j+r$J*_ub#W3I?1-Pgy`{5@R2;|sPs70pbkLq8wXwZ+`|+NXL!77Q z(k_i<{D}QwiNh1<^8-ohsr|Lv&tQ`aB-#V-FF!OnfjXYW{ZIb8d*pj2Za-}u6X>cV zNorFU?e??k)my1Q3->=pv6W%PLIbvTwDSLW`&k!I7ZMKP`tE~6OX&H|hLvghdqjN~ zIMa!Azm9*OxYgc%@HK(4aern06aCM%w3+14F<1Jry}T~=AH-Lh3FpjQS(i-;zw`0Y z$My?}^H+Cj5+Lg%aX#f+hj7S{@&`{ID)<%b$8rTZlZbym;%Y`FRF(2?w=%T*pG8Gs zq^DCbU9Y43KHmS_S@{%P(;u>XDca+s#xG+?3n_nq)qlEe_*gz%Ke2V zsbAI7Za;UAT_caC;r8=Fnk`W~E=hg-vUdHZTK9yMNcroFr3!xd`3^fCO5cW+?6=ue z?e?=E@CTVA^%sYmEB3+X->TKD2H&Lqc+CGaI@AD`NcjaU|2A@TJLvEnx1a2L(};JM zF?7aO`S*+Y>!93WFeVW9KluYZNxyOzbpBcM1W%YK<*%<^knt(z-(qh25!;Qp|2gt` z6}&18W{uxzx1aD)!Q^s0UjJF>vLE`q*vU*fYPX+uBUX_cQh(b@?))=vKfi{*gR@4Z z?7oF^f8PIe85u|BY>TFW*JS$_WpI&uJr$>X6)DiWx+s~mX z_lb=!o`18Rolb3HlhkdlX}6z?5pT$<*?4~8nR7Z_9wGTZTkZDaTV4rVyMCg_h<5uK zzq2+p_QvC%T{WA*(`%+|`AB)csNWXO?+jNZ`_Z#f*7^9SouvmEde4zUT?OBK|6A{{ zad0yX_diLCeTmy?7qotQ^o=k4YK_~^F5_TwsBA9!{jc2O_0ZyDFzeM*#=jW<`1Fq? zhCh7J{Poq&xezIxf39>`-Y@1Cc6DA)u1~=8*T3z5z`(N)*@1i7{m-lN&BV4P?tfmp zW{~~^asN|R;78%^6m|2D+U>{i{z0-c46mPFPd`I0KhCB*d&=)u%wHcGxR*LCN>bl8 z&~88Ji*ArHjqv=zmOgvwS2kJoqpxAxHJ8cFJJ7M(Qv&AI*U)>}iGbp8OdzZKu?VU<*Wwdy2aU(|no zReZ=r3%q_5FwqtI?PScyPTnu-zqh*si1$VpbpDqA=KvTbo$p?AP_b`b|K&G}Ag!k2 z`SCxG5@2pcFk3WGwja^{%p0vC)~@*Xy?b9f14DbKu?4r~{i6N3OiCc5rTG|G|LHKI zOFP{uWrsB97sT_k_aAa|bPUQMq`13b`Q*&tT1xf0%DL|%r2YlWemv9qK%GA}Y|j*Vzi2;2^Hvfo>HEds z;uL&y=BbnN(+z?p{kPFr-Y?pZ;fyd6nuhzYohQOzMNd~Y`-^gY-hQ6+j3K*L;ra1P zCsN_MK?pm(T*kj>KS9?wkjzk8V>NME& zI+$gTlkqLiSMan?B-8f$p!1zA$J~U(&S@;XSlQ2?-^pCClUVn|^_geC8q{`hDLWXi z9pCkw_mYNfasTk3&Pg((E?)n+Zhe_}`{CygmUby7+okV=VeyOY9EqRX;Q6uPLH|g| zWSqahw5|^CL-F`LaGx1C7=5CS!)1Jl^^+?9Y#?bR&c91K*u!8+zhL;B*~bx}!iL@O zkgqS|Q@45~F+b~wo}XEIe;G7b#8{6e@_rGY!@jL0#ZO$&{^ceuV!>THUl#UPJ3jAt zClGh3|1yaCex)ww0J^o?4NIzou#TH$e2M&f_+2VlIueh+r@t?TUebI8D+7fed3>Ju zn?-6g!}(XQLtXlOpTxiB%KiEH``+Fhk|)il!|IdsKb$95yWrm^s@h^5t-5E5TK!Wy z|Mr@3i*yOV^H(l|o|62GY-+FRj}haC(tt^;ca z;r;n5HZ_5aeHCc`eapkPP-#BSuYreq!?qJRes%ID!X&AG3&U^d!`0+KAH05%uqgmC zH!=2ol8j#+%GcKqKaV3P+q%-+cM3lF{`+UQ~Ds0eICF2hMXXzMl^kGs@MlVUtz+(%f#ek9I78!m5tQr-V}AAMY`7c z3iB2elY$+%ewdZ;nixs*moWUM#r+|>rTMr}AwOTSK2dLURj9hIfPVX@tn>JN?Pv-+ zCgJ_@HJ(|5<>v~NfA4JV0v0I-OsA&KssF^EVt+_b#XuM>%?CL#SHTxQAEf8)sqp;) zj^EGu>&RuP{}7vR6IL}8j1NotAXd3PkKf3BiPC%|oPS4_B|_s`JpYRM&nd6BlfKf~ zI1IlFt4aM$HX$tRyLS9;%*i5SyWspAoKg<&rT+KK)(XCO{`I(XgsdDKO!qq~_Q&Tx z*FJAVze)ACf13G>V*FU+%vs`Yf$QJwj<<-3T|8AW<@xdTgGSAhXpw|pueRFp>t0Ys z3^P;dKuv#xSie3u@)I!(#p6e}zq-(-9LMjTuQlQ5jsmKy`F@?)f4jV2L#XF~^Oq! zhr6#&L;G$atc#U`KfeC8VeNi$Vhx^uJh$`{{0vNEt=B61dHi-daEdH*4yNa$wBvV) zg$3PSt(3*A*3Q2M#RbHvK8|0bmBr-G>o|0N*sZdyR8OjZwd|=Kzw5u36Zb7RepA~2 zCa=PA{#}z-1$s!|Psh$T&Hh^#sx86!cl@2EFqq=_9q(!j&ClZaJv=}Si>3T|)*A&s zeEy+>>o}N_XUZP!mDk1i>_Rm!*e>Y@r(|WF$8UpiNu>EIT>rXuiGh{t81vTHhlt-P zO?DFR(Rlu$?(UtiyFQO!Q9tMm-Anv*Jm~cfGQLIquw`sM4Dt?PJ$5VjOE7}_87 zU_pI|9)h1A`gg1aG-{6L*N$H44BZdl`0eg702YPd{M)>)GsNWJ_&pQh3#)F~uGj&{b)d z#Z@>nFoYd;Q}Ds#_m=ZXa##BP4tD|C`MKWn+R*!x zrT(4TvVIZuL)xNyBvudS-*xO2dGI9;?LY8n{)1E=hR0`{f9k{NHQCf?gv>u;eCBFh z2fE(G`PJf2Be+3ue2%=<3OcJF(EA^i_rur!UHkTgjr(zZn*qZhWs(6~{XqGBJiiXP zIvqTu{uqBv{#WGJ<1s6t^>v(ItA9=-Q|sgX&l9F^1n|M}`DoQX65H98R_DH7!N+IE zF6{#&e^=J=g7W`)e1`7MC6UtiTjRL>e12i+u-i~GD1MKvQZ?8bh~smwo+(_fIEJ1tOXz3;y2Eh)f1;-?+^U50XY@!4 z1u-~(uC*EsPuvXH0)6fASEB1&NR#HrG`%9@SH$P+m%;E|(yvbom35v!O@Cz(yNS4d zO+36A#!K^KF#liq{2`Lq0_RWPX?$oZtKhXRLmcgMc*ecrSIop{lf#+bfpzfN|{c9f`2}L zFyhoRviuQ_&#K?Q5$hW9bcK`h{Q3CnYj-`EZ-wV)k4&rux$Cp(b3b{%$e$gWGysqD z$I$-8oYa;upc&4emHKpsK}L9fc3O*m5Gd8h0?sJ+=j#WnhfM(eB?hc$wdZLS z*xm~F@3+1f!S}Yf{#-NL96ayh{HfQYHQbT#Isc9Fe);^>*jYVbGd!TxZIt)R`}drQ zgCQ`pf;L?#uZ#7A-EOW>vD|?5XrmpUGmDqPrA$-i{8HX8^5@ir(J;9H=TDE2!=%*< zM|3{jqBlFBbQ@!1|H#)DJ`UC{Zq@M`<>^~Q=0w=F@Ea4 z;{^my3SrMnl=si`=aIp8h?_Lu*49?R5AWZXFEyfOXVaLqt9E=Yg=gf`_aK_qU0xUG zFZM2?w8s$%pQn}U^ZXfiw1OOw&e&l64?1^rA?5#TUc>OuU{s!@T?oPY=DEQ#@=ZD;P&@&)}5e7 zRYG4?mfx><{`y+Yu`tFFkB_eSd%!ps1D0Va<4er{pDzdkzpXev$5pI{*I#W|R1 z=-;gkPZP&Rc>bw;xitfAx8_ykP>IKfAf>x6>#qF%Ca>5bz=T$`+|F< zy)+-ZX|#fG9-m8Ze}<^Q5N14F!57b;uMU-w*3$REu=#5X-5St^v1#m(TG`LXM~~Y} z{8tOlpDqX-OwT8mvbBZU@o6|o2l`3%E3E%{U;S!O`*fg@|`vuP>e7>5l;ETuS%(55coV^b^U$g#Vb9yf( zjs4WrpG5xrRP>G9%m_mJvm8G=(4%`w*q|gTImFL6v-#=Z}9Hv)fq5W5zf^1>@vtzW*ZkhkY`stiR6~zC#ME$t_ zI$nPUEE)zydJkwLO@Fe;pGB*ufJHwoNmiN%Zfb58jX;@4Qj}?$W}7>SRjw zf6e)05uf*s{*q`(e`56~zi0!faW{(EB`ErrkAE8H)q#`2c>YLV^3R*}aDKEJY6Z*d z;{EHVYuG`&8y=qrlrRW;jpMIJ%Tb_H`2lS^M8=nhzw+RjuxM-rJ-kL<7vrBDWBs9g zi~$?nQ+fY9!3^YN4$2_%j`Njf_uoMDy>V$;Tl; z>OWc5UfwU_Z&KwFvLnR>&2K)PSOT@A`H%DNEB4RxQ- z{21l-iNuHaP>)cVpTzkNmD;tWiQCecVUn_+_urPF3)O!G(d%jQx)}d7zvD#BJS2X+ zr(BYH1$Hb7?VmE=W&#iM;%MGN`TdIi`|6b@(8e+qoe#7jsx=r{WK-Xn@_sRY z6tKA)*!ke`dF`Zr;CvDH-+lUy1JA+|G(P`5Z7yWG;QVOd9|#$019qX4f)5^_deLhk zT>5^}UXK5GevI(i4%?;gcYapO`$c`JQ|UIDNAdV)SN%M&n}zeEW79|EprbSTeMI|P zkHOf`mA(F>9iIgk-;x^@?sVWM1s}Y=JZeyd?u^3uu{`1jaY*-}eex9i@bS-ERV(^h z!l&yY`T8P1x{lL_TctQZ4nN^Sn|&%}^Fm~P6#chBMGe@rAPVh|s%2yb>q2q=J^oyC z=-4ThULGamPwXH0xVk+wll(V!{>RtW9-M-4efc_ZFx-85iH2(Yv)DiKb?+nye^o;5 zCoA{o^G8`N7eets9G?jnLLhIb0h>Qi#+MlXSU21N3)kZK{1uW8hb4U08!qn`@tJ8- zL~5kfc{sJ4u>w1JzsR4NSL3vQ$Qf1W=RO+Jw^4{&@Y znpLCmF(J(Co`Nr4Uz$GnOR~n{{5jpS9sPYUjhVbq_VfJN&%+Q}eGH;SXXSN~Kery8 zPR|vUvXYhB@fm4X2Vw%F(EfkpX^r5n8=gN3uVMx1`6=l9o2TzPLGZ+E`u(l^{6zlD zcBU}i3&*FKsRO*ryM*>PeRY`v25}|ym#KVx(Z9Q&^nsdFE9ilz^1A5XQwzgknWQiO zIw<(y`7?XvM#x`>`}bw`SupP^&YwShACjO3IDhJYy##lcF*b)N_vhpDX)Rup-L3Kb z(Rt4|5H-`4eUF#_pQta5*mshh;g0r4yELgut-?asfl?ViqQ2CN(S`f(edxPx3VwM0 z^eyf{yKPEiH#Gg%B7f%euMXZ9aQ>{Z*^TZ@m+Gv5?K4}Zoc43qbZ{24#w0|`jM`Lp2pM^H=i z`G7mW#q;O9D}PC0v$=GFhvNTv|DF?7hdv7qVUb_8<5RsrA3D3@{ypEZ3%zzKjn!x^ zUth#$hZ?n^s?@(Vvl62g^``QG6 zhq{6e`J&vP$ETrf3><8a^QYeNEpTLmDO)p2#*c{4-o6L_-+V6jxym|^&*K+gl2%rD zeduo8Tj16g_wPg8zK|wq&S-sTtm+$_8sW;u9FYH?$e(|YSAwNWasHf@W=sv%gs`qH zWc-NyNe38$`3xU4znRvc2c5qM$7lLFBbbwk^Ji$17j=905Ume&?9>ouhv4!1_m)=h zQo<)zUx#fSVdT>k`n8wxeE9rP@_7PrC0S^F-RtmBa9DbbRy!;27x}Yb?qnE!@Dh!6 zRn~d_Twiqo7_Gzcd0Wb#hg7ei4R0y?d3=^Pj)mt&2J8uw@g?d{2a|2kH4Mk+o`FZ8 zTZs+xTPW`r^=J0Xx1`sXQRw`uPoeiYV=N{X41llhji=qv!MP&;AWD6I|K# zd-DGi@!4g89voVM>(52m_2`k%5O%YTc6`>(ss@3{-e~>ufR&0mJxXI0Ve$QOHls-LF$_5{o{kO=U@tw`#t`lA#nw{PXik8Gty=dkC^Zg$$rgnkAiWHhU zM_K3bc{oH3rJ1;Y_ggap${OPSJ?+U9$XkQ^_uyxXA;|;x?+ zl<%*7-D_t3UFFs2HgU;1=ahxW3>`7^U=6{y?}&oAj$G@ve0eyQ&u z`S*$ZS?NPfxMzy{_q#!ierl4=y6VgCU-a)U_tb|fYjFO&m~xC7+?W5K$e*LP%!EL9 z+`lI*Sq4wGmC)rovkNx8GFVCNL)J|uEtIN+{ z#OLA94dKgzAawr4%kKg7(X&!kxs7&wUZ~vy=1ck$>rZM`+yUyf!S!dOp(+?~73a^q z4}&0oF`i#){l^Iwwa4p2eU0YAxYSG3GEx5jVt(mF^_6gSQwd#_Bd?42yqp{jfsHEY zy+$&AME=}!I}wa)8L;%3$~w=V4j-~1EYy_EUnZ}M_*}T~9K@ZI`sX5*bsnEqmVe0o zo{nh$-1T|SVQVLxKL`2g!;afHK0Rj}&@EE`N9Bgf{ds&Aj;aamf4b8&&G%8n{-k!{ z&FGc55T>h{{~_Yj=BY7U_~ni2&-F8SWw%S~N{vtk0Uzx+NX*fQA#01myuchqB zIPLg6>1Yjf5UxL0wCW7DHSqkWQ7VO7{y2X|mJNdg3vvGJ(#9DMNd6tGU)lxFhvj~k z=w|MG4zE8C&kF?SX(e>-I{EpC_?*)|2GnP8{!G4<4As8tqy9a{VIO3zFl8)IdH;NV z{sg-S$B*Is8I`F6s}77p`{zn;mc!k4jJ=*EUtjd^wi~KIV-r4prdy`ywc-A+IcR<hQTtvME`!$d@;23#`$wtNidkHO6a5jdB2Fyn8#~@rsMc5f0qhYRSnpv zYa2fwo8*A z5b;?tz8b7^cSif?Zu?fJho~!SuIaB5@tNAZF2w$wgVv9(U$CM#GD6sdAKLMGdu{`G zdk*K%emzIfuOHIbO@am7)TKO?s;g`X}sKJQ0{ zfnz`kJ^4<4J|aHf?_3Y{vOiL&F5^q|@9mrHfcq8(tl>6go%ipL|KvbdXPiH$S6qWP zhisTxhP+>l-yiSRhZo02q4Ck%E1zJ$5o3{>_+P|lwoXl`F_Oop$e$n0YSH&KasJ%X z(i8@FcSp|`ef->t7H*K{M`_MyiT=HIU}G3x=8fvlE!{@bhxgK0ZY%lui}*a%-Wp~} z{vE3yeg73j;|59kQ6dLk*NNxeuzMC1DroCZVrZ%vv7Pi?mGcqZOuaK zN4u-KLzmY_(fm@2`75Ae0FKWWO(P+GTnXJ>B0nDypBJ{qgVU*xw1uXBL&WDW+jJQ6 zQ=fT8%lH!c(>*p9rj0gbbtB|;kv}7=+=haEHmv6%Wu4cbg<}li-ThIh{;W0kJB-w2 ztk_51FXD4c<=SA|V=`BN7x5W0=kh|g86 zn!+ImZ}fcTla=FX;qNr|b-DcfMSOZiwg&JIqTkJAeir$2;LFw2FR_%(pP}$8@83h9 zGjyni>(8Zw)$se%2DCrq_T%B;7LY=h2FkxrtiPMU1{&Y#I!JVEv8DAm#MpXlG; zO8NDdaEYdI{dK(lw2|VU{bwW|YdeMp)=qR9`6_}nUee@fRK_wSo;PNHL5q_Y7< z^7|L@8S2mu?pWdZCF_#4^!}GpruSMqKF40}2EAJ1_05-;`@+H-8_@i`o#QCzWQoT| zG+-*MSc3DX!7VT7m5uxN#=$`lRv+ijlYL`gcV#?&KQ%fD(ieS1*M%LWb0|&{iST^aRi^|dqVSXk?4E|qnQI? z;@b_hAD3U`^Yi~yV`0(|JiipQcqX*-%Ay^0<>x2%heWSh0%Iy4qhFdS>wJIwyYnHi z{oh42zx49{TIg?v>rV^A6lgLY$EVTeeX!)dK8s3J?$7Jbtu`0nDZ%mixB6okw%vxM z6v_KV{aJlpZ8$v|*PnfKDpR!{V;O1kei5HlYuAVCYbK-hP2=eZ%!wHU{rBbfl5gHq_NGWqw5{(H9B9JtsKkIz+W z{Q#~WrN6lNgvVdLbvPuMUZMx?$k!M1n==}&hxU7l(fm=?*{yJ7Fs?6k&mDwoFZJ1( zqssH+@%P^E5`1cl_7J1FpG{Kk;bYh@x6dQi;S)i*#VEwThvaVd)*(g_(Da0^7^uR3kJ^TaD3)u zIzY$Dadf9<{(#tjyv*1cI?u!Lx%rC++2uB_(R5yqts7xzERYdDRU#C@fDmO z`@fEZZjX!6_}u334v3fVdAzgo{`vZP;)@)JF4SjT_ABc=KC{VHsLD*))C=e=P35_jy;LjfyGznI-QR`7x$SV<>MnnL2vN{!PT^UY#b? z@PiBcHAUVp^5f`)mf&~>$7c;U75#ZLgf%vj_lx*U^lJ~bXZz54ljZx1_`KW3o%U&* z#zyDM`0^L0l;vUqNO z4$q%=&-DkREjWLU7&{i?SK{%xNA3)0(g)|yUUR&`Na9bdf6ik`FwBa@@kuOVz{}?% zHCrV6AJM-bZoU~pci{ZFa(X7j{rW)Xw^iOh&!4MWpM;i)`e=UBb--;HZe+@0Ps#g5 z{yg>J1H7J&O+!nN8Usj=y>TK5LN$ls4w|rO2OSrdZOSc`mGh zyYl;Z|DId54J;fq2hDGue$$)IITON^{F*qQd1Ij+=uY&e?P9d+%cy3HXy=49)`-&w zyuMtN1JI~65Y2CHm1ZNWR+qBe?lQhb{ycPb5R6|DiS~cgDs_TSk+}YR_M{s7QU}xz z`^EfszU?(uk88m39ODLKZF&4s%J(n5o#YGepJmcjcNP5c{hzx7L&3})*Qbp)t_9Cs z7g2p$aWxqZ-Yur#n*657uP3HU@%g}yG;D_ae#QLfjsbb#m5S@r4r}f~_pc`G%n^CN zh~LInM8bto(k&`qA-?wP^jLloef(uP^fJ?>tM0 z8#M{de}&Ei?5&5^WZz?#(7gHbZ{5gL<$=_xlB;|iV_3MN$=OE>rKHK?TxjwI7`wcIF-j8tn z2I~I+(%*)C`!4Sn@jHH16WIE9BznF$>0uq(JYR~hUdsDL{4OoDf|Q?==+>*UeiZq4 z$PXL3x!8sE;qtdU|K5Gr0dgnJp-*?o_9OO>>>e?QCT!;USH$lCY5rf$N8YG@jkWTl zFXpAOj+*{k5x=@t{h;gJK(zkZe0Umd`=gW{|E~N#ULUMKHv($JMxy6Gs^4{mzrAsN zFy%)rHb+g=y>G78%D>$U=Y#pvE!1kicKpt~wGyJw;`p8WG!jB>@c1h>C=R}FxkytD zmG{f%_otd~ho3pcbYoX}UF6@bPY*!joDa0BN?sTF_e4=XG~cGrA|5I0Jbu+jOQBtf z2^xRRfBhR)4Z!*L;KpXse5jFVexS?sy7WODWlQfV_viIP$YC33GZNRgo%GsLyB*T` zy5a)O~Zd{(m z{5byR^~05y17P`i9KZFxIKtwrNNU+jzP@-qsr}gLFwT7gE#UgM`S{BDTOBsIHIC0` z^%lXAQ(LG*f_8kGoeu=Pl1!RlCjWmif9ifW8s65y@mW^55sJ@Vq*=DgejcArZabmL zW*ncDCm#m=2%KL#?ks=~u{b^l8$N;jmnLj$nS6gyA6)6KL%Z4G_>65}2^XXxkl6h2 z>R?Kz?4ry`!_OkW_HWw;F8!E@>VrGO+S4L^R~CI=`F%V-RiC>+-cvUepKp3O(D$=K z*lQDczlhJ?))c&J`_NN2W&DWv{1_cTYe%H9Cz|}X$gex%2g5qIK(v3fY(o}xHG9O$ zH0LWseb8ygSm@pf*9RZA&Vtfb8_@py*Nu(YVw6%)1epO`ryi}qtIsi2l`%<9~b#` z!;P!3e+7I%;AK7%?cW36bJ6P5oBH?;Gpk@cnoot<**F|NQqGjt|{U!@oadLsiN; zuMaBaIl;9iIDS3)xPvFd`FBqhQ??;mrQRJZ<2PT3&&vIl!NavU|9(3a3WqXq{?(nh z7IYGAi;avWh$8UN_FW8iXw~?A_t9}1OWANuf3?WJy3Z!V)OommD6HlQD{be^TUMhfV9?#p@$ze5Utt3lvSb zNXuKw&qw6n=hFALOxhOHHSOeeQQr>JKLuUM2Rf#&ye{(ZH|yJQYb?&cJwxBZ(+wu9 z@@;v)h~Juy2J~ZX8|L3i#-A9U*}1g_zi%VZ{Me-)jj6#h9KQ{^+JWKKiD>@zpnX^B z9_GSI3zXl-$~zS{A-;CL8)yCjW8 zYR+$q_>EpM8b*iU`Gq+<4pLfJ%E~nJVMY8J9e0JCI(UCTgM@_;UKhvjgP;bipOs48 zeVTUs8ut!>^yOR7{6bM|BNn?G)c-f7_Mh)7wN=;W@@p;3qrfCJllJT>KR*%QO+Rmd z#($2`xl~!_>$?+ew}NSHJbqKZ-3z7Ni)qFHdB2G7mwIQwc)$l~eu}&<;@jNk9z1fA z>Sy1Sb)KIOH2eq#VJ7TmvAizgd+kU=O1@g7_;$F|7QPwb`Z%#e6MAoil>ar9?L*|} zn;u=@cI-rM{LzZ=?uLioX6fVEV<2$=5gPptG(Efrq9VgMKMImgFCVwpA`(vZQ zVEb+{8o%w@6+y3VNMq)U<>w>fyW_>NaHS1ipD62;L(@K#vML3#eiZRt@NODpwu(gi zuW#L53|DGwpfxq~U&Z?Fp8kzk=X`s$e+TXOUiK#twtH_u`x9OrFlS!JaD0DR7Y$FE z;rZb@pW>mo;s`AtBtIWfe@vOW9qj7j`lD{!12DgOF-_&p_wo6)3%|}m`MwYIb((U0 zzP?eWE{5a*IKHoU{S5mS;`q+6s74LmTeH+IGCoEAE^lrNr4=L4_^-~SW^|BBs=w8g z_lx-UP3{H*nogvLv$X4vxkkNcIK}mc;hNsk_Yd9B{Mz`TE;M$22+Q_Wo)6zYGa`5x z3|Z?<*Vj_?E#E&=YjhO-*&~fjR?GWEeE+FG0bEAn`lIpsqclLO50|BA$9F`vSy0y$ z$9K@6r7%r@1KPh}Hr<@{&bC+UchZjUzWKrM)EURO^ZwPauQ#rrU5pbT^!X7wi;K^A zeqOeICs;hor_(k0Ur~P~1Ra9*my1yS(Q{5d9AqEpT+R7uk)QwBJ_NINcz!r5^c&<% z!tq;Cs|J1l%$l8JGX6yTKJL*GzO)*Fe!seQS#vtyUaD_s@?#=?T{3#YyP-Hgx7QNA3D! z<+N2au4WqRq{(lJ_-*bt88Qdq`eS~1E-n1>kPYYN!}0N7*3mgo+z{8#&b60AwKwZg z{5~#k$`r**23*6nRFhfU-|l+!^F+-_At)BfsHc2_6&~S z`mK+^^spkjQgi-Q)ED2E6~Jbj57LYW`TdIc4Gen>arJQgR`LD?y3+$MO4m?F`!WcQB`)Ddq7S;N%F)3l`II?)*Q`zw~Ad^>j#Mpy3A*znk~CLPkrR ze?y{9(QX$?nR5;K{fPRaWwUuO;d2D_Z6@1~m_H8s>JJSbucrew{3hy)4F{UD)@Ca8 zi2X8t#rksBl5ptKeGAR_sqjBvU%t_79avjuQUgtVEb3$TxMVoII~*rxbZFmt$(=q2Ee*poPRUtMM8_p zIKNK*wH~^g64ZrtbxY=i1^H^?F5$&FGlMd&9ASc`<&C*-+l7?5&1Q>`YdSFH;^_7 zm+ezL|K<4Z9PRp1!sifqzlhI7$3;-*BF?WZ)IpHC702iGDbXBdd$H< z!3UpT==xrlwr+v*XSB5my_Iau8oJ2)MgF`E_Ry)yNE$gv#)pW{kScAd|2tqu)bf52 zpUq18fPX5E&$vwkXmO!4bNV3vKT*G~nlJ)P*3Cxy$BDBiZ6)c~L#yQdB0eLgPJ(GV z-gNdr1z)`XA3k;i{djCA^B=72=lOHxX*X#4B>?TunKmh(#zvO1E7tOU5uc}$ePHum z9G@1JAyB+?JuPpd?C0ypK9Q^8hSe6TtI4m5{bLO)Z-T|QcA@_LU%eerdl(*H!T$X) z+Yjf@+gHxON3SB9H&yw4e12fy&O4B{4Cl{mi+5mm7sqG!lX~=gLlYLn^@s8NnQdN= z?(nr{Rh?vfiTHe1i$Lg-5orI|+F$MHiPOLubeH#w_;k$Z2L@lA=&YgI^8>4Y45D8T zIkIdfM9@o``3<5zjX50(f0NhK$TrG;9-k>M zVqnz4WHf)f@OuJ8z1T&!JIMP*{n_-*PAD+O^Rv!H2f@W7pLXi4?C1S^=a%PT=+q*5 zNt0g`{kzSm`%o0}o{o%H_Vf9xKgJ)yt4NRiY^>me=g*-|2Gr2RgtcfOuZ!_h-kbWg z<^pThW`?rP`}cwx6dn{fp!J6XJv-3N@wk7#+-eYPxikSi-$2ub(z*p9~bYwQ|WGM5u*dOM#e=$`x3Sm=n<^3W)KU|&yxv`7sKh1nWQGaI4-9+C!-N~Xg z{r94O_bv2-1FM9{qL+T*9k?%}Y079Kx26|IGp zX}EuHet$C@O~m>0bN>u5wZQ#*yM;Lr7nV44UEt0#4$b2k91 zHbCAl@~7{vAnNSnvjgf?+ec-!y1=eX#bb4Lnd^%nS<81_NO0( zZQb(eSB-ua@!76n0UW-6AFXdKX;KP}N4`h%|G(yagS-3nSa=HsA3T2sKB!8^J~Br6 z^YYe4wAx226rb})^o1X-@%a78j?T1`KQO1E%KiEN#7p0XLDqB}pK}XF(w1J%tbZMO zzlcwD)&vNBI1BCnGOgxEEt-U|TIJgD*>d(QXg_%|sy{uaC(-zqJ6YE}Wj~Kk&mW7S zgT$X0KDWb7I`(}j3qC0C7x~lPKLEnU;QDjJ!zdW!i2L_fAsfJSO)_QN`7A!abZAWq zZ10QX^TxVtxLoH5outXHiSawl%Y}|+I6hD0Tmf(6B3is$`G36rRIhmq^~~}3XuZu( zu#dz2yXl1LH1LQqsz2LKHK*6^;P{L`-XFSNc0l{TNA>PTcdZ2$&gG|gd=5M^0xtE! z@p26pY~`L!uDzM6C!_>4VnWTzb-=SQz>J&(3goj z*)dK0Df;)0HKh8{-T-PkSBbCq{;pF4?$C}pkJ#0_%KPK_v!!hitZEm5)?Z`St%69y5XX#b(!ltJM4(*eydy_wO29-WWlbNW60_V@$Z&uO*n-JF0QvQD;K3(6<1&`f}(E3wgU@DzhxRWJ3ke{!JPw(Po5E6y! z&p2|A9+Ku?1qaLfMgH`u2!`LoasOU-LJZ8UjmPhaahqUrN;19QN4~xozgz9u4!-s9 z{8I4ueX#3F4$7ZzSD%K$hZkth80GqWd~|x#4Y=WbpYGG-mqmR3aC!l)pS?r%r|SS6 zx^=N0tKU|BKjQh??muf$sRv9U0B!vt=Apoq`Tm!0S|J7;FsLHT`r{JyMo8mwD7n^w_$pF@m~{&@$| zf#xABroFsh#HYo0PZ(p1>(Aa(x6zjSaC}Z|?w3ebL`f8Ip)( zR#eIuLP^qEyC|7LNt4WEmNJIsRE8!=QKU%`l_4QT6cUAyG>|Dngv{x=zu)sc-E*GT zSkB!{RsJV4(yC=H*{sz%G~EdK8JPEL|q$NKj-eXgvGTp$^7Th zx(OJq0c_kF?(YlvoaST)e%I~E_$Y4MJdAte#2Qtl>-l^>)m{#_RHHQ#DKF z^%wK)yNzKW?C4ADr(>)AVAi-Fbqu)Y3+tadO=H1w@)2JCQ+WPRt!FB%8+ihimUHWc z`K9csS#W17&F2Zn0tkzz`7AJc0vd7U_$`Y2`$GM!@%RYl?LOh5uiWQC`+mzu4*eZl zv#Y%PIN!b(J1C>fblU&)?WTp{TH35v8;%d5e%>1@$&Wv`Bq!`IxlUiI<;8ndQTz*N&XK9l^E|A#wO{=))3;BGq zZxb}jZzStS8ItpZp_7tXe_noyA0PEw;RAD{ym3;?{1;*T{zCsb-nw7S7PaK}g!Vn9 z{cgA~@jqAOiR-83@d!w}w4cn+`?fy{TNP>lv!m=uQ2CNd=081Cvf;DO1+;C+p9%d> zrAs&AFnI)~=d;N&8Fzs-q^-#2Yo4K>Qn zy#75QpN3umSpD0Nt+nNzFXZ!NyKPXgd?P+sCbiG}`q9}ZshD#*nWeP&KSKRHd(s!S z8_@C5$J={g(n#8VPlZU(aNSS#pZ2sl25aXW!9&i{_sfrey8TXrY1dN8_-Fd1OR(64 z_Ah066@m3!nm?ak&p@~K30Yqsd+H0Q>C*mXXmVTpJ(%V%>{>T;Yf>irmu9F9M*k)) zHmwKu{)GA%;AI2BeP)vVAKflb#F9#5c54^6UdUgU<^|9+nYP~^aZ9n?O(%BBnp-c- zAI({?4mKD$^YZUP{?@7lq2hNxQXg+7ZwC*xjb#34q1H*Pl1*kR+1&dV^7q%lALQ)4 z(TF!cfFGaNne792`5;uT5ZAvFl_+@O^Z(Jmnt0G|ipBaC`z`bzH#VGxZyB`yEh^7} z^br^EX(0Fgh5Gm2r5H436`~9;KIi+7C-SSIxqCT&Xz4E!+UHX@8liE0JzBn({(XLa zy*HD`l##93ua^3^(0@#x(E}$IDU;_{_ty-;YlT{*eeQ6<7IMlhN&Sl`Gs9z<#%!xM z$B&S|j(wNF>H>Q@zUl6abqAbSznR>6A%FTo8(?LOGcUdo@^@m>ZcMxC$4Xn)3-xbE zjtBHI+lVP~;`*1+?-T|%C$YsX{-2P)OiBGPXfz$)9Ez<&rc}d9TK1pNJ{u$i!>0T| z?7dr@&!suhFyEQxGa)h&>Puot|8e2P3|@UBNsMeh9x{m1&$_LwIx$q&tve$MwFwO;hZ(4)%a z`KTB7hvBL`S|4k*9iY=)OHv|$O7hgT_W2d)q|G$t=lYU;{U+qTP=RPaa@vd1i+tm_Z3HdbH5D06mz0qEm z^IwJj<3F8HNKT>oJGk^PgiWLQb3Ty_KmNv&_PIIl3@qG0>tj&CRp@dh3m5U~i~Roh zZe^uV_@jWVKOX<^5~eDbqskRd|AhQqdHfrmKK)4MCp)Wjz^EEIGJZK2(Ho=o)B0$1 zcsSk()gtHre3ta*TwY^I=Ff}mr{axW#w`DQ29 zVZC%cKYsaQxfw8PIcc9e*X~28@ngA1x%EQ+;Fvdf+;&6o71zgW7cwx|CyC6TKatc2 zpAGd!OWys)eEWQQay{mR3B#@9(I*P&BZ7MY(+oAnSrd@R8H9n$rD`)y+R z2HszIf`5;3p9}dkRs07J+ScQnKiua+eVme`h+36$Y_%Qt`v~oK>FmDPbu-PUM)*i{ zT~G5lCTIa%d~J!pTjq-k```ZUpN?8~#%x6x_k1Cr;ZIk=)&=(D{M2xr^|)c76T7%W zx}MLc=DDq4G-f#&zvwIo!DVTF>}?>oUdZQ*Cq57~(2cC`_zXUa)%TKEV&iG&`q{wz863LbNc9hfS5qizYLSa&zU-O{>M7+1Q@qHf}<0- z?GS#Vb!>cEENuXAG(4?5EJbbnY02aaa6U z!5MD7kk7^1eo$B8O4fJ!tvHYW+9$IgE$35&d}`$G1t|6+^XD%&e8W}c)$HV5?)gIf zEE;zJ{)PmS`E&WJaj>f&t)Iqi(;(UE?3J7xLNfm_O`#=}Pv$bv=`X!HbjF z)`#5t5%TH2Fc_k%ylDGg^c_0|RkL0fx#tV{G!Ku2tSNzH|67||@la>CA0v42FTX$Y z)caG=u#UFx6S6NsqCBmi7h-NhrC%0WrEveBFg{m=3XnZO^O;jv4_nNiVC$3IdZB$! zu$RM|Uq9khWA6VK>StMpE?Brgj;ufau~J8^{Yrr|g&j@T+qr;~yEbi}>?a5|abzdVc;qWoRf&{_BOCTkfY5#y{zK zzfs=5hTUH-Zr`8pkAg|QftWdovmZkL^MQRLeCxCyGkEa}pUM1DF%-$2L6Y)(iQp zZIr~i#)+qrSg%Ra^?W`D90&vD>t48cI=8=seA+Zd!(1KOzZ`Qr z36he+$@=&Hv`i=-#@9z7f9Cgd!TDYaPTauhmoWYr`sglNOV~C-71IYYk+taH- zd6*?Sx7^Pzd20CAP?ZCUY=P~OO+-qedOU}=B zKTh+P7|@K(lKBgb{l)e1>f^&;WkKuX_RGg%Wo9_8JF>S;*3lMHf#gfBgE6 z`i-mb=Mb%rA#+Q?VL}!b-IT89>!ZSg7oe$KfE^A=Kj+8iN49(i%y~@O?=<6fXqo?k z%&*_i>V~C?wEb=ytc{y)cOmENJ??3Q1qlPl{E@5aI{4Mg63b3;`XJ;puh<^vESbQ1 z?d9IDkk61)?vPtk!TtY2eSByZ3n;^nZ-n+)ZEz|?T7;A5 z&%dlW4~B1Jc=;irKDJHDhgEhdWPLli?*sU7={yO#(63Lj~VB}WFZbuGWYF#hgj z=mOn6XOQ-JSFs}+x1K=uUyL5G6D;=Gq1|cDe-g$wifg@a>cM#|qs9Ld>SNS-fA|%@ zjMPVq{6ko8L-W^BaUaYX1zi-FB?KX&-N3 z=qc%XzW&{;{{yC}k5Q+b`&`K1nvM$S<3RIwSaLs?(sfz#e3?<*VBG3T+vlw^hzA{M z{ktoPKk6%Hknwdvof95>W<>J$*g!Hra1w2w_r!T4+RtO*Io$pc@)yxL0OkfSBkPOu zjxo4kwjZ0>fwPZ7{cATj7z}GSknu}ZSw2R*PbBL%C-)zOmy^86`ptexZFjk3etuvg z_k3Y|Z80ql4j&KT<KtGR|qvmwEyUJ z=P?A9oyW;7=bMD_^|W9~|Ksx;*uCX^h|quZj{OHN*^hAsZ$1V;KRIT82mCac<`Wcp z<8p6Vaz33-!cc6pnzql|-ZBifpyQV>Hk+Vp#0=6tPg%7P3)@fN<$r|sIr+I4JbGk@ z-`8>WO{kAyFMP1i=y^^CVJ* zHCL)%{P-mW3ox7|v08U-e+czayGJyfHlX!!(Zn`vmv1%evyFSckk9aO@o?^W0I8oU zQKv!1Bpf?CaeNBvJ8ybkhGjW1=-6`pS7^Uaox26s2BzRvUVVl?-)LM&Ias)!C-Xl} z!SA6u=mr_z9I}x?6Qu2Thbl$9Z~6g?Rk+_znE%-j&<7W;m1X(=xc^URzxV6v;G+q& z{qBFo6mzs`K5zMMfvV{<$oOVe#bW%eJ%J6r&wW2(d>xVK4Hw_qlJU*ofqpop>paGa zr0e;7?pY87wpW&t@%6i-NAcraKc+XC<3q@2qhc7`ai{fDN9!gQX(h4WUflDAeCFOc z1Xt#GVNedYzl8o{`=f1HoR365Be>@a`E);>04nDL$oxk0zO)9MjVsmW`wJ z(^_*Gj+2|fwm#dGjaXw9D5r-J14QhEzcM7*?CJ0%(eEy z*hcRA3;CQlAqlJl0#Jc>KAm6xUbpNFteqQ_?* zTl#B-{$;?gN~oGa`)&Q!YS_<6 zmYo06*>fabXzWbpALsd*JYKhy%#Zhe7>_+P{Mda$FV_oMCi>BzHi@M;*@pK-zM zDjd^`L4RKVBR~H$>CioJJ9nJ4-`n+SVD4zzzw8$I1uQggp!EfgKcPNO|09QqUXRHB za@oh7F>LvJGCyu*+8=Esd{XDbud-2?QPG)+YAr*X-li^N5r$zJFQZ^a6tAX+AGY?vHE!cAez2 z&(=2RoAL;aTl#y2`nk?X8K;k=`7F7sj@MLaK7;c{W5I6Pe&2GLipo)%WPe7Xh8NV| zoKD8)+wZT&8yQB-?g#gNg?ujQ9RT{Zwq*QMvpER69d~5ETS?z9pU-Xe!BFN%+wZ4F z$!LLo%rTi;FSOqie?~&PVH?Q$P4|itoU>2?R${Q1-N`7j8|V2#y_U*Z@`*=he`Xs_rL>4IzaQe$LytK{@Xb+ zKG$^k0n5AJK=nE)-~9Yh@QSv$MfVZepWzwP6%UMmPsTr6hH7GA zLuJx*e6d%PoUf6z#v3k6df2G`jPt7N&~t+kyU|&Oa0SmkmX` z@uRIHo7R&57W$Wk?Ly(k!6jt><+wA)vFxia+qpx^7k|F%r&Upqao>fs?+TjtvHVaX zi#*BgFX8?4*AwGm(@#$<@6NqHp?|6Sqa*8kUBai8IG=kToCK>e0Vv}x^>6w9r?uWi z(8&uU;_BhI7gGr zuP+Msk=%bv^SRX31q(MCv4e^nA3{DePfGf0x6%3;+ifqtpFrzprb`%<9$G^BpNk_? z@x8VmTUE?GU#OqianbN}u?ty$EZz42Gy5m9qbtPu+&LiuDs(-`{>x2GX`pa-7q5R! zm|veza0%vxgpvJ00dH-@jb4{xRqeqWL>{;4S_>(jSo7ex1x; zs`YMO6xG#Y0><}t}H{7q69XeWxkitzx3;z1Ro7O$^3fLpVLq#iQ%aFj{TM# zNSq$V%byGFbLyAdP;>4u=|8F#luPEHAIIsb(%+x&KL&1o554Z6!_fn!`-h+Zspr9{2kT^OO5B?|@q< z&F8`J3V8J;nT&68)joo<(>cuJ4?kQl@!ISJy8!<(N`5dTW88cdo#y4NB&p^B4T{tUUoX^>H zd9b@%7=HDU{=WSDr3qj0Y^Ft+7m9RtZIDROSuIKA#qwOcy59iRhrG6;%A6w6E zg}D{^Wc*!sQW2+iqW#Cgp1m>TUmcEVnLj4XpFesq1Q$8d`uXMO1T3ylBIBDK%WTlm zL4(D$%r_9~=dkqwP**k$L)uIKe?Fhn)wW?+9?fTycQAOl(R_wFh2euM4oqtd$Cpq) zpChhx{tqtI5dJfOG%ARmmfmp*T;Jn zSE6BK0$W(i`6og?p9Y_R{v$oe_-2ppc`){*`LoKs4mwt0lKhf%fAjTmtlWLLF40G| zbm`~(_-5*;=aA}7+wUu@zJgo(b7-Kmla2JFt0z&pME!n+oNdyo}9D8dGFNO)Ry@DGeNuYP_BM*^V{zLHARDj?<6epD;}4wz zSoAFvd*w^{f4|3{v4+tz=jYFpz8`{8 zuf?SOzW(VPdT08wJLARqOgxwX2YT`KQ8+(+?2#APWRb{buHc?8LGbP=RkZvTwL{*?9b>?J`$Jwl_B}e z4xNZ8PD*6`vHQt+cqfg|r_jIj>ADw=)K4YjbB~Q)xL0#Ld%}ya`F#Gmx*v?%&&46> zQvZ;De(e43NHpu>z`R@P+d}&t>=px6hZf_WPSW3>AD@5FlFTld@5^Q>i1Qg>nFKY? z>+#Te17PO zGL}txNXF*_+Nh&q{#&v>J|9M*TA2)aey2Rp40n4dk@M3>>MTIJb{gdUss5h(;OV=m zq{eXI^G}8GQSpVhXx}c8$whO|7xL>g=M22G*-7S?stwiHJ?9#>qOUl=8ERJ` zwA7!B-v^bfV<$QdF}WBd&Tq-pJ8)%GC|SRZYI+LsQx1{!qm=XS!9_b68|7O3Z{+(2 zQ#Ulh;p{Wy`3!&6_IP>|t-mvucSGHm56JTw3C}d~;L^8b{^{3TJ)C!t_76U!Ti~F! zO3d^#$Dh!Dy*FS9PQ0nk9+`9hpU^)Tc{T(Nub4{apGN2VqWw`rGQQd%Ip6Tg-3BM| z<|pv|gY1Aq*ec$hHMw&92=!NYQXH@|i^%$sMeoZPr{~MYnv3(hYIQ0M3tfj{E&caG z{rxcG9d0|FKkzpk0h(42LKjK6*jQozgl z*U0>of>(EZ8S;SiZ{>}(Flq8zvOgraP#+&`ruiK|e<~_9bRzFh)f>DFjc=%v_gA%k z6bdhU(EhEd89!2Hg%{zg9Tftnj>{eA1Ijg7@`NdLEFivj-L zAVbdY@@YFAbFOtF^9P$q(C=q7G-u8s z{f8sUlKXpp+mZary@;3e4=*J9=cilb;@w&w76sz^+e$SJMqXIU^M8f>%6IvMu4M`A z_cQMM3;CVW;{y0p>>&N$1#+4!^>z(2%NO?_HY?|YyeG}?W|jM(SRO*gXFE^UfJ|L9 znLnr-+yF<+lkh^GR3G^ML6(9n4zr^5wQGzbj(l^KtWRZ4?S)259-!Gb?(YlxL%+xm z!u45i$o{6O@5W)?2wGo9G|j**S)IuH1?~o}M4j{M>@n~BI6wbC-*`XhAE)^&=@fv6 zn#Ym;t<#dj@S{!)Gjt`-K5WXN07ON~G>-$kp^01)9hdr1f&Zk54 zDd?K9meg1D`HZnk6PRui_k1CrnQO8kamNm_zy8c!P1Z_sztyD0;(S(wU5EDbXg(jA zK7`!vp;*(2^Us9#f5i3|(C%I|Y5xyQ{0f&Od`jalq5YrIUk*>QGi3er#Nm$U7;$@_v?E`m1r(Ms=1D!u>u% z|JBbm0ygcPLi(?_9Rl(8U_Az0@ zQ48zbqsjOyM4=JlJ0_9&S+7Ppbb69W<_~l(cfzr*SIPX>OaDH&<<@;N{;EtFf;jyR z>AzMq8KI7{3^{*$r}}JMy0jB{KiiS>Yw>x$I?HMh=QsAa&b z|2pwVETn18A@g5(pW|@wA(~&K`^li?y^xH*=3U9h3?Cmd{#w*016KZBL)!m$`@i9B zE86})VV6Pq=XO$GgQsdUosHG(?*egtcZC&#QFmHji@Zj&w)zb$OJ1DcXq(5-m=;3j zzjh>yW{FE0*b963kAF|>&Wj%!+q{OWyQA@2%lu8@`I1Y8qgku{4eWoGaQmkRZ~gF# z-{HaaMAE+){ChOJ@wkC$p9kR9_vEd=pwI@@3Np#~?)F6`OxL(d)_>Jw`=YkneKNlD zP#A`nb>84IEskGdf6RMjV{E;m8L9JA8Evg`l3ORH$D2RK@2|c!Z9UF$Rc8wyaDQK@ z?`l?&P#t4I&bJ+CvKwavjU(%89ey4G)S&$jSDkoFbhhKgS3>{e*`O4VTey()KUk+5 z_;!*H3mqozf217Dgp99ic>aelKk>uh2RdaWu;3}u_5AZGT|QriZx`Lk`;F>!2eP_r zRjhw+@%`~g`xdy!_>=Wt=Wk-yeg@ z-ax_nXsqGQkKosj_q-g#zRS}4qnFiBn6)O6>|dLD0ysl&`E{o?^HY!W%E6V=JW^(?W@ccuE0DV^8`hWQo z^{+mrK82t2X#2Ektv-{h{meeh6W@O(Wp$vjFdEOdoIe!WrzNxXS*t6bN&8gq_8V^6 zCzAP@kK6Ux(C?p_<{I(+H+?`mEOyBx`-`>x^jX_h4eY^W@%{HsMH%nZ=8^Gpzy12` zj!FZI*Aw4=9z*+K)6n~5|9oJcK69~bV1*GVy8m9?8jj&bud!K=vrj_%_d&A$n`FJ) zGMAS9-5$p_hTrw8_V{bY+$Blp)Jo><*om^#|HZ)b>#Iw3-|AU z@ne}yLj%)qo%-K;L^a;}4@Pd71@!)Q=@kvHgDuGXQ=6i_sI_?<8@OG%Kl%C7vZ2Qy zN6nh-j}B=_#CIL-*ugmIdj9@4es}_s^A?c)r`vqV-L@U*{L{<*=U|fe8eaZixWC&w z{K3DA5?G;~`2LRQkq4Q~oy?yenJ}0&%&TOk;o|$-ulpS^-s(rjPmgvPG4-hL?8Kkz zqWk-kkaGQRz^Z9Niy7``U+XUB95*wr@@{hKVle@}ieLDld7kh;HN zuDt;>)M#Ly{lxe0#Z8jgJE0wU{X4?_tG&m7EnM8dmOV@n-MI^lc`-h*O z8@|_oU6RBn8u{1$Tknbec>90e+h|zxX)@_QueiAnN9m1YyIiDypTECtn&aVKwl!Mx zl=8=~kL=S)#&6}eY+y_NOz1!B4@m>r*af8j+*o!CXT0$y^UK{+&co18tI7EC?7k+v zxgmkM2Z`@*mw#6w`j|VJA8`vEB8fmN+1^C){T=qO7y@_tk@b;t?<+y6KA6mZxNCoe z6L+J?{9UV*43@KDnaTgWvj6Kp_GkR~@b#X5kk})UJRfm4DucD1zsw|UO%@j)GJbqG zuYY@dRh2>JPlAn9aKz+1GCrKYR2_fVm6H9zkA93}-s2jW<~MHt3H?{i7+tho{2C+8 zr1p=0zgcSKI2O{QfsME*zW@H&PQ;Pv^!|%#ZOFPzX<)YV#rL1Aqdi`a?a0f|2>0L9 zA%^U4UouAa(4KO3}8gylnN|G8oPaZC!cCGG3sdMT5cecuy^;yx#mTckd z>rp{|a`Vq>Q2iTB#;;$-e**P8QCP$~f6lkB1urvMPdR#jsxui>dy~N1pThjR`I}71 z?4xBSUmV5v=O|4D)H<9&_m?c_hN(*Q{ycF?1N#guCHtdV6_3Kem#@hD&4VwKP{HRP zQuk|o8s>;WyF0RP{kZ)rBRC)buWTE7Fm=|nL~1|y`(uM#Ec{zyLB@}1^&wbs!GO%q z>pCPsk9O8L|1%dq3H$q|RHk5_hb?QoEPX!TzYLK%4gD17DXfQD)eS% zYoz@0=Qj-4k`4BYY5OBL{suf;;7-;rHT;INyKAeMda5|zeIJy-%dUQ8|C7#IWJgUJ zSyed4w~T=A%lXg2qdFM9`f%?@SU>7;=QF%@rR~qpS*`Hp{RCe9NZ7x(-TW;3cw?za z(|mD$M>uuB$#EHEe77sOJDR_e)R2k!^2WLYP-#*rIUncY)zKK<=M_0$zJ8uLzUoEW zhooUncsrsaOR(gAA0fY0XSU-g1$FkpNy-nOUpeg~pghF_HRehEAD(+9)Bi&#CIlNW zgVoaYeE-Q}PcmGnvm*OTeBPv@+aOz(l`37&=l5nrIuy^HPo94ob4oIQ>8v;N+%C?q zfB#D`AZ;~SUow2zigmF_U`NWO>-qV|hr0{FOO57xy5dOoKBbB^eHQ2Y>el-Z)Z35D zKjtMf_OkvPi}n@gJ3_V=9D{?&{QQB`FCept*6*E~ve-Q;fsB8?4pu}}bJ{;j4C#SM znKZwhB>hjLn@h<2!u1|{XxHHt*so3+to(zZSyGtZig{ z>GB_4Hf&fmD__p_HwowCUHI_;{9pQ#{=c1^DLdi+jSXKd&hOUqFQMlWKEE=8`OG~v zzCj12D6;<~w5=RIpOQeI{F>zUMCV<(WPQ}uT^sfDXnubO>En&smt=qH z!l_g6XL1wiKg1qih;O%cWOF>k`F%Ln6O(WBXZ?8bC!gPpF>#Qwd@@-d)#|<OMZmWC_q=92t&%{c>?UFMVdXQOkam}BS7R9wXQmCMh8m^Z6P|9Qc; zTkuQCot*D<$JW;5S@ZcNc(@Yn*qv} zza;(FEqA73r9I7`sqtcLj~&@L7w-QT+W$ITFT}(B*~raO{o?cYZo)Ch?MmzCEX@ck ze>ax2|C;wxLF4#rQa@)rI)z;i&t>tqrO)T<=ZBKB5dX)C%#Xgj`vBiXd9%ll#re}# z$%WnVG=BrI!b(f6!N)J_a{tjA4TRr>#JJhtcrNDJ~3;W66$BAll8w7Z+hd7cC>vrdNBwi zC(`;D;yDi6=f5P+=LZj&j=yD_kh;HJuhUX=HtNUEVrU*U)?}^N)wzj+4px zCSNrV;ES}eWPDZVc@lQFw<7a<>&K_##;Cch-zRZCGi%R*k)IRUKdL{a49{)$W=R#| ze3~Zbfo=LKEG^{pOPIg!@~90vdMTb6wHD_ycK;o?VZKe`A9Cx3^YM1})MpQFRIz_Y zIX;Ep{EpLIIFAa~V4vcG9|jpY33&3H0DFh#dB_E?@y z#{c0z`(VSpD`fms(L5Mkf88Vdo0i2JqL($TpKbO_X3J;)CHYh@ScV4%cVzm<#reD_ z>w{;_`ZLxt|M36m-*}z?yW}R5@&9APNKA60`Lwf6gNvrK$^NE40U200Z!SCaRh-Yh z>&}C=9H!Ha=&gXi~Yw*)+6^?(!@g?MQaQAj>PIWvpo+8et z%E7zPEp{7zoWaG9LOy#+>VJOis#y74aXvfQJ_WyZzWBK}_k5v!uhM@HT~F-8Cf>!a;r$95BAxMJ*N!adGWWUAzQ=X)#lTVhnLqD-0KR>nQ{q`xWM=EYmZwuhLu={7#(DKOeK8YTi6tT_?`x z=jO+_{*M>?ohHs_(7b$@rcUdp{|o_X30I6q`D1jM{(a@$Y(+y16I1f zl4%%<^LgNY1vpNo`J8a{1N>OBkDOn&zhe``NPc6gfA0LQc6drP9&5w7?FI8=`2^Vx?a&>C+}#y^ARM&aVtw0?f!*&${0i zAiL0!)X$82$d4&W5;`B{kzpxWBf9wmaK1w=FG-4|366G|Ei_48jTth*<9ZI zWPX39b+aGp)%RmXX;S^->t|QH<8X2)t)I1r|EKpzpKbAyuIJ}R=N!m@zrASvY`^#% z79O-=#y_R&`SH;_^NX-#ks~^+71z%bE)^JgkLL5xiUM%RSxNSXS)5W}^OPm?9~;E^ z9HICCw9~he_T9VLkTIi5w#reQ&kwV!L9351zFjG9-``FC3`aF-`);>Z24%lQlKqwa z8royXsCc~kliNSS_&v!<1)m0-CjHM%f&KB@#~hN+%AdpWORIZi{xf0@qRXCI966V> z&%*vG>;BeQ{{1(3KE&zE8VtTl^Eu|XKW3))V;7U9eDL|~IVlBlW6a3>r(W(MJejM{ zdhC&|=kvM#cqUwnn?>qp$j$TkcZ&_{pv2i{VgJMNF_+;|nIk!$SxvSQccpld@zK8{ zh45nhN-{pGKiYw{eH72a-i!0;#U4Ua$E{d3fP4Q!{p>T%h(W_MreQD6XE*;E@Xz)k z^GiqW0~@dMoSoQvUbMeSweuIaCby5w-z!dNh0O_(qu}iGz$d{)F*U8>NmcVnPCQa^~ts z!uEej}dcfYp2l zEFCG%Z>eDo?g{c@{X2^DyKB{L`15=P=^soO+li^pPGDn>iSxU#|6^DeLi3w(+L)o$ zGq!4)xc)xRsfBN$K4kxR-Xq5HepItV-NpH}?$8MDL-vyX?Y&#F_**rS%wN^TDdMdi zG{42(Jupb=G@1WbyQGP|hv$&_tF9YIq5P=3Wd3TzMN_oaenG}x{VQy-Iruj(e|1#A z@4a5GxYI?E$@i7=#picUav+{k?8hPxNk8ZN59$>sp);-)q@LuqcY=cWZ(YOFWyv z8vAhk3HA4&&l8wzO7r`?y)HZ3e48yR_|anj`T74Q)mN~@!3U%C#QodEzb4FZe>EHa z?_A4z{`peZx8GsUzP)7r)!KC;t6(foJGoy1bwK4=JlgR$B^_}Ce|0O*( zmv_E}&wtjQ3-HWvCfUC@Rz3%#Eas5@_j|8vFl4g>89%0Fy+mty+W($);4V1yT!HO7 zOZ_i7o&)CI(1mR|A(=0*R$Tw<9#(*y!WR6#l3Oo~A3x7EVMXQ@Y}GJsy|BKvAoLCV zi}xna$1EQ-iJf(;V&nF5{MQKj8`};24Kp?NlJVn?XJ+imf*N*fjyV4YF>TP`8qL2` z$X%A$h33D{N+pypjU)AcS8#7Uu;di!|7iWzMy2JK$^QD`+WNTFubAwAuqZXhZ*I@Y z`!no*&%-Ypf8(_K9RDcre=L)?;C^#O7Ud@8o6o<-vOOrXQjM&SBy3KHi~f_y`ki`@ zWB6|^t^d9m*|71cC3*g{eEt>5{XlcruF>N9Zyt~jcPi~k{U7Z98b|!|WZ^@_{U4w7 zd$4Y+Gnqe8?A(==O8Uo+26Oxh{huj%m7sTMGd4Ji^RK<%ly!gqlr{C|)(iP}d|n57 zuOvYxasIRGGBY-$YZZIDO`Lx}^}o=$?_RRM*JaFPcCKd)duS`p|8U9ue(PNiko{%d zY)e=xJ(~Y`v(9L?Gmh7PCiH*sN*~m>K82UsN%?Ef)0fr8gV22TWio!Xnl%>Fb&JXT z;g&HLIA!c}GJf5=Vm{tg{*6~|OP|k=U-f5gL%p6f|A%cPzwH>B|Gq0SAWL@=nSVKG z5RdAs_1K$B(*4EPf6WP(V3yiUTx`JcBdia;kIY5qMr(Fsk~se>6>q??HV$O}?~=kd z*uKP*eb*G{zs=-QaEo=u95w0l`TFnJMTJ@JPhfpBIDUovPl~F7=c_i8`tMgfk!9yT zWoL(T>xKMp8~7erx;N?n$E`GHuE~|m%1)ero#G}i>$n%MkCDD#etmo301KuUR?U<( z#QE3NZijXT2gv!$2Zu`P+YWJLe}?zjzSwT~Dbl}hqdpk*n=X;@t*VOwZjhz*ebAyQ zc=Brv$#?9H1vu%^FH+why>Q3;za7{(Zz+F#eZSCsAO5LVWmZ1Y&-wmM{Hjb?`(z^N z-+K*Dz-kRWW}YEk&*yvhvdb{6!jj}$`)nQtMO(A(2I72YJuHCk^BlWK6GZ9q46dv^jmR>tuu5}1#2yS)EBwOyGmwY#qr%=FkgJe0vR;kxQEQ&{F9l+WXDvq+}YxM zpZ+Z`Ilme~`Y%!AyW*4XG~aqB)bMvy8X2Fi^&X00Ntej@^!If`EU>*p<|iX(Oh?(c z8myfm<(GfHHT}|JTrq^!@1_|ZsBoeKE9b?Ze7>JP55@(nRmuK%^{(eY+kGPGpWC@5 z;fI(pq<$~Ee+9BTS(5q5k%uLBSD`i2SSYUFvQ@XBPQd}s@aj9VJpV7?_y>$x>d97^ zi0k)Ay)x)+x18*+Ybfi%dR-VVXpWxC% zFS7sBeeG1XG3Oc2KN0esH>edhY3(8FLqn~mvqeQ!Y$uBI9s0gK#wF8y$Lgw}Tk%n{ zeq?m6A3mE(>-U#q!*Hn8CDQ-CInW5(4!J|dpYqN#u=qzc8Gm}(Ek&8ipZK&~%0FMf zdmr}1`FlGsiv+2@^7)?LE)+*Psgm)h!l?65Id>wNe^Cog#=oIs*uYZh-{UFgLY{g`4#rZDiQv|c0+haH0{3AZ!4(;kOh|i{a*2kE^R0jFGxWOXMc&^y=-f2s z5&eu6yNT;}*+^Nenzo1ZzeAqSV12$+u?q*q`OYp@z@Pgg$o!+`3l+TPa+DWeqF{dc zy43z?Hh|XevmrY8Q-StRHa#=K+x|slf8U}wOT3>~P5R&c?kz*BOFz-?vpC-qS9xLM z<_;|Tf|Nf#-|HoJ7bUc!^;=VNF5E?#=6hn?aU3w4=KD(YRj6ufiMyS}`F`510KH1B z*nC%UzWYSo0lS;___QUzC-hG)mwv(y<2;%9YH_~pLY~0)@Z~s}_k4bQ`B=6$Gf7Wi zchbfA{<`iJbg*7r+`r?T($@!;hZWmzw#=+1G3o>WdBOZr*8P(`Y4${JXEBPI&x`bd|9789AzF~ zB=tKe&=?JKi*QEE{iwqE(eqVjVd3FwGJk$M${E{T{E6kN9KXW+;el!1IA~4>W>>&{ zF6>|Fc_|F1z3I!A1WG^W$Cr1)F2KWf6ES3`luw@g%G?V}!EL>0zOy4G{r4wkkoujk zS%?!otr)Hp=ey)lF%-nu_D|-QufX;5e&W>b9G^nI&-U>_b?CruKjl6b^8F|- z93L0;CHn(4;!bDz%+ft z`EF(Q7VZ?gk^aep@)^um_9VvL76i9tOWxF4j+w~>q19%O;1oDNZcrIPa4_}{0$kxPL*zxUbQlI;-ErIniv_4`ztc9%WcOP?W#@-;>xKI48~YvJ{PZN_ zM^&BK?B|0DW>d`ZDg_B=_} zCl|CCh5Dl|lJ~EvS1{~%?KWAT@i=Uaf96+_=MUDuUX7azf8cU0jvt}^x~BQ!xEnOT zr`JW`)@gmo{NAYbm!VITDXzXMegAxZn?IdI4e!ycT?6-g;e6Wk!W*!8>U6Td`@K>T zb}gLEV*JGQcgFit82rkP)ZhLCzvC(|4>l}CoZph|m7x1(DH$I!dsTMFI-V`D{;wWMmbwEj9V|{x2xMvnE%C-^e=`RTeD*`o-x>XUbH`}$BQ;- z|1*f}FH9e%gjO;8N&g`_yBAi593k`5+4r?DrQb>Nes#U^qcKF`B0BNrcPa1yXzXN) zrdw!!6VV2fmQ<1caf0OTkcIg_@bYYqA0fZ$o_=^TjOJH%@&PPp>O-E7ooJZ@tc@v} z2aEHY(oHfSz-Bc2E+gfS?>{JQFN8SH>7;)=)%6aJjh)R_9hR==pPw;(cOUwi+mZ3# zV#(h9Aerz*>2J5aRdCyMDVd+n&{JdHe~vMQu^fLwe#2IMfW>=V$@2+aqOI82zvXQ0 z9&Wvm-``=sVB}s;vcDwpSz8=fA4KM#51xo-U2XcAoQv@JkM9MHKi~gQpU&v(wx662 zH$S#Fx=lVp=I3fJYh%du6J&jSs^J*aPR%CucbdsWY}BFoUFpt5bOXt)4-q4A}DLH+}`55&>bK%!+Q*2g|=0|wjPo~>|(>Pjt zG>hyY<&V$r=MOibpZ|1B4B+?|`oG^oi_zX}Hk;ZqA4phV`MCNa?69Eq*Vp0~cKElG zmE?=-Z~Vh*X!C6e$#2cDe$1`(7#nNK@h9YW-}8^atX#?b#lU=PmL6BmEL!|$A-}cy zf56_|lg!U$=Cs2v@zRE`q#JbfdNdLCod_7F^%O>^p z{?18QCwH5?zbY@$78MUwlKD0L9WL0Z^$#50(w{2i(?ok0b~RRDzgy-@c>+Jb7B}J` znx5!G=8xZu&x5CfO>uH-aXxqSNXN|uquAW#h&NM>Z$O{Ma~4eRS)dP1f)HGR*MAgP+#>F*Yuc<4dTY*_of=>NUw76vX*%&xy9|liE|(N>~2B`nHhI7Z(4Zay;$7 zc3#>Zw}b_e^$QCtWwh8IPWA_R8>-@(@K`dwa@;oY*eq4{=R(w zG%ME}-)*G%JX+>}wON&D9xBx@zJ1S)b3^Bg-?6hN$ES>-|FeBY0KR$Fo~NI}{MNBn z(dcf~hwT49yz?rIIwBcAPRzgjyet#{_>N-Q+ETvw_Wf40WIle*G|W86{r^Jyeqnnl zHXoVA=3bVr=ksYUIe(IqY>NYV_bc)FeEg>g4{PsaU0#dx>0DY1H-0Q8?R(I04ffRH z7`w7uoX-z(Um$JR2GTz@SEtcwpsz_eGVk!9~%o5 z>^z0G&y8#Q;ZDa`9IC{UPrmy@tm-?9MckG0%h$hdiz^_@(iUelit}fjAj4GCb};pp z`yD-jfBxG2;cHMlxR}f@;obr4wDB?4yFi@3u{|5%z;PGSJ}+`?g@!#n$oOT*oesGE zQ6L$=Wa)RqQT@Wn{LntV{uur}hRhF*N*;!L$ET9^cl~8UWNH`iaGCV?Lyt~9shkkZn*ypYvRQDv$WcZ9uFIFa;!LipC|3cUbEY?m2ah=^YyQN`C(K`>P^m9 zS=XfimV9A&o_GHqKfX3RdJglS=(1(wrTp;qFY?DdD2<b29TgKji=Y4HcZB_0kCrRqXZJudei`tw z8wT7BBlGXZOdY4Zjv@8&>UAB|8kkDvFYBwv2|D^!O`J){my=#9-Hrz1g!fQhxdM{r8gj;LR$Gj9=_y&*Sk(noq0O zC9qL@Dw)506z~Wq#m!_7YQ*_$J-iZ*_LxiN-~CNw**3c!Y$X%tbK#n|kkf7v?|w!h zpAHq;EX(v5JE+6OAHw)$^yweaxoSO`|1mnefc+o3&OEB7_if|N5uv$Ap^|wHrJU=j zs3awoXiy{~WG+G(nk6DBDVfK}oS_gAp)$)9A|m5AA>Q+@_1m4j*V^~rd+p9Sdw;s_ z`F;-0dd$+MwiJzDwp>$y#D6)dpI;o*5fv0q*6%O;rwi@d8%Y0g%B{}uoR~$p7*UtmjPQfv{KO5;ITU;(VUo-ze#5G8b~O-0v68H~iPjitV{`jFl%;|4$!_1p9l__b9^7Z8_;* zc5dGW&JxUc4{Q>nBviHm9Gji%$RHU?E@r5$} z`1ZZm{%oAHXwN*J$*%MDGv4C51d7rfLqz`k-i6b!9@?M%=PCPqKA%ULDkTjQol*0U zdp^SWTC39|+;(td&suWvi7pM#G`r#MbNBW-?@)Fcp(tH*jb;Z45w0?GW zoC>`!Ptfp0Tt7Q5UxD*FKk$XOACJ$cYQJO*pGxcJ!>u`ZuhE{xe&+a$lJNPI9KS9J zQ-m}}BjbawpO*3kh}P)OV#37v+*f#4q8K}htnbWT^BC8a-K0AR#QFSP{z6ivMDrQC zSBdRiPxEP|`$2NAbP{@eY5JeO3H8&jM0$SffgG|wBy->&$tj&MvVU)UcV!sHE+h5P ze_LBLoQfmk?~3ULkW-`iTfWy6?uA=P{=5$Lhnnd=(!X@<2E3{}N$TU}NH@fUUqxMt z?ESXlyEL=zbWZ(UILQ}+4ti;9=T!P&f@6mer)he+2`}^vqjtkN&nDMqa%AZ%tFnIGz*-vLASttb00 zIy-koS?{f6d=nQm5H?HqlJYOl%yVU zBI`4{&d)Gopevi$N1RWsXRjru9-d@=yz?&=HXvsy8^2y$9}!b8(Y2%b3@z))JWX;~ z>UMEHKMa>cu@=o|!$4Iiwx;!Qx}hej`qBIu8XHP?N3JK&9~mEI4u#HJ$@X|BHj{P-okdK~VqxPn*B@f*PB&${1C%o+LwNfOR~lN0p+L|tBq z=~up?ho0>H^YyWE?s_~~uS(kIX`gn$xJ;kSPp0m<=Nd3`!$p7uh=xj0#;x5kox#@v^|a&ognj* zg?~IyGmz%fXJRM@-+v4Y5$AKsr_|d>JqTUl!7Qx(0cnQ~N9A{O8QgvoK=zV|?qw@hQyz=y@50+T`m8N)evZ%Q&(w0s;a~|iOqcn$eEt00q6h;6`?4C|{10D0Uzt`( zIG>w5ze&oh{7L_E`occ! z<+yC-vq4-xl@z4&#fxT<_3fiwY}v@sN107m@%&Hp#Fp6matRs#+_KX~)wEc$zSAqo z2p?{wkooiA9zD>1dM0V#V-5_#lJk4e+gkSi`1wh#kt0!}b%Lxv7SA4!$iia$$>r>y z(7uP?o{i21G@p{ct8w}LSJdy|a@V zQ;uE2T2+Yi`DOQaN#|#NB%dKt?GLldWR|KSSh7DYdXzD4FQE1FgKbaTbIn9Rd+z-R`!fbE8;YVa zd&vAy#7+kkwmw1npS$-;dsmkh^Yl~5XL9>6^ttee)X%wbYmndnE14e(Td@%u2UN)X zd8?2;xLU49_GkDMRY)AZ+VJ9YA)g`YmoVW?A2L5#Klz!YT*@cqe_DCJMtqqI8#zXt zPran~lHEb$Nc(PHrN(Z%EMZ!2#Q8kW{*wfJ^&{&$Nvry?Q@YvA?7BFg%aawc-DDOo zKM5%D3`lyp9eWdbgazK_?7J|3Zd0d*vKdQA`yTpL2Y*as$@qLr_fGgXf!5DXH9hg+ zV+N_8mSZe2SaA;-AGw`yM5{N)QE$NUEsT#W{!D=T;$pJ?m@nO5|8wUfn7WDEcmDw~ z`26Mz86S0V-h{!)DrEoU9G|^7cTSJA@9p#NN>)1!hp7Yi{e^tisa(d3C4I>Hqw22b z5>p+T&$$(E@FmlQ?FbR)(`(NMNpht-Ip1TmuNA9%9YMxNzb-XMa`*bdT~EA!!((QD z)~8?_t3D~t=lK5=5n{yGPa&Tk*X`L|^&`xBw>Y2b#jWsKdkGmIJwB(4aZh5%`pyQ8 z&ImD}`P9183q3M3$o%Hpa4V!$?#4iK?)?etk44vf37Tkv|ijw)ieE+jz_6v#I5(l1rhhTpFQQx=FUFyQt#f$T4 ztNu~4_NY6lpF3ByX8VgGSeI7Z{J5~cE&E!dBuc@b+#jX6asVseyNxY)CeCMVkPO{npf4E7>;LBapHrWtVVI5znP2+dc0Wwa^~nArXX$)`!5*5=2G=X-qet^u zuUIYdo8ds(_YM=^AzR*sja@9x=gi1Y662Zfr2pw@ug+{8BbbM(IGa zM)3n#-L!3Fe(9l$GCB;KDUDym`7|mV$&7vS*uH3S{Y>qrE}gxi`J9-i50g_d*fWuP z|HAW^*YE9ur>oYH@q6&)K4|KnLFSjNS6UWc8hW6TruukCk5%M{@It~@p^>C=>t_%C$ z)Rw0scbhV)pQnc$gwI=DUjK%W&$0=RB*%x^kol!WjwSfHtT*erRNTHFYOPZ|4(=l3_wDLqaBniLpPzOGplvG6=f2J1ST^$^W*^}A6Z)T> z?!}{XQ$1V?YW{-lX|hmdnbmu=zA*Yf?(3g5?)_%dr!KLew#p`CAUrjp6= zDLh}PTfiI1kZ~h<`;&zJr&sGbbk`qE`kzAszDh2qj3w)rd#1Eyx<3}PcfZBs_s4es zBxg?elKN>LIhYN&mc=w%iuY&MOjpH@ZZmlKC1HG|p*D&wI&zrVTot$P7k0Nr`;c(* ze7lb4+T-r^HDvs*44fMC$^6pB zXMr$tzKp#A+}{`KXPeIvNNoQQ13#YWeznB@k z{tqFa+5zow*ESq43OM^OoPYe3(g8_DYsmQLHn%Wqu_O8cd z3r?Se^S2w9W#D$D61o3&%(cVlI8v9LRgm4!*GI|5Dv7d_HEF-6FD^yP%3jPXhr3^> zkE?y(N_sCF!L#2&{$gf+Le46hzuD}&q++=n*?&~Lw;lWSV-d4|DbC-y?Q$5m#fLn9 zE7)f!yX=?60*u7<@k6_oSoAN1XTRkH`OT0@XQuz>5L=VZ>7%fInP{$o8MhXbe9r4& zh)k>@`!i2I>x#&*WU@XK)p8(MWjdKZYB`6&qT?=f8_VgNFg~wLc0*T{eBOMnkk3JN zQ&70}64IOZiwpUDF*Fi~ogbj{4vtTuf7$&}B7zD(;j|IQhmg-zOEaN+T8WH*qW4M9 zF8`uK+V9urpGs^st>F~G{XSuS(`)t(L?+ODo<8zUvdm`$X}_aR)uYQ;XV&VlxIRW+ z{vpwr=SJ=?cr;6cc^_TGMt>LQvms6%c4vLa{hr@uS+b`ive;W&aX#fUT1w|jL&*8a zfa@B_7`+%nbHw$r!J;E>d98s;^ZOOX-vtlN(b+c{;mz~60KY$T*|&l4%}FQYo4(Gr zh$-EP10%WjBjj)Nva$Gb=qPW$tdPHM?o;t@#U)%^%H1#IulnFJd@z52amC{N&6=5n zAN@a({T-Y2x1u;mi5c+xPkw)gLCO&vD$*hKac$`{$(>8XNd8`UhKps8UOtJ z+n;YzgjZ|%=M@F z%U85wql&jO!`9;bP0dupoSYCSZ<58Q{QRZD5>1%AUPSUY_j^YyHKO_3f2dmTrloCUPAd=?(>EGoyc2` zE<5j&@yjgf*+IF5AF)DC_Wt?)VQ0N8{G6i1GG5B~<@1;3c@!Jw)B2aX{kbH#(=cBC zT&RETLdr1aWltV|Li@bc^n)bel07d!Ddew{e%jv{jQLHQNq$osrDt=M>>%@#Mw>h^yVHdSo=kkSYNw9c*C%{<=MbiE9)c#@BFV^g#;a0YzpE$q!Hnv6&*Xg|Z zTw#1Y*dmJktg2)$W7YmQKb|Atw@0)#?4~WmyBXsC<#FqSEWx#n?H5aNehYOw;q!>q zWPfpWQx9}>l-ke++5Z>c|8y-Lg3r2pwAcN{m*Xp{b@QO+xg zXN48a&dI(XpWi_VcVO48C);#_({CZa9Upy?xVNx}e5367^7VIb$q!sU?L_kX>-BF* zOsttfFFC9MDSIsHabICvPIGLC|fNn$4%L&oO?{<`dy-a=*^EzW0so-#^m zCXnY7*qCNX;sIM!==pw9X0s4Iw*UvG}4>7xA>b9;r;(X>E z>x?efR+0L7TDLb!+pdL~gyToZXUqjlbPCvvLCyVP!upSLwFBO~$tCUocr|Z4ZFhv1 z-xTU+>7r1)JW+)Ad%4dS+W*2UE0NIk9?Cy*d+o* z{yTp?fl>!;Cf7m67vF#Vq){VT=V67^r?T(I*H1}t1$^^+u!Z+z_w)J8s{bqr?rcZK z@B5>EqMxl3Q)m$9bMmt$$%PCTGQauUNRK@zS-`wg#QD^ZSHa%*6VS2w{7~V1x#LC& z8`h2H^VsD!crkn$@BC3ApBWogF)gEeY>{DW(fu(G59?yG<^t0GkIg^KJ}*_bUDH{d z-%oS8U{Es6Z{It;akDrHR?YnvLVnwLS)p%j8tK2n&x7T9kb1NT9iDUd3;EqKdlf2P-NlT*9KXW+=Z!Y&aqq`_oO#S$7xL?RY&+)t zP$27_2IWl)TZ@dyMD>;=kxn-`B#ZaFFUm7 z^|$iv|LZf2xZC8&jw*5aBjNrIhvoky`nfKo{U3W@k4*|$zpzva8uAx=d_6z%VIWn{q=eJk99Ofmspze*#|5e}_0F90MEdS4ZR-7r$Z{J8&NTmB=srakl z8DlyMnJja@IKM6QrTYa}1G)H1*#DX6sgG0X^AUSb+zXD$hpb!C*;#CU;`FvyhqPU?z&K4OEq_3SN&j{5bz9bWHG`dt6z4PdTsw4AqWO%{GQey5 z`K13^_{c+e5fb_RNM{@T4oSl{DJ1_pUs_OqUvkMAlizJ8>q~#0 z`ocRZ56ZmxMm~Rz2j^nDbjH!sNXAbq-v7U&&KfAJs6^de?z)gaPyJM^yIf29r)JM~ zV7G+=*+18`;tW)Swb(R?j32%}-nM!#@u?Y#s+-NfUyz^L_xL^@WOQfBpSk;m@qGaP zlU$i%3+BY#FU;?I?{9+ga7Xq_BF^98`|^1IXEcr|$?oUtWAZ-(7T0hR#rJ_)wmfWvtk+~DgKFgE!_0y9IFx{Bu&wtzpiN#u)zpob`AbSvB z|AhRh$23SxjcnmMfqQ;J{xq8Y;@(dOHpE?=zul7+kQY6g+&{cVy1Vvy$~-bY(n)TK z*rM^sUnAp(e?Hr{TzhuaB7>Ez5a-XzQWF*vrb4?=c0Zp#@73)w!e<_-e^Ju?Fg7!2 z{$ii^N8$2BGQKf4m0(rPCR8@-myo}UTU~HVvYqq~6Ylt9*7?JT@{m1$zW#-4FTj-< zg_zn;oWBVF7}#E{z|g1Mb)o*L2W~_`!8_7F%$&OmzJ>DS{Mx3#v&i|T$qtU^^h=mO zvVT)2iP|s}r`vL$FZ2(G-F*n%&)rD>@b225lBzw7)IZIoa;$WaBkOQhoWBW$3Q#=n zOvX3kQ#&x{S@W3E1#$h`$<#16Y&@oKl<~voZ&ZmUluiec{$JSW4!HGqE<%;L`-S~& z2c+Bc=jz;IJ}1P_N4w%~j!M6kr2lv7^#H63OvE2A86W)kWM+*7_f~Bp^>4%7F}P;7 z9VWrD`}y=eze4?sZySr8g%!N~kdVKJ4I2^N z`5mc$uX^vs_6X^YXk!0=V%Kx{Z?h%~A0f_Phxc_7+bKhM{T)L7w%&b&x2JtLL&U`P}`&`LvW> zYPhx2i?qKkaU)sip)KrtqPYGUpU}dM13@r)BKv&4{<&%!;_UXhDAMGv3;9&;-VOJ9 ztVHd6+56|8Kk;|rK=gZ`K*qP?|pU>xS zv-TpSFTFt8U+cVB+-^hj=X7Qhs!QLZZFB#TF#fnAoh`oaAW!CZmg%0yb3aX%IaZuM zosv(Iiep2_`1tkn$9OuW8=2p^Q}Ro4ryivK4Q;2u)^~DbM!h+Hg#3N^rHCC`&SZZ_ zqg+RpuyHQieucYV$ltEyR|3F>(GjPS?hri9zVXJHLj{-?Wi& z%s;Q3Wxi?7?+EIXwmF74^Dm6F&)=)NVaumzlFymegYa%2&FAs83>EJ-lKJyVPHspT zp2N$ZM+x=^_iqY>=F>xDd~(=yG3J}le7EvRhNc`D{1li^L;sC^nXG`YqJQ^wUp}uGNis{*c|z&p-a! z|67u`3b3%0{eSY~BY=An)mypjn`AXQW=uG;DmvcKZy`D6mlb*Fg_#aO) zKKAM6$YKn)uxD$;`80T`jif76$oM2=a!2gA7Dno0xAHa2wcsY3ww$xyzif4Q@#mc} z-C@5fn#?bD{cjKgXVH8nrrRRmiS&HF1>Ex$`j1Wh#$uCl4zE8+$Y4|EeMNb7In7tokI!)OdXJ`;&0s0{kCq zkotLK(^pCQXlV_W=khuzx1vd=9Nq zLS(%YIbUA5$%tM2FN`g(=k6Ekr&~g65iTta!}R9DvQ4oukS8PR3me%r>R@%-Uy%UAs48 zeu6lk-~Nt;PeL|n-=`P{;eqQR(!QUV8i9=w=i#CwG25~@j8(rC z=krDvb+k06`9#4ermDMzU2GxFXQ-7f{HiCD`nmeE5rWld{!Sc?VM{`9upl)~KZWO; zuX)e|x(c*@R&N;$w^#9`|M_;5J=$4qB;#*y^KtkvFPn_NbCjo|{g;EJey$q31ad0p z$@u5m_jv4^aEHu4_H<2`o?ljjXx@B~I?sM|HQbLa3*^}2KQjLLe12PBgoQIS*q1pn ze);*w@8^C<*3KP@g4x`4A)ofwpCN1rUq6L>s@ngP&X-Hb{LkICO3ZfnNOrP$Kc>*W zA6TRU%STS6eQ)!?m<{?ehb^uW=hNwiI-DMRplJ~op9t&YyU#nbZy(ZGS5t95Bdc_A zb`i~IzZu3TahXHL=dayk*=>^>?6R>qpA(Nt`-h%Ik^2u$M-73?*?6*l;}%9>lKMsr zU%~zV3+?*^Ll0^FFPqGdAN?~GZL?`UpPyWcs*mT${7^+y0&;3^ll7UM@6(Zz^oI05 zua@pdQ$O0iKXAPWO??g0|Gd2Pr(|rPCC+(s`Y7bnu=F`Je{^LQI^1=keP2974i_?| zIkqj_^AqZ4{$wSl9yfx`IwY>2cU4sJHk{`3&9YAH`{Frl-$QXerw(X?^F2NAbd)%s z`)7=12GQy4gt9oF=V$3b<7*(9pPa4K38yd3CgUH~rdVeCu9SH*aXv#sdSP7-&FB0P zLy;Om^ZED72$&v9CH1rDp9d`8Z6o>A)t!a|!3W{8hI>B{)VCug(z6fh&mnt`OyBtS zy^B#IHm2St_4C-8Ex4lb20@2p_w)6$Ea3pYe*XtbKdpaXl+LfUWAV5w~_fvJGJRJFMp8qFMF#j zM~2HeEV7mH!{@JlUm~Woy-m)isfJ`=K;3K7zpM^Bh-G{Jf$}eF%`d}se>-NnQk=iI z`!8{Fd{=hYSe(C~N%FYyU^uCN1yE++ob6f7Bys+nhPJ@7{f?x4jxX!X_D`J6DlUra zpKgnGxYf%8Hn+w3Q*ax@6#v^y#y2j-`jBr$>!0-|6!Ddj4!_b zI9IV4Edpr%Y~EDEplw&Sum{JV&_87U3RqJ)9H$;}zfWj?_nuH@+fLb$_36627MQH% zNX9SK!ChFNQ?pppesTVi7Pmw8qH$z?@?keu7MQh}m9-MLzk{|LK=VZanV-BmunQ)I z()<~|jA!jDuCo`D#QD3Q(+9h^t{~&9yOC(A*y;?2lY*HUrsy2T1!{ryPaSptJBZ7w0cqbuG5fzQxP`2bS|Kj-5UFwkxrTHNNIzmUJ;OWNO4Rj;8u*^H-u zLjLaDQH0*g;b`p6{r^Ns`1x;#5*0S0)Ry(?F3w+meM{_~=s@-_nmjdOk(Hrr`blyA zOkyMDS`Zx7%d;Bb(MCNaDBTR7Ej^^*f*hIE@;&tYd&+#YB z-?-oEi}yOqN&oNmRBKEyrR}erG`AJ;cRjDaR>;tQ5S=f{zyPxm>c}$;$ z%kle3{d4*mjnQWcNd6iVlCkXiP2T*M(Egr2l!c*jG=Gb`9D#A`Cer`Q3@O3s;cb~k zoQzMt{dFj*K~t$I)3M+>riS?W*PpDfM6@-7&e@sJ z?!?76!um<}ktC-5@ftg;bgFqioF9K=t?LiJP0L9BruG|-PPb!mVTtVb^Z7fp*BJ|E z(fSu#BBNUYVm!F_C)B?#+Uqdg>n3kMfsjAH zm~GfGwVIqi^lWn!1yz4Y{R<4b1_%ANEOECuf0{XO(P5@3X@56tQAWW58yHXIzQ2&a zNVgVjR19O2G{yDrKvgT`t{aI3&GVVU{+wP#W^9k!Oct<1oWHByT6o`gEZLv9JL z+#vPuq)s;EAHO8y-)Z-bLO=WuZaB#J;@e*@yX)BZv<*9yFT2jyzq$+WFrl|8&;APa zFYv80?!U9f2Lo~b!v3{j_9GcNACNM+HPY0jGsHyxuSct{Yzbztovs{zfF`d#w5UM~ z*9zT8{;GC*FrR;$*g{Kj{=P5kh{nGDWc;f*p(|Vt&miq@pVVX)WqO^x`ytMsrS3rV z+7n6EM}iMa@WvvRw7+wMU10wzg_nO3`hTO8{85v+73u{XpThX#+2k;^UB3?&4c>kWq5dtc%*OX6FG>A#_sfS{?r$>w)i*4K_IjGXf~&Pi zxNSo6=ar*^=?AQ#VkORBT2f1os}UG#D|Gi?mEUP>YRZ{$oTAoJu1fBAmiV_6*(~b_=4O|@!#BIs9EwGp`J2*!{=Ka({``g%FjpU9}~{+vG)eHCuV!uIGJeFX)wd6%`s$tu=d^6`V)A;FB$bl;$t!;4AaLXhGC#Q1>^LU<`bF}YlW+qj*VRcrtuj8~vN^4f9g|e? z;OsEcKJUs`W3TnWoCk>W88M~}rs~uB=v&lHIy)P}s}BqLjC-Vmx&&7;K3+4(oBcbz ziRIrF=hJMtF&f_ZlK$cDCmUGL;2Z4qc=7(PAq%@c{_*U3oV{_P>bups#bJZ7P95MB!^M~5qG34}g z(tn(#Iv6_=mXQA8kt4SF_-eQxvp1*lrS z7qfqH_Y3q6I_z^Up+ zWR8*X!?({r^vkfojOHsQ=OdP;c46N=#QDme(GovYtr7Q_`+h>c{79c?WU* zdvK*KVhikH%Bx@U{lga_Jy=?w5awsV@g?kk?PsWmg5oixeU3_-!1AANWN)*?_0KA& z6Izz~kolQa#cAyF=v%DKmo}pQVc%!nF?Y^%(m#AtKNw4;J$#8#viHx|H=Qs$3^+;i zHzj&3biCH_^3%fjIQHOV=;&mU{^5dU3$ge69@0M?>>7jAl2bU{>|Y7_%k7(r9>Lei z{LGfVJ8*Lp&7YssNo3AyB<-(`<}ED$)0%~3$oS;zTk?iaINr4j^Bg74pY=2~IG9-D zL393F$X}v&Yvx=sob(Sz8MninT03NpmAxN6e{&RjGQY*s+3CMrd?Ms8w^9$WlgFTf zx8IRJzt`i|MCN>IBTKm<&Y#ER&Ik+eA>-rwwrT7HyUF@L=KMq9em(Qp9tgcPjr0$1 zRSm(#PZ20rM>5vr}Y#CZs$S3H8@V{#HNQfjI@w$oGR?;&7iTZHApPN|A!cyj; z#qlTHFJeBZC*&7QBlXW@^-zqRPxF`8Y6L3#uOZ`);IMH>s7vP6M}+!U?-~R@j|?(D z^E72KjJ)@twnp}R`SHgA%~&kSJW2Lv>5bTk@_E|2~CZ zXMV!4dB3f2e#%hw4u)-O%@oVU`TLMmkNb6BeK`N8>pTcJU27;=Ac|6fA>w#-sz zlaz*&_2GzZ8hEhF4(|?e&qq!$Ke}#mFQ&3}8vCj)&foTT`sgy(g|xph>VE9#ijAzU zJGY-kIDeAm(FG+26UqI!-46G}u6@B|e^w~7#Iu@kQr}v=8v(6vtI7P|hru2=y)K#D zACfnEDn7QP^)2C1ICOi_`nKm@EEY$dB=zk~rL;HuM+q4}OtsmCISS9n^NswMpGMh> z23Y&b_~H9^=j!jE(Wf;tdn&umx3AeJKVy7xC*FLhkgu~f>TFY@4e7u2zNCQ-`L?9} z^zYQ08L?@sv6DDIwMhnO-NA*lpN5P4*s*u1>_?5be(f|f!S=cdr2m$5p%)fj2u6@6 zr;oz=nyKDqcDMXG8*6xui%-F?uZ8JJ&sW_LPR6JAt489{oz>X5f&2dv_E&{VXJ7oK z=Oa+_b*A%!v9fjxqMG+(3-imFGa}%-aW}d)?;jM}PdV>6^fadVQd_YJCytbm_Ve+z zU06HsDS7^&<>)goS=E4pVKRRBe5D;O$1ye9ey-X71(&ANe6>ty!(uIM$oj?Ma810J zYfIWkzgNB4qzA!lKtFN5R&;9*i`}D1z8;7Bv*8C)N&8q_WdgIf38a4(Z`K==o=Eq9 z5cS)@pH^_R2*=pw{X9bdDBdzFFRH;l?C+@=jXF@Kg*pR z&ZK|j;}F2cwMu2d%HsUYA8Ll{ySz#NJbXxBcwC$c-(8%21C)9B{mly2coDmZ%s*sa z*}@LxUS|`hTK~`fMS))*$l55KP42!Ly>4;*2<=-)D{qY2wHBJq{g*<%UR6&=izDe| zd}ux|65m$tBK`CFhw;$8c%0;`)@n26x?CmC*PT(b2X@`7NPTi$eikzy{~+yK{@A;a zAJmFXs2A6#1%H2_d_pH?a$B4)BfEA?Udx*7PapJ33tw)6$Ct1^^+}^2yPPmpy5m%w zFF6H6XiRY?^Q#&xkk#DXzzREx^JURshDFl-e^h;HPE=p$lm+3`WO2Smvn|Z~W(jkx zJ}c@!S>;&6T6zXDwcq9KOD9}QUq$902K@GhU)WkiUgG!@@^!vC1S1xvllJfaf6H(` zaTop#lIagW{wrRTfG4Ytlm7XFH=FTPk<$zf1J$k|Mp0SX5bYvzku+4DA@D_6>~ZL5#|^Awmpvn4c}3h z$Xyra7u>tvhtYX8R;0!8Bjn3i_a}N>FlNVUx$8o{97k)gNgaog{`sy|ItWMvVzzP5 zSIF1%DgD{>xk2o~C~^HV5ABG!f>GF0Cwu?={Hc}S6y_bgfo&Ww&R5ibT~Vq?^VMQV zf9x9)MB2xmOETEn`m1csCvm=_&4*)=bO#xgzwhAhjMA?wN&kJv;EDJaoy7CsA*dgH zzC08CZf}O-Ywr08{r53fS77PUorvfxu3rIhiO4@9J^!2NFPD3nj+__8WPYKbVIQVd zKSstl89)5|Rh#7Vc--MT>3?lHe;><6sFC*Z{lA~sx!9O_d>7|yeW3pYkE0NSn5q)HgMsDEyeV6E;1?`P=d;5!ZSjBmJ|A#4Tt%P)x>; z$M)=pT-syU&k*NtPpEXi)Vpt_zG0(^0gtVXMvInqs!Bd!(oj8Bt*+w`Z-S0!?=RZbHWx-k-*x?=G{MkzP z<5_6a{B>M60B_xzxZpJ%*OpH+t^b)zh$*wf^KpP$oy&O;jQe=q7t@dt~h_a zj9u_5WhH4}i{|;l$2|##&H5(v-~Qd5CG}r7W0Ag$FMfY{m!nb8ytjk2uZuS%q3V0S zbO$VVzp#F}SUm%Mjf%)EQO;{098>xTH%o@D>UuDb(}<};b}-)1ImW$n9O zWk+X<^S96&s97|h)vHDe#p6T0Pp8NBJFR|^+G6I z`byT1Qhgs`WlBp{Z7j~;&`-Z%A7R8&TXOu#3HC!xnXkoEqAkhz!Cy@uHVzWZ{lGoH zC<(tlp51y7`?hK_Yd2AxzlJ(vTp!?s5`FG|Vf>(BKaHhCtY8I@P^Y!g!MKm6d+d;;sMloyAw{({z0w)0ytJJMgAFNeDfpB?9s`gXmYD@M+UChL<5pZ#&gGm&RM zg?yQ{3&Z`EX=MK6>ZFyJ+mMS(!#VpX%>R#Rm5h69kCO4}>!M6tKXQqTPw#d+gah*) zqMMJ5A3k3eninzA>kAn_G@3s_(a#o4XMi|grFWY!??y)+UqbsiR(k&B{;xyX##u7{ zGn+R*@GQ-{Msjr;vVzWNTfU>#ioS*S!@zearSga~~{(tiug4`Blx*0c3p#rX=l z*8}gTdXV!6p*<|HYfu&3ET?%S(nK8;9BM( zm_2$x`e&M-FJiCp7cxE=dgBRphp=PS~pGkT12AoI5!l4h`{jVWwTFLAyOujq+P z1rO3bX6%yoS0@KRHC;SD=o^^LY*eqXJ-Xt2bsubpw&UiK_A$TK4I4VseBJa5z{|r4 z((~^)`zQ4O7uC*%W$Y%>J|6K{h4mA2;o#2w{|fc1M%o+nDenmBe|>$h6+2#EB>n$- z$zfQAJV5Kw;`$}O{1Srad?xFcXAVkhSHUfq`A~8F(yWp0#_8UXUG5{}hrgfm-YXq8 z-*70ozf1Dl0ROt!@bVu*zHUFTV1IljvB3pgf1+?cAl$wSR=YWn{#WjynXLPT6lO9; zoUi}7_d;m+IFhgbCJe^o-;+qb?1tvBoSVh0e1bS%O$~Oqaw3f6>+9FCc>g&HdXG7N zg!v86gg^{moqz&m86SNAzU|d{C@|PW_E+3{zY6j#b5S-`c0a#9P_%j-emfo^^BZT* zWMRy?i{ySog@(iEQ+uEE@5B8rqp_i$)UUg-PjN?`=4-#39NWFukhG82vUFKh^$=E= zE#r@GA7^-UfXYrAbRN(Bej#6NG6yrwFVY@~GI73YrTsU#eI2lMob3JZFL;7TUkkayhnaoFSQ? z2y)S5+FOUP1BDzv0H2>1Iy8v$^LCO6qHIU<>PvFq z^OKf4i?MzwZ2vrQehiFzV}-6enV+3@Xb8&R_>=l%&~pTS+0P;UrwPI1pfe(htbbo* zQ_%NyJU+K;{{4ddzSW`y*zZB})2GE6n1^l0!zAv0AwP|$QgC%!9?4JSw{38IT}1Au zK5l&kAGF!3FUv6E&0zkGf);%2jD|E*&` zW5xN2EANeWx5twDb7%TcY)|(m^=FR$NECORL-q$AcrXq{CsvU8QA@um(6FTSCoE_o zV%u*d{i7*E*I@Il9MV4;^E(Cqt)bX_+YiSQ#QpQ0mq(&*-E5LCBzvHp5zSYoV-UvuizEBLz6@D} zgO^fCzJ{JygCR?ENc$F@wjN8R=Z8`Ib>Du=hRyFna=-4gl}BOU<{nx9IbePjPWL_{ zX^Xgh>)G%EDe|i9;%tr|p?w?hK%VKmZO<0m<*p0)$}!bvDJv~_^+%z7%m398N)gt$ zb4gsEj;mR*{BM42RXE3&a6V{xxEcOVA3^FBPF_!75dCxK4|OL^$0OKjOEVU^B2~4cDv``s(m4uUzf9# z=1#NkA}~V64?jOOO1T7Cb3UT%ICmZ3`%kLHFY(_26_PLS&I;_le|u)1C(hTB1N!V% z2MgZ(g^;fbMPn4?T4O~Y?(>EAZ~kE`mbbuR><(v?oe>5Lvh1w6kWPioZw+>inI*aUIO;q+m z;;UsOU%raLXq**C=0Eq{UyPk{sbqZDWo-=RXJuoxBgc=>zbXsbfJgfdk@G)=UACjN zYazX#^hrK?^}37tDDM3U`&ZZOl=j}=twYlx*>yf&Mak6|8K}Z47I6Fs^{aJ)0`n?2 zV8=Id*M<6J+sT0Kn>~m(zb)j;$a5IeJMYW%XNmLUR?!vp>+Nxl*B{2`MO&gDycb4H% zlZ=0Uesj~`V7%6ggIhg!U6_BmaW)*&5;u_g6s8>ug`PA&C7n{??{|pIpBHCt$Fx}& zNdHPX>=-u9sU+>+?#0(28B)j7Ct-irzsOh6P*q{CmT-Is`SI0LWS7zn*v8}Bbs;}9 z&Kj_1#)EkKdxZS_GPGukr~9(RL~(wyHO(>Qq8)1Nx#ug4-~L>m$1JUrS^M?k{OI@Y zkGGp$F|03lKfw2&`uy6<_WZfRqPL3sPv(1uN#h$IlAqmYop8o4l$^gPeK8(!pCifq zQeDwB^uH3z<40)UR$q_6RnHA%{W#n&7RNHSk^NiM%Tl3z=OAg{o+#yF)xGniefy(w z90v6jBtJDe*ReYD1F1igtzRQsxERR>~Fr2-=2kz9>k*8a{jrTAV1)B z$C_ES^<@FM;`~&eHOJv)c0B(`$PZ4>XK5`1D0~ov%M73Dcpw zDi&*+_df{r$2MXK%>P?Y`rnVrV{zPh8`*#5^)?k90}qn+t1dSe_mj?(`r~u#I1(}{ zNc*LG;X3j+9Fj*@9)6!#t&j6K62NE{N#q( zFuVCatT;oQpIuwKp}@-yU9)7*pKrhRJzv23JY37nAB*#|ypObhDs&8)-!5?8!=~N2 z$Oc-q72W^f`P~|?-%f-gZ@&q@|F5jIGrX;5lKP|5Gy&xak?&4GD2w#38{#%%qV_>Dzdh4o2MoHOC*!w)u_rLyr2;2-`!)Ig zby!#_2E@K6`Kf*N1};66S+`WqJ_+rYf2|VxVQ9dP4VUr3ub(738?ryr9+cb`Tz*l= z&#q54?A^_Y>|CrkKc?5ZN%wcylKE@hB@5ZjptbDM1#x~}UL1gNA6-a(8t(39Q~MRM zVt;Y}Cnv=QTLNf)BBnYc$8`qTKQQ&^M4bDyl;r1==L|G7#=y*w<4dSN3AIac#$Y|! zKkz0q4ihKQ{6sfygyFUWWPWMq#~sjnc#b@udDpWO7_h3GjL(9*+<=e5dt{vz_n$R# zYasVfiR4FNk}|s{jlrf^it`gC-;v!tGms^B6X!?a`*8Mg(?qttSe&1VgziYuvgPHE zg!aql)gpFm%v$zDjoY6k>_4$i9*DYl7t;R;nl>E&eV;(ur>Bk17_vNs%wO-E=7VJO zrI=^Qy?#puhuU{(64cPMBMt zBlFkQ(%lSsEy|@e4%z$X>&sA^n;3he79W3d*M;%>qtLf#u~3QWtrgdo6Ze%_sJA{- zY~Ifyv`=L>JF?T;2C`|>#rbHTB4K^hX+Ea7_JCOx{z)Mp-|daqbnSuc%tUcM%=&?O zES$jZ7K!V}nTb8{vj}AVCf6aH&0my6=5IVU4Z^E&G#{%&C1~92O~yyFPPpLo#pz`J zuiYbGe6Nlm^`m}$C}Qrf;qf7~FTKYtN5ji?A}`p2vRDKXJ?3 zg@ACHj|sO=Nqz6zq<&PdD1*tGcO)OnHEU7-M3FgXi}R6`ro#Hn)?+5k`$vU*v?wrQ z4QT^d##nJaX4QaoQJcV?REqO)%%~^!#eo+eK~NtxUmU?A$0soh6LI~h`ZoyfyQSx| z6Z?J4Re=v}Xg=~@?PsQzB3AZeJRTJ!)~7l(m(kTF$<5R z`=@07i7>wQm!54DdvhHbU(X$zfDJjBIQUuS|MUAd`hH4-Z}~n_U)JmFhQ+f2GQam= z%4xh`MDufX>MgwdKf2C3s;aK*;@FCXEg&f+ih^{{MTj(_*n)+vU|^sqNGXb_SSTpA zq9}HQ-QC^YqGCUO_ZzQ=d-fP-J^!9@k%#*`bImpP+Iu^{MC*nUA7cISuKXJF*HohA z2c+kszun|hjT#21^d(aACn7(a9SlgXep{N@UYVa4^NFS=cct-nl=-m;ZHb5+Pj>!i zYomD8*5?E*`SSiS~hP{VBZ+j9uS_U0-MryMfG$OUU}QGCy;^h2UlUKv}*g z^7Aey5+UEl!$5X^fV@Ade1ABMtE9^EVNrknj7WsV>MXo>RM!vr{B`cH46Gcvgw1FE zOJ0b|W7o6#V|;TB-Y?#ZN_ExsMP8q>%XXvW{&}{)&eFJmZz(S@tE!q0c|PoU=rv~h zRidn2>gV$F4Ym|jBiC1rS$@_ZG$8AZHmv@fhZohW*_EC=SLR3OZ%eoac(V2B#^ZR} zmOO(lR#WE3Vub^WRd<~D2CCmrdA|3+ny~zCXLkL-wQK`LqJ)fJDDx9NCKQMF43PCl z`GWrBY8BG3_=DsV0>$$UM%RhLjRxaceF}a*0>|&Au=5>*b|xa*EQ{U0bhG6QbU(S6 zJ>NjH{vwnau4mUz=eVzhzQ$hYmEUhK?mzb|*n_7D=doy^#GknS;J5Dr7FK`3>XXad zH<hvSzl!?w!rzc4n%Yp!U}b$e{Mn0^jOjvKUMusJ;Lr-q zI(o4Ce*;%eqUDQcP+p2MUm1Fi*cuhU_D?s+3qLn^#@`pp`QGKMjdX2CG0WGCAz^qH zF+k>zM84J^FQmxY2dQY7GGC^zqi}reIM!be>=}d6J}K<_=@ zJ9x1BL+&?Dpr!gVNVAtRU!Qk7V$)B5z+KWW4Pkx4^WrAz+U6jwicnsk&`9!v#6a)0$xb$@q#y>)EA9$1(cO$F!iVR}aDyoV zf7{_{ob>-MuFo&-;6pCsJJYlZ%KZ6ku|l_l?ri%Ug-E2J%F4p7o><@%|W*a3z2`?K{kk@}!oqp@s#^e&6V(WS{U z|0VLZ(Pt{kLTBMgAL;KW?yvk@G7}w-N8oK2GHSMabPZmSNQGY{!+4_d4PfwltV(X1KXqLY}V*Xg^*+@K%NtWdYB0u;0 zPld+zOnf$0=I5bVChqm;`N_DE1OGN_+5XQWV?AO$cC-3qXS*L~Q_tek4rPAYcD{_j zc~4n=s`dIkI$o+ku3wb-X>+3n)p^;Fyt*mt)43tWbYx5$Hh;{CG{dPqw&>|3{e47z z8vE9lOfE*yO@C#+tWsLzY?>R(*UH;dXjIz_D$Z2q%X@$`GTZZf8Qb|_+?S4QKDl?$ zX4;x?fKm#S`KnvFBQAXDC-Yy4g1^7otRDt+jl(0^{ItA3biFwHxCZlirspoQKejIyu z!dsL6=wYM&e&zYpqRf6cF=`B(FU0Q~ji#@sBCD}Sx*sv< zn+6>@rL0e5A83-FC(jR3o6~=@T2te(%KT^)n`5h%E$g3pkM^aw6XCM^9mM(Ui#yuD zZmuhvU-h_`NY1mTlgnmheTqqPLGPx1?0oi|JH9A%=*X_G%~?}K_SySM`>Zlw$16sl zxL-f)F;Rd2a=zYn=#P;qhPeD{=lC($Flj2fmEVsp*1v*%$vuZGH0Q&)gm^( znlNYysy$!L=2w2hH(<@*ozU@@_!0fNOPyjQKRzw9*kaRk2p_Q#(lJYSnWtIn3HG?n#NucJ~hKXoSVk5%(4&lf^}&O-GQ z3t7IJU0s6Ep{rT_di!Am-lgz-`AsgyYRA*E`X};LQsWvrnmv})KXLxChs7uS{QDQ& z`rZ7aHECHw18Oi`nXlplCRF{V6>V85@gdHSINh>9u2oz3rAmJvk*{$he5i_lD4ESy z|9pA=P=A6oLY-YudQY7{Rnk!ZH~(W2E!Lk-k^d?4b#0C-YJBiz>th#JKTLHGN5`+~ zpD&+3D)ZV(iOu%Y%E&{C`NFq95qN#E59~{&_XmQ%>Ub_1ucwS+{riOPad>seQY`^7d4x#X8l#8B^$BKWGDXiQP!_j#wGCEdJ5i~q~{`E z;Rmnbe%2%Wr=zZa@_fN++b7liCx1~iNc~)%Um5GyqNl&=)8*09_pc$GuXEPgl$!cm zQN;zye6<^Hj%CZ+ps2F+_ZRs}ZRSgKEQIFdOFv)KuLIdO80P09o4*zN!`)-1QoCEz z=t48;{tj{eq`#XRPR04M_3>J+A4>aoVEtF~ur6@8*9V^E`-eq-LKhE!&5MyJOO)Op zvH$CQU@SVR&OhPm-}Emj7&(3hTmP!R$-=nr3)uNc%_@1gwsRFbfAV4DMi@3%-H}yQ z;zO)|OG`_T-Tf45Tvb1p=LfoW*WtbGp=|y{)Tb%uN-=!fe{jxG=EpFtmg?-c`eZyo z{r$@4+s>~tCCA&XSbiG6u)ulM8LAu0&zBeZ`EcH!urQon#7O>J+@JJxferd~aAy5^ z)Q730y#cqsET=an1mjeTYLsF+VJ`0I!L+rrrVbIp=%v|`vks<%a1pSr&2f-ONj zU&iJG5#=zF)u+56H7xH}RPR~P|{;O~>Tl&1X zKdEd~q3Zth?Kr1$02`saaXko8x$_kM4bKc42H+v%0;`8kf&HsNyGcGka7`*;wqO-{1@{crva_-%T?`m2T8zTour zKlpY>S-;}LYm?8(dXzjuS-(uQ%;-vRONup+_=2!M;BAN{Ua0nyd4L#7zkmu{nqlk|B}zdW{Y!hXl?2r56HRn)IN`G?T#zzMcKTK2t(fesI_ z)I!aV++Uru{)&_DezW>@<#KJR(6=62AFItXBRXtJ4|SCJ`Z3lLEsI;T^|9UWK)R~K z^X1mx7AK!Nvih~fCxs?0NT*{_%6v^d;DK*x-mHGj*W5+(R_vq5mGu?*O6eScgdw3= zTTxlx{PuT)m2DKOUtKc><_|Z#=AviK`Rw@?J0~o| zlBp|L|Ft}0GtNBPiX2h1-~Cejk%NNcttt_XX&c!Sn1- zS$`<iYUv(%F158`~oApI5;GtrWsm)~D2@^v-76;9u`V%HDnH4dQ{ zC85;#u`*u|Rp(b8&39nu8=j=5(&(Htq9kR$jG_ROx5U;*T#&4;VYa#p_vxNpIRnOj)CGMA~&m-}`UW>3`o$@4Go!aJB+ z_bx`Xk@ykyYee98OxXJ!>hpO-zOJ9GOD8<*vh!K}>sr#>K`qGflf;*p&u^^P8gB+z zvFAS(9(ATsb)0EL=vQg}*HfO)r@pm^mWw@mzHh<)G@9a+Mvp!z^L00cQ0)X*{ThB{ zHyP;friP!C{g?ljAXRo5B4{R4p2!Q3^g-0G3x2~(^ zSkQ^D%6z>lvBFmUR_yuFEh&t&gG1<-zWRPzIbTIn9T0QYj_n_BZtG2ciz12Yy)Ean zfh=F>c7gCs<-xe~#TrsNenDY2C@Uvr9rvG#DFOut0F&VTHM2X|EW&olM$Le6mb zMh#{CeXXp?INfp*77dZUf3bgDYBL>eUZ%7CBYft;<>6fReDX~{mSg{ze7rm;{d|$H zGrn7~E2oI{Uws!G!~1A&^Dw#q=)Wa-}*^LtIN5cF@u^J5kqiLgK2+5WKW@Db2>I0P$;r0-A6 z9~yg4!SuL^EI;uhRc9kcr?cyan{Lg+&*gL3`Zspm3S6m~k58whe_!M$sBkN;S1Q7Q z4iXk+}aWrXqgw0PAR^NkZ*V}mDt=1p8KHWX`6EQWusrI+1pUd^B`(G{k^rtqv zey9JSrSC_qZz1+E_^HYmIDh`iF%b<6 zCSt`3_2=dFZCd3Fw6I8L`@g;J^Ks5}E_=RVx7#aV6TghDZwJS2!>HoTut`?t$N0l> zBwskp*0(Xk@1y0VTL|f@=0nbp@4a6*wW@_ROh4Sr`WRV&s}wlhPayqK)pOT(> zW6)L)Hecvt6b9?u04xia_<`V$uH1^k(^sndm6`e#(kT`RUk1bMyP6NVKYHkq2a;|Gm^J*#c^X6(BY&5rI`@7bs!>NKQ zW4~mt%+Ho|CuGiT%hs>5@zbbEy%aJoR_15g10VEB@xZ`BH6QZ)Gj(+s>b~+vps)J5 zynoXivxj`gZKIl5%JWwj=Jm#!PTg32`coK-<1YuX{#&ao5d#-ZVD;(M-VB6*=WBB0 z0&Gp5gC(;5QojFYOyyO$y?ZG%pGka+_04d|c4#czghiv2^~s{~NsLmh;c))@+=d5e zG5V$~{}lVXo{@jhPPK-^tq(?atWU>w)?)RkRMU!T4l-lw+xx3Fs932bdp>5*?H%dK z{6I?Rr_9&x`Oerpt}T1MPrQ>a?AE!n{^xB~)&8rB{s`5R_z~;Z)DL^8+WDH&ShfHC>TK2@ zd1tM{YR{#p|6cm}B0u3}+p(bv&rklzlZb3|2))YhzXRm?K+EWd&^~>Gt#4Pp{6V_o z7jXMeBTm()(~-5<^}p`>t;oZ~jQTcL)~8)-ZE)~O3yjz%{r`#n+GuVkit`Jk@AH)T zS$54CMmufT{5){rbSjBXrtQy^^=b7KUo5}p#?FU2HVp?}wMV<*5?^9{n~~NBFAKV` z{@SMfNVxAG0J~n&|DWiuvmdDLF6%!YV=t(m%l*;lIWtf=E|u-i%9<{O)#TX-pP>G{ zTz{^AS%vS#d942I^4Wn7T?<)%U1#Pg?B9P7CgzgA5&7xW_z{+S-oS@w>A9#s!}k7% z3X4AD>IL<4xj))s-hhlh)@1X`CRVMf-3n8>tgp;3YAOcKAIIvCYqgm$Ymv&%ADmvW5LxE4 z+4~KgyjP=xMIPIqJ^!%-7PSlUG+w!Wt!s1|qgwI&%u9NNkWts!{HS2cUtIfE%GR%I zQ&h9*6Kk^d%VB+MvTA9{>d(q)Hdyi4oV`EM`AG!Dcn8psZOZzCmoB(oV$H6v1h{9= z?>(v+y$aI#a^igFkQME4^SUeRue%MjrA}*GP!*$$fBcH)hp&1Nj#GpEWc{0{Pp^OV z#hcZgS^quDYc%vU2eAEH#kEtBqB9N;%l(U3-~0y5#G9k48Dg3Lk+0t^y0Z|M7H460 zjGAw`KJB@-8VQ$kS$*o^w-cSCHnREm!JDTs_i_o|1WEcL>eGWxkMX72b(9Q~o{Rbv z-Ascj1(l-uWA$^nKAC@LK=yjPKK)hg&Dy`sgg%)o>(iL`)_C2=3}c#0`XK7l+|iw> zXMsPsWhmuGG873w1bYJE8G8TYub@vh>9;#=BxMSj_9Z5 zhtE;c?=SMDJHH<$RO0!fy`#~#Z8Ub3-yb5@Kb;d(p;;D(8-;2<7&Q^+x;3_ z|GfKXQ0C}QZ2j|(ZAga>YqI+v2ApX_ei0^g&rg}JxHmSq-@#0F|Fy`MkwX{KZ|zTY z&MWIzOa(V2m9$~=fx!ARNVfvdm)TiA3_Rw7j&W)}rQyny&an$40G&{Zk;1o{n|Wl3?{DV&+1oR&t%vyievTbxLqc`{!PY}e2EWne_-0N zMc8;@78)h1pUd^@z=<_z@Nx<3&oxKyffXK)HG5uz<*UL=Yf2i@oLu@T>sPnuwiwjfjGb@Ejq|2= znRcZ6@q79Do7}(GKI4YO=+^B1(@L00Is6d#SEpB-8Kdi6dIPp$f~`gPtr1+#jL!S?#@`K z$p*=6zTme$2U(voS${vEWG%LQS9`O*C8K*m*6{Crd9XUoja(5>W) zH=C9DsUJB2lcslM^{HsfSj46GW%JD@9a4~~F^c=C{REJ=$ROZK{umV;3^A^kcO3y|8 zxtiFR?yaj%6>}th5{3Pvja#>+!KaOAc#y=8xPI6FnH>(137anz^z2UO+qI*2-<0{8 zv`w`?!NQ82uj|}BlWufNWb506=m5+<;mGnep{Emh3^b?W5M{p747=dE>i!0<{~OkR zAVMpKv-PcI&GG2#(g*#oD)U8-so4K^Bm#b`pUdmpPtz>e{Yql>$?ElDL=?&&&OJ zg@h&O6Fn1a4yd2Y{dv

    v7mK2i_*id|gZ3i`qlivHpBxw+rayybtsGsrixf_2|zF zw3~1VvmdIT%lSItRgtQ?y}dK`Q$|$ye07^`m0TQE0WgX*E0Rm5cX$v8PkNO7*&(aCy0EVt!_ur%MGdiN@c$8 zH&opp-mN)%{!n~LPuly%hbH$`=Bq_-z++WQ_I|tyezU0faRRxADf6ZEUm%uM;Q5-A ziaL79r3|nXg^``(UNBmYsh&xauN)neWB9 za(^!R_o{xcFxU7Z`n-_%f^dK5qn{P&<(^mI?msU&*@Su(RF%zdihRvWx1*4jhGer* znXl?w9MGk)G28#$J=2SfPWsT$t;&2IJ_;CAYbmRbqJGUQ{4QBrH_tpYmliPJe;4!fI)p*AtXnrmfuVnM(^8D)9*?6o;j%4{- z&?ybQdX7NNJrW;@o^rmft(c9+;fbvO>YSDf;|Ce6|H{_hfLZ4jvV7_9*oP(4*RcL; zhW#bD=IvqiD}Tc)Xmz*%!?VhKb?aS;#_PXg_s>`dH>ESZs>+0n+q1~fiS znXhg?9N;(Hi1lARYq?Q}7pgO6mb{kwH(~wx$PmK)m6jMeOWnW8&mS7sB#TB&oJ1>z zD)Y5^T@Y@~vXh-3nh1IRZrIR`TD~`>gCP=M;{HFKi`{Uj1<%(p?;#jn7{b=a#HkYz z{InNa9}gW&!^xw=W&NYbSAESnaC|cb=XOZ^iTQimud2IgCS*J{9m1vmPOPPL&{bQxV zrnKy->i)g*^M^#foKM=(+6;Zw{s4(DF~2%~+EJB{8nOBN-|cR6J;9XvTvX<(@nnKS zQ42PI(BI%jt>R2o1#DkApYr+hs4>AfYGo(WuY7?oI^{-7vP|jeIEk-B;r_;ZFS{f0 zrze|_whSMN(#R0Bm+kM9>(|5I6H)TJC!0^?zD-lz-!V)!zbDqmlVj(gR`V$cJgCgq z)^>Rq_D;3`w0!@dc>nO$?;Eh>;sRE`)}GssvDvFxzB&xKjQI53sG2YFBi6^#iLcRc zcQ5>;ikjT@>DP~Wd2*um(RjUIHK2+%_njK)8Tt=sEjW$KV9@? z4rcb5%=-INH}kL{b2{t4j0-p7_Jjo()1A?;Ym2=Wzf1G_)n1$acRrDmm#)nJZ*)0; z1IqhHtRz&RJZXCGjQd+fUW~pzc4PLw*0OsBa^+bZBH^6LgxQPe|Dw! zY?|R1Po4{u`HQU?3YWpQviW3@zo)G{Nb8IVpBTkcVsZFV=&1I1arwoY zmm5*>+I)0$Q06c2>H!2yUd8s8S5{v^=K;I0d8fpWsBaghzQK9fS2*nd8E>WSfp+*$t8#}9|q(jc5IpC1qBJxB?|p#v!!$KtY8w$-__iu=(b@RtAFdq6{5lT z`50Edze~(#clsA&VA)ERzYBI(;dW~$+{^u$$Y0m$Z}G188Dx!C^ChpZcjBwix2n(C z{TEj6bm-`o%JjIlGJmK2t+D)1V_22%uN3*4v(Ay$2J6w{j}m|4`arWm&iHXwpUu}| z3wl%i;h>^OW&L|R(;K=8=Ir{UK~yLj=Gn;h*Nc2P?)9XH4kq;6F;lVsOnA@}W31e< zBwpR0$k(?w{~nIgYk{o3oftbA2THrK^)+DWG`y(F^R=-?HVht4Wb3PKvt`iso5t$f z$1jB#{@*;dzE(P3jNQ>ZU*X%XBE?E|$0?(4Jr=x0jg_a_`N9@AtI(Ks&)E5|BmH&h zzkZczq=hnH&2p@9a!g|wbeHsBj%$Ip*A6)WP&BrqRY1Z3N=$P8b<_ixB{Xy0+(BzNJsm&0HFGC^Uh+okQqprBI z{Xx?%Bk;FQAe(PAm^THxi@V`vc|I!67cPA}4Jo06W%?!hw;#Q-QKG~1b=Gg0>U_*} zHs4s^e-oZ$&qG2#<@(vrwgiRGRC^Se{f8O8*ATO92hJRm^hwmOzun)#(do3zpFzma z%x$Vt;o7I{e022-x^(w>C6=%Fi`KB++z3BfDD(AfyA$R1;`vJG;DTp+^;rE%eBFnp z!jsbCl=&KV*9SY-nz4LERtTifJ1wa&<#>7hmG`IpDt17^M{D$5Ch3zF$@34L8bs?< z^G6dVN&JcV+WPywu;hv>TR%N5Vqh{hfYrC}zo(#hM_1OrCDxseU z=ewCzDf7Y;mOp3bW|SRQi4IvQ>)VwsHZXQ=gsLve{1t^c)5MRu)X`j7-x{29ft?l4 zU!%2ssrMcavYf5V-<&4C7+=xw86p@K6kV5Bjrwtqe;<{m)%kzAj}Gd|%A*=J~qZDw{6Yj-_dK%KgE&BjIogu*USd z((f>P7Ev%==fchh=}wPDv9&)&{E~jY*dM&!lZZxLy0HC0 zpZC+DePDoWzFOpO`M!B5J3k(~%jYk|e7EPdd?cl%;k}GsIe&lmZAQyKbJ_Z8bo3y! z-IlZK>!;h^z|g?zX$C;z^VC3c0RF{Z8aLv@-e%=f4sIHrL3z+9oj4N*DJ>c zCOaCS;FP2vB7Y}CTvWZC4$W~^=C5uSR~TNa(bSMw_BA zs5;Nzx684Z9nhZ5=iF5HYhF{$xLq-q{FUhM_96o-zD3LUOBDLktl#qxad{jLe35>C zk-yM-%hBg+D%(G7sZ|8Gp>tXNb96ie{jK>df5A_0z+%=mbgie($K>k^d#-&z>9`Xt ze{l<{(cx*2SpBm~)}wx^8IVum%KV*b+7|BZ8(`NhH9zuvB=?95wHU2Kh91iN-6(a% zyWzTcS-yW?oPR7G5KS+3xRZxxO~v^l1NU|q`ms5?KTbO-n;gE4Ca=57{7us7go1%` z{t|`yYxmKcqH7payqm4b-QZKCBkON9AlJw0M+eZrL+-TZpfaD= zo&BJDxjEZ^Y;>4M<4Q(Twxe==9$KdpenhrL;%Djog23m-Tpzl-!HAYcEA#nhT5nul z?!@*VeLs%Gh)?ZUeSDssgaz6Ws8?B8ANAK~U|x;>?Ebpe3G)$iGmh;)Mt)h2uB}qp z`ds+62%o0TVe7Mfv%_%ATgK|+tF1QyYo0&dCZBNB<2W7`sq42qzl(COPCe>81b6@E zg$R8ziK{?1gOv60u!b%4deq0!SJL+<*5`A(U8&wAZHf$2<}c);8*+N<$n;U{fPF?kfie0V-1D@{eS z#huvt{hMZ>@$PH7$mY^EYDW5MF^)WcJI`s{F!15Wl zOP|s|YS5#;%6u+bVT)hy>#_YysEZp_c-@rVcT(o_L3MXrn4`_=<89*sRPxn@oqsxI z(;f#_7_<8LsC7Gv(J-PO*~R62%k!ClQ4u(*I{!1fr81wlw)#7FlF19(H9VqdsMRGpN>_(&UJYTlIp4opYO7C<;v90?1m#=@U>N5j7 z#`b0N8yCj~XjyLztDh#PS74E63R}O6j%~rrp|jb1TEp`Q^759le7bJG1?Rg(nEOVV z&l`HBh}d$J^_L@VSEuGZ?z8oKsD}YH&CsBc3Cet?sO}z(4629AKa}-zz;TU-y)0H{>l7NDQ46#LO$+*8uVfAJyw5z%`>10Ej8%S zRAs(TPqV|gzgl>sE&Y8&e-LlwPPreOP^*E;e7pQ~N1gdiS-#zJI#cf+t;qVIbU&cD zzFb*#H~9S^p6^#b=hNiZvGjDVGT&VXcgAbGR;>Q6)eoSh5yrHt${a<$7q0G$-0BXj zKkX11KnJH8)3*X;zQ=`(!9qtLR(~6ApNe^(JFxSq-z(09_lw@F{`T4wNNW}}rzMRK z|KmF!a=w!qEyReTQEdO;rE?Hv>6uV?rne&BUze`Lo59I&keyE`=lk|Wm3Lj5g}ii$ zUy<*X4Ugi@M4s=Dk8Z>6>}H&px+LykbJK+<=S?|!K@Naw{}mT&zUh7>nd zbwA=YELsxNv7O_^g~yg@^jXV7no! z-}whR`6$b|5 zeowgsl0S^7fsr!5Rx|tKMQ3}sJd=KZaer^@yg(Y3ZbVgHD)Vce6^D-3z1aDm50S|j zGd_&XuZG{7iKyvOY`z-uCV-qP7}2p&2mkS#DClo%)$Bh#jb-(BrA{E7Ff*cxW9Xm$ z8j{>!JX){{`3t9l4Agwe^*4LxHY{8?3#(^K&qcm(=pI9b=v+4cs`2&??oHmr>aWe= zFW7E-nBCu*-Aa?(eeSUOn|jZXboczh@)gQ_PbUY|+EIS&WGQ+vw#kK98Rv$%6vCG)CEsWEm?go zeH2J7PZ?4JQs!H4WPfxww`2WthekoP>60NDzE|dZ#ho||e?qK({3 z6ZP^VW%;bA&sUlUP&d{7j|{Jpe|$d__^zWme@e?S7WNG#{>1f#PiX;^yvu;*jK)8{ zRre9d{B!uDRnV?B75i(dKQHIo{?j(Rdy&cJ7q^xk!-tzoFz=Z9^YVPR$Mn1C{iYDl zn=1Q@DUH9P%_aKW%-?bGKh@k8j^KOuYdkp%qRXtk41tl&u`VM$=I?_ zb;dulf8MuOCh8RRlAZ4%^4lfTpOR|mQ$zpafBb5Z+#km~p-8+fRhrMF9V^Mr2=1-RR6!m%4%VV%=y@c)m;;P)ktYDts#&5sk z<&}f7{i|aB_WijgExmFJF;$iM?cT+RKKJ;(9gG-CU|Z=HtFrA*ZsL*@QBU(n~P%>t3{s?W}M9;1%*Fx!MSJvi}?FLAzjUG;AG z)1U(tFbkN6STrZ4d)>a%Ob02&{q zM=|vzzO@9thh(nC)$fUH|MyOR2exZxqIiS!^F_W}2OUS3iHp%BS9&h`>z~Q@aCXi{ zHsA2;RE8WiZ6rG%NA%aO9fwfY<@S`fN$USZzEcMUBB4N!^&hobb;Ifi3)Wxg z?+vD$u?CcsEAbm9HR}vS$*HIIR%Zj2D9_2RX${*cJ-dJd_&alSyS6n@1eT1CVu}vzVijX z$6MrJ;fUd^ziwAeb-(;&UD|!ZUD9vJ{fAbiHF!~&h{=uAe9HYt-jE$wv2-SOu8^LK zd`DJ3f#%+eVRc=4F7iF6(S7tbQSC9Ykn~raZ#6qx2KOMIZ|C_n$*|u|tSI*{BHxy~ zjHq*iA1vQ(Z5*+;0nc}isy%rb){rW%Rp$H87Qi*SA=^KWt`9C*v);!=!=*RzxW4_cGfM`gTU2J}i{@ z7xU@P4+dcG85?*Uko=d(ze%4Es`5dfs`XUn-@N5`EK%Jb!|k7YV--xpE9%qY0SAkv zd|2S$BNfw}gOS)p&4+w_Wr2M#MO4?P|9@rv_jwI8k-a}JRp*o4?$Lww=lJSJb^d5m z>!f}E-j9#M`(YN7gZkmaaO8pX_tStp-;PgjPX)tuXwfY<#rH!$c@4r{RWm0o)W5&{ z{YXB%16_X1VEfMjTTfu_sT@RoQ-5CW&#z6mkG`EYu=;;@%Qv(=SS&j~LCpVRN^4T9 znKxARO?tn?_amyzh^ANm4)y*OQUBXcafHW|TI_s~y)LQlr)of6dz9agdu<8N-!{OX z-V$G;{x7>8MA6rqQS~05{_!p9zrpq({My${=Fblb@5hfC!L;*FGwOCgy1zknpOB1? z&Lg|y56oGAQ(<5*mHOz>+g-}*H-F*=Vv~~%=AM>*fARfr93D*D{PoDOmehZ02N@F?+rA{c1oy|CV-)C}%(eD!!-8_m(PN7`(87%-=wmFM2darQZR~sA-Zi->+MHlqiRl=dfv51V_SwETP+G5@Zh6+$`(n^8=6N&gcC|KpUGib%ge*8e!_htTWO z&1CwYDCqx_dRZ_j=*H@Qy~R0bSTq>Dhe`a4{@$#=KMilIO?}Tv`Y!T+H)}0y-%VDX zzoph^xxNqDyc6rcWw8DydDcn1&RT@}AJm_h>-)q75Ad-e&%fV;?>HEC05Sny6kL9Pw77pP#?K37 z59`bF7m@$ml3*O0sVkcg5&3>GCzJx;HKWrGhb4a_==aaoJ@9wCDeLd&-3_Hfrh2sc znB;E~J>}doAoMOh%XCYQE%ruKK$Z z`@3bZ{$rf(DNNN|gbjbypO^EwQ}ZGG`>bd4LHCFsFi+gi>hrFuwQ0B8HPmod=5vd_ z2|eCb290+TpAgOm2nuw<{ZviFO;^@uiy>a*ZB$?8Kg9C`baK2f)2BY7Vx`ZEd^Ybt zf*jk}Qt1>a9~9Tuhx7`;-e$VEyFvQA$nTT=Jy6=hl${Uh{D|5g=$ zV%h6`sPI);|4xV3rpKeMvV3hFXF|Q7eMMNQGG9|FIb(f@rfmO(sDCjVyeKQJ9>uMY z>VH1!$=*NX`re4RQjgU?Gp!i%-Px9+mn!qsZb1l~V{~NtDEiyXQ9V(7#zeNiLR=qw z+h;#TUYSW=<>$L=2=j5PCk=+ljMl7w-9Zy^R<*y8TfgquAq}~g+Oz9_n@(oo#P`m! z`C&1iu*eRk)Ix1aDU$N#-2#7ecQ3|^@PX|4bc3b_)8Bk;G8`@CZ-cz#`e&WJ4r6Of z!sTwtd=7cK3$@2jXY;o>=hLeB<%Ni|k@ynxiDNpC@TVQm=Yd;4(I9OfwwS2-mCqmF z&Z$l9c3ffke0R-+7FGI+{BO#9c5!k>i*+?ve|itzq^nnt`W%+{JSgyK8}E(XemtK| zC&f_iZyWkKSDDX=YeJAXUt5+>h=&b`D7jcgiy`v+B9ysw7!=i@VoKHI$XA#$ok8a zcDoV#Wg5$GV9;p{@3w%|*UeFnaAV3^Ha|G`<|mRS?Pc?WN@jIvdB7Fym>}^j_E%n2 z+oJEtN|^5^y?=?GGI`WE*wvI;TYiCced&A)vA%D!cEQc@HCX>S;jTAb%+-?hUs@#B z-&5~Z`dgsI>hHVoSo#ucLpSy-^F3ftC<2>nv-v{$nkBURW;B%zROWk_NiTHtYtGjH z!eK-3ppg}uuepq!1p9$5Z2h11H4Xa%{MhyBrYW;AZD53~{zKT`R(Z`5e7_ORo^R%p z8Aj87Y17N$(tL%;=ZV?tp&1>IWf{`U|PxI<^(Z}l@e&B!WBR<0Ue^l)(HeZ{E!_Lb5*1Gc; z%OksBW8A%2`+OYdS zXRq&oj{h~0@h$q_A6Ifot8YKbo~z9FpW;YNh&N)_AFf^G#)wJU=+yW-sRbNW+Im>gV$F>nnz&dDY$P<<)QLH$}c1 zk3Wla7oKmUnNKk7>nb*1$XWIW5AN=w_T2^NwpPX93Ceuew{J(jXX?oK))4gjU5YQFg6gpTB5=|uir>YY{AZ;y8!Q0UeK(O;#1U)1l)gY&56`MxyxtTNx-jiPX_#E_kj)AJYx-L{tO`8Ma4 zO@>3PBkO-}w3wzkpVEh2AB*2U2Ma%TVDs0yz4PFGs4qKzS$lH?E&QZSnMvjRddl;K zLmLV(d4MN7xUL`twvLfb88BJugvF&@Nit++*rnEzThuz6z7p`jlMMF znlhi8e4@~;%z(`wB2ErN&DAYf{hh8e1-*|suzc2wnufeV-fVwX++Z$B!#c3~Ykn*b zp7r~}S~fo*pFddSz5#Qi;$-=&sGrw<@5SG5sVsjZZO*}{QZ`z&kn~B+w`!(5#l_t# zVc;n7A?B~M&Z_vz+=)_8>ABc{`I%|a?acGATBUw2=W9qMTeN)npJ#TsLuEdjYdnKiO`gxY{(lj#nz1o*R`VzK zr?CUI=-aY$&|IW`F6XmZfE_04{q@}Qqx}07@~ab?7WCxgJA{?ruPpl0Gx2V)>Rv@Q zzb@*d{bD~l>QtND$0+kjm)jw5LoJriH!fr7?U`0&SgOotl72_*i)@6V=TiMn6!@GN zyOhG)_NL``l=E9RUW9+RH z@v)!1EI$zE1Ey@aNjgC}wA$LYeEnBGANII(8v36iR$r&Co{N4{Ls`DhTQ7yv%_x@d z=NC8Nm%(V+`hlpgjo$CWva%FtRh9S@^Q}EC&ZG9dIc$HmteY%P=4zj zXxl^0r<~t{3tBYe)melVsh`XFt#wm1yE^xm=ZNz4Nl{-N23XLJM{kiIq^z%V4!hye z;mWf01(DyHcJ0aULM__8NSWUy34SOGsU_QAB-ZzoBV%Z~St~m5Lz!O(>IlR64KZi0 znjd+-rMGP*g zeV#I(1%Lf;??g@3e{SdFGOVKI?wy4PSdbOqA`esh&o7qRi*VStIacuNlkdqTEDGKW@wVQ;VeO zIB2KJM40oR+-hKhaF{K@&;F{~avZFdH}cdDPu`E)U|L#XXf z&)wzcXNr8TH)}y7KEH-%7iInYINBX9*_Bv-8fEEEt9I0+w9U$Vb~0`c@BcJq`+r3J z{BmZ2kY#UVQ-bs=BxWERG_2Q+wdeq&8M8-gL~@H?!l*7emk|X!>mW&J+tpg ze}9qRjHxZ?k@0Ih=%dVUnds)CwtvkZ0{A6^8O#6;{89?%`W1{o-EZFQqt!|J{R?TfqN&Hq0mF( zPwfA78dsn?!CP53+H<%jdN7nSDdviYbO7xkikBg#We;|Jb=~1Yltqugy+nym2>E^ej|cEGa4L+NN_>fY-Ze`0 zTK~${t5NTFihRaSy{MYs%3}TLvBVb`e_<(G|2IyqKp6#F&>%(4pIkp*4609y9-PGL z^XljF`d|N(9WHJxWA*c9kR`pge2EJqmHE7R-vhsOD$3>qL_VDc2GHnlHK@^cW&PZi z=8r*$Ol?;!-iOGvde#^}B;o89s zq(99m^%n*>^%Zo7zpLlBKXd-u#b1Ys1H#Dq{rXl_FtblAIo|@;6fyOCCLEL0=cW9f zPHBlHA1;Icc|N}{(*}T%-ZxTT2ORB=t%tmZCF}V74&FEnjyF*RbP)Xm%ddNlBaT|$ z1fN~u^V@ip186O8OzNx8>eV>Yu`Bvb5e~+$es}`iG*VD!8#T zhOBR;t1F>hw@lLCmTR}d4;GiqIO;ubO!DpV$pKn?X+-u{ue@1}n!CGTmOG#C3vn*sx?YRqdstKghV7e3 z>hqKjGoZ|?4LQFxZPPMvk1`?qtJZPlD74>-wp-6|`93wkANn}=BIgTwDQ|(rW<$yO zf)~nrU}};*S$|Ex7Y{pjO(6AoT;dU^?7V=Se_h<;Ec`y^NAi2+{sv*r-JZhCLvQN& z?ak=3<%4qh{+g|D-;2-h_r`Bv#q(&g{*}K#2|q+-Ky7*hpHh9^HoX;kdKJQ(R}DXx z`it3r2f)yswWPl|9p6Jx`>M^7#$=-~y{}X-fJFtUmjC>_;`HiP-A~U!NaLnh9Cg^+kG*P z-@qiTXmbBv?g1rqyLSXSBscIW<#$nDE1aBr2@HQW{9MX!m!kvWaMN1SUzDHefjKK* zfJZ2w-y?Hmus{BvtZO&EzX0-dfl!X5Yc{-R=^BV0PKM*541nP$M|t_ff)F#(KgW#U0-=)zlm4U4nmsV#o-N7mw&Vl|Qg?;JlKs}w z`GecO8E|veJd)qcXJ^62+LzSlpDi{BzmN40lxDrI*Jo2kpQAHxfJw(t=)8`v&%cx2 zfX}=rlJA8Nl`vTQ2spR~PG7?$`^~6Oe2UBW-ZFof`_hzrKSevL9NmIKu;;-c_20Ai$Ne8}fm;vF$^M%| z`5tJhW=rOex^EL8TE&Ib@6By8VZepCuqc;b|F9ld0LGf@$@=lp(Kn$gc?-D4@cDjJ zE9W~Vl6?QHpt~{-@i%+t)5>1nMOW<79yW){jR5*pJ2MJtMIY^%Xw|vjZM-;On>ErU~$@e>3M7v`yIN>m#Z`qdF@OVONvVP~=?+vcgj=+k1zQ6uh>;*0V7?J(uspraY z-t8c)FwNoW_syXJu&{d%(w{_5359#wgUI}`&Cb2>bGkKoKPYwMe(3kZnXG@jn3V~! zEoV#m&uo2K;ZFhN9rq^nxuUh75Tw;bSY!Qy%lGfvo6u!&2?r1%C!c4mhyeSu@1JFE`MW2m(TagvO%D<;)Bfb1D|gbcQXurT?s~|e1CF!sGRSN zUo!W3|9#K+6Q_}*Q0s;&zO)eaTRtlwxnCA4-%aE&Nky{X%#Yb`qx``eU(4UmbzQ~h zd$!g@=yg?t^xxKoNvJWv1x;S?`8Iwt8v=`TNWRaHdxKtX;h3|B&-cp<%falD5n2BW z(=Ef^8G-oO@g$e;SFQojb5?h9zhCF|a=xtw!kQxSd}Zr@XQTGQ>={<1|E{>XANE>0 zlm6q!9sOi zwo4=ZN9jZzJbmsQq;%u+t8rxz%y|BeoKL&%VTSitJ|XkRWBv&03x3K*PvrCayz>a? zxI-D1cMyLb&+ut+WF30mHNjaid_MKOCqlQbG@sitlJL{k@%Y`a71v+f={g6V{?I1- zdpizSqq}7|KJLl)7XvI-fSx+d=f9m-vBY~Lx_M`F`K-(efT8)_Nd0~MC=^C+8$jxB z&gZ?Ly-gtfg~#-%f?kxC(95|{_P_cJyWjf!pZyTlYAjjb%U_fQNtrWA|9m(59LSEW zq4UQT>xIsLI|wstp4RJgN5+5r3%>FzCOPR z)4?_JH)JV&et2;ZxQ~4++c{U{kM$p6c4k=cyh3un!jIW+)9)$5HR~TF-`S3%@S(Pf zw7$pOFAf+v67oEiCHuz;82*<}^+C@eCU`HG&%Z-2H|TRz9RiI-{qke_+XI^?WAuS> z*r_|g|C~9{ubVbm-&2jaik|xeP-%y_pMsqq{(fu)q>M2n^?8KRRrDVhfGW8sxcskp z8336tyOR4Se`s98p*uF>hm?W!-?RB++uxy(zezqrb4L9CXZ3rEOE_G*B45FFP5e3A zzbTG90H%IUkZRwMA4=;dmC;#Xy>te2if#D0biTv1@p<|F^VOt3vC8%lW-K!iCf%>( z@*gJLhQA@fq`ns(cn5|7;bebiNr(!5&N)c?lb<@cR-*ul2k`YhYnwTwKC34Ex6I!R zv&$bz?su~Mf14*j`oizBhWl@9etFhx6yE8pjQ^(n=f4^L4IYhz7ypzb^PQ~zU#apz zi=D=3eVNaH?M^pn-kRoryje1;`Z(iGB|iTF%5!1vfmWpcKkI)L*Y5U5#TI=2Gip{q zhMxghKlznZiXnsjG4JnjF8?QtH$rt+n*a9Gw}SDb+i-pT>&KaSi$L| z8QR`@Na}n4s{*9;`$qD;-Fp-Udn;kVXp!#%#(yWv_m3saRf6>Y=BHV{=geP^cP_Oj z`L@xY1oK2 zPREXh&dz+kyE=OdH_MHLDYquq^Ermu-xD+RD7+A+!Svk?-%Itq(Z%!7vg=Ax-}`o1 zC){vtCv=W~%;i5p`3`)v+ywcdeE;s0^&Wit?ZC^|`X^&M;`TBl6&kZ8RHX-kq#A~GB-#jOD8p!A0=;U0O zs@IbAH*5ctprxjt{Eh2|-=DO9Syi$U=6-BT&iB=xFG1NIU+fuhjH~bG!Z*UDwVg@+ z&7W?CyB%o$x9LW}xNpNqf8RG|vLLiq7lzI`FZ-XrS77#A{o0)fZxTn5@$vQ2QSewf zmGt+{4i~_uNs#k*`~0=IT6>f1?NHurc+OY|%iz{?82Sg}Ry#;p1;n|JeJ1-3D91+I_W>{ypn& zMu(2UF9u5T9h74Ig{_|t^&JhZRw%-NrlNkc{LhH;#dd4j;n??l{$Hz2g1F?ylKnxf z{{QHlf}uOd;Bj?6|J$7Afv}?mss9QoCD_PlJ>Hk-hm`;6r&fV(SX+2rC;tA}`vIFR zO0efXAIv{6U|x^q@;kJmzO(iB z!#CCnYCZ-+Me?Ki?+qA#j#)8-~U3*ch`if;^)Lz$qile#wuICdVd$nR#PL{hiH!fA&qmZ{tT} z^(}sVviYWYpi`nno(~o0RzXfo8`9s0)?UHHG;b8l`21h)9|(m#JCXZ|4NSv8e`Ies znJDT5o4;lkMu5Bgj#AnK@#k#*+N5g|_*@-9@@+8u7>pl3h4lA{OV$W|Q`-vfd-D12 zuX+(CwelkQR&BLbSl>)v2#S8lF5FxlNcK->RDXa`CcDY~1;c7o(OWMWj{oEH zt(>llrP?&#)`f%N_{SHL`VQ-V!kv3#>*4pIOrOv9!+%y_9$Z86ZQVH;53f2UVLhJW@zKw3r zgVowvPogT@5ONT(%106|!^YKy`oU7?Y_D8=w zi-6&CEl7X!{MRI5)|N)X_U~u8`rdL`5_Eq$oaFz|%GH9KUK`=+xrz0B+B5$D;I(70 zVDDt8E#v$D6D#HK`|5jwo2&TyVfFpOpf$qyZEXZM?+5jNz8<6RH}Bt-zxNdgoAbr* zS$)5-?jx++z6**+ihQ&8cWxW0p^|+P>Hjx0)x)sKx$tN&U*G@P4S{3rU&s_fME+R* z3s3Y$&AIm=zXzZH0~Xd$>GX;8KfVc0^0)I8NdKc=F$U%p)ydq=8}v&_a(;d}P_~JpK-ni-B)e|lWXGlEdTQjKEVvNU7)y-&%f6&HQX~hk@Pnors-j? znA4znkk7y6q#^J*`kCyZE1&;@f4%YIkh@@H%;#S<#u{pMK9c;uk&VTgLv?V}neT7Z zs2DL((+ zW(#1`U-|o-c4GXo^N))T6yvbID^O4t|9&bN{crYnHT0gLOXj~$Ie}m*pI^6^)ZeB1 z8jK`d-#j{yt^W5{bX@lS%j2T~S^w>@R68gdMoYSo!}$dVNPpv4q=!z$r(oPUKHqJ#hQPKBPf5O0H}yg9rFS59IG^vpuJYNW z&L7D6f>%4oqNm$G*zL&Y+q|n2OiBDh@@?FI1K!gzzykyLeCw~74Aai5O892|yW-$f zT-kRxIX~m=w*Y1jZBEWV-fVgWhifcHqo(5D56gEKmo+eFZ)2vO6@P!M{tNR~ z2`3lo2xh15)_`xpG?^W(#|uM>Fn{Vj9+?|nX2|Nr*efG0ZYW9T0-zh&P~Gg&+tLTgmW`sb>d zskpG8BQ}ZP>;K;$3*cyaGgALQFTaAP+Ipc;Tk-FQjgKB5*1(@;tx5ksUa=I9ep`;q zxA5bmdTbEfax^CW&xgWo^0UE|%n!C|MS@X~_zX8b5@#htlQKJc zK4;Sk;r6^%!my0-_54~e{>cBwariQFB3U20cjXd1^;-mE|MQP*e4I>LDa_E(7QUan z!;O!VyYIu>1b;aFMEw1;@zHB(4V?S39kzLi{ImJN^d^n)L#O>@eY9#t8=Pa41Gz8x z@zK>_DBQp&WPSAEoW9uf$t`Fe#E*|2$K~U9{JI>FBLr?heaj|SD z6uf#QIUfL|{>faWAMW3F0~UGn{L5m;KCb2kd@Bx5*x`a+eaR{|0>yV(4`nd|<=p`_{Zg z@V2-q*&pt7wG<0Im*CbDe7=K!c!TeVR^x5fRr$DyJ|{5gQM|Cg>HojBwu8>SUz7ZA zZaN;rW_&08|HlE&FvsdE$^Z9we+H>Df?!^UL`*N2VXse>u$baWWv|~{noV*J8UcIZ>BA3 zjIb~kF0~i=X6r)%7u(|GoMRGy!}9;;r3EZ*{D9>D;_rSqBL5m3-p<$mf9vcZ6u)qmJRqx!BANec#2!TZ z%T~CeJD-1rKZ{`8geK(tgRw>#UcR{q!*s;IAJ*UW&Rhp4ZnYr!_c^)==EfV4`hTtC z4#?Tmg`96*xi<>(_wlk+4SrfJLXXIB*h2jMu=#6Nel5&S3x${N4L@(zU{4j=<~PO>w_`xn zLgbgtUzc>($L4L0$@l*@%%@59JF1Z-7-!uh{rTbn{n2-K8RYx%`CXQ42UTBRkov7- z=z^m?zrx-#e113ob%w#pwPgMOHU?nxRjtuuv&b)7zj3ym3i_c6q<#-ReGvC=7x1|f zpWiN7i(%Kb#-u;5y(GUM*mx1zIE%l3mfw>qK5#;{1=-(?xVZ`b9n&ZEyQ%9AxD(Zx z)NkJhQPA~ZUkShL{7%a)snBi!lKJVOT~5NsVV~sl)&1-FD?;h}Hby2V;p_(|QooJ& zISGAjKH-i|o9e$W0O|Z%`18x~p~Eb4zB#%5SRu6X6L!6LT>KvOCH&rUcm&ge)=B(} z0!aP4UAHfw^LY!&e}}t`F|Z;UzO)hfXZ71MKp%~5j)HY-k$*qNzw|*%c(~%OEW4AK zU$Xw?cu0TT7;=^LFBzBZVEMA=lKnR9d}o^tE_ki~7wCMB&;Oo@)kH|WqcT(@8$ z&i`-!70Z8cM<4jCr$y$c+4{lY^`$LYze&&B0WB*!k^4JF+eSmxn?9s}w>^~#-CG0c zUmj~X39`EP80y`R%fFY)N$@x|hV<`tW==w7(BNT z>E8!!zmBg@EI?ajQD5Sj`pmli>tSP(COO}%GA9^%c5O@gm*)CAA+%j5@_jRn3DIyg ztGC3zv-)rUHWj|U9!Bm*h~{jLoQorK3n-l5^x|K8{qoDOo;5y=YQ89OIYP}oAf^egaLSbV+o9m;`^T|^4*6X4o}JcZf{Lj zbY5Kp#YuerYbK3{gl!*X5pBfz8rHu@*ZN~{<5rUTB+LKzxziv(_pglFAChe zp|dfc|0^Sxf@75$q%RZy{p@^Cp=UV;^jLr=rttYcF?&5sywRNW@4sV$L3vgilK(AB zcf$0A9m)4u&z45R@aDZq{r}>65FU0IM$Yf_?K(zq$$5kS4Eu8RzsHx8Fl);wQvY># zj}g54RO7vCfnxkH`oAQv2xiTkM(z)uui_-^%c#aHua9#1A2p`}UWTuh_#f8)hkJbm z{nE|gHBE_UMbstQ1nl%|JkzE6>Z%=!K!0?{%@@x4<9;xklp;%@V%16ANJ4;z!`m7 z;^>*8{3P?`TNg|cQ1u%Gc|I*pU;XLcHiPk3I_iKJ(B<6xjVsojC?=wyN38{B>DdzUK9;)p7oT}=h^(VBKsg* z7%kubPTXHqJULnza_lwgtn9<(zjSsEJjxnL=C@sIM+@V=y+)gUBL9^P|4!YC;rfiJ zK<$5jGJcG(bY>MAsEhn(GXBTlXoY;XY!%s`%C7ke%BGu1{SUs?1grA*!K|L*-w(_G z_A>@}^Y#%q1AP4-+*Jm{Z{L)ij1>7}{m-nw128VV7|e3{{D(YrfLEDMNdBYWx#AkT zk8t7=pMO_17l<-_PwM~evjO<7t_23Z5&389mwybV%is3=Me4uXm^A!x*Ao5A`1=3s z{!;MvQYGgX)BMd+KlA?z^7nXUZ6|nzem^Zgp{!+WPj?X zLktWX*^|_Nf1N|n(%XW(pT2B=4!n*WLHZl*O~o+M*+Y`Q0!ZgKPdytgD0sX=)9G3D z@x$_4cB2B6%U8hdLb1Nf>UVm#Z%{omn9N^Ce`|t^<#!mU{Pp=S1C085nB;e|AcKWl zZ;<_`A6*Ax^UX!@A&JlL(4P+QYrzr?`xfpO~Zp9EO7roKEG|-ErVA%Dx`nU$i0OQedgn% zyCS~|jDK%r?+bl5YLN5EIg>WS{eimV{LRAeJ0b0gG5Nk$>jN?HVzU`I{t@+^_3v+b z9fC5qp=A9=_h$~2Ck!X`+3!U$bP=XV{5Q*Q(7wm;w%H08+@!%jNb4()lfOZqi<`*) z&@20j;ybI)pvmp&8o@%|BP=Nap1%jxbi%oPtDxvp!VQ9$!CybI$F9~ z;G->kJ`-Y=L6N2ksjvB^zOd@LIywLH!9)H&R*%-Ces0p(1@`jyw?|ise6jcc#@vm8 z#am3}_kYBnv;6%!Eq|YV{}9mk5$hKK()stnwx=L0*pcM#ccT(0tdZ|V$ZF6(seZW2mrKyvE7fr{cL(*I`0HpNB3;jnTH|NKwgW{7Pq z)8XS-KA*MI0OHPEm%cB+@OdR~AST%sLQFhgKdZbP;ncy0WdCMFlZm))-CMX-#@El( zbQkb^S4H+O5A_a2(*P}!Pvf{5aQMeJ+4Yv<-!EJLu%4QZp^b)O|0#SvSKeF(E&3>v z_3!kzmAJI&a!lx?Sx~ZjG@iTKK{!<&-&+EUKvPH%1U z{?VLWyFh5(j?B+q>coP^^zLMRZuF2eFby?_SWmvb9=&i1GzQs|^MQF#0+Y2SN$$_F z=ljE9Par0GDd|6tm3)Vun*&Mx?A}5hcRkxf>gPxcBV4-W5V-#Lz6yK3pS%dLY-*Wg zKMb2cHETZz{hM7R`-dBZ;cz?ZzJ$*LWy^!&dt>IuwlxrDsGALuwz*k1Gyuih2!e{N^a|6k@m zV5xiu2z9@6wYfU3(bxmG1-`z{3^T$zXAeTiW>H_+`Hgdj0P>!dO78cw{OT?mgzB0X z$o}8hgTtY8*FDMnb|u5_t%+_}(zgo2RK@qN+57#SYg|F`z)Kmm-vuuOV)d}*c>gq? z-{P|~VF%XA8umA`{QAv2jN4|IW9<&Uz8^v-C(=Xkj$SRoQ#F^qORopc355-lq3u!_0`t;G)&O8CF{Eh zWhJmCSAIX?zx!#dzSf<60cXa7aUbC7sWB{&|F8{rNr` z_$cB3{8I!PO8jlca&;^mu^W;c`21eGV1(0er^1>5KED%w0Nl+hA^E+YF$j}Cog?*k zpY{lNxcaW7ex-oY`RZTK-SDygYgpTf&u_#LS2&RKTvl~hte>&|AiH@GP6}y;8RdL_ z56qVDhV5JLFIb@%CldRwc3i{y_w@f6LS; z9kNahfQU_e|FC?+Y1mb5P3{-9SzZc{D_mjs-Ufc9`mFKk31}@{NbV2))^~(Z9dQ@8 ztBUuR;~9NE@Z<;lofbgWx3*`F5H=a!LvJHK|A%AMv25Nha(=08n|8SCR|*{7!{|1W$ez`Ul< z$^J!N`ykw!s)36$`21T9n+0)mKFQju@bkAsIsd134U|>Zf@e7S z$|CGHgwKDkKYsAisu4NA;rICiUf;bID@GTe74ttGiGEFb6awAiT9EPaZRc*dU8Ya! zd*!G&2+^YB-9gL(SN;G8rbONPH`C-xGAT)igj@E^I{u5(oLFBg&B>(SM9Kqq+24G$hU;l@E z@dAJOevDl`8sbMq!e`dhc%1aQGiuphspr>ECf!dLIA;R{r>T+k3*Dz7aCMUwS%3Tf zcsE>l-5m0I{fzUNBZwkjdNjtqCooZ<>jT&yvukpKg`dsgm=&9 z!GWX({g?We9p=M@V4s^<=yd15{)V*vHvRlhX!&ge$@l#5;etiwO{`QA`A%i{cIlvj z-R|y?k9L49`=J^B&(5@u;?h+q_O?B1D`dlxw* zD*8wE{UYVf%i+6xKL)jb<>lTuJn^(6y8bAt=Np*%Tu|f&xco|$c`$ z29pKvB=u=O=6!*WLL64g-;ZgzkI(<nnTiZh*f-RLT0ve6KB_tgA`ZSAGk7z^H2*(!U(<9}i!rcZB0DMSsHfSEiW?La60s zT-ZV6Kb7JCeQi37TP5FLI$8Xl?Z2po=fZ$>K=OY%{3=*{9ZUKfWA~?Uz;X`hZx&iO z3d;koVMLO6e>jKX-#_gaG>h^h_p4L~I|?=B*D&^DUH$oy!}5Ph13S#xPWqdI7VWXM zERp2juUY`ZghJ{20!)8Kx;gslX20|r=aM?=ReYa zBFs&xAoc(1?;va!)`YCjR46#1pZ_yIH$Z}y3aS4}>$iYY=jNopxwLx^I4stKD*XmNrSnOhZR6pZa|bfN-Bpdk znCMIBnw3zm|1AIM?uVhrq26TwasR_yxVc0|^8e}9Rk%{%1m50!{nvQ?6pH%KCg)3U zA8-&Xy|3cQlj8m20*3!7WxrtC9$&J4-l(~wu;TSq)c*djp8o=d|A2QISQfR7~-#`~{x!KXmvpWUxp7&QvYbjxLL|C=vm`L~@p z8Lv01g!b$B{Qr%a2vtKLk@cN8VG}CL-%qFNJC$E&!;>>_B>tY&|MCs7cxhgHobX?L zg7rUV_pE@6n}3k}zq5!%jgIXxYJMSC|0DJN!8l!+tnZxIvjyf^HG`ClhVwzMd2CP<;*1Y|Hn)Rq4s(S{_868U&QdAGw3&HTdpVl|GXB>@W_QQ(%)on zZI9o*_d|Y^$hQJ>|0blj6~yRVlLN@V|1W)KQT3N*<2%LWzs+bG9dlluKQFCI3oH75DB*nz^_<>zt# zhxmH^&Sd<{=a9n?>(Y~)zy7e|4Cp&slJ%La#bxkq>S$8GS9v{yp*}On`upkxd*OX( zF@~s%_k*u9{Cd6r4Td^C;PRipWap=!{;?O%R~6%ir+@18yNJ>6^6t%W{q?P6{@VCr zdpzNnAn`9O-yM9dVBy2_B;T`qhoJfMQ!w(AsNbxAH&P!Bd6UazH-3usb(ZhdNt5x> z+ec)5#zn^svZvf9_XCCHZo(H1jj*bc&-W2w4ybH+Mb1AdeTl&{OAN6?j_40q{eJ4Q z62gPOlKNe`I|lE__m@8XbCJt`cC7Uvj-hf7n84TfM-^6(`RJTvzM9qd&tXHbYjO@4mhk!aO&AS+8?H+7SC;?g zrzd0k6%WCp72m(i`{xFU1^3AL)G5CWjn}eALJQ zH`ZDOJp%iEOv(D?bCoC}RdC9tR+i=4@N;Q>{`a$J^c33Sh=>bZ{U3VF zA8P#-$o|yc^P$jlPE&HeKs$9WfCo>#WLD)Jw4;QZ%`Ojhe z&yB4|AT*%|S-)Ipl?QryLrDIU@EY_g9!~1NRfp%WYrF?|O8QsQ`u%VxJE7v&1yn1( zR?lxG!~dq|f50ncHOYTjwViNn$3@(+>KB)Prw7e&@Y*dT|0$D=vHD=FWIloQKVKGD zgAjR^)c+GcLvTj*3D`PG)c;C`|90kMV4OjTME}|RHO6@g4tgT*O*iNBKSI?Vrp4Wn z{pu?6$Id4l8y}3b|EgeM6<_~*xXy(q2cD7lYbN}R#`*2qpst(v=d=1Bv3C^&2h@=M ze@9R>F3-@z;rGsS`ER2c0F@bave%OL;Z-H)%hSi9^7(@%Wc_ma^SyAkS1VHgi|P{O z^O;64u0Nmu#KR!0sLjP}Yd-(k*+;;AQFqe+7$3@mN+tPzYGQwM+XvSmrofS$zg6Ax z93Fk0Oum2jLfcMQ-}gMuGUxN(+wL#S&{{?Ee`KniuwdPJ96a~ufAJ&L|Cm3`u-q?% z^#3Y*jnODBM*hYE-~UYfV-2sbmW zdkT)qzDw%=zH5`f^VKbKJ~HQEFcwW#!9C6S`X9Mvp&cE`&P|=*M-}KeK4y!jikoB86 zRnI{u-<_P#X|u{!I6Jri7mg^a=U0B$Qo_&I+`n+?+zK-PoxamnFdJ8ZZ!~}W_q~+= z-)7A*>BMFU|LpzBo^Oru=gnx+|MY!s4Sh}X$ozMF^P%|V)G>HGRn&jh{|tOP27+>n zWNJf1eP#K-*T)0Dc;10-{rLJ{_-PVs8hewx|D*pZ7#{{JW1rT1{?iQR!H8c^$ohTq z%4qB~zBP6U6a5*>|D8XpV3^GZvVRrzG77I0>)@gd=eYVGvqZl8e&-*O|2p%nFg3Fg z*}t`szwd6)xCME?GON#iIDSW8;{RFx*T0tuvbi}py$_%Nnfe(}Ijk#rf6ZS#A3E{m-^T zTS2>jBXBYn{R@D!ejhz29A^1yk^Ng)+J5ks>68BFfF20_#-Bt}6OsP{#{b7UXMozc zE+qfwXXZoy69dTk<2KpXA-1<2$-mBt7tqqyjjVs#ZnP1CH=Mz&{8BFe1ET&x?q5$( z$Q1jFZ2j})&gNL&B3PpD?0il)Zxak}5e1(Q^ZiZAJR4Z>;j+0Y6zViXGgH~+}$dt=iz@aFGZ(%-BXqOgTVD?Hwh&-bf40Wc)@ zr)YiPv*Bb?p%k5S8T}ngsB~0!aCK7WPf&Vowe|N*J)hwwxpi#AB?`o ztJZ--@G=NH$>;mv)#g|&+XS|*V*Q5YyGx!4dKpJb<||qKE-alC}FUKa6Med()VySXF%k5?%TFU9o>M^qqa3eE+WbuFbfAk|KJV z^Z71lIv?h0J(BRv_FtXmM`1gYmZ)XM=i9_@4J_GLP4fNcStLH*-vaNhJImGYS;`wh zLHI%PU0b&m9&c2IOl`h?fA|#+__{f{A84SQ@9Trwkn=YS)H1;^pcBdO`d?Opp=}O! z-DCXU`7hm%_~uPM{E*LQzD{ZQ?~}fNWIV=NIIuSdTOIeT|2~!3?_BO#4nCi(;rMC( zd_wEAmk?9yO1|HsoMSDF`H_RU?jrvRg4EyN8&(Hn6qbT#DxZIkZkiYrEq_1TPvoEV z?}HzkpmxW7Wc_}hu`N9PoJ0DTCjTt(*ZfQ{)8g~LWq}ifuDc*Rd0*5w*1tDBFclwW zmP3DcKL1u5C&Q4-Wn}&G-o?#m6{#R!aLDK1bmDy2eeQvTf3|+FVHkx?OSG_AU|l`G ztiDg5y9OMtSCRdz0U43#KT`|u{K@C?-^X$zL_Yl{3;Qho|FiF3TUdrcK%olhUp6{K zKysJnaOl7KBzwO<+vWh|&D8^=ZX%zoe~+Ck6FTfaiiIzux%%$XFB7`0?MT+|N9?x} zjAFBKWov$XJnMEA?k(#}#z#fIl~9zEjlLPnxbdNIsvPcLv?Al9jfDSxKQ`MP zfC39$GXHI}P9_w&XQA6=F@A~||KGbuCTN&-Aoq`!nOO<>MaQw+r+qztRm}dyMDMfU z?%s#2kLE4060WJ9!2Lg#)_e=Ql+0XtZQ zljl!rxGfYd&X)8K*!<#Znk8Pekni{EE}lOMO#H09<^*rg6v$#uiTcaV|2K7?hI>@6 zk@L?Nyrw|K#8NVTZubkpr*Hm3x*b1$Y>v$bi^#iV{48G>iK!2p;ebPbx$)D?c`a=H z@{;TyL~2B0R6sKfIh4mef4sMCgrT9er2p#X9R?krE0Os{%R>?H&Qb&N`-$fZd;YYK zKLAOiTa*6l#okPCH#Z^cqX{{JFst$?wtLpDp07_#e4IRg7P@rpO~yy_pMtPk{}}db z#*dG{CO5$HGm!TK?k=(tDuRyTD}R1`?CkLhUM+Pd=P!cXkjG9 zRDSHk)w4BFi1@>ej}k3!$oup{mK)V@K1ln^@df+vTR#mn(B#L*lhYfaR_ikvAEV{( z&(G|wMCK>QRrf)_W_9p$<;RC{G6-MOGVuRvBLAx&XbZZM0!h~M1K{GR18)q)?^*x$ z#1;g-@foQ=%o`t)Ody)R_&?G_lI3x@E z{9RlhpE=C=V>9XooWCR^<4d(%5NeaM@XA&3eY4(-fAhTh3O21AOTO=2Iz|D1DbFYU z*}12hc&T3i1bXuGo8WgHaQ50gFtCsxKaq8|P;GQvQomy7Gorc-!%V|;@_dPD?hM*Z z&Pw{ztUo)UF&(v|O3C@^=O?DX#687ielsLL1T*CC|8-u&kDnVG7Qn{tx5@r=mt*^I zi;+5d-u_)5KYq-7(yE7RVVdT18Fhbt_riU6=y6jFo_~gWzIfc*2us&}BKs4cUWP%E zt0Fm{p?^p2&s>_4_1VT&iSX{QHd(*I7AQm(9KoDr{QA|h&RO6(p*koN}eyDW)8!Y zW@%)6#G5-q?u9&ZK3my*I<~PaA^q2ez8>=aZV_4EU2rc1r+EJ)&llgS1rSwplRRJC zUH4(?g(hh5;TJbPX3BT-UoLn``mf^y_Thr0CKz0u%Z-norh!o7@KN@>PV}E_{-UP6 z4F+wI*Bl#*`p@<+mZpIG{olh_UKL&c=T~BD$@ww6(LN~mZbHUS;X4qHI3Fg@pC9uQ z!6~~H+5Z@-kHP|BkFVVxS@6cK9T{J}`=fAo*I|6um>*wT2NuB33{$A^Yxw_{ z*4O$hM&Zll!?;Q&##aGz{WazpseLaG82YYI(mw=H zlJHkzx&=4r{(zpL{PXEc@InZ>aYJ(dldZo!(Ab9=^BSXZJAVA#jrN8cLM0i0X0Ibq z-@Y+!a^%O~s)>Q1bK*T2e@_N(gL{s3vcqztmMbn%cv|EKGKMcFNHW1uI^074c+C<8Gkn{=r!P^QRMut=?fHA zTu;Zkz5MtZ_E-U%<;)`cJK1x!P$gTwgNnFc{bx@{EXmpl_N9FP_ps0o)DtsF|98HP z414@Yg?FR*@pb*OGql58$@%8T)aM3NPRHN-ipcw=x&J)iO|wF>ztd;N7WDP`1|_@r z@%7AV5hN9t%aTSm@T)9|&w`^7ctp7omJIq?e}1s_ZAGhf&`sls?8MfF@1^x}KG%N^@;ht|lllMXF z!$xHN!K$?&bcjwP<8SZRL{NIzf{edjGC^=ENW#$-Woc$kKT z+xhW#r1?3}KGvO_|H_hoKV1HO(~DyKvH6vD+)Zd}IF#J4TQ^(~l1kFBSC|-o?D^(a z^BStON0R#?zl|4!6}QrGO%Xr-BHAh9E0>vIUdBJ)&Sh(1NtG{r3*zTri%xb#jl>;f z{o+&;dvIQ!LB^kfg$&bjQ^@+o)CbNWl%FE!V-$zZz&4{UljmE`6Azg0ev!<-ZlB(Q zy9~d=!90Ha?Y+AY9M4=M{pF!a5$L>M6+>NqaN|$Yb{*K*RFLP}Ww!_nO;AM-V}ATK z3JHYu@(wpOAMCn$8?-F>Ei3)d5TDZdnAs2Zf!b#^GQLVplVEVA78yUc{t80hMrl~l zD^~VDf5p}(j8%`ql8y#s{0Kd)1od8NC@Aym6Gs}IgY%=hL0pJwmuIwQ$}iA9B9z!`F`3CUZMgk<|a#^Gko}40L^Z36?G9_m>70PldxfFUX8tMZVbi`tZ6fcr~gPd~fmN zCvwLkD9$P)_v0vp4b>Ls|ken~`(uu%KClzeH?Nt5u?0yj0 z`#@-?{)RliM*iCdv$y?{eKu?0PZ~eo&-X$4b5+tGHZe?sq7+TCKE7#-m2lJe5Dr}| z#t%DRJP3}$GaY?0entja33i5uFhPEY<$v+V*3XyBJO^$jXYm06r*&j~PqTj~ zyq>#_tnaN{Xb%&N50mwa3HM~^n3Dt+*W0>$^8$hznhQ|f!;5a(cW4-U)cM%zef9j zR`~<6J|1^392I&fqmCv&K9;Hl$@f>kCiAD68rxxT#Sa-ZzcWxP5{B#0@v&%C68!qm zTvC4k=Kk%x`+^WZCKYuv`Tndh_9$E!-j>`S@~~78ifmFb$C>ZX2F*AJGn#dQwyPTA zTYA3i+iNZKE(^TgQ_dVjy#juGC?{4y!B>0o ze3>1nh#f9^konJb`xf}DZY>mU<@>Me;hnIy={7j>iGP079kz$$PibU)l=KH|b0iVg z&F9BQ(B^TlyiK;`ehM2Og|eBLw(SD=g!9jj2`baz%#{MNzdFw<6b;?v?}we^$A@2& z#Sr?rgsd+Z9SX-wHHuj0_)R=NWYYVICQd%^x5<6-{1_J&j^FMpqWS6^?)l-@F$h{$ zyd>v)_L*&mrJCQ#{AZ643EDkW$n)b!ZW4snHIvl8+4!i67KC4U$(S{qA0KA-kHSEU zHe`Hk^c94X#ALL1YREl5c3nLOt{R=m`TfNXHp1%02l0|IzyEsW!7b477zme2`SHXS?{UDz2$M3(ob$%Us z{AJJGnOGfm9#V?M_yK4k$?xa)oCcje&yweh#o|!;?#vHl{Irw%=BLN6kp64->2Q?Q zDd32<{P_7i#|Qc>yG!W~EW>)&0}ZG}vaRMfi2kFVjMZo&2@1IYS7qhB_H zu~RB)Z{x?;zOHXz#t>U_{^x*$t#EyJD(deP=Ns7hAJspKxK~v^gI~d~4?OT~fu?g- zk@3~zXD2+Yzm<$H9l-$nbv1Kyow9%0GJGTD)|NB*XS|7km&G_*(uiG(b(ovVJe@{$C z;idZl+*EGBJ-_q@oCl}d9mx8@lB2f5tJoBDv*pjHUK@EE7T5HHybBHIkGh1PPG@a} z*n=tLe4Xd*H=tu>L(X?MdSffpmZsqMZ~XW=rmcikt0$59k>aKn7#X}m@_qn2U#HTs zGyd%o3ZXCf=U3Z!2e`E_RWe`4&Oa3Y1nf5@0Ss1%@x{*9y-yeqy%Ud;^>5WCvv6tP zS(p+g##cOZel6H6kFSU`lKLAPUyr+O#c-W>u&|@JzntAqp=`Va`h2@A8`4{hZ??Y# zs^OTo;}2YQ{lbl}7Q5C%ROKx)KU!6>7yFI=0|#oe>%V8~2ffb*!34LbWPF`T4acqr z{=%P;VtmCj=hvIx+re?oXIX#A{upU}VYaQM@W&<=Z_kgY|Myoh{of~_B0+zXIUxCQ_I#LGRmp?zduGXAzKvJ>WCNX8H266)ihoe!V%@D1$S zYDM;+6i?X+0ZJ*D6?mood-i-g2uj%N&O|c)&fjizmyb3B;N;>Vx%Xcwr<&XU|OV)L)2hO@BjZ=R%n$Hw3IsA(`mCs(o` zfQ>(+bz8AGxf;A3#rRYBKf2C4uIKOl|4GQ+B;#$jms!^Hx{jn>N+O~NMH=>2DJnvx zora92WF(ZbLds5(85vngR>Jr7`+Z(7J?Vq{daA@Cq$kq z=GLFu435O0KR;k$Ts@P&yAGQ{|NR|q{5U^15~CV^!lqz0e{zquK}p(Eu0IiVI0}>e ze?i=zmH$3p96w$d8ww{Y>V*5E{flD$oX<}n(-RK?%Z=>b7@null zAxKnh$K~(A6CkfYC1S$>8GpB^{_=ur$05B}Pwx94<39n}^g9vtD*8(AFU_CY?F%q4 zWDu9Xcqe1xuXYGaa@hRM&o2juiF(}l(q)7((QA1Ke;3L4v!?35vxn8fP<6uPFT%r^ z^c{T&_x_ggN6%+Gcauj0)0tfUPIl{t_sMduKX@c@ICj%NM^Ng5vzGywVx2zBr*wVu$j|7EWK(V=@Jrgi!b-9g45UH{F>-wZKXx4HGFBPo%1sp&h+L>Yh2 zsQvPelD9cq!4ocjnw3#V8h^s=b~63*5ybrU?GOrGu72eDBL{X&AW!t-aPxXLf0ri3 z!OhUW0&hR@%Cm>Sb7EVOe?rHf8TK0Fg<=R!OAV6hUlPUN{U^uaMaLf8`N8~^K&ssm zaJ&hdzo}&xV5Fq~kmoNRYcM8XTo2;)K`W&ECQLhWmz)l1;|i&xc5$f3OlvBZx(U$}ppJWhNzgWF#i+`k)+2=?O6*Dfp`j^0K= z-2CpTmnr0qJIK|)LCJ{mZ4VsQ;GMzoVaAu;}3#_#-EaKjkR?Tw2YC z8YOZBK9J8Kj7Wp5xAwI0k+)vEYlyV|JHQw76@5( zi`#$E_If0)AN~zS>a+PXG}sQ~@*i>I&;64Ajg?)0LjHR;f2N&7A-v?hpi$i%KU4a* zBMw@;`7Q9~KWf?^mi*r@MDcYnQV5derL#Y-;Mp<%{$NGURGJ zMwKZu_3hc@i{L!(Kd!zleQHAfTs(lKpV@q+YTSq5GHp1J%FgfBA2T7=i3czuip|&F z(pos5B5>SDyMx8u3`cI@B`&^?*O&F|h#l*E_*k~gCNy>D1V<#)S#&WEILxuX5y zG+$RYhhQ&-8mKOn`TI#!eCaEh>j^Zxz}2^M5{a6lzCf$*Y`)0qE$}A)2G>6c=@5k( z>l>i66`QZOUfUsLY?TnK+{}l#ze#&fDD01U$E^?ROq@Xa&WOg_k0Y7!qfu5I=>7O5 z+*OhBL(f-b^*9XKW7=^2lhmE+#JrWH2l{BBRKKDr{n}`G0`h9Ra``gU)*>FmcOooo zFXihfmA~mOxCq_<8^HBX8Y4}~$S*0_+kYifzec6r2mMo8T>sxb+>~Hl3a(X7Vd~fP zhqVBmCvpAB3HMEj%kTrJbyBwfgy!qc2YLMS)|Tr}j?e6d&I^}u`LHE{i{3>0{-b2#n-WJ z3!uGeuE_tV`Er{g@lS47!v{ARUv&Ja*TM@@GK#qUONRm@@!ZkRkTOUXKhpgds^9~U z-j)eB?l$uw?jOA69EENjzrajiHecEsw}Z>}N^bnvD{A>02 zcTjbI0yqCE3NRx>=BJ>VMw#^U>HS$@-CN?!6*gRc4qoYorD;pK`t&(i1z&I31`3_o z{LBb8g`Fdlg`rbr^AU9ZRXUg8t7Ea?zFwAp(f(t_P2*T1ACBf{ed`b`*zgSI{OwruKYxtoXPcroti4~z^*_QIBk`(j9q8|7^Ru&u z4;*-QojV`Dy)+7&l0U@v4(Kx#7AWf7Y`3Neq1ly*G{L?w9CoXHGJc_T#Yv zHb1(iEpc0uHF&*e*T-yYy5aY`Zru9V%v=?mu^|AyD6;t}n`#Pr+Y*J)FS7kTMIf^0 zIxv7)&F56Htpu~*d zX0$j7U(a>o>d%*RYUJ+Y0Gu(5&CiY2mmoGunOk4}EN?+}WhGvi$(m<{`d~W?qwRJRJ z@A45mjUrQwjd0?O{n4e z>)kfT!{9Do1>Sz6eI zRlweIRc?ONZ=VHG{gZ^}%GiAUChx)Nw?24OH2W9g{-{M27Ua4{GTtj=^VMf_OKf;+ z0mbEPzD`~I2()wB6JczglmryS+_>mxElQ0Yb$7^t!HBbD>s;1hgSsGHQB z--!EfHv~l^roD$b2LI~Il)pEk#0P}iSA=Vqo6n2$qso~v_`CK4d~7A_FQoP9h+H6a zmA}i~Pm#SS3^azm;Of&#|9BX2zn<%l-=C*VW=+{H;!AAG(Rv=Ve@rL(;Pl@-zRz>ljbYSax(g3 zByxoKQZ*?LSo8<%+A`9)pB#9g1Z6kGOsnKG_9~ zhIJq;kh~Adn_rB$5(Y{So(pT7n!n%0{&@DAc#!k>%=I67uG1#^pAKoZs^W`dk84C9F7R@L6 zQ1eyYtgXn;O^NuQ|61w&4y58koq-P^W6E%@el?7=BKEF{*!CEkuSZAULw)ZtT)w=b ztjO~di8!q1E$Qde@B8FlZ;8LJnR4|@E1^3Y4_+YhC+PU_Yl$lQSNXzGGd5oh0p{TP zG>+TfyEtqze(ewebAn}j(fXxueI}S29OU+Ayv}w-%NaRv`VZR2l>;zN4>#nO^6=veqv2p`vcf5m*=n7j`(az6?7p3Q$Qet$N2 zLn@qHEGLTp=>B-~8EV9%lP`AKFVm+$%HKP4{3N_s-;Nvq`DIA*vu=L)-iV!F>6Bc8 zu*ROE_>bmip|&+qN=v{BT*u^Rl+Ob&mK(;^rkO93ojH^}p|5TAx%Oy@wV4 zqqzQF!DMSP=X3%l__FzV{Jtf+_cGzupVTgO$J67Tx&0L`Z&Wekj1O!yVDq!PgN3C2 z6Dzd%xBo%3FK`am{6`;W(B{oS{q{Fu$pz!tuc({zE$Pqbzn z76;eDxML4*8V;){2p*!&o7y$q3tJw^MKiYWcrQ)x}U zmG8r*5*a@}l>QvM_5e;x`g@_? zk-W>bX=8}wb{J&tX6sMQgPAbcZ9mta2ncpXUG*cP`7D|rmAfu*$T@@S@9Amm#+xhe z!_QW1e$>{l0EOAPf=-m|=T8E${`7E&!>ki;;BDe}rvB`+@`ci4=Y>nBWak0I`ICHX z9D4P53-vW@ekP;`!oA#5?tIDDzhUq}?-94ZJ;`ey%rAe(jqhx~rNW)wzq$N;D^?}X zZf!)58a6+Awz;6NOOfl3I~!<{8NYq7k3PG;)H~}k%$4*fEjugIN1C7RC#I1lo%i9% zK*=87E&uQ4(EMl*s|3USgW=;(Hb1t9rjh=w_Mt|v!~f3r6_4=b9&tVqJ8Dl zNTBLI?3&2t=dQT|w$U=;=0^%1cBHy85yJ<_;s1XAJnDVY$jLqMSTD(r<2ZKy)ZbDK zZQ?dTh``pT(KX+N13LP``FpbcS~OpoD-Chk_fXI{!{+O)+ANslkj(WbZacf;>(orq zesh{HAC-krPtv*i^l|)d^nGv->g#3kT@lqE@%!aUsA@PV{M2v${}=P6^fwNDZ@z{b zu0NQ3=}q^AeC;Bx|JP&`k9OnUz?T5o{s~&2mXrp9x$$)_UtKU9u1n^RdGTFN&^~z9 zrZV44x8FRwR*n4Kyb-lC*zsM7Pc8(+wBhml&^<3sH4rFX4_@y3I=`BCNy8xrFfj~{lk`O?z;2!=m( z!JuukzKH$3U)eUqH8>uV4ev-lpMJl6{wf8uEH~uVpRRqJPBxBC!0j%7rRQnB`bqeL zX>+*w)5^7Kh~*o&e0?wbDV$W$7j&P=_WRI$ZHh5Oy}Ns0N4AVF+Ml?fH48d7C354x zDj!#rH_CvoCbIaC&Yz68ECl7wXwDJyk9%1wK-e)Cr=zl^u{Y<7mw0@b* zh{v+&ui#M*o3ACSeIYyl9G9=Tjqw;{^cuFQ%l4PieBB=t1a_(=-2LaNX5nyHzLKk7 z&d2vbKl?Xaz8nYXkoEGuTz|q#Hw`ome+sQ zuSrg7Y{n&8Z2rb76vM(NT}AxS`Zj$+C0uVkkUJmpY@96_Cy5cd$*2C~Q>9)5tj zF*@A*sp~#lvZp!@m;7Y&6|z(TwUj1v_x}xBJ)Nxci^sKl{zyN+h|(|Tbv;nK&_UFH zMEetNC)6;m^?Gi62qV4=<#wY4tqyGcdidE8zh&-*(o1Z)^;SQUxBcI}NP~%I6Dzp>ddS^<5NGs?+dom} zl?J)`-v!?Ozb8#O)U2Tqiq#f=XmzpCNN#x-!q zo*f_7=S?SJI&t{wpt>~vEW-ap@vk-%ZoC; ze5m}ZLBdDQlNV5K)yU*){w-gq+jUkbN|T+Z^RIFH5^#}54fM;-m!7Bf%VAv*=p{+s zcT;ITFRl-}91Vvx^UJw>wdj%nv**3!>erwSqltHkpGd#@QT3~btJ7fbg9dK=7`{uD zGzPA~OT%ROnGfX;>i*4zA0rgF{2854CnHl<;{o?J()+iE>Yu&gRtz0ybQbMbmqT%V zcz=pEIc&2Lg+exe<_VQ>b+lx6Kn^=UTd>HMTsjqv!!NMo$3I&oyB{nyx&HdLg|=jv z+Zc7O?rcz2}Q?YOA&o z=@}!tf0Vz`y=)3DIvoNVdbIn;hxq-#A)&M2LvavzIIPs1R>uK zaO1cTYwd`3~F=;bJA&x9P|2pFPmhmbB1|LN7Bm zKLG_FA*quFm!FIJwxo-F6wZIm_BZS+70`U%ByN0I_r3?#x!Q^PE9m&o&{`e4bzaHU zr?}g;WbdUYd=RQ8)u*eJK203>Suj!25Ly(-=I7}AtMT3xGX3umE*Js#%xRB#)nP|_TcNErSRI0&6i`&O7O_e;_`KFZ6by( zsD|eELFoNw1Ir|}J;OZieB%eREPUMZ8+^$xlk%BF%{Oj}2!h_zE^_&raXTE09^B^6 zFHST}fP}1P-1!c*Cz_<4>nf3cy+QH&Ao*?5p~UGk*I#rzr%FbLc;d`9Z2o%coq|7Y zS|qURYIM44!Q{_Z;~~7SQs(Ao zr^9W?n6(k;clnU?Jnhftt@;E(Kh(JX#~^PTk~%K}o!_wQTQ(mhyB~8WaQAPPAD8$y zyCYD=>6i5LZ&CT#$!R^Y?x!sr&XxI#G@r2{>UeL!a<0D3w6G=Le?_21qpFn8TNIy# z@?Qj}&KiRE)o7VMQ2O^v%?R&r+5sA!+4{FI*#W-S#Blk{w^)in`ww#YbepmWQhV>` z)|anD@4=&?*Wsfpn@{BvE5RKyx&7~7cI4wFNemyW)3ZqGKU4eH&gl8UThmkA_;NyR zCSLIT0`rvEd>&~Ef{l|e2-`@r{)*$v#aeq|So|%n|9H+V0n}SP`0^Z-~WK(^U%hgIAEm>tSON3 z3D8LtAGse<$9z*Sc;U#7Kiht`AqzL|MYljUpO0^R7W86O1E=X5!N8buc%&l&PPIr9p5;t%zG6csPA8q*mVG@>y+d zO+E;rIO=tZ^zVN_?cdl_mH_oD9&_v46JKbNzMGbF`PCVc4rY>1;MEtR@1KHPZ8>iJ zK>vmcx!qz3D#x(-JnV4=Ms;crUv9|sljifyJ58cD)Ei4*m`m?BJ^ybX^AOyZDslDG zY2P$*K_v|T9AWoYSv~y(>7WAd<(l(1as8k=e;PS6F%0jO-jsem-M_ecSu1ScbsV>T zaJO+9sdWv*-L2SsCT#ABHEXR!{tK<2QySHAqK5~lu4eP;Iix{2EaC60CObd;o@Rs% zBZ8pse=>cf>jzdnXG05%D6T&G{8)-9-}Xamdp3Vt3KxOt>_jeq-V*-$4Zh0N$B+Z7 zAmKn7w}0g5`T`tUC6C(s*!*2^@B^a`C%FA1Ev9B-#g`9osP;OOzZ=y-V7uZRw|_Wu z*~v5_W{VetMfynlFE-wz zNqqcze0otbhx`BQYTjbEQp@$2_PUxoGWRRqhgY(BkuO~ta_fnaJV$cB^8C@f}{gIcg-EnVlGMsc_^I7V?7>Y(DaQz!-+=Gszi@Et_$DCC#@5^Cse%bMF zCKhjf4{K=QpiBN!~W-@(vD~via=YI~eYjj^&c*!pzdVBMEF@Ilc zRmk+Pg-Bf4`gbq?3hWG06!AybAC7#`A_^tTu=gQ$e0r(+AuLPk$&F8kf3ha;?(9N? zQucgI{m?pyR~^dj@9NxV8VUQf3ro+)_M8BWU39T^l$QW*avA6j&lGANBZqNQ9 zlF=x>4RZ{swJDR(6Li7y>1(1 z7|8gd_0Mv@ME@@D<<=isq`9NBMH1AnX7gp`u^8en#B=+<*4u{SiKmx9X9qj}3{zYU zXAT__F0X6O&&2-d(8LV2nX?1kcM*SP)thsP(v(cB7d|CeE`E(x0CDbhcBekSm9I(!U&E#i;%Piq>7 zk?4m`ctMZNU&gpRSRMXTNLbG1FQQzPtj=@6*K)0-_m9pGkE&jUrtmf*|Ayu-rI!}D zv0(}JSj~<<`?altiH<$E`=?xktjQ?|;m&`~wXTCN#e=!|q3TL&VlyHH(`w58@gwH1 z#g$gLd)#R5{(tO!YL7@1C9e<8$C*dz~ z2W~Z!@kj6fxc#vewkRISt-qIeSrd(yJ1~EQjK4Zc|Hi2F!h{_r&?b$of8MbgXfUZ>B)*aS9TTVq$luOBJg{Li&E9dk@yz%UQl?}ygE8SnhSRQU+k zf4LBrjzjKO!`psrzSc(tgN0=tx4*?sD+2yF7jx&c53Eas>hAZr^}*>^RLJQ8^F;c0 zl=4TDCTGCR^Dp@Pbr?gy5UtaS8(%i6X^;tt3vkp; zHeZ5o6^v`>%8f6_9{D!s0 zMwb!X`GH*$KC7n(WAx^4((^Q5&&Kz{;%ig6{)(r*HCeDC7?VeKk?NNs86b*pZ=Tga z4QCf_{o<;bH9?0d*;kqRck*5^n7q#A_QwR2W@7T;7tpnE`@io$ z@&44>krA*s^b*%Uts5|c>`GsP7i@P(&!9edvxHR_;H@*!uQYAf(Idb_nh75?? z_nce*s8<|LW}kDwgr~j&%ipnllm~})eBttarACvyxw-(~-f8nsAI19@rsQ3P3Hl16 z_?GrpEq-Z`KjHJSYow|4JiT9Q(UL0o9oPjnY-rX;@qBoiqZRob9f&pc`=#gU{i=$_ zpTVMT0M}n_oMA;G_6Fhx12+HJ6I@ zt*`y3ZiRv4GPwL6>YI+4PalJx4x3+-@4+wuPjdM!SdfWZE1y9pGa0}1`!yr{BcO}I zMQ;B2NV0$QYtU9K-zV#zr{8~9eVGW8ci!UqKdJXsNcCF>F25FYGT@ExQ(^ijS$s;* z&w8vLPSy;Vg;hP+`s~o|G^Ee^%;h&=sU}H#;e=|_*!&g@y9V#ITEf=0GX7|PHgAn4 z3H#!NUB9vU{a#iDmu7b6#>e{KEXlzi+i>VQHoxy@e1>i={kidR?pI4!0h?EQxD`nF78==@Y?q9*Dec7oY~Y<_>$ zeG&%TQWj45v*Y9cqK)y7yDzl!XY<=7Vvb}#)h=#*q-P%wJdhXzAqUv}9cx%(fkd`QDnQ>);?WH!HYdRyVCX&TpmZ7-jWkDaUF z^`k3H{cW$m0}2lv=k^bHD`w*DKaXMbvu)DzG`}5vB0%L`5m$c;+)aq)H_3d(BsRZu z{wBh^)i=2M+jt@a`iDQ})=wN-sF07o_PB5!n@^?wr$O%7N3MUg>!}9mT;hnsi&{(X zH{E|X-r*WdsBIzQlb*lu8mC3FgXUqkLuS(Rw7xn%tb%qAJ972aNV3009Ru*n_hjjL zT3?$Edrhf*xk~H%Wv+LIq;`f2$$dURvy^XESk%2n;=(Ej@`@Uckbsse{54<)#N5o`=C6OBXJF^-Dj1%^=JV>& z2zW8AklX+I{f{x3v)l)*F3IL+Xnoz&GYL{+OS$>)x#SF}n^VQ@ALxWCB;t}CYOG-M zsk!hp2o3MK`dQFMgY=DdK%E~le@QY6EXv=Wn_mN!19GDHS8`WGe;((pL-Zy%VL(?) z>HVhrV;`zNg7e2Zz|Ihv{sM^OUln3WjBjqm)$uYuftv3yI`z&j zv1DtB^z-TWb<$H?V{BhdE}tbSmgGoBf9&}B3zJV>h2EIm61nx2jw>{AmFpZXe`mIT z5-ekSi}<7WQyl4Lg8BZN!8C@gpC5nD0oAGjMdd0?eN6pTN{*3Zl?Zg9spoa--r z9TtX%{^W7{3pBmfz~0z+Zhz0WkaK7<>ND)tWcL^J+prbRFFVBTFKAVfhPNa;RCTP_ ze5%df0Y?@d<;K64B=w!|6D9j;tYv)C?_X)gL_pG<0`7k2vMgiLzSU;*bY}DU(;x{F zZk2HPG?474OivciH!4!|AwfEsQ2(V;2>bW`FI}H`JXMAGpR>hs2R6TTnWte&n|DHZ zd~^IPu8-EtQzzZh>~a1KHoqS&uEE)xe+1pjvhy^*n@3oX=qJ87y39*@|LOUxk8>VD z$(r_Des5p5AjyIsD)nXayRmyc+!)=5tFN2WEXW%*$$ZVtYfOG~3R~leJ?h;2)u*#1 zS-Zp!i{xbdDp2~`)TTFn(iBAf3ADZ*wX!6=!~O8U=uT37?Lz6Rd5$KIigo}~KeoQM zpI0YT9PT9;Es({>G~YqGCa5=JBc$(Q^ZnJx5j2kmbL%r|*FErfdIV%Sa`)pZ<($K%Z9hr&H?jHtbz&=Y?sJe^pE;8$$&Wvm z!|Q(R{Pu*^4zNu=!mXdSy`O;*iz?vb95&x(*COEJg|poG-^L{a}O&F|J*nz$!vCf9$m)T|SVzV{H83}o}!eTxbHX;=rfDQrG( z7&=1xNkQECb=t)e|#J{9A`F!9MrE}yBp*1)8lG2H#T_fyWH z-KO_&>qn0wR{y*9y{%9Xn8M}Lxgi~&cD)DdQN|}d{}max1A6IXarHN7cq9y+e1==! zc|6FNluTZWOEcO0b?{Gu@&Q-4`ns~CIVl>rN#rkep!C(lD-&$rmUHLFIy_S+hkn?i zcdfr5{ryn=e*ClhbTs|L*4Iw)*Pu?RQE1+e0~DWwB=N!N9-DFG z2T$q!ruFsZvqzG7+P2*Oht_}1$rAI;n5WC;^W@liaGB7HJ3n@+rv(Xh-HZdDU;W3I z*kAhnTf*lm6|TM>pKU?r7jDLH`Jext7w4}_+w7?;N8^WZ8+@M{ss<+JTJPxR>%4pXbxd>&Zq2H%}`bLXEE zE5a~l&I#yvlI<@|OIriAO3_^X98i1?r`goP>3TMwMScC@%;f#t{57I=243uP2NKm~ zeA4sJ8+Y%3x+NK0{fuyt>}EZkCn$;bM~n9#Zg(6-HU>GOvDQwhJ|3m&H_PghKs)QQ zKsLzqhkie3#*$1pefchT|A1WoGf)}*Qs@=dd|n*CHoj0N3k%IVsWJfJrmid~JC72xh0Yfvx`R{PStDIeBBh0aGs}O7FKWm48mCsE5`= zdUES8pUFN+OhRd`;|GlnXv(v{jQUKeg{hbd?R{exXw7P zf7?^lf?R0YfScQPl*X?;sQ7ha7cJZpI-Sd(WcXirGPfHyehqzZf)ggKg5V=;{yI1~ zg8kBM{Q7E|C%z8~$9+9Ec8YOmJ7g5XFlf6g`MaDL@$ z2zkZk?^suV__!#EtB*fdXW%X27QETW=C60r4$wNA#`TXzN_HdbY|7>K7d=-QMHFv1 zpuuxl{gmcU<-KGd(DIAi`itJwkz`oGERjCa`RDh5O!ypln_EAfE!i)y+|~;B1OY&>2wTKJYeC}?jhw`BA-28H|qdB=YYAyD@dF3BpV*Q(7-Udr-hH~Rmk|5!G z>sq|LjLoNOMsHLatq)T#$@r$@)9o+K$@t2(xFN3tlg}y6T4)w-1Ma)n`K42AopA9$ z7ma)wiAxOq2-TxO^usIU6>rZg~Te5#7(f?(Sb7r&o4C-$qKpW(K;M8Cy!w03SQz5kM3 z@}diLW^xHM=zbBJ=f`}g__cei83`|4i8_y$G5Pfx{}`hFDsbyBcF)ZS3|@twUM5J- z)B2jz?hEwn*NvNBZh2=$)@rZ9`cX1|yAUzI<<4zzucZH%w;%P<7<1AyXcew2`Xv4Q zF0{U0>W%X2$8ht@SWhhs*lx|uFNdu7EUb*`EYeS!&!^g^n6TapViVYWZgH9mrv!iQ ze9Cs>h33_};OiSUpZDCCz;Cx5-2Pn6nc;XBvLWXto6m7O*Fvvb;oSPl#o|J&>GKi> zO=t6YWRO2(sP5y|M?d&w;#-|EsGY;^A9U-m6HLMnar<*C7ezwhi(_2>w(#&sGC11~ ze+e=^>Hed|^OC`+u8VJ8hyq+X}4)viIlrK6?g2 z`#ceN`|}6YjwHSQ*r8g-4*&QP^O@;W0<~3jLUVsF&1Z<788JKJjoMl=K8q-Qt=aJy zjL)~^`ad(g&4_xVH>OJF)c=&!mdp=oCAO>)&1)U{1WRF30Hl_ELRSqT*lGBU*ST+>)!W zD~;=g9s4?o`hRJDlgF9j!R{U+eWm+e4C{VshVM=N$J#clRyYxKGXYrZGFxy|A%jZv3GcrNb6CZb$@i~ynPs_r; zK%`S=Zv5M>r9{8~df=DF%hJ#9LFwn{6K!zzh5uk|H(C4&AogeFoXyAx4^O-}=i|Tg zV*ls-_ulyB^$0GX>Icn;_c>2I;mhXJp;`<3oHU2svF!NQET>+Gncq?P{YK{B(tNh` zH^pUNmx}b2=F`i1E-c;Z%Z+~z-SEO?COhHcU$(y5y;}lSRe{|1Z`Yj+$2Wa4VdzIT zpYmPTfli-LE}sMEDsW%ct%&8{URdQ1JM3b){rQT=v(R9E38XAx^LgHGC#?39 zyl=qSk2m&WBow7)bNNg!N`@P&^MyX)?D)1|(kOCR-iFI(%+xICSaVI(pHKJyJ@Fq! z9H-mh&ZBHTTRlDlr}HYgd@4teBE?H=aN{htem0bsK+W{`T>UJFGbLTSx?{C6o6l|! zAH(WNlKv!)f3&K^l=w__$LR<6N%^4p^ltb9RRcP4_Y2irHziso?pPMb=F{qY8(gG0 zfSaFw>tsfzMY-eMk`GKi4{0mm2x~oVetJjKjPyO@j>EdK`BeO?g~ew~Ve?)#pVgB2 zY`5(lh4468e=p5vd8#Q^`MZhw8|eJh*>^7Z>-li`?B3vo9(RJ_z&AFZ71>KbbIf+G zf4lrbIL;&K(65Tk=LwB<;JRx!H~uxeb`tlkxefhC$n=};?;W1(55{++x%ugiB}Xv& z=T*4Y{kqg&rT2d=4c!UyKa;urfzQh$A-61xTi+C(T*U1;&!N(@xAgA^=q1YUzQiU& z+?X?5|LBkYXfpSP;hw#T`o=HczInN2&ZYZ_;%L)vFbX{>r|8==fJl&y@UXbj9aOmP+scRVx1Np!@{B zz56Th`i~lynv(oUZfI!0=J(Q#FW|bS12_J)m|;pT40FSWzb{EYUy0J!XE)nm*UkO7 z^%ajhrsUcQH#}y==J)VwC9KcV0sB|Y`Yhf*^t8Ph`T5NaTR(0mjeq-5@o!fxZ9IR> zn5(bPof?D+gZ4sbPUOG)Bf36vryrT(;bDup`g$j4E*w0!iOa9bHg61y2?9qg89#LV z`>}cnthpV)<(Jflqhfd}%&2Aa>yf(-ZcpCDov%^aauOFw-lnXmlzo5D{2G?}gPnC0 zw?BX9pCfq5k0#4!SYcMEjL$qO{{8abSr|UHoI8JNHf|)@H`W~U zIs*4tk9Hr zDlEn$!EF8nGi_WGZN$~j)>U7H2bXEV&7JDaf{UfVUQ808?I=6qm|B#DVQ&9yU z_Obap-giHINzUc=2i2W6CeMb<7wP9fsz0G!dKOe1y2$MxGB7?1u7B=u`P+MZ1UYDH zf-c+IN$+PWrH^F?ufsBr8lic4|&Prb2q^)|Sn%I5Q&f;;p{ z*eVoGm7S;OPrat>#cgvBf@TXgpRc^vL6!0j;a0ci^Wyy|Dg`GnckeZ*YRBf&w8kIS z>+j|A>FIJ5v(8?EtId& zSM$#=?qBHGX+N|-cY<4g`Mp`vf3#0LKTh-cyVVh}=zT%B;wOtQY5i2sJqvqg-xhY| z$o`z(50-Rt1er2zD*jl;=CdyAI-F8}A?jbC`Mmqrm~7N?LbKIwQa2aWWwnVw~`~BAd@#37^{y6uJFDwku4C#Stg8I?U!%zoR0C7xd=tN73J5LK?0* z;n7L&{_!o=&#s4+a5JiN>nm;UnGiK)XB>5`tu%feNX4(6inQ_0D*`X`*nB?IFeQUG zI-|1IfPen)eKNT$!-MgRWb zVt=re_``=6H1ne%`tyy3Ie0SsqG&%g?e7jevJ*axj^pkRtF5|(8hVvbI=A`vE9O_l zDGJWZALjZ?p1;mxqQZS>*wT|3|0bC2hp(NEbK~C|ipHeXu{k3B9ZKo1{n#T=J-SF} z3X$H6vP``1C~y29J=l7%Pr$@gi;g3R9QGQD6@4PK0#K>wcj&fx4t#U#e zBMX5WA9u<&A=O*wqIPC~Cf^NBKZLxDHiCJ3+5R$`@2+uX7+CGd?O&QvF%O=8TEVTq zPM)|NZT@V9NkiHCJpO=$?}a|x{MD>@FNP1=4^NTJ_ouDv;i69xh_XwHZ zY<^YBc7m>V442Q`geX`r{vbF1T;jPOQWbKzd@abIO5Uc6`-^D4E;$|n{Z{9=d{uru z3;E@x-1?{6Lp{>s4&wG;HeV(!OQG-dCnCOR{k&{vOuE=Opof)=uLqR>^SSy71l81Y zL~KtIxo`+isEC1diw!~y$dUXb!Z^JVF%h>meRxO@dDm=K>X zv(ZwJ@ima*OQnAwRC_cWR6eldTjRDmIHYJ2S05jTm=LW)v(e8}#!o*Y*2hs=KZTuB zTXXsGmGJY!d$wpl1MS}~*gFq)|M24aKf!aBg{?D29>HlJtLDB}2@-MM@&-fv9OC(gv9iEsb$Esk&7+4R9d!Z3(# z(WdBs@fT40;YVrcpyTxkTs}>gH3}9hTM5gLvGuFIQlejmv$*l;Ll-9qQS%hWt(WNo zonOvKUyfeWe7XMXpchMFo!bWPe705h2yF2p0bWmM^Y9u8aPFdnAT0egla|U{fwskp;IGEVa$O_Zh!8|_^BkOa5}pG$L907{!=J_ z`+=*UaUG1w;IVdi&7aMurR!JNc10eNel+{LVm^=Eo=Rr^n2zsOotOUnL#g=GG+7bN z6T5Q#A!iF?qOs8q6}!mz97^fuH|T>M?T5gr2WnNbpQALAl6UK$_}};cRjR%+Pdy*LC=_$`HL5|E zRO^pJ#qDfrwiXRf~fsh&zsI@n;r{5Svj z7wc|Z3LM;J6Pz(-$G0I7?qENBHMhR<%Q6C&%#7pf>zDO#dZ!<^zH)o) z1?=6e1WK>4`TY|f0CA1MTz$o>1-NhJWzb#3=69ZH2;7nj=lZvuYbE|{rvz?)Lgw@$ zbnSZ;W*=npIZ-_YlrE+TpVDP~(f#ucZbl^4(~`^QpNb=J_U%b-eB1cWfH-*}R-R__ z88aszu<;^SUk~KzlADjmqN%{)b8jgOcz91VpH0WVDnE_L0R<~GY|ZAg$?qww+4+VW z|1L3_N)+v^Q1?iTln*-o)s*mgW&K~lqoSE_vA$YwoJ#tISYg-uMbh)Cl)m08QbbGR zPTcob79~t2VMnbn?)B?`=f!;5=l8+rFaLplXEvX8VLCWIa|}2BO}zYD=uC5e zJD$tm+P8(cbpB;1AIs)%zd;IUK0hodB(nJvrW%pVk7gqNbSZsY`t}G+d39XW9}ggY z|6xGlII{e+fG<^dGxc%HzI>Sf=R9}6Nq~bcsc{~SF^}6w@82FOzE${M3V8F5VAQ?& z{)_h$nI#($6Ekx(T)j|wp4P|kvrpl6zgOJ&_D!u3k&BX?Hs$mH{1*+n!EF98b%W&nhb>(H^wF>aoHM)#!VY&WV%0}divvLC)po8v zj?XH<=h;Q@`U{&+ujwI>8n#<_UC~1N_XFks{DNqR$cW|oKbLkCqI~29@VeVg%0Jz| zr#2u(vVZ;{H^0=%nL=Fd8FTp@ua*t3>T*Q+CC#TZj3-(KlkiNSjL%zC{MzeyK3vQx z%!#oLd8=sSonggkAEYL z$fE)ieEmLJcAnyMkF41k*`QvPEi5`9(_gwi zImdDwsk%H4CmmzQuUo$7!wIhfZhgh{st##qpo?S2vibb1Tn1Yb%0zt9^_6+8jmUxk zBi!LCo6lLM-@xY0H!h#yqm0Oj<3{*Gjm@X! zPesY@-?rTOvg~vt(ocOVPB&unx%p`y)FsMX{p_Zyi=AV1xqRlgmV=*%e@|NDCEFiI z^QrUE95q{-!TNKu`A@n(sP|JRu(&jr+h1_<%L*Ks;mzf9r)2KW=<5>h{Mf~okvKhm zFT_Q#`5ddb5oTqso>z${N^0AY-e7z0I2Ai5JE?@Qy2ITq}ef(rAbM~qC>_MYhj0q*3$2PdcW;M$1=F?eO*)^q51l|a|%g6J{i9sUm!hC^M!w(!tPg( z1qb`)_)_fO%&nP1#6dtZGflTG zHoR`b^>37|jY$1ULtJ>G=HGd-{UxPe!@x~Qx*#C>If2H9@L_W_D zO|+Dy^?y~Werftc4y@NUO?tIKw*Q#s?_s?;l2~Kz{vgds&XWHAIo$nwfx}ngz@Hvq zV!@7I<1?0lbFwS9ez{{>B>E2uhhA6M{Nd9L@NxTUuD=6ax509Qt=#xjNC|* zj)*QgZ2pX=JcH|7tGNB?_Tf{=<@tyfx1yx?pUw{za=yXsRi6c3{bT5oDP;LL#3@5$ z{OMBhr}@mbc-*5kxBiiPehN|BgQ)fTrS$W4srtw8(aPAet{0cT;s8nfc|{ZUd}Z@@ zIk8dbIU$f z91XW4!@2S0nc4zed*BrKtFigZ+a}@fzXWdmLf_Jme7HT4%b(r-Y*1;FF2rTCGdVe_YYsSGN=7Yl9sH|v+!pLzVkkR;8Y zgqg|nrT4dviZ9LFpMjoyC6~WbMiTwIFbTVFknvYU<$oWmzCpJWAG!SfZaal+-Y)t4 zg9ZQi5$j)$Q(L@#UxBNC?VP5N;}0j{VoMo+qbU9wt(38HOiwOxOX;S)EU|@mPtqi&R<>@=a@d5VS{4c$7B^o|)gO>hm{wCUZz>VYu zT>c(hip1kB_Q0=}&H0;nKE%#*BRuHm&CUPrd0oWwnPg6n@?+M-Q{XAZ~QN3EpylittX^I92<-*rh8U()`HVWuHz z|8P9s8pr0V#^o8zn|@!gv25m39ABQ6@Y%BS1XS+H=1XhXcX03go*Q2-Z!jcH118`C zFBxB>D1GbT(-zULC3k<%$8l4L)%*!)-Sk5G@2B}n3sS~Oaos_&m#qFk`zxF7=;DZ% zs&KqT+oJ#ZfAssezYV95+NBdPuu@6NmoCNE3nvS#@j@+jJYK{M^W$ z-!T0Y0(RK}-1u=`Ni;lvvzyD0*6|dWtrN@TXI#Q$vR2UN^3%81QE03@$kiwRVtu02 zRvT><+5EUpDS+NnjtK)@W%@?XXRMl{O=b)oikl(lHb&tQ1sU9SHD!G@%`zX2XQ9w|Lf>yz!9Z{V`)4Yz(UBg&BUQ8&Pn`h4km znxCn$ZShKM3obvs-W!tl>kRPfDmFhe6O}P~e^*icj^=0QOI=(VKb#vM{=NQ7SSMdQ ziT8eV$|?)&RX>S4zgV!t8S3MwarJ5Xf>n63qYF4CviaFz=K&kGICAr^z`96$Z?qHk z{9wn2<_;U-%(f-m{dBp%17K9gbwad(jBfz({KW80yTH-ipF6*QylV_Z;4W_e_1Y)- z_<374M0V=J%)g#ArGVMuXl{SD-m1xD>!HzHzTB&_VU%YIcRu+3M1AtdKm*%sXU_)* zq!d86Nk_T6<$UHBH%kt@~C6ciaj^{vxeUWA9BScm9ky0i7^NTVUy*kvph zFJ|kLQ@>wA-1t|MysygUZ)pF+Bh3O8_DtaFS9$CC@NK*m*Z=sNwMw!-&KVMN*!<<6 z@_@o84#FJ$WkELW9O2F< z2H(~qHIDz`fle|$>G#`v7~Fu<-3vtVBkfOqlIZuu*(0$un9b+F@y|ie_Xc-AX}E+3Tf|L8jJxSqTJ{}-h+%#5^UWJG&=znfq@+a4s3=Vt zO^UXWl~A^pRWcf6T~sK9-~0Mr@7JgI`Q6UxpX-n7I@jAc_xI!Re4OX=oX7ILAVZtZ z=d02BsBPm=W>q67?;VWo2r7)tHYS@Q)a)uf{Jfs!4g+`K9Vbw0&-qaO#ivC zR2To4swT$YdE))(hK_6)I{B#Bd_H+T&Pk2K5&>!`eLsKyDtSNh^6^)|Q9FwZDW&^Q zJx5*K(5#A#k4lO5FUjAjMGv6vW|0_wq&`|qv&J*7>7g&(>HJ;Le+{_mE;ApAKWdG= zd+VbedC{WJC;6-G+X1=3uei0NyYx-Gf5k7~8gJLqM-9R`=>Puy%!vB!W<^hQ(&q9H{=Ofi_r z-_5`saN5U-yXoDfU*hxms-Z{G+@J$+up7@GseiXqgP|JpZ2l zR2RRuRY8sO>HNXEE3ioY6c<=a=g(-EE|xtr1Sv10^Y`Zb0~m1TJa<5^EB_GBC%^r~ zI74q7G7DNJ+P@Nbh?u`wedslO+jE|hW|C9O2jhe0KW%5D@7}Bel&u{vQ{rS7M zZUFVn+06Ry>+~2jQrLsp_J!9!3E_JyT|chjJ7D4dWla5ZI&~EFytxmq_M-DQGav}O z#;#}fr%1UTfP_Il%zS0FWgPq*9L(e|ZgMf2xaTDJO`-Rn%v4VS`Me0``#E}cIS{ic zfm#1Gp47#gRh3bqI-ReixGT_0K7*5ZL+9)6qp{dyh47BSUOZpRiT=zH7azb2>$76{ z3h6Jk&tqJgH3pduD+wvzxCqh-zV%;kjX!?pln9h zx2mK1$SGcxS^t$^=-@ste=1o2mA{{j)VG$gwkXfhkja;aj}r`)nZ$fQvf0cF4d~|p z8!YI2JsTu^SLLrAldtP`F-Yx1AbhOj`2vEkmpgXA>>x*GKAE@iDB7PN25%3vQR_R~ z{2*{%vWA)eZ=7`iPA7UX{iWZ5I2dwx4>Nx$?kGkouhOCSc{*RI9x1S=PdKyxvUqV0 zn68TxtKUfdy1V@fs1>Gi@|WoRyxlbxZ|*-335vRl_7BO={r5tDC|SVW9l`4p$xpQ_ z#)s5LA(O*PMe9j^Iul<*+@u>!e>fx_<8jkRq3Gl&(R$J!?u_XGCF`f$IRiRBJ>xJ& zHlvW49nTLC`t)U*96F!yg`1<*qnP*q;`zy@rx>pe7=>E(cz%HJhiz^us8e4?j2|+e zypgYu{9=Z{BSm_CayIBY*KSrNV7*_Sw!jv>zpKaWpN#(Q1TtGO(;uo%^g@E#IiROQ z=VvL}2)ch}F!|A36odRv2Z)_tll0SN$~i6wjnU)!_Zi`SsYdIbgObMyx-X zY# zpwa(a5Pd$$*FhUOwEM?LrvJmi7?)*^K)G2j|F>RTpEkv-pmuv{2${j_6Umoqt3KMl zbubJWLFa2m_)kvmV3lCw3wr(aCcqZ?FB=Cn`SkurBh!`es+ME+hdkKph2nbHGxh1# z_YL4#HjOzS`$!Ojve)hevmXxsur* zx#IQ#C>*+pc|S|%wK#ZR9l+G5-f1PMuVV@{-=p(Yn~(xQf5Mpgqf}uITrrMj)>rFp z2(ZEcEwr{Kg36aq<`ww;_ZTx@jQ%OYCU}&Sr1AESAQkZ=acg{8qp~r7#qs$ z@2|U`10NP2V)E6oT!5!!siVW&dA`W`npbUC;QWZAO#M2VHU_Wk(;F36brbC`k}vRi z2(F*9IHienzLw2H`0P+E^uEnew4UV4O|~A6uDrzbhfA{&KEGZIb)Ka2HD+Z8%#wb{ zoIlk`MmTJx7Almd^A&wa4!!;JhI^$$=PRoT;h*tZ=y3K6Dql6tD(F&+B;0o6`6BZ} z)W-lFU8Th2OY_zbuCDo>z{ZrWU#7Qh(e&g|VtkSJA9YS#3G$mPn0yty^+H#dPKW*0 zbiN*M+X!bpCNlHG!f%Js@-to_H-_hn^oL=G{GjZ~EN*)UpPvAT=ZBesB&1#u0Bu@y zzUq4hgI4$wW_=abFB}3cuVMB#&X0`)PSTfoKWD=C>u7b!F{nzS^R=)p1r~F`%=&6W z&s<2ejAZ)5g{lH<_e}+bjHB~qaPkV&tV(3gcmG~B2LC*wfO?11`5JKgA($^c#XXtH z^F`+KUi}ePbXG_20_lAH)vbrI`z|o~x@?EAf3!M^o=WE{U-k!7O~1!gD%0z)+|>x* zIi-&Jojot&gUsjM^W@Og@CI(99-XfvNeCM~R!36iJYQt}m0hKRPM-S9y%X?!k^Zp6 z*Z}n~=m#Cjbbq+hpo6PDe@jp^hMr&G&$ejfqLE_rF(hAuidMp-(PqqiFhhGAs?C}T zmiBbMHdb$h;ID{Te?6%^jHXI@!jj+o{qiJVflhuk{eUMe!h!?`K{ZS{lkjw*U=E4BnS?r^X2$01unYnVe%DqAqQ@L zI3V^uD0%*sQ!xSO>{3Q;ujuokpm`N=WIXfy>%yopc=9?q)HI#v3kZMs_u@mi_%~fl zzev73t^=OjsDgZC>3r?v>LH`!EYlx;{|z{{zbbn5^`M9k(jPkh>42gox4DlJbiStk z0sKt3{*)1&FQpf9NHg&jr#ywumzR+5fO)E@{&Jn@^GUt}lvR;~PbbIHFTZ65=oj>1 z)?ZiF{otOSC>2Ol(fPX9%MLj;4P)|kcGgOmBV)|W2e(h#hU$wZG5Jb(z7dS1Ii^4C zk$xE6Xxk|Eem2S1`4T@kU2nrY|2hT15WdcVSzo=H9uCW_oSElaWess~LuCsyUl0D9 z0#UAk%=+nlpIm6_wqGniC;3oypMZ7i1|szUIv?_DuR?=+EHgiMe>fWNmXSq{ZIb-{ zAo!4-QVw!2QaQH}y8ayZ1nfLf87b^vELu;_kNsRx4@T1pn0z>810L_8jB-x!d=wM? z8P}D5K$&AHvw!M)E?}!I%ILwvbE3~D`x6rz-Zmfh}R}Gl? zpYEk?Xt1F*JocmOk9z$^xDHlKf44Z}FbdeZ4x~@e^{1DE9}J6|!dd9i{oPadU|1YA zmpLDnJ1`t3MK5QbKP{DwhlG+%%zUq8b}GbN4q(3jbwNHCGQNa~^-qxb-9DIrKkimS zkEil{koRM?nqP&zeGfD91r$CSAABZ_40Gsw>^@iyOU@*7*{M7qWPZ1I0N_`b2cjfN z1|I?S5PvO~$w&BHz;izjL`_rae5}>^0dgVNnf*(S-hfRM2BFtG>3r1pkVjx#!_*JA zWWYwcgV4!y&qaKZ{S(WksG`BszKQ7v>CX}}4Unv<0@#|-`PiuSlT&xOCa4`iuYYbW zutT?JX~K}(^n4*OVkLyNj%Vse>6>k+dJ}+4Af1n(?(V|-Gt8NMEID}?mH$`;zYoy) zxKQo~E2Jhd{aImPFvRS)XY!FWIvh%zmN5D7w~Pnpog0|6{P{IX?Fz|*!Xp~=4@Me9lZ=^XO|9MX%qqL)11ZDI1Y3sdxa0bQ8y3Bk$X@NJ|^=1M{<3{3F!TIY)iD@Sb#0mT&G#AM(0j6Q{833d ztta`AZ>WdzCnuSF%=P7PszYz2=}PD0<_V#GyewkYFaI3n@bt~S(FP};5Ayz}y9V;; zuWLE8eyOkF@cN|Q=!FNJkB;N2Xi&g=CLdLU4AIR#J>cLhIv>ru+PVJg&I+C){{7?s z@BF9T4rxqLhW8yj9{_#C0J^H<3>S5DnE7jLh8q*OhkCb%oGxec#DTh7e6;bW2 z8mc~YPZwri@7{268|eB_Bi#Qz|8|FE0{Z@+oZilb*yS_#zh948$UbQxO#6qv|0mfv z!#11Y%>94Z${YRlGy?CHygnQw{8RXAcR;JgG5ynW(^zzCts^`?$M1hK-*QXX2{-$i zi|v0>AHoj@L$t$0rhhsZ7Y^|)cFg{Pu_xl;*@tD!^G)|Aa~v1j1HE6gPo%FoM19f_ zp9%vWZe-@eW8au#t+*ay^$Gbt@Y2{^Xpi<6n)aXJ^eW-LX-`^(AmqV2RTaT7QE$eu`$oqFskCsPzLAROx zJ3|#YtU6Z?ZJN&WMb5uR)~TXNBOADyP@XUH{Bw|nAzFPy65J=!`O?z;#$C)gBgoA; zMD<_O`p!ayHPHF`cF`F!ehg*$uk2yoX!dS>vGdP9NW8zmS7H;)IyZ*NSF<1% zeQR3)o3rSAnP1uog(fCUzE;KsgNY?#_GfRu9S-B(%wV2x`fZPg?L!@z{;Oe%1@2WO zg$xeye4Quw(!H7rhWhK6^Sh^KSm14!#q0k*#C)Ld{ak=$JDB|i4!bOHVS^O1yGrNF za!@fms0(4vM;L$6!8L* zynURrnbf5};`d8T4G`dnOEM^U9naS*B7ZKB{RwwQfA-V)>K?Kao_;Y9t8d8uf<0e@VbE#;Ghgd$Dxgltxj@>3p5+C7jJ{ujNif(D|}jVTgP! zelhtB&zA(D zUuza_f)=+C%=!05rC8MOoIT85PUmZ0=T2C$Q%_94NWMnD4Tdr|OJ;r$^eG%pZJW&0 zFX^lCkiT*svwy&Lz6EadmO!=J>3k(zOodTl&dmH8)?47Sp%P5K&ei6^5xj-z59^0p z;D7}ZXwiH+UxUqrek)`*vp=qLt`5%AXoiTle?)wd?;pKMu7Ey!Be?bwo)1#LMkY+a z^+ny#D{DGmQ5Fplm6^!oOZDRfoZs3Ft#}eH;)B$$W3E3TDK(3k&-IcN;9-*8(UIkJ zzUlf{Up3K&$S$RwOP){nhsKlI zIjhukf#xN;enp*~g@yzug0ecDuRE87d?~3g`O3=OhUO>gz^{8eU!;D0*t!W06lyd1 za+ZljzQb+B-q$4SuX06y&`8#0@^z>t7&1-FnDv+Qm!VJy-e36i*&O%K?1X))JYPA)`B1D~F$fR9nS8Zr>R|n!4UpkY=WE&X3b2`afZOqy z=ZicaO0l1Szb=wMI*;dz_$Vjtckzm9fZXZv%zUr>*aUn$LIOS5N9Swt{GV{(!b#@& zYe(t?tQjSNhJVc$eLnd<=dBodlsNS=vp=riwF!7xOOU zX3%gL@|fp~%r~-oZibK!O|EfE*ZvmIzl-0-pv#Ij;L?Y#UuNC>;l#wz%=1@mxe%Dt zX2jI5h<*_eb%JB+*D0w4xU6r>%r_KLg!#m$@35nMFE!u5Z&KmQDMuz>N@eD_NTr?0 z*N_jw^QH84VtfI?*Y6|dxPQ}k_;h!#NPkGaKHC(7e(6qTzH#=!NStc)5}Ip%i`Mrc z@(pd-O0db^%fTz2FH*m@$WFi(?!RE9E1fTc{03OFF^0+4yA>0#>DyoMcp9CryTL!f zGbxQ(e@%6nfb%~5f?Y{;zINuxqvG-lOn-Q4_XNCYKqqXFq z$=BB^LsX{!nJaao^HuS+oeQr&F6jJ2*RN_Rdz8IZ7J81O^JU-R4BU3i_?{B!%-5=hJ9LcP|_9=wG?o@qdeqK2s z0?M_mnD-wI@0kGB?l#Q+hK0+`@$6o$Ah(asmyu2yRDD~(%s0Xgnd8y+tzvx168XkR zK^~M`UL}@qkbD`er4cE9@Ko9j5oD^Yucp5ymw}G4DTmC*)J`=sP5SJs{E#(jNxI`~>-gWTt+d&=m6d z^*eM-=J`@3=4(?Eh3B_3&NBVs>{%1AuR%N9I`u^K`6OSv_o<ORXm-qjtTyt6F7|N58sUrfzPMMG4)I5XE+?oGh_A- zS^ka($*RdrfB4TZb1c8>6X@IVd}R>%p?R+~5J=Bs>X*uVbF6Xg6O*s@0eK+h=`5yS zq(6M7YL2tKK7r~qI$wuFilMM`D>L8NGiM~;oAwxvHFS#fi+ulJ`j|=>@gRuF*HA|* z-1kHa*le69+Ml-we^@ZM5o%{1WWLX(eBKJn4{n9uX>`77QhtKojbqI7ua76KaIJJJ zlw8XbeLl%o?<4XkN;#iX=}zxo9Wifit^}uy$~3o>E>@a zyF+ySIE&_J>F<%H#Mey`N?mF zakhh*e5sxg-mg+EVDhzWjX%gFYH{OZy8Na1d{W1>5J=uVhB==;WK;xXtTSewfAwvR zhnasdvwvu6y%|29)eP1ObiUR=8ayz!XP$qxzA?i)^P0u@k|Ol$^|U;=yKFf#-_Wc! z!{zbKa72>lD}$)Nd?SjXzr$vxew8YW#GMwEAXr4_%XVNTm>TRB%MVF^IMu)kS3UU% z!$;8hdi}To>Xw8v^LY(dE8I`{6FhU^`6Az+yde1t%3F>w^NoqZ^&niYv5x0!Fri;T zH|0^ur)fDqAE8qgL|zMeCnYR&Db}7bgsX;<3Db`4j$7TW2$5Y#6}gOExD4 z9W%Cs_`|$@Nf7h3*M|DTx?$?f`PxgXLcn>E4l|#RR*itawfao`+VdtJE{x@v{S_)l z%y8V(26$K&CaS+k{gRxN2Bk(bne!E$g=W~cy@AQsT>U&~_^?=PK8e(?rZ6+CS<(O+ zMPVZSA^G|eQw$Zk>zVyaVb@3Cmh$^he*c$fy+7d($BeIp`}qM(z9L>)Vy_o(VOsWF zs(wwaZ-6&P_c8OsC`Bu5J*XLmNzwVb(fb#y{1nfePm=0qg)gZJzu#o&eD!@Sk94E6 zn0!55ZiRdJHAC}EI$tV{YACj@gu7Es*RLxzhUimA9ml#KLUCX#C%Ai15NaGL+8+}C z_jfHJ`dKM_yZXnXKb-d}o-Z<=e>TwtlBDIC_tRF6-HzVm4T3)co-fiLe#zYgVF&s# z`^#nf#G(_c&EP^k&llOhbS20i0$->w^-D4;1Z++W=WgHZ(l_z@XAcPZ(zrQ}dH&`0 zJsv)PvSjjQr)h?V&v*$B7t{H&@=Svxb<>#jm(LtCY#jEI$=3>_JUFMefSYSX&kuhu zFvIl`FTpK{&R2G3F}%oF&E%_i&j?)GdK<3Hr}H&#ZYA{Yzmu8I-ww6J9vd5Aof)04 z{tk_>X-gQhe}k*G#KpH8!1m655uc=f?Hct9G-kvy`Fj7#601FHfbh~>(Rw99zf!B^ zQQxSO%>Io=c`IxwtP$rwc|_GOPa$9XeXeq&%Xq%X{*8tA4N;O_#G+c4@thJblRhb;Xk;ZfjnQNeg(w1z^)Cl%=xAx$G0QR&q^?I6P>Taj+;SE zx(`#oKJAD_UY5pSZNcY3n@!m~)UvzVyA?in;fSbQ+^eUP);Eb))~FFmD)rvM$SmS=zIhd@ZRq#W$rMLv(kZ zuVY00RaI6Dd)=2a=Rc-Pj==LLUW1wQdA^ntd_5RZ36&>3nf*~yWi7G8)n}l!mCl#E zPb18h*u%UZqVIG|JV>zyYB8O!AyU8Kfcin^`yo%YE%Anz&*0pL91-7r2>o&w@^!lI z1h@ZJSO22;{d{@emUxAA4g8hh`5H#lUqMgR(7qezn0!4PU?hD1QJCNV@BT27FPp4y zoR922CSPZV%tk4@KXa?L(e>+WqzfFa>BjVj^*P&7eq%3Kw1}=>VOuuCZbLa{K5y|g z7PT%J$9#W$Zm~b4miFTsQ@i*S&o}&pe0d#GVdnGS4@bbe>S0X%GIvdY=#l!&{P6H1 zQ~W@>0#xGYeEpM{2D)D+F!PNkhfHz*DHTk7y)rYH?>BlMF~z-RSHR4>p(6bu z`BF8%2C|bK#pd7rp{LNd@IMYk!*SiGOYrOA57By(uj`JL@I~04{3(I1U$MgetbWg` zAzYHqSJu2n*gj$xGvA2ou)te}KLV?7`$T+@{;;n07pRAaGw%ii$B@Si7z`u5)FK6gWg&lgGl*3A3HEtd}!s5KuHeLs`>_K)3c(PipenW8Cn+I0^S?dkm0UP^<;DHhE7?5vk5 zzSMCK{{1WaufL;%nEzcCnFq^vPGROBd9zIM@cZ}RVIZA9%L&)Ov%!Jc|699$I6hW! z9`;)E{LLct%{!nH?&z*%_Sa8!vB0AQ<*+|;wrKy6{!wK~BOtAv%=}|%ys-b-yBxY5 zqx1LI?H818+{euCb&4!-XJR?zInnvsr>uZx>`7#vk1cPtz;|oQA<2U0Pm|EM3`uoV z7?i`z7xxUX#J###z`ZFve@X;@&*Y7e$%xxr*ZXrMe`d{XoXU(n0@XkCe5BWb*{DYQ z4QG}?=Wj}#3%nNm5@;;q_dj`mda9HU>KxY-V%O36)7r2Zw(pQ)&UbC~j6+dHBO#=T z&R^AKf7o(PLG1o9a=t|%tlu8$3}E)(_lt=DWjS?bzHbnn0G*1Xnf;5;9-3h3iZZyN z#Pb(R_{*1(X)v{q33EPDPTCZYmcPa1Z|Lhh$lPts><^BSGR0YPw_uhPoj(bsYmnS? z4zqrnXEj`Szg+>`f6*b*Ka#&*rIpZUg{xRTLiSgE8e@Tn?6?bg7IglUwlsonp*NGi znZo|f@Edo*b|am?)0>6*w>FeHf8XL{fvqmwg~z|MMf@ue{!+nA0sX>p%=t0zXd(Y! z?!u>{D$#n9zx6-W5X#D8_E+_NW`P%2+=Kmf?V|N0f2U21(9a(?xUToLNd8(=zj7Ue z0tK#4bp0EXI~%p%ea$`1qw}ZH>H-sVMr?jxXJJnBx*&i~0PXZjy9KqDT z#ShZp!gT|tznoEIf?rl$7vt*-p>NLP^5InvVERjyJ0`fi@jA##(fLwXc?~$QW9pmc z*I{^PSq|)3%<~0=zK!y&gi(i9h}CZ-UzddQb3W!};P%vBw7D}q{q29RCiw! zZp-v7{?C7r`Q$x~0I*Y%Ve(~sB?L|>^k(KKS5hKi`>a9C`Q;{|zEzYAW%Bjc!vqg~ zaRojXgoyk(sc$R(q`}|Zam@SG`z$rVdSzFb{B1+|P`k&H$zNEk30@*~6=s!(i1aCz z$WLk)T!SOlHq8Ez6&b_u8pwh{58FlSN&XJ!3j0G=JBrnJB!AAwgzuA&FM(MrJ-LKH?SoW=UYq~Pz5WZ7asrwCSC%#AIAC1~=q}>9P9g)K%eqT(dVlY{&KOoI@-7=m091dle7@t4_X2*4t(c-{RDrS zyNuAxN0+#+`!z^?n_$<*jg|BkIB%o#XDmMl-TU=~J6}oX@5L4uD6f7msQkg--$MG! zlRJEnU5*5N3#RK^zlzPE;NKzmsYB;)%I!E*=A;I(@^t<*8~kCz+wNlilAMpZl@tQ& zD&(2|vixBLgc&L^^=(o`0<>(^VD>*=?l8t$mPPPmI-S2&uhL+_teSV z{fnutgtyln#Ogb;e?(DWj^&~*Ls-i!(f%X#ujE@J6xy$0>Yws%VSjb)WzdVE^Y<|G z7kn)9XWk!uQ^#6z%N0=d$#AB>e3WXA;m>7|+Cb;;jF&pH)IA|~zD=IL z)onLIvkK00JvHh1NoZ0VH*&LwpfZlm*M{D6(68o7ZtyKSU$Hk_;BtJE;Da*H2g%p> z(>_Sm{}-1MP3LQ6^JdV#)XL;bzc~(#yr&EmL+E@R85IBn`bjeLliyE5p!Zc-roKrP zM?h+-u)mCPzmwHxVSZAn!tCF-zHf|&XBC2jI?q=GQNL~ck_OV1Bba=xyJn2-jundW z)lB%y1etvJ^TvRAKh%_7CRp`TAxPQL`I@!k8uVF&nEGa{KMYUrp8~p{zKisYC!ej-csJoAOJ}^Jf9EYvA02dADd<|cwj;7-zX8)tc zVRJmo^8!q*{3iN*1w!9Or5GU;Sisb`I=MD3BY!=!zoeJ_9AuyMfa`cm=P!S(E4)^F zE$DAU=TEx92lZa`oqL^5=WlV^W>{?hNl^8Z*GJM{o_ijL#`z3nzJGj9HURQnIt8r$ z$mZM_6zQl0EgFp?|3|+6XnrmPhM$#Y>YwDj2=F?h$mDZmX9Ao)Fqp~bn_b4ZdQUE_ zstp!>KFQ}A#dJ8cLYrCtSq2*85ka|3J|pMk!)>SW%=5d``NlY;Fc;qc4Hof5`cH@b z*C2Gp1SX%UE!x<{;TVkZ=K0hl^bglof{MAV7@ws7+?!;EJHrdWWiXx3Eq{giX8STG zpEkeEaQeprcrlpH=l98-@ZjQB=KS?IDRb=HRsgS;)A_vPt$@N;hBEa}VuU&NQYwV_ za}^@KNdGz3R~?;@NZ=L~)6W+yrkmqeW`%HV5uMMG2}Wpaa*mij0&#vGj$1j;5?4Wa zc7$mEkmn0&JLVv7kK0^xJDpECYgf2Bx0cCgPj%$t>H27I5CGdWzYF3Dy1pO8^OfjJF(@je57a2r`828ufi-ixG3QHr3*T10 z@S`V_&q<#WU_p=)Gyi-%))@Cclm(CW)A>BEmJUVZG?;v5&NRl0^0LJEd`0MI<;Z-9 zPa7?!pX7Xwj-N3OeU$~L@9=y^5cT2S>}zmkhZ%Fe)cLG7e)c5+jAiM3-tJWeFMCd7 z`cu5v3_p&~2Iup3qWw+k=WdTC=pVj_IiCYp%&^vvZ1`OpCR$I{hd;Sa*f!an*&n8Q z+6>=s&W2CFPm9)*`Z+&bn9nrqVZU#pXpV19%z?APJfDM!`Y^>u9i@Le%+$};Ugr4E zq#PLC_Eq%xvV?x7RU4uHT$b4V2_&EIOxn0=9Ve!KZVI1+5-!|e@_Bo+E4-Tan3>OP z{NjTyPI}MuuQE;^@Nrf>GoQIG8;=q#dxKGbI-jZI0ze?_erBD&ulp1N7t;O+a(D9l z0*Lo#mYs@#vOPVR??*b^PXLcseVF}Y;jfHvuzm)tm`3L>XG}Vr+pNOmZ<&=bZVt*| z^4HfhAL3q&VCv&68)N+PPzLzK()s&)>>Bh^G-B3==T~XtNo_Gu?e|TjuYCx8lVU(p}7a#w*7ROI*%`XazcdpCi=Ky3L1}^KoNK%<#7RnecNP zoxfMtjnMOf8DjY;$)Cy$VLs~Q$mFkk$sE+Z;wq=3s8IZ0en9qb`mS+>>~rNzeT-E1 zMSGVwa`wq|eYBGDfRkF!1;%n+e2C|x!6xzOL5@76>(lx3m>K|EP2Y>@Bbm?K9vBMO z7k3CQCUpJ(#rczLi~wn_J9GX(a!?}3Ix8~snXS8w@a=TuV&@ZNKI2tmipPbeL3wvNf1j+HASlg_=}+ekGQ+d3rNNWQbpEo#I$^u8 z{$#yR*`#WQ7nP>Lk_B}B4#g-S_X0oW{J~i}Gwk$L*dwv8T%=#5{slcyN4;voxwZ9l zf2y2jhLdqR>=n@YJEmfcf)!J^LPtKoA^AJBjR%_IEb> zy27oTKJ;mn=i!bM+sv7XG^*VU8ypNoxf z-1MW6^N`Npz4_^oceg*Y|7GD3BRp@ z<=0^FxG~K7@Iw1gJo|Gv=w^MT>faQjD##DD5Ys=BKa*3YSih~LjOy1^9Nu08=tN_75KUg?DA=F6DpgSTIpVt1DlpxB4!uLFs{Uw$%A z0gVjV#`K?Kt<3O;b0mG{M zll(o(R!6@hLYVcRr*M8`^!g-FT}0M|)n0am#-7)h^MR6qH<>nDwE@fJhj6tyRD}-!Rlo z1lx>m%zUP_))3=uhaqASozLM;>99>!fmt8g{9}lVgAX(LG&!0Nv6BXh-Je48IdYT{ z{(Jr~I7ZR=tW+z3CYPaN{nr=41DoJ%H(=gxUNPNNct2nqjNVV@)9iaElpUMHtsUJpzaW19@*jI) zf8LTfFmR{ysVcmCee#yIOnhf?+s)*2?*UUhHzE$+9BdW+ z{v`-~e1FCm_4^ycMP<_Yd>hcp-8nx|;BnzUDash^S*^kHsL>?!;a*M6gW% zEijrw_pfu0m7zPIwO~WP0iw?*-+zuck`6{4GR*hSWUmX5;A~6h(@VVsRJW-y``c74hhoY2KtS_(K3{=y*VmiGh^bXz?L0=T zekApCZM6w5u#19>csifotD9h_y9G19xg=?dw|Pc^feoF{y4p_Is6LZfKeo1;;NW#p zFhP;$^9$i$^Y1C3x(&|E^9_Ar|GQd26zGoP`RqgZ*UJ^^DEN^-GrtMgXo>^xN5O-6 zbUwcp8lyRGhqzs-bUyc;H^nz(qrrZRJo+!6>4P=I{``MwwQ?2HIYH2LI=@3w=b{?n z`=@2=cz#HJ8#`Tv`T1Fa?izmoll)3Q@j>eCr5x*h>6%9#pqo<6%vV)BqS5zZAGtO^ z{_{zG_b&;6s#W)x=aZLPqLIRlO;PeV;P&GqVl^jEFCs4kz&@L=B|eL`NjQAe(yZZhh+nMG2dSc@iWAI zAMS^82|B+{HYJd{Q|uBcQrMPQ{es{JC^Vzr@raxZ0!UtuT7js?rx0Cr$bF&8+1{N{-z3mr`vW_=0`Tb%U07Fx6 zGX1erK{QHkYvgwO()m@K8VY4?6@tS3{Pz!ee!{Jc1iytZ1SX1I|6V*ldc7EhhAL_0}qI%hzJ^ zD`{ndZ!X*mffX}E`Mf(u!hkxaf4;XOKsX;& zEZ82>#g};gr0F88Z?DvG(cfQE_4k2cD5Rv`W#+%@^&{b9z!SmSCv^Xu=$?!w$Fy=T zt)Bn;{|^xJH;#)F;Z6T$ranLVS&ANH_J_${biU2Eq=U?X4uQV|&nJNR`wf394e<7} zyP15?tj>pxTcnxwuVNoVe5YYIG{y6L`xE(8wN4304DQ3shf@Nz@S%$vA+|T2?=q7r z7*VXsIj-RQ`$&DBQ*Dgbw*-N?9i8uOZ<=6ElCXbxb=P|FeE5ff3C=VP2Kj?@z76$% zL*QFWWL_S{~Me!pSSHWTc=Hdxq$LFYTLO&#TYTFcbu z7a=BityeI-Zuvsh=a}clD7-z0$+x8N`^D;@@QpZYo^M$~pU3ZS`t zIwnm0R+Kiu_kQgH+aISye3AO?qpgUhYfb0UZRva$k21kV0|UW2`Mzkq0#QHLDrzA0 z_s&fHKILzMi{}P{{S!Lhdu2_K-Je}t*=4%_E_FA-_R|6(O@YpLNni^n;i$vZZ?l$p zXqR?0=c>i?N&4>_8g5XecAV+IZF~A4lfP%Uof-UkQoqj+_JnIXry$jD+->J50VEY;Pcg zr?N0ahR%2FexW~~Si{W6^5&MJFeC>y&HY9CPv&Foap^ES^POPrN;==x%M5UE_BJuT ziwS?eS-AkD2LBT1$MNe)e;&Tc0L$Ip2D|&y`JQZF0&}*=F#UP9v=$z+b2;2Gr1RZo zUj+y4`ZM*r*FIx>L3Ib*X_zkJgY@TWhHs!`nz#u(p?-vRS%=zPB%uYm@BS;EEF()%lB zNSfgB#XCSwljr*jQD1A0H9?KPc5pu*()so;F~NK9`@tnd=X>Vj7H;bHp@J1DbboF) zXg>1Ph~Vby^L&zgFX-ncDnKWW=1 zAOp1uZdV1JZ_m&Gh;}<8#y6R7ue1$?wRPv2`fL&!3BOyeGx`0hb^|p^OM%_9uK9Fv zeNOjIgf&@}O#kgXtQ0jlNke)Oo!`vpbO=2Dn(4n~dmG>+q5u6?^8TxDNPdU4=fk}j zt%8GIbbh~a26*T1jqti@w@6<}|1Gas0>{sEW8S}2TB?cv*}4GgZ+_v|6Z+hyR|SP* zdT~k<>H1vuQ4?aaXx%6QXFQ*-&;H5AIC#G&xV799eLktrbL2Eo znC5)u`BPwyF_u5-3AL%8Me9j^zm7LS$8EN7?{3riZGG0lU0JFouzE}9Gh_FBlpVd7 z8?cGzi{#VC$_@5xJ`rhHTU!n8q z;1U3d&Kb=7tJ5qLRHO2k`r5oJ5<-_;W}Ywgdww06HT>ahkJ9;+Kb{C1AKhi@t6R-Y zbo#Oc+}KX%bN%ylaP_ER`sZU8^l|buH~4ou)A$_RAUuCkelK9XZ>=tEfa^2eU{oHR z&o!${phn`iphpGIH+eq%WVa?>&@>DFnM>z0$*~IF2KVIR9O!)h$y`wlS1DH&_Qwd16SkEevbHce7Q zLC;K?d``4C#_r$O!tM~BPg%l07iw#uTgrCK`I>8<#`x&4bx=Q*=d+p6*RuvDs9I$` z_w+iQ&#muTxI;FBn0yMh&qou7264kzbnzwrKKv4)e#!<$Fwcjt9QQ$&mmcA6HFT{P zf4{efq9;flk7d@s8VeFo)yxuZU@4u?4RHZrGUNnPKcD%A!k~^!X8!E5AreyG7BbI| zq!Sb2YyEX*{`}4NCfXv^&Yc=V=Wq4*bie~E16Koqn=kL9)270DEg~^|ctugj5 zbpoFrbpC=}P0+&O&fK_qI)9hGw{XAf`!e}E`glIl3kl#R9p?EV_3=PAH<&baFEf9t zEb~DI4`R5jE&O^?9}8az=iB5CG4tiriZHp47kQ@tQb(6avc&pLu`E ziT7WOcNO*zzyBk6GP8>x@%#vB3-xmdf@@iZBKHKAk z(?Bk595Wv-J8y)KeOw4BM*oO@|D^u;E;m8p!uKB(9@F{zo%e;Cx&R=8ildOvaRmIQQ2u7FuT zu39hbFK&z$EOMmt=PNwFS>Kc-h&Au}_u~Ce*X$!<&WsFZ|2~8#LiMadfxTAO{uMue zowoHRO2}^HmJX!zcjSFKeDo?2V4tq_;`*1}V{>?Yk z$6mtTg;Re5Mf{NZ=e@TC3T$69_0REx25vDj2eV0Z{?Y=fz_0DAfaO0`KWktcb8{HC ziq7B7;5SgaLz>Co&lN`a)7x2){VPbce@Xv&=HqX8*t0*EIGwJ4a`TO_a?LF0Gm_`8 zobaFdLjJUJw3+#>@m3?e=PcYXFvP%4!`Hh>WFZ!@s zc>jbooxiW?o{*&*!pv{J9Zx{N;WT%>jqX3Ab_KxZu@TJr@Q*_%d~A$m)`waPBcbnu z<4pb*7be0%k27Na)1R21Q66{`Wx3XJlgj#C<){V4 zCc?k}{eSCo2>)4WUI2N=Z!z_6?JGTO@^&Ja7SZ{uPAP%JGfxG9wLHJ1{tY~%f!#~= zVO`xnRQ)USt%92yJ}~vq`Hqm^*ZR<8%=70@=-)i&H=sR1g89D3T4^J^*lj8t&ZhI% z5cV5BX(%$!Po7B{VW*W-A^2g2h#!)_()Ef+Ws@3rV+lQ*D82eg^!X%z{q~t4bJOV@*G%UxOQn^YaY|Cmf5QLmg@5@W0Nv;z&v3Ffk|@arXr`L!@dPk@)ZnD;B7 z!US~tRvI_%FP*~X>JB&Hsrnp|%n`3y0=|9g3>p%6f1i`^O^!|mq4q-m3ogo;! zzH9%A>tDzD8_4BcC1>J8=g(1?zZl-nXY%L2PY)kZnE?O(S=0C{G$;U5scX!9)V)v- zyG@w@y-mmv`un`Vy1~@u_&fgqg6XfS*&GetC zJ6pI}zTYRb?c)6>$)DRj2V{&KIVBaI9{_Rwb_NUmr`Jr0R_$iyFHa&vVesmG%=sAIl$q78hzm=P$i`20Zi0Wcts_ReIP((TK@kigy8=H9RkHP2u?`{pU+p zJ-kZZ2+C&D`TKFM1RO4xGWGB52o2oJeJJeu^@*x~QIS>9+6tJuh zv;Ld(%@8MKnS%ZmI)C#VG|-vjLz((_xy}&BM45tJ!$%RnPYM5N@xTNfiL&5?{Q<@Q zeZP|PYjuXL+|H99CUl)oko;L`EI^~C&E^_ycz#I!Ts7SwzJ57#e)RT@9cat@t(?tA zem%)w++9zw9lwF;KUZcXAUn?(F0_%(-{YVFc-YIAS^wSM9tz8E>|yGkU`Hfu4d2hy zzbUms{*q#u{7HPhjuxN1!u@#G_bSbQ#>;0wV?Z*KzXoGHT;wr^$=}c61rR$mn|b~) zz(Nl{^cn*eW9a2WIkg{)&735#IgWE@1V~@6$8HcNdO>($;j*{wMiU z&r?JZFM4u=_R{^QrLQ60m^==w$I|(G>8gR=4OU_H@1!3!#7#HH3GbMq^Y^gS1mP$8 z+-?ave_Efu2(!r-6T0#jlD{0;1t_z53YTKc^F#7iKH3eAzMIG7Z_TS6$mY`;Zq+w_ zy+0>@{xEx#Cp`MRf|-9dK1@LI<081uZv8~xA7uaCp7Q~4sJ}b2|IT1@DC92lW7dD! z$0OlWNf7h=0fhROpdKk!|B?46sJq=jCRYl%exvC6w|H3w^nQ>as6ET;7ug@X=HYn! zH+!fUe;Gvmw{=1RxZX|^ELq2|C-qP3{dj!-)=;Q;w@aj7r2qWdTmpw23z+=9zod@O zHS~j(Q|SCP?Wux(m#zy~{d2u8tK(qWw?$&n;Kqz?7gzO#O5HZh)`G4~H3d z_lVY$`O7o&KOheu1g!Jm}sR(!W1b|L$2BV!4{((ER;_X#M}Ef9)nn$!-+)Or6f(dM8W#)I}HW2z~N@ z-`}c4f9%llE!?H0)e{B*-Jj;_FF-L%1WbL*oaF{X&P-?KqZ#japl4Cbn0!7C^@N() z4orXgu}32M=@iOk=+XHcnjHW|E1a40qrpL;@Ir4hQy)EVM#7lI{><}x=ZlF@FB!(n zM+G**{+q{HT&^OW&#%fEP$U(_)W=ZY@p#joAxu7(7#Bdz=_E0IB>5bFXgqd`8v@Ug z>3rHtT!$3}nSx(GdA`YfCc{G=AJ`)gbIU(c{i#Ay6?~jm#MDRKUFvxLL3y~GNayp$ ztvBFqa+k^Hp%Me^=%xmvj?(#5nfM118eTH_th;Q0O;)Nw=Qf_tV#1$#9Z*DLZGH$? z`OK|f2KZ8(8Y~H;^Xa=!16BJfF!Ry!QHFS8i5m2L!t+^9_|q*fOwb`|EiSqTozHk> zOKg927^s`k`9!Zp_2b`Re(0df zT<&I{-o^iYKal#Vn&SzMelwW;t?3sN&>7+TX)OO*cUah86Tg7zUt{7!;qPA;X8)UE zQY7fPcreco8x(|hb3mZLYkAlH7SC@ag!#>Ow-oN`LOP#rni&AQ_A&X?nl&Dm2KHm} zc~e+F+EpKBp5K4|e{`LBSWVsg#*=v{p?Oa8Tu4;s?6sD8o>DR-QyDUrF`7s+L>bG; z91#*B>g>Ih%n6k_nKNX_TvWgPz20+voqb*F@y~m`e{4tW&$;jCexCKLP*?JBcV{#u zR>|i`QGRnn(9a344@lMCHvRck&wuvoVM?ZWwm|VS>3p^*FGXM5WJ{s*CCpe;QZu>* z+BJ>Nr~T=-==Loh^snkGx{)+H9aKC`$tM!c&paO1fX>I4fqY75bR$Gh2dy`w^O;eo zfqVX_mO}nD>ufi&a=Z>Y-<{59N~{^aF}x*HS4^Kzy>hb~`4*~!dXJ{_x#4F|oL(jL zKReU;w81q@*&P`nYv>3`%G@4CHU>$pln$BLK{AqJ;cr@|0kZzm(2t=+M$- zAb+b%F5|aHcQYSm(D{@4W}s%4ancrho8Eub{^5^AQ!?^y9it}vQr4e(|N9@sulw>G z)b~ds*gy2jGbI6fe;I5Ys?axt^py__|DD=cfNp!Gg8p@~ktvBVtYh-L=={}3mI~hX zi1emSQ~jsfzpu0~C52XX%uY)>f75zZA(I#9r1HY1=T-an)po*s{QC}QVplqU1xp%G zSfA_C*y;5C;Z>Jz#Qt*!6#n+G!as`j@mGchcGG<>h5T!uux@0Gl?K}X;+o=lv45Sh z%na`!|D@1<=&Yn}WSWl#@~Z!!cwVfJwm*7e*BmV{znM3vh8fZ}2juTfg&#gK+MFq$ zpyV%Fl%Ga&AxQGk3FNQ;h)Dc^moQf(aK8Ip(Pg~mUNWeER|aRGWmXa3 z{963l9Mo`nEvRobwWeg7rQlUwLpEclzioi{O66c8hFa`Qt7;KdVSc-v>UOkYJpltDEaz>O;o<0o~<&& z;p(43zI>;3BWDa-BF9`hUlTs`#IX@=z4FdC-tBo>*b_Ia>Xh*#wJZ0NDCUy&5 z-+tf>bidmya6Ya38W*y%QaHmV{QB?jf1fCy88A5q+0-uw^O;tAUC6N(-x!T2F$#Xf z{&KBGA^PnQ59-_E1QXK9|1py>g3h0BVktV2nhfe&ScwVglKYrhbdk>AfSW=-`eiTZ zFT1C^lXQ~2 zf8Lgb$o+K$n7>3#F(CtOZ!%FG=={0ADn$n_tpn%NA{LpD9+I0(-cUM!mr)f8z}uxc z7wP)9Zkju3_V+c@CWg-6u%rgGdDtP)Uow&IB+}#!Q|Lvf6W?{uyPv6RXK@ z7>{pP75t0!uU(26e%1W86sqqubKQx_%r{KfmG_G0#r#QHd*W15Ert4nKX=tIZEht= zn)b_z^OdiL{&-+XGiJsTy8g8r5Q5GnwU<6?tIq%T{UzQHV0bqY_qk%g=$@=XXK=ehkh*V^Ra8-^Vu9hiz00 z%C#;oq|)FXqaLc{4~g=X!5<3H2s8(r4>dG5Azcs2nbU_pQ2poj)KZi?JqpynalK7Q zYJr@wZA0hp@WZ!Af5Zk*|N42llLN2Hnb?VR{`Q}5KyS{aNDUX$>$};u?j-6?Ib;4f zUGe^(68X-kKPI`RC)4EWY2umzlS${Qvb+Tjl+axtN4*wdo4xGrA2j)OxcE$mb5Bf4H`% zH(38MtTRz_y#(^PbW;xMcWEG~k0&oX6WgAbm~>}4pT{)|(T^A7!1{364P$a(>`5lb zl+Nd{l2WuVb`Dq{p4T)Xar;j)+e=*)e2DAAh=#Xl>zrt?KXJ5Lm|xGm%-CAc`CK5> zhu6Y3f&R3|dpB}A=Q88Fo6cv?N)6nGO9S)IHHPja{^Mn)vsB6FS5bX<@RAwk_h(DJ z-_!Y2Gj%7yUoJDlzPwZX{JhAY+FE$xqCGc3e>(2pS7zI^C18D65$TU_jCm?8Kc(bT zoPSyrg`j1>t0mC=c|+eu;xoh5nW2GnKC6Ah(WH`E33Pv6ppbvIT5raLXwvz#J`;n| zcDDfiX|Ih5C~toU(0^)R7VF0mX5ODN1%EtJZ z>|<=#(fMS4yhT+Oq0-fBnx0q9N0+C&ky*QQm{`*UwI= zZiL&M!werr=X2Lf4XoBF3FPy~D>pLuNe)x<_ln~4#e9Yd`nh)eL6FZ5TJB_Wo3l*t z13I5c&YrkoV4f7}@4u}2!hA2CEYb0!>!L2 zn_=#?HQ<%+m+F4@(&GuJWRV)!->+!S;^zb0nL$}}e%0%f(4-!1zfu zbbhbsSE1V7{!-|C@W)ARM0evMCjJzi-+?z8(7$tYLI3N!+>IPfKg4J_D*4S2`QHl_ z8u<2vHPVFD^!(>UvKtv8Kg2l6==^@-&9GUA?NaD|q3@^NNa&M8OqIWq-&~QtE*JDQ z<;gKA)L%TZw1$z?4+Q%gMhpCL-sm&ZH~Z-Png`BAy=GsM_@>h9&&O?}aEC!<(!X=) z{0{jVjy^oUDdAM|QFRr6`L4GNZ)vLz`rjQwf6=(`f#j=H`T64gHV-EkWB+ds%*U}x ze#QCEi>w6Hr{^09bpOeL0y*yf-GoV+LgzR5auT|6^qU0QPx(YI4Gk|)2lJsT_nk;g z#b%~cIGx}4gbY+Mu!Ho=v8MV{wLdwc-id6l-wg6=d^88S1nGkPlS#(TWUk&8=GqZD zzY81-(bKT5V166pZcLKYV;M^aI=?g7QnZB;>UThYt%n(tZ3eMSvo9_R{Sy1*>5?k+ zYB`b~%4qujP}N`F&W$wgOJ+XA(fQTm8_?nQzM%eIwsa$pWXa5^2Zt1&FXs2bI}LnA z5(?_?uMjtqR-Vk{h0ys8%Q3_EKChA9D5Lx1fh*m}+PBHfvvzcTuMYFXv$yV&YPi$u zS2p!4(`vT6Wb#G2{@xVychi+U()0~5p)< zes2!QZ|D@6;P2l`&->B!*R?7J9ZBXS(Eiw+4#hZTpdK^ak{)P0F za?ItnX9jkp^V{r464H@AkU;k{ytPk5p;xLT(0)nNbxvf$f=H&9C!OESjTz|cmOm1R z-|Edy^_&&UfnvA!y;6onZajeM}V2s5mTLvW3of)RS;DzSTYn zbU$^{1Q}j3`IZ#Qhqd3wpvT2WLB6Byi?N1ID~8z7`HpBvK=QyG34gRn-&OmkXPo7@ zsNZktqcf$7`c+&X_Z9M~$Q7&vI)CZrl!j~;6oY)rr#X?|W2P{p4e5LbOvymgbe~F~ z{juYO=fi~O|MyS&U;QBF`~2P<)L*Y!0`32>+3!Sr4ozXc4^Z;$Cd!wmcP&K6H5(<+ z{GMTf5vklUgfU-9=R4p>DOwuW4m|&5`p$@Kxi*BcUPkA8v_};xFw_I*8@iuzCH%n| zOroul?~x+D?GhT0EWifLuX?8l^Z#)(m>wgQeD4$a>-2IBe0N%Jkni#*uH@=d;qwcN z6nu*LE~_!a=Q@s(MzmEkqG+l+a8P2 z^55$u(0)nXc{2Q)KPmMMr0e(eQ!!}zi!BmpKTqcETUdJQwG_S7SN#2o?@y8zC7^BZ zQY6s*pXZ%LJK+_1ob=2B@I>V%mVq2Gj<|}`XR>nYLw#pLtH<% z3Clo!F8LB@zm}2kyo>NW#P_G<9CYWxbqTb8@@s$-LF*CY-igk)v~MBGwR|jr=I8&e zH6k}yXC}d%&i8TMGPLt^wFH{aeRjZze5-I~tnBD~&lp&RzPmO9{rAd+t|YFZ5A*m} ztb(sQBECC5Z9oGiXoC8EYpN?T`P_&3Xh`S#T!{wm9cl{B2l@)<4}7iqGOqLKd>g+u z!&moo1NHmH4OcQ~YF{QsSIPG&QT@Ct*b}3dL#3_~x_BpQgRr38%q~8rs zzcO2WD}A8;lC6_JUJ*M$dSwn>zcmhppvbF!pg&JvABA(ihDu8_>H1yW5RRhlr-A-_ z#yS}evrLjYE~fMCdoTu>g)9K;>o2vpFwtbC*=kDt7V~YGn}8yxMS=D8o6LNy`Sqmq zpD~?p$E+kYO*>u!-T!MQ%>UXROp-wNw{$z_NP>HsF+UuYe4C5%v7k#CD07)il6{+A zU+Z6XB!l{xsqh^w^5-Vob5QdIM^yMmqWeb+Y8^@Y#b(U-El~=8E!J-h{X(?vb&dqu zUvkCYh%{@f#q@npMfK;|k4w?xd6y;7`L%g7jL0z^EoR^gX9b_)`ueP66?*4?UjpT0 zo(`_0)9kK{7O&)6tlz^+8jxC_Y6+BYYj<-c6Bl-6#(g}f_IOJ-?XI^PB(YnX}evwfiRr3<9~*eKgn+BCl*&cBNiLQq7G1DJoO zoruE6qJ5;DSUTUEj)kLsQ+t5<_okCF?AaznI%g-H?^l;%&=p@s0`2!Q?_G?q58EjX za8dFt&d*-GNkC`D4v|3jFI^jvk3W>Jmp(XikLu55r;(Oc zqXQYy>Yp_4?<&RbFXp>3E(1A7E|Wm>{S_vTq|>N>(kA^D^PP1z2bp`vNud3h2OJ#9 zn`!@~?Z!tc_%s*!^E!h<6#8H@$ag^(BeLq)Yw7a&biVzK%8>dL8K~cNo<`(tLEb*As{7K-{?tl!%TY8a1J@jlReR=KM`J~8R51k&$qmqXB| zh0P@3{iY>R*soGkI{Xfu@6pGF-Q0)UfP8<6m0_1s7ir>LI^R{o`M0yYmc+|VSs#e= z@oP(qadhkqX|suRzWZHIK)c@=fd2eS$9$~UX|(k8Y&zd5CBpnmKI8hx{~hTW{kf7JL4G=y*Tf%bp;3eSfM&qMldn5CC`{!g|w$0?>^664Nv{(IkZ zA=TH{NK1u#Cjay2V*aZ`J#nis8zfMDzBa>^oC%GS?wv~K|MJ{#jEhaKchmig;`!_O z2L8BUnx&-ae4p6A4>X>M&W>>Nf$l%AjoIfA1GDXz<8>KG6N;14@f=z&M$tb`PEZ`@;N6Yr9cCQ2%W6`aJwBJW+DL z^sa(malZa{TM{yMoaD3PKr==Cgplg}s?K?N_*P1yq;D5G|8afNkpG8yD*TK0&kQej zAWsXMNqaq@`}>yy|L+Tiz_I*^>}%~bebAgbTTJ;*`zlM;L&{SR<adxl{e|7H>musDD25RS0V6VB-bNmzD=bVZF+p z-c9{A@%i4Qcj4&vWLGb!zcxVNf6lxhZ;1br!!ao3WN$BM{>8np7@zXr>U}er&VT5m z1Y{H1&kNH3{D3^X+-|LRos7+20((EQq4b3<}C|EafGGdka;`%BU34LiO1cWIhmQJp`v3^pVsW)KU?p5gZrgSeTpW7;&U#V_a>m7SNM)CddP?WzTk4E&8JLi?Mht9X#duI~gsn#2v zIiPrci>QA8(d~59S#O5oTd+(S+=R38RD|u5>=Y3K`$@evpzu#e0!$eLxo(G*Tp1Q~% zOIsSsq5ChEZwf&-*IDO7^Qn_kqHywsp7N=ul>T1KcYIPfdT`$*-=iH}-&5|&a9__L z`LnZheg9P$gKQFd=QrhZ;`hC|c&%>GL z3m-m=2KnrN9IHGF&U%N(2Xxa`A|ORzTAPh%D>A;4OjB5CCcA_?94#s8VmCw zzSk~tAV}4nGeCVKy{~x(;s*-Q9 zf48=7M5}_&jK|H2i(ku_8D=^F6GaIZkc= zCf~6Koo@%he+<#Am5=@YTJilL_V0HE{q~SHmqYsf=aUPO8rR9Uls8x8b7H=|h5CJO zoKrrOzyG!K$J%#OUixfVC|aqnY+u`Oy4o zScVM0{8uS2*-Ynqu%O=tlP}~$`n`2}F-|P+%w8W#=X;^x-whvL&WHT_lI)AP|I(K1 z`WJVo{yjvf-<^`~4*Bz8GaX2LdKg>hLFYTsyAT;Bx0gfv$r~>ikT*9cuo1!; z-v8=LaeeOmML2&Mt0#x{lizu5Kup_CWdFI)`Ibjjp%GEma%jI!&=hBq^JXb)I8({D zSie7wX+%TU^_073(e=A$kTYrbdMV3yr}ORGLlZ}h9wJY;O4n~$hBHYVvW!hYbiQv| znByfsrpq_j(D_ch>P(84E@OMnQu4h|l+TSy^Tg$SR?8v%p8iJIKcTgPjVht@T{Pz# zGv?Hqe5gK`e(}RM27Qz_?FSLp=b1wOKJ0vbK9s*VyAy>kx9Gq^`MXE+#b~inD>=k> zuUj%aHQkZbI!)($SGsUMx>`dH@$I{%7@ui9h3z+w&iCqz321tet{j?AKegc^Zr*b! z8=On$d(X2Z^yH+O9OC=jv^*Tybr@?`xo`#z1I?18=SI=km#OKEa)@C-H z|KjuvB-ztT4)LE}VNYb=FR1VzB&yH*@5(`br~Anv|K6jA1DQ1XB3u1_rGj6ve~P&uam$TdYDESxbdtqqPKY@l!s_P_7Hhob)5FE?{MePWgz()W_3&cyJIoK0&+=RYFH6Mr+fF24~* z_wTyLT*%ZO92@2zgiaG`q$$bbBu7}Pk6kwfRp77V?J&juv0o|^4> zrT(a%FYA9T0j1jykwf!wOM6_zZ3iZ>GsY?T-zPdBx}rJ>J#g@sCw`;na|X_N*uOD> zU6!fjpBLrx|LecE{}m#K{C#+uJt;J(WAC@8^Z&p8d(Nt5a;X1)rO=-A8(jzTe{NRb2nmA+IU3q9OUH?aRb|$O4HL}{N1yueod79%mX|?>H7hV4~ zhB}i&@r~^L>#r2gi}k;Jy(f+w)tZI+a{<9F`AJp5m$dZLg638{{Pp345YU_ z71aNP74{@iYQ#19f3g1WJCuV`mZi&~`S^*a?8(#lMjUZa@~Pk_dQ-K_+?>iC$@^ESg?(|AJ|M!npp}RfGMZ2{XVp0o zw=h$#F`CZ*V5vENaji3Z3)A_((bk#tk1^%$hb#HtCG!7zF`js%o*fI#-}Dvo!?w%K zxVxTo{ue&}%9uZBE{F8rl=$P18FN7XXS>Zr>fIvcUMrOOmv}yYN{w*-#b6`IziZFM zsIvE3IW!+H%ah?*J2Khy!*u^&Ssa6g86|@H|Kalm+#~TO%iL7@Bk}xf`Z?i#+rk~7 z|NnU60`4&2CTn=5M8Tg}|Bng#tIOu>m4D2l>wmT|A0MoJ9Q5~NM+^EI*qfWMpU!uu z{TV1$mJ9NIWsE(s3F-~e7~6PL^AVy zxbIm?zMqTuUhmzAOwYAv-yEj%9TqC^UFgH5u$v5#rGc>N7pd7ER5vP z{SNt2{`lwI^=#ArYH|G@_P_IMpSFSe?b$IJvvG&m2iA^Ba9V3Hc1o1NHk}KpI+NdqaLL~eD6Xoxx_GBP_|3i@9 zdG&T=nNffWzavHUc^R97IFEO7_Y~#li~YH^vpp#q7r-5yOXt^H*za-^-28vzFdeQo!?&Dst_*FW{b<|{ATuc zBJ2B1;$oBN{06saMAoI2tXd+S-*&D}NK6|Vtp7XRPJNy%!U-hX@ zWYW?}+=j=O6#hWWuMaWD_g@WTWdrH@Y`flxd_6XayL0cQ;(4(?m*sonCmNybrzqw7 zE9Upny{}B~kKI81)mr0^ADHZ8<1*>~JE6l&6OS=EwEu1gc zu0IRrZ~dRh@TAV~**Dkd`l}(FFQ3}-k{p_kn-_Qicg$_e6--n9{QE@y`}DR1WH#@X z9NOQT>V5%V+R>IDYb{x@04k9huNP^KNp-MfNok-b8p z?_z!PC`Geon}Gbj*`!a(PfX=PE;=aQUva+XATcimA>yew=T3*~Dom(?)NHGM(-B`N-R z#Dgq$aUPxDt!F||SZ%%>%FmtKN8^?icR>B^StjgHJ9!nXpTl!xI3}$T^v}aD#Gpf| zrJ(+98*xE6zoy6S8?WS7?4OIC3jOaF&*jkhlt1;k`1NyL?sz*ozi);8F7K{<0`>Rz zv^4Z~k{S!mw^T;h5#!kjobEh2zsBn`(1pcqS%}}V?RI2fR07Da*@Yambw(E!(%&VQ z?8vhN30z$H3aWoLb}B@RT+CRgKlZ4PK3O$+8D~0_&hJQ#GIaBs6AR_zhI94F)dRxw zyXgEntg1qti+$LlTTR~|s`c^jJV#QfwUImTN$1yHs}Xs$9?3%e?>09aiI4F{Zs}z@ zzdr_Q;y-#bS^f=Oe;t21lG)5g4h7Tsb@VXD#>Zko|NKPI|AF&`=cg(8-6E=w&8~Xl zz*pPZjvJNluULQgzN%qX{Rxyq_xE;K>5q5qzXIy7(wS2$F!{m`JK~d zF&g*mh1|klSwADBI-mMp;CE!078iDmuD{=f{c6)CU%>jeJ}&{St`_R2g-yS|>U_%X z%emNolmjOzxvkJYaeW(oCkfThY{f$Tt!6_1YD1M4+caM;*4KHH?Fj0zo7*~w&S%7S zVSie%5exON;(hH%4~N|#pULSt=+GJ)7CJu`lW0fMC-3GqZKm_t=5YbamUU;_=QsHS zRecTUqED8)Y~;STq4Rm`PboS+y$=iJ*HwD@w5WIg$#) zJzQodI-l=$HKGx_=dk~tx8(n;&k*YHzpzj7t8;=QNjBZX1#O`7nI`z-tKC<#6+h^F zn(lKXce?N4+O=2mc}-N`#s`?=`rBLCifMFz+~I*ESroj7%l`gCq3>cozuxe~E$19% z&6DYTo=dM`#-3X&ht7vN3H7au*%P*DKdHFBov<+kty=gI>`x778I89)sdG?$dsTfg zdSy`y^6C9S*x#_pjLWa2^Lge_4647^oQ3u`SiZ=`L+ib{cunQcFV@#N_Y;tsT?ZD@ zSC{x)T)N+zlWeB*Yc1r{EwMJpZ_SD{WNcy1rm5V|q&h#kx|tnmR(^~-SGb(&j{{;e zQ1fw)puT2W+mWK$V=DY2QGL5j*k9`T*pr3!ms$?8BM(e6x$Z7Xe$_| zh4Sb0hk9gFa4Hvn?xjMX#q%c{o0p-)ZT_IX7X8#Cj%!l6U_&~;dHbtS@Ax_Fv#J*V z&!4KkwjJn54%(mOjBZCM-hXjERnn&st-l(>t~yWW_ib-S(#Pl|_q(r>-vuIn9POZq zFC=bZ^-AdceiHaU5PFh}`^76hU(D|Oa9RTawT>}4Et50%+vg!P;5avfc&Rzul z@%Vi;%*eVmAiqAdh4WvApTK;o=wJxi_p1Ta*F~?RaPP7XoYz-neJh?1o%cK(NiVlz zq4|=P_hq=}ekU&W4xL~3tue@XuO4|K)N9mCF_UiTS-NDHQH5^JAg;@4qQ}B(LHy zS3il)@1urN26QoM!#4j$l0q-*oJ z@+>;PgU6fWJyECF6SL|1tK;iP#%#;yj*U|CyH4bf*Pr&pGWQ#7L!457#Qr$@ZVls! zlR$s$BlzPR^P6!^`}@WEYj-~c2^%_CX#Ue;h%g@#V8B`JQSytBYQ7xsC>&XI=>qcm zvRHaQmHdkHsi2Ys^d`|7)ZYhYx%gxTq{41T` z#gByh6=Nb@dee_Iwgkj1ve+%i2nzhQojs98`7 zt9OmgFZ;-WOhCn4*YA53-ydTAZ8Js_Oa2~X=lrAVZ>GS%RZKBgwuH{_fqv%r&w8Hi zFp19ZL1RafyQP@x(~-{a%wkWxzvL;~XAhm<0mA)L)4I##(EY-rg#G>pblP)JK6R_j zOmwV3hlTpPg)4>m&No(^%Kj7)zu0~;+U{-2zFyo^f2!8EYDb0sZtuYyK1t`d$Ep~# z!N!(__AC5(bRPd0J(qjzOXt^SZvtw5*qw#uJ73kD$7KuWazTHJsrBy#;eM*Ejou)? zI>P?&NgoD-{94VjC2EEbxd%U%DSm%3zZ}j|%R`H!uf8&)=4xs)vUn;}-7X!HIYv}wgi;qD)nI52jZj*T) zZ`>Zm&F)F(ci{H~Wc8b2FQ0Gv{!q=Y;$EG{cCVv2pD%QNubfCiqjLv?{<(2*8oKae zJeV(E=weG;quz1uk#v41&(AKU#`9x5BleS-*m}6jeA_{>=%3dQcOYDSHD|qq&aY%iBa*S%V1BiBngjV}_=)SENauH)mnQ!E zp$P2nCJWymCq{qbnt$dL{PCjv>h>IStmjk7eu|^>>y+g{dae1y8EvBTt6$)W)6X`7 z`kU$Wjfwh~Er-rm%oFyX474@np!+*+&j~>TbR1Y{zPdddg~?BE?)XQge-`uWQ!n&) zHG8nod{y9c8NRkNn6v#z=l9X-7*sY{3i2Da={)}Yb}eUPMdx>MdIH)xW-wU)nl#VF zGbQm{kiODCBhh?y>eVDi)dG$wKGUI*)XViwy_xy!bXtu#IP@e<; z*^?_zYq=HbbiNA`8&S-?Ja$_RU7x46b|Am2Yq>=}biRl5*Tk+CcR_z0W8pw1cB$i< zt)%lke1tj9Kll;U=egK{3?OyfKXoPF(W3hJr!c?qux)D&^4IU%3jL!YayfK9^6)r+ z>||;W>a%`%2ujoH$wKoRf!@)0&&)xbS-}6#Uy1Zt=VCajb3>p$o8FM&QGJ$hpPtb9 zUb`sY6+O;c?@@`uI&=F3#_g#7Vx;`Ti&Lm&{ww zV4?HRHv-d8xzkcGpAOn*Lq@^$mpiZ6tpCta*KN0J* zc}xxpxwHxFFPVR}AwLY7^H~9Oe&rntQ7g9;kl#K#b;2sUgrO4Uu zFxX#8I;Km!)2q3=MRp2(6X#pkcUGaL&(E@-Yg_Qj{*Y=ujZ5vxtiYCh-tAS2=f(cI zaZMw-a_kz&uhuQ$e9E|%{O@*je&ypdapTrXR;LR+-zw|iK=y5D$+r)s^V=iA9Oqj9 zW9yG7^%)^e75@^^PS|ge(2|!FRw{pf5x)laJ#pX3T0;I$ua7queq-F$UY8p<`vFG9Bbsx61__ zcOZqEHcmOe5zVOHkN0V_kWXhW1nc9wj%g@&SuCi((hwVx(X}1_cL$x{cf&JK#Q6;@ zbiS!5+=je#ZU^#foGbY27CS)wEjejJv;y1li<>F=eU9{1-mf0D1<3aCesF%{_e@=K z>wGQu=n|dZX7@|c{zqA$zt&x#OZF7ja?{q+`L)|yh5Y*S>@W2u{Z!?*VUsNY!O*|=}nmuSp=hyzJJz<(@ z@OD0Qe&=j8$7E~&C|J653N7a`UC!K2)2n0Bp7 z!TGBb1O0Ky1Rqd;i${f^)zb!p{`!bTG@j8jhR)$ua0f-c+{f{E~S7`PR5xykzixZp%$NzvBxMQ2&k#S!n;r*pwvH>uMxe|C)|T zL%-7#Kz&_cBIu)ECw_Z3I-lXf`NNWhTUltox3;?tX*IJG$fs9!4tlG%2jnwmxD6?a z>BOf*ELG^^0#X0>YE1#M*m4Zy^QW~g*&5iK?;A|#bF^@ORtdQP>g)Xxy2Nv}kj;hC z`IHIy^ZBG3puV0RXHU`{wE0O6bUu?wBf31clFfS9#JB4FM%$_Oq@3r5kg`=m; zR2Dj4xTQrJ?m9GylUj9A=zBENS>^kGkZ}Lqh>H23zMiNl#$%FMPWqd^UtsKs1oY=t zB&e@5g!99HTF0}`Y@6~e)%||CrfJA;dJ?Fg3mUD3`%w*e(@si0c~O6;=%R4HY*!f@ z*g(&hdl=Xde8xb9PazLc`T0k#&q2XjN5Fh)e@`2-^0om_rYZRp>t{{tLS()?2h68} z>vTxuwRZeSS2~{omrK#bpM{`)4(uw_ubmk!nIYuMN6$Cs+`H2CGg3nuM<%wI=*>f|F(e-ottFO#~Ht#_`?+W?y!Jv^` z&K)|Rd*214`k=||y;|k@H}UzuUPAr4(qI`^J)h3!z$M`*W>qN2XNYC_dm~Z4gZw)XQ+wtsSmq_ z`(>YQ1m~;9p0Fmkzd678)Ne(7VUBfF_!?0sLraX~IEDJy3`{|A)A6WZL@$)Yb)wedap4hL} zoztpP@-3dlAxPF@4miIt7Dr=W*H|uf6`k*+ z@!@E-$1*UVN_i&3C0={EnHqGy`=5wG{Jzy})A=GX-+K19v0b0LTw51Ig?_7v&KJ3y z66T)^Hh}(EeLRa@Juh+A!Q~3R#C&UQPeR2-TS30n)zi?Wz`bDq*KoTvsqAdWd#d-V2Ujdn@F&*i ze`AFGJ$P z%=ZsqeJej|M}oRL@}2wB`91H}i0-a##zFJX3(nY)-V#Utj1`^V(L*%xjQLuiKCifE zM=nluZVhgz!*H!Q^|K)RHe#e^& z`Ff@!e{Wu+g8yBj{T<0yzA;18nz3t#DDx{dq#`eBJCpr!x!w%U<1d}>cPYa81@k3f z{ybz%G(I(X9rtG!o$ns^!qGb2Sa81MsW4xuec~|4_pyW+6n``U_SfabcnkX&)bINn z63`&0WKh5F$&%1DHWln2eQ#qzM!dA)4?p>!;2(+h^T>qxtoxmhfc0_QAZrqI#Ff8i zN$1&kanN#{GHLm@IASi*)G z()sQ_L5K9aV9KALOy@iCNGW>t={e}XYZmE{=zFI8+O0~y5i(SH0d-eap*w27*oO8^ z{#iA@+C0yWyld#j*VaZT-fyx0-Y)Ft+nm{&ds*A`ylQAm}N%>_3h4I>_X?;`II?!zwE%7Rnz%Cc~S5OBf9f?gwFR~y)|G2WVdvhw7| z45ahB&`ryW@|%8UPXhR*Mg){SVdj|KHHpR)eAS44&j1Z()rD(5`KPd zZ{DUGo!`o>HO$mk?b)XJOR+vbi}1&>iOWHKZkQf|9@fW!{@Xk_8t*%^jSG|0^|@?H zI5JtoQwRy#m`TP?kfw;6xodPURuog?&@n5ezr{MMyW z!hZXq87y@FWILNQG`#UFsK3%@R;1yJl>eDV=htCu2D1BJ0P;KPi51yhEmh%HOO$^Z z%*#R7f8GK44b`(Ip4}MU>ic4azve~#qlxbdknY77AipCkwaJ!QPW%V?GsW}b`uO3# zQZ!rdCpf>cTSJF9?{(tiy3_fc9#(~1TD9U@=``u5s{Y=7ZA)4&B>dF=bbgl)Y((0n zT{su@ruk-7{r&OPmKa14{?b}Hzgm+t@q=f?B zRZ5io4{?1wGSH6j^@P7uS)t%xTpxS3=!LaS#)A5r9c4#mTJ_l;C-y-tY7V$OA zqk)}3e!tuL<0o@s!2a;%q!1J^WCJ)qoiINd?^>P8WtS-V759g4EDT3~+iqo{^T7je z%W(7bd~Uxny?(wb%x`@v*$wjR+fa;4@BRks=e=7KP-$#BSU*QzN`Med; zwC~UNi~6O|S1nQgwf3tF^|+l6=GzA{tVp6>f4}+K)!cAup%8s3eWGS^WC<-0Ik~g0nESZSZz}Hts6feh0gcM?Lz-)Lj%Zn z^+Rn^+o?P6-Hgun*|SyXcTjuIjnMg?a>16QUme6B?5yPbkElPaF6_tpxYhvVTUKOC zCfpyyhXm94F7(jEw{;xB{A%zF&5*BZf|c zdG}}~-$A1MYwk-=e5ThVu5T^9ewIn?$fuCO{DI+gzWZd?FcG$TY}0(ESfAHB`r~d% zYr+211D6o=dfOJzUmxugjjzw!#~nVboal`lr-+n6iR}=A{qMe2wF24-w`{<1g;vBOYZ%CXm+?7h(e@W0|E346$ofyic;hK_{zn`tKz572gZ*bFN}B}Bd-IR_ z)A`?!QHp*Cw%`s$Hr3~<`S*%+ZPM#gZ{GW^jY6Nq^>wqsRp@297U<7UEwLrrmW<+O z$yX?z7xSP0uK}qqGvlEC*2ENB@@@YpUZcN~e>YKmJy{~`4|wm+J?%x;_woa_M)Wn9XcM&(9)+`OO}l8&v#xG^3@~^s7-Cg0dsGgZ{kzsA%l|E*D1+Vr7q;E53ga zQavA)g{_EVkT1yhRreee|M#8B`DF3=s6C6V$f$$9{CEdC-!&-($XfOnJ#}mDN@u!%AK-0EDtnFN&40-h-w$HG9|`sMzA{fRKRXp?OSDtQ@j1Wp70-+H zeM4Uh{33QFw{J6@@94d@Wbwsu{LwaazDrMd;;NN%xyI*oecxMQORlsF;Kw|ySA4$M zzwdAPjmeRA1^HfD=Z8~Gws1OE==qt)fnYR9mdZYBt9<{({p}*RX#C|_CZ~IVuJ6^+ z!u_-F4uX6)J0rvD!riZse`n^#ASV6<=-)qk7ULtyZTW#Y1`0mJ{jb?05|DvGE_nW8 zMX0cUtF{2t?>Rz$D=Z}Qa`So_KLZx+vpgte}YeU!5@gla!r=($~mU$H*B-3mrJl6~O(SgcbtCUx1MKmYwa40RcOl!f-&2Cb3d$gz*W z{A^K}kbm=MRQlIqeYPtW?vH(`$wU3?xc&)fe;Nz&`#d@cEogTG%)iYZ%TVI2M_~Tl zH`|g}44uZGx1#fVaa0B>&wUT_d$PcijGR6V@J zQvo_Mwl(*$cawgq_NPPtbRkoh4&&RW)A{v}Ek*Ypb_V_RDot(DYR53XxF4P0;K(Xe zl4}mu*Y=lf$c-%_yhr77#rrSz*OeNLXuP&N$nU?0HYDdn2w!r7&hG(X|7FIke%vfX z=XYRBThjAm2>*B$o!>A17TCIN5SN`z=XZ^*E#VAj^08}`{EigW*UNJ-I;lln5rSn^q?uU)+Q@J<$==!_&XE5sZJRPjBf7nLj zEjqcJM@AT6LL_*x@Mf$UFGMC^|_F>B-4A$ z;d>9F^Ie-=fHKS4b5MW!5Z8rt_44J*1L=J4m|lv`-P7Zs`LQpRUC5f5zWfnmI^Xx0 zDio_@!|B=5{q@8xHsmdu&-)&r^Ic!vfR5^Vg87-jP8+gq@O*ym3MJpdK1;QxU+snc zU59%N1@rOrVjJ>l*L?oe5IWxmV=b_gJcNtMrSskXn+@?Op3mnEr}OQ3%o87cw;I&v zovm!i#SioO{+ItLzTd=r>uY{v42O1So6b*(^RxWTet7%mJ>2%)biR|`2BXhyGC{tr z#|isyEm=jQ*T_Y*AIkc52qJOK0Y1!XeC_`L)7cU|snNnVyLKMZ)>i zOOKZDpRDNoE?!}Qd-k5sO?g4*_lMvw9&}vFZ?&NF>%GGh|M?fsb^orckE0pY^HHa2 zY>3I|rM%HuI=^2%zA-wLy}T}4yuH;KhMf+Kxd~A4%$!f*vy9X*tLq+ zF{AVUr>7=ft{(u_*RST;kjGk)d`fMe;`1{^{jc5gEpYw(B_RI`;%vx(?vecJr%x2m zi~afUY)?GNVW%PUgz#Sr1P)#Fbv)O$$|XO*dfCf>wkg#Z^AL?OUz9b z{>A?Mi!eW`*{&;}A4umvL7IS$>O2Jb-~8Q>Wd91|le@d{|IMd~{rQu)BsAaj4cpB_ z`ST;BdVcFxaaZ!xKAPvu==?{2lp%Ai-=KegRnwL9>mSW$4x;ma(=r2jOlrYF`I<*F zOX52^8svXpzZ}&4g9ga|EKN&c{yCZ_;dK6wUoAk5V-2{b`El|6G9OI4kQE0)_(i+v z{J&gViqzt4xU6)#{;wOl2{qXErZJ`kKQb^BsX^7qB^W&d_7o)`OfLm^*VV;RK7ZKdnKxq}VqS`y3i7wG(N z-74@uJ(45sl=>~+Z}5WHkUcMB`J3D5{I7rQiC-6P;W`sK|1G8q`NF?g-dvr|zi!?) zCUJ9L_D&X^f4A{|IBwesuHO#2{6@aJv3?GZOB9)xQg#pI(qyjI|fr@Mb;e{4ej5fXqic1N+~T)+eF+ z=RUG)37v2K?K1RjS3TI@nsvS_F}S>%KhvDfuS3ra)X%dGH>h3H`>)#Hnw-;>9K5tz zh2Q5$^?ast^%>OqOeYT7AJ+SIS2Fe8YJOjTI=^Zw3(&PyCSd)2?qg?S{CzGzHIUA) z*UVD%$K8?pw7coguj=0=nq5e1$9eqMKsvuuI|}_RV{gvPjb49mJ!(x#Y}WFAo9O&L zEowmDM+^u1TaR?Qbz-D~-MWq%dlKhdImZGirF z=6aT}UklLhrGxzN!(*pGevwWHdYj3!1J*0wZ?S%_d>o1Qtt#VowO8_sMEi$s?+8N! z3~qw_PTecR$vf2f52NV(B9|C6Y4!t9zlSU-#@$Cag86uFzXase;te=on(3}jWH(mv zn}jn&H2q%MCkeIn`3C0a4QFL2^r$)q?Z=-vr7PJwEuMGUu}ICC&E6^BHP%zWWM%_qFQ^`g3V|XYw~8 zoPXSs&iB4vrD%z<8|csNpLQmj--Poq-RXRv`Scc5uSa0MRy)UmIb)@rcZ{G{YZcO2xuUGOdKL4RzWlbiJSfrt@9U;yZIOd?d(s zZ#TdHqwCDWsruSCPD+{Qa1O^YHKUovv(`$p1{oSvLi2>?BB{_IRLay~N+k(R8tkNh9LbP=`@MeWe4Tw=YxU3j$9wIsqt0jF_j5nbdKP@0dxg3`FuT(d@T%us zD&G#T1L5uCFPQPhGQNX&d>7vE2hqA^)cMmfi@5m|D`iaEpHOAF18D7kCC4|vKJU!& zy=+u}Jajl&pRvszu+F`ns?WwzQDFA9<~&;u+53y{za8%CqO&Diap#FIrF`=D11^k9 z0LiY(3~hh@vECMFgYiB*(VfhwF;hUz-B=ey=3f-}d&8fT7J0YW|j*sEg{ux8kqu zR#N@p=WpAKYr(ERW99NU1)wJ9ue%SlMnO5@*jbUxcXw|7Y|+&@Oq3%ze~XYPx_?8^zT6`*GZMXzcx#c^*OLyWcy1V5#|(I-ioaIRRd2QNi2Ck@ef&cn3fk z)l|LIE17@MGINMs z56Jm<{`nFUM{fVd^(eeMjLiQ47YDd%PZG0*CG)QlX^m9dqp+_QnSb@cKPBznbE)$! z3)J1Aeho|IKb2VwZgwuC=I=|bw!;;sALRCj^6T%mL;j#B`6X4~?}R15uEiSI(v!@8 zsmTs7_2Vb%e9L#yefZ}7Fz);TnScAidq8XCAF6*3G>Zb2>y#MU`Oe|o+=S+54TjeL zZoFuYc5OL`S3mTX^3V6@H*TeY*}n}L+I;E6B6IX4{Gc4am{)(l$2q|3kp)A$zp8he zIqH1w0_V0;UQuCGCSTs^7Z%YA-bru z?=EbgNalB$?gwyrnlm%OgIs^lyKRL=Nuu%YU1Wai{Mtdvw#C%?JN29uI@2c_TdR@z z?ekd!W*!J)lID~3+gHIFMQw=2p*h#2?~jwb{5*{F=XdoEGD&S@{qEAk8YRR;+fEte@R{qTa@R$iLBpsy6$kvt-I9umcaLm z!TW_zsQT^Obvt}l@R^Bl{ZGFo^7rFR^zsLvo8MCN^BEGZf2N~@Y5S9`8iT;A4d1B! z@2<-C;h4Fjakx5}-{xL>fMIq!m0!03QNXEGnW61Bo9dPTM)%NRX#2TqHkhNApQ7>d zP%^(g@1%jtw}lLCf6DIwbF}h%G?m{koc^xu*OPhi-+U^+|JCW5IkM?>1eezPO8qmx z|5ds97J!k1nfFsW_>-ScOR3R8_tu4Cfeo48f(6|C3UFku%iYf^&#$YJE*cjViVN41 z`K`sZpnkMF(`y)+-<5}~(9-)cIDa~s-?1g_;78O-=9Lp!e?Nv;p&~X0Piu&i={K*w zp8s6~elFNa)!$M^E-aDIh=ecn(mY1Iu=lqn|JXuVwuYV|T{qMcSRDQ2tS`3D+ zuB6u29twfbE&2z;6wCJW^YgQO)*m!J`H(k$cSrr&Nv;5ha8H1*vh?xPNo4)KTglba zqDE@|9aU8V=e8D7i%7`{I7nI z-*09!ApzK?=*#gP1my3R3?6EZ?z_g~xg*GYFMON^UYsyvX!{Fmoz2nn)v;8*^^8-)qet0iF93 zsQR4sQU{q_--~r-k@*hEs0B+F&!zI+$;}EOrv!YpE1B=F8{2_KSFU!U%(t9&;?BP~ zCSboJGT(#RG@zAQD7C&`$-N)Y)&x9n0-5i~>E`h8s#qplMCN$qB$L%!n~BC)dX_^v%(;7YX>A z37Oy2v^1cMEUEe&+uIyPeoLV8Ti}xeW@Oni9rru)`JLxxj%)?T@WenezjxJcf!_@y zsr*)i>7Z*@!ttDf7gBxapZ|DZ!ujh%Q&kd{&n*A*t>r5c?tG>4u3=dpL z?Qiu{w?g@OC$L}U2C2Sw=JltWPqu^Qzcy0!c}_noBz%1WJLi)51reMM#{3#a=2v~26}sH_BpzS*T>AO>`Yasf0IinhFc065`3*T~ zg+@#}iRb-kmOjtdXQMwqC8zxTsQK8DpKh=*pn}TprN4_o(e~QBZACJE`2DRar{30NxeU(J2ziiXl;TAg_8Nj?LlD8RRyMlUw;0bl34<^ffF9o zK<3x#cNo}~-i^xdK<_BGzYLe_uaT z3sk!=rk)Sk_}UU#?M}vpJIH+R7~T%*GXt0fmSq3EwI~@^wB$-ZKfivS=Edz_P)lSEjVJSc)RjA**P4u%oFVi5n5&-`y}3fw z=f11B^YeNs_!dj%`^xbK$^2Pc@|wWG|GuAc@}^Mp*$pOteL=mSa%9wEkoCKss?UBZ zTz~7YBA(Ms=DTlCf1vX04>kYVDN2B!^3ACFta2s@)TJviwENvphLk|f>CU*dhRk=H z#U5~KmOAt3Z3n;d^W&#qM}jn@PtCtZY)Al^W@3gmKl<&G7(LsRf=}eh_yxTF^z4gi zpm$io(3t77zKYYLTL%ZMD%a?4(>Kh3Y7qpQRyASDF{x387zE8kxm>)!(3j*p|} z*Q1PeP<-HFY&V(Aub`$Jq(7QT_16P{4%&3;FfOPd^ZRXIEpYs?f^nEkuAjGMT5|Wl zrD1bdGQZajw1eL;nAzY#;g@@U6!-i+PcpxgA8SCp9#K?(z2}o9I?1HrUqxhoUvcL% zlgv|@MN`TAR`j$&i~gly`(0#yO$Io?OF=iN{2sKhLjRi6aKSP%zkO%_lq?Ggpw`do zxo*()@Ec~xDf0YSyy{}G|I~Nt{8-c3K=^2I7d(2AEdS!y&k7BGz_V97)n7Y^6JUUg zC8o`fokpD>_5NsB4WC-a+^5()gK8#2S+E8_p3 zKjG{1rAazSr~N1{KSS2%f{6*BIna{YpHg2WMu+dEVY``RzWp|)f%yJ*RR29UK#Y3S zq{;Dpl9zA0oy!3U-2H;I{lX2$#b|QZ(|BDrnQ!5=TflbgWX5B4hkusO$96VqqaP_p zaa?aQ-^Oe?aNRtQs?TH9br8OB6wf|O=KJ`DTCms9m&*73RhG!9=`8Nnjm)>5N;?=* zwTr6Hf*?z@Ry7^Fjv@1%^Hl>b-g20+JxkVSlhc-H^5As*GfKvH3@_ha5^oN@w9YWQ z4$AoE&xaoGY=v~9({b7|GT+@C9AL|3%-DBUmwx~F^Cz2rSR$1j>3HZ+8Q%+e`505x zAX)r6IPdXJvOeqDxWo4P8fKS*ru4thKYtx;vlwhr{!Q&q1)@OM@U|;X9xUUVzaMFF zcYomjNs*!5Um0YO0K*>lpw5?tKMw*2ud2xTZ~lCEj9v-cDV~FSq?7qR-x3B|m+CU5 zkH~!Ei;-Y-x`3hGUpJw*7}@ks$D7T6Nd3)8-uaI%BN9MTTMsJVpobWJ>z9t9KACU4 zAq~uJA4r}5jv6CIW1Z5ed^^w20eM#>)cKQD8^tJRXFC27PUd^)KNf77Gfi&(8vuE} z2Vd7lR@rfQZS8ZZ{`2eW0VU<&;51KaeeL~S8~v?|!?WYad_P}U3ucbmK;^rQJ3sef z!+AWqY(4n@_bD?ecZ_UJsw%2{O#v)grSV@DjD_d6?dC>V8)T3^?#v_vyA&SRBJ&!nGU%*(&ec6WdiZ{J}I{*dcy z@i|NM@%wo^z2=Yfc|PB#*EULiH}1|e{Yd89waN`{*!YQYt0e39hE+ZQ__pNL8_W3M z*Vj*V0^zlERou`+#y7wJJnn!$$oSfsS)C($9sv3L+jdC;OuE(wqYQF=Ev^d!opRNg z*oz&{%jaXW`jx<6Z|38~5;EU~ufu@DQUj`f-})B`O2>xU zHUFN-ov)kRIU9Fwjg|7j=R2oZ111&3QTg8EXo(sfvhi|9GT&Yr=J3`1OvZAMOuza4 zEsMF9DA73^FU%(MeXpMb^j9lnR&*!p_q<3;bbVhoHYq3beP7ZbDH;<-t*^VzaEF-| z-?EFgVUk z&L!(JP_aZspDy7reKNn7YPkEOcjr+1S8d$++TKc+am*GnzuSx*pvUt2RDNANEs>7X zWgMSE=C?AVQL^>rzPy$`hyK$S1-U<~I=jR9=YBEkw8{Lg%k%+pY$qze8SevNkG4Qu8sv2yL{*J_XmeTVPpzEk7Sx@;wsFR<@@0uS?yvQJ0x1xG|Ef z-<4_!-2Ju#sQ%n9%nYR@U&4RZkoh0vm@_}3mx)o=eD7RX3B7fP2G994W(s{j1@`%sA(X6j#I-WihhJ3`A6)u!cA`OhEf0Jq&N zW6Fn<^;?U3f9%iA#dl_r`QNprK{93f0c!o7rsNL)_G)Il#bo|_Wch%Si(MGn{qoP2 z210uyeViL2^XL5fyZ(Y7_%c?5T7NeUPJrEB4x#$<8FPcczBLBad|b6_2@DNeg}=Wg z^WTHh?|0+PsQgFgM1qD5y%^g0>s#FtK-B3WRR4W+rWx84oQvHNncvk7r@-t5h9GPD))muR6qbD+P zDt8Ms^4|@7w`!gAd47F8;__c0xp0UXJCdy5VlNBSMe`=^x|__e&2bI*=}ijNf2ZxS zKvlzU;*@kUzcxu?I8*65b-pa?g#~hmy@}UOc_#h*{Q7zscYf>Ik|#_xAoDv!ncL4( zd=sZnBlFuit5NbHH7ak36Is6#?z+K>b$^-1UC8{FUiJY4Y`QVSx5)ID@4ut|1;Bj= zyJNH2WPVp}^8@~j7S(^B9gqMo+6}|!uafoKa!U{}b1`D_H_LuLU%$6qD~99t`QjN@ z$o$?s5(aF4m@{{-bUZKL-?~#438v-rrRwwBA=+qL%US#(oUG5&4HLjd?P1jUlxQ0> zv?BKgE)w6a0ym=ioBf$O0t}!T5bLnQy0(zo5suBh>utM}G^{I2q#%ZyDd1m!B16 zYQPO`Y0Ps>_UC(?El`{v#;Sp2z7?*C;mU|SW~Vh-pR@N`paqvP_Wkoz%C|NzKXcV` zfIEi0pz8DfBn$3-U5w$wCh7CjdHHyPb)%%v>2TgY6*AvrUc14Pg^Kv1HJR_s1Ru~` zt4iftV?`j0{%DM8_Xj**=m(Tf>QecBqL%=>JQ+#VXGMV z_ZKc7zj$Ri;}Ro#Kk)f}c1R0(U(UeB*<`*O*O!AqNr6=T*1D;M;KvMnHbsAby@sscbE>)d*H^c3=Or?}yYc4FHoX1|_8f|3v{sY#drX5lx1Z`ZzC4o5_s0kg z*k@cib0dq)x1zZPa_e;mKbcGB`~C?roZx&0-@(h%$$XC%IKYv4uNgxZ zvVL0zS)euXcktgUWWH@w8YOFo9F^lcNTMM3XXPt5IJ{X2)ABQoU>~sNqz0Am!ybWf za+3+p&m`;jJ~cnkJkNlk-CzGuCjn|52h{wm&(t9Bd$x#Le|H&H0u|M_QO{os=7fPs z6M9kkUN%+>`IKM40|$`nZ^P0^(Cx}V>U^4WgceG$$->L-Jd^UvKc78WoB+ON0;bC! z^8D$GWDy!zbQ_-wmhrE^n{WA2cM9xKoJ!UA5syUZZ09>v{tp`DfY2@;RQ_{5i;%I^ z9X#OsYN(obE{fDbakg3b?rt*w zLBHMu-`a30|F#L{=-|40_^lzC|2e^bL8r9|)cU*s8FQ4l>mFX!mCS!4SAUPJJY@%UHg=F?i^mGR)|GJWUwzh|EC0mcE^3~fJ} z2j|~oADQ8a`^fx{@bm*#yNsBc^&S3MK7TWN5D$Y59Pxt#diekIuONx8-1}+4@*tp^ zU{39S|M*{jY;zE%-M<+-D-38I^J?@s);gw@E8YQHltCOua|t zzu%8+FngdU^?dftViC%JdJosWAoJg22@51X{#1XzuD2HY-sd77;7I0w$PjM6ZR{@U z`LObNTIk4%i@0t+ng1Po--EwvBIV{&`TH3@tusem1{7o8W`C)_OCpyKH9XQ!@V_FPkI1UB!5sCYgVuU@=_#uaN5R-M^co z*(Jqz(gq6u-2I)WVm>gFe8~KJTXFmOG)l0+Vlw|3;lCxI=~!N?KAHb(^=|N^rV6%N zDC3{sKRess2h4t|OU>W*zYBou84D`^eR}(Wf*wL@{&wn1JnUOKo~r+e(LuoHjuq3n zyyN{L-ye5gTmr{724mX&o&VN_fj2K~sq-(cH#O1S50~+Y8)W_s#zulWuNuCgw>v+5anb(L#x1uHZA)Wd85>D+i&cL#Y1W z#7GMn&%1)RT9Ww}op=vSMTe;My~}WO6c{x5!N12a^UsQVfGp*gyq zSc(%1$o!u>rUCnHyu{dkCG)@C&m0}DD#cSPu1J4AU;p2&5yJt|_o@7w#h9Za?FZP! zn9ToQMF%J;tY=pGlKBt3V~$cMKEQXs{g(cGetjP??6>6Up_6(0f63~5zW?w1$PEVg zsZsg&8pzf6n+&M_f9&4?Xq{q>Y4;ZxJoW{ZmrNOEd?`VUqsq z^$!Aj2KJ=pcNL3DAUkO{UK>HK@4beFf%=RARQ7%TIi$TI$qZ_Q|kW}c=_J$*(_Mre;c*`rdObe z){nS`gWf&;?|EZ6|JG<(4mPUoVL(;K`$ImzU)`vQj&HbzKWUQrAC~hT{40rOJU5Z+ z|IJF~XqZwtS3i*Xk2=-{?&YP(-ER;C)a5?kT?=!h-me@Fy-DW((s~Uj3cgC!|B7km zsBCdL*1ApRUvIq_22L!a&c_A&a{0x;H*CKH#&!h@tIQT>2mYo?6oj)9w#D z80ZV!#)ui({X_O=;^E}DsaWMWnSXz~AaL5E4>jL=FsTIU9SWuL|G+B@cq$K}_TM6A zYa+jIH}C*oGXHm`MFPdW5{9-v)i6;Lc}=~E>oHmX6Hz>{(49&>KmN&53w3F`iLGME z{6`d>0-}W;)blO*eYKFkavqicTUFWM%kouJ{--->p_Bo6_-_T7|6;^~W)MW>-#Seb zt#rSM^^3^-oAxOOS2pcq?*1b4@0O>D2Clz}w^o}=zyJLHU1r#Ou)rmTTK~^15u?%- z6}W9Gng6@z+ko&wnwQ;R zeEa~J|0OfTu&MAd{uOxn{v}NZcz;p@Qxi|-f5;MZGsy&_5&u5 zEUEK13vfJ?Ff;Indu0Ak^a}!)R@+eP|C>8Y;7E_Xc-{lD{wG_9fh7(O)c&38Xia3Z z31f|=Wd02%M*@e@W2p19K1G@+X9$afP00E$*%S{>d(5Eb|3zNfC~d)Q3}R*z^}llI zDbTa8C-r`Wh}qhx)cH1*|A5?V(DK-qI)Ag{f;RHMcN4uH1jY;o2DGXJTY zeZgew9#sE7BPt%+>A6$;dr_J};F^7Zs{RkZT>@{v+mBszh0^+ge}Aa2au_JE9YOW~ z#>=!&;H-RHS4z(R^ZG=BrbXkZ`ajtx9>hIyqw?)2)l=tsrwusU5$1ky;JDJ}z6EvXHid&4%8?t^MjS{1VhL`xcEty|W zb1~dI=Owj%KTsw{%}%dy!)7wSLGBLF_3U4!_BWZ|eKlevT=ELL>XP~OtZkBPzMGNv z3`P_A9qr==_Z%^x*6&A7dV_DA|EA5)RU`$#XT<}s(k(K-%V+t4thc?Hf&b-i+<6r_ zeYku*9$t2vgL~DH^*f8%4qC?zqW14>hL=Fc-VxXell6PuuTYR1JDSRGXHz}YBq_xU z1wEzw^Y1r#h9bd4Fo`-Je+k5cF=uAW&ByZhI}JIZhXQ|>Vy~?EM1D7KJ_X9Wmr?gS z^$6EPHm^#l`h06|HuyGe3zhGXd_82}?*SfIKcC2Vb1eo94xv*zOz!8l@)cN>PvviPMelgZJvL^C9Wz>66oOP0_&!hW@(UkpFxFVO#clhQuu&(uj zoIWe?_`YW^M&nOZ;pl#3zEd1Epn>LHsy^HKiqY+FRoKsx%y*rx7{;uqqWW`>onj3W{6>(D=neW*b#Ay12xA<{QqwMdGr_T`k#2gi6&`CgzJ z1VY9QWolAo&-3SRJOWGL!UIvbr!rZeg<9PCmJ5)Y&$njiBkR+Ta9N{le=?tMHOokF ztp5~hK4;<-4_@hcQ1iEyHTo#E@ew|Bc_ESS$2(7f7PVE>{C(^-eUy^>h{|`-u556~ zB9K~trzjYpa?{7S@7sk$zAt^n;F`-Gs(ycV)kT5RAL1J&ul{>p-hZDtUk08^qN#jm zF4aXRRzAeTJ$uN$pFkk@e!sNlJ@A^A%$m8W84{;f<8ps8-*p9T;Qf~zx&9mG z`R_YzX2^)G#=Dite4iM@?N>D}WG4P4>o*)JMw^8-_E{pQ_1{-inZcVe)ztmS z>lTVpr)f3VRY2xD@sb0ayIBbfy*tj2%HL1;#!HM|yVT$p`^kL2RcMlEJ@$8*Sh|7`RED>ST`=H4>C`17+12L`|{F80*b{q`*~>z{4?<|cAG`!JF+blOs;pN^1bDo0fM6Ec=47#SepOy z`tN38u2uiXul)Jdva#{t(X)lr{=3n%Q$X$UTB?43jLimX zr|)3So5}n+KR-WmraQXT_XXay!%NB^e}3lmB@B{7_fhpZwNek6nLNQEBdUn}W(Ajl z*sP<}{9Ie8j~X{V!4G|UNx%O=JbwLu)qtiusnq;zXqFl3EBS!+fQ(;t-u&E?nl|uO zaD{;p%K!cQ$ouc_1>E^R&kwle(^2Wq=jUhh`)j}#{v}j?H)(VJx9|gwttRv9^TG^1 z*z$ooKT{zVqX$(VaQM3l>CflqX9@cq;Me0_aPv$uzr!8GD6`W?ymbYc-<5ey66cYZ z^Tv6R{kNXb4W4C9sQR4a?G4r`^rH697ODimcJXkkKK~iy3r?&YK<%I3^N)vJvc2(* z*JOUjd29zRPe)Mw_iul$f9`z*C-o%rn{z)D{4N|%&Ce<}8lqhluetoS-+$i^`SWY8 zYLOu7lM9vK*cXOe|Ktt+ytJ0cZ-rhwcx~lPt*@62I|aV)T}S0tV_Y`aY_XH-ucM5N zP%HZeCl&e-`3)<=VD!UqrgD>vfByVy{u~1ol3R%d$KOex50c31?}8;|AiP@~m0u?} z1GG7-62rH>rQcsZzuKMOgN*g38Q;BR{hhhj44uDJhcm6n{H}l02Hcu+nFB{<{POkJ za6dQSf3*(R-Inni#LK@+tTkZTsRzu{&fTQ{z5r;*`GYIm`QbcaJzkSV<~Kaw3>K@` zQ~7OB6C;mx^;CYtxcn=5X;<7wi_C9?h8SJjP>)R~k@+pOZIax{xSF?IOy)PUyBo|I zY=*toll6DdPcN``Y9B^#Qipyj%KiRt-)w`+zK+Bp$H?{b2Pa>UK4CCJ+mCFwF&<`3 zU5XDilKG83za4mXl~Dcl&vhm68n@s2`$#gsm#>F{)#a0@{4T0DLb*XT__De!kzb#i z5nyPcJN0~8PtAD1WG$ik>nFR6k@DjA_>$&QDc}70R-b{V!0nlvsQs;{bF+aO+Rbd% zm+{Bf-|@x9Xu^Z{xc}y*M1F53V(_m%g6f~`o_9wZm%hd472Xs1?KHOxoL`-LL4FZiZ5ie8tBC zWcphLL~?u_sj!FcvsG}#cXEB)?YbEneEuue``jS?{rmIk<0EmuC1LBXQ~h)D6IWPS zXim+)URipBkQFvm{ayKX8*Cf~FztTtdNp5QG{RnPewAMzr?|w!)mAI1^)aXn1RJkG z>iN-k<|QzrZ#-hp3nEl)>P1U<~Hj5%9Pgvq~ceP z|M!*ofB(;)UzyQ48=Q3xrOvOj^#T+aQjeMG%ccDC{rCMt7#MpUr0VzDwMOU!{(uz@ ze2_lR*YDGl%D@@J6V(2-?pY%=%IG7${L)7H{pIWTzqd6&vn_)OP9W>|4#_T0)u$ybYu-S zx z(^d~^|GM>|0BPEM!|_h_Wd8rgf$4s0m|L%9^JDyc{Q6iC`n0nFJMJc*Pu2OE3Z~fw zQT=(!R1wOEYLMffzrS&6WfsU@v`21!9e{5Cds#^TXzUW90W}TyP_^v*S`cr3ZTf5s z0uLXi&aY^+7^BW_zu=!;>WKUoeSHY(yb`JN>+RYCw6614+$qA2$p0e$8nAcc1#10` zpNdeRPa_^1K;}QYR~sm}cZ->~LB>Ddzh7?@p$CT=@%!~;{?&h|!}Oca86S1Be?QQh zJHKDuh%Z4h|5qc;AlUhvnvc66Gi0gy8z1RU=D+TgJ-qx<1Jn9n|5lixkV(JszUyTE z@xI@Z-BZ}Swsvwp-ZjY;p1s_IT7Um}=LM#p8%Wjvy;0lXEah=j{_XtM0^8jq<@(or z{SVUP`0wXW&Cga_YzGTfCQ$jW_*V??{y0Iczq|Q`g3n&ARQ=zwR)~!9e&Ie21Bm?Z z%#8r+7I;$YZ{~U&$WHR3>U)fy2;Hn|!sq6Y`Tq4M6$~;Drsm_pViEe=(1ibo>;LOJ zpYLI&*%Puikfp~b}BSbr_K{$|3wK;@tz zRQ=BK+6JxvO`y)7A7|Ernp}xo{mtjsS{x6<^fqG8X0m?wY6}F@wI@^g9r3mp`gkN! z`Mtd*6tou1r0#DM%rQl-CtC1~9fPF&p5*1XuYC7JKPe^WuP0lTR4DT(h)QNgBGIlhB<^XDdavw+zl zZomIenSbEd?~NKFRD81)Yi^M7&G+xW`eU$MGnQJvoAeeT^-ryMPTF@V-~9a&cfLIY zuHL7p{{6@z5jx`7hSf3$OTYgodHFe-UIX&VFH!k_zFveJz1pzYmdyWxZ>?ZwQUP;1 zP{#jB9{<00i_q6?ZP>`3%)fJiIvhTtimKn=FNx5s!Z!T=$0h0K=l8!{{LJ8z#=lhm zUiDanPPVk+qm^X-r^njE^Fwv<2m^Bd_K!P1tY-cf_mPnK$GOcCznH?jN`s?B{vTa* zh02%v;zMy{{s$&`f%n{ge%k(+Zh~zvVCQ7K^su&+AO8Nge^1wfx|K+-{{?vSD+`+9 z;LCwq@SIvQ|3hvDf;}lysQs_1=wfI*I|U1s$o@TYX(;G_Vh)x6KjTc1($~K@VJDgY zRPP9|dgl`A{Mn`eQ`Bi(JNCXs=HJ{e4&0c#nR@=r>xd~DwYnX*Rmsku@z0+;PfrEc zZ|w>Rta~w;g2uds)5TS43|8SfNnSTdi8}Qpz z%=9=dq!4$IV}o`5!dJ49<&Hz_j`E z>Ua@yP*q?H(#iZQUa*HP6ZCQNFf#uGFNn}FfdU)YiOhe?@+Qg5q9SVjemch$YPj3t zN10^)yIk=CHYvlY=g*5Qwn3-UQ>p%a4O|O$bNy%9{`CkZ4*p3Gpw6Gai4Fu~&rYZE zzk49Jzjfa!>iqd>mr%e~cu@I2Z)=LKJXT<7{0DA{00{$EQ2o26y(v0WslfKzCgY!< z-_>r613^OrsQ$ifi77g-q{!}K$ozk8Nd;F_!*|-}Cjq z@j@18O^%}Oml}N06!k=ktl1zk|C5Je@Nn-j>i(JOIi_eORAko;lkpz}ya~^`D zn(0*j%RZW-@v9Ws{^Z%x;pT83;!n^+1@)DW<8Hc>UqnV?q{I9Ow3MU_QruNS_o?Qdl7muf&KeH~5gB68A z)cpSU?Lc7Icr}9AoE=v7Y8yEgBY)RnZM@y`(eFJk>RaQ?3LXzzWMq5$Es9N*=aA8@1E|a zX!D0oRK9IevcSlaLsWgA&%IxY8#}SeHRSW<2kRJ+eeMJ`pN|MOMJv>m*m8Xt-+X_6 z^WZ}e5SBsZTl0b`8aGghJvNBUcaD7xI9hd+Idq#rMYK;G&}a`_zJ-^V1y!Tkq= z@wXRbf4^mHAeeE{ovQE4>_fqe+1}LowQ&=LXp)%{J1uGe=RyCcg8cc^y`v+*?vK9I z{+n0537QqunceD2=G!1D4&2@uOx+)4ug&@I6P>Aiw|b<46-oQ3{#{wk6lunHrt;l< zBnt#LL{sy*iNj6N?^~VOxO_6-!z&rEMj?sn-?z*(MaL>Tvoo8&$?`d#euw)$1nr6! zsC>5snxdw*&a9mgneP^*8i2zvb$)eKoGG%>@4_zeCG$P1?0 zL%m`FRll`VL@2_y3tQ(e<6F$@zc(Ihk$`JY@?QNT*Y7{M`dw8r6jwKp`QD}L1)9PU zwSIpVycNz1oQeO$XiNFw*Y8WZt_3gCrpV=Ye7;|M#KG%m7uL=q^WCdD07Qh&rp~`z zODuvm$1-rmS@QXlu2!NNYr}}sGTPA4qG-XzM zB$@vqwsD}=co)^bKP)vtc5{^3*AvM4K5uX;__!~e+J8@~G(mlRl&SnXZOH;3v|_0I zSL>T1ha<}D>>M)x+8GS!IXs1`@7mn^tNTG^)-2~g{(19rcLN@RWl7nLrcQ@G%kPgk z=xmDYino;u9m{hgZMl_i>@Kbl=xRY2x{+jkMXY}1X(|AgzNsK}}->)V;k|A4{vu!`Hy zNb~Qu1*Yh!T~`*^llebt(kdC+{Y73+?-*i!hda4(`MU!~lK<{ck!b%<2Bm*it9b!8 zuK!KjA8}uOE8N~~4)$0fUm^zV;fpAWN+1KZy0 zrq0hLCz&7}m2RwWA2Q#Yd{V);ln81*zv`$7a{t$r%J&Pv*wF$ZcyRk8cWqbpkz6XgP0vGlob-r#{S5tI!VK>&cV34%F zz=0AYl9pxqObF&o3HdiZTv&V{^mFe7nw9 zhc6%gqWbsDji$)>RyTH6Uozk2Z$$7-iwdUQPi_^>L7f4|Vv9*)s5 zqx$z(nOwg5vm2G~?Cvd+uTx*_f&2^w)FA{?B`A9`+LSBP?R~I>ff)cZiOGM zJ#e33GT#R#t^wM`GpKw!ImW@G??b8i-1!dy;Bfi^YJU!>6hXI^Ec|*2S>IiLhkzjk ztEm3|t(pn?yg`Mn$tUw)-aP_bHr__v58E)t1kE_D!fF(d`9G-^2hwvwsr;u*H9TE*dZtK!fht?PiOhexojUYs`%TsN>S3I|2dT1~JCXS>x+H>$57emn{D2jvXz@8! zHs&Rn|K*DIFmb3kHJ_iq+7u1SRAmph{FMIwe1D(m*D5*ZSe55nK-Ty4d#*73-Y9&~ zQN}-iKjhapi@?X(lc@RJ#KtY~@#6*5{g97iR)f{0uFRtrMJ${Dl%KDQGKhl(tM*X+ zeJdLPG+h@_`LB2s0-o$xOU>VJzY`*J6*bm5i_AB!H~@AO1ycL(kJ^N2fmn?#2qg0z ztP}?_JoZq}pRE^~psW#U?8!7T-{h;bXJFGvRT@XsC=Y zKHol^KUuY1jU6c@^X<2Y0o$|BQuX~AFa-MGGx9Ny&ej?3oNPr zz26j5U=ia))pyaME$~mm zB02xguiqE!Ukws(%w&eBcI4yoeEWQhg-Z7O@TpXC{oZ>^0B9WPL(S(V6^DT4Qh%y` zCyx-IrmbqMe_em+`-Pv+4g7QfTo}EBs^5~=LbUIm@jZ*D-_ zP8$jb_qWFL&B^)uFI}$xprOgWxkl!DAy=Ot8Bt5sZ|?)H(BU1z1E-Ps);hQd#9g08 z)$g{MTVP124<5aU?BA`wuLl0QbLHma`T5+7l2|xFDV)0Bu_-wKxQ8#L_SX)ihJfiG zHc<8Z%yN$JLmI5Igq*(xJUjrH@4-~QSHugESGp#9Vg#A*MXzGP8r^Uz-|d+~1oAZ5 zZEj?~t3RcH{6R;l{ye8hh;Ba7r1CxM`~`6PZz6Smu1wJcjaAY5UwuI2n-w!4V`L^( zzjbs>5H!?cZ+`nKeV*T6^Ur?(#M|?j$z5f910LU}98A#u5nAjFXBpr8^DkG1RD)B_ z52^a?>~4bc+_l)G6*9j0{`{$WE0|?d%lvpw=G)xE1hvo8V!!E;`JU3E2EVy0;2lCT z-$~IXs3cO0wLVVf`x+2IPa_?SRLOh~;rvJRH7$18A~N42gNDL;E1HqjM^O&W`T4kPm&I&~3v>pX*+zfCvU0{ik9@=cbrj^p?`So{Y zWeV6hG?uF0(JO@L-CAub-wQJ?05~v(T7MUA5hA7S+Uz$Q8Q++9zQyrh9+f1Fe|77r!+>ODx>w8i|i=C-d#xvJD)nT}AchQ$s_*zAgb&e?CZ8h(2Q^ZjJ; z0bpCVn>rt(&b=SjeAQvQSCjeH%H{6$iHM}m$AnJc_~@$3dMT6jn|+f4MySU#Z^z2& zXa4+~?Gn!4Tj^5yPO85EoEM&Af}Lc~^Xu<%2ZbopNtgY#LB==VpN}ff15f;NsQt4Y z8QlEAVqJFADKg(|!~^iX|7|MY-QEfjKBCLo^dj>;)2JG3kEmeM3(0&x{3%46(sbEq z3mM;h{cfAr0xW&&&xwzCF{43zX|dd>#^HM%lOvj z_0Kc=wn)w&{+buPo2=hh%N1T7IfU4~%-#KlVU#@)7qPx<=$fA0s|jry#L7MbrgZSR23re{n}dB^ke`t5R4 zh#W)oS&jD9Qa<^7uOVI@Me`LI5#`jpJ~jx%adJfI7v&9@%bH$hvT z>r?r5)eymF*Sb^nTgku#)o{-rd|xj8{CvLq8V`lr&)87Uw|H{zm)b^s_I+0}-(}}r zptpk)))SER`8VSUqKjrz=U?nIHpBOC*2?kA&(H4uSp^KEeW?0;uwN{+y?Y3=OUeA6 zSh@|Q2K!UzU#5)+0ae>~Q2XCu)y61mgFbu1gj`>TEIa@X&)q}qf4{jWK&>+j*s@qM zzt?`R)O>tood8*`Ghp`?lKDM!I|UqVIL=)4knzXY=c;xAQV%nr@_QoU0_f|0 zmYR>ZnhKHDDFZgyh|KTAh&&MZ^a@p49wS8kOuDnh^)i0>{(Ih_7BJoO2Q@$QJtjoT z=G|H0Ei%7lacZ#UyfU@EZmi_|l}C5>J0k1zpnOy4I>ZPkwW&z;K>=vWz5hS_6(WPc z?(Fc7WPY;;4u$jY+EM%8qqzQxS6p}Yiz=C4mFmBe)aifnZYsn}>pTAW)YywIaDdh{ zYJHuU=?OBf&!g(|#g&`kqF?@U^);XGX+^8RoP$fLd|y(Hh1KVy@lS6u-|O19g6s_& zsQYF5GKKK6b3XNaT7X>$h#R$&ny=}!8lyk4-C6%RWd6sv8~~|<_EGEauK@z|+t`pj z(ZRYBm>*wTzV^MBG z^y;%AYZXW4Un4>dwgh&g`g3FM{qxPnh&^UV=HKSLDV*#ep!##+4X(a&He#1wCG($> zI0Oz%9e{7w$@WVDAitk=R<#g?Z8Ty7s(;A*3(udIuTTVbrV5O@<#8ha!;iW^^L5U0 z^KAgg&$q4Q^gVau0&4x8ptBh!gm1vNMrr@|e$$bAzXhM<^nLgWD*saqW8ubqM{%cp zWd6r3+y<^b+Dy&YP7MwLDbIIN{rPsG0CfvDV!NIo^L?f70bqJ#KULo!&k>;9Vk36# zBr@L>{bIqrlSirgZp^(OQonG|Zz1!2OOyhZZb+i;hf9tZptowqRK7>|zW_3qo~QQ5 zn2Q2*!^)UF@qo;C#>_mhd&Lc^KmYbrfTG45v-zqrzWMq-T;&1y_@jh*DCp2J#;nb0GT*@G9eBg_uW9W;@m8NcrODYqi0qFsWY1?e8Y*`}(b1e)Gwg{k5CS zcj%rW(CXqKx&3iLJihCX3(;P60b7_%=KGw9BJf?K$n>u|M&#RmjSIZ}+eMCV{(Q?c z4^L3|#gnS<8_YLDTXr+mzb8ek0^fSBrrv)ZSr-FioMLgoRx;n#`r81$w2hjtJyb4) z7eWj1+YIu2+eh^f@N7{CHGfNZXN(-j3RvasWd4hOg@fX$2dMKeR|g5up(6s;W(1l4 z0XDI~CnA=bzqL9GP~AlVYvn`cKlfiUc(pWz%Ktfc0Xm*5pz^QzBNM#vyg<#@!y^PJ z`KN$gcbm+Ak#ionUz|ssZ~Gj>y+7Lo?3*WFr25Y1e}w|qKimC)s_%#M1gOwl$THi= z{JZ^q3x*zeN7Z-Vm)!eTB4op-llgZ}YX=2E8{;%Vj`zcd-kfq zf7NRE=S*_{Y*-&IUkMko>MzLroBEi-E=8tP{ufRaq90j8HfJrF|C513VC&BzxSNtJ zf8+B%o2!o+SRre-ip>9tkN+fI#fnT#R05IzjZ0l%gP%JNb|u&EMk_r*|FhmyeGgl{ z8MZ0}Q1`EYO;`o$y82T4<3+Dy;8mS?s=m)I+6wkA+fKdzw8pd$ZtYZp_f(Sk?`InV z#+!sO@6r^|bKjF{ETrLg=FDoLb`Ma>Q0KpL^>?sp6|HN)GJ`WTiX1NKK|24NVLE6M@>ir8sAV8u` zChXjGWd3*9<$HXpS1p9-uZJn?HU0XP$^X9Vz3Vum8#4N`Xu0W5(01gI{_7Z@oZ(`s@?2&dy~1 zEgRp0RoWk^{kOIt0jkdsv85(t{-^Y91~wo5QTeY*79h4v#E$kL^Z#v}8Vpg@qVm5W zOMs5O5wQkQWd5(Vn!pFc%<<0>GXGOP2#|uI85=){%zun<2t2AVT&}+7>wn5OuKqGJ zW5)~0{4dRDmzX+rW^B~S`kyRufuWn{V%;@l{og*&6Rc@k#;m?3>re6f>qf6O!Pap* zsPpYw-&TTuy*5zm`(f@eu)^^;em9!Te^0y>)ZPuI?tkAkxDZZMEu-(Bd%YV>G}uSw zzl(`6a?>?qZ?uv7b0M$8L812{YJYCw5o5G2%8VU*pUnT|r!l~z_&C-7Z@OlTeqAzTYt*^;o)bz8|{=4QqW7PGI8I^wz$4n4uc$pbq*5QBT_s2GWGe&#Anz1!A$o%gu zya~41i{ApbBXv~% zs~rXC_Bb&s_`FJ5f6wF1$0ol11MZDi#2x!7`2D$n(E?-&#B4=(GXEoN)Ll_0!C!fTjv&sBV9=a9$vE4=W|07ik;pC`CRQ?lh?FM&l z@2B$rtknpeZx>VfACVmnuxT_k-}jnljK+JLvqw_N{M+A+0g}5Xsr`B1Kw~5dGiQ4} zSt0cg{Q0^UHV!#e!8{Qjxt1IB1qtT~ncA?2B1K-XMqfBspnF-p8^&aNCl z=Kn(JP0*LQ$2?5x`1$hpA6q;yMk=q&|JUD;NcVs6&aVf0mVzGrpHu7qE8PC+52_Yy ztRdN3OP_?T^RY{^{-(7VMe(GXC{>{HK2S18o0v!nFDLdv*ephb-8}o@D;p zwAA3hS-MpIa~BGbWP=5jf8_=fsMpV$%KwdnTz-4jg1w5HtS^wu>{6D(xJFe#Me*kzP4btvb$|^0SMPzi&p)|BaC=pSVlvFl} zXloZ4C9`CYBJTU3gpxgz$R^52_V0ck-!Aw4dz{zz|NE_c?(_Yc=e$!;_Vpa$stj@d zgOKEYPLYW=S=(8kO08r2@0py3?)&bL$p88GQ!SjKO)ieqr@d~n{qI^>gsy%r1?PLg zV@3D3_YwVk(f`Ef2L%%StMtHwXw!jHVE@0<25s^zP@jHLV*9U|aR$9gxdhJlhVIlR z-{SPCBNqGT=l^v&TA(^;NofbiE;1|L<_nA$Khe=+B$i#Xp}H|5dJAV}}R?`uB0sA&+bfsMKC@ z{Fma*_iReP+lBw`Ds=n8uK&BnPQYu+XMy{7#Ybi!hxg&&`xm#{EWxu&;v~+u^W%T0 z|9qsLvkJ`rPxsHm4h==%{?5gl%g_+D4HEG`26dMBe!HH(h@TkV1<$uv7003awvAx_ zZ%Lyj`MkOxb-r%KvF@+R$W1{XSLcELE84Zl25LYz%mw_1=Ar%rc7pz;rL{@;WdnL{ zA>04X6-B5{{SX-cWk!hh3+4KQ{x5kRMD8~$!1=zen>JaY*PjNz3h9X7{Q17~- z`3ji-M~a?brsn97yC819zksX`d>xQ zubchpZF{!=L$$hC@u@L*{qTswcb~hwhaLX~E^)|H zDIMJJk(neQFAf<{!zJwge`Ht+I`DQASpN^I(;{Kx4XLpg+rRC~JcK^&67KHuFMsYT z@%)Oqtwrp;4C(x-Z2x0DiqNZ5hr#{a+s#^}Ce#r0Z=in=ea|}!#{Zjg+GJpoAzi4vKmIS)x{6*qHG=+U1Za~J&4x7c0o%W7b0bo! z{tTXL>evES`>yposjFNGw&ep3C-Me%=r5E%b&UYdcv%!vm5Zx$}b5_{sOb zqKl~hf4>Hd|0_=C;ufVnocaj1fBmLqNTXLG*#B?4c@g_}spsAvV*CFn@}GG=1Kj`7 z*{nsn$r#f{4GU)cZ(fjsq{{P!*SE9tf9dsFTcP_B-}~{XgMhEuzue zn0kA${hxO!LgTL-1^a&^IV~bP*ckNhIN%_9{fHB~V)65bzu$-NYLS_a#?&B%?LWcx z47xhy8d(4L>8?$3V~y#~r)>W_n`_bS(@#PFmYUk6G{u-c-Np8Qw7wB-&iX2`|09JY z=YLA0wMlxpG2Mm5{`vX8U;lP=HeU{`|0hk>CUb5Z(-W83{`-_D;KQX_p#K=r`#t-} zn$VvzZ2wz)bnzy`f!xd|@*UqV{(kSyOl?vlFriV?*#6ghTjRT_4xs-(2SxRtjR}1* zhV6fd&Ud>A^KKIPKi~hlK@)Is%RH{%40iudA$A6mzPJQ@|ICk7i?QCB1d01E`2JHB z=cB9B*MjlCC_5K7m+j>iTe1B=o3;#XoRkE{|9u4)ag=2P82=yG#i3;$Sz!Nfu9p{2jxcH~$5`QJ&kJT%6BADI8YUaCbppERMD z2eADs_b5V>R~`rB|IjQg;(W^l^zUAK0A;701MjDvRHQ|EJvX5TLfHO|yPiQk=G*}1 z|NBp9kzL@V@hkLvi;}uw8rz7IC4jxiTnTj{C{)0Ht~9I z3i@|{(`Hw!*-iNG{u{pk6pab^>Vf&-{IBB7475XK1vvkY4P1;1rX_KkSF+=OW<>}p zy1WjY|NAb_#pe5p!T3K-ZW$VSFIl4gN4)y~$L5PTud$J{tzyUjEoyP-*}H5o{-*^i zk@k$fbnQ{L|7O_~B-6AF?ElLdYLTV$22iV~Z2v7!bJ0`15^(?b+bAs(v2Fkz)rIZf z@AVF}H{m4cf0~CDG1)W#^ndBt0pxe{0+|2XhiZ}23Jqqk{XajWMbgv<(#S-%e}j@nq^;Jt^w8(>z1L?$Ew*Q0;3OH3o7p(uUsfzYDA_vkRHEjQ* z`-tNIv%#FjD|Y;!G)kNF+c}VqvSa&CZL-38#m-#XJ+}XcleEcs;XoR#%Z~q3%i8QV zF76Kc|9Hg{zie6n_Wz^PW+1clRiOU`FQRcxdNL>F!S;WAZwLw;upW&6;d66wa?pNm zwF5i;zi(ZN@?2BF_}?S-A`Y=_0{4F`>(`-sj=5m{zfoO@$i3@FZ5OirXKALOiF*pb z_+Q*CAa;KS(%4gM|9-!7(HPZIu>LRqAs|?35M5py+>t-<=YM`%cA&u~<>3C$_1;>< zci14%e_`wa)O5TGjQD^*@>Q|FE)J z6lV8EIDZA(zf!&yIdowVeHzF1U(>G<)!F=!=>PNmk3FbGjyxPhbKB>4#9w~=-@NH7 zy85*{2it>=wlxzmmKTd4_ zYm#cwkVEf4|HoaWZD{ZB9bVyDp31N0vk>xmsNFOs<5nt%SM zr>kiG_jV1q|Ie+A#^dH~1mk}vlMs}5Js!;eSC7lZ{pAjU=XbTD1`hTZ>{Ih%~!DvLn>!4FC3ypX6aeb2?b*R{P-Ue`W0RHti&b0>B@=sBP8#~d^cE& zqh#DjC;*!lnbOIl>uB@24^4%`3n!q0ZU>y(7fHthJnYPu&LV=6kI zJCEJ}t2;CueSIAZ_WvCpMd8?lG|pI=o&OiAg`iHBiD3T!Lq8XPKYEzcpUIB@Gkz{b zm0vQ1<&FRP?~?QXLF23N&Hk^!_&?{-I@I50i}0oPzx`Lq^FOmTXp)CN%xQQc+rMd0 zGE!FG1)l$_cN7rs#};(2JKO)s{kiDu#3RCSD*x(d$@$;G=>qbn-GUAXWBae3umioi ze-^wy^GURTL}*xo{sq$yAg#`|;Qd>3MEQ&UcuRVyp6&nb_zKbf^CQsz+6w|w9&Sm0 zDY5+vCe|X=;8xJT-a7$t+HOe~nX>(FY~m^w*Qywdt$r#p&Y%*&i^-y z`oBf?R@C7s+y5e0E4<>`1hD>p5-aLIdstDK&20Z$4L{jc#VQL=ED*n+j-UUZcksj& zbP0E4Dck?ORnw8)$aSE9=?ziX_gy;o`j`0g{QO_TG6c=5P7*$g`scTk!~inmeGa}F zbd=L|WBafDvjpY-%mn*?F-BE*Qo>tqffGCb4>-IIRhDlB^M9WLO>$eoigvDJ`|s?X zjMmld2H#)z#8^P|O0DS032grd6LZn@zQ;iS`9wgDT(P3#m$3cY`RqUnKR9sy=RHb5 zLMyF6{{x##QFFyriTs~G|EmrakS>3$=! z_~-w+eXBtOcYYG?i(uFP5hq0T(KEo(IU&c4xxLNi2XOB-V(k}e*9?X*q{RXf7Hnn z%l%vi#{aOw=_sHi4($KEniqxf)J!g~8$13-R|lhUUz5T5|5auVR=9qQlhI)NKl)+` z8ow}GqW4ur zo7nynV+6#ac?ezf-JF^KXRUgSOwGH3@qcrHfE-pEN(Xt0{qx^Hy*8o^^=((Xl&sZ}vq$R93oP z*wt1Xzxn6?q}wC$^>bO={w3Ym!h3gH^KUUqqKlr z478#CtJwZ?-<(FTZJ!CRocve6NS^=M*+)P&B->Em!)*VH?$#jJOYNY44L1QPJ8$#f z`D>&10mkmwS zWBXTFDv!H-H3aYX+C5T0k`CC=wZ{&3{Qe%i{Xe6wJ+ZvwNX}Ep_HTDpKxWPuMqT6B z{zpBu#J`761^0jD-wMc-*kN?A8$14g+|z2;&r@Ca>s7Y!fBg@>|4w5(@Z6oNxlX2H zzx@7R^K(CR-aH=6|D*CE@vmMvT*EE#=lS{njjQvJY|KXR{Lg^pIoS7P8F!el{qId) zf^3uX!27*|^DD7K+DC4d13Uhg4OoX(joJbB|2*y~lJ$CKbhtFT|KHF#8Leq30nh&@ zuFxb3<-_Qsmv1`$efj%8g)+Hl!pw58|L2}6>OWi^Mt4fH{hur>L|#Ev;Qa4_P?MB& z8xHzc%`8QB%C{x_^Yj1wdQH-1Hk^7dXZw%KIE_AzegW?P-1($Qmbnb4nmgG3zwfC* zvuu8V{`HImWPajs+W4I9|2%$-?7GT}&UcCP2fqLOAp$aV%WxW?Blgda|Jb$-1@{(! z`G1X#fV|u`oI3r;6hD7>_y2^PrpG|5UoTe|xp+kc5tE;{OPTKHP;U;LEp|7A`Uoj;mwONTej`}=&>l=yz# z+E<8@LaM>|@4r%$c&FQf{x>WyMO#(xg7<&?*se)NR*1eo9&G=`*{9LS)K_5qk0{k7 z%{8|F%|ANo2Y&uvc%lX^y!=Zjl(?T)^8SyocbY_|=Ll+A&GtVap#jZlmFNDQ|KXJDG}WN-Qp98pSR_4wk>S`*~Y<0Hai3C z|D9CH!P}pn2Iv2&woB0cfP9JjKlt^3TU#a0x&M_5y2188>CajeMs|Vz{gx<_lwKBe z`UAHA#>ym=`TGDE|3?kfB)2+`q$_W*{da$#gO;{cfc{l%HHm@7NILcf+rQ)DLKI+h z8SMYtjn^bE2aJUM+mxb%kM4o{fBk1_5>_f60AO{!>4a?rdcHud$WK3+e`d`#--${hybgM$%2SZ2x<<>friJ4Cen#h9Iqt{8G{~tz?_{M_G+-1>>Rh%D5-v2SGdoYqy$P$i|c)x{Y|G%qz z4n9$HhI6oC=l^5=EJo++w@CQs@BiB9RpDRTzH`$xdUpJLDWoP5KWiVaMb0;O!~Ul$ z64^VJG`5NDUyddrqbrBN`2YH&203$R6n%Aw?Z4DJ2Yoa<3%*~A{?;I6!cmk`w*N6R z3Xy?94H*9`HAVXi4WmH+MmD5bY|J(Y?!}hPXPzP7c z7z6hI1AdGC`*pUX2m7=ASJ+wNgDYo(`~T|%0`k0{9ew?P?f*qii(Qw!+MxgTICsn? ztOM)+SY1ElZ<7M%{|PON@VP7bp#OVw=OJCyY;gX+s4W}&qzJ+N-#bqiBPq{q;Q2qp z>yeiys)AtG={Sx;t5t5w$zcN%L4&z1hpK7-MxacJGP5%fu|C=Dx zARip;XjnGe|JfNi=$@$ke6Hc&{()rvFR0ZZaZ~JQ$Ue4zW2ZvY*7+*9|F>WC`7u-N zK>rV3>_^ic)Pw%-|I#3}Id*jEmw6reJAeP@uFPrlyy-pI|4%j6BtErv)Y+Ep-!-xZ zeaq~`rL?mB+d69!zjiyCvzG0@=iCNl+^q+9{+amm{QMu!*CaRf5p6xr_MbZP3#!|$ z3(o&@7if|?Lqu0pu>Hr@%V8|K8v=U2-d9IW!nN5^Lw~maGoy8Isf<1Mq?ld*4}73W zY!4wStIzg7*31&8NZDR}>9L*-&L zvU0o7?fk#bOYZ+%DXPTZpZ*5@H`lI3K0o$>`#;*Bx|3a1L+J3sV*d!KOXLr7i;~c! zyGOzEKN%Y|$i%ydK3v51-_0inRlcBL|1Wx@28n%w=*?AZ|6OYfP?~?8aM8zq&kxD_ zzpkIvAX&XI=zpkiKiXK`0Q$c!dVVxpU^=Lg?f=y4Qz%xk70mxr+B8UXAf^p{+5RtR z)u8G5ox%98t*c3%=3x3bitS%t(11#ZD1q}omtmS@^l40!HnaVY{_+{6e%1re|0)d@ z^-m6B+OnPPzv-qNz8q!FIbwGIPfA<#`)6Qk?!opSi*@j+4-Vk|@6?@|WRnA-i{;q< z&%dz1UJK@c{r`mBnk3kXQ2lJSf7k6I|1NsM^uuib-b(Ix$CdTq`@8m^n1%!gH-hos zD|Zp5ncG1Bo>g;^enKwT|Fgc8jnmc6gZKaF>n%pN8ww=m|NQ*lJ*5&0@};Pw5bqnfCll5A#__9+yAtd0<=5vI+*`=TdqM?Y$u@qm}C1YT5ra_865ZdSK8)pA+PWu&fy1EM|+aQkL{QQ6C2Myw4GloV4v;A|o z9wD!J%HaO5g_I__H+~FNUdr|_XZQuV=l16M{b0}kw|CMc(jH^z{2aFbWn1O&xW^W7 z{MXVXTA^d;h^1`*EnRhRL!u*?|F4>>Np{^DLq9yP>!{!P`@bV9EpSz25SagKFViGx zZ^zK~IJSS??w{=5zwRxu|Id&A#;4q{dzX0bMi-^O^|R#reI`3hLpJZzglf*>_{*RF z`!868b4&}s{okaAbJ5lzo51=1xY%qw^UMYC{@>4EqtU!oJHYwhsNR)0>WDNgc*4&A z-A&h`cboQu@Ape;S10}C#?po;w*N%uB;@XL5}g0bC~1)6{l|j-PbuY~wTmmk`0sA2 zLAE)Kr6VV@{ja}OfUJscg89D<(ID#c#)AIUHta`2*(T8c%mo_6qG&AW-*3VxlxOw@ ztp7L0X^AAL!KoYS$V zC;i3#`SZWoWuH-5=e}V5|Ef}h_-oqJm224k=LE~)t+7_%`~9AYo?CFvuwtuTS zZ7c|M2J`fF(@f-!g3Q6|=G!y0`qwvjO{a@^o zjaA&MxCaB+{l9`U(a8645$ONnwn}{0t~1>f%#Q!7hO9+591no=|D-x~Vp(iYJB6|R zk5EiPM~;?(`9Ez|Ctf$~Y0)5d{QoYOgElx{1owaRWi-gFR(opU$@ZUkpa3;3xDEO@ z7ibVac?Zyc>-_y_oZNHp{+~)K4dOM}fezWsj{hkl|94k@1?&I46E#RDUk4gq$M*j| z@(SwPN0y7d%#QzI>7xE=i382?V*6JPe1!HWsDbf+ZH5LJSn5C>h}gdeZ~rGH>@$j* z+z*`pj}X;g*Y`Tms0D2QQsHv=ob3=W|4)3VK?e00M=cWA{$uWGV^5#);QoJ1vj&kh z97i`4vHi~*Y=JNMgm5Ou*!_R}M-)FsjiY^S+5Xp0Y_)sZ&{r7xnVtV1G;_l{T@tx5 zZ+bA}zv{|q$n;qzc>Zrvk41R6Y!P=`PwbyR|9^gZF1n?&1?>O#nV5|eCRBs>f9tM} zMpE9pK>riX*P_;+2f_Z{tgcB&A?6eqzZLhW6W`!*wBpBfAvUqb~8tiC#wvpvQ3t0bBq1sXch^qFkGn zo&9Yh>^7YJ{=VP_SDfaT#C5*S_A7koi+u#@YDw$4g-U&bfOuDofi9?(Z1fO~r%eP_9PjNr%4}JIVQ7S*Nw=jsIbAez#C5 z3H@}a5H9=seiHuu-1-~T$qFqedhZY0_uI^DG-usq@P0n89qPnoloQ=)!uI__vj9~K z?}6{^+P#LWOJ(Qhiie}nj8A*O z`}uwSQt{&*=eS2%jep~-r0+X>V^QB7N5K00p<)qMdDpSREJGkxBPou6-Bo{h|>*MRYzM5vSCPtG(G&CDn~&-e}Vb=u`}vqqmK)nnZfqoCF3%(U#h@C z=W`CVsFSe;E_9&|+rQttdi0}<0Ibg!{8A?e54+HCIkx}XRiDtRcetU(q=jR*ZNlmB7Yec&MBi{;D<6bGHZ*`K6N zI<=0comPr{Bcv@czue$?8KtF(-d_vczo~mzo$NDkr3=3g?&v@B@86h}SC32vYJu}N zQ&IiX`yQ&GjeQNgIF+63{QX8R4brv3mEQAW`(Cr&9FI&|1m^E4)}sE$16OMPyt(7= z=XmFDt@^p*a}BB7c_G{H_;tQ$R8t;!zE&Sa;LW1@af__kes!9IP|b!y;l39*Jo0J`UWU zwRxgObbh(g;8M2VqQTjy~gqQ4*Td!|$t z+y5R3*5B(Q)rr$(H;T?45lfe1erw{66c(gkm=EU}^G{qdd6h(o4 zH|vP~ z;U}|jZI|oZ_r>h|dxL5ek{-Svtgl_uQ*dT`6}SKAV`lz+G$|H6Ty_%dpOubCMAse9 zf&FiV4^oy zu#p{qwa=>)3k^@2H=6C&&)FPzs#*-5e~D;RC*h+#X^;DCzx3F6?B|*e#@~teebBhc z`C$H>cW@!@oKnKA8z7Fq{Qma%EvF#gsSoMQ-AVa({!a4zy4q_s((=ud)(mC)y%2Z_J^tJS^!vW2DE^TNwBa_} zujZA9=t(DC@cep+xjM0#F@d_4v;EFW`G~?z2ZH-+j-uz6tL_BQZ~c5(9FGuqe+3o& z{!j4)`rruLufrNGd}#F)us^o4K%IE}o&d(*fRBUmx2mP!{7R!tl)v}(qFVKAzte_) zvAcP6u(0cL_WP?|P8a!Jkio4jX2)mEZ9XWiXbb4u7cImF5BG!nD~=ljk(}i&Fh19J zNx@UqFLU|&Y~OvtBGJ2k2SMLT%QxcC{910`nx>BU%L6`8i{iEqNYN&|6b#^ zqr}nA!1HSXOVr5E30|Q8v>_!ZdGZ(GyIEqt{PXK?($q-bXfH}%i~Vy*GJfMdW$27+ z7tnvfVKvfemlyT##r9wLq8hzzRpPwO*z@biXKLhbvlq=i&-S1E>LKz@)8lTni9gTZ zUqAX=jYO(Vr0T_N|9IC&RR3TQcjqH}f9=ObHPWrpi#9)G$L~WHvN-lM2J7d0UDOHI zok(X~Wcz>VD2m_1eYk7!?D!qzrcR3ECelki*zr5y&tTl&dIh+@CRnOY?wp%Q51nND zN3EaiN+y^K8*j4rS5nl*#`myok?4NiA+WyQW3>_Icdp|eJG1?(wy#0UpPmNaUwiJ^ zM!ci*HSW7v3DbY+{RCt*?jm@8?U$Y!$=g4X`i8Upx0Gg~^Y8C~{zC_-5gAVO`8c-! zYf9Tu*VgA?{(fY<8qsT+2>RD;C`Ou{zJmKJ-RFt=2ilY9$rob({PQb6vdU0dunY&i zzj{@)8c7&9iC+5o`fvUq*+0A1T#XV(sBkkUiT(2TS8Ynv2wgIXp4!j$e?Iads@mQQ z?4Q|QQ6qADCeg|)w*SexAJLgVW?=n2WP=(xI(8CuqHOTz4DV9+4*D= zjcR23x6#qU>!0{?Qn76Rjw94b7bkBz)r9Ro*{(iqD(r2kD4_xr|lq_ycHrxNwKp%9>Xgla%>sL5Fu=OCPZqCl{ zJL?9bo`?2;@!$7sGH&WqD-r(@-@kGsTKMoVSfAUJrsCco>$u$gPyhaXlJl`)onlee z@-tw4t~@Cf?^;;Lm9E(L_w$nR-?S_NC6rZz{@=Y)CAoUu^vOiF|A0`Df3JIB|1GAQ zD1N(p(}hWF|Aw!(q0#v-LI10@)yT}*-k|@CW5uZDN;~MkkC_@-6zff`&$0aQ)#$9FD(L^|QZ-WF;!Vr9u>A+yJw!E?y+Qxqaz*`1 z-N`g$1>3)(-bb`P%pBZ*xinRcXq@w=RVUg0<$KCv*Vkjg^XrHAsgb0ilfnGoS4|85 z+UdvPt!)1Z2I?gH^<>&Ig6;pj?_jK$wVIRND~^wR|3pTe{5d_DevV}Ok6Y}5_ixPR z0;1TyUG_{xTol+=Br2 z{>u6jYtX~PXTkVAW^D>SrErb=a$qmhuW?oaG9;Hlza?i?$t}^pUzHo%Z;~wMzXx7&_%^;zvFLo#fz*RIAwkIeoM9J z_aB}*g?3uRj^95k1$b(o8JziYwqG48%3o}z($*JOJNke8{qx9HGdwsihFiIq?KibS z)V~Rs3i@pu;DXm&$>A;pi~S-bdA{Ue;8fJ#w-EHZEjk>lEcXm&~ z-)CIsHh8gp&)krJ^bKpk`F7`3s>D5VDzzNM_I=to3sp2f1pDiDyH$z&p{Z0Rl*Hp==_oDB|L3VuBes&URtdIli zbMLpJ{6y1-4tdCq&#guF1Hs!wt@6fY>*`{x0!Z zgsi8X0QXa5!&7nO(%al`#lQ78@BWw`i`Sr$a_7MQThO9pY`Xde_xb9cj`+<#KW^ZW zfLyQCg8eu7QL3bTfG^$JjqSU$=w6~d+aH1ZscpfkBqiLJ9-PSbeIscbYTViko*!8e zt4gkB`hvdisTCvr7r(*%^WmAQLE$GfVYw-QC z%6nBwpBi5}dmY>N&xo!#CdP^Tq{fcli|?zF0h-fjtq0rp>JR}w`C%3qzrRgZBNuK? zqw;lZ-)hUuu#7O4^9>REh~d@W?^D#s4g)``xrXg~_C9BP(0CJP;LncVd3~m$NrIi= z{9Cp<44Vx-E|Gup=VxQx=OEkhrJ!$rnPlu!bdzh7`}_Oz=4Y}Vi;&-wlVE@C!|G(5 zH|-V|ZN;9SeGXfL`tCdr*4G)TuyqrXXWp|h=**wXQ?%gc*&F`<7?m3CHuPA`^bz;0K8NS?)UOLD2-S^=|)F3Ya z>+4y^RY@nIALyGpK0roa4Z!;P@g-H#{>YEUjAZ*ZZ)`!Y;?*uoeAG?3{LpU30 zdmjMre?TM|TU@@)z5Vxm;`z3Vi$GUym4WYn`+7VH`+dH}9U3IwZzDy;SV=S#AF?rES( zR?+F8PsOr*=;ah?PHU+6^ZfbOBokEZ zKfgZQHU%xXwHx$#bVeAyq*Mm(uf$)SjgEad2*%%jxtZAL+f%NsnZ18jnHGV1tUCqf z*SbU2pif7uK!503JenDJ1B{=^qI3CQ?mh+U+vEo-WTC4+9ca$>m;7ienpX7@tZ%>8 zs}K`Uf6yOx-G^qHbpqpK{cjcG9On=Ei-|vps(UMP^oiIn|NZF>eMR;4DSv8R$o7|L zei0os(FW(w`9zg0Y4)cso@{@*LmnW9OGaF?igVyvkY~eoJvi*H7nu4O9 z?g7tVtsNGI)n=7*R>Q^dkze12li4V)=@1wnS8vP21Ft;eih8Pd?CsA-(Emf#-b2Mhr^*(H$>wn8&i&A%RKWuJyRr1|;7FE|_`%KQz z#O>4PaWO7zpZS|q$@QTDVE!tvYKpgAS<8Ld(cRU+dRKwoRJeTKepMbEw# z2#tD*zkmGmlf5`699X`UyXC|7d)90Us+Qgd*01GH7vN}mN}@l-uV3%E&qj_bkAU&> zR6r&!Tl9jP*PZRR6OKSx0cXJa_0^apd{ua#yJ#iOZxPS$_02Kpr1~ZB{N#iKqWF6J zw$QLt+<)Vrk1kWoLgL>qbH(EL$oKpHpbD9IIpDwkwVil>S#rOtf6WOr;#CjO@B0fX#Pn?dZAxYPMdzwe z@vNQ_eq)g2`w4VksgQyFX8-qoIPrco(visDwwT;UFDp&J`-z*{RLHpDvuRMvypGS0 zCp{%Te<$w)y5l|q>@STkRw3(Y0PW<-_FK%!;L&|O!TNLgBNdXOGMlc`VEcW&Ruez; z4&k^!w%$n$ce?QOjTb86se)gS1^-S1)i?_I-){FvS zeT{TSd_zd$pGT^}+X?rn-Uh~BkN1<&AE#o_@A~`&*l=J4=(qdn05mf1C>VdUM`Yqr z!(VYW%51;g)gw^-tFz$!#G$fDm^wb>yfpy7TVv4N`paN{xy>#f<-NEA#@|n0GSJ*B zFTws%cXAl}U+zYaZ&du-pO$>T$d8R%QQvj#;C^m1pBpZlIb*4LD{hfBo%`T4O=yb7sIoI~d>V*8C+QiVRP(*^6(@>43r=D{4A zHHPhXmHvHnbJPGZ{(ifmLZYPtY1U7%U;g<(eHIDlrZXq`TADeibKc;%B`>LBEqGs}kGmfs~_czY2SdaaZX$uAo5t z^QCxxkBw6$nPq{rRGRHKBG(0_JT4SEzZd(B;radH?1W3Y6@c-#>dItPl34=oXZH+R zfP1E#k;tF<@i*{L01B2n4&E168540zJ^bwCMS< zH6(}{4rBXQd2tWvMGgf0M{ZFeeUpQz{Y$Zbe*8YA_yJ|Bj0WTPW(O6rrE?IygxUT# zg~;F#lZoJb=;Trr(ljxMj_b_!U#O>vpB`Vp^_luN{-Pcd-;Y4i^J9nmT(CY~F~S%} zoQvZG;cWj({ZvVg|6F=jmhHc~!WmWN><~&Nvi*Nkbi$6K3PJyY!pZ2COexsE@(?V* zU0TmdoS)?TkM{^b8^@mj_qWnIXJWh}E3o|!XxV_U`~xt)S3cd22Mw2^D)D0f{QJpTPiLS( zK5xPOY|jIyu*V4vdNfo+{QD!x`2QGhMJgkHg8gZqN@dc+dM@aHiqBpY(^*!c{zkn0 zj}FL%a@hN;Y2U4hYGttz0O00 zj8U6M!%W%!TaVmB`j-ZQ=PL(`onW zfBqXI{A}NP?#5)cf72FG{iPO6cm96Y@$>oj8$5GxMzf9-2{Y!3{TJ}!e-~8~{P;#Z zx2Wtx$M=ulzuu-a8NE_C0KQ*ncGm?sw1DG!Pi6PddcT{6$j*~s{@#8w10UMe4Eo>m zA{>#==fM88T2LY`>D0(2H?aMe4vj$#>*~P!$!b?5;@kZjxvTxz{*5neK+b0$g8pld zY{z7jH0_-v_Ro+1!QmNbW0z(y|8G0U;R7Ff(wGH0O#gAuwxEw6eu4Lk?=4d%S4IYd z{;fmyqDImEfKdH@=bAEk9}rBx_F?3Gn9tG1ZeYXFf3HMOXQG>z#&gVl!`HyS}mA=jP?<2Z*zn3}&&u2ckqfClJ zgXx2TZ2xn6%ixyi$zc8NN>oT@&k(xFj2-_?%QWyQuL#a#0z3XY=cy2GcL)s*WBX59 zVuV+3*uXg%vHgG8DXO1Nhfw|NZ2$LWI-`Ccb_!2!7W?OT{?BF^?Df5hAW zv<~w|x%7bW?ce=P{(jhb9}}F?C6SxIrS|XlSMq*gx7u0g{_Qd_{>Re{yvgbVcNnwd zf1Aca)U@;h_4XjKF2|MY5QlJqm=zx{SQasD8AK5N0+ zO62>s4|h$69slK@DH9Kq`Lw({+rL2J9$KVq4&G0?OkRad4xCSKSF`;`2farj&ICN4 z)wxKSOcaLD0zJ0>`|rEp+L9??{a-&;RDWEYPnS<;`}bI@f!hx+;tq{v`+u`RG=H%U zr8|<@{sUBvu$yr_$F+&?hv3)$uOn25xoRkVd7AA%I@B4Ri`*^IzvIXM2M)&gP82{yFCgS$YChqDSw*S|$8_se68^MilC+4K2Z(DMQ*&RSDkzw^&` zEE%m#Y=?(}{-4u5Xx2x0iTs~m|DT(qOztiXrBOeF{`!^d-!I>B9F_WNfc5{)&B~YmR&&P+|P$o757tp;G zZ2xlF@6panV?h6Y>y*jB{h^eavHk0v?}7(R_5uBSc2Xgp%NNiC7oq`uF=Q8ULH?W+AQhr@{E29GZc-Qy)2Z zC$|59_AoT_c@;Q6?{zl;FI)ADlR3qX|8dEy(X*>JLI2w$6LH$w=iH|QZ2#l!HXwD& zM)3VY%d-=){Hf<$Q~ivNzn|mz?_HIShVE(w=kHCK*Kl~_Kw5vssN?f7y!!u(&lYq! zSDNc)#`Zt3uQCaFy8!fW8M_C0+)?0^ev9X?eE)ZmGI`TGjAqNQ=P<_rtR_vFb|07ZUBAXCKou%3S`_|k=6YDL({C|Sz`7`=h z7@fL@?LYEKGwN(=56<6*Pf#YOM}|=YBewquMP2Zf24ArMcREp-1Z@tZ7H;F}Q zH1IyB#o+w?maJ%gGB2FQPG_)Ht1i) zA`u%lz2H8jvi-j_*nmo|JOT56gTh1{xa}o3-BKL?`Tf63o72%X`%j?%N#WOURv$BJ zd{gXS8B6y6Je9YggEKmT@jpUFnPe4&gZ^z3_MrY>x^YdW;^zn7f18FV{#As7{wM1k zM~Th?&_A&j^&j4cQ=g%1|MPZSKssX$xcFbNZ}7o7BU8n^bY*dIcQ z65rpQGnL6!+l6%LJGTEp_3C)oi6vZ^2|NG)a7Fa{zgtK**|GhPx^Ia4%u3?6+skqP ztFQR^|Ht>rX*7t=(JSqpX1g4Cz>2^-nKoQ%pFDX|39z(zjtU7 z`YAXD`ghqrA1@BMDAE7p_y6Zh%|gmc&Vu)|SQusCNmJXn{{HOvKgKi+3DPcs`{mF5 z60l6-OK!wkwtvgIRmfL(2dw}57$@Rq4X?P83by~G*Xz;qz$P&M+r=f~2g_e`&ppKc z`SpKFTsmrW`~v3xwGZm>y@7+NeWuvI6wg0>osR+oJ9EAJ{qrNapWgMb5;3%j0R8t0 z-Glse6v6s`z&$0>H!6ZUwXpO5uUC(uyqQ{H|LN0ep-f7;Eu!5r*#1XMZAJs-9KrM5x$R2i zVo3z;X2OpD=EJ+-qK4_5(=WFFx9ZAd{lf@4_A=YQuuL77mM-IzY}o#5)0Iir1B>Vc zOSXTl-bQ%Ky=3m(ezyN%70M*;%ObG;uQGH(hwc}H{XgGI2dsK)FE{or+dmGUguI=O zgZ{%U=i|n$)nNS3@tld`{e@uvKekf_J}cYK(IB?}YS%C{7heI-e>V(F!1rWcb3GQb z{SW)F3aQ861Me>{C`rHr9=+xSQ`r7J>enMIcn;S8bE49byw+E6zOUp|heMUjskaB) zcfz)O(fyBII46aFJ|uk)-J(QnKQ97(dk@@$(tjy}=TF*ll}M-NMfAp1w(lm7W5~%! zn`;dC_wyz1Un~$Rk(uU^w73V`cbn`5G%3aq^i5ufettwGUGRqO8&%&y>q3Wu=fn2M zE0cZ)B5A)ov2Xr-FS+_1nxW?e&i9v>DG@t^NUEpK_MKtY1y4`(2mAXvqMvVB8cF3^ z*}l84RL8qVtpMYDoWCf)!BN!5l>Co?*-bc z(5=^oupy_lQmT zsC=*tSie7+szkm9MS;FgY3xCzqIbW>ju-pn=kK=jm5Bd_DA0FK*fBIBLI=#>)zg%S z@In+#m1FxZd~hDookm>MC-Kkc=kIThD3JiEXzKig?c3qV9h6^b1Kw}G_nH!Mvx=rS zW5vGt`Fs7{cPRCgGkAZ4TaXg@xGIV&zE2m|4|ci|`T39EopI*ZnPC0C{eTjY{}x4M z%h-Pig{-~4T zIdFeZzdRlHSoedww2bXrVao#4^=++0{T_olOZ@jSxe||8>Ad4E&u06cTCx)Le)B+h zsq)|Rp^L=ly#^=X85iGi{-$i-8xE~UHjCQB(5K z1EsEDejYefi5xXs4Ej#W+l?kyDsfBI|M`+U-+lOPDb5mTQsJrYcK?eH1-$!HPy9HF z+9vb_=W~4nl*o(ai~qa7qT}=Y_m7<2d>#p|8cX<&;qBK4uTmnvix<-c57@p(&cB0_ zyA20@qs>Z0;o)MsD_ZQEAHT~D-XZJDE}Y?B@%cA|B=0|0aaAHWCoQHwJF(+;`Nus?q|Cm!G0 z-^^{BBKFNc-!>|BC0ez)9<0yJ`Xpf0E$_KcZfxHp)~!dERNjETHylYrpR0d>{kJOh zQXH70N!x9^i~FCv`rFScA2rCzg7MpIXDJ?_CXnzQV<(V!KG|;Gjplq(2J7zyaiuu8 zU6YQ=Vf!BT_9*gA&;{%7yM{_+zSdGYy6qLyx61hQDC3QZM1Icqt?j8qKF?fA%j(&_ z1HRuzGY8m$`FWD)`Jx!Rlr9No`|k7kt?2xRE4Y8xqNhYY$SnnZlfusUO}9DV{4IEb zD8HY*l)9Z_$M5p@YFOcT449v1iSmzXyJd7%Kelh_7!zEzB$Kmt>&Eo$_C<*tTD^?s z7qETT$T%X~^#>*PZ~4CWPqoL-2bFTq3)t~{;G&7>bLc5>{(e#|1b1_~%1L>MeM|A? z?_LjQpvdqGpl{W^>DYG1A1>}H+xIc`1?b+}YheAo-ZvhP@%X^`IEa1o`|n?WuRxKV z8o>Ci{3IS1+O~lCdELk(kbvziTRFEc;`tlD|CXMThJug$5}s=i&%Y3o zJpUT|ct5r{Dxf_u+keB)&B$9?4)os^T#C~NX@UL=Ja?n(A63BmTpE{RPELy&r?LIt z*?JUdZqozrU$cJOgABa2jDCN?_P<*8JX&cmK*B#ie}6nci4@x}r)BTh{_(-v$ZPEg z(EkT(C6YO5Io%k}_HP^X7I|g3ajCiN_@2_-gE-$?Mw_~@+>`6AvmP0j$0ln_Ro*+hhNP=u}>?( z`dr2-9a{%V(UF?~|3^bnFSQ#I`8&Tpcejeio6odJ_~*y>4R2PUF>#N<_^ul-%KyDu zxe?Or_&)Ms9BR#b2j2f;G&%u~$^OV`z5YMC&O0v0_x=AV?Pa8)l$nsoCUl&atc+4d znuw5@l@!_oO`}PnU6it=uCrv%C_5vBysgOQcYhzB?z*nu<2?TMxVppryk4*4bsXn$ zvibMi5d+Fw|DpMuhi?*m3RU96UbVg-g!$Xt4u{D3FG9Wng!;a@LnidE?11*y3L5iC z{(W8ga1)#FT*qSQ6KKdg1hx8qVgAOuNc_QYJvw%IWV61@5aE2?i|^%7Xk#kquk#}R zes0MjVodbtUxPc%&!>sb$ErqFgW8$V=zM*(k|y{4mLCmSA>~_KpI_M60Fj+-(f(Ql z)!;tc`=R=7FhGu+e6pA~d(Y0-XMEJ)4rKb#jm2!fUwCySx26a3W*Th&K6bt)H)iE# zTBXS5+vm3lS?{o$Z!?;$@A|=-+~d5>)M6`}Z%d^~U^b*kkiUuR^9K!9`BtKZ}IO|N%>ET4X_A?*cnAz;F{YB^NOz(!k+Kul~eLs3O zoNPGQ$e&xl=DWlx2EHZ9@R@B}`4Q^-eV=?1pQT58PL%5VJdwZeu{8;d4=SVmb)w7V-S+cZbG|3ufBf*M z33)YT4_`Zg&2Rk#i9esTmHu1G=C}RxiJ-l-Sa3d8%x{su6>*$b$Y*S4^Si9V9zJ#` zMfvrZ>q(9~R0-;DF~4dVZlHAbB03-Y1=+hbXLH?8+TBBcE1otHkLN> zZ+c7pxmcf%Z}NkTeb3SJaXCie*PQA^1oJoa+4?+3Pm?2F{!WoL3jZk#RQ|Lg#Pev9kxwKFw1yJP-zR|UKN=2P#$!U=%Z-?!Il za7S+W)2XgfeHZhe-~TO)JZI07XmmIWLW%)k1J^7SYsEAo#Pq4l?pu02$2=F$AEbInpxJgS;k^wAKqFZ{E6 ziT204+zKNGMc)MVHxI)77w?vZz%~0ubU(WJxNy=Z@H;=qx5b}}=HK6yL_?nra=iTa z*7{oL&o6vRgz|Z6X#XtBIG@!0G!XFpROG+w2WP;GbZyjsFK;WUzaJW)d@tHq1no<^ zqxzj)ug-x-03BVz=6m)_3TgO4J5Gcl zO~(cPUCj5IbK^*2Lov$tbALO?*+5Z!e;B-!9NAkV;9Kn9-^_G{U9+yD_nTyT#SmA% zEj@gK&3D+zWl(bPo?!k(+#e6>5=L~KzVpMrvH6~^;tT30U!nQ>0;e!?^XhlrEmx}V z;{E8(-9zBz@h@ooJy}1TME3v5FA0?tpJChw8h^Pj&9O zZy>!nn$5rY&o>aRJO@4B@>WKJ8xj~uy@#;%{fMB7Z}f@Hzitm-m=yRLt>5iP7-{tS z$y-o1|Fa$jgJzp1biO^NV>q$=_KRPCPRhT(NZ&&TMT6_kwkZE8EAza5BlKLbq zh$g*d>wlm}Z&L9qiT99a^FMpI26rPjh^`pM=Kpb@39$CY$+DGsQhq_?@0S{mBO%|9 z@yC4CTj~$t`L=#hGhpnhin4QWq|c{88^Qd>1&5_%RqB0y?O7@R;`)9;lMAeDa|6xa z6WwBnPKE+aR_w&|_x8(|LBHsSDE}`ngpyN>exd&U#nDZmee(@^zHNqb7%6-5iw`Ph z^RL+$45NR2L+58I6~l?^=|8;ZuNMAA`|TDPMnjm7Jn!DX_V=re^2p|RBSHQy)_(`1 zM0j&egJ1i(^?70c?Y{+iWMz$!fd6(x*nc}XD;+L#dT4%EV3SAu&KaTlA9VZ(JS*vi z@*m--&KcbaqLa(m{P!M6A-3NT0srFqzFW5X_2h&r-*!(BIdks;e=A!kz-!XOWlSwe$GLfzSmMXI3PvjbOe(qqMI`_*ym`2GL z!vE$E#rv(kDR&^J2Zi%dGVFX$v6BX;8W>EwtF!gL+Nw8k{g=!q>9F}%kklWmwgsd9 z-z;eY%#Ax;wyJCEe5e3lnQILk(dcr5pB2jH|Ikxg*gEoDSxgR_|Aqf8A>6G8{Lnlp z|6=_&&3A#FV{fATPwE*%{w-0Y=D*qcpZwYr_(PA-^KEN)h7#HPzft{P*KZSikZVBe z``x9XM7{4H{&N(Yf6tg;nA83TdcJkomoRc|)j!_En0>x&)bA*GW~YGG_Xq#WC12yZ z(vj2H`mbb}2vJR%eACF*{+E#dKBM!Me9UwTcQJ25N-)&E(4jYHa}S|J}qkE-*e_o{jjcb;WHD4YI@_jM?zY1I+s`3_kzSX3C47qHl zL=Sdm>wi1{>|K+YwqFeNr58BD*zj{kB zEGYYl=KE?%VWh9E3~k+SAf#w^EW*=t8?Tz&VP7fd!ltd0?qfeiqts=tx$CSM)$li znRH_>%70ynIu~acO0Ugf^Z#+pc(8FQ5%4e0|GF*a$kMf^(Ek0MBet-=(*=S5Z%2gw zU(b07d6)f|e{qtn|NqonpvRLcRR3>OMH7d?%2criS-Q*^(bPR~#h@!voG z{5>}RlMeYnQ~&p<{|}lUN}SDQXeCJw-WjP)a6l- z`B)LH|8FkNCBLJ(Q#~uT{^w>TfKFO_wEhn~n@dWbc1QUSuQ~{}6Ae)QJ4WP^6NkH_ z`k$kG1TvqSp!(nQh8j1_J`~k|62QajgTn>=J#qdQtfqYgwg}g+4X;6q%j%)d>@+sDMzVuk{XtNaA)(s(0e>gyLlGP|0=%_ z614g>e|{O;|DV;hg@H;J%l4j<`hOV_|F3#3A(g$J@ZGLR`4`v!uT)&%wa*DnkLm$_&`QISx1G3H^(EQ(~PbitxBtzY{N%ddM z|3Rx@xH#!AdjAX^5k`jmYD51#XV?FJ6QbZtxf0(xU+*uPuV0~)OWtqoL7xv{^FLI= z|H+aL{Il_F|KDL_F1hol2g?7yJqMu;bV2#oo03ZskMuzKpZ2m4rm6Hr&&N(oP~(>O z3Pbb%Htl)XoH_#S|M{Jk_=gE$)cOd!|2J2q3W8ou=C@@?=Yz!i?M~cP<2)9Gq5l6{ zSv~OQT=@s7?Eb!UwHnubUKqOHF2t-2xjc6x>i-)I)VYTAFj}L?uK#ll+mp9jw)4|p zDz)Tm!v6ljG3uP#xiDJyjm^KOgE8s!Diy8&FFL4m8*0O7{X91Rzih{Y+o#g9Hvgpj ziv9ngbA&7jJi{;AAmv}Y-?mA~7Ean;Dm!ss`n;I`hWm?2sq<5mf7kWS;4!-z)&Em` zG*L8ArR5%M{_Wl`g->qJ1@n92{9o&02&q}$hGP1E$iN3G+kHaw|HjWD#6GnR&GBRN zzx7iPymkJE`v07tp(JFVEEVMcBK@E7ClZD%R_6UHTk|_%e}Bw}9HO?Sr(nKEod10p zn*d5PJEHnuVUtVN-{^_*KW*kgIHPVTI6o^sAHPvQmpn-6Nuw9B{lEFXLMVCD7w!M8 zb5P?x+z6v@bJ+g>#_=);3mJ)?uQ?v0#?4a*r;m=Y`B(mQ3l#fILH)mbwi;*MC0yYD z#q;-BvGs66dmftq7ampP%=?6+{$KC444LicgUm{ePEO0YAP>u-{6||CJ0v4xKLHzs5-U z7w@;f!rQ=CpUWu!ZmEmO?6c4KoA;#pFRuTeeQ|;!*BZ3{7v~pElJ2U~Gxlu$LzgUt zr<>|f{hz%zghY>!MfKl(!$x>u{28tP*PjX@-|S`SrT=-HZ|$_oP2 ziGiV{Ku3-`ShMv%^L`}QS*oD^KjTaeQCQv!&HtDEj)#F=wb1(iU%Ol~q^uXpf4crb z(EWzZxe|@BLcI4Pnp2Y2`?E{jc@&6^t>M&wmMJ>wk=&8rQiY9PR%P zJ1Rp?*KXoVjR~m`UOxiu{|BFKM;5h5iO*QVz=m^yR*PiP|Sox`hVAy z#iV>h9q;y-&A-b@Cn&jp7d>C+GC!I$JW!+k*Rc8b`Md;%-g|-O|Gx7>h@p}kEvRDq z|1LkhK|7@p_5XDlA;fNq9Mw)>^WP911m$Df@O?wr{D)_R67LCZ(fqIN*+}>?MiuS< z4fV_+3sxGV=j+Sg#KYauozU~OH*V#SK6i{!{*AvKfW^99(fPj_dveH$L}S$d2lXig zD^1Dynggx%hw%JOv4TXuqa)DzUw?cVl)bV*`Cl)^ zOcl$~{{Pf(K>Bnn2&sqbQ<|LO(*P*UhM@81-iuOIH~ z1d%iEqyGP8&uCJ9R-L-7Wb^;@#S(}~c_r}w;`6oNOhU-h2XZv=Dx3eQo4vuM-B_22JMBq&;|@e|v(@+0*BXN+>l zQt#eq{XZx!9vV7nqyFE-FNeIZ>W%UrbNm3zH0&neA4Khiz#6 zUo^KJ3I7m<`u_#%)wo|;+v$UUZ2xaNxfe;zJ;=}c$JYNI5o+9alkN1e3tRv1TpkBk zj4K5CFV6obJOolalIM3POZgZ3{~oF~aLDC4%Kz8T9%Q5WD}I|MoBySM9pU4I2dMwA z(1<3l_h?YL2sZz}7Ayhlw0hM4SG)=)%e>pt4%t%v{YCq&H;(s)=^L6*{eJ=>#Nt+4 zH2>Ec7zF*wWl{YB{pp4Zco@-5Eyt@0efZRbOjZ;L;{WYIQxx_`KIe(C=^zoW7Q zG}^pD`EEQBOm17r(>{mUd~3*h!&s&7Xnj9ZE`$Wf$kS^fY<++6F%X{l%JJ3SY=7S+ zHH0*pO6C)d*!r&db_X2Ts?I+-*~*tt-(~W$iIQs{`rmMNzW;G>JgmB-gP!lXt&&5y z(mp8P>-7#mNM(1y{WW5JpKvjotn}?et!&wRJFP2#1hawY`91AD1;pESARUw#*R1b6 z2={BucQ1vF{Vh@ccO-UO>DGthibFGH2HAGrg~_da}i2?}pKQ2r~9 zt8(q8>_G3Yy{joh&d2+s=ktA^t8z^ncA)b;>mF;8J{w~AEwya^KaNu4F5TEcKaXbn z`>MY^$=5>}d`S-}A2J}U?~jQV=3YP_-lTdf|P%8zPDw*BUqn&gz_K0H<JJ3z@=1I_ncgR{wMyS`|?7pV~srTMz3zOSp!CJWR1qWlMc+z&hQ zd!YG##-42QW?^5{->>UZ0Q>$7MDzXAy$i@cMRU4-rIi16B7bk*sT39&0-Em^_^NWf ze(pf`V}5YE2~(2o(Ek38U{$WOTqGUhAk}|yzVDRv654fHg7PmTd47j%B&z?aXZ}Ig z(E+Ib8<(nbc4H!`p$c37z2h~BdAC?z<1(B7LsXTkgGj1!lkM*<4)!Fu9+_x;zv81R z*JE`gdcG%F!oTN{^8)=B=Xq6==R!qdpznuig^yFV6RFepy7Ky1zyJ{gB>{ zpln!+=6ii6F9z++4QPI6=NU|FsuTqEJBa){wb=l>Fa1RIee~gAvR+3~;NPE$&gUwJ z1j5i4ZPEJOI&}xE>#vFC^Y<*XN%-`Bs6QWcY7aPW&_nC<>oM7+DXkyMuW8YKa68Zw z%G(0qQF&tZ6wZqC1)-kL86^SM|_zA$5uDOFBl@5hq6dKNy8B?5lM{@u<@ zmAiN>60Oez&)k5=0ru$qGhH}|f4>xo_U8vJdkL%eEJgQY2GLA#*bDhJg+|%JvG*FhU-wMlmlDfrN=zQLWYE|y5 zTNE81$oB8=?sJfN|AK&Dv47`0EQzhnIlkJ7t>3v`)1c{iRaxtNj#$4F9xWnVc>}+D z1Y5uLQ|H3`Ay3MNs#eKy&hZi@0i{rVS__&`*j_x@7h zJa`~=Z`bDGtciRXKZgjXL z;9IQEoS`Lg+*Zl=nlI&BoWI{#G7aw9+(GsE(7Z+DWvBo6ImT?hwZ_kd9&t}mzMb9& zktr@pbjAlM-~J-Ln;v_>zts0={@&R#ggBm3ruHwMlu7e{A>V%6)&qa}531i=?1IUa zb4v7D2Al7zeF7mYLILGF*K7yue$fuq@Ab#Bh^a$=biO9hX%DC^)kpnzABAkPC$B%s zck$f)aH7%}-CsMXCX2{!>W}L8J?+D=_TylbZv*4AFfL#m4^O51i}m^ZF%?eHEgGGl z>tcQbe0$GE>+5xoRXCOKXxeuco8Ou5>!5S|GQRIDcK_^zw+i>%Fq#J5if!&+`HSwC zSY`hg4z3E~&2riO^PEr>ZkAazT{eS#erD4b4PsfoldrwW_SZEdRJkp$qS5_#%J+Ma z2*(^WKR@dz;a@q1wqMQG=dmUnlxSQQ+z%_}*ZSsI(zx?Hs?SPqr@}6%F3Y{do}aVs zwuor2d(X=cVe`9(%!MM|=V<@z?Uf*M!$eu2&$c3dBf5IP$;}@G`!mG-GXt$)@@cIy zwF2pWEPqQOza18?2Qu#;T3_Gq5==U7QKqBzv-wqg5&*Tm6?rq4R(~O!pDFpd9cuI2 zqx{bF&LWp4nxXtwDeZxx9tNoYetRK{WF?!S{7$V;gN18*qx#%%Ad48UH$&&+R;nL{ zt=)&B^>e?f66hFU#c!^W@++QyvEQS@eHj^p>hJ8&*FoKN4tl>^ z^Do`Ls&M;KV$k^)--A6!`>DC8{_g86@gEg2==s+>PY87Hc?IQnV$4|5A^(Cvf5rKD z$eXE9ceDoWf4M(fNK~pm@Wq79Z{$Y@(6y;U`Tf2>h~&Lfro9!U`51`!T{p-Bh7bOP z>Tg(h5Rt1=7WBW;ME?5jsdZpJOoqqqhlzU^M5;%rp!~)k4uECPaDKa=+75R-I-vQN zA!L!vu>(+l{pjXyQ2&YZ`yf7x>`WSf@|&?Y4gOf0py%6rxMUG^mjUQ}%eaGwpz*^{ z^nMr>qQX@?ilK^crSon6mcslyA+ZFU_l`&Px!n>KE<-*RJ>Oy(aUJ}YIH2d-f9b1m z?~ldMA0=$QgMQV4*|U}C`8G4j`{l>bSUS^{?XOFV{y@YVobQ!Xg`4aiOAi{d^RL)c z4Z^S9jq=_5k>vTUvFLou8jl|2@z6Y!@1WNz+?XA)Xn*_cPXcxau9ltDY}FS*c__1S z`BVuw7 zNgtj?-g*o~_tRN!KLoxVhok!YOGkw(JrqkFezW-K!58%QiaIE3ScU3ynY{{k;IJC3bAMnsc@cHi+Xb{z*d(i&Xl^hi=W?~$=pWPZJxO-^+Roj0d zX`1ty?=^k$6j5#_r)R+)RRFX1DI&G+42b+Fyi3(db&dZ=&~$K&W5J2v0b4*iC?W}$q@PB!0T z#;b5q58}}I)3(MMl6X#O=RUWF?(--+I@ewOb}x;)J1|2>uFL*oAQ&LkCX;Lx4a zZ9AK9#a{sPgRi6hyYk!^vPSC)$~W&b1)|ID3-(Wl^X)UQ-O1FKjr;-|Hs1<&=fLBi zuh9Nf@R@~Bd;SYrA7>Z^5eqvt+PXhh+@DfRTnpKAWKn+|xG{*#JfcQ}Z?o&;((VDU z-&_UlPZ`$-lY)^NG~)w%zU-CRb{O_q3)Sy8t1?Nd!5}I(md$rh`Q4!7V}$OPtbdeA z#>Eao`L0q*gJ`ZFs^8X!GRbt;LG+9loA2C<`7oz`1e$++U38Z`4)CCBCmwH}Kk*mk z+ZKn;z?{321ogF8zh_=l<~Fa{Ngr3U`M&-78q9HYM)${S-%{ot`|cFv+v56q+qvhE zoWBO;J3?KBi!9kmpKfCF-NoiNyp;(<^*c;kh3kKQCk^hz_TPUWs1xh!@o4{9uiY&& z=Cm7)tV)*Vb6_aYf6w^tq{F{MsD7_>QQ_1&?4q;6*?f=JBA_65Q{cbF{j0dtF{FO- zRdl~ZTh}SDLHD5`9~1YV_olj&X`{aK0S;`wPwt%qhpb$pXp!W9fR@{QvT4 z@%+gZ_l1z7-h}dBFB?QI_Ee{Lx=Hh~fg*iRwpa`K@^UEuoL3OZPgbY%RHXMeiO-iW z{Ob>P-&N3j+sP=Cczhp3y)N%)&ez5JW$SCVfqP0PwEiv_oJpo?3`X;_KUa2v%=E4( z|3PV)WP8wHl>bq?Q{l?He*A-${dD5~R>jgx5;bWsx?fK7Y(8k~jY9qV@yTc4dgWyP zTe(!f#eCQ1Ds$nsyXdY)Hs8OuUxVFVF6exTY?dC~)LDf) zd~p}LAAU{m?xf+!VgBlMwtlNg{70LrUFiKyC7S>?+`TF2Uy1pS9XE!|aJ+`kmwvK_ zH|CE}e;#M(PP(sXLi00^4s+n5;~R9oOe=Kgn?<_(D}0L=Yiy> ztOjkppHZBjJyTr^p%3Ix|Gwr}5GknFpf@t4e0LS~r#D{mhpr{6DBn-^WRPXKgXyXm zDc|D#vBQeDLE>g@G#}S(%pkrRL(ut@^EtcV$JB0UKJMtANhXC4LHRBmkqSA~lwb8o zI^QbhyOTvGiFY1CKl!uuz1}e&3fowq`=exf-zD9>mQv+|Y<+jrJp=#!vqtqjezh{U z!)Q0P{>0{gj{P-AyWoo6|I}rTGB>!}Zo&PmV*Wqhdj@w@*Q4i0ecLK?kh_c8RI~H* zUmJfx`SNhozw_fBlKJ&3XpY4WCjSnz)QR%kM1JovrDpvS-@knKwKAu0V7Fwx`g-&8 z;`3t-FS-$p>;ja3+N8`G9@$O3cd_+7-x;95yb9eP(Z7B)(eu16*dHOz&-d=NhOdhr zqx{>wSU}Fd`-bW}A37WOrEk&uS(i-OK>{c1(OWy%{98SAhm@b+QT~0_u7TYf+M@dX z$HyPuEKo!1Z>^mf#Qoh6>VAREZ@tep=w_>f^7}0zgWUQ&gx)h}`}6a|c7e{9Zs`4s z6~i;h?6jdMzptA1!JOj$0)EBw;k*B2kcxRjsbUzL-*yW5u`tJ%#+4i->+#D0BAVd(eFCL5?N- zd|f3t|0V8Uo2(yAYUkfT``5D;ScAr~T7f?o*WX9H7m)CwKhXNyY~E}zt#3f}dzfhi z3I8m)UwmVSmiL=*zU=A(cd#7s6V1o_HS8wFKYG%l<^P)fvABO7Zn6eyN6YiqZ?p5a zCByw;vyM7C|NX%sgG4qCr8{o2`L1-_20oU$==rXF8kuC%nPF7*W((h-EvUbCo9%*k znmtf`mi>@HjwB2d@GZVSebD!P@Zh}}IzQ@v=_a|uFQVU7&713I8PFAce&Oys$hbKg z&DZjVR+GYgo^c*mw0;cAX}eveJ$Z% z+dF8!_Q-BDSrc*-)#orBYv_LN3Cj2M&-2M+$^9l92C(bzXU?->k>h{p{Y_)8gcD_N z9m#%eDc=A>zFke+p?}CPRG)_=dx2BAJlg*lKD};Q7E6^3iiR{qXW?VyY$ZmlE2!8POI+2 zmp+LG|}k-_xMmeL9+NyL_o8d9Rk!Q`eQ4{2BOM1>MC9_?JpjeH8Ckd-za^ zTNM#cZwE^CRouTa|MC>JX!)T1tA^!DT%tz2WWIyVpUl{wV6$x-|7|;4UlWRyxKgKh zx<8-I-+2$k-Z8J)V`-DogcAoPW)AoKI55|KfkDNcj_=zbrUD z3&u`)kLqie-QnbbwJx1Hh0Wij1q+~l+3&JZ1ErrYo)1fC;{{Kh75FpBt$!};U%A}d z3MUU}p!v1usT1V;gQ--%F{PO=8PWNvn3EBZ7_Eo$shhtOdSv%R`^zz|735#dTmgSF zqWjPGy6uC~Jp@jtvTASJY9T}Df&+Esc{KcQHA*w4@(cP;~F!iyXKLtY# zZTO+5*!fj-)jg6`?nTemsxbL{)%_}L*z1n+S$a%~lUtQQZPM9%8reRDa|WBx{OXBG z4T-tDlA5_MYWaKvfj_vE@&io!Z0Ac?u=yO|t;CJ%lYriDdVi@J=@*m2Upvg^^SH#n zcm19~JFH>zDPPi+en96#;BO$=q}7qSY*XV|`Ls*& z0@$|dFFOCFb8IzC>aNK1Icz?CW8%rG{(Y(S#`0$V#P^GTPTdNF12xh82I~?cz;a7x zw0=!HuoE=S^+N9_cvDb8+MaYm`D|~u4^~u|3-*(U^QDQV=Sf7ME4^~hq=he`f8Fpj z7vdgSqWz=cl6-0UPA|H>^U0Ryh4WkGvrj>|o-JRHA>~u-UrWqu$l@nOWd>`y;BKeLVxo;I$p;(%x)7|8!jd1-btO_Y;Zrvov5e7&a-Q`O?XY z3FP8gQ~K2T9Fxx_m$$$K<#uR&>TMeVBS9bS|2*G%g0$agL&qc=H2-`M)t{LbJE4=e zF#QEP(6r7I`=S$sVpMXiF zAF8k4CH_~|GKqHE%jUN>@H+(g?cl#nWb>PKP>H+imqhRTu=#a+tV%q)@8ex0Gk((Z zH^Tj59rBepr_dzY$C1r%FT<|HOX(OtZXcW9h?`2>?t&ybr;g3wrNlq})B5K^|GVF23m9ay<3qXD zKNp^FFx89z^Edjazs#GB| z$*{mR)a)-ie;u~_Bv=O8qkLwayhD8XwRCqcw*F0Pa|NvTEkX5f`3ps^&xvGOeNoD% zSpPc2)c78x1|k_%{TvbS_MVll~MoN`_N`^9oYfRU)KkOL!fIH zes5|kU&8%ZZY$y-^|}cB6Xg!Jfz=Q~XwQegGFA%gygJ& znkPTpUCNI*e_elDk$by4g&vpOgYrLq#QCeIMJ>$M^GErsq2J)mjVOLeFkAl$mn(9s zj8bTADLY^F8>vd(`lq4&jkm*7Xn&Us>agh~M55yygxzUoQqLaoX~G>GrQ| z{hK~<3~ayh5bbYFKQ@BA_N(FVILh)Ci1Qo$ zzxGhmuc@q?WXAV@|Na270{&;O+D6*bu2jFA&DRKrdGMUbqWU-UcsyxmI*^Y2ApQB` z{^b{=RdB9G1=YvV!#BfV`Hm=m9c{uvW3nMXHlNMkTa7rFoZJWXpB+<5$kDcV{b%(k z1^kSMq54;JnI|8gxY1c@y_)&)7xf=kaXGMbhZVoXsx^NR?yqV8tcu)wx{iMT#MZz6 zZk&J}Yi6POP0*FwMElcvD%Xb1pYh|%&^c}yKPQaMpLbFvnYLjO_1xCCMZbjScdDK} zhR3)4(ev?D35uNO`n|MIA-n$j@~a7&JfeB6Icz>PZ4|i*qrKGpEt}6bZ&gUN?S4LT zr}X`H*hX&ll%6J0gw~?OC(vyenOr zpO+DxukAm3C0rk`isr9B>MO{LFAM3k$A4PczwhTyfX2nyg84tO zzK(RgO&S!u>6AvL7Cwdb=f{JW;ppw<{E|c|-vFwDe?L$zCrc|AP|cFwEzb-2zUBQG zoIL|jeGTwDOS-zbQ1h|VTAmmB+ZW540RBbuOF{bm1yC1!K9N`ClCSQi3vaXeHaMa} zBIlUDj~;K!<~tyDG^8olqWT-NY8cU> zHN2joYBL}HAk24qlud+_-5SaiMoIY+=d)WX?Lgh&JL+FY4Bti^i@Q@#6*j*yxo+?! zU5Cge)-vc zFeF3^)!%n_kCAwd*>vLSy)DlR`5j#o27a%MP<@WPdW;NdGn?j|lIFKhMf|RajD<X)vSo*l+Hlw*SujVAX_&ao!=j}wU}&}Vo#IKcD9t(Z^HVOp2~)hy%W&=b0daS z5mhg5w0?D6eFEG+%t84MxmZY!>e#XnQv{Lk;BPrkAF z&fcIx6#pJT^IL5nMXq{dDveEH^Bw7DNWMp(=FJn>`kfG`$UWYZN`D%#`5v%hH2m)V z1kG=KyAC5m58dT2>9YCGk(&e!58su|Op@})i~6H^w_J$s9674d!0wMeD6xadp#ybxRGM4>T}3MKmS- zk9J2tw(u+D|IcS%7-ZH7zi* zWSqVY%J-Y^$uRcl2$b)xDMyLTvsv`XNBtJQgnS#OW<%5AiD*7$99u=yoqXu+J#77U z?|cG!RXd>bNyB;<5{o2TTCKw7TS@jZOdqj|UwxpJPoaKqIaW<#I&P*tT}L+a*-mu6 zUgP8=a4ZZ&_1p3*CG`c1=;5b!Y`)XKg5H`~v_BK_yoxM6<3sJwM>Ie0FFIfE)kTG5 zM;+v+ZDjlNVu`;m9-T%_3fO#e`i8{9;tcA~)mJNWa_(t#?pQY8kLHbrxcH}Ner!`c zl)Sxk57lqqoQdGC`d+|ynuzZs9xi0kFFCsP6`SurR(7C#)L0-%fpjU{w)sPCMkA)bpBm- z|ET-N<6xlgDA+G6_U|gPRb=@5O>}o9+rO_&yabmWSEK%YV7&r2v?h&Ou4dwC(ilS4Yc*^ABp5zlL+p?)15+-I-!^F`-#{c^jIvp>%8>t?a_{aSxTZc*R;)N&}B ze~qUWQ0Vy#ov&DxGL)pfy3Z?{vGv`2=0rGS@&V-^8lB1O9c^jr{g2}O%(-d?WR?9w z=PRyWiXc{Yz33UcR(^%^!K0#FVO@|s%6~<_10-lCM?dyb=l|zV#rawF&E>GAy#~tv z@qxvp>8N(U+KXYwC3EDXk4 zbVuv+?n`eForfE#M-iL0&gXt~JxrFpv!#CnHGltQKbks&Ds3_Emzd!2S1aKV37C&A(}g1tcasNBJ)qHk_@^_Zgsh;&+)>13RC4c_M-&dKy#ta5n#5A6?*& zjsoiMl_wk^Ioei~1hDx}^2LC^1!TStlE zR!3^IpIzVUe+`9DtsW@wQhnz|`TOkDESMT;jrPCxHs+JsKeqIE<(_7~c~Sq1j6M$KL!Hs{ zKPR_-Bl9D6(@hoKn)wD1-**OGf=@0K zawfJnaDLurr@eG}_< zdhIe8u~ZYy=d#KU5xq(F^l(5Oli&NleW38K4mzJzR9;My;~nYnA1Texi|0p@E`);8 z%O2=_<;;!6#B_`!1vP0tC!Vk5ZDL@W-vE?f3y&it_9Q-Ek{*%-cP00ydPp)(ss0P^ zZ+r5(h@6g^OM|1?`dv9Y3#i`|ly9%5Jkr%*25s9{%C}g*4^|z61U(nDe$Vp0OXAxE zQI+=U&3uaWTi)mrn8&W;%YU==JFDR)>8`$ohHM_z{Jg)2Z_P=P3kvN+(0s12q7jsb zN%qSk`rLPp0%zlVkm^>l`L0$`CJQq%QNC}=T_ZNre5mYUwm;w3U_jQ~DnkU!l_sCOn?pD*=sfgH)~IW|9Xw8H^nzjy*&eOs!}AnKoa zc`bwC2JKM36^sv&;Z64RP&YQ;W+gt5^H3Mf-#+;i6LQRny2-Njc}PSkBp&IB^1ajT zC~>*&Of?O=G`}Cje1A8Nfx+Gb(fWK~O#w*Y!mNo4Bxrp#lo!_^h7&y79G$@L#A=(9Henx7Z*9nj$t z81&k}e;L&3kA?ocM+zlDvMcD6<$YS-4?_Lk_WS|l{=oU}-zd+0`f-qI{Kxj^2ZlGo zyxLv7x#SFt^!+I8ufcd|HyMnM1DmUKYBJ>-&36wxT`+tw42(Emfv5v zKWp@E19JUv86V=r*7q6@1uiTsof-zS`47k*1zz`FqWV74U6Q}=dCFg)Y<+(eZd4f}JJM?^^kzzjayJJtsC_HcGPh6k39qj{y z*Xp79+%8f~w9h!xgYDV;znl>YmlpLx`46)xB(a_6Qit1mO#V-uiv~`~9IemwW*3kZ z^*H}yAqnz6jzQ9piIn{Q<=C6XYU&Ho<7=G(uE0yn-_ z2K8^l=KJwX0}|rTqkK;pqrfejnn4$&u=%d;WC6Qx)|Z_OmhvG3g7&}6OVwdyOx!cx zyM)bmAI0(D-Te!y?=g2BiR^Ag`r;%ze{VQu1K|ZizIl!-o4xt7I?Ks^S2wH^N6nIEV{r(%D0Rte@i>M z5!QF=jQaQTlf~p_p)1WQWAmM^9SXU)0xharN1#e&6{c&owAy zQW;Y=-(g?$$$w)g598SSJx5J}tJlq>dk(YtE({$B{E~Xqznc^cB|rB*=Z#OW`7ZIX z0>$=U1@muW{T}A+NZc%y=-RVvzI~V5fVZ<`zw}ROeJzbu7jBQG`Ek2HJEWzG4# zi0|o^8^OE^=i8(9D2Y#;PnW5sHa{<}&(E9<0n=N?Xn*Z?S^=?W=S2Hokn%0|?};QD zHWUm(^?R9dF8MQRrhspM(SCugnTfDE(~=)`OIn|c`5vr$m;@NlMfolsnF*I?*`R#8 zCKr(9%1-pyE;Et@$Y5sb+$X)t$}%mH!k;+4da1-w>((i05Bt@$%fVJDD`wjLrYXJ^G}5`*L1gvV-}5 z-%s&=Yl|v*uJmmtEj+>IU&d=BRK0tR&d*%6A4)#bI+XuU+E!3LwF%|lN!gLSevk8C z^wb9SM#}ONL!|y9O{DLAGeQY5>O-fLX*K`-{6+kae&z(6j*7s)i}@cibPrjbH<~6c zX!V!E{<=rrQkc$nK>fSt$W&7BcOw1eT*c&nQ@J-}CF-O4?z<@jbh3M+e23hT>dIy^X+6N&-qNsqCQ8jw|u^^KJVeBPd1LN zK>O!UlH|DyH?!!wt8Bix(h)Fz^P930Nm6|kpT9h=J(N7DeZgyAVC(yIBP(dE{Z?k= zDCJYE?~BsrlIfw!sDD?=nhwAB$O`mb%(sJ&WIz0h-gIQLbia>yzWsWE6U5(E;Wvf1 ze!fuOL)z~q=RHQ#(iG|UTkPN0lr06D;~mlSCo}!_k>Y8S=ni_TnLqJ<>-k;1A+4_g zU)x*y`QrY$;)F+nv4|@HX{Ljjdf}|Nk(DR+= z%X3J18Y_&|1QqwypuDaZrTi#|7f**Vz6c|4Sgu> zpNsozRu_w*{|I+f-zO|9AnT91(1(4c`Yz^wf8cr8S+|MbnAgg$(7$i=yGZI5Y^K(- z<}LgP>vPjx_u%@Ya8%!?^^)i0CT7#HxzhV(#P>h`EBy#w-4po7Us^w3$iHb}TkdC3 z7P{Y{(MOT!j?6>(_tBK+miNo1`=7D-kNVY_On+Lz|L)7ycMTVLZc}77eQ}A+|D;DF z;Js;spnoo|-#;B0LY$wzMC*5r`{Q6z?;mLY&7{X%vd~b44$Wix`?k*0Vb(Y~zV&`) zvA+-N9YBsv?@2QUOZS_I>-R}@jCz{7Yx7xgItY~whzeqXJdPqIEZ(gEQ*&H9@r>aQ=>$$)qT zJHBCLtA7%nZ!>P6OB9?OsQf}{|4q#QIj>?+nY<9?zp_gK*?7T~{u|8Z-~DzatjP1_ zC$4YhPssl-iT+=Bl`XkHhdn=&V0aI*Hb(Fr^;@48`g_|=*T}izK)U0$d&~PnsQ(>2 zK7!@j1pY_M`7QDJm(1U7xhG~hv}(wa=I3pRaR0sRAVp&EHxJG46yLPv-gL^L8U-_VoI|2hkKu5wEb-6He8`SZo+yU(YN0C)R$f_z@gf1=wE;`jU&%KsL{ zaiE^@1NHYR7aYjLvnsT*fX)ApKhxk;jgWt_{s+GFBb5)k(eSlW{~_kzJi!rS>Qx2x zy*Qr_of}82W?9e!k~^xT^|{dB|DL`CwjI{uk4b6_X@5ny|K!S)edJrJH8q;R_V)qH zHo(5)T~L2NSyJDwzBrHmh)HhdS6tu!I2sK3wSCa@`Q<_&g0PiD~&(0h;G|Cba+24Cjah@>9D`2J=&l9xH^aE zzHp#?XEy&C^2LzZdl7oRwL?P@IUv7?zRLZt`SZp4|9x2{s2ua-Etj|QE9Ae!`@`hq zTQ{mNr{Dbj7thz|m)wQ69k-$U`)ai1qLgzeIn1u_T|0h+o>_@}r;cp@e{MosE@?&% zx_`yvivp4S&!YU7B(~+QpOJk2JGTD!p52*vM^*9{b=mwkeQV1t8P|N zGW<_a-;4RzRTx6tAJ(JweGiRsFmL!T)c^mR6%=sUt)$-4pDzq0j06p5@GPUE-!Y2io6f9#dTu)?Yne`G70 z|LEMEq{?h8T^k_XUk0Ll&-CJY7&5^S_5Vrd3&_O<3+U6oZ2oJ4gCQlqFY5m^*(UonUB%546x z9ZiRJ-DaZxzu*(K z`CoCO1bV#>=KA;M+Umm5mT4sYC!7C69$!JP-!5+aKUhm$=&GAW&d0Lz|8e{3W4Y5I zF{B$i|L-jty=Z?7EyKTUgzr&reb6Y~8rMtjrH z&3Fz8(w6pj)AhUi8KDq$Z~#~TJ=z|`cY5fm=5DlIWhI8|OJC76;n$93AhqC!^ zV7DKP8c*fwe^%pE+}LRrNgl`6|L?PoLaez9SO4?f&%v7g>ty@YXuj9?RTrktN+)+a zFH!0{J^wn%A$ zarIp4W5dCj;;i0mzAtT17u1T<$(|5)e1GR)YdmdSECwjp`tFcWli$2gC(Xjrx6=CVG}9EVKfmYdd+#9vjGtD?<-1hh4i}8lAenR6e6LtF7K9n~ z#Jc|4XOw^cA!<49Sk{p=87}>NK>7E>^k+cH&ZbP)ttX4mJ>cL;#&$-TJs`LSl{ z=r(p9nf!pwx8{;i_~UKC<$GAYgSeope1FaV(f6IvFzeU|8Q*mO{HzJd82oWMdF9{S z>VNqUo!@7dCPDSBsoecF8DXi|uKOJFxe43ft5=Z)HeD8qpX1p2zTi~`R;_m+i@&~6 ze*XW_cY|{<=GuC(y)`?&?_!vVKf5d-r+Q2JuAusB--&l2Lu0ErVo2S2d47Mhp}KIc ze+DUA&i41lhkSvRVR2l2@7Y6L819fkDxKN+{mK^g@!Yda@lz`{|JPj9h19GJ;!?=w z|M=3@7-x7vJgFn`LF>Eo@|yZWQ3lyEm(BmqN9J(9OR4OB9Gd^=FD95%{(-CSHRVC* zbhV1>?@d-r!&dG#*@~|1EQsptG9|yXzaNwA3<*9hx&B_asBknjwjxg+vH7nz#}^Lz z8gS$L)w)N}!qSDb>&@nW%{G59^KlJp?#Ju6aV9Z+A@L8CzZbA836?yV#^t}FEDe_i+mm;@W0d^T z@qJ)=7WhtH#MSrE*Xg(+&w*4lXY>Cfpb)yu_Y*5+^>=xG?~tP=G_T4aeTT61AB^ro zn>|~({{F)M)C9rc5K#?b^Z)VnXL#B_UNn7D_x_Ok`zC7Y!tptWNW(BT|IuPS+?{+_ z9NUD=zgm`>Q2Z@}cxtoxFKN~qGu19~^}l`pn)lD1LnPLb&42UV=FoBUH?ID_O)!ob|o&VTC$Nc)T`X0^ylTvTozRrNCno7SP zn*ZiL)4`@nlbhe0R)t{39}6PqLxYB`xc*+V{4iW;WktrcV)L)4x!?ZC zl#X0~KdWmNKG0lD5*F`PzJF+c&uf`K%sSee>+fCqvlV=B5VwBcbZ!d1?8N80UgK!^ zyL}Y5e*f7#8GppjB8dtqey90f-C`@j}+czfnMH-E2jcX3|h&s=>U ze-L4Ap+a;>WApuU>O|D&*M!`kSU2CIEz@sRVgscs8;CKo{dRJF_j30_v&{x1Vt1WC zD);Za@7O_`n)^9;`Fop#!FYGR1(_E5SIHO6_rx_$@F234nBgUTe*n3E-^?`(!J}fk|EVK){{4#L1VRIEV$&jt$#>T_{@^gZk2rG^JAXgAsQ?GtZ6Lv+?E3xd zBU@p9%fVd!i_Q1rxOsB_p1vP%)2k?$cF>yZ-#56Gj0tz=kjOg{|8#tBt(yc>o=oTF z?_-_PvFE1+q)UXUd1Y1b_)BgSC2?gM2xI=>GettPaM$|R9?Y<=Ig{tm?c4CTi6!3)&{oBT{tvX`yzkD7djEAa`U_?pfC ztIcXc<-1JsEK1`49#y~V(XJkTQp*wtzn7kGn*VTHHNh<|lf+oE^}Tv^D>Ny(#MSq; zFV%!A^AD5Y(`^1#oXw%Z*B|*F2Ga9S$M-JRjj{Wc&*GnOseVT9r+n}oU~@ecvG-!> zJni4@A3q*DCpIP_CUxiK{5N#A0ejVkGX80O*Uz(q<-?kB>vI#!g7Ez&3*ve150mec z^PJ$leQR#~zQ=SsI`~_W`)5Vv`Tvu@ulIq~w>ok2_ctw$;qvt!^X)lzk3iIVSMGjwOEDFHsxKfRE7<)0TvGsAO*hK+tJD0R>!~KJ zay?9@gh>2q2=e}$#6fqUPvkc4{;E?&s)F6?Oj6LB&F|*3p8#!lbMy0(d#XZ2WhM#! z$M)ZIo~xtD2|mBNxfihU;7w%W(cQKFp1l9gUbPioA9GnOyUx~co5N~?L)#+Vod`H{)9VtYq@4_`Aj!zm|UyqvPxNlkcDWdJ|yb4HdC&KON2QFUzr*yrB{C zTim$z{VL~o!G$rfvgYoGy8e2a-+E2m@!c>35-;;ljY2<@4=fV2^sQ^oVfq zqLMErTPKge>dw`Ch81cLVk5- z=jWOE8{v~iKW_akFu&&c-|k3$HE31){pJ0)^SW(?RoO$h`W;=p52vi8{5h+ZvOn%A-oqCEu-ja>7`)z6dr*2Xej^`id_TRLQ_zzmP+s=*O zWBgSG^|Oabm@%9GrJX*(fq%QX`n@(;RZ#hOn7nBr={Mbf($_f&#qR)GvcGSVvzl=F^AVC%z~VxjK;m-Bz-;xy>8N}HRX@BTdpM^4itEA*uMOKAR0w>g6KRef&#&8~18 zdMrQ^{(;T^BGC)xIS4{PqQ```POj^EexP!ld5$|55zZYaM$ z&Hp#ImRM|XRn)j!$CsS{FD7cjpwn68X$hPEd0ow6wmkkW8iE_BeBd#`h1%Ijt}Q!VuU_PUZ_z1 ze*CEV+=uXK5MZVw^XKXLnv4I`BDD-y#0Hj zx%F)B{<=L6)6leJA?ZI{(tkRCzjNgrU{99Olgv2q4T>bz5?+=fi zS!DWXHvf$WtD~*yajrlA_@}CHW!X_Oz?#GVb3I(N`>JRk%jSP;jepra?kMqU@>Ti% zpzHG%+5I81-M@UpWQjjNivQL<`{9DXZ`}J|uAa7n^R8;#_=9s4^<)j z)=_fq8=HTH;v;0~?dA60m+e#)8rDBX3acgl?J55*{f!z{{db(J|KBgD3Zra~5xs?M z{*OJ-!@oDK$@JfkivNe+R22?PKSow-viWzJ)*tMQ%eef%J=7QP%>OQq64?4b!p#a+ zXsUDldmZ-?m}JtBJh)RAAIbR-w-^nbZ`9nsR6Ac!^KU(4CjLm&BgQ@I{C9c$KPYG_ zsEu#VjsMRE&Omi7JyJTD&A)o-d?2B1x&61Ro^8VtgAwGEspQ|&{kKtjJ!|y18@E2+ z#yK2!$61rGD-!O}P8(uUTcGU8paC@($AbgVO)YPlKU(oRwHqz>fb7 zi;~f+wKJFhp_-9ko?^@8zfDRSy8A34%^K({`4=huAEUAtu6CZw)&F!M4_ARd`Lryf z_WdEhA3Rp`Ff`ii#ht&g|B;Kujr_^=mMTpC^)vF}=D+~aE11oHK_^vV&(>q4x=P}I z3g!Q0?Y#xMx7967h@8zp&y1{LbIYov$~ki60W593v_^N0r~7=HGX- z8Wyg|7I!_Y(?|LJ!cNOo1!tAxHS^bO{#SbG;neW!VsWmd|1|%DcBu+WjgOQ3ZfyRO zhV+Mj`^)pk-ec?km$`lM`T8H?+p%o^pQl;E_POdZ{~oCP|K}e8|ITbccDmL5edPT6 z%^3~1FEKi1Yd_()XwI z-_C6V=x3X90Z1-{dbDVmp3cJo6C)bSF{4WsHa4wwS^6zb{DvbPe zoY<{p^MAQa7q?p8kj4Kr|C=3Eg-IIOq^ZE>pPV;?Gtm|KJB!);=N|2Y@AZF*MoroL zKdBxH-SX7My8EYS{xduT%q(d@il^26e&zgsO}B=(HMKon{{JW378~x-BCX;+)IR@m z{?|903ODbxkj>xI{dqfI+hN5WJ+eAn;+Ky96=UYZ;a2Ur{@>CLzBqMT526>7to(dh z|1XAkK>jR4F<4*v{n7q^_Jy6;|MhsX-*vO}{VD!)a07IUH{1 z>>0O^tM9YDc7oxO@mzhM`|$)Gk6uq+6n9nfN%MWjE)mL_*mL#$c#AyDz7jxYsvT0E z_oL!_OTA361Rv353%mdJ%q|rnpj9@Be%Vjri`tLX+dU5~ngohQ1M8k2Io~E(D#F_V z*(AO@n{UO*n=mP0hq&`w-FZ3RXG&BA(Jh;#^dN|Ow!d|S(xobN80Q=qh=F1J6&_2xu$UDljPa^ z`dUrk@}KuU2^Ts$lf-*ceIICjf4&Enp0O8yY1Q#7pRb>DBNwe*0!eWjHvb0shv1Ec zFPHy5i;iK(zH3O@bhf|WZ+0GRyBH|W@TlWg&i_aU6`}E?Y_7gPin|HL6C$|&9vZ3$ zYl5>$_rvV?erNSNP$x;;`u^C-DuUC6Y|{L+l;6|!y#@uU`26xoamfpIe823EiqP%w z2{QK*n}0WTU7Wn^rsz4G&Hsc(s>09`*xTrJh(fUq|zw{&^JK_Gv24wqWyZ7BvPZPSqmsd%UaVQ_i>TxXG~HPgm4em(J7r z{m#b+J6ZK2>m#4ko|p4&-OK?N59z>--|HRo!eEu2WZ>QdwS39r_X~I2p|H$|>)$(1 zj>Mm1CzBa#B)$-Y9Yu z6qm~Rr|0X8UW~z;qnnZb@7etKx0noD2Iz71{mObToG11q6ZkV`?;YfU`{v zxcxgn|9E2Iyq;vvVmAM8mbgQMul zsGsLcdOm4edtT0eY)}wP+&hfRe|pap+)?btSEji%Sa}sdt;tf6e>D&gm4{R4m2! z3hW^3?{PCQg?~d8BCmcI>t=*gdVCYxcVzP)p%@B3#y61F?`VD3zSbY_8L5&Jj?#Rq zNb#RJaTHuRswwmD{HXcb$Ax3ip@%lIT`pdT{-F$8%e;@%GW=bFU4x z{L1;)R`-L-u>-jM_r9fRc%#6V6!c^BU)nJU3TF=I=J&m?rea=4A1?puLnENo?MYny zZ&|euUpXuypFXqs?^d-N#FPbMX_q>FOB}W(~;=S*kL8*hjRTljmQ9J{pI2d z-@5a1{a@@*gcs^>BOYtm^*hJIXW>8H&0>9BHvjG4D1_9oQ)EsOoB!LxZh(V+BzJ#~ z!w-d!oOFs<&SmHK-tlk2;^qOae}A;SijeXA6nPNL&hP!3s$$}R9B%)f-!v6rr}1f` zt8=r~-;nq3F4bv)C)NMs@*n4}BD9=xn*930=D$GQ4A$*e5skvw`X8KPgoPizi$<_abQC{d#-kY>EWAp#1pFNoQcI5W&XlZ-kp&q@+muvf_&!^_= zFMM@{%Dp|f{ktD7gy7SuqlxwwKPLYbZ`MQL7z?g{r+qIK=kN6;GNT2W#S&hh?Y9p)PFxHy1U>0r&X)hYe8?)^^DuW1E&L-ygL8&(So4 zo10a|oR@6=t!Efvf4!gLmji7658N3H3wk!>`g<{J&2Z^GRnqH##6PY7sw+mq_h(vM z{XaO^3=bYuB{v0$e+8xgW%nk+VS`p&{>x^1V|rF!62ACpEr0U-|Bd-PSa7o=H~&{r z_rOOZdXr0C+4`Ro)=_xkhT_NC`B+-t-`_OFo4wS? zJ&^dO^}WN75wOO&nM~j5_}*&18McX1Bk3>Ld=F?p5xQ(`#r5|tRCuBDrhcU5b~fMF zlIFtLMV+|wwGT7gu#H1+;upcz_u0K%VUKk$ZhSvsy~n7+uLLZ9JZOt&F{xI z+lLptT#0QXN#ALIZ_lR$$a8V#@?9}K0jGyKk>E*ezCSKchxt8LapU{Ycdpv}(lFZ?#^g=)FRX1U&kud_HOY z)@nHdM(l1T>%XJlJLi!!JyL>n5$m8#1=weJVHe>d&(W*D<-l=wBR?z~*T@7GU3 z-S$gm@jG3g(|QvQ>)TG_@;!LRKJ2&Coix2J@lD6?dy*3%eU=M1f4^^;fDVPu#B&py z?-SbTa6w}=*T2{Fy^T|h;>fp?Y`$MFI0OCtg1G+ur+{jFwDt^93z7Jy{kxoT*Wjc> zG}pf`Q78nL8a~==Ve{P^UxSIoL9r~K9ltx}RAcJ{XULB6Y`(`7D=?|ztXOuH&G*#R z3ZX~nSu)#~&G(v5I=DNbL`5QKeul;0&;`2x%&Mn#uPJmsT0kIY`zx_nEd z`n%zCKHq;6!=ays9XCJE(@(;n2cG0_qMnuHugUM9Y$YVXGK+;={jRv25FIZz z-y?j|VAZkJ;>1Dh_yvWD;L~irPYhNFooDBg0~^?UKRu*_BVzA~B@5Ynr~1_72bsB~aXOptk^)0KSN&Iv zA0wTo>u*M@2Z6m~W7+&1&G*Iq#<=*78c9AS^}o}6Uo;;MD-*P3^RqztZ~fDZ(eu6< z@hiVpt6%c^dr;(fh;OPdmX%2QN$dCfRh~Fuxe58Oka+g!4@^D*V;)BW>TCMdAbCy(1dd(=cB=#9!F6}Q=Z z8}HY_U&;4HuRRiR-3{yGd!&C!v~$IG|!6r@k* z>ho0HeR#mooBTJ9&F{;Uc(~kTF*p7;3yQ-v^A?g-55tuDPWxwf8l{0*<8|EpI`+<9 zbiLq3(o|k3&(rg7^?#oRjSsH&v`y&E_|GX*CA^mq$jT#IGkc|F)vB0{w0Bx&GPZ3)Q$+C!b8d$>z6@ zj}Fee@<6;-DDg-0JM~XBI`_{f_7~au{Qk5dj?kzOXFrwB)BG0R83?oYHj&lG{j5}E z_4n*NV;mY(~OMKuWdatc>Hzc^G*BXKI6uNV__Sy)KcP0 zr1%XuH64fE?L_L!eE)Z15q#X$m+PM` zs@#IAk8DYsX9KN0Siimp`Egy^KTGTLxRvp+rt=c+ew&|`@p$F(Vp4dE zt;VTV!qq;sm9QXlE~ zTl?P?2v*(2-A|`qRE2qN`NTjwQhA=9Z|U*k1vFfl#^u|naWy_q%qN$pvibfRQVou( zBA4$*o2&6eRX#b_U^jRgc8qFGsr06r7?<28>xP5Y^ z*i%c|KSlGc`rZO^@|wuzS7?2H)Y2H|-K|HqMo4@sP~QJ`!)zGjY-%psKS%TZeYz?7 z1velX6K>V=DUZK<92o~4&DzT5*J!>W#}%KwH6insOZ{*3{7ScTvtXuPH?Dv7d9W)k z++sp5A7IDdHjNfRPP=|w{eJXd3qE}?j@VbS`R>(zHIx?*<<`HhU5r2=nK2Z+ITJH^G)mbzlNvb#oZ9` zw<Xv zes9=cg&({`^30vhx2aY&gcgY0{gV%VRN;$5BDtc*<~yvB4wjyI#N~Tu&uXkL5lLH( zZ_1y)8P)$5Rcwggv09uN#O8a!3JVxESwqG*t>0U(8RLFzKq`7m{cUu9{qLgyVIy0} z`rB!~M`;M?9N(O1wtA&}zJaQ5TbqmnqX&Gxf4VNhV`0YR)$0ef=jHnC<2DP#58b%_ z**-H@)X6j@SL(6#d(P^G@aZ0(?~yuNaK8F@65f%`_n^R4a4g)C%eT?@2(-|3AkO;i z{JPWNO%Od`ELXoDeT%~|koULJe4i-W4pTK|ar5h2KN4{LI8Tz~#pe6j>NwB}bro0C ztK*Z(uQlT_afuswHkRGrqEmbjCN1z2W9{nB%j?@6gd2Ex$!?~>H7AI+*4q% zWh*y6_cgqZsXG(MAA!wxeX}c|IxUWSKa~5UO0;TAh=VDc@6|V-!-(Q^(cPEL_r`Mx--3Jum0;!~f^ccH&FPMrT(e1B2WZv~~_ibGZS zHiwYKhHSoPbu+@DDGIWva})7@`7^EGJ9=2atalo+`4pP(53P+c$gcred{U}!(|kYf zDu7o=3t9b(=G)Foz<%djkONI#*YYXX?}N6s;MJm?%s+cZ#pgFYoN#eSUs9YEmlF< zG%Id={-}oUZ;tcHQfG;8IzE5?y5|1qS7W*LuckeA;mx;v{f^qa9ZL4j5-UR4@%g;# z8Q8!gfS4cbXeIe4a{ug>RUAAHbL0Bsj%VX=?Ra-NgTJ3=5CI!BsM^P~LnT&Gizs2eJ_G-T_yPF4j@oJNSp3MoDhqx5^|%FCdU8OQBk zpXOhIlT8VUI?c|%J=Z*k*uV_2WeA(^CSNM>ZvY{~8%liB{+Wwb70jMr!0lhn=u(CI zybFlGjl_2%6`y}EYliv{9*g56*nB%qt-^QF1>}bvoA2pkjPT-TVl0QGEiW%K1U-aL(g?OdL z#rD@uhOC6JM!@Ae>qP{1j$c4*lO(=rf9=@uKp1?{mK&e{S`dq!bX~drT5hlHpf!6o zH~&r@nt%gUy~)Ofl77?mZH+&>VDkoduD>?(^)9q=b|*LQu;cT_zf+(IZs7K(X-_|d zeolcT_0&)0`-SFva_UKFJ}p#y^0w~%AfG?2uHmbEe*rP-?=Hos)O^a7RhMCARJ^F= zUdN~0AJ3Xmfx0FI+#328=^KyT@p>`$q$}b?!{u1A`zgBgk5?)#s za_@h#{auN>JPJv044dzgbzs&M%7LJ}Cl=6g6A;meV#q~Sd_-;=sp zz=@rj;+6-JzeV%?+}IdDnlvH@ezW;5T8`j%MVFg@ivt0N-EBdlJzv)HDcA24V{L)_ zYA@R#N$d9_3rAGX?nj!tvGx0MubJ@hvk`axWalndBqjsMHK!Ei=hObV>ThST`p<-$ zfA?J-gc@(AkVR*u`4f8nH1+uka6As&_&h!^0t37qiA93MH?7~sLSPM_S-~ zDsX4`Ir2S$&9Bv`r|`flldI1|Ln`n|?m3e6ht2QH*b1<|c#eC2)896gxTnu~^8Epu z-w}7T&|Ci*SD!cPR3aFjC*9Ap`7KH`#9Is0$h$vmek;zIgN{&hKT_TOYgGL!!ml6t zO>a!Bx=8%e{`j;AfShl7TzyVVvckLl^~l%DY<(7njfDsL2D1BGXnxxkO~FG&-N><` zi^}Jpu75pkJ_CeqJ-GW{vW|LVpTU-7>a}9 zw<>8leAgGa{bx<@;Zs3iMAqPtF<~SH}Nz{M}$t1*qRUFAkX|^>@N2q)m`F!QG;@!r|2_WR5A+1@z-?8FIt|E%F*yjdQ^<$L|7P*{3y zo{Vq$e&yGmvDo3W7YXPt@lEH~F>_;K_zf>E-w%JsV0KOaTJ%(jZ`wcW?U@V_{r$Q5 zb;P6;)O_bp3LMz_o%}r;4tQ+m#@~&Gmt%R0A~N$To9~hTU4-&Bdqmt`7eCAM>u+1i z(blGj48G0gTjS;v2ueB3^~ZhBmE(X_Mdao{Hs8C)RzTS6A~7_A&G);O6{vEyh;01D z=38^T7OwvBT&G*>}6?pw!5i#xjUGf*G`d8$KZdhTbPAn?fe9sLY0An_3i{0Yb z@i!bX#uYC#$mO3^%I7nY;=64xfN67EiT=(~eopgU_R$jk?OSsBzVTrUjD2aqjlVB+ zoPi-my~wzmb^WPwfBd`obeQ4Zlbc^ZH}k?aHTS1(GiB?y&1FZ(bm`BX?+z1VP;HPm z>EIi#{Q2qoQ-^(82J?%Dare92?iGW%4=PDIDF|gF5lzB zLZSW|d#-<06&8zI0(^+>E{ShizwedDK)o1mab2nO_ow?yKQ@m=lRR&-zEI+u?oT`R z?*LTC_;da7XGfB8aE|~|pu*;R-^FZL-ziM2YQpx%ZT^+vp2{LJvZ;skd{h1zalZ(^ zv-gPGqS<^~X_sR{vtknZjLo<4$tUnK@(8zoyvnH@uT3r{>a*E=Pq3~4s|FXubx$O| z0p$CcKV_F=pNL|TrGH!b{b_&v?jKF;dg6uHW&@k=IrqwOZDuj?uwe6jEuHIn{*BG77HYI;!s+oLO;N*Qo5VNmpRE|0 z4G%VjiEm2l&ddGrHXF(?si2rdc4G4#{qh1dGD#GF*6bkr-_Hji*YAOc%W%=#Vq#p* z=KETQC(yKG7Po)JpsWnLcD_(^KRBCj8|!jd<#0jly;tI!j?Y)GFUK{Z7l^i##J5P* zzYZpA;?#{VxqKT1mZR#9n)BWg-v*R^|0?T>vF7!-{+U_L{Kn*HP4cRlbpH{p&;K2; zgqy0Zx%KPFZC1D^w>9~8kzKz&@TBJc74=TC`7Q-j-)b2>2`$vSlUqS-enX7ypy7#L zTzzg(bARJ>O)DahG$lWN)O^>G6AQq-z?`ek&qqgM?|mL*&41gN{NA=%3T01*bLTg0 zJI3G*V_%Z-iLK8!Hv7Y0gUMWfY*Xq{9O}58%WscwTfuS2d|CWW^E+gJ3|6QuB?}ix z`V7?m#X~(};4%1${twyw-uW*YwNLtR=RbxFJpfa72XOtfuua*x<48E!(qC1nPc*-s z%8tV$t8i|9U9Wi=W*xskMonh(>o@-bINj#+>ocbe-AgZ!b3LMJKVR;DuTOXkUXQcH h38{7b%j;Wrg)-22ctJe0n9b*iiJG|6>lHVC{(lC$-ERN@ literal 0 HcmV?d00001 diff --git a/core_perception/points_preprocessor/test/data/input_structured.txt b/core_perception/points_preprocessor/test/data/input_structured.txt new file mode 100644 index 00000000000..45716fb557a --- /dev/null +++ b/core_perception/points_preprocessor/test/data/input_structured.txt @@ -0,0 +1,30 @@ +1 +1427157650 +349046016 +velodyne +1 +55631 +0 +32 +1780192 +1 +x +0 +7 +1 +y +4 +7 +1 +z +8 +7 +1 +intensity +16 +7 +1 +ring +20 +4 +1 \ No newline at end of file diff --git a/core_perception/points_preprocessor/test/data/output_ground_blob.bin b/core_perception/points_preprocessor/test/data/output_ground_blob.bin new file mode 100644 index 0000000000000000000000000000000000000000..78c46896c83b83b2d84929851af3860224094463 GIT binary patch literal 269632 zcmZ^McUX?^`+r76GTvsTlo4enQBu$Kx{YKNNwPQDgsjp|gS0nETS+!)$&Qq)GRn-} zE5h&j9-r=duHSJ!{_)3kyvBK+*S_!PZtKfvtXMtIB+>p}UiuCN=|30AfB*Mi-9Mc% zdcx(^Url@)UC#YqyB0c$jne-oO7Xwjtu~d1f4N#ucu?5LY{WJiA72>_G=6WoY6h+U zK1NSi`P|hkDpFNa=MSA_^t+#k#(=T`W|pmKy!&B2;f{KqTzvlHXbe+YYSv-_jX&?9 zCs;PCH51O${v)!Z;m{+{%twR9U$g8hEE(EOa;#?&nLmsD(fE;n$n5@yyJY^4AMYy+ z7|kRN@$cl~KfgN~o913KvoEFbpKJRH4%YMK;`fC_@HfI1;9gk`%89tB+6CU+AD{Xbqk&*=I}VPZ)O|^Fww@6nZ=!@xSrM znC$q!t}#H^UinEzKaR`K7qe)zd$dfF;Y9PR*A&9zW{_mw?`o3YFIZCuF?}adY*{D~ z^}ERAH(6T$;@g`f7M?W!iN@#gA~jl~u;~TKzq^m7U{(4{#y?}S^Gn71C>+vplZ>vt zBi4tT9}V6VV(Zcbx&E_X4G=E6|Hm4}Zwi;6Zo{MTYk`l%J%skZ&Z!X3?xah!oIa8M zdvqEotn*Zp%ip<4G@=IVk@PjD`6oveVrcGhi9);gB!5%;fx^Gc?sECV?nl9LL%96> z^e)8A)LeOm(~W_`8Hc_y{D-;xc)g5*cBr-*Z`__2d=FzeQn? zuuORf3+Yx;*MH_gw*RQ<3=(#$o66PSAl1KeIY|kdS%SMy~!8zbKSV zJSUgG&*Agf*z|`)A@@4T|J_tyNYkGqmtV3a3J=>|mGnML`ybt=5Jpe`N*X6B*Uyg~ zW#*SCl?%woQDFHMg{1y)YklE>#Znpld@jG!JfbjIqf~Bwdry{*Z^fppscI`yKiu{L zo-a^j^B!fB`td3H!rtsPa`kJxLeNORMDq7@Q2qQRJOBH-7Gm%{B^I?o)OTUB@jv&z z0AI9Z3VJ6<{f9sG1@Fwwa`l_f4#D?~JCbqdX#HM+A^7q0j-*F%QN2Ie{b$zILX6t1 z!ft-0{f$k(fU=vdSyf~f>94roV8PJUMaJJ{u09>tguu@Ap=3)Ot#2I>f`HtIlFPcm z_5Nh@cjG`j#)N;Cgk_zm+h4dyWb>yq;3A3-wr4Km5=eiMD+dc(Pk6}nSDO`r^!?8y zs`}UJ^=0!DS{;G|U!F-$X43u|FTaQkn=VXieJrW3eq^v<_hqMC{YgpE`t^J(SN~(r zP_%mYRx(~Aq~4!wex~GK#QtOrHt%CFsbBVQu<#&zmyCW1SD$&7A=vi%lid28dmf6b zPG2RN6GKUT@3M=y`azqyJl{j=$J-hR{>6dv^*0&_!sam6YS@dq`tIcRkIT=7VDOM% zlG`41eSQuOMZm9Ll8#fw{4j2Rcs$fVFnJ!uYR}R9H&=w>iFqRyoGs#AB(nJp`DP$Q zj^D@pm0yznDkDOndb=sR-j>c!+pa@|D{co^ekzSWV;_m)!^+Gx>~?*AW&7WElSssv zv|-V9bi3}>A%eGl3bXqBs?OgYE`OIlgdt>STc$EGyq;e+K8x{@Sbga~_Ix+ZzxLt~ zp?z>V(`x#L6*~|E?o_UTb@~LZyRJNXq%j2hil)}=|^z+GkzU`hu5{( z1%bw={V)^;UCNcw|H$e4Wkq1&j-D*}`>p!?%hvaW^-!U*tWYjKH8}zyXL_@de`&mf z{ZK)%^b&i}?Gx#L)S3u<)bGoB9HH^^lZOfm+^(?^?LXJysmi(Z7I>Y_d~d0R&2=Wp6DVa>S;nfxdSvgZe_ ztZ+D*7_!sJG~Q%nIO6S%SmMu{B>$_^!-QTFDw)!V?{)rCxcGPUG!nGVJ!Nmb?n?f5 zK1$*Cwz3~N^j za`6r)jD&Q@ckETidv*Q}bN)`f3&SPNG0dQX)-QfzBvkzV#Plc8_%CYV$Wa-`{#c9o z<^6{bGZxxE|IW@t(0FejW1*Q=Ewg(?w}%f8$M#;6*ryXT|Mom%!F9RPprzP9dH?BchYKr$8^dMRzq2~$?;rRAtI_vCD^Z(djEKCY)hOSz)|KR1}xV&N(dlOINhffbj`KWo!CrxbU?+@GE z3PbxQ3)$k^V*Gsj!ha^hgXSvuGx&a8{w{O*(?b}-J1$`>UWxsK$M@|uLKqd%1_Kw< z_&pCoQBt#v^`9)_`TR;|=m|lJO>u31XJ@ z(!X&UN*0BJh}fFx5897?52wR3|jwXpD@fjr6oIzs$ zi{s|6DfeUX#KeQO(xmg#>+v~^?0kT^=o}#Z3FQT7H!Fd$u+wCFvpHr$tB%?*N*4Xy z(3%jrrJ^5zbJ6^3w^j3EiU-8&qyZyU)z$0QJ$&HW#ns;-+5$zVSQIs z*uN>M>pyF``WVd(gRhD=d#otx^Ye@4*}a(RwVPcqr1jSo=3;1%gRJVrPg4Iw|Ng>| z|J2cN|Ht3IydM*WvpGBE>KB{t!@Y_h$`O-6ITd$M`ero^<{XwmXYYUYU#??n1`5_UXv3^V9iN%p_p{zigb@*vc-tElT={Q9r_GZaS~?U9>b z^E*buKMezfFA(whT>re56bh|vfimNp@1O59aPUc!-lB6Nb~1< zgu+8Rn9VH^$2ZUa;A9S#Z9T&jdeoBr`_nFCp=hWP&T5J4FYo{R&`?Z`31RkgX#RDU z=ka4?A!DBhko@1PjfMLchC_LW$j|Q&vVVpkvR4?ZR;Bqr|IEfMvm7?_XhZ#F&zFZ* z=c4C{JXY2J8L8joa|n#PMaVrrw6QyjSvvX5)~(@wQI`KlZY~;!on!36J(B--`Ea4X zu^GH===JY@WC+YtBjxU&(oUYm$2aGgclX_O{gZ!wb+Bt5RxG%{;*745`lpPB3+q2g zkoAqu?*O+DET10D8a))(f4+Zg_vvxr0w3jAx#zEwW;q!5?-G-=4Itxhk)4MRF<0f@U;cY%Bz#pGiRyl|{=eo&aVRa1 zMXYeI<7eFSL5tD3n3h0Y_{Z@KLV9vc@h-H&dhzw7Gef^u_Px%@HBLZGlTj_rt`>-)#XTzHjcCxh?F z`E#xbMzD6g%=w7#AIsv+1;rz?2wJbpE=G6|Tn4 zmEqUo{2kaF46iwf%+HYK4=*?ZrIDA}gq}5Z`+xra*4KKhP}O6BTz=nW!T7HxiOror z^IJ_jhv#?iGxo-e^k1{bP*^|B5?klc>(9ns!B7fLVU^8k{_P9T!D{Iv#zqez`4hhd zVXlxS_x!ZJT_L=)9y7MKC5ex?IYgLKY9$kYD=xq3FN5$>HJxp1L;JJ6XCNduo+5)+ z;_yo0K^W(e!93H&^AX>FV(kos&oS2M-k3h0&-DvJ8Ovm$H);IL5B&wbnU?7Ku1xa3 z{m~w7eGO7Qh*O7(*?X1Eb>pXs8{hwm^@NY*6Y+9yX&v5$!#^-F5R87?V#M%Yb^Yfs zcRp_?2}0?$!|c8@?XO>28cHN3Z0I~kQvcgTJz>4IC6?QY`uzTNTY-U~R6GNRC)bkt zLBoTfA9RHEI7aJh|1c1?`^?5$*FPlwX3HQ%&N?P@e&y?vv_(%y`e_ZblcGO9KaSbv z!qt(RF(OZ+F20vseoSrzV&9|VGWSP3zhAhXaLjfZ8oj6aS%taaq__?5jWkJqpY%YK zMW2+*@Az0p@W{1BeD51|^|j*ayVQKFpseVOQM%p4`f&dH*aaf#?;+Qw^>@eK@2g`-0iyLw(6pK;v$aO&Sd>GQ3ptnC%? z`2)Xx_{aAWX6DYoiga4v_msY{J8d~`sf+Umf4}?o{T{G?c`VR^?qA<7q@u^2C(I~L zoWFQ~Et7f)d8M=Phw_o-Sbf*UvIXX?+IREJo@?8XuBlDa_9ekXgU@=Qjym_MmI`%W}v6-R=Dab*J?*c>ejz_Scre zJ4qmlhYYC8?>%mQc_!sgZgW-U{*oWxzls8IIIu{res77caQF6V0A^@IS zirM2Jdj7bcAB&FOIt(d)z$++P|JLkAQU2-?LXSaOwJj z<*Ljf{k<&J72aLmio1cdzNJ)uMfpwEZjY#+&*?k+MC1C@7p%?mgQR|7{}}j;sb=f5 zXOa3A9=gIm=k56INb75_*$vlww^(OYv48OT;|E8>^+q*o6hrF|+!_s=;V;>Q^)pHR zJ@fhqRVCYDazq>-eEt{B*^L_;?yz1GQJ>Gh`K~Br9DB*SmZg#L8(xpX+77SSxWO|> z{V4PioZmR(Z62+EM1ME#Y2RZ$!)X26FCy`|>=m2Xmewzt8--!m=}*DGJMbh}hC{{0D&=xG0jEjO7?>Z`cyLfV%K zX1ayu-|QFxo3c0Txpn>hBRBrOw2MUZg17AOL|c--%tTkva&^OnTVj0t{(o_$Ke`m( zXNjIS>hO%~--phI1F3IWz{>jjUrxW3e+2%#e#fMTI8wjS(>_A&6n9KIO6!MR?ISpC z@j$n$bo(V&f2lcoZ79Uy3ov9>#LK8h<>mo0-ett{xzx`DNH-8imD?_6NVS{L!iDbN1t!=#L+tN}EE_Z^##Bq(}S9mxSTq*00Q? zDebSgLQe>|=!elpck2AbarM={>W{Tr)$F&8I6v|EX{H~F9e2O7BZ{>Ch`*uOs`H&) zyEBEX&+SX$*wC(qjY>LIcYfjb*P}n_2~U-FL31PR&rJG!_>q1z7R>BO=I>9jKkjS3 zVxLaY{v~5Vk=ptP8{;7Q=byhkz9W6UTl<4`dPV!6+bSHwuNt=c3H^TH?-?V6$zCzY zSL{Uko1E#7D@m`J?q$)R0yjSmw+V&M-=8d^SoFv5&q7~?BK&I&o3~A@FTa1kS|NQu z#N#(>e3ka6P&GoR9laNAM|7_9$DiNZ&6bXjj&GUrcF`ZdKXot)Lr!2VQ}C;wKe^}A z$=x9g7(i>(>X4|HpO+qwgjl zcgic0f6abBxn!V`BaK#__ui6@*_oNpSA+x{g1e8y_*7{Gc)8 zqg?*U55sWbQzHy^rumyV2tu4y3Z8AJ`BMk@q4LfrcGrdW@Ao7e+nzPSHplw?5$9jK z*GQpEI}J)EZ|eN>&#$fy_QUn)FLLugWL`M>FKG(LH}w8vb+{l5ZhjDHwX}bw_r3_$ z_{KaB(f%Lq4u^HTBJzAh|NQv-69pl|=OA8$(&zU@VZPYm^qpOqLGyok9*#pzn&ae)8kz(!L0!J!&b{7tb%e z{)`t9@Y7UAqEcqw|Hh{ax4zy_V?tE^A$Xe6^l=y9OIo4f{K?m6OO-_EVv~tA*TnJ7kH05bKG+meD>we@l1N0mt6*!kcz)#d zllMg;<-Q7*Jv?0JkJndP>VwCx{xH9DbbgO^ln9q+WubS7=#QV@W@!81gZn?WEr!M$ z{V)@H#2-QM5fRVFr~Gp#Mn);%_(2+vi#riNvk^Kc(CyoNB|^@X;}{-F*Kf<#otW0N zF$|W{c+(>i!NBGuYTncM?{jwI(yPX(459H|yd{EU*(nVCE8_Y2XOikp+~3&*p>t_` z@rq~&mYs3u`f{@W_&<>d(@f8xllL3R|N1Y_|K@==F3)a?*;X|F`P0$Zkl6*bomP_k zX68)T_$3?e?cS37FLruk$)Bb$ZA$Y$H)g`FB{?t|P2)8-c%$s6A_~UR_|tos;QuEV zKMF+rVQ&2i?C%Zrux4;2H zuQ1RH-FCOY^AsBY`vL@i(@QY^NaLq8^1`7hE#ZEc#^+lKf_C34=)Lbloqv9RJfqAL zEjuft+bJ5~d&^#Q+T9bkujSU~SN4AVS@1s0tk!|o=dJbaviDoR_j{sWwKB5vX#Tqs zGjJwkC`^*>)#GLP&A&Xx?5nE~nJn(#`1$XnwI_C^v_hL8nm;PwF-S%8RO|Ln%`J*Dr*$o&3Yw!W2`Rao0{12#H~{0iLji-!w6(9gZC z-2Ukpd=UQ4O%N^f`*d0UFkKG}wQDCAf74ESeLn(@ad*l3K6zgT z3;pGI^W!2Ln_aK>C;R@q!qrslwlKrQ3wP?&Z0#^1>Ua zKE48Z#x#HWI5(vC?tsM~uGQ9Ht$-E?3%N6`FG*`_nPR6HC?-4d_S7sa#0HWOGcwQm-ath;TkTkUxSHz zX?~j|7eoqOWcnAMAHA>1SnV_hg==X3uZxSIIbba&n$i4?O;WH(G8R4?>G&rn zby!!OT^D~97ymn57yP@_1?^Ml@g)=|Be=f>ZjYk*zYn~MB!l%>lT7m;HFUwn_o{ej zF7|)E|D}Z|W2M13j9y6d_e!~f(`pV_vy|o^wA2O1d#cOSFOKVfLslkZ)8O%P*Oz8y zS1`WS2COls`KL0_V?6;rwPsf ztSAYec1}XJ3cbG=H{c4^z1)n-c)EX{T&^u&WEar* z_OB9g=g1VK2GjT>3ySc%xhwXq71vJ%Zv5?>mk32CYuFmm_(7K2F(OD?uD(4I5p!TF zoV;m#Usep0Ko7*Nf0-lRPsqOiUU6|7)(`KFr)hM2=bj|s<1QO$uc7(%FJ42@HV>%H z7Vl3Lxc6t`J4pHOcE_JpG=IT3>H3oCiE*{!^AjF#KXogrm-oP9Z5r=rm4H@;)8P1< z?mzc#9Dw=JX>!MZ@Yn0GzwHIBeDV1duWt~u1uA7d;C)e?ANl@!d}}ejtL;SGy6JWE zE04D|*n;dsJyG+F#%mcKfXM<|Xm_Cf`@Jhh;#eOn`DsV;n-`a0hL+F?gynm>I}DK^dCjWjdyevIdT`e+jtjq3x0uQdN-_c(m@ zn1N6wntz$gCfwD~#Yi=}|J(JCL*I=v<@!_qP>KPG0a#GGfXwgAYx~gLb{2ZQzFpVO zKOY%WxDi>0by0Ae_P^U4(4qMc9f-x0!Sk^3HO+rKEC*kX zdf{$&n*Ye7yHJ}DiGH&Nkn_Xj{p<0zs2?0U)A|Xu>yWmpKNfzvS|6Y6`Q_l`Sa|fF zk6j;Wf2zUju*P@*?zW-%TYip#L5l^jctqoe#l)a*@d7AbquZ5(tZt=HKcsXsB5p{+SNx!WB#W_*rHDJTc2KyuWR-3IGy%)raTI#?kz^QCNzGW zLlpX-UxND|%j)YVJOAe1K7&{XKioY>_n*@XCqns-Dt0yz{rd{C@pTK$#+)*LoU}Vr z$ItI?cGrxDXND>seA-+WKYzdMb9E(#4KzS!13JE`<17%hP!*|%50d%&B}_s=FAW_2 z)S^B<+4;e$;{>oxUC~o-nb^)fpNaLDfY(>M$~?bv;l6K{nKS{npLGSBrc{Twf-JxL z>M=0wql&13j&=Ula`&@y*N(@DKV8w~@lsNM>GkpWJW2y*cbeC=GmbyDY&?!yXkf!t zjk@ux0NLNqRJ|J`9iM85G#2y2_rKcc@vu?Sl!;G)i%&6X0)7-}VpN!zKVIMW(gY}e z(8RG8J?iw^a{4F!yA7pFiKsniO3p9otIWY}s>{@m_qTNF1eEUW2LItS|NdoTv3afr zJZ#eI^4k`&{cmvLcv#nVLqtG#(qFOfSbW=|i97p6d>n`WK43hwgS0Sx42^Fk{e5}P z$5lxEBi;}4>!adNk<#SULwC1$A9OS1y*`%Bi)$hpR&XPn^d}^_O2GG-*rGJoL{fS@9DJu$@628 zzq30wjHdB9XU8ExqbD{6i}N4j=C{EILa<7*4#qO?-^jNmeS_3T zVMvlTT4~1D*GG2!i+(;v`gztKxV1~O&VLnm{;9MNhGU)s?BZ$u3CDsk^oIjZzG-;= zE1RF6()c>)^uovHqJRGV9?R`PXe!-fh4-QP73T%vhQTI`jG^1lFSUT>{l3Uw<4_-; ztp1G6d$4-?RwS;Y@i~uY!#x?&`@u`~c-j0k3kiVVu&v0NOUE}Zcm&!O^~8v$;`cce zxcM(*)NCjX6HtAQ=5J{ofZ##fu(V=Rd zd+YowD9HLx8@C&)w{3@GOWOar^}{i_x);V5$C7wq@GNLw9)%VWm&yDTlA7oCeC~vg@Hfm{0!N;3%O66kWohSKdCl?*HRs{ zRTF<7)t2KwX*B~KHjYNdQJR1ITYoHfafXiv%|Afj2yvx4xa|GAF8_RewG!=6@qIM* z?V|asr0>sV9N7VbpEUocwZjn7p*NT_VVqe5(x}qkY&QFi;2H2C*2hXg2kp8@5Y^3+g(mCJ;&F?(g7wV1N&}1IX zztYM88#HyX;hXsVB|bkt%co*ingyCi(fpxLd=R}{KL3ujgP}D^7gZ(S>ioxX^ZP!F zsaP{|oLqjVwLYjl?S{pMwEw*8`k0z5<+q~wh2J|du$eouWZqAZ9iL`q`dIUy9epS*ug!AA4(=rNnl&++c3(Y*Kw^6i$2{M`C-PHhUFhK@)7 zUl+*!p_}dv#daQW%%t^AlTTr^<56t)p!q`vO-7^I@wmO0=J%WEjbYMfum`ef{-;;0 z@V$5f?4Hv2UhggOV&FtX2hi;slILObp4o8QwXZ%t+5ERLw1mZxiSV+r0=NHPzUL&|<4?fAU%Ve+T>lD8o&?p2lc2kf<~LKD3-gFM*f2`u=j;3MgC}+v zdEr|py8p#BJB4nVr!cdlc>l)hx9@9&^{tJu-z}v+e%bXYQSmf(^*V!3Tg3ZW9^ZPx zL<|xvk=&2=-{FS`j{ft+#9Iyb>$3T^2|A6!%4{4ozh9@%^Z(jD0o8eynET^A>95mi z4>&}6;kY5)KeQ5#A@1EtD327+uRQ0) zpc*fIM=q1rf8#b1xG)Je8^q`5{PVRp$*vevz7wS@X}s>HEa~sR&LX`B?eF0&0g4uu z*fE>tzudzWQJT_s6bI7$Q$k!2Ve5nA6%F^dvg512&0*Y8I*WcU==t}J`bgX?u|jBQ zUVVLK$N%oOE->EXgXBP(|9p8S41>=i;xEmAv3w*pUYde;i^b(C))jOrBL(Utd{&E#QpxgME=XiT3v{`VfvdjepzV;pvMjp0vOG)#+HhJ{NPsX#P=7+pt&D59aS^d@JeMsL>c( z^md^26$=mI_VHY#4WaoT)TCpMNq`pf{LH`q#_Ptg2XEw*8Qlpj`& zpzFI@_aNr5Jh}QeMy6xs)_kPgR3r6=Br~*Ao{ky?THn-S3y!+`p-iCjGv+`Vdgtch z;&3|tiM0~Axlc!r*W&wAeE;gQeKYhcq`!d}LGwT9lm=l;K5EC%{ACj)=-$!}uPSK% zT@M|x-PRwmTWEg2Ff&ZuXovg9XuQ&)O>o%ck57s;-sQU~2B^%y#GowaOz|#MKEIw)5*822NA^c?|D(X|uas>@;N`U$I4IEmwpTge z+M-=JdAQ+zSay838RLKf_jbXxnr?sRoP?z%1v2k%^7=|;CK%~36WPmX{Upux(!0Ig z(D$eLUrOI!aTCsCpSQSw$>-ubJJbZj+swijN1A`ZAnD!Mh}~FfL-Wt?pMvDt3ou+s z?@#8r4~OHjS+E#K^Dk3c2jR@zQzVX#gyi^UzLbK?w7DFmp&iNtsRE3d2?X5R^;c` zPsjHw;q*NKJx0>}9{+~onYYSi)P5ZZgx)4j+2O(f9&42cH6ilaF#O@qA zKi!+@qwSJ~NIp&Tr~5B}L?Z|eFE5e(J8W1KChoq7BukpV=g>ij%wLGP9yEVk;e1SA z5`>vgX#P1Fk=XU&BG!(i`A1(Jh-K>*$*r$K)jUi%9R%|SG{0)|NElDPgc41f|5%fO zICysvO5&WJ;#Lr{R@3}DHbh|hwM%H)m*$_kc>oH17enTw0@yQKg_+m z1mVFnKdYPtvxC9N?n~osrQd(OReA+V`{?|f_v#BxEJd%4G{4(}nK=3~7#fXe{%@D{ z&@5&tI$P5Cx6-{y){YP;d(-%ZeM8YA?<(%wiRVv#eXVV;hknvIaEm$3KgnVSCdP-z zjlYHT_wmPZ4WZTI{RzLm-nQ4pY{z9dFo@>gGsF(#Plmwy>P2#Vp7;@p!U@H&>?l58 z;{Cs2K7h(fI6Peef~c9tGP){|emu z!>zLe@UP!x_}-f)&aZ;(`R`5CH2gay{SEm8n*YALs&IVuG~sL1>N-6Cefo1cy>a@K zJv^V$>!Z!&AT0iV4fnUy*Oz-fQ!~>Bk{tQ*g=y*FUAjHYC(!(f&jJw~avlH9)$?=v zr`lChVO>H*WXD`oaqJb$3{{h<9frQh&(rTLGJ^Fz~7 zSFqZa=FflB9c{*~M1LRJ|G-2`G&Kx|K|0N^DZQHrpCO%}i>yiiJ|nwhd)Z1fiKF>* z$4tTy&2S|DZn(dbt?#EBK2Y9y1y=Rn_lV>2ubrihYWr1acai2d3z&%cvEjHrj`nZa z!3SzLuRupf^w0B;y{?4;Cs)bMkM5G4=-Kru27M5}Pr>6q7-%7F#%kO>LHk>FVgj0c z4@aBXw7<8PyfMw`Dr%pI{QUjuX!mYt`Cv6R=Fv)@zrsS%>2Xm&(2<6xY45sZxd<%t$L2bmp2h|$HxX!O$_<8 z2HJ1w_+CEq#MYHX(!Vi8^CxLZpB;9J#PLzIf8%``(s%dP;zwg~{^tFs-r0$7-Aj>W zC7yrz^(DY|EWWIWlv}@EwOvv0eJuw5NAu5Y>Ius;*Dz$E*#CZU>qEirG4Sddi4SJ< z_|R?96`lL8lUx6&E#8=uSql5V;`xvF|F6jyoDYfwqG-WgP9qT$4qid-cKi~gyYE&_P)q0p@(s;WTBXQ9%3I&5{{Wq;t zQMqS5o?6rRO{M}CL_}fkY#RS{aToY#JHTc=jb9Po8O06`GV3GXe_{p#H5a3BupiCe zXQmsvWS7G9o47yY>*M&V6OPn6AbUBjuQi&XW8-MptI_g&&~|NT=B zLEA`02pE5`ZvNKd-p@NZq7&xYZ-B-^TEFuG2^^+GBUFdhzkb0D?KN+s+e&);cs$R* z$89RYsj0O7pzI(10#>B2ySC({Q`*}2fVjxQ-M4TT3<3%5dO z{n`b?ac)u!T5O{An}u0I@*xAd=3({w1KIbdrZoN!3Y#~gNnde)#*ZK6CC0GW5`z`v zY5qZD+F{DIjTqR0#z*aJi=I}SVBdpo@3Pzokaiw85`$n~?o2S8V70{_(Yfp(vaki!W>&Xxdz8nkN(X@VWh5?3_ z#-jY8c)!WtADW&rN9D*&JenFx_K!Rb75s483`Yw(|2kg>!`yJM^f#Wg{-~@mXzH4Y z-sUv_rxmSG@Kip(#|M49UAh+*wX}baUZc@%W+omSqw|-YrVL^17TgEzfAh;hC{5W5 z^^Y|FJJ9}HzG#WG{4H|xbEb442AtW8A8|DQnSmp5OXV=ul+*qXv}uXA z&$i%OQ`-Mu>GQ+q+Yck8G3{@c&;mCmZiU?+x_^IuH2^0&?Ss<=+TV?)1EhCj`_LnU zZtt;Qf|n+lsOS(Z_8)G2Yw4{7MenV!xJ&DI_F)(^Aq#8mX#d-;HAnGx>2C-h(fH!~ z{qWd&A70tg{>rT+NSK)=Q$K$EpVDfMc1yRR+k2Y7M6(}W9^Z$e5SstNs=hceBu;Ms z^d4r0_mR@?BQ>Yv8?>q!x;@(_x4t(G^kCB?4tASpeeZdS7#z0^k8NoGRn2t~%i^%m zfX2VeHGyy|3u_|l`yW@ovdE^0ZNFXS{Rw`3xMI);tyaXLn>Nj_Sla~im&(T%_U{e% zgK=n~PUCO3Zi1A+?fBD$j&Ht?4#F(UjU9jX!{&9v`An9-cycY%y6%K8 z&1n9QAzG-gh(~5)nm^(4FBYTY44Z%Tzi;R26CnNVN2{apNE}V$U!+aL2h9o?hKl*+ z>*F|~hJ~g&Se)9)&EO$os58D5j zVCip*O5?F#=J|?j{&wkF&&L}%W^A|meMEhyogt#8}>+b*O zao=a{9MctUzvE%PpRS*y!W0avEk~OPwEm!wuk0<`fj;bv+ zmob|NkH!^H=|}TxDXYP_WdgR;*N69aCH4cG_j(6P_38K`PLIc*b``LBB%U95|L+|w zQKI|^n;$vJa^QUa!U-|i8zo{KcV-loy zK(xQW!s|$EC*R++T!td^`)J`$`+F*kM((^Sx%07Pk}K|xrt|mMwkrn?v) zum8yADtf+MCbxc(Zz|biV^=s#q~kMRI}peIN&VH({?3#O(zEAdu*>xPQ`xdL5|1T7 zV+HN6V&x3AE3oG5zo(m2Vz@6V@d*|9UJz~vipO*%^xyWUq&#ow><=abA1Ein7P1bB9$@h=w}10x=y#ami`v)Mfse!~@ypV0gU z%0}1`^biF#G~PMp4h#4#AO9z#IXaggz|*-6>zizRE!~EqG~}V&{J(wL3|^xXV31AY zbFSTDYo+?V18D!ws|?}U{1Ki%q5TJJSAZPDdMsZ;GhZ3-=y$)>qMRF#Nrx{O4%@E!>J(j-8wI_dj&}-4_f(zkZc?-k8Q;%xHw3 z()rsxn~uMEzw2zp0XICX|2_lXzjazOJbV8YQES%J&yTY2H^hxoKs$>Btb5VmPquzX z*AKv()JN#wk**@Vehqlp-v{h`(+|a~A7P`nIR5$i)^t9CE=`umonQAh zy~L$3NfgFtV229iD(cCJlJm_}psrFzD$+gzpi@KkqNd z?lPNm-wm17;`eFz{0@0=7&+_Z`>*)X2WKS@G0|DT>d+~f3n&I2`G5cpf8)B>kc|_fAJ8C=`_D@ z(KmK>VFF^qX?)qjLgv@i9oZfY?XvyDGNKn=oqGg_rF8z)%nfk&&qu8F>qNd^c3$x- zo0FA*$(I}WW&O9lU%+0Dc886BL%Xd0x2&Ghy;mjrexvnI&i}-&S|_0QJMsG|{Qf}C zFP~+(yJLR=&7az$2X=L@gyIC6f3nsGc3`M<|FebWUr?LNMu)qj{{fm`)v!AneW*lE z4b87&^^WaboPf|BH2;#s9Coq99pxo7|3!Okq+P8--f4RL-hTLoIoy_?AGJi5c*M^ANlbWwcrd}+t@>H z{$8uD#j(e_LgZ*#KdFTVp8k7;hmGm}->Lc(+i&P0xBjQqtJ&7f1oYLU{qG*S8V6hJ z3CUw={n7io;>NNnD6XXId(ZnMo3PwN?)((x`JByYo(SXm?^E&p*Ee`2;_dZ>nh;vw z#IP$Kl|DxQ+jRZC&mL#*CwstkBi(=AtbEFX8z;(*->_N@9wtxV*qmNpc1(TDp7u*b z$1ZgKPJceis^)s&wz(YrMylB0{TSgN>HIZaS;_ubB%(}_<_|o3gt;B@Kv5daZ#}p( zKD2p^iJCP3f4L7>`nv?=4LVu3{_^>6+a`-87I?^=AD>57u;Jel@U7+qi8tJn$$Ed0 z-@iNQma~q_6LHdk)_2NnkFG z-(l;TBqAV!_P=#OI*XQmqx|0>nm_GM8ME3d-JiQ0C*zO%*cKc5Rw1}8?cdKkjio;J zz^aQ4^_89fR}8z!grWp&E2R0i>!z}z&Yn>HO5+DDN@j0#Jkg?HyiY2>yuE?905xzp?#d@H%z_EBx#9IeNWe~IxdcN?k=DI;qpuD%@pQ)A|RILKNz3SLf<3;tLgmx3Tup|f2IDNY5v=NqS(AC zo+z`R`3sKcvU7hEQEfx>ciI!d-cR#H@2)gH?^hU`wLyOSqpGR@!7L}r z6P>>|)K9j5JMH?xl)S2Nw=tdH>;Ii(Kd&UgIE&_=(KLvaMtkCVKFz;9;tOl-TZzTV zVmlvy)sABSFkq{EA#J>_fM|G|XVd zW27J0k~996t$4xErb_zzXA#fqZyvdmWfXYg_ASvLpTBi)(^$Yi>HKknj?d(=7i;z1 z6Wv;h{5*cZ=M?s+akBIsI2zx4k|(SD<%u@WXnohjWR{beEO-6RZ1RX*xmk%HD?~gW zpL5ql7C1T?4hL!dy;t4Yygt&uaU;k7tlJfA^QKC8mxy?t|HRLDcHT4@fvd%KetlZg z-i?jv?giuPqCY-A=X~z6J3T64Y9``&{JvFv3`vfS}uG;Av~ z*78F52%6t?a5Rf}nT&lWMSed1^{q;nt@QkAx>s!H^)nA_V%nNsuxw8Ax6+SfoARXd zi)p1)Iy16!-^h5hAXJ6~VN;oh(-8R z;b4u}&hxjPxR#kp`G3gtU)lNJR_ikBp<0D6<7vEgzg2Aga4!tZ7TbA$$v;Ba_7llC z@bV}*f9vaAV8MQsxb7yl^ZxGrv}d}Vy|7Ovf3p6%_6%m9vXfzORmAi8)y_W0hJLEV zmm;y9=TFF9!k+e$e!mB_{|~W&?8w{{42*1Om(8#9l{|LzoRohB&A-z)fEg&I$c?{N zO&fY$Oa-Ouigo!Z;oeU$@4JviHuXZ;9g&~UueDtc8+NG@pT>*re0(Z#yVzRk->1yd zr~R8t?}A9 z6ol^+@qB%pi_|gl&L0-9L4_P3zy+_F=z_ zQ}E%Wi0Ab?9a6=R%Oiv(muUSjFYH+GIxht1iTUI8Gyff9DIY5_{4cG)d9ybw4oktR zZX%x7ANi&;#^{&|cLvb;_bQsk{H1?mO`}xHHb_2g`eA|yZvo^jd zsM*laE~|fGb{mY>GZWsnYDUfv-JQ3xNaqyvH>2^F=c-_ZARoUpVhjt|ApMQi#0I>q zzYpq(tY1wfKK7;Kvv@O-MaOz!+cp~CKYtUeUL*Y*LCqW5W#dcOq>M31X2NzSI=;m| z@$8-SeCOJh)<1WeG5-KBgv!J(>;HYrE_LA8xoy@NsVa!nO>%BMWJkd6u95_u6z{3`sP=n$c^SV{9@0>)=KxcAH;Tk z{{pq5 z{!jPAS=P!b6g8&n({a!OW;Zzn!~2QtJilF`0n0e$g)Eu;$@*_UY%Y`ZNyR!VF+To& z%75-4rj{h#f8^BjbMH6Vw+>?e9j%1R$HV0O&{r~(E$WhrWL1%$&+n2|{n^xW(!X(e zi{}5D62Qv8RbrT?m_I(h!&ccc+n%Y|rb6?Fj@Dy(C%llom*#g;w`MnLQ=ogKp z9^I3!ud^E3W&L&Q;?2HKt;8E;n!l=S9Q*z;1~82kTzymGJXpw< zN*qw7`P;l1!$ww1=XWETf2ghoo4(5nrT4`8@$1{g*={WLdnMlb(fk9AMzY`*sW?}^ z{_*|iQg=0WJ=_b1r8NI?za6aVxitTCX#R-{CCsW#DxA$||6f0KVg*iK=;TTB3wB#s zqxn^MS48u#(==gUG*ji~XP;ktHqXZko1JL>G5t2MXD2G*{4tXpUz75OvKdvTtyo7>PX+ds99RxM(WR`w4q%#{$Dw2Od&l5Di`SXCR@Hr4kya@ z_kPzncIL3uUtikaPuKU77w%r@T0j5t^G8;j&g|YE>Hcgdt=~#xG`qO35*HfN{3=b` zGl$?5yxK_PGn8IR{H6M1+#1?t^BcZR!fJm#f{GzMe%y81u)Q8Bm@vKpFPpy}A0JDG zOZU&~Ry4HB@;`JK&Wul2${n9wIw-R)=Tk5vqyaC>zoNWC;yK$3s%;zEW%-|&7_#hY zDSt;gKX2bQV`_;hSTMN(FUw!zd`q%yr5BEMZfNKD^#-xePb*>Ym(I@^^(JiU{uC$~ zH{fOY!|jVDLza7?N}-`$mOo>$9&1$l2sYIjZrm?Px>0YXlVa`bX|8`j_>z>NEwl2Wk=cLlfBY&orI9RS1LtXk|O(Q7nKky zD=I<~LPkC3u}28mEA+_^-hJ4yo%25XT_0dKrt}q$Z@Z+=3J*PnC8Ifg+8?{x z?^G_X8Ujwa|BcJ_TO(hW{WJV2yt*Qm&t`E5>wVhM3P+0Nn;3pxxur)6oH7vO%l6%@ zjDH&p&sKB(RDRu_m00dnE&g0F|6dQk?`0Yl zi@V@x6=NmFfBnE$Ww$#|;q`DnpXzU+&N1bPfhmw&O)TFs=S56;*U@UPjhMc9y){aY zl3++#_8)z@{{QhRQVu=)1YYWk<*(#&K)Jei#qzx@a$_@ZIa-Z17xVvM5Uw=)7z~~s zV*XtMpDEAQc?vZri23hYze{QTayJZd;`6C~SIu=~L$&$Ern8uTQQH9J>+9NYsI=ts zsr{-SxvO;0-Y?a^ohr=Vm7Z)@R%aXZWCW5o2wTWIrpt*5ZH(SP&h_`FR!Gsi!U zR@It_`S1QVSXuXVFl031^r`%r_Y#%UCq0GJj$-<0TTIzH#Vo7BI%4|Q4f-ij>wi}t z{Wo7OpWb{gWoefbD2U?xss5(9J1XO~{@-qgczoT>IOU(kPXHao{^78*i*kkb{Cjw; zn13Z^tUaHaRbl-0yb`6fJoyAPJH_;SgpN^O(biAP-C}&UMh5Iw{aF?2-`Aw2vi+`L z@bwqtyA=_n+%rlmUn?M74v`7!be%)t>tee=D)pjH|5US+JDq5#qxI>P@)`VJj*IqU+f<#%d087rBy8d zmlO8NPlej|5!qt?3(QQFAGQ4V_7(Gwa(bwo)OeQFDP7LrmdHQQ!P z>-)R%`b_OxdhUW{+2LTgzgSGaWnwF3-vf_f;b<}a)uC@JzbR9|$4jigS;My~*ICT6 zYG=mvNBj3vn-5r)MFzu(&SL(_Lux8JY<>(?dy4tH7hJR~n^kdqzbFV*mITkT+PGTG zf1M`Aa(8sa{0CJ3VA;0T6YV!-#Qg7Or&zYp_LmjOA8oP7a;sYIpR|AbT5{gf_UL1H zQT}}@>K_;OuCknOQ!#zjiXoQkE(JqcG}j-cU)D9=vSpZ7fAz)q74_;^KJ^WTykZ_7 zjO_n+(2TKsFfj#=1&HlieB9GA*5)xhzaoC0x8-e9%Wc~JOJ}Tj{*D*d2C&dzu&K@Q z)B0gPFWB;^K`X0!`pHs%K;NgFI6inlr)9w~zl`Ij^S^C8G@vV_RM>yi`5rM~TjR%| zw?T}5{gm?qj_q1vwe#*&i9h{5smVp%{{B0H;gf|Jf6|WE7UM@&Y`@99rkomF_y}UB zi21J@te>T>lLD>ki}hFZ(JHI2)_#3ni{&4wdpzsQu8aMfBob7?2(qiU=_mYQ~BafmSv|W-35~sNkaR)n%_lzcX=zT!mx7^ zeigyLa#c?D^x3;%RTDA)t9gsmc|V6)ov&R_qF+qzXFPSRqsvJeMj$x!PUk1#-AOfHk?p# zd|k`0s(z%+FMnj~GkJfXI8LRmx92;Y{J|zAZwt1F%Qk#d+ zb_M@G9Mw-*cs;f8%!>JU)pS>TTU2b{4pkPbXJO)(1!KUimzSKX8 z#;Dbnb}g-*wc+te>)VQr_tfKh_OZ%~ESBEy#S;0ZnYL7GwDwzllGCU0mFpFv9{lPd zoNyH5d$wqd`a$j;)+O^`Fz9 z*QmeDd@KG--#^^+xsSTTAh~>$e!!bJwaKQ3P^G?DzDMY$ z_6|sdQ+{Il_7|S1Q{OhW3XJ3NL*@H$+*+;My5juWI%21~>x28Cdv&YipEQ3q-0Y+N zHDWuY^xh%KNA>%4a*=wIe?zOPVH>1z1<`NMo5kug;f<|QR>ey8SCIct1tyJFx76ax zj}+_QY+afNOtgc;+5#sCd@R$0yZeuH# zI-7*}y4A8%yPE~W(hVFR_0PszL)1g|ZiX9oHw*bk9iFQmqR{)<23A>3#rXei8KoXNcr)Y-7xNF-S)|T>9R#NR#QdiY$x*Ml{{SAl ziT(Tjy)EhqiQ4z0;8I_UXT;27aGj+bXQ_Jjp(c_|JBoW~c$v3ir2K%}!G5Y2WWwD&+D}{62F-)!r{F zw$J*Sztwv`euZTXrU>!vzg`_58dSA1yFNg|NB^(3{X?pHk@ovA73pt8izu~));^mi zi}g46RFOJg+h2_e759%ic{(`R^eec0oFv3|V{vU9qF>c&^g}T|rw*O5+i)|P{uK24 zG}?R5@9HMQlBS$LjsIJ?Uj0$~{;c{UG5$VPs$*pCXDF#QQHbxt@%nh}v7S}aQVXH} z(kBnVI&C`1@P!e4mF-Tcm-a}8Y31t=itkeVCUxeP0NCGx+n=s4M>#dYv7Pm-3@i5) z@{f=GtS_E?3kO&68ofo0$Hu%UjjOTb4rY9^1?HE1y4RlRj#SAA?Cv3*q;Tj4Ity>zgJ+ zn6sF^UD{6dZ0+|;I|uxiU*+`Ui(2BO0pFl$xL7`qix1SSRx((R6Vp!{l%oFCb}^h& zaQgKB>~^_&c@E0|mmt}Pt`Fu< z{iu!`SaE)cpKXW`8`rDt9|DMf$|sczi54&R@?}!*Ia;ZN-_TzyDjm1pKs94 zsgjWY+eUxXKOQGS-u?gLSKePKLvz(xc0r)`Ud+Gu?{4^L*fTIc=_2%xWxsXM?qec^ z*5LBd`mp$Pdz?AoHuN!SQyyRP@27NMa#vl&M*IHuu9&}dH5;rF`Wf1*PCty*e!nkz;XomMAKw>h=XyafRJ)Gi>mPai zelDqwF3)$su7-SlNc}sY>Ilqne+Q_aEzwUP_194ITHVAT2nu(I=|`V7#4(P^Fw%{W zQ~GH$+F)dt6RjR~q>e>a*txARO6Wt{GjO_1JInW-@?MQ^wDLjAB_>COZ z75xV9gT@Ii()0cO!IQA@<=;ccOLHqy6YXh*q={`t1 z%kfkDBsa6hp?U|Q=Hq8V`qhffv2n}oaO5HHzbO8asogQeVjI+sD_{ST{9LC`56sis z4%;F}Nb;$a^7H4a^=+_b_k&;&^IXXP)0c^um75JXq}_nO{*T1}J(WXn-PTmtc<-8$ zkIVDp=b&NOfAs+{y#827f39yYT)c5Bksvm~`-Upn7HGFJ4qD#h`!7_!24fbYPu@Am@3BotfA`%!c-(Y7JaFkQ z#GmOo68n5if>uYeCHtyKe#pt0iBkt2hSD}%KDxfH`JgSDw$#4wHskk~D1INEXk4@B zMTPlgX>vcbKC%{;3|%APW5oZfYwfr4!dhs))Le-F_U|zW8F)Ci z`R7>m#kdwxaN~2hL_dM>?>oQ(J(fp9>A}wBBSl4JZw#dH) z?*q0dd4D8dU)+lxfG!uK!01PNA^rX9rs3vJyCB~9jF5h$wm++r5&@O(g-Y|Oe{^v7 z#<`^#GWi+F@85U#!PR@ipiZH`G@t7KS2HChZ;J$jrMy3&^`)xI3|xIT2~vlsh4^YG z*ken>B$(cX+lS`&9&P&L+!vwHEKeomKit9!p?4(IJXzi!k^ckeCp)97cK?X|Bj#W8 zu(rQgrGlkqyUX<>?@z0*R$}#4VbHEfEPwB{*0|O(0tybAN%N`v)7^LBwv$CN{nGr^ zr0Npfl9~=@o!2P;+Mlj3pFWAkfs3z#YWVJxf5&P4DcEU+v;4zge3=-Z^Kxrkem@+J zy0j4Dn|NXh0*iymAGQeNV@6^kK5g^^7- zeERpl{4dvU$?!oqc|;hj(unbIcN~o4wEy56e6^Vn|Ah5BF)HmT*qbj9_E%0#z0jdj z5`6h3_OCyCd!zXkKiIL2*9V%PtSyFO=BF(0EEK}FH<9F{^kawH;<{O3@Stfx`MA7(CUy72F1vQY*8Fa8+02u4rZRz6>@|0Qcyp)IQ5} zA~CvA#roejb1Vi92m=<`RLH;4ya{;OW))cX2reI&>vwwAQat!15mILI`bYCqLGOMz zt(O-J%G)H(SCRTW<->M#&AAG_w#O^~>X*ikUaSQ+>^Be8dVD^WuiKr;c(Ls&P_z=` zyQkcN@i{p%|D*Zkqwf^FlN|;=4FZMoU8yw#uNkcdpNXdB_~rKL=ID<<{1c)1RdM`0 zueB5Zb<_ICy7Yb`|E`hYfU4uGp-Yw45`CH<2i9Zg8}ANhaaXy1{coc%85AGCHFcDWM_m9H%q>hDt8 zUi|XvT7~*I&kV)k#}eWBIC1@Pwc3Tc-rE184xS^-4~D5j@!Wv<;B;+*#9yJ1`{%g) zIoNv0YKWi7>yL`$r@?s_G2mcvh4{K`4!~9&H^a`g$wK{VVK`i89_-vUmg6V=Q>e-vE47G#noD{8ruf^Qy^f<&K10zk9gdHz zPlA61;fhC_p--vUzNuS=qmTCgvS9%nAC1o!H-hnXdOU2~lT=P$zW)7KkcP)6Tmi-T z;U`7@?U81Swl`hj`tkLWdj^sDGQP2e5m@MNl2tBGhlOyE{5sgn;A5 zM&QNmC2)1|v3(C~ux|J<+FO7rsxzDvzV;`>H(wciLHR!(2; zUyWC6#A!ZzAfR`oQdA$d^xTinHl6|1fi2Sdg03Gg_<7>N6~SQFz_^^g9RE4)0n-Gc7Wrj>#y+b2eH>3 z?fUD?AmRFGywiM)vkr!OXB!If@9I4oRj-_&;fg3}oZ`!O)$X5Y|Bt;ZhOaMa|6J?m zVSJQ%4p1TH-=Nkc%%46N&QB80AM$b<{&U$A?v3X68x$n|uPUbC@R2T%_GM@}ez|?$ zI8DdL`tDF~)*J5sWdGn$j1z9H>kFq#7Am>_%hxAIC(glH&HZ5fYs2#S^7uK_c^X>1 zm;;T&#r%iNbHLOLE&g1NpYC5w>EwhN>GLa$p97jFr>%=f<(o@05?6Y1c8^=^T52qYrCH>O=-$U(+OKN+A>LHg;LGs_9ICqTD^O51F>$k}U9{9{( zEC0-@5`T*CgwAvvGT#y0A4UlMcg`p`EJ&FLX+!*k`aM?51KTf~5ADoDIae~rfP6gLlyy5|NFISYjL zJMZU%renRpHF%*=e|10kq4ixKh;XkV;iviwcXYMil7 z{`>N+I}VJV0XOW!CHV}Af0>2O!}WFSA+txEP`+z^D{#H1Hb0Kz`la-1nXB-03<<#Boy=fW-?QUyS6hkrQHYl64pqOq?a8 zziZ73?5&s!BRlf=pz9w6`s27n59sx~Tt0<7e}~-(z-ei6{VNpm_4TL=jyUtpNa&`& zNa#PK2JXNcnsqY!|G)M5hn@IkWDMj!2v$n{4LRRGxyciEZI}dS9g)jNsFcETL0JlG>AGN=3!_3=J72>a)=!j0G zLt(n1r$nFjAGQtLuyMv1$nAJo!jA-hvrb<4V8%o+|6wKZr~A7H_GO~e(xeLckDhu4 zt8_?%=~Z5F{gC{E^~3P!3oo!}B+l=Td}rYFcUI6Y+g@ltoxb)s+H(*n7sW~AjMb6t zuUu+!9HV~itPtPLo8kD`az2<_md7WtPmS(b=<_oP9ysSn_!-gv((!5>lD`YujXgi$ zuYb_^s6EII7rFu1n%GJB5=ehq|Gho#xjGQMHJhYy6~XVmauv?it2llWvOREC&k=BF zjIU5XCJofs>rxU_?kUE<@zDnCvqJ^h2kVscm*=;F?uSu#Mtp_(Yg*?hHq74wD|S?p z{9C1z$LGH%&taEiDPVa2o=|^%>(9XwgF(@q<$?wx(|(aL{})kuVMps z9lQjZ*Qz1Sr|VM#y}794Zw2>!9EAKc7o?%fkhK-kUwb(kPxtqNUKV?mJpah|KiW-6 z$5pc`o$NXsLb@pFBJ{4EFF!cVpKL!S%rLjO))=8bKpSwrLM zT)&k5loq}?Dq=9i=JWkaB>IiFyN&(wQX#tCW{G|R>0fO(ZNSxMyr56LMUwoqKC}*L zrg1I!1y!DR;rWHkw>s;KNA6fdwaIgY^51B<1jo-A3^#lJxBn+!{~Vlg9=rD63g+X! zOZXU}-~aJ={MxV`#9W;((KiQq{t2wL5~q%}f%nV#{yOasQ{u;CMvFF3FO=Jdk@=ZT zlCf_ke>nfKoDyGT$ATq+Sfa1N9~P zw0_^da1mb@ZU$p#g%sb^K8xy`Y4RHXhKSkSg!-SX8IMEV%m54K3iXp$e*(s*nZfs3 z8>Mk%hO+$Ks@Y}C3*QWm9Wo^P2_*m89=?pqKbzsp)A7=Lx;`{}d;(i!0dk0q;aahfi14$sLpYa*)~lm-?txAG4(|& zusXow-;40C7CIdrjLcxznD#>ct&U#9b01^D`^kPG{qc!25Qdn-#yahU^L<;}Vc8y2 zng3Jy-`zNfWBLa|*i)V#ssFy&a~W+X$3V!a`j*^(<@NRL>zi0@X*{&)#rrqfpM796 zF}dSndj>|IadPxGJdqg=cZu?hOj+bijZ z_DAO5?QzDMR^V5I^UoywCk7qB^PiUk&Nq_uN9At~d1$>W7OY?CN&IR4F`AHvH!@nt0m-^^Ztk0=Y#P%96v&PKL0ULDe7-n?q%%c zRdIjv@!&m7s~iV;xm6^5v_5!Lx{t~I<7D}Vu77()I^z_-mQbe8_unc0hN;eYFsdaq zKh5hujjs;j*YMhuit%0f=LvRLxEW0T`6jIYjjuQ(Ha3A12WLt8M`E8~BVW8SuRSz1 z{GhJA4&DK`)}_|z-b5f4->Nfp5~Q;BVAl%`l0K~FUogl zH6RiET8jJs<7^S?I>YqE5_F`0n35he`x>eaLN_e zuQvhhPt=6^Su-XdQ!dBK{FB$xHEuXR zuLZbvb&~jNzZD~^--&rgalFzGDxa+-jnn=m=K3-`ZruS2X8w17Pj0`}JKmwbDgmsO zwK}6!e8PF! z|HIq6ofYz5)yD%zRBaCH4)gUX_-DrEwa6V;0WGDGOUbx&!wg>fbldt1!>L0|fmm z=6}bqgJ!xZVb0T86~?EXi4VS>(Ht85+luRt#P@{#{&+8-9h8|C3iF5h zi!VBkZ!Ys6n*UxmUx_IWW?-}YzHt8D2NUtp+3Iq9e zSq+$Nch2%}{o!n!EMG`J{MHQo@<<<|CpcvN zrEf^?M|~c#5bZQg!2QS!Nq^eAUb6UJxn&_vD{TVV4fy(o`uEuQ$#~hXnoNEbc^}nw z_*A^QwmPWxbNTX#e0LvDL(5GyAf#PKN&eBKKXoi!gk}qxfXzJKUsL;}u3CxpCYZp) zF1$ZCwvyu?bZHs}j;#(FHRu0|@Q->m9i8;G|8Sn&N#gHC_%FX>hcNVi`kNx@&xGi2 z`p{)qued4XooOlQkK!xozXC^gX%1#CJb%*uV^Oo?xUc(cnf_?~$?0jQ zQGbv+V+KCyULE!w=klc!`Rse!;mz#oV3yD2QxW;*Je!FpuhoFjHOEQvnG^ZOm^?BkC6OJMb`Iihxz0Cs1{Jth4+6nKivOz46EwOOAJm3t?NPEHBl2Irq{5F!n?aWrT>mtFng=^#POlnZ z=G=kLC+p9BagLZVum&iWjFj}FBKxN=M>*rxulkT;qmb-R>rd7lcU%)vTV~$`k{_zH z_rPn%Ys1)1#u9(Jet-Mb1NZeagz2Z$(m3sppPY8a+RgPL|0R!ag+ji+cXIY@Y!Rdn zdG>t&-kjt|)i@XI>#YwVUm~-)f643f^&K7i_7+3;jFb-8rlj>k9SO>?@Bi`Tkqg6|tI5{d!t0pLtKRZx1VZeGb~`fk&Nc zLg~`V(l{gfwHh;DyT51vDc3hi{1qg=LhUZ&u@Vo6bX#1`U%r3Qudg?Dsbv87I_gRE zsefGv@W!Qm4PZquf8S2yvv*t-&9u1X)&si)CO5$#}hRA3PaV6%5ZX$$z7X{~9;dp8r0t3I_S1(tHz;=Z~)){PE2|dH$gK z{kqE^KVLV1?^b;OK|$)%sH_#(Pn+MCR5@+=H$O#_{1N)YAGhlpKt`9X5`XIdbGij! z%tQZDRqaz8~OPLjo9(RJt1#iXCeME89g-~CF1q@FEc+(Gy27B zqqu)15dF0b3cw*Yx{$R{jIYkCZ0x5q5bDicXZcq?g+ji6dGysQ^vre#v#T{Zei9#< zir3ibt~>0SJWm>@@%L%mZEO=g8BXhn?+*lY_QcIO#mwjiKc6=y@v-ORT?{!e1ukz8 z&;NH~AH=2|6$E56+*r>k? zWYiVY-#6eshOC$ZH~XyM`Xl=vmu;Wms-1SS`astQ{fgbtv+-NjDuU~m?!S(#( z-m;L5MahRe4!`};~`P4re+s10fI2u{qtYn0L`P2Fv5pn?)m6US*llwir zqLyJB(~s=LG%kNE!B^Y_h-t@{Kl~;`veTzsg&m@WorQ z{wMwya=fZWc}xZMN|y@t`?-F+#;u7~zg;?Kd@YkKmA^^yr)N`@f6~JkgVMwT=$MOtvp21UpmpB;Tjb_ z{q~+kU9T^VyOa7bb^3mM{MiIvec}pStkDA8QuvhhGt-gg=M(>3_bW)V z?ouhdw`ecfm-a`QX`3~!b81^%`&e5V&nNxI$cPZUdF%^|Id@mWf05v?zcUR-KWYKf ze@s`3@@K-K46GGI>_hU`txi|)#^QeP;Liq0ztp~oEw^a4|1hw!-zCOZY>IvVL0gim|dQHJkS z=TMw*^&PW`8YJ0=k^PVAd&05$;1bsOLo;bU-5+;)l!~42Hw33|2POGv|JSd0KN{p3 zLrTdp9{*&2`c~9NGZp7g$n#+ScWFz#vjnw{|F>n8>Ae_fZg z*s6zGIoJocHiMqNP_fP)Ftiva8`w{tiuZh6C zv=a8@9Y6n~=ikl?QZd%O9t3^NmFz?HTl(cD9@gy%3r%As`_lYhw`+v<{H~al+4B1f zG(Z1%7=?#QN?E2GKVPQ#>pauy|BnL9?~hjg%}?}wTdLhYY!YGwHcpR({?qc`wfJp! z8S_)km*l7Yf$94g{QU73Q`9t-;)lk+QSL2l?%hNC|534gWA^UHV(+@}>YqG`Ki&Uu z{&@sllN-zIL;H(!o)2)8Nna=|-6!;qo61DZuFM)%Mn1Kq{FOlByP+Zs`(^#hoX}8; zKdL`3*Kjm4f5ooF@%(Q>>i^h+NSyut18etnd^vx4fB5_01{~)3i={7aCFw^&`1crj z5Eo&6nS8W9|K7eIYi%@w@BNNQ{z2p4XKEUH_NohL&-F+B%VESS+~V?z4ZeIv!bkl_ zXLkffFDPPWErxOY#J_c?rDOBQb-}Xmu*9Fn&+#D#QMtPw*hE|u`p=8eNgA6+)vbEH zt0~lfqx^6*sa(j~1gItcbp7oybqQ7-o68J$^8NE@QeXS)r(?4eBj|B5L&8V(qZpcw zA&-n8X-PdUA2~m=&rip)>2<*?=Q_tv`b+l@>3C{xUAcWoe;xfHNt5kd-D+owSU!jF zxtQ}=!z^y_{UN%3T6OmpDqj5qs@W=G{_Cpy7=I`Ah70R>e?;{kyI?8qEV|C3mvjA$ zCi>ZAb`qP_ZvsW@#rObpm^BYzQ~qr%Cylo?owDpsN`Y zG+Bm^=7%Z2y|MN2vn=IDu0)@%-v>b)YI|sAzH>=Ae|diT$1N3qp4JEB(AQFaqWN)L z_yIJZXaG|;aQ&%B|9P*|0(>5IhPmA1@=^JNTDf49*9kW4K@};#QvYgU>Wc3go??A+ zyGrBHq`#{g7LJ!UK4SU$=@NdrzV5PlJ=Smaj$K?fQ7B)`i9@)ieQg*v|ET5P`bY7P zi8_i&Hbyf2DoA{{?Y{`GoI1ynX7lyKD`MY8*Z1SLHu~Vw=#`{Dn%{rruEv!6PuQt% zttEWsz|&v*rx5>Ia@qq^y-%|0Ujxg>YsvDTrG+Ps zyM2=7j^p1?i-nr9@nQXA@U72lR?uvuBtKmrmxM0D=SHWQ*BTxl)PBvkX5f+gwV-T* z9-ps}pC9SOoWQVc75nE6wF?gDe3Y#l%I}xZ`eKqj7vFw6%DU9=ST3J@{giRM5YJrh z0l_M9eHqv+1Ebd0ge^1Q@%%^5U#-_>;+$rN&|`aDj-UA7@VvQL_wErHK5C!P`fD+2 z=`&_Ih}VC5zC0i&7B6JIV=?CT5`9MEr$yc&EKaNeUX6-{{Uz;P+Y&C;;EC@xu^|pKC7YT_M!46w%Cl04(}NYa+dH@|9@fo z7CrTQLZ;_>A^txU9zCkG0$1S2IBS{kubB4oLn*_a9f?0L_DE>mk1uf1gF=e^;~&ONJvWb>;aZo!IBN z#W74@qz`5#JU;3A>6tnUI|Lfa>kFxGi>9B&$vf*q<Dq=sksq=8NZw9-0 zSZtr>bzb7dnOz{-TTDO4DI8ZUy~aAM<@dkn{Y%}mN6~w3b%=Eo=Z|)&7tyO(Lz(`} z$^Eu!O)_!h>go{D=8J@%>Obz_WgNC&KA(~KSq`A@>ziuebhAvze|N?r3|(}LU94P{`yc7A2W;2w4`1l3eg9m(zeDnO&!qJ@ zZPWwV`LKfYuhEg2=+dzoB*0H0fAi#X`0Gy{@Hx%vH+{dk+xRlBnIvET(*CQ{pqqGV zNfU5(6YnouKep5awvGgs$Nc~3v_4d`UWA`?kFr(Px{~~~K8_2C$2`jyvhyqYeg7$= zE}#!Hg2|P6d{F!i9$mz7E@XX3zVBx`=pN1~Yz~X+Bn$J;z{N`K7s?|bG=bx%`JvRz z2lE3C$?7M~Psh5ah*xHqs4NJ6y@xi$Is zZ)kq)=66|pKUOXutuNKJ?~86hb69K7<)iUEvS=|*+j4{j`0@9LbboAb@&fJswRD!M z`6=ZODqq94w=kq>Bgn1eC;69x;BRW4j$KdvX7&R%aQTS*U9TL(vk?j?$=D*yPkXfY z*HwmxWch{qN6gbj`1H>qwjyGJIDV+`2H`=kLv^P;AQRpc}3qRZ*?jNo7E zgDYulC-#EV&$FfZl)ql(otn273SiZ;4np}m76qVX^f8t_mhXS0ko>%ETQIKlI?4P7 zi|ha4sB{dB`N|4EuPL{We0~3Owgw|^RE0hbKMdgcL2m!A19xiHRdU;okm#ME!6X85V+kme;mf9>QMh?iR)V=D%5`OS&^ zp1%9BRl-MB_UJR0Pa)U8b^BjO7%+b>iRQNjo$6 z84}IyN9JQdC^kQNf=zbi{W0~=Ew5MO!jH(z7{A|2>xc0|4L)+!g=!0rTmIF5KIz|Q z4myp!e(FM>Fy24V_^+Ruiwo+@`!||@jkc+9tKuND4dLhCG=H`q{}KN!q`o z{Ym?oA$a`DG1mCeMM?fl(q9(zjljfC$P{ke|INw%Tccs8v1xl%C zY$p_O{VL`D*}Lm)R8BC`e&1GEJ}%EMO^2*RkKihL&+nu^E@%>j)%F}_ zc2#-&)AixZMlW&wou**ZZ8?{Z@W;*XaaE;OkT9l>R9|TSvVC;~+V#z5W>*8H`G!RQ zhxeSusb_RxcQ-Nq^BFfVp_u_(e!%h5{nr6CgV4w45KB<=^=lcif57WkxTJA2h$^fm z#FtiiI#zzSp7ps=BH@cA`zsHA&%n2~8(74`fztd0kngWNo-`Bh_TR{so(h%5%|TyQ zU&l3cz@zgwu|9Dg(zuH3zvy>6i#31iK>EHnLi^76eI7r()P;;MeE*WhpWj1&>^44) zO`go_TQQNpVB2fleY`1DJ1v&~LT?SmSXP3B(rZHgPgY&P+pBe@HP+?# z8yWe&M)U6)G_F($aKLpT{s9h`@!$bHa6-O6NA*`LDHns^)&N{_ZouF8q4_1CG!Qqm zIl%61J0jt?A^nB@xkB8NZw#ZCdUE+ld@Orfh}}z!;j)6~H!7dSq#0<@Z5>Ox_(7U) zPyEm9%`7b3yOA}W&ihZAKZbX|g#C4NA-^)W4}D+RbLvfO+g=|`Y&DX6G(V?zdWJol zll2SPzrBzhgqhtAu%oAsO8Dsh==Gv9{8`Hk6k|I|=RYda-%cB8hpqptWf|>@rTH|z zHs(2Dw97`eB}6RWm%V|wCq9+E-@)r6?eAFoNGzOooEh8vcRnDmuY(FQ(A@eRQ*Gn_ zZ=&_zaJio5)Le5}e?`wH_Sw(I0}D5@*aycY{3axScltZ>eUwKkBq_~O#Ej* zYd-0)G`|P&pV)7aIBvvomapR9$D{snO|P2fn_E{neKXSXuYc10pRkRy@ptM5nSapw zsq!ww24Cw#&h}Xne|kT#UEdJA{b4`LUd-)F^?Ncr5>F%_W5s`brTL7kpVKBr;ngFV zjQuEo|3&sUFHbK)zc)?6_Fvu~QTdK7DnZkqO(DUD*Js-Qd#}2V$Li=o{8xT{tRVSk za@U8Ld$bm0DwBor`#N|U#x9Ix35TCc_`^tijsHFkpPq?iRc`l^@^cEw?^!)Uv1z|F zR&6}@Pcvdaof9P(*{UflYsKYL5cwS&f5Mp#O`&EkukW92%7ezv9I5l^nW`bB@dJC(-u{)~R-A`aObqxs>;h z1YhsDj#xBz4a+RrE#ag3nXb{-d@3-9A>Yg2*OB^~bHWwZeqYa0%p9fp^!tH*Y_H)@ z-O6CJgVzT};%AmkE{+~9$4~q7h`M&z|H5jP^E8MhG*0V}PtRCQ@5pQ@7&bs!-_rd-oaKfK;?^;b~iekMq zDboCCqF?*%)ijUawFeVN{{1O>zbUw>8{UXn%eJ(iD$O?`{o#kx53pLY_Wk3|)58AX zP^c3+I7KpxdECC#Kg&{oV~>8#;7`I<%fI=D=I1g`W6ieB7LYrt{C$!_o}V(c-{*PL zFOr>jFQz|R`#$_*A2qL^$E?^=7Cnc*kD=@5>l3PJe)+To zgY5l6d{0Z9@yNaiX3?0-PxtR$xA4L*M(bH8x7pHs>VJpsJ;Tq_wEgSA1Csuc#CM$u zukk_U+F)~q_g{4XDt^KR3^@CVc{dT`FY2*dgMK-%r|knNzo(G*v6Y6-$14xC{m&p5onqS`4n2mO~Rx``_iPC)PU#|vL*4Q*@4mHO)3+uy+E%UIbC|VYu z)Iaj(oX0~CKd{te{QQ9SFME5tpxgKec52`*i9gkUyK`mu=5u}cU1N+Szl!uf19ZQm z{qY8{$>2y6|0$rSCUY^oc_MpEMYw}UNuh|r~5POM_fhs+h17N!BdvP z_;PrOS(EgkI44e+e|#Eh@x87OgKhZwkLJg-m$ct6^;^ZPn(dVMGm>AnZS=u*6W3{f zAIZ&EV+!Y~z%YEbV?1JUYWO129|03Cc_Lw;VJB(Su)*-)toIuvc z@wI=VYqth)Vt~IipY~5@3w$s+aV;w~;pdn31mD#=w=nna5BA^wDfPcpokv*hVP&Yf z)^( ztS!ecuRl89rr@|mD(32UTAEMqr%&GCg~<~mnR|8Ked5Pw2szJ5096#+JujqqjXOmgb>SQ+wKONT@3!3+yvtVN{ zE+6&pOZVns-9M|D@x&35e6+v)_393;Y5jv`c=7W`S|9$T-@^c_U(BH`@1OEXe(iAN z9{LU;@{{%Rvpb-%4%YsE;3~&Y{a1YtGz&u=Vf&|ONj{2y^Bo8Diw$J<=4&MU<|IC^ z45^}d|DzE^Zg-OWPeJ@|*$QWTRyCMS?65&NKb^T@$-*#Z6T<6fF0t?7l)D%{`8)gX ze3riN*wf|#4z&5jn&upn>`V1i+_;hEd0+2m{$;y3H%u07ukW9AP1rEzLsyJvUMPPdG83qQ>1ll|MpQ}1K@x8Iqe zWvLYZwEr($SV@ywRu8%~3gYugd>!jvOS3Y$6~vU5-w#p9{W~7C-?y_2VL6GLh4?M1 zc_2IsWj&0=_!q_8#_df$v#DiioIkVOO^Z@kMCwFSJ=4#$p1PG@eiV<4e8!+Wzz_LqmRkPWPAQcYJ_9OUtzS z{gm}L{%QP9I{g#RCCR@ZMDw#E(gEYgtz_T7^7pa11pkeC?$|pgm|Y&h@#mBM!CNin zq0YKc_OrnN2|p72J2Ri)=p#Sb*{pws`qLyl!>@V@DCoiW9~g;$i^dpJ;aiJU)j__{CtDr@4u%An?0=p(KjAR^l5(>@mWW+)Uh7qTV4>} zpEg?Nh|{JmXMK{+OY`ad#FdR*ajapWEdS8{!pn9c4ynJ2o&9IDG@s(XRAm8nSrW=7 z`&&ul)yV$K#OV((IQ$dayOf_FD2RO)_IZjYtAAtmT`QH#Ctn|QI8lTr+E;Aq_ABW04s&93Ajj*05P#>nx|%{(4^)YVgy&~@fm5-P_k6ao zH{YM3{@2oQE+#AdncY9p5`Eeqk9YCGdxt`p`v;K5sr{TMyu|*Ne=3x3m+c#TIHZ#H z`(1}DMg6T;!YACmQV%j-@%%&2r@dl+U~Gx@eqD!e5`XHyMy0OUY>Gdd8n8}?fA+x2 zn*I8<;Z+?6Vf_p)Hq>00-lD?%-fHk7{N@|V63*L5^lAV8J?Ir0mCEf)`!~BO#b}kM z1Ac9u2=V*+mE!s4a{1}^&#K%Rq=8S9W&h`;`cd6=#WsE__9TtlkFKv~xw&Fwvz5#- zBue6+PWlVB+z*d=gfjPKJik!+Dh+;(Rj144OCbH1l64A(zd|D5mh3HQ&e3}++w{sPTE0rT82?8;KM<=$0^ zKh6I;T6norNy?w|_CwGU^Vp3IQOY5ok;eTU8b zf3nF3FLC>m@5A4$UW`r8{9(RF4_b=+CvuIRCUHY;7&zRqyg!xiPu=S8f;*2cWKJK> zO8n{hLFREc>=?R)x%5~qjnn>IzljQq(?eOQ-Xv)}mh>Nu-haeFrV1EnEXEhyTcPPv zR8_wIBk|?+y0Ye4uJ-=;DJIEJ``3lJbMRxnk8FKM^LsOmHy(3PvGL0{mE)857uQXf zWAA>!vi^d`|B&<&T(|oV>ukjF)B2n6sIn&OXLarO+4%kt%}?9&X5;JW-Yk88w!}Yy z^gmO+`Jmqo70VqJFOAdubn>?f$JYpD1+iSeDxzQOf)9AD;}2H#kGQ^Ms=nfh?b`3h z?cnD}Nb<*z$CWfD&9wJ>+y9XG)BKg#pt43erJ6Rs*_V&Y`-_6R3$UnQ1tUf=VHe)F~GTR-YWuvZsuN&M;lccb1_G*zoq2lumle}&ecYcBIK$8oW2eM+*O%3RX;|J4%6`B|;DUod~(FP7T1Bj-=*!`c}?G3c}Qenc1k{}@_d z>a6m{!haUC{3_!5nloF4vCV^+MK_+`=>D14v1hol`7369F}0k(e0`waQHE{ZezQ-{ z#PZc$`3GIkR+i@na({RJdN0h}<;!M2T_w>sA^z9*&PrUI7r+Wu43@^Je|=7VhVM2N zvM+V^aeQR`5})`Ezv_NsUR`TR<8*zutz|Jz-u#()4Y?`VkLqtk4}UbBA1KTJlz-a? zFR(1@B`e;@*T1xWzR>P}6&!xUTpIEFGnD_xy&o}C`+bYlLDwYyjKp`qf-+S9`pNu8 zrCW;n&$T}$_{RaCY3TBBIy2vXM;gy3`!lA_i}BN*B`j|@uOGC(OkS(a&*S`A zpX7nke7Zi^V;_js`v$RUzWn|(-JhR#^)>E%^@b%lmS*w%D9^7i8-2t-lSqo~^)6w(t zG?spw+n?SaUvwl09p44AOkLi8()bmzJ;J;8fSw6|N5x?&)cM z_0@yehckuiGn+fJ@p^(2vpsx3@-G^HV-gqR@e7M&`wz4}UG#f`>z`}i=Nj|+Fq)ii z)$L%1W>=>DA6?%amvi?%exrp{5|WU;3E6eOuj~=xNmi2aA%u*`h`XWEAUlL4ZG?~{ z*D*7*WoK_fkqW>2_j=B`y|3@<{rr7i=bUS=bDeV_V^uz1KZ(fy*^tG!Y|uiupSqrp zQ~h~(ItcGdTK}z!|0sQmHw0sOt(B1ZD23A}iukAa&#$mwqZeRv?KU4r!ru*>O0e$r zVlZotoWE56?@alPMZ3yi<8INPN6*&{A}rZR_gaqMUvCinC-uwLb;skN6=R^q@>`1d z*DD*3%_fb7W$xmAP$2z}vz{%&2fgOQ<$2fnd|MKKtX#Mh(;qE_JHI#bacUp`v{{K; zKLtSHFcIHT`WY{LhS#P&1`Ix|lP|e_DCzMUOjmOyEqrs(4UtYgUBKYOmOv2uy$HORl@&8w}qmiutvzqfHycaSaYL+GN`MHjU zvhhYM^_lzTijLN$-#L6V{uy}Ng!$)Hb-Wk3Q>|oQ9t1B%v(-K@`nIs&-o!p^HeZf~ zR=!|n_ekJR=%1q(giWgYgYnKGe4P51K0_a2>YKY@lp4k9YeV#7V9$5xmhl44^{c?) zQxX63^OYO=6}WL*nHBj+u{(^fuU-A~vL4?_Rgitlhym*)_j`jFGtgV6WG z^8oyObs2akDA(6+Px^`bZfW1w`6%8m$tU*xcC$sS)05eb@mnt|!k=1yF;45}4KEHv za{5vDoBhuZANnr<+e86B&3}VpUgEN4kH8}}o5P<;;5UB%2DfGwK(`elzNPvXW^;y( z)<5Cs>Z{yep%>EuU#J{qim#v|H|nxku+hlf2tH_~iXnEzbqw`^crT`nLy(|BQW};~2erfO+D5?pU(^mQ5dU z*8QjO_kIBN@6(SiVGH-naXfqKilTfZUtf%w4Q9iO@eu+)Vqcy_nX%%K%8uu+3HwCX zFP-Uui~5g*_*pk~_{r~|X(fgP-;)W;aEZ}uC`eb< z@8YY=uyp=x+4&lcFWon<#BXlPAZXV>zP=6NU-J!b@bat&P?#s;BbvW_HGhkiuOGmR zw5sZV;ivX#v&%Gwk zzW*PpF2(8E_cuJ+iv6koUk299b)x)zADVwQZy14%TL(Z)@0lEa6~V7>&6=!fd=r{L)YV zssH^-mSJ3l>2R*`Wj-GWe~Z4}!Anoh!iyVA_&D`XH4?P`c|bm#+gnZjul@nCAK&lV zu=XEoIPS_^%g1T{r+rx)OX|&pLc1G$ed_<08vEm>ZC)_;uCji_R1U*W{(cZ!Ao43D z{inU>y~B5TcVNo@O!@xQzAZ_9g=K?pf^AQ6K2GyjRen7NF7o?%w14Md!BSi^<$rLi zvpAoo_HFG@e^jNLW0pYVR=d*GXTQPF-FPt{{)31498n|+G>sdKs+%iUJnF(fX6kJI=4 zhh?qA9L+rFRbQOH(D%KzCI;h{?h9o75gNju;#aS+UD=f2RF2m!pTUmrZ*7XZ>%F_Wzo=tnuJ}U({Er{#w_)i*`Y$z-Zip z93kIw`_QYsKRPf^D7Y!&cPhWj?Sk=u;XF9CU70?6mj) z)^*UUQH#?@L-cF>w(t1K>M^8T$`te?@q2`^6U#l=)p60+gWNyS{><)C+V_?24u{N? z`+R>hl7C$Lcn52BVvsv*E+41*@w#n3wj6Z|JZgW>7W5(cm_TehW(H*574bjy?_D!P zaa8JjS^YSc$iLlydzjpcLH4|bg1+Q^yS%vjIBoJNFxyd;!{<%n*M&pgW0zUi;aByO zYC(Vb`ETv%AF$!98#4W&{t-`q##i%iL%`cAe7-Z$zqmzV=(fZMUQ`_>;3M$A-5rcm zwf^nao#%YqmiUi5W%1}-x)wsK{EhGA`9prmTg)lH3b7Z3{!{th@Awhlf4UAkr{!?? zsQvk;;4{u0a0@aMT)6(z`tbe7<1sw2H|RNw_|=x=$F)BOW8#rn;FKWXr}qntkFLhz zGfSaKhUhN`g8!5+@wnZ5Ekq@Y^8s5@pPK0P0HbmdeCO)?Cy`I9PmeHD?=;wqY|8md z`FVzv{{OaQEKe$+W3O5!V7W5(dKlV?5_Vi_Y$0#p1J`QC3w?QZl>!;0M z_Pyf#qw*WoemBmGUkwT8#rZ-miJy#mBw)zcwUGWr^go0W{B4R8(6z!kFgk6(?azQ- zX0rNDV9zwI%IEvKAXk) zrVYXWamHud<#r7U@24O+z z6i`(Y`JoNbzxIoE;F}AfP^<0^4!;@UU+C93%*>7e*p{rb-*W#p(>@g~t89Su-J(C+ zjNsS#@;!|Ca~!O?UEuto^0heN2i7#aBZD6Z{KxiA$5PEeh;b7BGnDwBm?taINSX?s z7w>WS3qYR#t{brf+rA8eGpj^=gap63zFPa5nFV1x1$@rr|FEo)1?ZfCfbju*ed<5f zc#Xl?Z@WY0%cp!?L+nT86=U%5&+c$*&m=D2QI3^m@_l0RI6NNT6PA^V_xa37{qEMW z37EN1g58ya`FtSt(Pt^a*k<%pIJ5r&-=D@8Gn~ROFT)G6KgSFBNPlO>w>aF?B^+GU z#_E6l1MM%kV|EiQO*3Ttq5k2;uY362Bn#eL_1D=~d3~>2#tZazJq>W$MbUq5{`LZ0 zBTs`mPMoh&`fhI-j5T2j#4i;7Gm6OX+rn@hI$|~)*_h1nqxaj}w)ey^)(3)2FY54@ z#}CiHBw*dUkq|vV)VHX8p68r|XAIWBpdfute;U7TpL$i>-?|^%+PiZ40r8K&Up~NI ziCNI5IG2wX5d9ta6o`rt@fXFvXRAc)(K8aj`4`tu zB>rR2;v~E^ZZ%Y~67bXf@L+ZlzSy`LqT3DT^sy%Ie?In0#{Twe;PQwpKHh@#kFNdU zhx+qfA*!o5Uqs^nem={`Z7+_%?4uVs{u-iR+tWUvKf2*|bp9=e(Pwa!2 zb3Cqmxe9Fil=Ahjk^KD3m}E5Tyc(dI6^GA*#AjH5t>lhJ-nq|Co25&X~ZUVt;+42BU4#r-%S_VHb0 zJf0n~3ewN~9 zCqnR_%Kw<;L|oQ398}9*ar`udey=|!qGnn+oH04b_je}zne5?(2affI4a2YU@o2)| z`VRB(-H`!saN|xsPW?l>+q*DRd%vJ`QcVs&jqf9^;_*nUP_UWWj?d30^bN?^jc-ju zAa`>sK2GWHTpEw&jkNQ(26OzJ34TY1?ZMB}L*ZgKVZZ44%WU8In7MNR%zG>9JCuKV zM}4qlD_qj(c11t?m<=>0ygK@arzbz`=_oyAJaPY2m7bOe$x2i{QUWtu(&_; zI49&oMf^*fhS$-rb1J-I!oJh`spNDWhm1*u!niz+Kb7x>pKhZ=r~NYe()i~0mU!%K z8w^p^TXX#A|5+nG?7@hEA@DFEiI3CxGOl?d9@O67@#uO$=nug^anDrz5Y-dze>lPC z)ARSa_6soWQ$HBmT*wy^`yh?Gfzb_9p>(E@A0+jK8gK7n%S<_bDiXg%c;Cm$c?aNp zfsh|0@^j!x3Z4%PgM!T>f2IDvzVTFCR@hzpKIU-_Kh^JBA7-QW4jZi7^tZk&kN?ya z7UEsI{xIN>6Q8dl@ej+|iKRpR;fzOhK2GzKQE&F(%IU!n;4b_F)z4=hcd_!oePF!D zN&Rp9MC)s_^0oKh{N(g0p!5m3hvTZH!=_f3`FyHB2i+6#%)MYx746{sRT2Jn?~sHC zfMD@L}Jp79KU;2a+{}%N)A7{_sC({r5zUt#2 z$r#!q6kfbb=j&7aQZirTw++X@c4P;|_@JIq%w--C-+27;=eA)jwc=ATYT!sl+mu+Ut{ zM+uRS{~bxie)mG5;H&75rSRVzI2&jD;{X-!UEuIj{j=KUgAbf~L!qO{A8CI1rCL0` zzvB<8TkZM(PZU1$ukmQQM%zERpfO*+kjRgB(j443%K<`9U*hBRe&fD5i*b#6Uuc&h z@*6WEzX{oKn0!tHn{I94^Qrtq8|Gt;11YfizK~Cv|G9_cV?^y#aGB!7{g*TGU+1*( z?E{ZgnfxMo-#6yueH{2C4W^C~_K*H=tUgeP>ApEIueOc)U;R)K|7=`$A!aOdgv|Qe zIs7!g+q!=d_B!1QoR13qr1IHjY8*Zow*p)bZ07T+|9lY;kDDiG`BTB3^T&qBPmjEK zycXjRMt5!aeEL62_UpUYc}FsAYkZZ%uOa?_qGLWDc$o|by9oN(68fDu{{VX*PJ=RE zK_41l%|_4S>uAqJ9S?e!V_45obOMkonhiB42|7 zl5m^0Km2ceM&pNW`kvV7n;i_=n#u8}@}FNk8_k1yfNPW0d|X51@4&D{n9#)$M*mOf zmx{pmZB;xrP0~R24Pk#&B)`&6c!K+n?Smb$y*Pafi2r>(`zc;+oDP#7iu?hHeYpH5 z3ENE9-hbY+irWW@U)iS=O!yK6`5`?x{9Yvgvlz1oSz`bgCgjhX;Mcb2Zrr84pW;+1 zI?ax_RHpM0X_)d2eGw8d`#fPyt_`=HI^)XX3{#c5ugB#BUV7 zW9D;l?Bi~rS9=YgPyP3NlLxr7P7-WbE9_e=(a&aU-{IZ18L;evtyZ`Ae0yzl5gH|ALE{gM@9$0I z_vx-O+&U1U(dO!WTt(!6-iFDzU`SiIV=A6B z41gy7BEO~li_-pYRgxX7?cW*B=SLIy>3!@F_SqE*u@=rE{vh`A($wh~dfpbm_z0h$ zPV&==cRpZz)*&c7Wyj|ussGlR@D)#$AB8S;nsEGq;O{y28|LO^%KT3(i7!X3O2cox z17Jj#y?p;z;{U&f9l|4tAz;yZEFY)#eNy#IeAFl$@{g|M@BzVZ($$%mvZe!Et)0c^ zQ~5m9UV~SbID(0zpg*-AGm{I@V{Wnxe)>Ls*y=TS{>v!H9W3GtAo0_|MX5M6M=fMWvRr$AMdW`p{+arDKi(Ll?SDR{^{-J%uXYuAy(zmE8q&C7+wD*6cTAcrH2>sfOug#27pUB{& z_Mvr`={RO_Ye;hv{?(h{pJ=}vW88Z}d7WK+f6D*wYl`qe&kU$KAQ9-prv`fL4TKSosa2UsHfUoOF~f%7q3{woBsV{bbAE5DS#d1ERw(-{|_K$m~f z@i+BnqSyV_aHRhsu|L6YM#&PiJlz$xz7+WZ^=~Ine#4{l4}zX|bB>=aiO;KNf5+n~ z^79c7!vD6rW@12_|K2~;d>=xvAG|r+nZrl*|EJzptgnsl3K#d|{H6GH+`1q2hc1Uu zbx%H@+V5{o58@$1f7$!H^nAJsF2tfC9RY1;@by)+em}<-C#~)TzE?X4`VszR_Fsy9 zQaZ!Xi6TDINb>rNm2EzbXdMFyA&w_`enaNl#gD?`?scJH)+fHc2YJ8hyZ3%Pzi}Dl zR~Pn2L*RSb{s6Xax&n-gg#45c`I#7=ftQT}AU2={$B)|gVO^Kwsk2?c_LGRe3rPLz z#_gFnv};Q^xL(*Fsvk>S591r=56gy+(7`Y7UpO}C2wtDBef-7Xq@bT9@88Lucnnn; zLE7`}=^Q?qAGhsy8k63H1B?>)Yw7*bBTg3VK-eu%`LB22^i|2@H~T66Sly&MBm^qw z$HC9PE8^jN`-xLCi;`J@-Uul>kpT=4(IsU68hJVIDuuq zf}y10S|MM=K3z#;=u@@|uwy!hUqkG-Z=+nClB_+S+WDEUPvtXXp)b0Ru!Ute+wgJf ze+=KO!0tJn!Lz!EA8d*Lx~2Ytl6xwc9T4#^jW44OywI?Bb4YozpRZ5Pk0y>jgat8v z+Vdd;Mf|L%<)Yn>NNCbgz)$5jwoXmfzUoal>yxJbmw%N0?`PF#oec!5f)tQ*Ht0~035cMY@@>BO?E;d~d3D!#meSqk9{TCLj zinf1g;b%b~AoBUHr4^Gt1U=)|raN&s{@H{c!A0x*pvk*p9sT9!*U6D*u)?8G@T_@E zQ9nW|pT{)|!r)b8B*%~TA0E46!3^(Q)$&K&FQV{|+~$w{k9UGQqhb~LH$B^cU9Wx| zY7Ecf_)+;uzi|$y%vl9NHW7S2koPIipU=hFd0`NG?!9hYZom7UHDE0)vSj@^1%!Tu z|I}kOx7>q*{DF%4t4jCB5BECC&Yx&~p-s0ps9zx#hWaVmg{O4Kw z=Qv}@Hi)e%>bI1>-^<>jY0Fpuqsct}r}52(Sq5yPTPAe8Uy1XN+LwAw4B7E9$6&=A z!Cz`WjSJ7CTc}q4%q}Rx|0OyAO)GVT;6Wn3rSQMn@gC=PjRgzWi+q0#;cvq(AF-wL zE*br){cJNY9P_OlpfpFr<%imzV=vC*u1z6;yOrtt>D+Vdo3|CrTM7D6{dh6)EzV2Z z0V<;U~|0zMVt-;&ku(dr*9{n~nQ`qBQ95p$=Yfmt2M zpDgN|H2#@8F%&liY5m7?U4B90-zD|K@t?jupge!6B7FWq@37(a7$})_Nv-7n2R)jG zVau(+D@x?obpIX3;drcJcThc8%-5&!&(hf!aCw(tIF%{rN8_`qcASZ7QfC^ZuH)t1ChkDuSg$T1O6`cG#? z`b=5;5DO=0|2H@@n~$qh^89+v!pE4uKML$miTmAD{=y^QqH~342n`eY8RhQ;t^d6+ zFdD|@4&?OJ(n^M3wf-M5aN$-NeQEsL+Tsf)mc&5xcjf+1$I@>&>e&uxupm>BzHj$@ zLz|o1LACNNx4%?AFVFgpQxfF-MdClIY_G!RKRN_|{~x3B|Llb)KKH5x*|yg>f2jU8 zZRLeU(U!2}hR**J{umlQLEAx5U{}?I(;rEG;$C3Fc67)DBUfX-J`(+U95x3d^XouV zuIL{zBkQlxzMt`^a5coFi~m7l$@;9pTRiw|BSba%oBzr6r%AuhX!vpq*gtaQ{G_98+{ds}EirD|pO|96Py=TG1zlTmf<@smRL37abktIa< zi~cN%U$J)(CTLo~;{xHoG-Ul-4UF0Dz6asz`bZwK z96s9L?bm2NZk|*Jb}UNc#Etu)5 zV-VA!F(0S;U;gJHd!0DJv2eo<9slL)w|=YrztL_3v}!p(E$qA8el=_S1KS&Ig(rr& ze4N^cy1Ra1Ov4>8D#ls*cYXnR|J%k;#cn3=gkN)Gb>njTpD^8!jr^4ap?w7XseN4& z6pSvPnn9C?%K9~E#AD2I3xkX^l{tRS#J|t2RFADS(e}@;U+JKP-?+vqj_v6U>p1Eti(X_m}EIy(1OCDK< zg}XPytu{iw=>6>Jt^eSgvMnVx-c)&NTzQ6H!D+qTYzm0mgt3(S9r^;Pox2|F*q zy)Mw6@O?d_!I`cLZn|9ts_mlw+A!<*pe*sTKl@+TS|C7$8)V~Kn& ztEk7ij*fv?%OGyQf%q47Cq0(BE(XFT3H{O#{q?T77@K(4fL6)-1%8A-|9ts~(MKYn zq;v@1pYo@5Kma;K*MaZe=lFbjKX3W%Rd{Z8Be1wA=tKQa_08t2dr}&>t$L)$|DnYy z)-+kpe-)9>g>Ngd&26_qVTy+1UqJA0`z!zhYt#W>i}M`5SaN^x(DYU4^V&vszCz)9 zwX-3!9(w}znkIAnseS1B=?1$|ywI`4-&FU0gj_yu@0^a0?2N#=i+*E^?}|R zefC3d8&rw%<@y;*@_Ux7&$2pigD{J&e4O$pH@PWmlX4Plhd6NgQ4#tK{L_N z|M!yk#_xYOna|h-j(vtJ)9-fo>6q5h0QyZpMgDE5xePyztqyiw4~lUjUwvbmv70_8 zwei25qI~c9UrQEw;1ooi@e}h2d@cND;rUC3VEshYFG7j@ENy4NTyAfH<<%ulAKG7G zvBi)XYwNeYV*U8IN+pj^yFRJT#yciJ%!_x5@GZJ>i&b1T&(Y(#GJUR;OvmdV^W7FH&Of4F++ouwD5&>3{c!Zu#+*xwqyS;C~8W#pro9gPPD*5~lkt+7uYc;6ShDm&V5?@|_Qjt|O zS}U^;v_9iey)wI5x*6<)#Q8gozb1UF%yxf?hKR>iIQ~H5%Yv)nxT3ce+;Vxw;nzs= z`r?;;#kizl2xvy-^ZsT^pS1i6td2JS{;&V78jq;Nu5O5e*vG#Kvh=7XA6A# zVJhfL{Ik`RKzwn{6ylzRaQLYGv5u(3%1*EO&-E*qS7zM{HbU(0t$cm~@xL#l>ay*w zDbVJ-_}`o6FJbMgur1X#!Nbbp{F~0d)X;=2oV*oE9vBMvsr{>3j%n%I^PirHiuG~N z&U!3**&68Qr=t&%k7vWGvs&k3V8MoCVtq2+ILDd|RVQovm&E&;9z=fJ+WtcI814Op zT1P~ENF~qzUL7-M#V*_7`sz%vK8bHUSJYrNTJL~1>&6NFQOVEm)GozXU;Dmj#I(VD zKFvRDUzTE^_J5z)2^z6Ki4P8yo3rYg7`XGvmCHYn_`OAsuh=X>1LuYhS6sjSwVyco zc#ur~sQ-2zP=$?YxE>xAoK(cmxVJTn>$wNqvjzWEWdG#GHmtTsGIV*chQmkSzj3)< zg0DLT%J)~*meo(Th8Ll}wFW-z8LHb~o?m|rEyXVbwf9eqdMnCDEA6;yaDZ%mYTsg$ z%~_2*(J*PS=#Nzq`3|{m!B*GZ2CLV)>GWUDzm-FR@nE~EP_*f6&cF7D>i@K!_1NK0 zad7dzppS;oXM6L8%%Dml{Qdur#-|lt{lxf2{?P2SIG>^U&;90QSnrbmf8w{-%7VFj zY=Ij~M1LX8&l>ADU|aX^hWY_Q{%QQ<^nGyfp@n9h4PBaAP<6?d4 zA3qsaW}$Z@VApx3II>-u>oBB zBIrx^&+sk7%3jN1@j7MsNYhki-}{8i=u6LsSC@W8gG?XLcy_ZF@+-G*_I(2|wq7Oh zdi;*V2ZTO*wgzFfV100{n9awj{9jM3%({#TgCkc2|AE*?%db_L``(EEgm1LBIg9JR z9wrozbC(ecx~}?t*+i)!&#t z#%yDWoImvbp;3fC7A{snY*Qhh^n5x|WzLSB)SeG?JkHlgLf`Vt+HCF8O|Yg^`G4-Y zM=LY0xuG)pCz1TU_t)xd*8Vl{-BYZuA?pvhUYl(Q*$7iUDX;Ia%$gau-3k`Nu59@6u4O^5O1AQt!;`>woGq+wt7N52qV%~`U+*l&NSg{G4x+)fI z&*}0b5})U3?}r*bt_%5Q4|VIy={IzbKOQ+=CRz7-!N)0mcJ*t>25*Xi7fZzcDo43} zD4k})YH9y}i%ZYp_*4BJ(#4!bY5&Le-o01sPwG#`N6gvXA=>vrs_OCi8e+fST+`sd zktLFC#R5J*n%JN2IgOZMSqxa5>B+~D(5GoN1GZP&fBZMTruOfwUv-w$CIT!6iT*PR z|JLTg_-dvK;#&LJ{n-L4KcP0vGkFVm?QGBI+YRQ<1gqWwv06KgXwi?z^WVh-P*`p?t5 zs}{E6!4<(Z~zZ`}~>`^N`3{WL`W zhW-D+fwAEEyL^oCk&HHN{~Ibxi`S2ngbYqdBWoQ{4~l%Hqr+WOpsIWqcC{ z_h4u-rc_ZrzI>>|LU*i!Wmm=h1}a}YtyIiv!xU}N=Cb1cPnOqZp@plUyx$oeedP6T z7OG;^BPN620})?S{kYrMl)cE3+h;02$%E>!9yfxa$=8npe&XNaeXLl~gAjPt9u@bm zm}|vaH4O!qDmIGtaqR4-EPkWB{!Qy!jjtH9p$C1Syu~SwKlLw1DqFMVgG1p%*+j8E zi66$_ZopJ~wEDTTfq+jX_y5LwT-c=4OwjcHYrp06YkkL*-G1*2x%YMT1C>1gD|=$f zDroK7U;j+uKmXf`1$PeyW4D)_el)(Sc&rK=(t9?{=+r{sN9Y?BV#=0pUkHutMf^?q z*WJyGRWgMqvephqU}bEWpdayHcN?0q`H4O<{OJ0_ z2W$Utd8oAyX*&N(;-hbl4O!O4Rp7F-v7kS(Ux}H|SWX2;#}UP5isv_-qerrLbq~YL zN6PRy?=@v!Y~FvuH>=#5%{>_e-klx_`6d26FXb5v@s%9i4l3{exvMGLZsiTyZwv%~ z2>+Yd)nN`n8j#K?=g&p$E3-ER{{w@k?R4|y^`Ev!YOu3=<@8k%|LHl!Mq3}#{?D_- zT9JN-=h`p`UkPqq^Y}Qm&m+uD*}{TZ5Y%4euT*|gS6i`Z?N-R>N9DIWvtjY4f}n+K zJ+VL0pI4VgF-_V*D7^(b`H}07{%T`Zpf5?T6@iaXv%i$F+SbvBsZW0DXok*5AH8uF5W$ zPKG;!mG!gb#fHpsX25^im*J->vu20KgJ*nuMgA9_f60nZc5}>mR$Wp4^L7tnS$1)d z^6Y?)zjFH(6k3%v+u#mSeytSOcUuo`>GfyEm9uebz>Nt+F}RT)>g)^tic5}l&$fNl_CLQ_sR+M)(NK1E+*+_!3;m_}&x{}AS-bLWpbio9>HbxY z)MITcjF;&rjc>oa9M2x^-U=0R#C%G>^0)@<^keyaYTtZA2C&U{wC_`f>{g^->Kb?E z`g=31*do@a@QoNfnKdfd0$CLUIR13JeXQ317rMeizaxs{KPLafLe53P0_VT+ot%H> z0WM5x90^r?ME!);N2*;J$+A_eq18;?{RkpoRvF`2*r4?ge>zxk|JF}NvQ29vU_d+N z`H{hHZ0(LUU}F%<=TrJ-zEd-cY73#{{#YU3B>w!_#)UP!8w$@4tyY|WZM_!${-Lnx zT%;m=Giqe9Ry{v}@8-Y#&vN~2Jjs>4NC<&z{dDt5d^dc(8+)X!58CfghQC%lN7i%I zTyU~+SA_pnrNL~0_W!K>qWGMD?H{%O35xKA`wwG@SC_)_En+^^uczk!uuC;H&~#yx zBKW2+ubJ{KjGqv*i{Yza~#ZxO_dc!q>e}w-1M+{&`+RTPV zt7j;}zi5s#8~kb!d@2(5lj8rR&Hy%R^i1fMJ6&}9HowpO%mkWVl|4FAG1pe2*9ND8C6Tu{Oyl#DYeel)qLF`9cFNoXMKsPSm z|4GbPHgEZIn9x34kv``}4`&y@d4u~kW%#aMDr5)aDm%JZ*o7-nTxadVF(!bJzzO0ew7+9Sl-lwPW=i23C*^<-V(6U5_KgjC` z=2m@K&;(b=IiRaw5c@ZD#aOoB_AE%X7W-5C;D6kMWu-0vUx-%p&p+Eav8sp1!K6lW zbn+#aKl{Gp*qQ2HVCf^y|Ed1$oaMx>hK&I;XWe{|&wu_zyZ*pYU~x}3PT<$md}HmK z{D!oAW&1FC*EhC%Vi|kzeoXr@jQwo$4~+f3KsPRj@5S~a zcGUhmI1N;m597PetiIE52yj`bI6t}6jcr^#9@6TF{#8n!BR0jX(fx1GCqjAskF$;< z(>o&BZX7S{2dPgro$btgW(@`3UOtNZU-cWuwk;Y18t2nuKB-^(mLJ8|b26l&^%M9w zy&n@aR~tX82E&xcjdbhF=~p?>nRPXB0)r;X`;W*N$G+Ac1?E0tf2tp67MZfVH&x;B z_jY1^g5RbwZmgj3NJ!cu>XVdy%j3;h-h`^);v?c)3jeKcwOCM|8T4ARQHQ@A{u(1Q z@%XZIX~!c`f1>wy2XA&`W*0_4&^56?^}oL|O_|kYBN$t^y(0V}F=niOVr8(FzUk;I zm#;y&HQ2%oV_32`l8@8;bl=Bgc<||dDf-^u{s(#gr~WomHuAColzjiBxc-ti)!CCW zBdEAp^uN*kJZ8yptp0JIWS;srzLT&2XPi5$d~qlg)EEC#sR)0(1I$>;BYlW9`6}p3 z^!r11bLP6(5EeRyD&ptAKMOBDNtHIW74avf|I{>7_R_Nw*!l_lG-UlJ_qF?L^x&DH zGXMK_ufZY?7{HNb8+81UpZ~5YHf5Dm6(Q?{MiIWnW2!TwzLg;Ab!U-3lKf+DEpwLl zr4n5B{Gmwy;-+S-V2TPZ8u%-&Z__mcoxOKT@wuP*cme63%?vPQ^M{p7c*;!duad{- z`ub+9LDyf>2sdT;XJd7i(^LgV7IftJQ~j_hG-sKeDnQIxasQY07rUqqW1{H}DdMrX zKSbZp>u6!h244FiVO2u`AE8h32{RUQtW+A?J3!!1>brXPtFvvX<dIzz z?g8d|bm#lTKlm6P#aYX@OKnaH`qTH(?$yh}gpRS2wShSQq3^R;e;CH@HS7rcM$Q%T zLDo-yV8Uj-`z95-R8YjP!IY!eXWcf*#lJ-0N8X1qj|xPqgz?g{J39T4AD7N>vEwt#Tj9=VP zWTRK?fHU@@f0^DdsJ_vJy>@#m74-bf>njw#A--DtZ@-gl;{^WHK5s}cWpNGPOI~rJ ze~re6PhTCyUy&Q7Li3-B@?rDdgiZ2#C22fLboCv%elK%3WlLMUmdgFa`x2D?nP*H{ z+q~CO0gC-qg#PzksH`=u6M{$ir;*PZetG_4*ed8#jR{?PvLW7AKt zg&)>|YDQZJCH%5lRAY%=_au*=`#FA8eje4_jdN=+maNYT`f5o3!}V&Zn5%soVZ$(8 zeVX+Dw{RH6-di?-TNe@)?f2)mCG6Gu9EfODOEG_Gu&o+vZ*f;fe;U8I^w^D^@AybD zWdc4*zlSrEaL+YAsq}}4U+Mjhx>Hl}S_glrK!1&ne)9OC#-MDbzb+Eg4aNN-s()>w zeloW^$Kh+ZGW;eTOjwuUw?yCo90N%b_)5Y{_{^!3JzL4SDNxj;Ex3V-Z@X%=+YhFHKe^x z{^ap(@C#%YPldp;72t1$6WXNV ziMz8UO*>)V>HBB}6Bv7}9}JBw#W>ynxp^`MJe?|48I#NRM-qQEyPkq6L#In`j0FC4 zf7jgoSf!h{q{%r04x0LHF;wP&Aa}TDX=|5woH*R@4{gKE2MU(eqTk8pu z+F0Zdu^^8>CVt(InYSiL&ex-L^X2yK!9qz) zL9GiF*FSbC2}46iNKJa5Zawj)J;PWw;m4M@ilV>ihrqbcVP_0RQO z(y@oNo0MJFRtKN_{z$~nGFBcF1Nknsb^0NfZ}%)?mc3%Hq-wiN*nbj#)Si=oo@)k6 z8GC*!;kouBFW?a*k+JHl2G{vCr4 z-~+2M(&Z9ee;d)?zCJJ6*y3=gU$LVOKe_%*Y*@~IXzzcPj#tM2$5Ugr(mzGgJ}}Dh zr~ccgZvt+K?Jt>Ii~OD9XF4nqPrMu;*&J4J`9TtY%$=|wU!55t-AdY|z()?46D<@fOKmrRwa{lCsj8NcB43HbAmo|LreZ~j^|Aj$k2oVK$41=Gv~@I;jYo8uimiVeNf`$`MEvJy zARG7CU6sAOxkrkvHjd*@_1CydB8D6Gl{TFg{b@k*JBQdrtQXQ(vT0O7tWW5>e_k5a z7%^BXNEh~#{y$Pa>>zF*KSH|py|ZqAxqcMPd&J@&_(P+y%KqE6mN9!&VYh@iz~zI+ zpCS4QI4?nxRNane@%)e2&!q23_`$ljWcEzdZ;{~l@Ng>b8r@Ht5-R*(0g>-VgUVUA zCTk%~QkLHaqpPu5PP-({m2gG)-nk~=v?2DA%HN9L52f}aFCqyy+*eCxpNs^3Nd0N% z5AFZAmwQPs3`KlkOa6C>eU*VVt%pecvU+g-6cGEq=Y0kiG#ny@T8jLY#vk2d%2|@- zYOtQBj9<|n?fV}eV-6E-mcUFYI zt-&6=+P0IVO6;u&|Jt^R=n~agdRVI>hd-9^r)|BXxS(@?DML!p@lS4F5>_9@I*0m8 zdi#WZP!aszPRT^q*a4DizR2Hf$@>=Z^^KWf_f68@_ct|!{yz_zux9#OB(F;|b^FWx z%fN04Sa#7?Qk{uW)Q`hM67kND4$`d&0zYd14p!NRYx{MV&O}w^^alc8@8L(V0rZlx z4}KK;6Z}q^X5r>x{iGyae-^b5j`v@)Dai{UH@=gi|EO>AizTgH3DKd-{4H*6!b

      !>&vE>y ze~fvmL6064r6g%DhfhQB%ht+gu2&DKc9ASh zMSYLPpV9iq(6drEX!WZhL>-@q^%=eu^1ygG>ZhQ2@e>ESOH z^KSls&i8am#k=~AWcj0t*zZwYkK^+39i$hl$~b%!{(6^8Sc4ZqQhZ(kAE)-Y_x2>L zkzQAFPB7r(1w{XEFG@wNa+;xsqhu>seh&H#643C-+Yi*Y8EENDJxmyz6|N(%1OpVZ5DISK4>AHiwVC zUuH4sDB4=pla4?#pC3x_>+n1YEi#QIr_ajr<%((8N@XUiA5i+Wu91a*oa;&{-35Ql z$okgpwDs4Ev!$Yp|0&WZYH|vOmQ|KQ{i-SA|Fqg(Ol)T?c}I%;5{P`&Ier-PN7azp zL<{^We`?M%VM~{KN)IbfcSQR?Y-avoxHDauKmW8yM&EKhX@PwppN~YpU$sxc zeR=v)+8Aa2`Jc$Zh(0FLi+!(j_{;O-2OrGXghT(6EN;El!6(mOeEn*(Yufrpl<^#) zA0$7UVV{C|`4#?i|8tvC(6~WGY4-DAzJ4r$-|l`o`u#GH%q&cWe3SP@0;*)7v2SI` z+w+BhpV0rd>k*vdSXFvBQuHs;^MlbXtFsLqCrB-BE#&io)NjrXtIga`d1~>SDexoy z(=ay~m#ivPf2dxC&!_sGTAYfluKiNKnIP<+hTs<(x*tuWD@dW);{8#YpA9*61Zx-? zN{xDp_t~g_zND4UxXDH8*f_yo>YpDT+>5um|5Q(UAo33&``>A>4{h%KR2SOa(BUuV z|2y+^OgLDsj@VR<(;rBFlWA+gn)Y{PwYk4ZC_;YQ~CZfb{~FN{8b%sP8ojB7DsW$*WczS zYLAu5^?CPWHJHCi4=H_dGrm8KpBnd6ojP<{`~I7L9Yy~;>Ha=^v*y0qL(hiqPvx(l zer2|!xT!QkXa7|Mz84!U*z<;V5{%THuM_*R(_VFIOo}ypEmOvS==%i3-MMPjLtowg z^7v{@6BBm*eN)M%sd+aC18O8Q|pB;($QDGevK7X*oQ@R zr8XW{b^FWhV@+-Td*@Jnsld{mk5l>Ce%YMeeAz_4Kf%BK-~{a7?U>rAvyX0l`Tq5j zkK^EF*VV=kY`A_R$v-M?FlLr^wI%0KW5oW%zAe~MomES>mI}U>i~NA>KR#{`njK45 z8?THXfOZ>$iFwjCY1FQ8&v+9sT6-?PKE% zd{;L~U65FV%Qox+S19D&qu<)2c!04{R->UuMUd(45i=JvO{?E&}Oy! zT(LeqA30M$1D{{ttbXUvh3`-EBN%SXO3Xj03rt4w{VDzv%2Lt(N~ro>RdGH=_dj*& zFb>L!QhR#U;_K7@8%NYWg13H0sdLY~5%eMFZ~j{Uw_(*Ph;de-lW5!^B-rS=HAm((e>) zq`Tt(C+770E>;S_wH>;uE4__Z|2rN_;*+&Lsd#MrJhfM(=>Jj?|1Zt1#DeXPt3w-$ z{#Dw)5bjisspni!!+JMCKO%oMYXo3H%U0?q4fgQ;fxPd~@J|~4$(pS8Too?pL;gpa zHM1I98GKybXIZ{jUnSSy;b;A^N@hLvkfmaM53;_;pA__{JzVYGUGNVGemjG!v0-le z)C-P^{>lFnpXB=E)qnFI-4CVU%S)gxoU&5DPu4dvFkx=HcBx%r?+f@zeYMIA ze+)0vSL?qO@YD5sjtWFeLnC$Ou4(Fj`DaG{XRG_r3%v{r9AclGbP)AJdH%J|%^&*> zD0UcHCf29)acvTS$(O%7m`F4E`t*Oh+#x2c`uR}xhxHG1_{r(N>Z?Cae)rJfxT{#7 z@;CdJKfe3*&|$%vTYP=`zSDr_0XU-HqyOALAjO2aKJiiKKYPgc2SUH(8nf`2;ROfH zjGwytquf3h6#3(?Ugu=+ITQX>s2qTcC!KTfjTQLQ{|7yv1>&cE7aUp~(&O;c{R`r~ zF-nSaPz^<0eNevt(bfUj=f!>*ej38Ri+cjlBQo8=wWgpCz5mp;AOM{or#oo;jrjh~ zjD%9uu)Av&i z8wFyy<{yXk)pYxl{^yU{|3U8Tc5sOH+sg6R5d7cYn2C>Tn9Ig#eWAi`FLaAGcleOd zLcmY*quaLw@Lp&m2b)<9IebZkJ_bQEapj52_7AT&;qzn3{6BVHm@@8)z0sK%4j2kseOF(br~)h z=Vu>vTl}v`>$`D30x)B6puKm~27G-=|5&SY>>yrraJnP%TiSnNRT6;j1F!Uq=_BNy z>YqdDS=M<&eTM~ml;^)mU5sV>PajWu`;pTpmekj`crC%QL1&I@!t)jBvm{gdzRu~Z z$IYMnEAsFA$Fr>Qy80&?tykVZ>itseU1vjf%ogDvy-ECLSw8?B>ut#{xmt^_Pye^Q z=e`gJg}%z3G4Zr+e|dl7@XCwvUG2BozE?-^ak_ra;{a^yRGj^ATwOj+|JTgZ3qKp2 z@u%_SuAzZA{85V&Zk6hD_^A9IY5o7`y7IW1y03qm6q*n!m5>xk5#mYRl7x^cGnr?S z=E6l9Ns}oau7u1{XwW@tR|rXxDO2Xm$xQT~_hawttl#H6fA6#RUhBKYz4maTV9#Eg z!i>8uX?`S;HW%zaScFHzg{iiMdDqv_c73$J`)EiCIJ_HBnAs4iY!~hi+tjHR9cpnz zQ5I|>x_+4=a?tA4}=O^+{>uI!IL=Usz+XoZ^T5Z)sE{lx9yT)Q)?l#9t`C zInL|B|HZ_@(}ntsKUX1tjZV>^;WD*wdVn~89Rd^K^ohlVHVtWHH$il7(?0!8+h5P>|rqPgY6jgZAU7UaCQwi|<+Qve! zLlKmJb625!H!sj8KTUKLsiUhX{WyPJo!OS`h&NOiJnT#R`?MATpt{revV|G8^xLTelHq7 zZ>?Gc#pW7{8t2ZmzZA*;*Xv;L;rDJv^z2CK!}ewG8V((Y=qh~AucY)zP=2>-&`IbO zGE7n7yMy?uLs%TB4`8_qCHKeK94$aIv7R!eN;>eU;Ks zxO2!*;lCrC(vR;i815)0Ki>p!Fjm|@Tyech;x4Y?BzDF9#PSdS4~t>g({_rwNnI&@ zIR8kw9}F6UJN+kqUj0JBvZsZBK3rc*)5`(J9?KM-9dc{Xw z{^7xbC2+K77sWSS8`h5GyV8cw-y3Wd`W;p}|KShM-?ncEXsY*6$iq9(b}av|2H6m| zb(LbmJbOBR4VwS;;A|N7XqCdN6Wia$`OCDgdPUI{SGl_vK2iIVBL5Lvw*V$P*($R3 zBo_XmPmbc>w?)f9V_8pyBrByqvmc@U*Ix{R9<3Y|VMZ2|e(b+8twSN^X+Ht}a#UX$ zaO@-uogSr#InhIuzwl{5+MY<}5--{-?Ng|~`o>G4+TTeb`IoIP@%~kw?J~GOW`Lq1 zJd5%tL;M{&a1!=rC;aF9?MDLfEZV`zPq*Whc!Z(lYin}1!o zz8BK}vU?~5J)5jhEM)eB@gZ?*pv8mP3ZJ+m6dzo_&0n1ZL0jaC4bG0rcA@{$E-ob# zOiyw0jP0WSsdq#OsD#Z^lumgmD*wiBIS}^qpu#h%KOJ9+^l#Ro^W?65At%kgBszY) z;Yk?N>bRohWOv#h$Jfr6bjhJ{I-K_4xytc{_1ls4p2Te9V6LL@Z+%g?|Mt)1GE!fB znHy2W>d$!n*;cUxvPUjgc-rJE%cpd}Zxc$O%A zF`1sEJbfe=*^SYM0qfrl_3{ zR6h9pTs{9j=vF@?u59cKQThy)EX z@}HPj{Qag$?YYSH;{5sgErh2o(F*zEQc54zua4u^K)+p^6#-og==^wn?%pgJVA(;1 z<7-wQ$N8ZONrl@7jwpJ1op=7@|Gd%r=>11;29vQz6`t;!XgkLDk*Y4~kzmPrd(Ncu zOOgM(uCWN>3pOa~k{P}-WMANw3|DNj6i%;{_Y+b5W4}f!qzyZ%h^l1t$q{`{!KtwP z)=7nYdK|?^AJzB1Ur2>p{j(LxHyQnYsJ>d+YBTiPmaQ0_W>5K(p!#RCTMJ?5oMc6f z#d$iu9m-EaKPG|o*VBrp>YT)!BxAQ|iu&M4f2-zwXM`RV$FDRBQ*uEM(^iHL2TkW3R8-9OFZ`n)25!RmnAIW~%qW= zK=ha@g+;$#R6p?hVOmD1kiV-+acmE>pBnW3oKAZ`c&5lwZ1DMeK1^8O8h0}pmO0;1 zm{7F%MrLiOhCUmS;)FmWR`CN4s5)evO6twr;T zg`If&O?<2v;?DTT{x_5NZ{|r)6c&1nKm30D1H~37*!x@|?a&~KPlH1$v@5Sw$h~{9 zc8M@Q*|#JWT3WwU$n>o!{SxHAdoLYK#+L8m%s(BV^yB=*IlPec;Lq-V9FXF|@@wJ$ zHO2)GCK0K7xtfFfMEl>FHH>_y+|S)BOjhDA%#UK_gNb=?CMO*&XZ_LpNcMT7N#2VS zT*Az~qWz~0Yfh?6{5VOk<1~N8`AtBEHaQU+%7Km3*+2AS{J(beAd9DDaW$QY==`s0 zwMm}@87I*iL;K_LpUu-Dv((mbwa;1n$LDKq7I=~eMQ1pf<{HuQ{ZDz48^;Pbb9b3& zdzbW4WT{~ZXA-@K@{i9)P3PbD(zsE|#mtn8w)kAjFFA~2D zH;|Qk()scIdDqM)MOok1!2Xa<%Kd+#e$9l@#G>C-E^%gt==_@>T_ipF4+e>|yXg2) zADa|y8o8c7<0?MB)x;shAny_<8#SKx$NQI>852nhx4T@N5sMEPpMhpWNNbI&ob=-~ z(f%7|3?r7)u5n&QsiOMT?%8>w6+axL_WMQYSK%gq;we(*T> zooPVv$M$vJMw9G3oXBPNJxBY?QGPjlk|*gu@D?ZCzLDXJ*2hy9dlByNT~0D+Ce6>W z{|NSPN>p}k;i}Zd&xd`k7)n%HKjfr0RVaVBf4g5AqRPNyt$IPMQOHh8A zlI})&PI<`X4`B0S`zB;8nbG+>=cU@2&5!yA88#(hU(-3Q_$#9Ph3e>$;~frhK?~XY zi1_`MK!Y}!gEY>mw}z5F;rg$7 zKrlQ!-iC|W%g$fn{HJMJFl>0)hMQ}~&Uf3n3imha(}SV?`!-y~qak#BKeT@_|3EOj z`p|}}E@$uO#i07T_pA^IpVyYF1BQ>Ct8jnG^>qluo^8w3JZ)t1LF=cHCZW*(Zd=Z8 zbOVh)fa33)h%mT)#*jyPSV1B*hS&jMpkTKxGe%P)obv(tl6=xElC zlNkC9_|uNp7cX+dAmCs-?%T??&Mf{2={xb>fHa+!%T?U{!RANww|?VF-elHsUNdE) z^v7C{CBF;R_&e0%??3*q3WR@pw&VPyj6a;;_q!Pgx6<2j$=BKY19*SU>}??AooL6^ z3~5dEM~d`o^Y=iwp4X1+^ERBeSD^c?0q#Mt>Qy_gp_<*F#r6C089|Wzi^ng9@o$dw zXYcwTxNl&>{oP;3^@TNx5ZDuC%GLD=rTF9X1xLPyz@@{coP4t}#UGzPxfH5LmX_vl zvUw{gzPLWT?VT$LZuOb7+RpID@x|g;0BG(qkA={)Ow4@p^%9afdnQIQBX9ALa<(yDov?cb4z3 z&Gg$3`LEKAflyOt&gGhk)aq?(!`kUPkfEC)-|4DyFBR{`|HCLs=_IKo{{t(tW5CR>nxlaiZ z6n|gDpFy)AxckVOlj|I&?J`s!>17bW>rXd(kEvV49Z9Gqgq z>8Hj}`z%HF=^h>kP77_g{zB?hKz8gpbG3K=4Yi;p)5Fx%|lw z@c&F|5$%d*ROzCL47#=m3{gP@UKDVKlGjjz-q7lT<*f{qVnD48VF^n{kaKVQ3L+iH^%4m z?-j5(%87G0DXu@o^8(<)9Vf2N>=nfi=Qq1}{%_uM;x=?={9*Zi<^6m7=mFfeC*t(| zkOab{F#|aF3YLFkd=q8`LeicAoIIt1>IWeH|M@o%#$DydSDsJ8{_*SM0N^B2?(g|V zET8UbfpFYd%2gbGNBP6~@lQU#=;kWr?#a!Z|KNxHb6-9`t2xP!-|H@=56fp_+6tJO z@5-$#Vffnn70@xSf6A54*CRw zbLWBFhJI{)iu3o}C=K^78{Z-|NpPe|UY|<#Z5uySsB)tHP;% z;rwx2Yu^9r4dV0`F#d7=!HJlLeigjbwj zj0Uy88ie2b7ySQmmwn)@1~}630nP7ctU(4H_{dFo$Lha!NPk{`X+n&Rzj87C+50ef z|2-^Blibt!#!VQvmaZ=)$i8;keuw>^pL0&*Z#e()pMc)SO`FmPO^V-ezAnv0>F;8v zPA>NQ%q6bxPwB_!15B=IkPDvQI7yR>v>n&4)ovJ*f`@wWG+m$0FGc%z+jjhfZ4=*c z^QSDJ?YKS;?|;Lr$oE`gj1Hv_>-W_p4YJGpCs(wDt?y+>e%$AuFvayf*JS&A(ee8| zl@Pm(&XmyhO{x_HP+lh{k^&@Cv6S8W#3S^p=(e@g|-_X9z$l*R3APHJZ;{&dL zFP~&WdOU9f=J&+u+jy%1;%0o|60+us(x;-QMt;OJa#|(5Md^z=sYV{ok$}H*5pCCU z6V^91tlN>=jcuXLi9$L)-rp_V`V%GuedCHoip%G2ii8|)@|*i)DlVU*O)BKy-;JE_ z1#tSK- zY6ALjee~pDb)pug36YsDls*aafBqk|N!LJqfRGnT`i1&a*Hwp!#wC|%dNQk8##BBGZ z^kM&Mb+b8H@J}0fTK$x^%aDKF`m#BR@oob-*6jTrDO&$X3XMps@twi1rGm~cNBm`P zS0!4vbU=DCjM9(KcYT~>OcFkKf%!6q501|<{Qt47`&dJcPBS__){o9ADrDh$9q?<% z@-uw?;O=@A{{M%%Ab-7w;fM0WtIdqaD@QA+9^OK9eE0rFBz=h$^cuqWGe`B27h8V9 z^u5gm_Jj9Ns#R5pwW}VOU&vzmgXYf((Iu;A@&0EvyT2ht_%BoFk%DXO;c?7DYX5lu zH8jD9SX6g~cW)Vf5=37R;r)9r8wg2lF3O+IxStU6OB<@Pnf+t`?b23_?C#PEBXw^{H;w~1b0gD$A3vs{;!@9 z34vp_a3;qjjDK{$D#qE0wxFW=L;;^`B5nv|LlnM5PEbQmob&y z@4@dsXpC)y>AX$^GMPK{nq} z6rc4~{QIdhI)Ta8a5}ym#i!jT3`yN^d#LZj^dILh{*~cyuVo77v-~9OkN@v5!fP$O z8oP}@U+|5#o1^;d08>>mc$%TWzhV4_$7zw{4eepVcsFOJA42~YdqA5kyl(+nn;HH3 zXnpi`h#@(a*%Q)2+5KT0|7RXiB@HKyLE65LsQj*^X^{uz9iY6#mCi3i`Fp!wYUHho zDM;Ek5$)fLkB^~tHehBQ!|*})rfH~?xtH66M0+JYzoL)y$9rf~a@WNYwC_En{Uyjh zbl=mA)II3}rTiIsmj4OkPvaDIa_4FXsCzV&wqyBz+^IoICU=6K--kHU{^&eS0He62wC@+>`{hx2n? zUwy(g>jOoWU1)#&e#ez2`otutFXUch?KNopu!U_%^Aj#m+ni(lCBpUB)}Kb?pCRsG zXH-`BM?N@z8UI?1=%iSKWZDLLe+biOG+&=6D*HiXPjUX*JGUWM7P`W(7UJ{Qj*$bm zzMOL$(n#eeMfIoL)IBi2TLt%HKKs8Np#8tVN^|njb|f_X{l6xXzrzw$(qfD?+#57d zIlfT;e_v7~*UY*J_`~t*+;|<*@kn3z`+qq6eo^7wHsoP{-gJJv|8{LeD>8hPD^#Vk^Hn&%IJ=|)?$%gB{&V&|AkMEN>l;DhWDS;U zIXXYar`mS4~o}qc?mpWaHbR@lEqpNYjV5P*>;5=tutdRg@NaXXyw|FPtcS z*!~Lm_+;GM9?Dj;`c4g^@Aq6)(mu@|p0*lH$H)1fL1s&mujUEUf=%f7fb5rRCm~(l z^ne5vRzJY?<(17mMH^QZap78iHd!J$(s^4~Mu0o#da)5|pw*QOeqk2r6 z`ix=j$`_FMYtSf!T)y>0i`gBT~3*BE%fNP4UP6cS$BsU#|z8eug-GZ=8NW^36Q)fMbQhMdbrVcynmYZL4{b3>j#$qu=+T@zcF_k|NoEEp5QjAJH<~Q z*;i0!17fjj46OaY>i1ax@7-ukVs(9>=ISX?{^oPd$@mFFAo9yOIzIkCwvkMofS(jh zB<7;}{dIH`(yskLc>3u+l^?dBuOpihvTiWkdmTdC@%pgnp*HCaUf>wljm?kj^O?ec z*`tka;{znrs@4_IMIml9pzp(y4I9ije+Uf!NBcIUu@&3q;&CQAB4ln5b zK%D>cW;&$v;}MYS)s@jF5$3JryXQsG7rUpBo zD?{`J=r<#Cn~#8R1KIgPET6`0ZOF^7zA*oAiKzaZv{NP1$_7I9<#tRz(D-GK)X0tL z9*_}qlktcAw~bD75;AlYct2XFY!~Ja<)*sC{_{Afd$EAdFOdk(FYos1U9>1EhJ00A zr}JC53FVXiNR`Oec!2zpxP0{AsguI}Lm<`hu5x~1etn#O-_B{*c=-GNG4>D9Yivkr z?{&ccpnL$!?}YPD7~Z?6C@+>w)U6VwPqCv3(Xt!?zS|y)&YvEkO;)fJc##y^S= zee%r7#oa+*GUyWPFA?JBBC#R%I+2j|C03NalI>+=Uyup8ulHT4pTho5c`3x<%oA{F z`^$y#XDoO>C2ve4{QJTkJO{A&g#B+mA76vF4+5Y0!`S$!e)`X16{3G&Fbs~{scaXX zuWT96oID>j9%Q>*DE~5~--aF?$d9?95Vf(4@sIrb>Gu*+m+lE=^{gGQKX0h3kiI3J zFnZ1iIzO(j1#791!*#Ww!YkfdBU@e^=$Jg_7wMks|B*^Gu?feHn z39{b@XWNoqiHkuJeT(vk&u10<)0Fre8xL9=mG+7F`~JK+x%Org5i{0QP#^y2pz zH!%52g!Wr(_8n%N@qpSL?ENVmUt=32sZK%GSTPXgax^F;ectZhRakAw*H z2gmO|m%5U+gEm4`!y(2$(tn*&TQVXo5x{EV05Shk;r9b(xqHJ}P38GERG+cmq(Rtzzi^2Rax zQ2x|r*E=XE8VvPA4%7MNNIz!v*CA=27eo5#4s3kXf1Q5|a?mUQDy|-+^x^u~^e8Jb zJ!2!>4Hu`c`-u$?~ttd#nX{!bFWN0(^#SOM~@NpyUi{~pM;A~`J*p{uHL ze54=O3av=6aUxhvN)W~0(e@3bE*J{ctumSX5&l|}zkpmi1{Mc1|0zfMbEWwfSa?(d z5zXGw{&@ZNIz^ZC{1Wh=_$-}dMXDbr!WMHS{YZZ-w_A}3ZIU45+eSt|@^2-#?aAo& z+d*pptFPev)#BkRP*EKQ{dM;<{!o1ITlf`zHjab--NobIu|{2TzdRVEpSDr_v44@9 zbtZX3Ho<($y_7zDzT%B@7jn!p3EJNh=Pxh2HOacZ7JiRo_Y-6Y|6`XeN#D0gP^Nj5 z=|93}L9{kGv?v%VW<*l@u>Y`_-I_E@p3|51vcbUcL;9gF!CT|44-Qv#rXs$k1$mNb4;gzee3LAQfFB!MuXyKT?$6 z9X#KejG2-GE7yq6zpkYo$(FAMtHW~2zZ~_yRn?lvU$2LT+04Fi{IrN_OAJ>;!?Zr^ ze3Jy>A9TTjlrK(!d)M5MHa~AB|tNXfD~?s}h!W3Ko^WhLZtleKH!ft&dat!{_(Z ztUHsNlea=lQzd@Lz9U@c5b2Rh=vpdH|I$`%$o%8Lre8=4A+I^F2} zxc*+LuppgVZv)x%G*S847R@C|yKX>fq&R=E%M8fFnpnuR9z)|p4f2l`gIkj^hvVSv z0k;0e`gLBv9ZBK+v$l^uqYvqCw?XsB>&#p5?T+~T9j@q+A*-W6bzwT~kMr-mf>vaF z-#Bo%$KpSpUv07(896W&ymxnC^P~H3z4qvnPNQQWv09h%2gp8Zx*L$5Iq`5WlJSq% zN7lcn;+*_{Y-iPacTp! ztYP!x{JwE$8?x$30=PM|`LTV?$}%Sb7q>y;l;c$X*nh7vwj-`v4?ysYz0Sr51zcY(K#C*vQPccF(+jaJ3+259zVubbRx5c?1sfYZp!(E^_%f--H6Ke{g7~B zKgAcHpPJg)xMdq4?tZ?87CdWT;UZIF??g^ke-Ao2W|?x^4jNZESxV*eu`ix@r2kbxAthFQ``(?mvozV;C{%3tE*C+CXP4L5+%@4?b6&SQ2bJY@IT(2mme~AA5N6bk7%zr@(vYGy){9(aW zEAnsE0Z4bqr1Hh}-MnA@1!=VKk=8yz2h5IOffX**J8DvPtPud2Cci8zgEPq9`aZy2b z8fg-5OxM>qKP>UW@(W%UZS|r54E$65vhe$NH(g&6J#YwhIh&tZ9Fo zA9b$iO3qC=0;%`d`4jB_M@H+Bsx?XQse<8$obbt46ag|`J0ZFW8-5xsx# z*v*uf5jptoX8cQ#{&RENlNVpoAw%UMqaXRV^;=cQ0gLr;Tm3Ko!un>H4Tj{3#=r1J zyOk)ur#E*Zt=D8i-7EG!9ImfSJKC1$_4pT{SWmRSVRT0_ivNdm$O`tp6YgJAp+VNh z#)HH}S^q)x57oIQq-fe+h^$r0M& zd)-usVqT1(zXaKjA-{iCeJw_CJ_+l8N~0mU^N2q~P-{f_mm&GgR_jE1Zao5qF04L| zKoZ##CzM}d!Pu+|pC-eV+JilMGeaXJxU@|%ueBUYS z8%RF}955!@HU~go$CAyD=pWHcLb5gDL4NRu==qZ%m*!;ZgssqVD?7i4<@@VU8*=se zUg&tBRH+|A{R^~jOESYUpyk!h)PAsi*6lGTJMJEXvc^>e`Tvi}`<42VP?I zBmQ0)wkP$0$6&UPi?Us)KUMBpB;9Ze$Ojoai`9<`W_BVMNAds2Ec~qOFQi}1!IYFH z9Rmj)N7jz;Yq{K%c-}k)c0JQYe;k~o^W*%^w2vj}G`0ZDdoBER44T zM_rbmMhMJPRTiO4)KGvFUM)GTNKpLp@-zYv0p3{M7PRoUmjUSc#3+1~k zrVA)<(QD5Z7&6=j{{A1<7rl>QxZa#_!MQMd>IcRj z(%)sDHiP%SHek_|@sIBppU#PeIM4Rry^x)c!~e%q?1_gti5$Cs+l6~uo{ z5Q&?|@;mJRLkFmm*%Q(r{fM%@kMwiuKob&{lm{jyQih*IsDHg$#KQmIZ;&4Sn;#4J z*KG|{Nt+Hk{&WAJ>(m6eKeQ`E?#yN5qx{cqX(!TYZZX_UVdtMQf5z`rNXoArg7bOU z|L3k~O=jluZ}`@>SB@{F|LllZn9-{k_1SS zbcetH|HS!iaFZmMd8G%~loiwQYY=}|_O&KgtWSZRPe(={!uQw*WAZJd0220w(fMV_ zzWcbE5rdN)OfX>fi}Qm#{RDVCo~O?th>nlxyZ^flS*Mi?$LjqUe`tKI0wbb6uK;QS z#OqJntvV4K^$W1LWFZ|N+s|~V73n|p3Y<)2_gAp|<}X$!wq4VqNz-=DV)1VWzjjzw zY!Ckbu>3@Z)<2#-jfn260?0ifPT%G8CZy9OfJ497{~K|9{~W4bbmwF`slFM`_UBN3 z9I;Z3THhp~!huWqH z?(bmvZ0xB<)GqG@{W~V2{0H4PElS^1LJ~c!DSmaRK3ZOFOx#Zpu+(Gu6OP{wkaEZAM4RAI?t}?RW)Cty977?Ql9i#^>rgvm(jVQewHN8>L_3CiE{e zN+e|Jt#tk$3dKtNg!QXMyncNcvmZ(g#Ph%0=l9{*lMUdrsZzB6f;h9Hr?wY~nq8FZbsqy3H0>8(l6L=G%ss};;Xh5qlF>@LjG z+bHOd&$kb1`x2^NZ-yh^y+r%xc8Z1rV{D;j%X8X(8_Dm>_73F6@e1&`%FeGyk$uV@ zzJTssw!rO?Lq*4L6Rlp<$@4IIX)F`fujZ2_WNy%Y@QEvOX7ODpAGhE9{z>@>I9W2z zh4PQ~SElc-1@FYI;JJDPogdrhtw9~gyR2&h`f>hQ_2oB|jNT8^OqBY8@V9+sRc3vxDmc}`bQ8yWhj28?w61p75*Q(i^chG)LIK8%zHr2m)msw8l+#xOV@#a zoINy4W%ZFv|E@vv8|bwnZvD@LTf-#AAM&qZ@dictM@z}1tl3n4 zx#)gQhr~uWXLb}G-_(3q_cWyn9>ziLp_wWNYL`p>8G z$NX>K%%G_5LM3^}|3K%Df57wKc8G@5ty0LG z#{3_yzl1$bgz=|G2=KxFB_SgTR$m(_upjJS#&3QJH`NY+^x#Qm-$?%1YYmDX_OBu{ zQx=HQ_aQ9~GWL4FP>l;rzR3SQDo+H9!jX_VzX!t~olhSXehLzF)^ppu- zq3Tx_?6PI~5#FC%|B!zlU}*vDe>s-MUtFJ=c&r(Th4V1Q<2;=opHDjZ+r? z^NfGA{vK6qP-J-L1~J>Rkn(>U>Bm2HvEcdD17c2`qvK=woVa=l9;mK^MXzd{ssBg( zUEQThhB=*u6K@#(czssv+KjB^A2&%WW8-7`M|SN&;`;ppSag%okL+{!ia1dH>Ir7~ zEIvw+{$^}E1u@6hLD$=iK08F;Ym4tNd2SA*|I?n)kH*j1twHjR63|#Ip5OhL(Tse| zEQOL{R=>sdfni;=$ye9QV0h^Y#SiDtUGF5ov(+QPudxelmmvRds`?b18ukGM+A{u; z{DxJ&1|4!3lArdW^ke^Z#yK9Uq{Cq5sWLjg9m2=m8eKvBf(+!}Yc~AWPlE@J0E5`i&QG9pE4~6>bkBM;D_HwaO?XC<~7R!+Xov(=hq(c41C@n1lg4oCST;AmX2Nx zL6ZhRg`Cx&0mYX=J5E9L+bD={$MC`W{owUmFj$hs-|x3`{$rmKq~E<)NysXqfW=A7 zK5J0^Fg|!4)Gu@ggI5bF{n-C@|9uLwRARsb9@6o%kbHU!tA$PjkAm#rW6EC*;%}z? zTR8qT3o^Db`fz>1kzaqdTz?E|>Oax``l$ZW^~`E`|JDU2R6e2fWg&cSPhJQ2M-2jl zmy2k74T@jU5D#sfN5k!*RkYm?*~e0g99S6^4H*j=zWDvrfyKY!%oGk*jbQl65PsLK z)k%-N=K(fjGfQB^Sas(=`Xk5me`-qf z$}2#74YObDzsJ`$Ba;VKLeV#CmcOI=M(&i=uuQ{E;2$Jz!uvVySJ%VkiX)Y??-_Jte+z1zN)MWKBTwhRs69Z=(M#Jow4U|5dzc$G_0Zt_`g81u==$qF1 zC75>M>1*DW(udraW+c)427H=S$>vArLvBX~La+P*kWtOf zSK<0wGyga+ojne`jhX#dAp0Nh5d+yaW8lp*7C*P4cH>2{F!&{1^dUTx+kEj zOROM%;rxAOyN_Vj{4CT)vit+zUz%1F06PXdL&g$DKaQXMJ*>#`3{|o-!=KrgL|9+{ zcF&r)K2an6W0d>2`&@`W-{_Lwr6`njQr` zZjXYc7g&BAgYb#i@eSP42-F!KqVkm>|9`Zh8EJp+Hq@pm>q}^T7~mcV{qDGc)j6jB z7RWv-`@IH#qg-e**M{mZjvps_e}z3eh`_$3$i6T0{^`rpJK%X*e14nwK+;@ z@*ZdqeZ?_0Kf-UKP8QT&j}zFJ1l31V&A!6(GevMH!+_3@-yd5WnhgKWmo|C;%hperzpD0eP~kNh##U{n^ke%wyCE4i{hkjo8Q*C;Uf;gt z_djdb@OLb`<Qj!sWt!1WyPn)HJ8NA_o$_!N@Ap8{yE zDeB+OcKrrFuAGCAIDKca{H*JqI0y@z3YGh}G5S&d(jt!c{qLs0&EMku?+JMfoBdD0 zY*R)bjz1r=oSyNg8>HTskeRzF3WQIDKmska!4<8KpLqE2^ z!=-WH@nae|d|~(Zv435_pDj1Fo+vnfQiJsG%Hmi^kxYZC%q@(6^ndWzI;WwcMGDj| zjuOT1V7sRf`s563dlf-m`7l4DhiHG9-UmnsD+0q7gtp6&edz~$gt^N~ z1pYz(-|B5CWlD)6LLQT{fN}mkb_sl_Sp>Oh7_+}5ZJrm(` zyWbJ;J-Pv6)-wCR^tE2`3l@DW|4;fBmKzZR#ZQRp&(1gF{KZVggq-tj1gl|Fss3aA zu|By5GQNxjFBeun!txEgp99Hhsc_Pl$w!9n5BK$Z3XVYqpxut`@8kOKK&^V%e*Qe< zUfm;VKf}#5NcQV$fQ477{z*}O*0*O880#&Aj;H>{H{tmWH3Kd3`SwG&w^iJ~y$uP6 z+PIM*d-{&zzYXQz0~STWF_&o|@5171Ol|A}z~7zv42bAFsb|hBP5ZPCf)1Gln0oPYqjVL%u)IBcmK5 zDgAhV^Xu>RVBW`9kbhzQ4!4PgLz#2nQue@`wb*{qgpV=JzKS zK&Dd-oj(`R_s%~WxTOogD}?E94Z=6Y;S6}(`>E+lA?e z@ciW2n$Bc$3w^TrzS2GseRE=>KzH&&@Cw~Q$H((Otd4;PtCvD)2|NE|g7z1yKimVU zD}kM{3_lz{TU0!TwL#}WKWq|}e+{BPWSRxJyI+rtc$q}yhx6+W8)Cr9cNvWR%;uM% z`O8P=!S_!)sRu)y7t23!{_%SMW@zAjl^%P&MA0NiXfn;^A?R?Rfv9dPyv3H4g__*%#W5@!#JV2djRpg!I@`v>n%fJ7k7eF@^aMXJ%v{6~?^2a}c)JRa@-t@8nG_#L_ zZ;CD(AFVHzcxsdU<0>TAXAy13`E!reWfW3dIobRRqa;m;27ziIAX$k@IW z5*{z2{7YPg{MQ+0fRFn&C|{gI+hwjM0(@4imk@_j@8Ibuw!V>|`lMqUUE*z`P7;0E zG5wJU?dM3ZXn4Cfg2(qGr623}v)S6@{CG8zHO5Y~f50*w(qybUaq1bY#80T7kKeT< z&!U?Wg@N+?K9Zl;nk$5VM+@LWY!;}$VET#m|6A%=XgTi$__{Mn)XyDDvMGQLcWNE3T7{!#p?-=s&} zEHugJnd>P3a^zp!9vy_t06ENYy-($j+?dD$SDtxxg6{>M1<1~i0UhWtW%Ha?o);id`M>c`V}T={=B7omRI z+zyBFQGT%DJlj9P^&7kI5&Zx0mIJ(C_iJj<`|iKwdC<831bAO%{uRsLHTEo=3(tWX zV_i}DTkbj!YQq%*e7#+T^)st2VGy*zPjLPp+t2$M;ovZCIRuQcq54^i&bPK$wg&Fz zgn+qhB5lX?ADVU;Hk4&RL&05&pA_XsI$9^-(S$<~*DG8U-|f%B_}tPTa$>G4sDDNF zG38($)LuCWex3%j9mnrEpN&cN_|`=6CWz99~Sx}jB2=*TppFdzx9t>NP4WIsL zO~;ob`@fPEMpBdfiTZv`jg8a$|=Rf%4{59fY2y}nu5A)TTe&hH$!YvF+rv(V~TaLy*ykRYWHfS}x zvT#z;rz40D(K~j*srzYy^KWvbKZe^~m2A*%lMSTghA4lx!}H+E?OYfdf0Fk1b``Dk}*QRN5cot9RRoOo%cfz5~9B`u9dt7m{G&LM;27aQUNuQj}js z=;weh@Bj2G2a5VXnJgFNs(AqK&FK92{6tJ!fO-7=sqp%8%0Ko`lN*f5lel)od|aDC zG5y~p%ZBmQIsE&q?sWbd6hBkno`D^+^I%E>n;-k9i6OjiHU`)hca_dBNAb(@34w+k z#V|=Rg0^G(>tbz8W*%!tV28daeI0Y3lA`u6$fOzPD1P|-j6%Ht4(%%B|ADM0YCpNV z{~EDx0S0Q%n4e%*t>o>gqurKaK&VF$G&+#uDy8?ysDlqI` zPshjlJ!q8ydG2FGYCf_03fA8aZ*9rxcMhcVNRSdAVSTDkVGj83EPzWc*QxyQ`mkYm zA?!X_^55_4&n|>Jqy!{4)ts3A3*&?KS_N3YKL;LJmni-JlYdR{(D~rq{d$m{ zp?%59Wxpzeu z&>PYJyK{G9IJz$hy3h0n;~RN=2>Dnsj!e+b7uCN}_Brr;90x;}GyY=`{~h`L%?v#N z$=(-~e?b2AZtK&KGlPJGz76Fc>xcZ4d(>r?E14Y*veTzU>3ykYcX`GyQV4VBf! zU@(p8haBYx7ktiuv*aB3#V~yE{h76wa^c*T^DwE6C&drf?>g!=A^Yy?lc!B0DSz01 zPS?^QzrzhleieJaQHJ<`d9gbQ8sS97x-N2N@mH9?&Fs^J%(>Nq_&jF*UyAS@-%gi& zUT;j)t<5NXQZ&BfGDEWYQD;)2FS5$Fk>J-Pv0m1Pyb3%|M^;(;H-EnY+vLq$)Doyq`v_oCWz}IVun{ z*T>*d)8*29+TR-~zK!$z=QT*1!N-52Pz$3n+F|QS23-7mUN=Ga_67(C(ComI|>={dlG#zB7gHXI{15xAuj5`-ggv8{=2`s zJ(ijb!9)4WESUeO=b!C11~|0cFf0vV^b3Ukz9&2597A>bf%uPH*#ON)8{i;)=HGOE zI#|5l)OlWK)Ur4v(NE*=iV>^9{GPgglte!Z*=K?@sa$8p0A0EXoM+yyI@+a?$S85&l#Uq zLEQYkP&}3OryYs@rq0?3<*km1`@44~{%C#LeU=s$=7?`dM`v*Pzqq(9+GGvJ{Rb~{ z^>?v;dwhb!YV@zxu?84cV2*_=8UH}|chYHq{wF$Nu|La?lt0hTdT2LjaE<)0HNnPhdt%AoK3w^=Kdq0egG}+&UDltZ`TyC2Rp31E05sIAE6v|T z;6D`q2aJ8LkLNPk`btS#moABOb|mRqp;L_Iz% z>0S#Ly=aT=Td@8s_3zo2HL;diS2T`h`IFWMmor=8hxvo?MJmHj?Jwj=TioGnrpCXL ztUop!s)Jk0I^a7UR$o*6--0#J?STOfDQ4%7sQ)BCZH7P55jV-$X)`I}%Q~Nem%qmHOWu23v|$LR)4%Q zh|hn<#uoVaOU?XebkRfQLvxI3#`2Sr`0vmq`WSpxz>n77SbQM+t7YF~VMbOOtg`0& z=f)FX;azSkTrf_P>z}z5wejBFj;Qot_LWTdclBsrk}s`Kw;uli7sNLnV~kdF z?W5o4SeRIn4k5;@|3UAE+u1Zjo%uu2KPb|ISO0x`)Esv%F~x)}eEEkiHNd`0-eBDjrkJ@i&d{Z>)G8ivR+QQX;s*4UD@*j#- zWqkS{f6_&}L+a~0nM{3uxWT+uSU5^iV}1KG(Et-$kHTKt7=Lts=EsI85MmEOlllDk zxi;l9%$n2|gAcOv2ekj27W)%2LJUy2*jDPFQTzEIo*mD6GZc>(^ZEOIR2NM`)YoS; zKV;Nzg>7Cc&^VU)hm82g&_^9Gb?PX*8pY>N(KQOnzZ?RGD8?VHFaEsz31^c!qO77s z`k!1N@ndV(_2T_afXdK!l6@+P|2N#b1(s=EfHL`RX1_A^^{0D3ZCuwtTt78l!L`q_ zH?6VXZ0j29uPDnEko`*3&v{mV(*8)Jy5C@?t^q22U90<->iwtXT#3%>q6>wko~6WilC z^Job_txwku`2trKi~boO&ZYlJ(|A}`aY`+}(e>xWu1zs!ggJU`Vfv@^wGsP|v4K`< z_A4Xn=M|5`Ajtm^7|Q=i^ilggFTPK(WMMkwXR`Av^nCTe>+hh2_y@?a6YPCa+873qgye*rsxkU;ErW%?_yvKRNScd-0O*Jp-vK0;iS0haDw&*ks! zy()NF+65a%Z)Ex>_J6`+5FTq9fG^MIvHUDo-(OtnBA#!H&jp9}x1{;hK5r(ihUUBS zK(k@>{(xNFzXy%g!UkZ9x`iyhQTwtS(-cphe?ay!CExvD|eHz{gY<*7oJ2HEf_&;49%+?5(@SBkR zYuATbn3`mcljrgEZ>iY~U++-w-_iW_WMng}{5c%cy!iPm?vD|=eVvI7d*v|wkpB5T z&*gA(yC@&a-(2}PKU)bGR^+MquLfD4+<&(c{w3zY<4%k}C8=*GM>oVJdrZ~rm(o9G zXJhewb2$z_8Ezr1uSt9g{?{0ndI^~G9Juw(I`MysNlyiQ-sYJ^zmnKzg!?i$+vG4D z@@4$d^;==cGgz}$58dzgHJ9*{_0MLDxA65{2Ylg^%%yLlejLmlbsDxExh>(R`hTRe z656HYiEEHBX*`GMztK%?yf()gfA{C>&mnsmBq-9=;v21RKY3QcnoWkN><*`R^rr+G z;gF8A(KoAF|HMBV^@@e|4a7b4AME@Zjn8Hc)Xqf;N-oU9ooltO2X7QQW=ZGGw zp>b{T{KUm_3BM!B|0hyc!=0mraO)vkp8?@-eC9XEPBg-LPgsAI@^>n#0g7L%quE#1 zp9SJy=VBV;TkqjGxi{Pk!5^1OA)I*KeD>uOa_* zCo~w$*RNU9DoCEK&c6xaKPoLAB4?b3xYq3a8Qnim_6&h!-E_!k^HZXa>Zi%BGPs-F z9`$8>{j~Ic11-(EpfYcsq#s(}-Fp!W^{*m)k7V^BjSt=rSAyQILKtv&6_XE%pZ@hK z!Kb+qeop7_UuUn8q3!emnCp=%&8PLpm0WEsoitJ{{?h!ob=N|8kR<-^v6=Bt`_CQY zp2DF|?J=M=aS<~k^kuo(m%tBeqxSN z@cB!!(!k>4VR)flq!jn}sC?t}2T5$g}o`uC5$20m$MhNT_jr1?s+zI#_%7b~1CFjN+8@n8HB zNPgS?v$AjpbkF_F95gTqczrl zTQB^8x_U!!;re(<|J48bhSkD}e=IP^b`2MPX?6q*aZRFXWU1}HB@_8JZx8_y!74av%J7#G`F1TA&u_an zK>PE2_}^ClgHcD#@%ZLT5`9WipWMAC!>BQGG|b}re?oa63_6(w_I=p?AoV}kDfYLo zn&R{D>i3C=|DPT94+g|oV5hI_{yW8QlMoK&-Oj+rn~c8}mg@d{OT7QzWX~n=dBggD zn}~hC9xB5}fpQ$;zM88)$3F|8(ltwM|CIWlp5iz3@)P6VW&ZmRXEOdmjIA8~|M$Kg zk)KgU6x=y}2^N$kaP6Z-N;Et)E&|QQ?EWF`Zxq{}grmzFVTpgX1&d$m`=b?JwQ%ta zOLQz_`vWvS=_c03jV8k}wlI=A|4YM`XkhP-A1c`S^kfoWQ>5oR3ghR2*IcPoov83OL#J|lO{Dw7GMfyC7q;VOskGR`^U|L@V=A2>qh1Ned zEt{cNo*Tvt4dvo@x;Y>2-pv6`Kh}St{&(Cc8Wx#egHFpgN%-mcoV97`pj$5PF*nQO z+DE~N->^-tKnII!(tPTlRg-17=E!giKVnrN*{4jsK3e)f1K%GUiKScF`i9<59r;EV zJ7mtp7PlR^_&s&zgJsM~hZlYyWTZaLdhQ4H+nj_;>HPS2dCYz=i>r;|6)%ZD zir;7SA4qWf~_OUDP z4?JyQgPJD)dtXs~e&^+N(Qu6;_G-FCvLD+2+B7j74rW~z-#2CYrTiV<;Rg%)o`R@% z?0rIN|1s;rU|0TS2z}4i_tZX2JMDvOW9wi~*VYn$r9{7<>wFjg_O!%J#mqi{=x0{* zf8Y~siD2C)>7R zFu<}1K2B!x(IoosS(OS;`q#m^1ZOzuMWmUvHFSH-~DNOK_|8j+PvJ7 z|DS)C68<*ZR)OraB^m}@mBy+5?PjLK*IEtL_@njZmwol|*##FY)=rk>N8{5`V?UVI zM|>mUUjsHy`0o^}ggV>Q`KR__^n#k4HN%{JtiGl3=k4>i zpabgX_o)4a?fecSnvcM&5P$i9`ltE-?V!WZu<%$gAnS|2-^>nS^Ot|Aoh25 z_7U(6ZldO2rDT6Eu3jc+U2cjQbtX#kq4mqK=HmO1eXMbu1v~#t{nysM3Vz-c^Uv6Q z)%2;y?`dVh@L=IZwf(v8B>y&@Z~%g5H$>YuCDMEf|8Zm*yz*{@6MNT^_@nVjmXi*< zU)0RshB@mY?{B5r{d~&*8Q(47KK&1Py{@d*uloAon$uS3_VlmX|Im)a|H2Lh!K&vM zVa7c@N&i6f-)HVZ=s4{%lul#%Hzx77Lva#><$hJ8&z-yvaEo zsMRM}>OTSvH}Ti^TgCqEZl~93_aA}S?=!n3_~cWihM&G)5NQzz{fA#xJ3n7a__Hy6 z4joF(vGgG8k5c{pvH1WxlWp)=IqT0+|Mz>b5@J(dg8&Li{*=BGU)ICM+dswqvGdjX zSC60Ba3MhVD3cl{gB>GB8|G7%k@8YVfFrYa*pGoOI zm9!pw>->ga73U=SXna0Vz8*#-itj6`^sD_(JwBZ2v;jVU`wiXh^p)n9lK3#^=Tp$| zvQX=9Q~gEf&VxTYFRR(NJJEly7Xffjyx)`af!+V0@iX*r0>oH+1%uUW{o_T}=MlTs z!pav_FeIMEZzb`s`&W`6)B86hFJkw@1yWyi`kn;8#P_xKHt)~$NA5RH|KSJ1fFjsy z#r&t3&~Mg!9(=Jcf-cDJ*U|H(J1rJ~Yx8U1zL#%bZJVuwY5Kn)L8ZZ!e@Mqj=;~9Z z=3oBAzrTt9hxA+hLEJ+hCE3USmtT(ig8uf);B%kl7rOq`2=s@|@2`S}8|$x9``I70 z25!x+g5e%)eeF){zti%yaIEwPxVyhP&GNUp{q(%M4&49#fs(=fn0$%-tj~Q0^*>wT zVBeL}IQ8$OpDQ5OqFjxC8s99&%z?(2F018FCDG4}_HmGv@BspEkCf!&PV8g8kN{;q zKR{^3{@0=QQJ$Cx^&K9-#(p7Vb5;`>P%YAJ4jITIXaUxqjJT1)iP{1N_OKA4E_Z+GceA<;+AKXf(Pm$>JC+E{m?(T!)T`f@SJ70d655&R=k4jJ) z>vQp2mo0!d<4RyauNv_034{w3_aGmqO8Dvftiz1n!sl5|SlZ6(VtA@cj=!WIN99+U#(9Pd|LlB z7`PLZSxr#+ht;n#5?}J?DxpQ*OL$c$N19LLSAWeIP!?3eyRQ?aak_r%5akPJB5nip zW9K8Of6Tg@06t4=W3h>?Bp*uubCWQLzx*0zpJe-!#l(Lm?TQ5VULV!`_dAL2-CLxB zWv7<7rxV{k4;#&ZUv;jF?@zM*SsLF1OXtDc7WW~vKHHz6_ID?z5>AG>iS##?_^0Qm z=D3LOuZO<}=ZA&TxQyiA16QJd74t9kG>DF z*zzWrOt3_Qzt!&p6Z`qv#ux1N-h*4cswDoY{dL$l9TG(Or)*^O)B0fT?kWMe-2s>4&XRuU`oVs-66CQT;jzgD ziM~yQKGQo-VQ-}~YW`J8{z3h7hTjVKXY><>Z1Z4?&&(eF;` zv)Zk1Lziy0nBe6v!Kd}9*_hdIcjiNI$YcArbpJT1Yb0pS`~fD{rb+l|d~&f~0h`zT zf_G=+5`Oyr$7_#SkTK{H7(QkD-xU7g;bGu$@+&0kJ4^6s{gK@!64qP%0^eGUKl(qw zlWSL?{G%1>INh_a{q-{f2XuOg@zUz+JKM^i3VqJ|nRFLE?Kx_c++% zr-63o3c36hzV?LH%^pCLMm;3^3nBfTdmb}kTG(RrhyE`3oc)*-7L6 z#J;v(kAPz{{=)u$W)gm?-*yI`Fn{L*7#+m$)B6K+2F`@&BTryRF590DA^uZqa5VH- zBmQ9-&emV_|EIyvVqote4g9#slAAxaC?3I;pX0H&_g=|=>HVMCwh?fr>@T=yG5QUN ze>ilA22ZOxc)tn5Pv2jB*=-uQxry;@PghC4w0_>YnZ)4}} zc@0}eu>4Q!)81}V;Zw^JC~;)*14w+w1o3UnQ!;ea9V*FRo6vvSe+77NtBqb~8U3Xs z{&)E^4|cqK3wNAPO8TYy|C%3`K;hSKV77a#G*077QNU!_bpI|)3}xqQG6;R~eZ!%% zAVW=CQ!ahI=SG5WSZ(~@`he26zE&8hn#%BW*jx#}39-Mi&mtiAZ_WJ0ERF%$!TM;@ zH$<`zT3>$rx(sB+qW=HPl;9^5_}+oxur5&i!^V}ZUnqSFPw{{BS#|JtJ+?lh@i|QV zUoW|V*dI1AmhjX3Ipz2iST*(`ICeCY?1%bCmowABV|^L;`my&3yoi4Y>%(F7x;hv- zn4Q0+@v-fS2pBE?pqg>bZ!Ehax3UacSX{^iXfV*jB0 zGemi?`ibs8_ZqMq2284r6TdU~js*U>MTOv@V~5FUqa^qOsZT!YU4nh@Mx%c;+aIC% ze`~^AQ1+>W47+m@{Yj*Lo9`M5rLSt?s|x|rIF*0n=Hl6S@qUB5(|f7Dp!g>Yy9(P* zjYA)chthmn|4k_O1AC8epl8PRr!@)w*SkaDz+)NuUY;Y(&mjEA=ADAE6_yBAZzTN5 zg#Wd_0KSCSV&NawpQrl=@6Q*3f5kWyzCPg6XMV{S#x?i`Iak^F6fHvEuSY=;>LJ77 zbC`e8_>tp00q&l83Yt@UaqU0%%u?{)p@Ht9EPlyI{HoRGGEBTM4lB#WIsXF82|J7eK{%_Ph4ps-vQMYu9G%h3OJM>i-VOzN<{~$hpM@r|zhqf|| z@n!X&Hqn2R_+XeQzOSwf)-rg`55|3M>tYy>c_@VBf zna0y#&F%MKXvOx==>Ec;8ha-_>h<60F}?qvNqA68%bI|36-31}pm=JH z8Ony-_*5?b%@MZ35q-Zf`lx+%x^WRsyqSc?hgg4<=C`woMNnp2ANMbdmhjX5W|S%n z=ExeW$yY}7ziwtOJYQ~)$@x|ieKI1y)@1;?2b{3Xj8EUFm;R8ttq!J?1~L4^KJWf4 zf|gg^(ZQJQ|0qd*>gIe6&d>5hlhw7P`4s<^KQo|i?Z2QopWVOmC;lD$;1V=z=Z=>5 z7Fn?Mo4S6FG%JGHi>G7jEtQNvnYw+~-sc5Zt^dGxhZ_=p8b6wEjDvZ0dT6+_5#x{0 zzwYcw&<-7qo+14Htf9*#&>k`!9~OU+=2QNQIy`_a0|HS~IjDMEoxVEVJmJIUn(348 znE{Qj%CKYvtIviL`&?Nv3yM=~W2CFE1fS;5Su0}Ud%&lFzwq1brUakn_tZI_u@eYDPo{rTKPSJ;hHo3k z;L*SQ^WXcuJ-{qntZ$z)|EB%j?j2`C-=v#_Kc2{c)o~w)@2i0hJp-A3iGQdR z8Q?k37H2rJ^?^X_YiM95xZJSAk9plB`hm#*kV_V9Upxjck7Dwt@uN|M3Th>}s_jn; zWPf^ys2_{rwb0*_6D{Wb1hl^hOiky^WFhqxt{%_jDL^ z*cSCI7=P6M=j;&Q-YOi4{>#iH{z?gdTgRM$K`kBeQA5Tbtq)YS#JgYR6KdpdpoTlR zw5^587WX9jN=f`^eR?LWKT;Q;Z)5xw6aIAH%!MwK8=&ra_Wq$j^!IagD%cfTVB)43 zaw-0h_}ZdtI@tHL!;CVQ_-hUgFGnAMEwht_AVOAmo&fIa#aXG`;`e!A>PhseJUX!48o zAE^J;E;#}Zf=1)6Ppd4L{?+qO|7(xnXI8ix|MYy%j)-Y6L_-6Qe<_pj#}NCxcG(wB zw9>+yTBZ{J^nAX#`&{@sUkiVBO_b)BlJf_qhPxoy(*m`O82|KrBdD7Sj#^e|>zFFd z2cloyj)&pQbq7@LF_-)^nfT{OTQ_Lvp@AhASbazRE8Wx=T71+(+f*}&{{6(iB1RvC z@$(!|uo%dNZ`e6gyx%<*x7xD%AvC{ytrZNNOj=;nb@qQ2h2P324T5w=p)g>W1Yb$$ z|8?Lvd`g{!57)8t*%bb*fkCjnxCMHB9nGcRuXGP=&9_n0uZ-+ZbdK5!r5g5X|7QzC zzJFYgK+CV=@b^mQ|3Lh|US1G%o2QFr0nQSBcOpN%)ZGw}t&U&Zs#W`c;9ON2q_uRy zeK%SBr0`WukAto6RP?uC=Vz3JzO@Dm;C6INv@aeb;ZGp=FOAp*GjeRuw$Us(tH0FW z7rTAv0KB($!W&N*{!+r6gCG7(C<@j1QiLA04aDrx5-sLsMbvhB5eWE8Bmj^abXJ!0xHy`)Y>lekrX# zmrc(FJ;&MN`--f;N%ecMPYUSfjS=tPGx$L0e|jbea&y~a?&|;TPpO}e(hfcb`T?G( zZT^hQ-{eQT;SG$zk`e}=(mx}x4!%p+heeSglK%cb`t1F|eS!Es{N4%DIE}BS9p^*W ze{Jy4m6g&st6h$}mjAd2@y=nG;luWa zWJEuDqjtgS1!GW_$@=30@!x+ZcY$9mM^xQl{8Rbn9-aqLbM$b=x=9lKbp4v8=MM*u z>EYW|tEBOdr2ce%5CkFN?NQH<^=E1Qm%HUY%yC+cAy?S_6zV^XBYffHu{LPv&*V$v zQ}&)Eu;6NE+`FIkN2q;Ww@wDDFJsWrfc4KP|DKz7!Oi1NxP3p%KT2X>(J8ZG&)qio z#+BiZA^saVV+&;dw!;lBtUoCu`9sfYCpa&0M3YY=B>SWIg@(!Cy21&I{xJLk!LRq; z7gk->$KBd)l6+}>-tze-xN%9WFAlN(B*lMk)h4LhdnA63V)Y9h-+gr(Z2InqrOs@B znfiZ&_uFCUGH0B+fze0n;~a|sa0u&!8=U4y^l6d$U1#!Q*gU;EhM(*&jk^>3-XD?( zNn2`u-(suvLcpwUXx6l!G@t5s$J7vbw6HrWFR}l9XnbAX?gZTI5{NT8G?3;~`|1&% z08U%2Q2Bu6_hhpF&}Y~}@USpMm%+^cY5sU+yckkO^~4KznEg`z8s{AW>pOnIJS~;f1{o{I%7Qphg-EeQ)z7l+Te$QpvLh)zG9yrK%i8M~v zA3Y!)W@paB3&ZMg<mt#_2Z#f%R&tI-j;$iB! zn)zF@b_2ZGF8b#}*8i80_*6VB5PA;ofwQv~N%T?wpK|*sH1J=D35Kk{M)j+>bQVII z#o`RZK@$Bk;$Q8{;^1&|1?uhO(_h{v9)_ML@5_+-;Bi#|j9AqZ?<@`F($`{4D)dXA zf&SCSO5@c3iUSV8k`jOXP^bERMPeU%;`x=_0tKGG#^_TL`&`s>BMb`|hs(8@e^UOU z(+eT^KrDuyA0Y8h{rA>xhH<9>j zptl32taiuZ=6Ni?6Z>)bE1rLr_d(0|0+;^UXLrGaZ!_`pIMzQYCGp$T>;M!zTYzR8 z*!?5g-~3sT2?uv9N98@a#2=0CvoH9Fdkrqx*Z&QES1} z*9EI4vHFz8mowexLy@u{{_lTU`hQ#hbII_0*F4NgnkUJJ&Y$-n6>#c841`Wx`r_=C z!x}?5K8|DgRh#6ewDS?rF+$z{>H1(vc`O9K9gSb2*K+Y+f3_Wt?3jysbJ+Pif!Np8 z5qn_S%OE`M(~e7@i@1LpblC=vn9P*_7hmc6+t@M|bY6}@c%8t-|9;0dsQ-R0Ca>Y+ zpW9&%OspM(znwdC@%M2`fyjr8(6#I@{ zKMPG=;c@+*=s$I#WdHPkkMVb{9ZHTHiiH*SH~jpm}`JyxGm`Bo@*LH47C_^KDv zKg};bZeg%5YlPbRlhWtx6b?NG+hOEyCV#sAKl8~I9ETgD{s~w|EPxHehpJbR&5`x+xU8MOmzO1NR3McMaLZjEl_;dDBuKu()ErLj& z;ix~RjWkZ*pRR1IgyjeAFtx4^*S-x$CW3p%nP~ECnPlIkB!8bimIR~f&cTO{jD97d z-`adV1U#FAn~cA5>+e%x6XC)}Bkc5k5tsfYmlNUA%Ky{fC*~gnez4C37(dz=b4RfH zit1m#lOK3Dl%wo@wf~X$GIdl4g!_)b#&!7i6})i`3|c%Bqkb{|X?)xAbSGy=Pm-j z2z%7&!t_V|qnm#`%xvs~%Vsh9l|+BdnvRE!-__}(@(cbt8~XbQnEcsQqTi9ww|Hw3 zEFHf9k7sE~^iltAHERQ0a|yztpDh2-{Jmht8VJ<##mLAI$-bz3mp@K`jVt_c_+S~A z|L|gG$PwxH>d53v>A&T=0UDoQh!z{_OZ3zHcj=uEXkHSqpDW8h0^x7IZvf0WX@|;V z%s%M;WAUOf@SzRP0(Hd)|c!tw-M97JL%sipLT!=3yszMi_+IKYZQ!k?1c@7viq}2a=$dC zA`TXBnT5i~P_BMTKdpsnX+a`=Ouy9sk9740yG#WxST>DoKPSEB!ncREc;Af4m*y}1 z`u4EqiV>DHW9vUk|IoIhAS0|dmLJ+B!50Yq!*9pIucvdw`<-lmmD*RI532y8=V4(W zfB$yh$hFY3!$LIEtyc|SUH+AKJmB_51@6~i{237Yv1&92CKuUae0RnlwVy;)JghJX z!e*huVlv5L*7{H2KJ6Vs~Z;kZNW z{5IvU79CN~pUI?tSvD~R>a0n`B7e4jK+m@ut_cJEAwF2> zST4~|@i%BCzR%S(xW@mNuGd`yU6v>@XT|_&K7}8nKMiu0+M!olCV$F*+7G1hOf$CyrDlwk{`A2 z+lj6)FVG&B&Svyc{T?e@45&E+|GI{A=LeWfg?Rswxa%~3zHXBcxL4_ohvM0MnqNA! z4*`7*k-y8;@3YI)&j)zy34`F>{s_^0`?$YjGT5(iP^%B={zRR;<>2q)k0zeqCH(;L zpPvEYu+u3BgKseVqVlP?d?$qL+kg$7wln<_`45i`g?YXGQFF^TX*`+0-) z5_sM@2q(Ysvta!n_4Q#xZ6!p9EJBYCEPg2o{oAI6L$K~LgmK-u@Fy%E2SyR<^vMW) z+hZ5Q>VLsFWRfoz|E}9gSU+ePzUs_}ANSHpeBY#I__x>22Zz7@Savmt3x8IgBm5Qj zSN`{ZEq&jv-HEx7_-P(4KCqBGe~-35?DAZIn)xjLQ~8E;SpZHe1JV5u+aIC&UzI-! zjztjsL_Sp}zHl~TK0aQ-=%?{_qs@G{@*o&pjHg%U7xnjV7R3g`49`%6XC1iuasE3J z3>G-!xR-4Iiu(7y&hGH$*I!cexN-@iNDYED$!5lU!?f3P{*Q3HTlu_v)9%Z zf^JU5dF$uO|Fa)jUv7B565fSxR*O$c5RbO)!j5X_s#>NDEk2@9VN$Kn^^--~?v zu=%qR1{Q5avxoa7`Oy4(W9T%L7C&;E-mJQ)&- z7kbW=r}mjuHV&MOgRsu#?OgqPpIih#0~2sYW*;v6CEvm! z;rK?Bg>9AK3xvL|rVcRa_gsATJV27ajP##l8+t&5ek2;2v-LCe-vd2EVAhdfrsY*=~qV9hj$K*0QX_OINFGhzoNtqX4*tz!^M33ci*|eTIWby zwzGvK9~wW01qDOzlunG@9vTC)AgO_0Z(W*I~E6(SWEh${t*#m1?z_U;o;kS{!0fqg3I`2=zK0!f=}!J zBZJ*xxgr+D53D5k$wa;pI|NwqWiIL-53MJ%Z?#72&m6H8Y|7#L65{@-cKYv8y)2t3tV6*co ztmhRY;ivX*RqhJLhVgjGke$Dx^-mSrf$EPsd|KZem^%rMEMJY#lo_Y!mR#-~( zQU7oJ^A4r?sg7oD%OWClDtxgA|zr*Y{IN%8~7xqE8N zPlMxJ;Ci$5_(FF*SN{RsCy4#A_2{B8Od1DL{~nng0Q2wwhHNV0#y=hLeZbz^v$1t+ zwmzZpb7Pbo8dpYPsuz>5jL7#$PZw|q+K5H#H*x9P@8$R@B6K|{MR`%7B+R+fomOO!}crpZ!RfkXc&-8K=|K~k`mERcu)P7EOoDN0S2eJ6$S+4w> zoU(`0+1n5d&q(;``>O6kr$DE&11Ma$%AN0;^tqsPqxgS7zYt0O^!@ZN{cPa!=dJi9 zO2vh*VQm9TYHhQQ3TEgL- zTQPYU!(U477wuha1wpsBp||k2nm%>>jZ?;gjd>bATzQ4d|Fe2mUM*K#j1K@dH5z2lm;rZE3j692oga6Sw) zDN*BJM*KT5cM<4ce1gUGJoEnJpXzVwoqGilI@aR(-83^v{xWs`n!f1;kJoI+VsGYu z0 ze_3^|z)?d$gOCXs7aPe163xsdViW=wJ+N^;kKeSY@-g|T9<6c_<*^2-ZZzNUIuTI~H z(I*SW4>iT9^I3n2%13|oJovZxV~zM1yLN$vE%sq=hn0+f;$JSt^P$}7dyVspy03)C zMNL)jOoO@f#~p}-(~Y!M|Lf1u_}C-!a6vNzbM!A{_q%BP(Q?&?J=q6w=eJc{`c^u( zf}qK1XztG+Pfv>gW4-38nAL3kPUBx=hm?Yy+Gc2|ZCk+nU%h|RqknT)S~m?(kL1JO zwNnX2e$7>hKCHh$;g@UgE|~Mv0v#`QTiGkqG%-Qi}_7Aoz7 zQC#?~Zp&cU^@Dh|luzH2yDo6mvS#?k9ex%(AAJaCG^&;_@egZrNAY|@&GVhFeJ&VL z>o6ADRnI5-S$;-YkgI2kN!ouT`lfp#nX2*blhyiFk6$N4`@^4MI;zNCOSt-5=G+T>U+So|el6pU_aE$5;1+6% zny2{k(|_bvuujhm6ZA(E@ceswtM1UbZ!^_s8zmS1+V0~EE=@H>TLmA!V)&$jnIUp) zJ!O;xpPrA~`P>?k2lZC-uViw+W=7VSg0Vqjd{{D1!cXJh(ZUYUL*7i4Fp*E+h!Zvi z8$X-l^Xc|n{-XWbK+@A@s>z*mx$?iU(X^n`YEv8+$LH_tN{fQY-!0H&4&OdB&o&36 zd(BnfEBW!oc;FBysvN4uzsyqoe$TD2egzw+m}2P@_P!Cd|9&g_7354aMf(NTT>kQ% z2Nry|D$4H!-~Rd@(1MZ9%~fS{`TUR4?^)1tvMENM=i~3c*SKI`iUlhF_2b&N#lr>= z*T1!DRpDB${hS-uv0!nmy8Y1qKhOT@T;M%Ojv3*`T=-%7e+%l~ZLTuN;mfyGQtJY^ zU@ES!tMy0rZ%SV46%?4&41Y!0r-DbzTd1Dz;Kxtv+u8-!{+eRRQdWN{$^Fro+RqB~ zem7SQtIy9*ZC~Cl_2>*o>PZwNr)>Zl3Wc^1vU*~>BzWYNteyq#S&$V`x6m*NJ*?*tp zrWcfYwN&}lW&J%0U$|D1-!<73-x)IfQ2n>x{H9=cvV*G0o9B{$mXh;3pY<>0>uy!g z4|INBqbvD-f>?j<>&2DdxGlR29!{#+J_iQnYdwokq(Ae0 zSHs_$;J3dUo?j~dpEcxrwSCFd`)hsf zPAT}fM_(1}xq}OTcq6a;Bf+K^vW!1}Yx3ZN{H3}o7u{9d_~968k?)5!%Xea@j`^c6 znd0~PeEE+|`<=gGq^_z<2;csnf6^p8{}9r`Vo=%@Xq7#+wz*il#I_C1cvpO?>(yyPz=ei8Y$4ouIx+1L_u8ngUQ;afRP z%zM?`47-eC@rl}BRfu!mn==aW|M1Xi{iydh+%$XU|C`oI6|yg$OW)Zdv;1Du6{?63 zCZA#=pW-j;PM^3~v-}?|otl?#*hzxM`Z2Zx+`-HOa5pYa8>X*Tnp>itk^JOAIaK39VGh zp=-GE`;>IRJaL2>Zu-X8Pxgrn^Wl$b=6|l$Sqp=9R;mt#k0kpnA@bke?X-pcb6wS9 zVKo>3n0*!IebdzAFSU<~MnB9WcgfKts0UX*T|fS@h;tQGZn+P*{-Jcyx0q*dh98^q z*WX6&wdH@G>Z@Kg-&t*c>irL|Hl`M>&yx5?@>foff!wb{J5@|Ef4<*w<&Ll+_J3Z`SC_;ha z6T#o7**y!v!VG1T`1WJ@*}zU* z`@XXDh5V;a&G2WXzmj_w4OVG{R&eQW+N4T;ZMXXTQo{eg@r~qb7AnwWpEei2(d;@x z`S+UVzx8V&|L3AWp-6{2zxceCU_W?}ntUjJhujWwmpJi$X$}2Tt2Ql#|;dEdw8gdoH( z8LaZ&bCx@9UdvvHs~W7jJ?oq_{+-N!(QT|S+h&Lwe)|4&{kcqAt1nqA=Hf1MN~4|pV~<$qc~bgCOE{HQ%tb<>~C*C6x{ zza1|>U2ciSZCL+`&JPHQ5%zfuRqbkaQNmB>Bdij-Js7IexyQye3H)u=YlYH^p{j3M zm!$c0{Abh#;m-PDs>Ax1rEx7XU-@8*P^D?As`H3HZkD)HDE~c7)$SR8yz$@^p}(Q2 zYM*Hl7k>Mb`-R9rQ&s)5Y+Re*AJ^%y@Mf2(YP-P|X+9ly`jI2I&9uUP3nxh9v_E2Z zBUAX>(oEI3oXu}R;6I(~Dm>Ww5`P$FOY>!9|K2e@OK9HBO!YdHng=M=lCk2hCMquN6!1^$GsOCn17+mvX#onZxD((W0xuyZh#<69cYu=lf{f z6w0rftKJIy@frTN1YaHX^^XBr|7__HE_B#Xj>mrR@tb!j5k4-lP*r%`knkH2`X9Gj zAc{_s%a-$Q~lnXUT^@s_3im zW4fTysdq=3Z%p|6WcXWtvPyw>650P5GJ?N6_?OV@ji4I!lg&3F^Dp-KEB`)Fz^XZ8 zx%AHu|0k?(s8AiYyDN>;`MDcvE7r#odozFjxb5{7sb3VTn;q`)@#pLjetNyak#48B_+LJ4plICJ zQq?G#%^yPO&vV)<6llFdyY~F~SKYJ}1umAVyju4q_;h}5GXh_g zen>du{u<|(pXSmx^tFz{<&>3b(cFj9xIpF){MJG-(QCNs#MVdB_;4~lOMX;1`{5P# zIKhYCaeOO9(%9ju`sw`nKO#>EUjDCfqkkTkzH}o!McMt~D%bswx%3S&%N9y~Ug7+i zeEhG%+9@tiuu-*X@l={m<>Q)lQZRU5j*n{d=g*EcP~2-gLUm$7nKYluU#n|^&`R?t zUQSX;ZF3ayE`R)2ZfC{hGb2>4JDy4NseQjK0%2gxYpidaFOAdu<~~13 zc%XF@+kWK3pKjYtkzLPHa!%XyKGfY$Gninsek5m zoF#OF7(CmN#TS}C(@t#?elkvNty%Af4 zLB}((?i)V;x&3=9E}gPfDem#%7jB*>cwdOYQ;~f5Rd(Bi9#b>%SUey8);lJO+D+_K zBcfkQ@}coFyH|kVd?p4jr}5!W*|kGBJS7un7VzQUHtVmr)y7UW?-Cz=kF~*qeL)P~ zE9S%BTQpG7=bx?W*ggLI%H@lMrq^O{N=p|1sQ&I(B@51>nRv~BuRq;ZdxXbo z#@0vF{~Vl^!qdtaym^`r|K>sqMe;Ix)mGJO2|leak}vEN(nbIJ6U~QzqB2Z)^*sjL ze&)l!P$npztgu&Q*M7r=uOE3pNKDJb1HO^;jnMNaD|*I@MZnZnk+q-OXP6%Go=DGn;@{Pz-kT3@>liW6*)#ndSOzB`T!Zkd@l#h6e3`^Tdd z|1=y_FZ}rMTYp|DY~K=t<#YJ-*BaoY@H#(I%R>>PYVeFHN$s3kSN%S@q6V8KKzP>Qx&IF4l38n6+ws3B8MA@ZfbmeAi8GiW!?7R90vC@UK{a(BCAZ#`saY_XfdNl+XBoeE9wTprCdC z2u``qkKYrLrz;}wIH=mq=F9Js#wOufVGQmZ!0ISVwtu6{0V-7J({iNVf``0zI$IV%jXJc64i@Zr~9J5wq z{#sFIzT$Z=Csp>K?-G34KU)#JL%6tI%%5lZ@B_>*3mBM=OV9G_i;X1<6koC&RoT-% z$p7mv?kD~2{vOG~!NeGR|CtZpwP%nbEyhu`^5i#(J`J)yFbuvT^c#`^F4jy;0KtQh>$n$^$LJ|~nf zQ4~ZtslJx{kl@q)sD|BjAsh~4ui1S1pU+Pfi~?gY+m{bNW8zJrYGcjw2c#@h^owy) zc^duX;y?R)uW)vf=)Zw{_^Nrgg$)UZ@yQlGeZQY56{Aa>R8K4U@Vl+uFFdq~!5%C5 z@MHb%3T{D%vGZX*{5d_-gxJ9`xcvZs{>!T+!t6(faHDt*_CNcg`MvklNJaONV^s?; z|B=RDk^c15ii3iIK@0`}AO0cXf#6hr2yZ&^>64}FDC&KAj*CWs1fQ;-;$jX9J+;OB z`2G7TO3}N^cvWJ%S`z=ogg(KgOei^a5ZC$h@#|I|6K15< zO#l1z)r!cT<5kZc`0($weJ>FDe2enS~g~?TP{BE*kg6RQa zn3Tlfli%-IzZ?Sr+TDar_d`4CSMvOY9rZ?_{^lsQO{MeK4Lv8A*gp(SRq6QaeriLZ z{WDyc#o3eb-QG9`F4f2ikNpXz^8YS)E687e6m=@O{3GN0^Lx4Akd|cqkp2xHWdR5F z$_hW+rsM0%d=OmSev~&q9(B1O&~psKKk6JmiGTi-E+njdj-xko<3H)2-?VWMqarKZ zFqzJ;c;cf#V0aXL8##Q^zep{82zGvs%E##Vjk*@_TuWLQ>9m^~KlXQppmBK^wr=ah zm+W5x*w2EKukvwpb!WNc{iNGw10g!|8IDw=^N$Qe!En*P{>wYXSU<; zdLL?hWCFekYQpnTj_tIU05rNj#h%ezImtimeHK(jE*82uw_E+Me-{w*qhBGH z1iN2_qW@yfo}6E7m@o?Fylg{xZ*QtT^I!Wx>w~kz`Kv2&ejKmgCUEYXk5P*{@g?<- z*Ea;TdV+HAxb{ivkC3VqEV&(u^EYr==#L~c}Un@?`T1Smfanb>>{_Z5~zn&id zx$A$4-c!rx?LR749R(%tl|qAQ-1#24zRZ@oCeRgx;`>ir{78Mqvy8#5?kW1MrswCr zXMY5BUGsVSmteL4rYNiwZc(H22W-DCDAov-7$3;~M=oS2MDB0l?H^XJ_$T%D>-&cFx(&%tt`0lkIbKv zXaRgF`i|XXHd6Cj-%$p(#PI7s|LeBkN>d0r{_5nHY`^kG0CT**@%Asv_Q^ukl_OaG zsncFEKMbWtz>MH#TzG-gPqyETkh_96`$Dj=rqf=MUsIX^^{}rPu-1#}U!YA_7_55) zHOF__OY&C>?h9ULhG2~*$4|zu%ZQPX(AI>#Jh*aF-wNmkk*&FCDxl*JJXR;jS{H(C z(wses|HOS13@&WK*UPwa62Hy6J1F)!!aIJ%D%A_-j|#z%XPx|#@k!I41_=SJxWI@W zpFKT$fT3S5=4*A@OUCE7{#elVZbI`Cy1umbdVya;Fh>2L_g}Z|<)B|wF3#UW$Nw^I z0vz{ziY9^F``YC9x5oHLa62_vqW>n_$B+3|3}s1dgfqT|QUY!V#F3YMsU5`V6=0_5C3 z%!|J;bppujeT?%jaQtL`_!vJCEXWB)8yAkB#BbK<1^X`?=8gZu?Gs_{wFZ2yPshJ= zM|6O&Q4*ib--YLT!Mt9FF{HY){w4Eg`Qm2+U)x}e@Z|K7_KP-7f|pVaC>PDylm2a(9d!Ke6Rco%`a^69t|?R#2T+k3&ni{U_2sq~(>M zR2YOO7tr|?_4|O{i$i$$4Lv?bZVA9gx*q3P((!9`-UwuTgV3}O9e=>PKJX{%5bylC zBo-il%mXY>>)78V?mrk#ek+Jk48oPEoIWYy{gK!|DzMD+5byl1M>+#b^6PNJbUMD* z^LK)=?*ef`A%{=q|F9uy@W=fS7LV-oPclERnofakr|U4Oh{Gr2U%%ypp!G(e#P~zv z5C2aMj@>(m?nxX!S-;u0roye3I()*=;~&-fQDB!Bh_ml;_9Xu673yH@co0#KD<|pob6>z@a>Pl@x7)NlIzyTEp_q<)g$DzF~}ir#3zuO8OaH`plcfND> zWcwSCH4k*H>(IfHD<|`7&!2ySUo-gQo87Jh6U_JXuCGtsk^%#x-RSU=t}o~De6VP} zkEWyP{AL0@xH5S^Z~Z&?c7Z;v0le)mC~qNbGN{9g^>qBdM*5Jh#UGzaOKG@#DFDwj z(e*pLSOjT5?&JKwbo@;&10iw1eq6nx(_XUwUN~F^66yo6d=0lgCfn~}))8JzxR2Pe zKSkD$TVDehbUlZ+{jFHI7&flDkG&K)e$w8nNe1-70rXkB6>fY zPrt)N(eKe|zQhw*-0ydh^Yh9NM)2`lHcnQf^EcEih25X-@viTDOuIp%5`X=j*4h9) zoL^vRD}8@vw$)(BHp@X}iSa`+KR$18g~{gku$Kv^kMzI(b2m6w=FgiyTV4-_#DZ+z z{991b9a3iV+lMdlfg8)7<1Qb%{*UjCVfDIf-u?G2nLXg7nLj={O|SpfCCfpn>Mrm3 z!ZMwqaAZ?9T0P_ZC-d)d+zLqFaTl}WxNjd!P{N<`XQZvf~E<`kIzQ;Pn3F3YCkWxC&X3m#DNm`|0LJn z)09lXvp9?Qd~o<4e^8NmiPJvO_doBCQ~<|*J5eU9Q=cS$tF#$71!nP{4`;3l0E^5Q z`1LUz-{P$TL&!n%{X4rWfq{b`;%7Skh@uc!n)Vtu z9@the98D~;27|Kmx=X{>Hc}n^8w!- zH}P`E`hx5~^yWuE$>6uRYdM`?-=+_s=5|c#LFbog9}7F4XQKP;&T`54ZacRLmNGZd zuVem2^7q~w315%A#jW3WQT>0fpaOdN+j#j?gce}!pNacb>HN1~3tSs0@_!r`ACh0K zTm=q}-NqZ=>y1(H8{VOja{yJ}1+DSWzCV-q{_M}gzR>IU4ZOUK&TkQ;3Kw5(MY%zp z`X%dEHZ%qrLf&I^?QSanrI+I&(K3_wep80SHpu>U14n+N^S?4ygOyHOdHp~AI~Hy( z{($Z;1F8J?Urm7b>iqr>R`!D*S~qcY66YTo|2zNGK%l%84-eF2Y|$BB^Nl7S_!JMAU&?{tPbwD0!i&7Ws}J3#O04fMal*^~P8aT2sAX5fZ8uACe{ z2L)@u&HlPU0_rwHL<4eZa0m>Hht5OaQ^_PdG|-8TWl9 z@jk~Xc`ML8l7R=kE{W@h)R$z|7p&U1;QQqqKN;UoyZs^c{0-dQaX*^WH!nIKj%t6v z$9i;qetiX^`%f9X_ahaW`ocEvEvPYv&Od%f0K65&=UP3dpX3iIOn}tQAMj2!oqv3_ z0K%0s(04g!Px}8iV>gWMbraRzarbLU{Fz;oK(*^fyl^6fn%_NQG+~_R_X8)7q3eIY z0bpTVI`)#L^G~!4gu6vIaNIXKf8PViaHGp7T=a#0zhmOuelU62X5RK;pfDL!F&*c$ z(D|>X2Ei}4o2cQ@@%=8bzo@F13VoA4;kM>5s{hNZwcwlQX3RfB_kVRv8m#;D1uf5> zvHIWnx)kyLn3KX3&`D0mE~=dWWc{eV(SqSmH{sYcI{w7XX^?9D8QWUIsrsb9Oaapc z>1e7;#}8t)Az;@gUj2_+)8V(l7yQ#Tl8T=pI}Hl^rDMqyI(~RsfB3m_6LwMQjK5_2 zFL29*hlO8I`7<5gUU@qBcTdNUX>@#{=K#o1+l0pjbo|CU`#?9O6@Mv2Q}v_S4CwhR z4gWl)Ui}TzvcY-qS6nI|L&dl0HxnkL@Z;bAtOG$4eNb;HUH|&?Ip9+B z6>rJMQt|)l&w@v8X_(QgQd~~v&zI}EFka6Gx1FQoKP(7`$$x6mYBcwKHrf7HSRR0R zyT0KzjXhL;pJTHi@l7huJVlS6({?@3Ox=i91$6#L)dyj=*LQqp7e~b(e|I*FsZPb9 z?sWeij?;$;mK*WpH9EdtRwNXyyn#B^*E{ef-@lP^I1D3n+c3v%Z%4W0{jtleH5kUF zVv`P?zxiV%SoL2muKi2rZ(f%N3$lNpZ(0JCU*r5hu$i?1-#(!8ciUhCx5HEMdwSz7H9G&< z??y17t2d5Ip_glxoqz@IzwpEF6e@nn2nV?pY#Xk#H3U4FZ`Vc=I@hnWi}mO zRnr)*U0IL2tLgYDCyK$h@eg*{mqEq9@nJrktVl-9n{@o(24gtkxE>u_==lA<A&< zzqq*PK01Ew0&rTFj562h_zx}*fdZZNs4})QKPB_8Oz#YAFZ_oQW3s6D?zj+M=_TXz z20FgqwxO`(q$kdqM#n$UbQaEANeMN4v#I!gT^u1rI~hkVz!2FUf!Xvo{#r6S2`&4Qi1}UK)=y#UR@2R{5s#YaoucvhULxWgI zQIHmXt~(^g&mr*p2M&i-(jNG@h>jn9Z3$G%Bw@&TI=;qzgiY?!!ijRZVtkgsZ<}rk zHU;h&)kw!*mgNkCPbc!?UtXLDd&?_%$M27iF2X@+8KLXpBVzt$fs(Mzkd zekJoe@~aC(WhJ8XByN5{=2xO}5}b0a#FZ{wIXQnQ-h3HmjFk~y2r3b;&vJ=j=(=}+FA}d^#RxZ}xOz01rn+g{+ui(_t-1{{o z|DQQk5L+TEl()G+wg0c@NSL>0EpPo)Jz55iMG1K8C0$?gjQb!{-&5lLZxM0-x3nx3 z>ULG))Nl0oj9*X#R!mpnsEsJrCq;Z8wMBXqlx|v!ZLjF@yDVG|?(PXVOp2?2GJnQ| zKY%~G6eRSWCG^SN5WOe1C(^!ELG^$keB-Bp-#+C-y+u!H6DS`gHo= zg1rjegh~~aRDIfdt6;in0-hRsj{PmQcf0iRGAaUU;?B1L6pXB#*s)vu7J%qY?cf|Mt!v7wY zYoR`VFDAIr^~I0Mgg=Lcyz7ezZ!Mta?MjLKCHaS)egr!UdkD`K+!yoP68!bs*1@#h zd(r&~oqza?Oc=CMh`$)R{}1KIL-eba`0*~?|6!LNL+&s+Va|W`Vt!YGe`(b^70Av(`^E%on49jr_<|qQun9u_?x_NTkqTA@h5;7f09z%p<;a;UK_&Ull{-l zfBWFw3Pc?fx__CW6F{TiO6;Xa=T|)D0h{dN&^(%s|3~>Llo`qkze+cY{r4vPzhOBM zijr60bTc}>)rx1Z?UuYyaG^zPA3)eU4_ps#=f&Zjj`|_}n^%+##gh=-E$RJ3$(4x^ z_Ha4=X{XoU!}~Ab^roJ|qL7zj{&0f7d8`-cYm4F=!o`o|SDugq!_Ki-Y)0qbFm)1S zDlbRBQaV4fuR!NwPhp+z!5?Vn4eihOU|lVpzxu@__~Eh)v(qKks? zK?VK&N{jdnu(50p&L6|+C;e*)w}jho+;H*{I{wq}_mKBkLD-=4S*%|)o=J879UZn2 z)b00RSx-9trknoYvLFT5ZtK_|A>KdSWoiYUtKIO)2|EAdnLc1`ya(l0)A1c!KEls{ zUP6U?U&Z=z2z@&Y0>Dm~jJkv9{NoJ-psDUA(f>*j_dh3ieF34lqHtb4_xsp+1pZ^4 zP2h4q7BA1E>wB|30EUc6#*=S5_NNH{x9R|VX?4ZyD6ajG{0k~KL9I4R8a9s>)6w&#=t=kRu zhZ3=9Hl6=0PKIG7{QUFcePK^f48A=`$G^8_H(dChfKftj|1yB6zh0}_;j~L{p-~oH zfAG0>uzaW}JUWsqC*ynK$rSj}%@tpc?ri^(^|Q8ND-3gt!6c0uaeT=3+x_xxc)K(K z+ji3RmE8RW$Kn+w=BKK}`-DH;r$UVDQuNWF^GB3!gWMi5SZ_?{AEy-vD(~a5&6&9CMQ>sCB^j}QnrJLrMdvq|5eO@-MZXXFliS}W z-&Z}iLWU{RP!YZeYqI*^`tB7mz8Wb_heuH^xIcofFYT@$l!r%SVLqKdGCL5~;9k_a z!tqNH`4Mz_I*gHaL94xV{7+tfP!|@3kDa*uBj*qMe+RQk|QEa7m0uR)BT$m8w84z;&AymI{uiZnV=Q0gctu%(N1{e5GkRbY#-Ig$7wbkid~GF=AHJE?SGAPH)fpZ_kCVmQxNNaMf8tO|M^3~y$I}b zw9{Ua-|$v2ywKl+{ibvA4Iuc(_pycm*~R#NdZ)c4f9~M`c>Ev&|7@k_f5MXEkiMl1 zo9b_H@g?xB?^;7rR*DH%ID2ycr%kRIbX#8I!>NbG z`pEsyvhjVH*vkWifgYd4@yQ|L^Xz>f%$_28|EE8PPwF$;PzZf&OEKvsS5ESOO|XS) zqZVPsEV_OZn;`i8Jd77V_Fy42_?KY9YC8V09(G`Bw-B@c(&JkYxCtgF`C&nG=lg<^ z?Qi3VBDnG4G4!Wu=#5PB|{*;};ppqhb-$9nkKQcbmD-9UiErW$sPk)Ky zYevNPWNQ&b-V*V*(D^T1w};oo3-JAabpF(pp71zz1KQOUiR(9j*ni0NISKF0PV?r+ zk|aY$>G~kyIm6#neTv`gVM5w`RO!$0lk?x%8KU>2oINpH?>Loz;H#6Mm{g1jN9g|D z|6&KMg99%A%*{W^{e@4V9&oPN6PK(zLB+q*W(!xX?C|ni`ufD^^GWCxdkQ@pJM~MR z5ARMeVg}b3@%pbe*%OY5{HqD4^XI+IgxK;-%=lT*p-&QjWBOdUacmC$`pccalKxf1 zuZA6>{T;=-M>^~!^RwlG5i?cONI0R9oVvmVP@J;}OW$zkk7Rz=Y}yAUTQbmYHJ!hFhcz4%%;f#PPTFEIY(KaV zSL~tV$6VhB?;F#x`)E48f7mQAGMi3!M0^XMv;MEH5e3oqAy$Z5mVS6h2c+>H-=FSAWIKcVQWgYyI|CIB-8{+qCF0-r$5iM# zc_Ml>7E|rtPtJzNbt(9yC!N1)_F`~zv&G_i?);yO&)%eLP_$0L|DNV|;7i88@c2}? zEBgIi)AOe~$|d9Tak&ea|Fpxmi&8tvCEMrYIZI*3U3(0kV#za8i4 zeiHA02#E8!RoinQ$TS7xOop5n-yb99j~Y*>K*%=>JRx&ZjL#DJ7a= zZMy$zx}IQ==7fi0Y^nKS?-2rHZf?d`Ki_iuV?=(u*dl}xHK)*Gt%6N z9-YMBxkJSIq=@{r%MieVdQ)_qlPC6H3MAW?f5c+AJ7ETXd&uqok@{YQhQJKQ2cr+Z zrnaA@A5Ov3^9OK7W3CnL{-x(}Aw2(Agi6zlsrsbm2tYe*IKF4N@t4$B;_3wV{!PU# zeYyQBQlE`eFjSrL!s}Cfsr5VdbqKr&*oZ&MIsE}vlK0QLmIAci7>+gWTzts-TeY(g zjE-mF+*gOh{sj>COQ)NaL+z-1RGKJ9&5xs=i(%j0sW>;4u0N(W2p+q7;)tA0V*NQp z|D~210xhEZS@X2H{duzf7mgRekRTKM*UGIg$oAooT?pS^?n5C<*DsY@4#5R^_{x;i zuSDdJ>Muulwtg~xOpWb`uVnwb`1@v9w_pj*7~$AaF4?~;4-Extfj7n}y`tt%bi5Vp zeK`cB{ki)g0Yv+0?@EM^t7jtk6L}o8Wj|p^r zus9Ud2YF%YN_u>i`dGo20AqYTt@D12Wcz8@<_Mq4MZZtc9!=#h4J?GP-x;{Yimrdy zcwg{+<-{AmQ=`J5+gvX^y^+gbvi@Zft-!r`Fj`yD^}RdALg0j>cz2fuH9xnuIKtj$ zE1Z0tu78m07O1UPp6PD=&@)$9vV&87co`}V&Lqhf{I z66pM^4k66>m56zZ89&WWhu}${IFxGY zOC5jm>a8Gc@F0v?#@(;VA@XxZ4;%P9Z4{RO4WQP)x7v1?w%rj+W1Kq5CEJHXQ8@I- z@Wj3YxbcVVpHxO$!PujQxKeh1hkug!_sGBrEN@Ii#w)4=Uo!s<7wmvpW=^>2*Aj6# z`TJ6Xu7|@jZx2)*LmyvEcIAT1g*_NI-GCaO!#%CwRk#5*jmhcYm(;gAZ7~dZHxYN+ z((70Mj4y2aD4L&6m`~T|90fx>ys-My7q0$^{`>ZmT&Nx+(pN&CKe%dILS&6Ty6)ue z50d@MImQt#HjYE1z=#h0lJVP`y$uST=Hme4g&pOR^*48CG~EB?h0*fgsrtTt+7FjU zN22S)od5neJ_?BWO{0MoWaR4OeFN_PA*nCEVJ@h@F-3#D-1l+h`sPMMBwQ+W$A+== z{NDO47Zmo!;HPsM)cTv_W(kHGdN?tUyT3{DXRWdUm!+n-E1%;h$KOxWcf#Yw`Dl>O zHH4MZD8Ok6Z~4coyx!Brzb4fKNW8_L5F_H{2r>G1nthg zcz0tDak&&RKYplr0Jgb>BAahd&F|G+Ccy_2ZQM}Kt#1WHe116Fz*>u;_}|fO9KV%h zd{QoY!YbV_JBU81UTx~L@NK00SWLf&I?Vvr8~+c=eJ6u4#P~(P|VRkNUfib!INO% zT}?c2macD;uRSa*8iIp`J38VkSwFwNPJ-<7nrQHcZol)7Em+7Jqx^Pyd_8?UV3DE~ zzIipFL%(GHJ@4fS=hOwF-#4EmE+^ObVHt_=D9{^gGh{pTN&25SIt3JpH=&t=ytw_4 z?H4Xj0{O|B7#~m9|6{K$xY`ZI+w-?}@Jsry86&EnbC$U15?#OQ&O{h?zzbb^)Af}# zoP6j)4x>LGn`P-Qyx>CT-=B68 z?lr~o^7qy8g2-=HSlz_+pDfY-B0TrP*)eM|TI!d0{3H8^Cm)mG{AzFfRBK3$zpMQu z2y)fH5r%aChKDbNsKF+gKD zw^TUs)f)rsx!<=X^S7J4CEOpaj{5(&{Ux%02{dtl638%Za4sXSRWaq928#6 zL+=aR{ZX?1Z=8*X;EgL#x6(_jkKEreJ7om}SykTnm5*Nm&X3JdA(y^Bc=df9j8qtd zXP1tm>XWYugSzqdIByJhf0nHOXKD#BFmpNHT*2wfA?7FN>jYqSSrs2x()-u3_m{)E zC{t{|Nsr%=q;;TKG73-YjHK$jYZC^tGi-7FoN8)*_BKj@&nuRp?Fb)g{ElxFz^Y6Y zgxU1`bGow{isQ^tLzBM$(L;3p*5|}X{JUWURo}L$VX#cr20!$!qUu|0m;e@PZYXH= z73(A8x2VD#0wTMkRZxf+pS*wJa9|y*2_J#KPnuKtb9LRJ`Q-?VKT6+!>a7?KO%LZ{ z^c8yiy8MX;AGf7w8|zPv-nmSTcKlJ>{Gz$mmhB+ub zn$EA5mmR6oaYpnNhSKmYZxq zrY*(lf9tORtG=DrSEUXf^ne#HOi{O-u3uK#3-;xjV{cEo{w`O-VfWzK7(a@h|C;-g z;Df#k#@$^0M15fFJt2CWO|_3I*vuj82ESkz=H_Ah{#pS=9+1&tHUaceDIUv0Mt zcs+R*mdeoeJ)D&angy%-)OvQ{I=;_BS^BdcyG`CdkOr`D=fBf!D8LIBPZi z{GtEvNNAcr6P4cAQuAMC@;;EtUoJ7f2(Z$S$lobF^I_TkO&H+RD%RIb#Aou5ncy}= z8J+#P^>YriRDI_YAO`-y5}EGQ{;y^3Q#^ z0rag*@YGehe`%qK@YUJ@%`R~JOXU2dFz*25Td&5g!@2$=huEK&ntBY>Ux?yAW;<11 z;q;lHpR9;pW^{eG$J&C&78RT_c4dct$@yPP!v?sfH5B6)aPtEJ(f&slCxV=TJsuj$ z=_mVlzy7756dQnSw;AWf{U4DZ&Oc^DkL=z!yOzE`);@ay{Jy7-OCr3e`W}UBg!!>U zFg}^C@71pa82#J^m-y4?|7WMq1BD%`sDF+7zAS*q&r?+kKzD*Vp59OAFPXOoQgmkE zIa#ip+@CYumIST2wz%Rt7ay{I7d$C}uDLt0=<7IYd`?s>g4P^$T;a@}&yxC%tHeT` z?o_;Av#ujPlI#1qX>pL1F#{F;J)*XsEtt+7KAZ=WE`V196@_P(;Ee8yru!icN zyJ&yq)nr|CKUN_wC)@woFM05F&k78EPX~$1rHK8py1QO5Doht0JKl#R_04@00r!_#U*xH+DDdcSfur|u{N()5@md^= zG`B*1T@Pyff9@-Q&7R9pDz9`rEq_nUCz@?pIBXPg(R{m@%btby+d9^tME`la@GhJ>5RNzN<;DFs**~9i3V@Qi2I!xDi^~7#Vmur< zHvx;8vsC`CE?KZ{*DT!1gm#omjvq&cpMx(=o)~w~jM~1Vjs-!X=O8@1_5o*4#Q*G+ zM5tUf5eq%eiOb3M6;`+pis#J0im%-Ko+bR>W_$?_eb|b5(wS6#=LaDGI>vbIWCO=f zjNhx*B!PFqL|pl!oXWq?BMS=uPRHSK^!T5ZzXEe){IL1jaVr0S*ieYNI~ac*dral8 zHA{sncPu5}FDL4M)7)(MTs$33ZRzp%_!|cI{Ee}0R{>=4~ z15kH&8v4}V6yuZoBYoe7L)tncUi*pL_Cvn<6f7Cd=_BnY53Gj6hkWsey--~LIYj&a z_d6V>*c)R0gQgCC$^PfN%YFz-U{J-srlVZ4|Cygz3mT8MqHE<%D!#N@1b8nuz^G_C zzVoGH(Dq?2dfn}ek0gHDk6PGO>WgO^>G;!)BcP}2KpbgK$CuR*eSe{4!&|>L$7^Bs zsm-``ZZ%cE`??5lD%QvDGwApZZYLrCf*mjZ;X@ISRjr3NEa>(X|CNCH{Q1~=?SnYJ zQbhhv^0@)3%Y1O~Rl2^20}-H%y14dCV@Lf+)?e7`WKc3O!$Re#zqxc&rN^Yt8Q9 zm)u{fiim_q0R!-t9zA|3n=V47)lw`k$f4Rh@7oO{eN?b(U{#0zlJQY1E(PVSHps3K zP}iS6=7F$XRfYHaF6|Z}$e!hopY7E!I54X(R$Z$T^ON((eeX))$3tt(w5HFmyhZ(| zoUaC&3hDMovX4N)j`0%pNA7Q|us8|Nw5Ot!iI#Z$*Cp=ntz8-p;a}8opdmN@k^QsF zfFv;bX@JkOPj$pkGJi7sq9AalCf>8A*Z=g&L$LhaC|vaBU&r__*?&J$3xsxQMU3hA zzMbs955Ee8!k3CDdx|?BA-_-UbNvvwA03I|igf(VhXUbPMlUq-qwnv=+8>5hKSp5O zcg~(A)*mGWfiUl+0l=D65DMPO;chF=UO?E}`Q$>br75}&qTBcX7YH{7%SpU%VN2NC zOb>$3K62>m!|gATU446&VztpE39u|G)imy6a9zSCqeK9t@+tl5_b%hnt5w(p3W!LY|d8kPER`RNUk z{d?ZKU}$rY#u-!S{%a9@2#H?3L6c0+poot5cqUiir4?ZC8F;ezDuEjAD#cJdnkHImf^5KL3K;HVFwJ-!C-v49y{4Y%mfhFcry!q`=912&ME~wBz=aT3}hS*B+=GWAh`Ct~Nhf0<7@#pI25a>1J4?8QEiyw)< zc2F49c>QCwHRDw=+=o#Q8o|6_a@xSadL=3J!5=b-&j*qNfk zo1Y<@LZNj-JKOMzuK(h+FtBR-#Y*HK(LdhUe-!4P8Gx=b^!Ox+*55a)f3ODSbo?E2 z!ysl@JDd54YhUF2B=`PN$iC1YrAE>5ZDqqi`&1j-u!ftzkp0JsEn#3B_=7dO$l(VN z`m@Itz_CZ#Xx2SJ+&_`~Zxt6qVgB%M?86!K_WM*T3@+4sV;cr@`~o7s?ze=2>)1Ay zum4gM@vo23l4!r=`!C7up|JHrE33Vj&fj1k2A`IEWoJ#H^Vcp2heXrwZ1Q?~{yh&a z0H1<>ShRwRFZsU8L5najT>ORYoWGL&r*2>vs5gFLJMTA;=PNHig~67Ct?az`j`$Pf zlfv-=NI9Y@k)N)_{L!X740btumZ)D6-)V#Beet9(?C&gk{!dm7hyCL}vFDn&_>lI_ z`@>=Ch|lbrGj#isKF7ekSVN+I$oofb4&l%z^8;%w%gx_O{GZd0!K!3+-tj4PSvV}c z@{Tnsr|Ww*;5Z~|sH4dcp8Twz@idI@%oDK~(oeSO?W2zMk>vVvl2$Eb^)u(?_iI&T+E#Do<-gMy4nrTmW)s!v@hcg< z7cO-F!InsO>>m>IH)cmIc=k3!)_pP6|2XsBjP!dS9CMl#w{HP)KHGP1ICPDC$*wQu z+LtXcKX6za0nZv=vHvyE^=&*G0T2CN^R_Q3#T)Rz#1xCtms0iR%<9b;joio^pD8Ou z_a9nbu-3tJ{)M9bi&a@K*>H2NeG7>GE&SjONYovU&8f@9{N(*ah3wu;VvaX2zny#p zY~S^awRq3PM?l2q_K^sP3wq94U!v?&WytMBUic$hTq6}#Vo&TqB32wboCMB6L@72ou& z60>a7N?v>|-$ZiFpO^RvpEXPuisP)5Yf9e-ULF$sbZ2qbQas89~6CZ1onbu!RFwd*=ev;(=T~t66=uNxLcE10XL!9r7 zKNtg>w%ubzzcR?>7qS0w@V+urHgqxGw4~#!mqx*^gq!TP98N#EKe?GI>0U@h&m2PkUTZI|gI1BrZ;qIT2^P7e8 zu`p~Uvj67L^Y^^2Dzl^SOzb(5ZtoD52od&IS$I+3Q9qLX&k=ztvv}Qf{AfbAf4nOZ zlx-^6myvXP#oL#l&PoPX_IM-4C-+|s*Qzojj!wnQ9&+N}A1BxM+e;F`?ffOSt%#2A zZGQ-(S)3<5d~`9#e2@Z#w?!?n$s$$xZ}Th@dH@}W}5XVbiT;plkp!nF$qem&$AW#>G=39_G-vztBW_{KvnLvno^+vNehe%q9LF);(o@#9N6e(i!J=&65> zm6=P&zoT^-ZaRHqPwt@OuOHcqfoN0oe@Dl6Igtd5&zxnG&eHMs)n0;WabMWBikH;< zd9$Gx6WV_`9v=OV%RgfOtB6Hjag+f3b!=%ptj%3ddX0`x|nspLB}t4x(xFp z-m<+b>G)sAsWbQFM`Gq0y8ht{lcBx%B)jb!9pBaeGTbqI%|0ok*aAAptMKE8#W`iAbG z@d-ty$2-yYKk{_`*b~WMmVcC8oKKJ6@Y+g9ZEog`-w@f}%#V0I)Sg4fzkf9u-k;55 z_0sA14RC#t$tE3)UPH$({E!TvdLQA{Z`}O~xXL!La!GXj44uBr z+Yf`#YFaim{-64%z&(e*UNmpU^-aD*sART{WQeWo8UtL^~Ovm?#5XFB=7VrGx z%<8K!Q~nk&es)P;W_}+XUi`^rDPVm#lXv{r8FCe@SJv{jFJ)n0M#H*4Dg@K@Ypv2` z;=cCB!Gm+C`SnLR70xPWuw!S^=QkR5SHVxZnwLMeQiGZ2+z+=}(evwK|5Qk|PGc_) zq2tSpzY0ZR*Vu2d^!ysLLz9^@wIAm6?Mbcw0MYkXzELT>`ZY^5nI18HF~@>#|7uby zw46xd?Y~{VT!m7*%k0{5^!zDE)MS37siVSIdi*ahO@-l=3B2t~f2SsMa*HZ1D5cv^ z4i^1>)R=fSLW>^1ukZRY?=1R=`04R?I-Ux_^Wxa0Bk1-u1^pPyyUL>XP3iG*zLpC6 z|BGe+jHBBRDDB6r9;AdO_v!i7ODYX!$i%Qyz3BFnW&1I03B54q0p0&p{WOpn8^!wX zqT5fpr^&SW_2kX}OEc2os%Hf2kVLn4-l4_l$@RoHvlOWL)-pk z*I?Mbl18WdoPRmQ{8soS4Sp2toyxyXR6n!R=kkuf(z~ia zB_WJev8Tt+xV0Cv@#BANk{TVq*YpffN|?=-tJB*@kK`)ASs}dm^DGpZ(5~m$4bgP` zdff~dT05P0d<;$#wU2Ls?7@+A{T~)6GLt}km0n9+xD{STpI={@+4CtLD;Pv0a zqYAnx>|nEx(DyH7niQFpw~N@6Bs%}5NduS>*DtaLx9R+HqWbN6e))jDRS*{L$*Q!``OQBMV73O9 zv0Lrv_!e6-VAvaTRx6b5U;i#u5Z`kRYqyh*fBJ53X8YJftep8zYW^tb>oA87mazXF zqw{N}XFzS>aNhhW>t6-eLYK4t5p@2>H9Cxm?J2gK-7#wagR0gq3r^6sBqQmKX|4GjBu7#)A`d1WT> zZzL=F5e900YTwjlYUZV}fs^U{AsaK`p0YAKCy2iPHGW(*OkQls&atNR?^4oZ8eS){ zIgjZ0ZRMi)RrTWC-yUdR4NW!U*lmmG_Dg z(P}?-?2bLu`WbsskJ+Lb#ky=eN%b%3b_T>JOY`<0yF~mWZHBT__t5>DTBX5cUf;VvUJKs2n)u6iBh~1Du$NxD;pE-y@Z0G%*X5xNg>a`5ei~L@}x4*3~ zR|AUj`l9s(9p5;nA9M1%4{K6GU!UmQ6XkEekG%NZFIGeM7uxJSZ#w=TR+AZF@6I+q z>_(m6%NJ(A-`g)Msx0aCzwc)i+&ZDb4jWGI-(2qKGf!`9V26Au7T0eM(ZBfDWWbNl z%@y@4==dogsz6R&g*_ri$M4>*$*iexX1mGKdGn`n z)<8zjdO15@y@aZN)Qb#|?t8m}@BCBGy&8_h%drAo&n#tmhjf^xT7_YsQs~mZ~gIhlL3?Q&QhZNDiObLzgapH8crOq z;5&cLTu}oqZqF+C&L{Pb888>_jbV3%pQY;WEuRUh$8&k{n|sti+=Yh~g?jY%8*@OL zv3Y95)+^G_2X$Hu7}q1FthZ_zmA_g!6K;&p=H*|YX2|IN93&ART_Qf|qcfqfC8dII z{QNl0Q1k;dx~#C}s5t+0iTt}bHWT!%_g3(YFU^>15UCst%s)A5fQ zodKsmODY!rqT^rI7{r_wecNgDl8#>}mkDF`oABnZ?%FdjUO1~Fe*rzeF53)ZhNqpa znBrd{)=z$4vA%yMw8iM~jxYT)1~Fak9j&mK$5QRJUuA%;k5YwZINg7}4}+LdLozBl z=SQ|g|8eA{XnfoE@50Uiy8Sk_!Ho90h>9P1Naf$AmLkivAEow01ui#jb*+#d&@j;Yd$pyUnKfWEz#Jh~E2<&}H%ujy5 zF!VtNeBQC=!Yz9`f0TkTlRj3fqH-PGe%#*-xM;qbSHI#|W9Fh}`-QE~==SdaGGN)^ zp}h81zQ#;uYuSa)`g0}fFZWRfJpJ8to=^XlhsMl6Pag?;Z^FJ>HWQ|dbv^$vi|)U! Q!Vu<2aqIa`e$xK`05)tqF#rGn literal 0 HcmV?d00001 diff --git a/core_perception/points_preprocessor/test/data/output_ground_structured.txt b/core_perception/points_preprocessor/test/data/output_ground_structured.txt new file mode 100644 index 00000000000..a6b40c5e737 --- /dev/null +++ b/core_perception/points_preprocessor/test/data/output_ground_structured.txt @@ -0,0 +1,30 @@ +0 +1427157650 +349046016 +base_link +1 +8426 +0 +32 +269632 +0 +x +0 +7 +1 +y +4 +7 +1 +z +8 +7 +1 +intensity +16 +7 +1 +ring +20 +4 +1 \ No newline at end of file diff --git a/core_perception/points_preprocessor/test/data/output_no_ground_blob.bin b/core_perception/points_preprocessor/test/data/output_no_ground_blob.bin new file mode 100644 index 0000000000000000000000000000000000000000..f17170692dfd1111c3ebbad8ded4391fb001bbea GIT binary patch literal 1510560 zcmZ^Md0b83*Z(yorDTdSWfmbbX}Bk(Qb`gGLXnV!l-ZTiOe!QvDk(xG8LGSYI);)d z37L{qDn5kF)6?^N?!M0cz4rb7@%jGoey#Oh^Im74bMwUPJa_coKIm3EOq{tx^uPZT zYyZFh`@jEm@%qlaTv`lMAB4$p4bxr%{BqiN?rBUhe6Y-r%l8)Gt{=X0$#;ukXGxI^ zmvDUqxY>?eZr0m<;Bt`7AM)-SXVU71fIo^8@`u|Lb4#Bj1Ft(t&M&mT=xh-e6H>L^X^G-QlH9{zj#E-x)x=X!++e_zAK6sEO&oX(ZcS&)|5|c`yPex2e}gSQd;sPui&EjTdON27A^F8z zTb)cO&S1+A-i*06U5~?_UQ1>2`c(d()L-D*olk_P;#N%kDMp3dX^RwyjT$S%>H1Fo zi#Ut);}GAMtzX()z^(k60?$9Q{g3e~|e$g za{JSc!u7>O1>oKDYPJacKRE9siMSq?~W% z3E0@3#6L+a?C+r4gY&;|8JU3J|6ZrRR{H^tQt|QI_ zLsjA*ZC}>UT<*|{(-5!2#@`&z<;H28fpz2A_(JDgt^6-;R*Rt{Q59heyJG0>OC3b(W9(|4*c{dBHcC+R8-#f=`^v;HY4($0eq&|nU z+MNwmDQx+$gA4#SOg#b?Iz;w0(Ee;!}Niw}%n3`IJQ2myvmf`+_gQ_Q0V*z!vH8m6)P z`Y6ngMSdoit0#q}>)7&f9W+eME&K8xx`fN(mqo=-dvYc>qf`p<+u8DxRvM;_Tt9xX zA6s6d;S_fu96@>_Tizq+6sJEIgMJ|!w-|bg)A)-a;Qb2(40!=oE){QS=oT+hHFu&rg|->;wG{)QJr-9Tlg|Mrew zx%~L9yw||(GQ5JyzwfjY+=oFoppQOVev{W%E+MQNFZ#xo4}F}*DLuad2WPS6d;6ww zCWlL)?@BhlX;K2VX>4zO|5e4Lv$=N4F$u<^m`k8@kz--3w8Z2b1599OusiT#FdIK^o65aWzY7WD*mz0bRPOtbQYhcV#=9n_aISf!pt75d+mBD- zPW#=1o@s1c{aG@1Vo4b^J!In@eUdqUwfpd@iH+YKnamk9-G`DvDop>Ql8iCb9u5bWaFc%^m{7nJ-6;;yrCjSfki z7?(i!yow{T$%HvXgL zF!yI&6+8@LE9SzOVeqG4)Fu}jb`$@`owX+C)dNZ zv26JV9pX6Uz6~&F8No%=^XL5|2f4w&8o)1>jc=ZOko$O{5t1&m@sz9s+>XFEVETfM zpILf^`zIL<-yD=2+3m*+>g->yBlpDT!LhL1ZtGv&Lv z?dMwI&(K`K#?^dcxypy1VR|+jA9F62n^680?k?`a)PJ@)hWo*N1M@{}yx*u8t})~r zw6kU7Wwp^9C;bkR<7`~Avy`(-TESo6PWDp~C#?U@Rd+b&$Q8U)e!oHE>rdU`Zj4>U z|M!Y5pAenT8E;$87a0C~eiiCJxaJ~vVefL@N|lZG>X^+P?BT)ZDz_%_q3qKyJ`!4^Igc#o^U`WuR-BIf@8T0Qx@_CrEK|9zrEa< z{;vGX$80<@(VE+E(~>t`bylulct7TvHG`X@IggJ!V|$@u`}m%e;h56jJhDN&v&@`Nz=1NniLyT@vPS%2rUhTw-zKHhx90P*#7z5^|40`5_qOHVjAhsN)&ES|!p3d*) zJHcXZj4}VNj@*CI^KH%O2=R|m)A?sp(`54W{q@*4yTq+_nefSvC&+Mm{@r|`B%T#! zz&93-k>OcXf6Q&wQ9Rqvnm;OL$FD51-sI1@N&NQSzB2iAD!!Vt>P*hGp2)WveprUn z?;j4BJvDJmvfyKz3}v{8s;{ir5|i=$rt(`pCCYFOs{Z?>9XENHJB61j5&P3A`yZ?c zHu*bEo7e6-S0*o^-fvw#vEIaeb1yz|y*9y3g!SFyP>jh!qbdC4%Nt~P7Ukch_5mhJ zGpF#Ab{}EdSNPzw@xdkC`GVX48NQgZf3RJ&amU`h_}-t`_HEri%6RqkT&V6^HrPJ z`&H$#P-)4n4t%T@$v>Un8^IT)?X}eTldIYC8kewiV!0-tb$yqNpPs)PqdrLYv{C0h zT-oxWo~_aR#l870Z-Qm=A(a0WH+4`qlYabb4R(ACyK17TiCy@#PGtV;Q16E=7l@JQ zW?w!tpB=xcf9Ij7|9bFVE~I}YCc^j6dm`qdan0TNQRVqE`}8UOV`|o+?}N4Y<{NXE z@o#+RgHB!T!B3ye*59_xR@6SfBX8!z-jBEM4nakCTJ(pq^LxrW6fGa8#y`8smQO*^ zXf^cUZ;5T0_NjH-kFw)bcsn=JA9Vh^UpaVIHXVLEB?tF+k$v@p6 zv&)Ln##a6LZb$mcTa*X|F9$H6OE_+{fwNo`}5vW;WGVnf2KGVp4dA7XZW6`H?Bc}Z$~l=^0wetoJx zueg3k?VYsv$q$m{{tM%i-}y7Dv{L8YdTe3Jk4n?QZ}yMnO)Ewad20SYD*uVh7OC)A zKJ55BtQFw__tp676>R&)H>qHi^;-OJa%VYCk+WtS656t-?Fmv+oCVC)`BuqRxYrK3o4V z?;A+%#W`qtuSfDj=`T8>i~nrx#{2qqm)kF_fAxTJRCBh){+UES?SHp6_tD0=xnN~O z?3Ymbn_)C|ZQqS=KY*=&Pq*jjbjLifk`VoLe7N~fk#DdtzI1&0L`}lJY2Em-N7?!l z@717_;`5-PK8oqT$G73Q;!0coog4f6ne|)Wp=+JV7C7{WB`+ng^A!Z2vU?JkI4Nc z9lzCEeB#Q>H182+a70sJ_)`3l}LS1{W*T6296yrl&ACmbYVwqw)_-)lfNI6 zQ0LRJ>~=Woc`}R$)gk(+{Qg>{fh`?Q!I^wHKPCU#SsDMDdkj=pk@5MnbISOyoh<>`hv{Jj^l>JGt_$ym~ z(#8IG3nHqx8QX*8^MhIR+w6w*N1F55@)ivcY8^Ti)@=Zd@^`3mS6VUok4Nmo zt?qZ>w`^s{$KmQgT)a3Dlmh$6DZBY{^e9i>#;;`pHTnlb|bOR$W%yd z+#%-|#`kdCL98^n3;)ddgA7li;_IC}95+8c0@dS*eYF3No5gsh%{g%0J6k4C_n-9C z7;JhZ6~1*~+t({+3~mA2nD%||J`%eXCqS2Vy=6GfzwyO1Y&|IlejFtAPxI@& z8;{L&Q{l@&68|KzFh0)h6S2*)&OC2fF4IrfpIY!3+}rI4G=5<74+mqg5jOzRtFp0OfDk{e3%nHlE+IANcqY`;w^s znKJtvj*02W_ZW4KY2Rt>c{uEEDp)s5e|Cd6j@^3} zIt(WF_jG(d$9UoJTc@G+3p+kdFE|`CC>(lw5`GC)9|7U+_(%U#NDpPt|HyWFxTazQ zXj=Z8e?tG-E*OFh$E*OqF8`iCh5ilB^T00xTYi7?j+}3F{uhoNi^p%;40fLK{nJEP zf1f6rW3Ds|d<=;FBFg^W?pE0Hb|gGAGAH$AB0N8rNk`#Vzr4WbH+lY|>+@u|6E>N< zABr3Q%@?73T!anoek}~l<`8~5ewlX`;#rRSVTjVd`%|I3yM_UtFkllTUm^P)oxhQ} z{hs;ZN+-mPQYg= zTYpj02;ArILYS*gxgCCk=E_W+L)wA{6=LcY4rBiS^I7lup%->F@ARH2Q1}a(| zV)}PGb0j`~)&&mullxzqf8^B}c*e%9Q2m6>ANA7(=R`z80g(O`QT=&Cx*HosoQAqN zq(ABX#O=ULJm>ai@cKDHZoe>p9(Mciy`2|f&6z!NT z6Y)=FS9ohq@=Npo*ye$=CPczYQ+fYT^Y3}P5d35533%y9?#Jo)memWW4p*LO3~u&9Ad(I@TED1vZaH%Hu1H|KpfFxUuhPI4owL50)d=;?&#wz|Df# zNBh4^(*Ua+bp{(#QeU+HWz8$`?aXk{&Nh?hN60_g+7tV!g@NheMKT;y_0^O2#P#-J zkUE*%4~wb%r}sC))5@Gd&x_69O@9r3)HVW2^k*{t-{7_iPstC3*ja3Tan33{=}jmY zTq5_!H2?D-2DovB0}QDp_irL$$z528~1u23gb_)`B#7R#_cj>z0p6&k=t95u$+b~G3W%HNzS&x&phrzmM zgrD|bM`D5(Z<_~`_Y;0G<-hCZg*aJbBY5;+_y6kJ4R}(YFmM}8&M!LuH@FSBLK+HD zk4XG!|2Jt{;x=`zkU6-sEWUL7?Pn~(N*0?yql(R6K5#Y;OY+a5o@wHzkbjbP??!3JksK4T47Z71=k^>4hq9Q&wk1M{L4a{Gnn)2Da# zc(imWOzY8&*hj_J?w3F2ii5!C5V2oO&6hRn=i;YY?y%9rM6O>rUyI$H@RS=XA@8O$ z(QhK;f6>JrJDgn%xs$rca5}%C=N+-rBM){1A3x*)*EbS=dcObBcEalOmx87bi4PtB`n&*qG9(nD z$CCP{>r3nQBAg$#9BR|Z{zdZ_M!Vv-Q$66x0>Uq%;;-I+3BKLz2>~ajG2{PX&@vn` zbv0;qbd|?f7=N=Vi|~bNcPRbVRgMeyzs^1$INyI2y!9I;kDqY9O8YFqbuX4d`5BJM z|NLtZj`0bF9}dKSOwE@}v;^M|b%!4>2|w-spuO(+(8^^{-HG^5$G_9G5PZ6Q82nkj zmDoq=&oYn2;?uF<9ZmX^etx*U(jA9ybAxpobmjgF{Tt`D8tdeGL1N&)^F>(S_{3`L z@v{XtWXD%`YcMW)5Cmry4VBv`jIU^!8xD+ig)SBZr~9j@Ul^XfGX(4>lKCm2&ad-&r`#(KDx1@XEnD&d|mlwOgYWFO|GvB#F`~f!qlpz~2NY;X8D{{Wj^}X7` zAM0iNK$tt>mr(t^!Dl5tIbaDWcOdzt`}^@pfBbHYH@pkhC-I^7U#CC*cu}A?IQ5k8 zH`M&>D-FgEp9H{=XKRT(mH(wH*5Mh}9a7#7xK?p6oOZ$_(R{f^7~uL zzw$f57#;9~Zx20)eN_DxgzU!YE^DEDIa~jU>KH8g6bMgdlldp1{Cjt;<^9Nzmi^$b zCsY6Vm%;et{I&3GGtp1yZ;o{k_DS=C8ds7(dj3t>7lx-8_<>{++rRlO`MHIbg1x?@ zjGxZm!rviSJ<12d#}a-KRiC$yL}GZk5q>33lFJL{p`S|@< zQzroYo(+=WbpKl<$KloY0wH!cJAN->_u$!A{b76fY`MH}{-(~2#1^3&z$J;DzqmGs zaNNFKaC-3&x&6ZWSUEoqyZs0N@h-AI(EX7)Ee@+T1b~ediC+@c|J~Le!qN}BAZ+9Y zrvI|bCJ22zx&|xpmTC)oDwv+ip zpKt3eV(`ELE$440=^whjL!U%pQ8zDe`%L0X`)ATB8V~!s8a%TtNPMaJ6px~C@7Jp! zt<7Q?PWv}^@NiF`Dx75${5G}cWVSU$hKY*{jSpya8$I0~z=f|7J`|y-jE8uM?d%wEu zc?>U@uoG~Xbu#%RYQD@3OUIK#f?%Q^+282->F_)NZ<=5OZE!!ieL{YRg9q`uvunW5 zl70TYey|hkud;-;2_0ne^nCm=C=mbZWdk|4iGGntsNeeKAw1@Z50o2Q$^94h&yk4- z@s|T$&}9nQpTv}ZYAXWpB^L`w9m(b&mVXx4M1(-#a*{tfzbbe4;oSvGVElLae5LB^ z@zzv))_MoHjr1Y*QT%t$p2qt&27%!_@_Zqo=EM5lG5DF)<1uKGWHs|35-Kl z$>T4aPc`pCaO2Y15NJ=H?~|zW=ZWYbell?xB;6qQOLYG@)F$95PTp|+hkQSy{9Ab> z9WR+Cf$_oY{jgJqaBQA#3*%MQWcJbgFPgIPtqHr~q~;6~A8J2@#4OxvY!Kw_B>O+6 z=2Pp0Xq;#10)Btw^OM>y9$1Cri{EV^&zAUKMfv|*D*|5_V+&UC{pIl!)>rn=Y+O@{L#==->>d`v^ZhKf^3Sab*2Wh;7fV@0YhDaZsuai2ft{GhN^F z7aYQ7j~Bt)c?*dBRQ;Z_3&o%MnYFxMP$v1K;#=If2QPQGftRm{ei2pQI|@}WApDeD#nNI?SYP_w!}WFzNc@xj&FuW zLeyx|zf}~!)_{1t<(3otxli&-&#&nH;do-%G-zB(_{CKG^B1RMUUxNIjUnd)onKRz zVtgqq60(-E`8C!R;kfDua6ZOMPX9k$*j{1S@)=*)23FO`EC#pL{=^IumV zhaEf21D%@&viKxX{+GNj!F=yM;B%4O?-J<8z|fAoh`;-<1B>U!rk#>@>)$B>L(4&UthI&wgqSA9MQ3?8DT239n1Q{j}!5 zpxcw>xNtwH{}qp0@34W`acur#yI35OJPp2z*z;}A(F549zzn+WCHo=Gzb`KVzx-eW z57!g_B~*Ps(B6;J8ce|yv;Av?gSgz+488;r{Z*8Io?jEN!Afh;43oeAqx3(DOu*xx zTS1+e>|gZ!*xBPCPQN(~G_8q$bbLo<#o^rg8E|thn}7Y$1Z>=Q78q#C@Bb+NE=P{w zw%%6Ytx5Rl`5C8r2roG@9jwaO{GawE;KfE3(9xglf3*KE8js-5t!BaI5rm(vFTGbO zc={tdIIxz?Uz-1MQ#@Y3b_N8@C+8#W|FhN!`1b=dh#pMpOGL$g#jhjy&TXU+_B(}g8{CmCf*F-OiX)DJa>@lD%l5Vf7e7gPE}$`4~z!)cIUM4lh%`t6pKgpFM-VE9(zAI-mF z*$M2~-VW>>Nqi+#|Bh5kXnFs}DLfz3Y>(hWLDOJhIN_)Bn_QTJBQj@!@(gx;zcNn8 zY3_5ttu33s+V}|mbex00YIcA1m!{y7QVWRKLH2_rD!&)GH2mHM1vO~X6)T7Zff;g?YT-97sx zKCCwzzT6@FwEuygN!a?17|z^e$G=NUe+G1!0TWdSKb`-e;n2LYU-XvVH&;*i4v-wv!r{PsA&0w>L%oqCig?|jvaZ`!*E;2OLCA5BZfw>n$L{~V=nUR6 z#2ONQu=j(GWhppszcEZ2#P;7=^%QP9Y$j~4Ve=m>&%}{t7NFcj{HOEpG5RdN*VzhA zS`vOSm47$24BSs|8cd91*MA#P4$e7e4P8~q{b>@_e-87q@#97-sJX!2AJW&H#WrUx zLEV+?4>Z5>$g_AsqdBA`k>^i3{+&ZN+1+J-yy^4`qOpI#TH|&VaZ2zX8!MGoWq_=tiUat@MFq@$iFSt4j1~?IZ5q18k{+EkYMq0tnSi&!%_|H6Eha2v- zhg>O}KYCgPZn)+PdHdJM{G<2dF`hZtFk>c2-P!RE*3HAxrdgnIh|S;O<|X{At1akX zX2<_~+$G%fWHxN{WA|TXr(Aqi$sA6dWAnE``S{!gTc~t3WajtupG)|7ferX!GG9bg zd~-MF;)8$8px%nD-?*Uwhink)r{6C=G|R^?j@rPjN}`{x-}!sb;nrKHLx(}Ca{Gk$ z7o|Ne;OtfAu=^@GpT*SqaPsCS?4h(9wm0mQ%M14tKle-6ZLtLe+)$I_Lj4AMS@^WR z34|;p`vKh_14=L8nB{~gbq!vmDWg8h%44`XmPE`DnS zU+T#HH|>AVq)XU%yBRF_Oy(mUf2s8yJot|bbjw~S^PkRd%G5mE*Pnw`eN<#P?f-xs zg?N{(1uWJg{ZU2rr?zK4c2u7!c>bXI=Spwm-<3{~H^ha>ucwFbi%1LbTgBEd)|XmvQ1sW5C17^C2C-aXSEa{?@YJA$I(lH{ZpB1MNYqMeY~r z`h3uI8Fwo&0{{2K{v;|tcI|@jh@MI?$c8-M(Dv)r-Nnj2bHQ~DiI0SupI@KnUlWjxWSYXN_U)N#dV~`u&2d#cn*sO$mI{|H%u_N4>sf*s7mBT%1Pyqxq%p z3UO#RV`$z$<`3Qf{!UUnCcqeUF0%PQ7Tv_NTF%ciHRODv{dcmzj~$=Qg%S%k|Ic`Y zN6avW^gK5I&SD;;%^XBuCHoou`wd&;5NzP01iSuY`~N|EH})CV7DO@Knf;%>7vZ#8 zLzp~(%^wk0gx#B`Lqy*JGI=`xpLYb~zNg#5=llQqTNr=yg8TTZ&K%$a9GLy_Vs
      l`zp%*?1c^Z{j(*|dhIf%|2rJ6 z8HMAOv2DS3F3CU5|Jfl3zfb>-J<2;X`K?W^ z zn+hcnZ2P94*^T=R|Bj!3Yb}c(ZC{(>5UfA=H%{P)etN!~xKM&$U7rdUpRx7xS3~fd zl|OOB$2KzkQB-_?j19*+fBs_0G4g#Gt$$>%TR0_sD!6S)}A9S1rN;`;u66$;`J+>ED zs{FuDjuHFl=L^k0d$8l{Z}`qPdH+!Hf4i;`zg}krP1A|}wEn?{nfSl8-CKTtMC=z) z^Y484Yh3oy0xsV(md95(|Lgg^xH0S-uKGjxbtwMwR&Vi9Pb;|XP58x>e`9aH!{49S zfbC>Gxqe~(1|F!#xaIzL_yxkBMAgr)miLc8oxkFD8HAsX?`8fizJGrfNX^;&$28yL z%BR*~b$x`4pPv64dpF{ST^8^}$wY?J{H?uX@b!Y9_}V3sKMl(NS*9QGQ+pfeJ)7;{ zz1MHBa(2u8+bW`;?hoItG5DUxckETmoaXTloz) zTFi#(UOi+uU4N@8F5}J3+VJEAdHxnt^>5!!4OY%v1-Ep__gQrRHS|}7q#m9iy|7kp zpOD}1`ADZv!v3MvNV{)>*EyG2K^U*rjkjmUmU*Waj39l`UgCs-w} zWAY#Q^aCe(+JJE@HvgDg?ZDm41+LyB&kr>J*`A%C_UbCwtnDnacr~8+;i+ zp5JMCu|yS`KDaMxV0`M0*yhQge6P#rK+jtl2^_xacG@F;Ca{Y1Wx6p4iK@pkD6%iO)8;LCIp zKkEC9Cpx;|ygm?`7W*>o_gr!mXPA7(K3~ZEwWa3o%snmdN3MRxu?xxkr~T93s|Epj zjv&5A&ObW8k7u>i=XY1g3nI^dBC0;ew!A+)ThfFrgUR`9OP&Ac&hN(h8n^KDm#yUS z5&C~&xdx0F>H=nO$oBzs{zhNu4Dau`KI8V6N z^8G?La2QGUJG#DlSQO)XzcrzC4SD{j=bQW9V|exPkJxoTiEk2BABjD>!PiHwko$)0 zr((*!D@vWA<0vPn4x4wpFuILID(L`QC#kb;CF{frk=|Mt^8Ajf_o#z6Z`J7MEY^88QRf9+K-SliPLmPd3X@uljcjpa>T5#L2npLBnH-JlD* zer^D}UTptWzx9LbEx&Kexk=uC(Dip_?nvmVwi)`)8ZXa}us^2z>c9z`Hg9v?gzC8-C@uJa{o@-w|r6`=>B>USbrqv zC#`?;%Dzyav;-=ii{<$d=1=3tUfe&j1g~}^&u3z)KmUmOL+g5X@YN^rNuuKKw4)Cs z*0lV7FqzG7vFR4xTHOiqdJ+HV{CrP{!XrkP;O&bDKRsVvjtqdu{8B-F==w2l>I2$+ zTjqx^;TKWQ2Z!~eal4^6u}vE?Uupk#>=*zs#_mvSL;R!TYka9MylPko%?F5nI=%^h z{aWt!U7_qd*}rN37OD&a`(N(x`8m-~+aI>SAB@Uh2xXY9|LeitkR9R(llK@h^Ea>a zPo1p5U~7%khwwf1A=3 za_Wc5^$YvoIcFer;1__tCy}T1zj7G}Ve0ci^+A|AKsMGVe3K zJA>$_&yPVLhJm-zLNIvBo)12IOrfXSHc;o}_tRAW7JnQLGn-uCt~tpMo&T-B$AGSm z2UvPo5dW$3H7R}sc*VKEFZtg$rR6Ul9tO&O^P#doncsAL)29uGU-}E6(`7bZenbx* zRXV~;p7=+{ckGd|pf!0hJZnYjhvvWPr4MJcTp(-~yM9;ewcy3h;FYZ_^N*e%UETEI ze3&EHz9;uXbpMYUI24MNZJ!rT+M?bdl3R}YrG+1ntcCWcL!k5Y1Q|}BKf^7i!5BYhQ2AsjmlvL&cXzCVQ=3Czxf@&lZniI&-w6Sm zp}uncLiw-~J9s>CB}{B$??1+)u3^2=kMYIs^H?>zv5>K@yB*|=aEHY;?ESsr=?*v~4uhe`_Q>-utk0nFW)Kr< z4<`*-+n)SBp<+U8*@me ze=GIxTRQ|iX z`VcR^LGBmm{CLfAP;gA^-5-6?oIFEIhf1%qRN( z#@X#D9v5{6XK9o3SxnX6=lzv<@PM6%jK!_J8O3(9`f#lLVTP3JM3X~4CnV?*LVB+k63?R3htTL zj^vlJul<8h*z{*IuCFCH-5=+yR-?D+O2~ZgF{8{K|NDn|b-31ozt1aOz6z=CZ;P6G zo@V04QC=v{r!DdnXUK4UO5TcJg-l1ZL6h5^W#UP8tI@Z~Z3OaSN`6l87o2+1WH8`|^q+mS{DTdCsOVa26u0~u z(JyWz$WQi|)u_|UZwlpmSNWpf%_3A0cZVr|i1$Ky#b2buwiFPY@_(J_dc-aHBOO-q zh~O0ejQZ6`&F71NKaP^OJ+cAKbo(n+#DChr8%>`3Ss+jQpH%3FrVRcoje1kUeXu)daZu4IH&4icXbbJjrZ$L|S ze3Nec^nmbF`DxY52Nk3>Nu&1pG4)TMyBe8<{3jLbU1jRO?7smOoouNO1^J(ruogu^ zlN1N9Wa=Nh&Ko5g{3p$ti<$au68w;%{TFF@?{XQQMA^SJ-50${`zWpQv0>_;F~ zX1-AvpV)kVbVL1%G-ORFQ~%s}Ka}?8qqNlBScZ$J`g!$!HS+aukcRZUF2m{g+c)~5 zBMzSw#=mdCMijg8lN39QV(S0pzZywbyq0QwxWUwKQ{juajqjyiKdWRo9iO%T`60az z@1;7+O_}7mUw&jenwaxJDq7rO3M>8w&n0O2&t~c3F;`{w(e-=G+8a&WQYB5j zaa*RJu3ta94Jho@YpKhQIwpU|_d&?9@V8XQr9&Z$ziN398khV_DpKn+mEgkpn|i_< zT^;m7A^+#?erTX`OZ_W||A9e~Xkb7)KY($IQUrT%1JeT2gf4$M#i$bH6koa7(j9)Ak)_+}3AM|P0b3uM- z{Q)gse_OfNNH3<>F!leb*oS_5D5I!ng);pTO8@;yYmjEErwZ-Qp1l#J&8<;bKPA^< z(Ibfp!o8m|^%v!Mqa7NLrM`Ra%j~1=uW|E7tr}k{wEulkEaG-_K=th&%k(Ev_8Xty zg);n`q~ibl<^3bf&-+JfQRs;$g83k!@}u-|BdUAwQlWqI567TroA#)5SqYPWig^&q zefmKv+1H-gAN{0jP~H27QvKw6GXH7**F86*K>L?cU;n2voUV`i$)CXn=<`Al>gz!HlZ2XFBJMe)O-(`p(;WlcOqr} z)AjSga2IMYZkgXbQf2%}6o10R^=RqXM}qU8=I^k73u?dVg~Iv#qdW?krnN$%muWJ7 z5taXn_#pJthD%ko3#-*{0B3N&vm z$Ul8Pb}iU|HuZfV*gt9g_0nzV(~DM-Cyez+{m0)I=(nZf6SQ(Wa_Rm=q5gG!6Hr}b zdo<`u2Prupg!9w-%O>=0e7W@B^ChjHTP{J9&ODLUcO&}|9sjr7X4L$tOdv0&>>D>o zg61VuNcH(!%=k_mv>74Wd(wZ;r&Z$C0s}wiO3=if6$<$)#amF-y;5nq-YJ=WTE21f zPL%%Xk+do5iVT-f`|YRE+mL_fd(x;aDRTRS{0R?tqCM>&NzE?Zx!BkgH_ zLXHdNb6N$UTYDZTl;86E1nN4WBf`o(Wci`@rx!yd=+Bx`Y5j+TGW}vIKBs#Gp=jsF zQk~y~UqtyAcP$<1{Z&QdRkca}ss4-ln}Ig`P(@aq`Z4kF@h4G$s$zVk(kXQ3c+2_L zc>q)1z1JBOKByzo@1xJeg9m4!>hg{#WY82QUbr_K?Q5@wymU=uI2|9KF*)ei{EkRt z1V`kl{X=OCMxE@{P;8;KTwa);?gJ4jGgC!Zzs+Rg@pBMLo3Ek}A2kI~??4swEMvAz zK8ebY|EDXcvyUnY9Oo>M}eHHChQ$^i6E@I*+>pChGsUqc~Wla5Lq8n&vs4DVV zx`v7KswF6;mn!;ZxL$@!DE?(tCFt5N6|}UUpA4t#OMSv^RQ^T<6&LIv@+QLgJsWW! zeY~fJOdm%uafiYxq}HH@Mm>onI8~pIi(jHX-&E1?se5HOrtogpUn1Qo6%=r74-+4n z^AdefYKNY@BmDGya-UO;QhT)(@YDJ|B-LngV{3)@)!b_25Zy{4Zg~48vbX#zeHIzc zv~OhO%a;3vU(%4|FeZLKz8bx#`61QcMC`Ak{P!)YMw51aQ-}w2sYY|PKMVBJ@`E>3 zqi$s%rQ>@N`)Is*RWc$&s&B|bz{j~fD?P_Ej(kPAKLYep{wQ97T ze=V)L8N$RbOsPhW2DJ+Djc(QG*`sQOxPNgqy60Y{kU!%>HLAb*T%o*US~Yq<x`&ld{#Y5e25TD0O!zO+)0^bd_MkE=zdpD!xJ zpO2_R(G7Wm`WMmmdDfy^2hIujX?*>hT6E|^mcTz6Up=W7sT!UU#D~U>Z`7jUdYKCK zPt2-CH&1#~y|WH|S4tMdA5-(C-LzVi28n|D zkWhGJd@Wk;m>{S>8n>&cL$9Ob1^Q`R*|H8jbU7%94~-9Q$&YbSte}5re3xrWe5L!O zbsb23)A;GZbx3?|uR{BN9eRzrPT3=<4>9GRfB!nv)jv$&KaIz{u0!g6Ap-kpT>7^T z%~aa05D#D2fEJ|&O8=ctB8op_%xjeUNFtD@@znvZk$dNDg8HEGXM=l1{B_5nRIs>a(>Zx@cDYw zXY?Y4{0}xZps^`Vg7cG>9~{wu+MJ)K5RceikL)yO3;K(e?`710>Q>DX^aqV+UTZ*C zEzA_^uU*=JOdP}td=2vl%&Sv0%hkHZNExUBiehSjl%l6Z~g`;pZZn!ufJ&dC7G{L zmDBq|!`L9Ee*0(jsC#&A;lJ~nme28ggH}DPRH%RTx;LoiRk=c3sc$1v-cVfl@BE_m z*A&&GsqTe^|Mn{y-#fYyHL2$+lz+}Qpj%@z3jgh2v^=-B0o}fSwD8~lMdL&A8_~AT z2MYh~hcuq%{1zpLMif@eCi^#yM+|+7E|%;p6zum@eLvs!23<>CUHEUmrRCSou1BQ_ z4uyjGPRU1SzC|VRGYS>ex5=D0=qnymsA&GY)P93Br}QfPx1ZDe6Ehmojfd?D|Lx~A z?iAdB`ny*Z{M!#{e1Z8}wB9hkK#~8KHZ-D9J)#Q~<^Nib2J}8@Zh@lw$EVbz{fFBY z?Aakd|ETzMtayVCt{j)IsQw?%Z9u1-$4pgJ-?431AjiS;rp8@tmfbIisQbfx@0Ouw z2lJ*b$ZTc&fA>e2!aJv|Mf=oXYVW5a8BX8-uW;Rj=6xxe`p#cPjtie34|ecJtzTZ7 z`e%!-3>Q=9qs_IIC~;If!`=(u%IvG6`1f}5Mzv<`4bxsK%jD_zFHu|9qgnYXh6P_W znf(9t@k7d<9Szg$MlktpExb|8-O+}F(#ZX@gyQEPu0g$fjxk(Z*_O%gc-035JR4&e zUC>*O3;nN6+kgz~CK&!O(qr=P+PfaTZnfAjD~7y(rtdeEMyy3%5ep69Jtg^}<9{w{ z9cuf_)v$F1b#lH4!R{0F2Pk=>EqhCLHr z%JM_=|A}0OJYEI}_$Ac+K^SVOkIBJ?D&Gb&`6DcYkb7gAA$How)UW(I02N$HF&xyB zyuYLM8`bSZ!IP2=A4)qh^{YsN5i}yhf8T%5@KQ$1u+E*^}p7rN0qMEj1X8eX;aDa;HvnDpr$?p&8zfYD~ z<^VBIubA{5VlMlBi~fGiuK#N^@{5bHqWD_*HJ~f$D~uJz@4)MM@W`l6z)$NB8twp3 zT;7;;)M4{K>QaZMOLrJ6imyT2*J$#-AY(=6)7$2Hbbm&uv7+<0Uq}NgvyCuTl%K~{ z4QPtNUSmb)@3~X2(4rra#)|5<>U|Ab{42^hx-WbG@|)jsf6*%1c)Es!nZGu@UZN>2 zzu-}nUzMMgXlZz?aWf~s-=xmRyPcjR$*cXw3tq31>8GEMcC?)bABXi62U@b@uY33@ z8f0+Lc(J>OOrAcUChI;!cjm?$y9{2z)c;Fk9{gO=N8EQOTmQZMXXrz#BMR*coiPt~ zl=l;t6td-ecvhnJqGJO8Y5(#Q?cq!J0pc_Vw*2j$Rp`&bRO8r$%}o2}>COYVHAt-f zkS*`fa=-a^OuBJX5Xm3S|KpQARA>$rKfA(~ANIQ%nfA{#jxA)*&ocdakgqaae6l0? zeG1(_k*(^`wr<(RiuS9Cj`P6xn4Wn0G`765RvkL`=$x^l{f`f`hwl4FDUAQL6?I5- zE6-TbemU#YJjhu*Ry^oGHhSz!5wv7|Ny}^#3-IiLkt82bO|J@Di zP#bTl!ue#ovKBpy!V3LAJF^yP|Kb(m0nW837p@sAdVbJ(Rg2Va7Ay2mv*rA&dUR9a z{Lyc@--{}_tx!IGLM?i4RVwh0u0N;58kA*TCa{mj&zaPqfKBBB|7biwtEOdtc__f? z^HuxuD-_V_vBLOUx4hpN{PD4|qVwCZR|T5lUuN8K<1$(Q(faK}?xR;)rN)x(bD6kG z;yq-yuGF~Z@+>Akh`Wt8t-NELIn98H_irpl^=)n$``#MH#Ak<=AWgMWV~wHm_jlBM zjdZw;x?g@^Toq2{E4@D*-&urSitieijvK_(&jl4B=k$BV<`H&sT(}?mM;D>d7w#Dk z>Ni-93->GIJy+4+<)y|OJDSOHp?t4C*O9AUnX&$1`TI@E{!2ZtAj2N_jMHa|neuN} zUPXfrml;=$(30aq{*0YGYDQ(oF3!esT*#j{@EVfdeqgNsxVIb^%Il88=%`DX@vp-1 za$G2XDT+ra!yXvN6?Bo~Livm8SI|_=3gfrqOy#&xKGz$gE#J%khpsCRtEv0K86!=S zWJ*Y)P#K%@&G#K(3lChG^kyKKKOzBIKsY1wH2^r5hedc*6vm{DL%8+FG-RJq8 zeck;$+x>Sv?|R=g?0xpxXWw&V*$Xt3c2#`8(*i$j?*myv>JX(}6+h4aKi>cHW10O( z@_d@^&&BJ{@)MpH%eEPtGx2qC=lO+hC4Y_obKMD1H{%(%!iM}mg8qNs$bM(}<@pa} z5xsje{g-DJ^DQ@j`Rn)@Z(1O#+mv#vmH)q>|6f-wKg-wDJo>BtrlBSLxcQCbD*H#& z{pp)QXZQ*FPh^^IJ(>C{zdYx&o;H!I?9Whmyj$at?ct_s`J(Z!|e}hTrh`*GV){F$ug@;}#qTK^I_%d5XElQnJ9msy`uty2E@ZFTvd>%Tz7 zpYnLO_|m3`JJ)Twq>ujp#)j|5c!RPhviWY>Z2#k4@W;Ap$p5UbY5x&jcZ8 z{(njPFH0}rXU}>e<1Q=DZ&3HoHIrWO-@;qT|Lo7v{?k8XiQZ!#a7&cmZ=wAMgdgM8 z0-wu#{IuBmEno0gcWeID|D|JDqNc$kZtwxNe&g18{9a2%|6TuimfRn!&M*7YU+`zA zYs>HFkmvt&{WfN2iJgZ%`D=c@Kt8`=WSQ*zqCe-GRQ-<(e!;&yq@&_Lma4BwMV1(T z?HSj%1-rhtxTE~GcV)66JDM@`qyK%l*db^=H{_r0Qh(6@9~(I-m+uy)z?Xh!#_v%v zTr9~>;{LpUm&QBjWXh)*(P)ScCz(do^XJ# z%_xzjsr{+H>iN)zwR!w)?u~5prshn3HGIymJl#hAXaAAzzq8kei#^wE_$z?G{wNlzu>w7vzF~4?i``7X1dgKVd^g^X9Nw2#Suj;>M z;1Rx~VWo_lUd^n}x(6lvS$zYQ_~`x#oitqBQNHo7@l6jo#6LOsS~f-F&-y`?|4^rA z{0avHmHC&W`qT64aIvsp6X)C6gxOykuO8sH40$a(*!0i(K-K@G0VTZXWGMf0|F1^* zf1Nm7ym=svoAQ(0ACW%$_<)n;vYhXK>aXfQJbSpPX|{!1-;b^Dfd4+erCOyd_J=w% z|0@g>@!4(tD}TGq`}n{KZ)GOG{)}%`{t1za^J#hSW%iAAnErq14i{x*+c^gZw!X%L zv-!qTt7N(jO_}&XH~hr-4jJ5^_fym3^9yA2>hr2)r44`P2UUGTf`^O7m6_ax0ycl< z>MY*r&Rbdiqc_U_Q^jk4y2?*AZX*wT9HrE!+W+u;51$@XBfDOwrnIZ#J0@J@zgFnV z(=z_-PpIPYb`~Et^@FUk5&-L!VEwoXS7*n<{^9(0M+j zxV1d0dLq$Boj;2)*v(&f`AK&9rp8|LVW4d?#PIxK37Zzntm6Tc%=tzo(6SZNv!4Kb@bU zb2IthOF#cL{zl0>KdrgGTrJawS)XZd&+={0wUM_dcbDvR{ZD$FL1{eM=sYHGWeZs4PJ-^z@yW-;yazNYZgysBloOOG+_OD}BTb?mBT z1=sAe$xpi{^Xtmd{MlPe15xL zB!ATT(@O_7@)^$GWV%BxGVz)Z5AX-?>B@8~%zn$~wSTA8)OK zkEPD{-Z4t$b8q~VC2Y9KN&v`Cs!N&}1WDlBzEM+y5KBho$ffKCAx~Kj&I1pXSj@p7!=VQ{O=azWLjhD*n}| z=cmUM@$LDyl{~@YIl)tQ?%PIw;%Y5&*6KKCn((1s_Z4>)l3?pYv_xx92rT`qe0V?yxQV zuHg3aDy}UVf7JhHTAa)i%ifNG^r8^y`bOX1zv`VQcE}kEZ#S^*uY2W*FAk3dF)~4k zSG~WU{3}=d9x)acnv?h2(D#QW?efGmX=CBTxEu*jzrSI1VXnAz*ErCRX7f+Hl`F;{ z9S7D6*!<2Hb49c4aZtdq`Q7H`igV=SpsPNcpA&P%XYB%D#zQuLT2`)D@o7A)|Ch~g z_%>HG_6&d{+u8g}B6CGuemu0C#^(Rr*;Rbr!4l3Dg(=q`UDW>kxc2d)?%5ESZWYSR z|07wP*lKeK_=HVo+MD_oY+|LlvW5> zUI=FTkFAIoJHssar+B4gr|TbkB3`^bdN#P;Zprk2H#1)B({DDMTkWOvuloL-mSdNQ ziPga{M1#%WuV1{F7%&T(#IyOgosARSb!S8VST=v;gE+AbHyaX~vH5*hMvFU71Vd^6 zAf-Ol{Oym36DyNu!S{h|{$-_#ci-Ne1&xPzD)FlEZ8eAzFCPhpyJ>&kzoqKGvUsVe zetH(Xt63r8>HOyQh!me*V ztGlrI&BsQH_Fu!`wa+rizd*eo=DCfb7*e4NMZH@P{c5W5c|^?>=bQ?H!l9Fhoq9iC z(u7Fylg}*Jlu7*4`HTD*AtsEQ1rd)-m3YR10RUb55itt#mtPXEvr9_O<4mwXEoYwdzyrU&s)-@gyZ3m1o8nF+muh<`PzK0&4J zMeEmX!FLStPwRh{KSMN|69f%UCrJ8e|7bQ}ynAsbSZlET--(HF*SADSlrjLDMhenf&F3v&85(VNjL5 zl$oDH7EYr6TLj??o4;RCm>91Z-}aVGmHt()zZR)sVyly3(8<72>0fnxPjd|trvwCn z=0UbT>(VfBTa%fvY#Lji+|Ws^uW|&l@C8bK)%v{(oFQ&2Qs^sfqO_~(%YSJgR@t_L zm>bIcQS~cVpC(363xcoe-r1Jhq)&5z6q2ilnGa>wXtTMl<{cTm{C?p1px++Q|3>V|NX%bG4*>G+@HbbU!UwKR#&>f+skbJiXYR&NibvY##sn_C=7B|u=!UnauhE*ctGhY zHh=uR@#3bYL9i^3@YC_DUmh>6sheXW z{>5Ay@x}TMpz{4q>ivXW#s!Flj?=+<>{w?0wS6Xt+gw6n+GFCMuD`o|fH-+&C|n)q zpv0^8w@r%x@uqhu6l4?snbi8`;g9j+KF3fP%_;p;@1MJn*jmh8)dA*Ok^ZIEXIr+7 z7Z>zZ)aNnrPxo)m%kkoc$QiKUs?tAo{m&UNPTZ+C18!E>OZw^h*vF0&2Tz#+_RHA* zvmD2Xm%Gh?78Rub==^l)HdgHCI|EAU#wh)(&Mz}>j}d3rhk~I68$Wa1Kcd;YP&jYR z#=GG^qR!?}Xz(KApXT4ZbhP*bXMlTZXNjLaACWR>v=~zu@5hY6tFbSTkJ zjn8$8?;jN{F@`q}$@rtkM>ek|wjR|LDp#@j_hdSWyPr;ks-DA$f9m@#U*EJ8uirKT zgP}wp?Z5rz55n_fE#Y(MpZ9;N=4bfw7UI;lM$kB2T^YY>eSh>uacky8C>#}{w5#TC z^?6OP>yPemxe<9kJI(LiqM3N9qywBxW!H!M!HIj~C&GwJfA&9A{eO#77yCUif~l!W zeQK)u0?#!QT?#wFKiTb-`c&h)TQ3*q6i)=FIJWcfk?FrtVuj$6tPZIMI!Jc<`!7@HHxb{T>j;lH;-8*>k4CGDj;Y4bwubnp=Z_1D zZ@cclG6_b^CHiBj`S;%R#^R6Yj$rVZtgq?yeeats#Jc|7VfpGm^OtIVUM^}W%9@zK zuz)}BXI9OBdO#D=e^Y0Odqwoq`T5kPx%ldXG0fV`)-Nxr6f|eHf^O}V{A#NH<(Vx+ zlQ$-CXE3|}U&<>5c-{)~`V%~z-{PGu#Jg2JplBZ(uUW46wyAeFh%6-f==b}MRrFWl z>K<@-I6M9e=IUZ{V^hfMOZ?O8t39Hoc>I$EjBp#G><`uWwpDA2Wj1}GLLl$|rN_sX z^rm7>QFjO#LFV65YX0cBOH*9HmaVQ}Orko*)z1{(o;T6($K< z@VD1r8nu{gfEg&+(nCPSG=QF06 z`0GD&knbb&BRxLzu%&4A)DmXqcW2@Uul^`xTs8)SHtmRAO?CVx=06rzrRc%+17v=u z`?Fc!OTuBVW?k1dj`PU=={>L%+Y<-}k2QC|eVznD&zR>E|bDy&njn$J#*RX14!9KE=YL z>3X17MCwQPPnYQ1LLY4%c-79F>A%4Dfsl7jAGr1;etQ00_+POQwzm!VZcyr{`a`?X zZDIL#9Y`8M{L}B(9>*06mNxn@`!XB<-t(I9!deUF-!WtAJE6c|*K7-IUz7ONsQToc zDiV$!(ud6VZ2v(aSB1r6wZQTu@gGaQU;IR~d%~J&`tXm8_^0EazwoYLSE~FP2>u_QvSIpdP)Y_$)znesJ!nCOW(x1b;it@k2!o6`zqs8z5Wb1a!rWZt`7wkZ2Z+(FN6taO~B}t{ulxtUo*U#F*nRKF$ z?yu7iN`(iZrr>p*%nz~D_;U&0D^%{UXoKoluhEJ z^Y_CdS$Gitj9bN%`xE;6k3kC`3AWu7*VktRPv__BkAH<1VhOjp1KA%;p!f}|9}1d> zdqRL7sUMA>SCk|q+LmzBjuQUa6u!r*^}_1)&p2&cw*63PqEPWo)gDXXQxn$-k7Uod zJ*Qeo`3(^o0A|n%uvXQugD~8--$*Ph8X?vj0ryr^}#~Lcz)>T;luYlKyN;U+KY(g0Jlt z&JLC9e`^1yvGX#)-{2v4O-9!5mnpo?hFGCP@I5ZNDdBI5s`GPBNVKpo^$vHlbz_OY zl)~R#vqX@KMV!Y_f{&x{xpNi@!th(1(RnoqpF`ny-d?EqHp*=-&Ak!Rf1>|fA;0n_ z7idcGYLx$@K{JIl_4hd4`2Dg#KN`Q@ zG)%Bt^p?|pPWn%v@SNr}p`vv;H)uZT4@=5^(sP>NIr%LY=t}T3f4A-vg!-^ooZ3Os zAGH4@(O)<_uY^m~Ao>a@{|86@BP{;!1=q=o^j|Dx?|sW(xZUuAYmgH=?Z2(JzwrK7 z8TTlW*lB&b&xZ@9OF6I^Ypg%kQ+iLDY@{KYsX)1}I&i{;YuEL0OWtfXJ*?&wi6V^q2;+h+h`JL{MBk=}``-gH) zyFKZzwG_X>q)x)`!JoN1`$_zCekNQo6mrEH?$i+W_;f#~Cmiiut&)Fw{+qZ&Q~27q zg3~%j@xpxGz>+<~v$>cPZL<12?&^I75-&M}1KpB^89I+gr`$F#Ih46s!^Fg0x5i_6W{qu5vu$&{@9F1{LGObx!6-A zej1-~=qo=@T??kSCj7<}fBymZ`R-3^xuR%-7pV1-c^s^JHn*M?wS;-AL9jIZUtr|H0+b8LKR)qB4E zEFJIBb-YozTt@5kHc}Ot%6_tTN@s9Ao2N7{$FIgS;BtP``B^Q|Z2-@z4K+VQO!pBn2=WK&J z3ib_4!1NB;U#9QB^X3l~PER=u0|t01`BmfhemP3$mwg=8J`7j-R~=s)9%>2KBj&=E z|CIWu`kTT~;p@*_5E97qJ9_^(b?^uw$ff|Uu3D(%SM~p5jhk>eBNzG_5j-7VNr|oy zF(DdS^cuv(C#-KNR9u)3tJjnD4_%)`LuVnlCKvR_vi;|sa1&Pg9s}LB^O^Cly4g$^ zpE3{5>9PHvyDb-T9C9Hw^Uw29)%;#8aulZOAA_eS=SltrYJc;-%ul%Vq!5mcPLb>! zHNIzMHxU*XheKgH;ivoCw9Za=u{Rg|J`;XA|68|m0^k2QOnb+U&u5pK;PZPv%wNU! zuf4N@@9aMlRtsc)r^lye3wz;i)8jCEC)iNv;2jBBn#d9FZjm%$k{y(Vq5k^`cg=u!=`?s-F{o5N< z@xf&aV2csaPuEvnyO%Kh;Zd+ZN%YhHn_E~2*&Zk0=~Xg*>G`Ysh#tZ|yL>1+-A9U_ z_J3RJCBOXJTv&UK=%@1^TxBZk(>M-eeAxAkooONrsXhT|W#st+{eFmUKaGWus-sX6 z&gQS$X)J`sABFwHNPP78*M8GY_+)k*(k8L_4{tXUK3zWpoqn!oj-QnHj)JB`9+>PU z*AH6XyHaBzV^0Cx{%R@VOR4$o%CAm>Z{vKG{L}gZXBr7dPacCI#bkWb^?iB6L@4z? z3-i5`nEK+D8wkC|=7O6sTc2&Mk?`}xX)v=T-@m2nw)>pN^=e6q~ zJmHUl;dP>qo`2pIbP-M;Is?wd?ELLmt0%lZmJ7!{i9Y)JyI1cHZ(bS!4^FcC*LbbI z5GBip!w*P(>HcldG!P<9kHbt$QeRr1>#YugXTLKrG=k_8sQJ;oP)E4xbrfdyBKwoH zKG(1M!ga$_5KwK!tgln|*23EM$KdK_A7=hSJoN;lZO1`vFVRQWx7iW{!OZXsObuk~ z8)B#_#1`j6<6mrj!6~{zLd7YV8BLzgXHxyQ^@5h*-r)pPhq3G1J4j1dyX80tDMX(d zHNPwlQWreF9fg9$grDyJTg$Ws+lsT0c65LgKh6L2wT4jiqyT=j7{Sbs|2RG2AN&uT zf|n}os@M0(ewspA)+w0vPoiX}uW!C7O@vJ!j)KQ*qK~d$#pb3$TF^20F|@CQr^n~O zg)M}=UrxdKuOpTGs{Q}wcne{$?`f#JzDQ|T)z?+;7k~YeB0r&oKa*2ke^>NS6LPj4 zgBdf}{9Zqs2$}w;ALH->QKh1B`PfaLEIt@t;Y<{(7)jTfDhgr(!_jG^sQv1Ni zbH~8C9pR_*uY0wQ?;mp--i~6&zul~Yk25@`(*JaP{x%i-T+?H4^Eu8P*7y368eXI1EHqyfrL?Qox1nzdZ*}Mxob)93S9E;tPoME~rXGWU?(FzJ zeSXU?C=?*7|5#>y2S>l=t%b8N!;{Uw`1E}~>hUq~3S{%|8ufr5JncAWJ|p~eea{Uj z=lxz5LRqiz%J@{{57_pcpYZ4`WRGX_e{Ze+5V68z04bK6rgk(+kd~c$9cWqCtz4C!PEUw z_~ZV2snB z^?Cb0e_vIz^!dT>9^MV-4;&}OCs6Za+|c9v&P{bNY%v=@{ni0~!K|;)^9tMEdRr#{ zbI4b~Jhr`KSt{@UxdLKy$n#@0ir?32Bfn)s9rT#X#;>K;0Wm&o{Ij%GeEWr8 z;CwTJR|D1f|4okP6SlvBfS%;}F3rEiCYrCRse^+_1Ru+(;=BJ&=Y6&qp<5N1zhWu< zJJwF)U0;5Mfp6IO=i`!iZ{seQ95Y(VKaD?oaTu?i`V|geW#e1lTgp#=*9B7o{$b)@ zT^Y>hPp^lShGhLl>&KbX_@W|XEDanZ;WH`y6R!8VnI+X=RmN|V2pulwa0XTs zslor>zcvI_=l7SFJ8>(wW}ue_8(+eA;_{Of_Tj6g{6wK@{@*F=qQbtbknP{>um!gu zJOlgJc9QV4zNy|W-6!p<%^Jmn$b5llS;IeIOez)iD+<2D^4Bx=!*V7)&9T<{xfkPDuWAocL3FhYZ&cNj>*!&(2;aop`MSV`Q`SV+Zb2T5+ack`= zslVv>wavo0!sZ#6JB#iAXPY=KxHcVM?`HeYYaYj~dy$TV-mv{&(2V1*SEggUJv+W# zZR5BJpVIOAR5pLl^i|x8H|c2d7yc7rt2mpZ={WZqo4-C`71wYl9c_EF`7do+#pRTx zqh$b_KW#t~7kWD#b5q&zKhRI&1|C+#f1Sl4bkvJt z^WTfk;5M#I$Lv#V{`_?roX)0ntoeOj>OXpX%{!36X(;sf_GI(-AGn8`pPY{Bi`e{I zd+y;*ElpZmo2hcfqC@K-+Hr`IQK?(~NP$7-SCF1f#<*QdXG z4uHsBAE9h+5V?L*>;JXy20-&hwQzeidHzZJU*0ePuItx=#x}P952gcQj(08e{V|Q{ z->>ID_^hypRjiTh^!?l1uz|4lU@a_Il%>S0)@SvOfiSAJ7D5J}mF)EXQP{0PFlS&b zSe|9;zoD>KE9@Fi+4^;M4}#{uYQV6L==TBD^-+tIK_I@af&LHJ`p*i3z_wd09Q9-C zU;A+oOq^T`o7LI+Q$7uX(^G0;WL>coUo7?fzR`^wXg*;YI&>!Mdo@s9-`NKYfjFC5 zSUrYaUtOmmkkqagJayMH^Z$GL5NPdD3u}_u`ni9Hz>&qZFxr)^|JtS@V6m(g1~}hm z>W}P@2R_ZGVW~b_|B=X}@czP7oNBdc^#e@=MPj??+F?&s#fUSR~oM zD5ci_iS6R>RE#B>b@;`^Z`!jIgC6w7P0xNvc1ueC#gbV3e$*TXrZq@*3(Ef8G!`w^ zn_;)$ddY4^*+*Pjf-7`;;=zSqnf7nrC!pb0UHrAarDUh|Z_tTB)1TdOlgSs!ZbJEg z<{gcb=XAqF&Cg7GT}l+1emBM(wNH}Wn8FuUMdH0XMmVW+oMiW**1y+<#dz1h3;uJj zmWjVUXgs2ED{Q(&U9!{TGq>?#{7}>xrzy_3{r~=p=Kt_`9L8&C;20M+zTLV-c&WA{ zc5PfB;ghKKx9f~ZY#!YSbsv9_?479iWGxq=b#@0do^*nV&p5aUW3)Qr$y?P-e00iK zoVrFG`%WVBD;=McZUl}oY>yrEVsT_PFlwd&zD{>AOE^Ax58UhgFtK zB)b!Zk9LZ{eU64W^=xr-PJJaI@uqh^EA!?yyx1{u0o6N;6 zcQx@!JGTF<4|DOPn-*Rf$o3!QF&A@mG*M^ND<;2FA7A_+tAU%l$o|}AYX9=IwJ%yb z*TDJFTO_dGYA77CDL)!m~i$2)Hq#DjY+)VJ4 ze|HC8{J6gw4m%M41(g56i+pgGP8Ey`A^rtQ|Goo0xW}zZ@%{j||BlUlvE*Y z@zegVi{3b@;0;V!M)n73{keU7aIw`}Xw`)6ziGM;Za(rBes*B{-|FLywntw>)Khze=MjzAL{bT3zIHC0ku|S{!OCn(QCcX>Ek0fZlEcxU(%@al}Xn<@om}z_-_cA zKQk$OZx1hA+4&)~EojBWKOE|bE*Zs8Fp@sC z9~)oV*%=d-o`F}j&zX43%})4r!zsu%BKCU9zhR0ac6KR%#P6<3{i^%(r{6f@uG9i> zSV!*vvZ?Fac3&s-sV{))^(7Ks4OQol3Oh$MN9RCF>`Sn%@RKam0JpCt$~&XH5R!ONi$#=fjX!F3kA+TRP&cX2)RJ5psW?L&f)U zgo5Am7)-Qc^H=LT;#%EfkbCy2{mHgB38-GSL3O@=qzJ$L8#UCXC7PQKR#O=-!p5}M@0{Fo;7p~`${d0Q% zFk?F6r`@^mQ;qOjQu&WW!29k;;Atba|4x$tBc>gJJ(g_$v+n|$Tt5PHeaQNb_J8#T zhYvO!0>4>KO#Ro?0Y6_l1Rw5_{Wbde&ebu1%k&O|=jmJtPx~J}9`L&UVVGC-NV4lv z`P(uC@J8}Ms7zw>*E=fmx9uP-y~XA~>7mfK^B|0fApFKu{w_uXhTlF2)>qm5?utj- z?oSSY#aA}Jr^4>3un%d=&hO@Oz}?plz$B6I)A1*LQ1BNWfP>%J{7=s#w(55PvP0PQ zy-|qh(B}YL3t{umIF2~6+W|-(#IEn}Cx{~*4}iG;v6O#JD*vy$IHGIk{m^0woBwIJ zBkBh4hxj9G{(%vW*m3%PNX=mLhfhPi?3@ior`Y-JZ|Q`VclN=AU&KE>KNuQ1VZfPv z;Q5K|->AJ}?~v-OZ}HLzBU{9&l)} zX$P!5j8gpd)cjjJ$Q38P+XII7?CVbtbyuAJ-yZ0iz@GoN`nh6!y z3`lce^ABop#bvz|{A=0#zplBWRg*nn`I+$hQ1eH>7H-&a;2yYS$-e%M(&n%%Bpr4h z0cQMOiHh}M@NQ^-p73W<*FURmZa8KBZdf?$n1rYKC;jJ!ds248&tq)d)qHw#XfS{g(ypE!Ii?X?}e#cl61~g3DLg{4TTHQR7S&j5lGgZ%Qs%;7rrCu;-eU zU=y7KJ_h)(F6w@pStYq_#I@cR3Ca(f(HA`iD zs_UyQwH_GkunVSKB>ZVq{>PMgpt;p9NXsGofmHp+bn(RQlXk(l0QUNE)!1IB(`h9n zoFwN1)2R46UGc=ixSjB|TcV_o=8w(x#GAo8!NQ2_|Iz%p)t-1Tb0?J7u=&@G?uGZB zEr&B}*!*j@d12zA9Z(-h`04%0*)zN_edP|YT*>D5z2Jq%Z|nfOmF)F**L`N_HDMW? zde%pZFNunOyT?#GtF;5*0-OK%prL5?D-&wf$o?rEzuKIkc+GqVs5c__5A^zfQsZ7Y zJTx9oHL&?NbsdJY2WP^XF68_-9e--4VVKxI6UHnj{IjY0+l?EB@26yf*FnNxO0Dl7 zEbN6|N8(^Wf0BPX{)2CZ;kW1va11B>^!{YxjbZ2?oB{UbY<>+ZZ+wxT0i)esO8KSl z-#R(>#z?(5@H<5K>HhnD$r}y#r9+n@Hh)Z-H@;ey4x>h#l>F22`#aVOK^PClFe z$;00Gd-_rs@{7&id!7&06>o=J!z9T+y}zihuvaMTM~ex6ES3NATpyg!EFGTuypr(r z{qOg?<~ZtSEX1bwlkAyP{~a3Yi_>+sL*ha<|9iPFc5b#E0^Cn2^{GBz96ZYx6U?@Q z(_J=yy81{gdz1lv3dsHdy}!_9js=#5#)3fuTi;nTKUAB$4Sqak>vPfa!_DKjf$@KA zeH-2VFnIMgC|X!9>8JM}CMS%*sDbJ5%#*Fp&d36fna9BG4QzdpMSf_zWh*!jJk89{ zfkDGDscb83w_xvo@H!)KQQS7T|AOpq(EBImOD%AcQ?1Sy!Mnm=9aEYH@ zAKsoZ9KWsH0ymuF;)%W-O_|yx#+@Ay6T-f@0ez3rV)(hZbU$(yCef)4x#6~z) z&z>JnYxrUIgpH8Wk&I7zew;N_F}~JsghTFRe~aE9`&i+JU%zjJ3mdGJ`)8{97w+hZ zv)0dmU>|cSf3vCl4!UB2VRz<%_MLgm{6=T{;=pGcpi3~(PtUIb`M&sX`36{+!k%AE z-umK&|gx~Mk>#tT7KA5Yw9>&+Q_b>a+GQ$N0Q(#ySyMG;WEb!*y=@9vJu9RQ8 z{*Al);0bQsU)P6)T0ZD!y$+rlvh_tx^1p*)sTi@mjKKSVHI>q}DET#NbQu!^~ zY=&(fPJ*Ifw*E0Idt=Aa@F#MU80EVU{KKlMOrDhmzOi6&lGuZK6aP!7P zHxuCCauQ!XmESJSEO6h;Ku9`4t{=2Mzt$F*{3#G3#?6uHPwTt8ei-hqUjhCH+4r|T z3cHWOZu*$qU(@^d8jAJ#zs4(}sxw=k*&=h)xjG)!ni75V^;e_F0*|bk01=vGe9`(! zjfY`xSPl)n+4@cd48ztT%fUUI=%e@lKSU41fzitWZjtj(YN&cXFEDo)PD@`7v$q&Z z_1C2O!+%F_?3gwNQUffc{KZo9@4#05(8@j#sur^6FY(Dxbh{M~`)=h+c#c|s&AvVq zV=lzQ&*SX8V&qeZbxy+}nI877MYEu$k-+($6QR z^&E<0i(|nyud#A|Q0))vF6P+y;t0r@!mj`6P%k{G9|JdfvGrx9dEs=g7QnXS z6FhOik%eFrM)Va>>z9%mPu$-p0_LZ(^_{8n#47_Lz@stINAKT19jwqF9|2Lf$@xZF zU)LBfw0jf*ZT;B#`n>OlLmG{McZia0A?U#FE zMBi}e5&T%nFa7*y!EH}$yDA*+FCzMNsr;Uf?~ew*Mncj&YYAUK%}+hAd7$UvIdJs~ z`}t6fh9~xJm;+C?v7gU8>g$QmP3FS6ibqU+qbGZ!&*ZtV!-%afpuiL7T%HToYuifo zH>B!cHM2jqI6fTCJG1rgjPk(pM>C;1j;((~p$FPq%mQ6UqTiUBU$eG(;D+Bb!L%>Y zuTMSS+0x*F)-x5~&%8v=x9U^*Jug$}KQ{}8b!6+$w;F&Kr~5$}&(`lh&;wg5z8{mt zvGwar@xWNu8L;wUj+9?o|B|U5*vEYasNH%f*=hYr*&gV-X$CY|!qz|Iq6c<7H3Rqq z`po?6w(E~W?+$~t7px@zIaL2#y6TSK8-gLLGC{Imrp9MVGY>o?3xS0**!o|8aL2+P zA)sYN^czz7Z!yCIujGfoJYefzwA%x})rCOj0;0bY)j#F;ta1BbFEE%Lm0#2I z?%4Cc$zVB}t-sqlchvtd8OEP(BlQQJUt4c$boOh*btqQ1R4OoW@BM87fB zACVW_v0Kzc$iLWA+5f8h7oTohVRnWSSo@Rs=>5^U5pLLQ;dqEX!j5ljz8gA~j)zAT zhb4VvPX;-b^!k+HfXU|yZ)RO4$M7>{hg0~eWB*_1||EZniivG*| z!CH&0zu}uJ#@6}6XvP1${(pX5jT%4A-@4+ka(}3IW9x5Z?}qywM#IayKbZQvJ-0-U z8hdE!PV!4XU(i-O-`&iQfH#FJBs`tpfqPuB+u)J#BeI-1tuT6yu4m;xuT2Vw_DOG<1D_4}Y@`Gdc zY<&ZrT`|)Bw)+0E7`Cc9u(Q*RhKh^?<_ zsSCCk=?#-#9AxJ2ZCh9Dw9XrxS`vL`RQ}Y4xMFgSH{9$%^qEol>+-oDmQNfAYEDES zeSckU>w@l{UNEwHxx`QBFK(F&s%`Rug)u~5DfR!g>FZr^@J=ttpL|ck)A}ygxnP3k zP_WNxP})`Vm%OGQ7M-yM(?{g~n$~xy(iyMMcZcoSY<-(8UGV8ycj#cu*0)5{1^aDw zhgQN}iQj_C-`7ztc>k3n?QDJDGMsVpau-+>MD$fs{byI^ zjJGbiz}52yB>!~&`rLHJ{G%>lFrKZ?-N^+z^>&4oi`e=)HSLFkF7|=B4n!ZlKe5@= z8TTJ`gnn9Vef2TUIH;8qc#dc5^T~6@HZmu$GG^<`f8&fF=Q}~#>w0GXruA{b#syCB z@?v*s{x_rM$HZ%Wu`JRY+#1OJDXrh-z7u}b0w}+_O!80Xx7NZLFH8c(-^1AY&oyzz zxwZfiqwYv}ORD}pW1X>A5AIEGI;**Hd9~LHzz#$SO!~`ewFM4D1Cbr{b#dS4*K0m zel4i{2DI;sri$-(b#f&7>HF&vXD4j+*bcTTzmHDqAFhb6iHpbs+qfAWT)erXmK$BmN*sWm* z@U7YTf85;(FLt(p@``=T{MRVXr?u~G13!DP_2(>i!m33!@IAYZng3~9`e4W7T_HJ# zt?y2lBi{Wr5MJ(&m+f`{AL`ZAh2;kVU;;Mt>FN`BSz!8*21xa-Uy z@aRSK4WatOEyW3=bO%FVBX)jGLi=F(_%5IkPW03JSF46NqQlt!usMRQe_OKR{P3av zuo8*>Osc<|xjN$V;Qmn5nCKru^~W1U{4IX;2XW^YDLz{N)h`zKva%CwYsS`BREFp! zT7vmNw!Q&2j<`t23UbP`CI7TO!=a8C+0_aR-riL5tLAsg5=U(0Z3Usth(3ENzcWnb{Fi<9hXsQUgC?_$K*>3zXr>0k8qaKuZweIaEx(PvNP z&&$ve|Jl>9K6pFeRO}GPDET=W)2zs z+4^S2Bc?tyho4n9l>Dmsb1y=C-o*mO)_+pkRj;p0J6Yh|HU^Mo%+@zk4RM1}FBlfX z)|cNOv9D(@xO{)F_e$kJZWV+zs7QT3f$Vvf@`w}F|D zdrAK3`~}7Wx^y#zGhNyG${ql6VW#kU0bAd%YCz4UrZB!MTi;V-#7hTE;nnkx5k^*s zzt+zH@3b(17hy!76O}(3&KxJ}>VT;&Ti>^84v%;13TB7c`s&>j=kLS1LceEwB!0TS zh4z4}Co8^hD`V?(SpwLwr7K)1tCjGyzD}ek6HvXdm7l8Z{yM==FvE zE)J_twTCuK*!rHB^~U5!&0vcGTVIbOax6V-0FCq6`g&E%al{7$FpOgBtJC9fkY+p3 zKYCTtPwQ*sz~O*C?cnL#50agppKU99VaTB-F#BFl$xiQoZx2(P|Mk^}SxeaZig(J< zJyIVQ^=0d;IxWW|>-1r(3(-fff89RH@%RaSNM69!r}J+wY&EwLL@r_LOKdO4;SXCw z3P<$O_m9oT%F$9o4=P?}G3z^Nx*W^e>cPY3S0p>Fuloi$Rt?aD$amF}on9YsLwezX zk3YFcGosIu8XrS$%Wy$=9q?$*)>qwDj=TMJVEAUXz62XNdd}5>9UF;0`u;I$z8u5S zb)fZLwm#2aW_UjL8#n!(siZ%L(${;H45LnJ!qfC6lAX?<)@d1XC7PhE*n$85{trDq zJ{8GuRIMhQ?abB}STDnQt+YV<$9rb}G6gg2{_!(+c^}bdOzGP{M26FwYQW6yY<-1O z6#OO{F!b#%roP%4GIZ>%0VbK3B|E)8aAuDTJB`qQtQew?zP}j}SSdf9b69ryk{18} z_+#ZNuh&z%waN^m&(?4kXR-CKt#rV=G<8Tm7$fo1`&VThWSDeD9ZqEs{iW3WGulCh zor~3B$5^)hX>(*apg|o@^kD1XVs3^d234FxJGQ>a3kEkoRr|R*i{1dVkHdl?-=`YX+A#R7vsE`Ax0viFsWrxxSBkNOpREO&s8WWv3d0 z%l>F){*Etqz@r}e z)ZkF+I|)zgI~P_dzt(P-Oc&Yx=@Z-&cMo{ZJswW<>r&%OXQw^d&i>9NUXPOe)B5AT z+vDKZ-?^62Z2e`w>@n}%ckbAoixQsJ?_}hFbK3skb_^i;EvWU`c*CA(bnG#gpicB9 zQTp12*<;lDIxa8#FZvYvWyN*et)6Us_NNs3Ki6^QkwhQ;e5dM-!oT%b?)$U1l73oW zm-nW)X3u?Y&_ff+PVWz$`C^Bych+(_#fv37{e17JuRXRh{K#28-XYoP`mb=b$0yA` za$i1QknFTR;XivEqxgPS@@BR^F|ks9XYv-=fZv+T`6+OZDgLm%%dObJ)?aqb4(~mv z;?}NZ>p%J14)xl<=QP(4{q+8SiNek)?0y+UKmB~t)yy6{c)jO#-Fzd(NAC}tj5o#F z+c&sjLy5jvs{Xwf+2O*H*IZ6pw!Xf5?a;AZCFehwtuOt69iHh_$t|#D>zmtPhs|Ru zxsFTO`Z)J;x$Ii9EaFZJDZgr*>ij>Zizz<&c!j&znyr6wcRQRn>m_$LJ(AfUkHYLw zxbl))`ZH6q)A?N%X@{L3z2pkNotNzN^Xr)1c4(*did&_@)?ZgzDL?u1UzPr#^$&a0 z1JyQO;I`fDF8QBL<^TROTimMnZ+P8cqFrYEw`BbfE6?{A9{i*9oR?`24KdVCZPx5XdZZgb@u+3_{3vBhgo zZgY3SNPNcB^{2}bThwlHhl@Q+;-k-3g?4-`@94E$mOe>?IsQKsn<(z@^SK+v-6VZ< zd@C>5V29{yoZ$|3e6O3^;`;N~xTQPU@vZq`gZ3w{aV@P#eDwLOHvJU&skz1(S64{< zbbJTq+Tv*2>s(+0JH8%|Ud!v-#mlVCTQTE1wax^WT*~2krI7gO`~Oi(Y;dv7CGMt- z#8*Jg4|Nx9P`2U{mpPRk-}wR?R9|?B>-3^f(oe^i^4b`b*q< zUlJdEJ~E@tYx#d&mdFabuMo((RYQOE_ZBk|Ga|IRJ5L93WT&anxJuM^du&9~Yp_IC=omM_TpU^>3p zaTWig>#n1!=(+}gqoN|+ap~@E1!mZwBBFv~qat=UCW=T%DJm8gc4MJ}3ilkr0=ol~ zFt7s)@tbeGcb?}tYwgRwv+m{m&fX_x?#v#}rPbUJxBeZ__;Knspxbi~zsgwjc`)N| z_q_m6&M)IX_Q!q4OatN6qcVO()n=KW^$qJ72--i(`0rhC-xMwo_?9x>e`~$$^Q`a8 zjRwws`iv0e0=)g#s;r^A&JO-hjiv1KZ2Lp<0^sxQ5`O5HMA`AfO#T%-3jofxl<%+{ zZ@=HjL0ez;XUp7u%uFCLHkYQFlz z-GW1Wl^O1P*gpU)e;(pJG;rUEE&*`m)gj)(6Zdu59RL@@5A&~2i9YuJvz$Ev(9-!Z z@2(^I*ykHe#y4=c9TMcmuXk%}==^0Zf8AE}X)@z0@ti*#4c*Vbzc&lb&#vkLFg9&J zA9#6_>^M8VCbbO!*QEV?t9l|kuE6A{R%8GulQR_4QoT zz*Qu~$@QgPvx2VoR`EZ+TKv<#|33e&HPav5vUc%)<8j}I!~PIWck#;eaNnX6{xInL zE@sk{{=c-D= zL!6f2^XG}%me8tT37?@Q`kpcGCuuv`4~l!`^Xjc|U%w50FlS~yKPn0L<*e|7jEVXD zR9^J4^~3`ax`5T^ZDZD#m5wH5dT-Lv=zsAZBqWtps^P6YLju$fHbM62?*d3q8D+BJ2 zo9zecbMyEJ6Wp(r<|o`An#Uiic`o~Y*1tDLIG&ludyN3z_)a^znsR=Tdl&EZpy#<_im6r||dFasTekzHs?>3cuI| z_YbP@1t0w-eB#|_vi@bC{|T4)0f}A0LtES*uj~gg-InnDF5Lg^L>;FP=O8!!-L_bO zWKldHrGWeQ*!n`LNfPf7iTj5J3hfU_;zxJJ{SU)^!9OC2A9STm=3}2P*Gu+=>VhPG zX%g;l5Nf--lO%r2Uh(;zkIeX�l%qm4$r2N4P(ESsfQK&nm>>5T5_>@fPqtaR5Ky zl9{Z1$xQr*rwjeFZva1CZ?KsEOnuqspL~FGn8_=&$Ngi4y$eo3$|WaQ4| z3v6(|X{0ZxY?;YtOvL@RYV}}`IsYE4?h9LN zCh{sFqVE+G-@PXF+^R?exxOdA%^_n$1RpU)^eHg$yQ^mbif1DDXUVwl$}}G^_fFvB z*WkXLlYF4jHGz+)JtJ#B>s!9X2L??{;P(&2eOq7pK=Szn{+{M^zK0)&{A<_pt!eaOz zyG7qKCO^k~uH|+pw3F*Q+|?YWp7rES?wHEHpN(J32*Ll{laJac`jVOXrR^4P7(6C| zzw~0g?DOpSo3X(g5=KPur&{B_=x5%bayWuFA1?Y7neo@6>H`;^NAO8=ao^LP^<31x zR{zOQp80(y{HGawIqt+Otj2vCwalU2btk^WANO5}@rIUUo`1Xz_qhal!|icAe_-or znV*f{e!*{go#*E&;<{PyPGG3;6A%5FQ^{q#{aa%eRuS{Vaj$lK5-cC3k~#!`g3l4cIjW4pY_FB)NzTQ zo&^6pzp%d4er9m8R+~5c=lzT9_}e2Ke;^!>jKX~id0rqbu;mxEtdsqJcKn%UdO>`? zEkEb^DcNy0etS-ML0Y*j@7!1;JFdWtztOk7Kv}pq!`KP;wQueS_eZ(%Bh|(F1nl!? zeG}@qGed6&=QoJ+E9(a}Ggy|U!sq?-enQrN!PpG?tyJM{+TecII4_7BW6Heh2>ZL5O+-QThPr&mm2xW6L5ufRms|E&MPdsFz-Taj2kR5Y=$X(KiJ5% zbi;j5HhIFiTZ;U8U);B1l_%(5R^$_3l*;i>}IsE+&8#+ian$wThG1@5~N;t4x_o4CcV z*UJ7so1ZSi^QnEKnmDzMxUVY76F%iMar`LU_js2lJU!RMxlI#&7n$)n->;r?_TDIW z{2Bc=fe8C*Zr595S^L=Wr>ANPKEc(T)v>B& zaNqGrPp}zQ&yBUkeS2a&!E|grx9exK?EkYqhs$-G(&ZJw|6c!P=a=GA6R_G*#*q@- z_xYv?6r3&NmQBWePp^Bxw%R+~@#VNrk$S+Q>vy<5YNGEjlb>;lo^a9fF4y74Ls|RT z{QTwZ3EbejT=HeyH~Uj9XLv6yxV0IcpV}i$U|ZiJZp|#*7qiC%(zX_H&4IWtEZqaL zN-DWQvAFMQiU%AmuH-VVmdM)A`pk+wAfvI8>pV^LvGubGPI|!T50zZ9mFOc(erCJZ zarq+><&M7#0Vd#LRmjcjjr$IcH38c`h1|0DebM~X;XGj6hGI_H1o!Rt_5kVfVs3FV z?pu~5JfHojn6q)meY^I0z%Zrb+-uF47b zt+6tJQ7S9B@Qt`H?YleZ=j`B4)vl5G+4<$Ywg>Fpxr5_}ioQKees*>7fL>)gxM9~G z$Ue`;FE`2qCO+E1NwR;-j+Zd;d$_NT3;q)!cYQFfHii|gQ@A<5C1QM-_m@i>j3M7B zg&W%!_YFGh4u1<*a;BxYZ)ll2JlMFBOI5~wd96HP)18&v`vTneLeB%z8&+~!A-M0; zm0GUdc+X&)M|k|&ZZ(DulF?k<1KgKzz!)w&jplA^;=Z^PcPKl)n5#_}eHWSii!{?6 z+)pp&tnQtZ^&cBQz02-k^mZ|)H(2zs?`Jvp(H-pCr*L1Ca9^5Gf57`>3I{^~ zoN@mE;ri^chIVrEd$olzRF%7O`x9~hoFHTP{MePtT88`eh5B!4En%FRljy(B_(wOp zf$94&&a5ZyfA8WBu{Pmc!ZzGLa-=(SO9jBN(J99ls)MfF%&(tsU z)U4xH#Xb#^xBkR`l0d5tnw(N^+^_Uk0{iqdxuUMP|3-xyXpOhx!oIAQ#fOc5k??$a z+%zjL`=9#lZ2Z4Ic7q-%R-9{B+<(K;9Xe7gZsdobvhQd8xyBxFagQ~pwH^0IEve(; zULOgPcm5i8Py$K&>O!o|aDV;{2{b&d3o+5b{lkRk+t2?{;0n%(em4FNDQ@8LRe`g* ze?r#&bxi)ZIphXmdabw_nxdbruUdZF4Rk$QaaS^Mzg=4oNYQG|J;}rU7rxbTzU?xC zc)o@oWuPl!zGY!IUz){3im(y;|ik^Q$yCqiGDW!rLSGVd`xP{ z;;y)VmbV)iZ%GZ&U4r{>O>l#^mr_I8{r(~AAJ%UH?r>~kT1a5Cnr!^D{_lnLoSR)q zr+vrpTQ#%H)ccTz2PsqKNl$$jzlKlzjq z>^f7^scAIsFZ*i**UTSx8flCBT^G8-TjigfjyLDa;&Y#w|Ep45Aw%nDrx^{$WykZF z@jv6JD_rXPvy<(oyZ?Otzt49&KX(2j9{E^P1(8_+@EmX2v$s~DNCsDEo&cp{k$r~6&$<#D9aG;q4?kPWo-Vh z?d%FKdi^LHd=U31&UOWlwLi)f58?jGDp%;P{EbBg}{LBp8?=ajIuFRfOK5pZ8S^pL?^IywCH=#boymF&)xc|rIdalpm)HCwN z|6g|_IBmJ7{D=bXPmMH!%8)(fA#u3hRH*O%ZFO1sg+$TM#y{$=3yj=RR=%!_=wHg@ z|6W~J*z>Bad_^ekAE)IClKQgp>pr;uaF`n;_(;o5f^q*!?KLX|5?SDGHG=#~j zFUrHK4aNLs&Tov>jevH3QU28k_g~K!>Mv;iEk6}4`q}tDTHylvs(;I?+vEN>`(0p( z*WdE4SMJFE|9z&u^X_^V*pczKyu+U+H2z=yy26)L3Q`T>8CBWyt<3lzAngBoZL5*% zKUr)D&YY@r+b-O{_mLsoPf(Q_*2aka!>s@HJzSv4%S`&)MD)iq^WP6}fv*l`()rS2 z+2`5#w-Nf!V}_a3s~Go>-0lKh7Mn>s{8K+>9h3i0j<`aHx#rRdH^le9vhSbRp;pIP z+-p-NFaGD|8^Wq#_R{f5xPNq>Avh%3ORwhP{`oD=u>W+B)UI}w%=e7(tF;sS6+zPO z|GdA8^?&1CV47mEw0VH&zs|(}+)x+LvkjJxh!*3|`gp^DSq{3L7FlUWxm5Ty%!#zC)xYF=Bj^nen~xw=)cxJw#fr zhWn_s3w+!+MB1hu?o(}7#|1We$&KGKWka}~k|0fW!F`MD4dKqg1nE@^-1j`)89pQ~ zk~Zezz7AWR;mW2((uZ!iPvNpN?0mdPy6VwwS^U}fS=TuORY;chIq^+)oQ>b1{dJt{ zr*OIPoAKBHl7`KZCaU7T;&z5`VcQ&OYD={2``Pt*MPFyA(9Ds(8ISw6jc|q_lN{;3 z@5jW?Gx0ko)JGZ5K4Jg|ymF-a+i~A+GiP`#*(`k$j{6Q+Im1e`&C*rnxUVG88LoS8mIjB2 zzKhKG+cni0rjOn%t+T^@ukY7!eNW6PlXrf_O*eqt(FM|d6!#5VZUD}y1=7pOxNrM& zC)n;-Bn_3|zT{g@5N2E?b($mkrZVx%uy%%R6N{uJj=0aOqca>@QY2ka_f^*aZ2WR> z3BTX}N|ozd?QH<3AMcWmT8;ZsW*C5>&2H(?QMm8n9w*3)I3q3kyi)f6UorEi?p`Oj zE*x(ai~H)HISJ2aoslZl-jaQujo+bnPS7X+jP!A;=v&IqF_| zeluW$0xh~+Xz0} z8tKrrxG%}k2}U^ANVnA=m3=;*$w`_7o6?Vaai5J)Uq<@pt+dNz+-LE}5k5=a zN#|1B=VI#w2YbJh`dNxT_WfSxBb*>0^_{dQ!F^AJ-_{m2A1RZ!f3KdT4`#)WrP>;} z&ooURM%{fZO__}Qeynzc^EE%EQ+;q>bD<-AfBRFqa|-S=KJ5r`I=`eohi=N^!}{7k za)hq%OX}_?`jVOPXA)e;C3P<=lXrgh*h3#)r@xgxtk;))KN~;iaDC{s^Q|<%1@}Fg zDAWfU+Lo-4;J$sM9HC-BTjCUg`zG&lgu?8$BxDQj)7#+)7c<+EsZF0{?PGmso9a1_ z^h;&yPKo!Ave#c$wAP2qCx1%&T)=&YJLtpail5S|k3GfjXU5+;d!he{DoJQuAv^w& znLjVO3GaVAuSynbioR%O{8h|y1g@1D89W8|m1j7DtEL+9e}MZ^N7Ql3?QY54zbu#P z!K$Hc$kO$=Z|ZA3@L$q~Xy3wpy*@j@PA6TGa1r-y|Lp+RymU!n!x5RE^(6`ZsA0Nf zq#f=%36Ai0sxEn!j{E-q{->Uwp2*Elg?v3&cu|?CFT{N>PV2#_cgkePZrn#sI>6$E zCZz8++@~fSuSqf?nFn#7i_kwSicN^5@rKOLj=#g&jmTL-@!rlPs2}cA?%@D|!OoB?7K=v-<>Kp*#KtLj1WO*8WLXAjx`=b8D( zQON;bwRjN^58VGn!vWmedy|QFqMv8xpXuEkpj)^%dDjK^N5l&G(aW1e&cgj;7CFGy zByVEijQe|Z7Uo}#cIEQ!&zw-K3odrHB(+gb=402FnfG^Pg>*X@P;I?|EM?~MClu>(xk?L-cG z;ePE4bzDNNO8LM0KLzIg;x}`2A#a=ui93h;eRu1E>lPRCc0KMNyU-rmPXjXYZl0|D z?E14T%N~pt0r^^r`#YA{L(4HBT~6ZuH{b1n`~lKN2lsb3a)7ZmVPr(3_pDX%3 znEam-WDnH`V@NTN`@4;_hwV>eh~hZh-?`8p_B-_^N}F+iQ`dU#@gkG*Gqc707waGN zSqHSPa^(GV+#jo?3-jM_M6(UPZrf*lYKv%|NRv0VRvFY z(No0zOU&${e0@CG7>WBYbZFo#*E^KUdp^0{N*zd;-GjUh!2Je$bfDdu9>nJW?ynH) ze^up;Ay=(%|C;G`P<(Ici_Lc6*Eoi#9l`x()DEPQvE+E^2ifPNneo5s ziyd5#A4~dsiTOd(~z z#rGGp{_dgmoFvM-{NM90cKp9~(1B$IgUIzCy0ZRd*MHMc9T-gzwT>WxHdeIWX{C>svYfsK1d`M191Pcp>}XjV>US-i~A#m{xR)6o7jKF z{nq2^IlZR=a`%6x@3mp+%Xs2;8~1P0)q$Q?!%3k%?w@hk780|PNL4BBpIK@PKI@W5 zL~q=mq+|yVH5Zc0E~0-Av;HXy_365LFC-^4aQ|n2JBS*%kmQ!({wq_2`U~^9^78I@ z{kzl>ZJ4)h46!K2{Z_Twu&RCx@o4TYi!ZzX-JfI&zt^UaryE7T0vId&`&YHp7S0r= zkoF$9|5Sx7SY1mYU*2AoeLw4;Ut!g&8I;vRdd%+u;6w z-EE=8Vi`&DkmFy~z_s1juUuaJ%ldjP2x+yL%n!i*ixjmX&}1=*^~L>bH`u_rx>mWOIAm-xOy9!Q5(+_-&c2eeC?lb+LiH zPOHg)5Ztd)U;`@>SCdl>S7e_rWaj@ZQXAN~ZZ(;+3-@n)WCP!htR|N}itndq$N%6* z4cz0vgmQWH{%fObz_Rsvk{K%cJ(&3G71=;g=k+A*zUZII z%zrHn^_=V7(Q?Os(GV>-wmpj+euw+JCu)Jo=`1p*9QSX0Z!Nq)W+Tx!iTk0!8e+mX zlAV7Jiv7#@+X?*x^EZ;^^KpMu9~;pwRB79DM%Q?EjDaW(Gm?%crbnlWAO{MYxZCM;4} zLF|v>eibz>u(uKBmr=N1YmPP8q-`gLGjYFhiZwVa-%dK5#{C-Q*6_P(J5h4O{hmU8 zwfViB6x87UbM0&(OJ@g}KM(i6x$%-4I$&OT>?^!}=Dnkuuwh|7Y01X@)ekgb&aQmo z7KHotyIBjr-|Z&hL*)2{z zi;BqENYVd{|L^;qIw)DgkD?+1t8ss7J8S5Fu!sb`YLw-N1vCGj>TC_KJ__Hjg8LtB zf5kO@ODmUG-*~uxJmuNt7Gy_InGxWCp|Q+WUDR?>SX?ynte1)B8`kcO{o<)wmCtn590oJzpOwj>I8Y&DAo^V^I!eBP`|q-yIfxV@vqey zkm|aFjMb6juhW2+-FA?I*|=ZL*a{5Wm6C_Yaeuk16~r5tlJmE5zejH?cp6?xDqE^$ z{lkub$Guk2u)9>Qe{YEuSB`p=Cc z8lZi4Hz|+C{p~+mLeSqcWX*Qmf2!FM+Nzh4jwQH1)Y=N3bu1(Ip5XrOGp!(CeHq!F zjK}}l7AtsBT}Gx*-0xraihH?pMftz)S75JyS;lEV>9l=hz+K!wV}%BMI=qj#1mXS@ zCoN&CFClhmxIeqf625gO?G+l7x$ewq7FuJC&`OU z-1qL51r)5iO6F_fKD9>{aC+-ia{KpwS^U}YYouxk`OmJB#Y(uZ)YB5GG_R5LDBNc_ z)Dm`fyGD|PcQ}d951Ida`BdTHaCMl~=@i-3ANMIOSBK4sr%3cH+^4h20s`CIB>GJ` zvi7s%GyaSPsJh%F<38fPDX%Ty#^{>_nyO@)V!tvnwL9+n&|e+AW|ff_-EiNhQ5JA@!X0wtA?^#AVgdGZ?vTJz(O1aKzq9sO zfI;OQa)aW&kh>O8qi~m8RTO;+%=~*z!4d`s-X(2ciuK3Y@i*UI9j@0BQqu+Z?G93h zL^we*N&?CrxlaS54+E>@MqHcKx_tVGccVo)NP=+&BD& zIdt9fj9eUs`z|S4K*fh=WM@Cz_ua$-xDLt1yvqX+Jr`^Oxf^r<85<8dE1O9#wN?h>a|{Qj?f#X9h9_Fdw4xu?vR%v}Gx z9%(K-KlYLY_Yr-n%>E}UL8u=({3UTU#eLfQ%)$85OLAEs_f0uv4%eQ&Bt#GQ-4^oW zQ0rHue=poOOt`--z4Q^8d0f0dnti^#;k_=*J@Sa`=^BmtK3SVX(eXDVyEE=PVrvee zC2xr7_kI6-{=etH08x z>~m7yfIlCka!?PGyf=JLPPpN|x=pZO*4aq zqrQ>5pR#4g+40wRxfxtr^^F+r#eEJHX7IH38+kPo_q}^$2G+_=S_#uODQt{y|ng#oG_#%wSvlpXAAUy#2lzX0YDx zC&}-Ix8G5yujwB1lN_~I^+;?%ODTHOUq8m2izVJxxrxl%^i2EE(Oksj*8+v`J=wtJ9Pd8KO;?;&K7T`XO zNv3eBR~s6diu;BonL^Z%Hk4}Pz8zak;riS*G~@v8+kV#+R_ty=Uu+e9gqi=HUz$Si z<8A2snYd5)lL>5kq)4?#h(0!c`G!J$%4S8nW+Cot?<4fTZd>|t0`8m9QD~o0TUz~Q zuPi=n{C3PVh2qGzv~(@*b6+Ub|LonC)<)sJz1vJ-`Lwolc^}bd!K`ol_L_kH%67Dg z`^U%3k1mZS;9u2_o*IMucDFW#zE9fG9l|>_{x?3@`QNdPDO3u_xvRKuLMK!Bq28Vb z&%k{zVojmSraj%^kNYkTH-&rd?P*6}+&4SP1Wtx3(W4%sk7veTo2@3WHeQM53pLRH z*M4?>Nk4A_&Wn{O7lQkmYfRu^z7l;)a9=kqQ!qNKL{ARIedTVZQ1nQNs@USb*~0j# z{j4O{HzmddMyo5+CM(?cDb)ndcT%QNF1Rmcoe8w*p-kJmi$3A^nE&jL+8#6k-C@eK zWk2pqx@7`Cl9lNJU))!%XbPhbDAQ^U-1nosDR>`Jrgi#w{QM;*@Mg6N%~BS9?Ed+9 ze-o&H5LKH0 zS$zK>JHMQ7Fo7Xas5N0vf~4o_|5Y-fd|{wXygRZr@*WapC_0=)Gak?EW88qfBB!xtPi;>OrX~{HEL6W z`*IJMz$rC#+TpwS{t|Y6*}u;iLJc%%=O?0%T_5T zjG^B>P1J6LWEolUi9*ZZQ6jbHL5W9VzIMO*pdK7(ds7}!sX z{yr}HrZVwM_cejiY%O{q4fib=Ak6Ovv}m_yxX-w&F+`5mrrSz!-?n+iK-Or}{AIXr ze2y{9*{w|%R*F70exq}ZVbmUNN_24FYoY$9Tdg+TQh@t93F9NlN{8ys5PgNr`uPx7oUM>MY#%uAec4r|Z&=M{(b+QN}Pg zUzY|e<36_{W0?0qSFUf9aJ)`9e$Ej0{TBMC;hQea*@XM9-IaiQr5+ucEBe^+H|K{0 z_SET7dGBvf^fCq)6Mbs5SM;&@sp4-8?JV_a&u@EV^9MV>ET1Kek0JWhIuVcG;GRA%Pij84Jfj-sTg8Nn-5bDS6H=us0qK}QA)5FWq3?<7#tXh2n_Br*K>XgR+e1z*)HO!xafAZ8xIZF5teO?;Vh}xCnzO(>i$WoQig%faJx|i_(nAbHbuS!V*&vu(oyRM>-&CfA{U;m~FExCvLJo`ytWRnS(w)n2Urwb2`i(ZFEy1|YsoDqz#hKAlZlaIP zPw5XMaLP6l)_2^uMk0a6gJ!fK6!*;w7V`Us8J(7g`+i1BVAE4G8c~V+UM5RG!N8ne z9gX`!GKKMFZcc;kao@XjMv&BEPCuIBzM(gbK=_S_MjpU@Nl%QRqKgIP9YtRpvp+Mq zZv>{i1yzc~ebqw$j8C(m^A6&^{jn0rrWSO0jOa^d)<5&X5(v3yLDw4LzB6Nupu=NJ zdP+<5vH2O3Zv-!ut*Am4?i(arAJn(9qDm6cr_1<;UowJnu%ZrwabKTbM!+Rn$@TRU z>VH1pXGK4B!F^MC33MP<)W!_=T@N;bpJ~=qxxMIP^K1VxMsUx|hPt=MeP8R0;IY3AEqEus zUrd47zo`E-1Sbz$s{BU0zRCI)co;#=1X~&zhx>Z=GlF&bw)9+k(Z{au4}|_1zs{Bx zIpV&uJfZ(?*;1vsxG!&~5j4HFrGKA`?^kB?^8_`5u1a=vv1h3lL(}!;|W%D2F8)qlfSC!b)``WnAcZ3oAh_k0DBSl|4v%hXX zPx$;Sdn&z*`$h}>W53Lv);_>}r*;~`+7t(2{>Ocn4;jM2Tn8GViu?B7GlUhT4z%5E z(Z}ZJhmVFZ>W%|_{b#qhelqKy#LNgR+B;JBK-?GNY6O=J9O<6rxNm(o;r9c7N1A&Y z_jQRjgq^<}>F)!$Z)c_q&=#t<>=>y#7@ZJ#O z_c_tMHn^`*)d)6UcA|fCaG#H}5%hWQB-i&>sPCut)R~UngZmcsH-tQ07y9sHf3g3W z{mYEGhH#^!3-v0)eIV3_d>G_HGpcak_ydLzG}DE;Dd4^jcMXO2m$=ZW({bOd4~9@7 zb)k25u}%Bvj(8y?@mW&lTI}ieLS;&X*a?U0xo&d&#Ac2bf^K8 zPW7UrCgZ-7X$H`3ix+*Ehx;ma8o>8TFG}X)z6_!M%P)ISCHmA^26y{g`H>0aFD zqhko$JA2c)dbn@Ci6LZ1d((}haoye^QG_l zioR$3fA6n5@kSqli+yQOgy>`E7aNHIc)s(c594v4Pe%hdqT@%a28%xS_Xp!}16XbD zM+XkTeG`THkYfh;QT=Z!zLiV=OW%>FvXzyPlP@uy|cxR1Z957|Zj^u)_b+58#J>|Y*? zF@WL20%&px?%SSf00UA2=n)=|-_%@vnAbg!PWQ*-carGC#H>KtB?|ZXUegD^je&F& zFZ$T{jTY)dzT6y07r5a*?_>IKXKtWe-&J1dKl_f<^BC@%5Mcm+Jv!2#F1Sy%t5ARP zaz{E{g8Mq8>qA@PPBhOA_x0GU50b!6G{8snvGMabpbs&To#;U)+!wG^sQ+o&iALAp z@w51#4?Q<^qE%CI-(fuiFuBr+_BO|TOKkOF!~7t*KD8eDU~({sTIt|E#c4wQ%7;Nz z-x>FHo}mv-H9_>A4(?kg)Q5ceC5T>D5XT>zpI0jM;ZkTYT|5H!MZOjCZ)PwJHNt(K zuk_%AO$c4z4v$})sXqK16GF$g#eKVd_2GDW2)$*9`&xc) zpgtjlc0Pv3@6TExKiY8g#Q@xAc0?cQtvIUQ9``w%)q_D-IGWQ2_ua15gCReJ5~Z*E ziS1+dpO4z=!!2u`x~StmPbGb!z5-7VeZYMyUg!a7;^@FtxbM6W|Bi=w+OZ$*3lQSJ z%ogPp|nd4?yJ9{2O+0J>0AZexA&qR z^g9$vt#9GJf}_IsuMDLlmf*fG!TPYi3($R?aGy1=597N5b*{sGzP7~jGq3mR2E-$ehJ*D2d$#R=$1>kZ-wA9oD@bUAHaQvLVeJk zx5KEF5$-#tqYrtFVRTIm?sGKPgQGN@UcHa|4u|W3-j{H?tO)nrPtb$2lFoE_t>|Od zhm>J@5U<~v9xldx3k&q1WkhGXza01N5$c21<#(o^zr2w3p8~W0-1$rodXUa^!7bbe z!u^}A2X~=nS8-nlXFVv}--R}p;yzOsJ#abLh4#BG`l6Zj{f>hk+}P8F?%9g_Y-Z_! zt9n;D@(k{iWavSAyRP)qUEKF*ogQos?n?Kaz>WW*<>0>0Lj6yL#}Tws1@0R%Sor?>2zvG^?%SKK2czw} z(S$18H!VZ>|J%FKz>~Od-3eWYukA*QGjN|~wNRh&Z#Sxa7WX|ppbP$YyHU5PxGz{! zm_Oqp>70$Y&&fs)PS1{{Ud6cYX_Ow^D~hCc$8lfJ{<^SyP)yJK1I=2J47GP+~0E|QWy5x^q}|SabM+lU8s%jLHi!TeQ#ZL;Zt)Iy%L1` zUM<#zYg2pBy-~PtVu>!aJJW-zWZ*vgt3vx9_Ml!lV*ChmesuM%4!qdVlRB@(eQT|C z!Ru8|xjrjDU1;CB7cJU_`);?>1uN21uFp(e7rIsTq%%HM$mU0Of0mo63xSEf=!6Bh z&qt_ly8TEmdVLM<3pk|%w>_fif*jnJ^IQjv#zxa+A$a_Tw$}yN6iv0a;J#0lI?%vH z(@+aMes_ib{V_Y5wrRqB$KrIsQ!j>APs4qx^K@ZqNDQ@1$9)G=bl~I97G zzs>v5T^YEqV|N{By|WMf_x-`__)}k~1NYwbq0NrCug5wan5h#>gO}pI)x&i_cFNFG- zirxCroH*RK;E@h2@7<49kHLNO8nhwoP(SJ)kNXzr=s?ZKe$=83?px)l10^Q?>9}dQ zZ^RdE&^z0Y{(OV`x`*jNwqJj_`DtCQ1FK*6r`A(&UyTs|zo+|C-B{fBO)B_e2gvm~ zz0`(=+yOMa8GpXvlo0<`)dT3SS-5YZ@csFH2GCuPabJS){ejB{P~Tm6eijcB^2dK5 zwUOXHhdDxh)DZ*a`aY&=!&?18v{ft~zd>c%&~N-8x~v8Foh;XexQT;kW`EpQo~#W+ zH3!knRk-g-l{So8IEYR!!F_7ZI^d!7-;F`qaP!k(y0kCu zo0F&w;l^<^=LznsUZySF9}-6w#p1qwq1s?^c`#jj68CA%&<1DyII56}`&NC@hRR!U zG^jQ1TWYTZ+iZqV+d;U`#!ASK`9o-RSKQa!QyW@KhsgEK9ia_B9uJ{2VsKxOL>szJ z86wx0)I%G}&kUgv>A3I2er<5G##4Wkwnc>IDrv_X67Fd7qq`+RO{!I@`6Y4BP+er_tl`1Bt}<3{7YyZPEMrb9g4 z@d5X}JE;w|A@MYh$9>OEX@T#lc&gx!`+RG(V9vXEdh{gjyW2_|`r8kuT{`1F&q^)G zycka}9>aZ(_q5=6eLVd(2=|5c*M<}OhEv@;xUcg9;rY?p;q03pz5}`Z|P7iaB3Vu@4Mo@6N|OL#cCuCKY+(CDNo4nz>#!}v*?Rr&fgot zv>=_1puVZNPj9vswj4zr+;HDlOD#B;HHu0s za9^KTE%1LhivHS*`&LcV5}uDAO_MxDAA5bmQmD`NcHAghH3#=49nk`ZNu%k53f%YM zqZV|$F`9n)iu-y#*Me0gqv=!$?mO~J6HdF1q1!BR-v+_IX~Gzqvl;iP`)Pq?&KP>v zPV}+y^LeHT8{3Sb%`ESkb z{Qe5{+1_`bLepC$GCzBM`_M=e+GkFohsWT)x89l%Qapt|Ylr)8HEO`=peeNfAl%ni zsE;?MU3~5 zKyv5MpaFRN42Ah)Y3&@U{T7ekG$PcOGMr1(pX0t`Z`9%I@VV414ENdoQ3th@xpc}a z+?RDy9X=?{mFrV{s}9`AxpeV6JbrFMeq7|{(bau%->YRBaCp%?di56WyPB#FF1P2= zx(B##?m2bX*LglQ>x26;ud2hUzVqq)M%-tgp$?Jv=TZFtJbu6TsKZ{J`Ly{y?wjJK z0nh);r#&KYpG_Yj{viwKwo2UheZzrJyHF$AFjG@Df3eR;PuZppKW;3bO|QlFv*XKp zusVG1vp{Zq8Z*^l+pYz4e*@nB`$B!d;K@m}Z700_$4xch@%|(_`6%B0gA>)E*Sv*v zR6X9l9l`35Y`2j5b;J92Ur%+o6TVPx|MsEkV5PN)mbv2XTl`EN4o57aUYqdt`R*zW z4IgArmzEmJ`d1Ivlx? zOb5OYN5BuXjm+NZaTeO&#J;Z%$)6~Fw{9-!L9QVCAsRkPB7Sku! z@c5ZKsY54)6l!LT`-XQ_hc}WGsetjoO9Bufuv(=rJLU8ePJD<;V7g9*D4_ zb24$?-utSscy}7LyoLMP)T@H$u{7Fc3Ld|5eKiPuA>UWjT@424rpsM_llrN_O0#sT zkd6Dw$Et!~pLDtLGux^PElbno&YympR3R)aU2c9Z->V8LD}>{6;cnHm-0L4{Csd(vM+WWC3D3{qd#W(3GDEmO7xyK6R)xeT8B~&w`_wpV3aL5Z`Vo1ryx&CsY+8O_%;BKiU0ZWKSVK9hb_@&!{w^e}^uWdwuoyPE}A{ zxRjo=#eM6qsY0J!OXZF~z3VD)ML53l0`3d^qXN}8m(tr7xNoVNDja#Slrl$8!Es_ zGii<+?%Q=!1@4kes(c0a&3vE&=@&BP=4ZW`DwL~a$z31*_E3d39kXarFdjdvp{nqt zTbA7M*DFs2a@J-E`yaghXEv+Aot;^7D?YHw%fl`+ox%>NLAu7-(Fh}nA z9}=wsn%#5c{=TBOKxltrj@$VD9x|Tz2r{ewJ{j3ViF3XXdKi%|H!1h;;-0LfL zW-7w{`MI>mQ?dWq`K!QG$iLRPa{Hh3SApKaxilsi@BglYRiKv7rNM3R_P5Vc0qd!` za`(4yFDS#sdT}s6c_nGP(JGq^k-%^It}f z`{M1_oT38XhApFWj^p|BV52gGsq_a}-;#uobWa5EGFQ5ikJ}BqS68K|w;n0Escc zK*7K+LNPzK2nf9Q`~0|a&il;%d!7q>X4b5|cFY`u0Gg@7wtq}_P2PG)0FCx$$A3=u zG<6PE?b-mhVwZ@NV`z9SIzZ~9)E zyyQS2>K_iLYw)?J1L>hk_WX2iYVd~(1F3-t`~1xF*Wd&91k$;Y^7-u%eII`QXAS<= zr$9Q*i#H;uKRXTHePfWU|Cc?# zw6z-i3)dh4|B26EuLKR=?@|zLpTeGBk2DQ_a6u5-UovG(36W&k(0tX@fA$IA$5yY_ z;I-QY(>>Yj`E47k!S9(KOl#+}?T-Wv-eyX$Ab%;gf8HPsexG?TeYT8k|EaA{$fMrt zWcBOlfA$IS*LYTgPq`k9=J!s>_FwT{Fq$7WS@4kb+^~jzJkQ=ABTWtdK)1s*Z7zF$ z=e0C=lOBf!^$GF(Iz+4Ua4ML3sk7(zW9w65SLHyTJ04}uZ-bWxuXg+}eXy48Ul$(K z;0@9b(^G}){b~Q;I=MMx5jFj|Yx(&R+yC)Db>6;B2-S*U z+wY^R!5fkg>SM#^zolz5cu7bIjX%P+|HL8SK~{ zc?0cjX~f*0c~TfI z=ez$2qn7dP`3);p=MUD0QAr(pf7Z(QVOo%^KVcJleqWZCl9U}z)W3wie;xX%^X@al zX^;+kez%R)`4cwbv@2!rpY>FA-pM_j&fLmAUm-#2{EVV-8hna9Kl?y+zT!qW9rTMm zKNF8q@@~RLdclG{zqXr8$tKB0+Oxy3f9o%-Pu)yz!FxUl7wB6te;ktGQ;9o5XP2<& zMiprBYZ={=lC^GT6_xV*a z`iU)lAJK<7zey=Acv5tPZqQ=ypR30s0$N+?;V?OWir>Gytf$U@m>5BO6tL%~*-4#W zGbV!0KFr=fM^knF@$v{tHQ4j(^6(xp_u5E3R_( zf0=myj*%DS#YPW0>)-pk;`wPxACmcNw#xd)+5S1BvIT!{P$d17z@A^Nx;npfP9)mj zdF9M~@~37q{TsoyzqLaP+56Cuw3Rt~em`Oo`q3qDID3hl4;xZQ&9 zs2W9WblB@ZR_7jh{CYE8YQtXta}D=M$8THc+Er}(Pu;#srfyw9OTJG3hd*5bf7%PS#xbE-P%+B{T>An&MzbC66tQUn1;n|`Zs?ezdwss z<0FcqXs8pXY~ABs7oaoU8Ym6 zUzdOO3Hi_2LXAJ=7A?q+iv8D!&C8Li_r*}Wf>z`tMnEvhoIoRHv?z?K! zH2*fD_;I5lB~_^_sLptof9oUMzY87iku}+}{-2u2rg2YE{5bW!8h_T}7+qM--oFHm z7QFJZW3*rddwz~G{)?RHMmx=9`!9*vT{7HmJN-M5jnA8&YP{LQV|3O!Hh(OxROK^u zkI{;)?DH4otH$fTI7XqEy?>QaMdV}EX1a1w+Q0b=-*H8g!F9b zK|fV2`nP{V{<`{AmA6_HODF$fub=YpB4Rbwg_@PI_um85c#;!K2QOyZH$R+`J2eh; zZWUXf%qh+%yObR0nR{0M@FBFX@PI1+ttJ+|A3U&BRdzo#j=t@~Uf+?wRQV#8I69jv z|M&NW_;pfH<9F|lqbC=#?Z4}jN^A}0(+8vF`5iI8y!xI>PR7lrhBL^&zb~}^ZJ;W@ zr8A<$H>v>h)vQIocYs$9o%|lgw-IRFr{%ca-RB}mW0bMyvZl9+pJ~kMiNrpz+ z(bZ$dG3}eaQk8FgGoEf9z_!mZRF(gzc7mGNu|K#g|v1od;QiVsqopg@#y{AdFNI5D2)?T8p6i!m-({wdvJn2vt!#|x=xkP z{cr-kKkZQ2+rPM&s`7;;3ABwTd;MLaQ^=N##q@!zeEr4tC#4pWily!} zZMFRUD6zh&%2nZ&$0wrin-ok`;cL$%pz%-plPbLZz(n-^Y~pVfe!E{HJ>bE%|IhRk zvaN6lUFpfT|FCTR3*RQv*jTpz*mb&yTs`YWYxI1W>klC+{Hq}+sp@Jr{$spU`1c)7 z(j*Huep;2P@Yg&}(kJ0;`z;O5kmIT==+n{7?>7tmpJk5}+2;>!sMi`f{>A>IL!vV8 zuW^!YE@S)eC9jqFBQs8-@!1>`75+}P?DyT+_8$yX;n$g-qSu4i_Ai{2K%TqJqaCFk zo7PXvF9k18ld->TY04J1{UxWA`7@nP(U<+${<~B*zdjvK(LY6O{O7+^=0g^oqGM~> z_+PX^gndnwoF;`N=o;57N!dl@wd zmanh)e6BmL%wIK2rh}8%>wE2rGC$TXS@ymw8{exHRrr(X$@Iu?w*3liW&Bi-OkZAS z+n?V#iR{d^qsyJx_Sel)=G!+U)5&+)>#yXf%=6t(Q?p#Q{Y8<=e8%F_==(`gla%?w zZ^<-vEZhDIcVzQFdYZny#kSvn{YlbAcE5SgUU~c=UjObVm3Z3$r)lMSw*3u5mH9)@ zar>9sD)ZiYDRkF0_WBR+rp&J@IF0%zP1*Sv=9)r#m9g!=)cPcOU1mpQi2VP+ z3MF1IB!xD-WZU0cNtvIVmqIm5+3WAoLz%CCmqOd$l-vJU^#10+Dka__A_aY4rjxre zU$iup+WcnQzu`wB`KhvuCLd?pzvP+{zui8SzW5`zUt4rPd8VxrKle=v{bkFxf5S#4 zKBzv0<_wbCFTTGt;cFq$9PLZJ-=zOL-$H%(W`Z(rrZ{<7^~U6Mh1?b}Q@zV80d zzX2$vv+kR(%CBA6u8M@Y$ZGT@GfAo(y zgT7z7{Oxt3GiD!sXv~i9c`rr&dY3cQFJErI82_3YN_^nGGqk#QLeu_;f&(etzZ2KRrRpR64ou!Yuv)4bUZw@Kc*hS4f`Z4jd=#nCT z^uSqq)|mZ%0zp;%Hzfv)SYWTA4e_*1-Z!yY1 z-^ZOc^9C6`Q`Wzw#jX#?-X-UA7iZ9EqvZCB*T2C}k&kxDphl)_`x~z)@<*~WsNy2F z{n}NE{J2jUbYB|V{vHjA{7mgkdTbPX{jE(EdGF4dv|*xLzl;4>(IiE_YIr79oWQo< zdV?aL?~qAf*s<;R-L1&e1DSO7Dz^Qd(-ry01)1pk()yK(e9uzQ=iC-(Vm6R61dO+7~g>)Gr7 z;kY6%xsKbv=yN&=sB%O3f7V6?e$C8tg7;g+{Ig`U0zcLI91VEMw*P&S0{IUw1%(KM{L@ZU|)Kf64^~KDq1yZJEo)f7h=H ze6Z0)I>AzIzo+Q^RWo%(zSHcBR40&a|Iyg1WY92~{a$SQ2ToJqBW*9r`rFy|8_4i8 zF7zT*p=|pX9#)WjKlviHd(XC?m+kMf+Kcq{T(S?KpO@~iHVsq2r>ISp+4D^(jw-{>q_xv+0sDw*9?2 zDe&{RX44#%f~NHm`(Lk#3jCwIZ1npyR~IPoDo?VhTPAz`Ny0rc+c1L8GZ@KS|85r= z$aD8>nz>DGzxe!?nKqJDvcEqqn{9vC=LXUxKAT?iVz2)f9R+@X-z6H5z+V3|rV4yv z_9c3wgl+%5yBA2E_Ffw2(vNw5FIF`Wi=s=ku7qv>X1xZ|&-@a#TgSFvA*g|*$m}Bt zZ2OO%Y9zfD<%B+Xj7wrPH^ zMfHI-I~&Mb=Nwx0fo=b(PO|-}%ApVDu<;Wb)<`;z&qcq#l@!}ZtgLcT`-{|Li2d~q z)M8a9=K9Z{eV4qhj--`_Z2L!zZy@3Ob7{MtiA}#3>(3{N4aDa`E_K-~x8F$=KQ`1g zkeGIP)K}$={P!aM+%uq&tTfA`lN#9TALVe2xXSuJEQYh~e{-##bQ_;1_&%5z|5Iz~ zNv=a4oi&zi|3XOvDLa-&8}_j6x5#QB=Nj^8wUlkY>GcL;s*z9K+sMD~CiY*S6^qEk z>qls%k~wqzN0}CrbH-6LtYLN2xUDGudJ|MnlBD^R%xBx5@u;4B*pN@#A7|U&vR?x! zKb=n-&Dr)BE@>c*kMe0^H@W@d@6XQMQcP0UMN_vzHh(58xI<0`N6{rG+4je@t|y!x zrNJxN_W!l2C#F*=y__ny-;@{T-~Rg7lkV=6o*2ot-{f^Ysmh|%YB1aW2{xxmDeps7 zJIM8?SU+1<){z-=C|&nO&OZl5>%aG09hqf9>5Wh9^DFJ~m;8}kFLfR*w_nWvujba1 z;~Ov2a~^X0kBRUfx~HDJ3%yK(EZO#t-JeW6SNPEE%X0lDw%@qtUs4x$nHEl!e;-eb z|H=b(q=WHg`nnH${YQ`eO9tg#rs3!0_KVN2Xa9O~Wc?MIbBk^NW|Mj{*7*uuWW%<< zD(@u8mfhc7-=-TA|K{0s; ze@Vc&tMo(#+kVHSzvL0QN*z|P?Z2@qfxMN)zr9lA`F-*F_k}v*w(u$)vz~4LVV^n@ z9C(%Xxy!cSDYuTi%(+S{2NX7~k9hqDTKy$Qhg_q5TD@%=7vm?>@-KmY*XR&8w*A(s ziDaPc{xE2HL6#`wtvvlI1+kUsm zIx^z%H7fnhUjK#Vb)>FU0o@qPw!gsV1Znkd7o8BwUVjVcT2iM|KwpQm?eBf5mQ0;o zKpoXi{==WJK9^8kONMVRpehb*`*kPR5yeXdG}Dm1{$F<0k>Ym+)Fg>*fBVXKGJ1eF zov?~+zsI0jap zRY%-Y3hCWUw*7yj<4Js`?Ebln+p_V8ex=xSZliS~2^!?E*7c`r`(A zIl>*Ap`$*=%Etke1mh#B+#oz<>(*b7f95uJ6 zeEb-w3&sZ<=EKm+{iAwGv;X~l4Z-*^#}YWRKXg>y{N`~@!T9-x3aIppAGOf-(!bwp z3C3G0{e|+pbE8%`<^CJj7L3md(kA1gZ;k4AHvivvOTqZ#g9fDA(l?{t`(0@oSAbT6 z@l7h`q`RB)Xq(@K|HfMj#_wOZCI?4%9qm5p&cE?Cg7MLX?xfQz^U>XA-}^V-RxtkM zKo)T^^c_98#Jg!cA9Muc%YPSO=7w-S?Lg(TFCJu#^>+lj$rhCq(wiUX8Z~9slCV@ zCQY}r$muKpJ%A9Ou`a&Q!f=L#^ULPn3-Ni~&L8v!F1E1Q#>VH&HZpvEaJ1<0^J3Hd z0fhKW?H3R4uk5fm-(QYD03km6#HB<1;=LA)uJUm)K3~1hgT-dS79&5%#{q=+{GMC_ zFTWnMC{1AF^QV3#tjSEZaP?;6bJ68GxPOXTG!ACt6I`{)xhIb-?)$Lu8SP|1G<*KA zST~oAPouwPn9eBriVP{)ZnSKBKGMNt+(L8F zk(ZnOB^oV!ntm_Fr|o}Pq$u29^1MrZ?*HLW0XhiqwO#EtnLjU5(q{u3zu{X4@EJE0 zr5JvH6b#^V)Rd(6YS{SQ9cBk!!_zD_RLSur#;@6UM+kXx(PG(3`M8*0H*a%?oMqQ6 z`i*7d_ei`i99(_Z0^`>n$^MWW{=y=mo{is|t&hO(xBm(7>nXyofegQs^BYn8{#=m` zmV-4U7{8j!@H^H-M}pyZv<$zY|8{2KqCJ2C8hS#ohF z8^3F6v&gELR?>*cZ2Z2umrd?jww7MF*2u)~ftn)nc#591YzZ5`_E7`)qBlFGLt5Nu z`h9oOQGow|I|FzFEidW2Mmc^HMf^Kti5>WDP?T^9a(s&M`^nM~&Ye(~VEA2K=mwej zZ6pan^52X3w_S)YM7--F+264l-$MRf8R-wxU-gt=`rvn~BXB)&s08C*IyN3`hFC~e z%x~sTA^(OPPlwosi4u%|GpqBUgW>{-Nn`Wxh5WnnW(l0VWiKha!{*=Lx|L8fbf*O4 z-*aE;;Jk;wK$0$=k=&Zd=HGztW@L=oZHewnHhxEk zSd-I>zoPh^X6`}eylN#azR$*Q4WCUqwVf$_6UD}F-Kiqt>9s;?_VLX>ei!P4#z3jj>V}L|sl^kDUeD)jb2$oAtQGD9!yFfHBN=EV9~bL`!nb)~|0n?E*WT|+K*=sr^6?iNpZhc`!NKj6 zWZg!#KKSfW2T+(TiTarHPu~djYbQHxGI_yW$&Pt!e0JJuK;9^Sl4z}9<8$bHGjexw z3u(<=Ha;K5SrgrK18IFXHoq$Cc#u<`7Ea-_@`AgHzjBNsV#y?}hO{)P=)~&{WB*r)+$da`7-{$R*Uj zXW67f$;BH2e2V!~t8G49==D_6zkf473jMoF#sBo_CzL;pW#66uF;r2C`S<6EbufNm zD=DT=^~|-&NP7e64{bJodQCDQh0(^+_ubk2*-&IgpnQrH)2FIo*5u?$C+Xr2Z2nyC z=1yW={iXf2*!=mS?ImK{a8DY&pN-F#vigv;s8V{iy0QtsVtjTxH;|9B1WsjPQIq~0 zCeok#ehlPcA8-vX*!aA>&K;iKJ}JTCp9!~oA!kX3f8O@#Fs{=l2^}FH7vsz5OCBV*YDD#8Us?jrKAKWY zKXy~9gv(t!NiqNY%eoFC=l7MayUF&?S{B;m?y`~6)_QDwjhbgb&b6K)?Qg-xSN~IH zXU*Q+sN#ctW(&qe1Ltd?q5vGH|wQ4wj` zL5(}VOU{1^AmqQf^#l3pS$3R``E4e?@<$EgE#mCBe4X1&{)=(4gALxH5-k7OWs4&$ zP&+2U@}Ip-?VzUM6zbo%`a8nDqZz1w|Fg;+5)S2|_}<{;3sdWEO0fLYoqT`jAbo`L z=h@%kU|&#$;(Octc=&qoj|9t~R;)>fg2Ad%4Bzj%=0gkRHc~8qdNaBN_6^gMV)4Dw zmkI#K0a7f!ca5n7m#Wbyf7XuFCOr&ip!hDcG$5AO)}j2lKh=y3>bqMya4#F*Mp@Rx zuOM2ALrqQL5p+ccQgI_&BaAz=Y&pN@m@B*eftmMU%Gk- z{QDk}{`6cwh;Lir!QGe0@eLyXK6_3)yqKUZ#rF68mUI|m+fjB@)0tdNaQmf$RabbSkNETmIxB%)OW%XS+p*35I={Jd$HYt$UOYJ7I`Rhqn19I;_ zZ)xH4%T4Pm&W{hyFe7V&!lY9Vv-fxBLu-;f^Q^RfGn>D_$(?9Ve1Q7L(qET|$q#+* zYA}0$wStPs-0uT8jaTgbeIGK2KU^Om*x!Sq{jJU%#5;64$Q|Cy-ruZhI~cK+N}jEf z`#*7f@n)|he0Y5e<)4BQH_*HC2#qgN+hq4<7V%2e01WC9^c->o3k99Fx@-iZ?1qvG}a`hCeJeRhJ%} z%GSRt8p9#(WIHLA-_kLShxP{gQY^pKV^%s0a4?i&`Pnb+^5N4^bCkcY$CrS^2}|k1 zZ1(vMdQ$;45pz-g?hslBf6qCf{M~J=Ho3FVTWUFqeZFV)lhwbp4@))vu+R6a-DV{G z*(qtvJofqaxM)o(Dz8iRt=Z@M>_&HT_~&P-r4F0FVRH`Y?89?01NSibyGD61e`RVq zioX$q2lHQ?)44bI*!atq_QcNFri%f@pFGfh$9AfL^ z?yvJebJKV!mS3&dSps7>&qMu-Hm!iF9`@3a7VP}h>78}3-pmX2FAWp4i9*{z+`kMo zAifJ?r6*O{`nWpCj5JKhmcDUf<8RCxYjShebLopgJ{sk(u?uANB{~7spDxex;Ah!96hB=f zOJIZ7I+VXA+^T?}b)M46)7bctSk%GwO@3&66=|tW)bpZH{Ad^&ko=f*6hD44{<;=@ zOL}EF8$TxRtjW{pFH-lTa{PFT@YBJ-oqUgI$ql{C#!uX9TR0b}CH*o^&L3iZuqnV1 z{O`AyZYh(Gi}R1uOWnZVNl%L9ck*q0VXbywDHflY#rQ)DC7C|#-2C^2`JKQ5S$=1W z1jWbB&hg;cZ8FL)v{O3FIx=6{StjIOz$Hn;Y9PUoW6m;Q|-m>v=YI_7pinid^+QV*MMz)6=0*c@4@> z>R#$RB|N|;X$OCu85`0Ki)4g#jeNr(Ss=YP8P)h3ZO z=TQ7PHR_WJtIHX@SmhRrm*>G_AG01L>TMxPyX@skF|6t{FNyGTE4$@xi~Kb-Y652^?3 zM&s`u3rpbikwYkd>4a6lp)W^K{@U5M4)*eCsDC>sCWtYRH5CsW@4BgT*ZA2+ga%`omqDjPq?MhxLkseI?2Cb0Qu zwk-Z>IOB`vHX%9!p+H5Yx`tMFW`Ja9uD1X1-;R}}TQ>9q{QkQgps5&Hsse05pw|3TQF*=vR!q*x9|@v(EgBYcb}sDICw z<)8MdPDSxC)YTWh-JFl&V~Whb+t{r{>Az+<-r2oYDSh3%Y99l73fDdtex>s!||2U!@ z46!P1!iQM@ou6O_=En$%k8=|pVUfoa)PK*G^^Zj!nTO(I`6^#%Y+QlHrwZ%*Vc3dI zC_d7jgo6+4Lh)hxIS#<<0IL5EjY|is2O+3`3C+xdg_Xxq|MFyQ34F57Lj6nN;RumhAn&C#C1lw@R26BE8CCxke&c1e8)Vrnmty_jvuF9j%V8VQ{46=-4+9r^O0oU~qdnnJuDDNH zx`pk3=-W8RQVB-!Ge9XFo}P}D?)oMFy;%Pl+|C2Lj3hLE;15*5c;8YKA1Bo6Knp&i z_-NaxMO0cSb6Eeu<|2JE+Os`}>5pTJ&4`Xwe-6ukbzDD(B)uEYxkj_`Q8LbrO!~YQ z#Ygt8q5OsGJt6uW8y{=0+QQNI)>5qh@6%-mDE(q5jT+yae-P$R<22nNsJ#=K|7w)_ zLb{Cyn%{79^oP%vebM-!<*{&xFbG8R8-}v{SL-_w()Y*Y{zcqhHAXWXR^B*)#s^f! zFF}hkQ2ladW(l;rbOo)yTHe+t?>p;qyD3{=nhiE1{39b&Umo|FL;6pgiJt$V1Kr4$ z4_moHE&2Hu>&w*pL-}IofzaX)dw&(OY~e_`ExNxZD;#0kP)8}&pENGP4T@X2q5dOe zyf4^Z^+C_S)+B$}8sLZK4|HVu^FwqP8vm_&90!#AU~lPd)PLA7mBoJxU!(fN?^!K47*|X0Uu5eK@6Ouf;7bh-tH0hhol)-(iEEe*V07w&n`XeV5^lqsvjDZ9AV2A z7nJ|swswc=)!x!TJ9hjZx5O7ZuQ`C~%i8t+pc5aA<}VXv=lesOW9a^GE{TIDu1VRP_#a}D?AUnC6=J)@5GoA$lh6w zp1*r*Dy7MST-$AE{i*kF2Y^>z==t2< zO?E!(_o4Z@rz3qK(Ig1vXVvY)c=M{Upt4(zA19H1yw%$mK2?UH{`O4S5im@)$ke!4pg1n&U_GeD^e} zfL;;>u1jZj{vmB{Eqw0Ql9S9~^ZTF&T10n)K8mllDf(pHbR+b9Z~JaaMh>6Mr7N@J zgV$HBNnQSW&i$u6|DYhsKiq!0oqY5@z)j6+#-A|%^!T$aBwzMK^S}PY5t0Y*LH+;b zXgAn6=%5tq&-hw2jCUR}6`XIe@iS4u7aZP1OP8H!){nyaxxaxw%$kyj;-}@JaCk61 z6O9kno{xi1&X-aDKqjR_Zi~BU{$bp_Jjj?O)CM9A3xFh!lBs}@XTG6!|I=| z7i*zdqdn>$y5wk)9%;R}oh5Al@Z*|3Q41P@#+QAcm=dcgvp9#3Y<>#fYfTglUAUYK zHh%6b-%i3l26EYB*!byo(iXNB`JnM*;|xcz$@G)f88qtyVSKQ5vm2bMJdEl`^PD(1 z=5-Uz?=Sh01~V+4pyz+(kUW^U;)8TzQnUUS_MiVXmfbJ=(14!**zpyx;kPEbfA?H# z;oA>c{wIum{`F=1XRuzDA4L3ntHb(a#Se}fe}e5_$_q?Mz{iECe^HfKlVN*yayd5a z{Tnf4J2Ac!%603=-oM!@M*P~Z*3kPe`+OQk+JfbT{pkK$ZFhjxnn7s%mo~u-va2J| z`gVoPf7C|BqyC4O`a_pFsc3%5-7_4{|GI?gL-Q+fz<0cd=BG>lq(Q;LGBm%G#^-_J z=pX3$KQyicP7xIj%TK0Hs(`_L+i+O_?T1UX@T=GW)hCNGwTM^VFcd%2gZ0UiF5^-E z@wv#9%Z>O?zbL0;Q%TzVQ770Ympn6cRh~A7bj%(#ZG^cq}csIW0}5< zugXO82lrNo!_V?70{tO=UtpJB1#EfVfy4Trw4}AL=Y4N(y)*m#Pfpe%zE6gu`=`54 zpIq-^h3=nTxG8y{>%diHvG=dl$Jr$H@O}=ve^MLbLZ)tv(L?>aoR1)r@UXng4Q*#RVV(P;f)!g5)Dd3hqL4{oUXf?n_$R6k}~`NQ7DIcR?H zu|qhlFTI7H|538|WaXx(sQ-AAng;K?d_eO9!_D*HsX{$^{@3*{fvVja9M)e@*{TAL zD(a&6x$9R8h4%(pq7|2xI$?1tF#+X3`c;wUCXUO!wJj zbGL)stHbj1FV>GX$6Sa>x0BrIL^gf`o*3~v>eoZc88&{t%g%p^Uj(WzU(`83&8|39 zUwS3G!QoXY==mR}>kI2%TtMp+%5(go{@WF_zPWjvEWS;?ht@Z@EscX+F=bMda&~!mLdA2#;VHB}l^EeB!%v1_|2;+T%jEs^fzKoIQ2sbD z#UB!$-bD9*#e#599{UvKkE<)=U}n;LH2&n?rh!W5I_cpR^8FRp7up--!K^JUIIKS| z-=G8zS+z&?!-vLlxV)`9${&4Y{wE=M7^**)T(pHO{TP(L$!2|G@L@TcpZ?}3iys=i zIGV!7&u}`6EZ7sy+0deY`43_L?VdyzQhO(Z8~>1vpIkd*ep-Sj%W1A%{SD4JoZR~qgIL> z)*rc|A{W{vX>nE|a(syUBir3ChW5`oaoGK>@H6G`c6}eN`bTsBn(+Or-~ZLX8bfn5 z|4_D9i%jk@8I2#8TiZgV#tBs4OV&8Z`o~jIefEC7K1ut$4vk;xd0G5Y?aK}KVB@Dp z#4HjqDw^97!^Tg@br(_@ki{vsWXCTFCyn`=72a@W6&pXsi`}4$W5x+y9vFkmZjSCZYcQ zOg9HOo|S>dhXZW%$+K>oQ2xm?HzgZe>__o4e9$aXcJ?@@*prQ)yM-aG(e)iOwMV>Y$a8#RpzC1!~A=mvJTA$dw-T?;3<)izXG20F9uPzekJMsO#LB&3B z!|gGu?-c*|fwkQmG`_cQ8x9&Df1~`|?!`=!G(VXm<+qsnWtz`+($A-ei!qSbXTzBhqjqIw*VEU&8hutrXmdN7MfVSM}>&@|p@czZv zkGY_?O`pT+mp^n$V9fG?oZ?va`M(lV4m+GiaoGKfQ;9XO-e4+v{=1lHkr$53(evMH zgg)6_>WSiSfu0P1tAbE|zhqPLXx!Z)#-yI^TuRj*m*Xd;wzVSi`^tWT<huzOpYF`3@ z`NIVK;R!pl;&!rL^FHUggnhoY%>AD}rKtZ1`DqVJ zLvKm3_wf!sbcGVl$Eg2!@YV-(R=z>|6QJA=deZMGzbMp(!L&pr4(pHpJ|qsdscUm( zZJYI*@cl7mds%;qWk*#14S8Y0=k$y~@zwa!grC+s0`zvW@ztq^?ETW0W?Y~L`}}_% zTn<62EV)O;Z2VY54aD*Dxo7R!_)+VvMOH~SqW))eM}1O%a1V-~xH~2!(jbysW5&kM zFT0uKp5r-gnFAX?dZpWmhx7@zA%TsbG52lYQ;!0)zbUWY9)h;sMdO>R)D=z*e2L;` zPOcAFWPU{J7aQOBL2ynD+TXJIZy0E=RpYSxn-kl`!IYn^aeX*64W`?56~v$7{KEsk zT)3Ir7mYuEn49v}K1We}^`BwNyG0&_Z?EO}Iw;b|E49mEugfH^Fh`Cb1rWxk!}iy} z^N}`ae9^j#7U{QV8;YMaBYl#@9pJF{Cw7LJkPGU^xV%5t{`qfV|Hat;Gs*E5+1!{B za{P$v8%8nPN$j+lcK6_L&LbK(1MAr(Gw zW#J#`$+gYn!v2XnX?~!}DRbES19vLIKz(^jlz*1>i31YSiNoF>cxRLb(>!~k_)7N3 z1?$a2IjsI}aJLwS^x*{hRE)2VDzfC zgHU}sZh#4S-Z7C|wS&F?kABS{5f`s=%Dve8Upi+y$+rA}>YJKUQ~sTAB6@y4RG9Lw zf)ZiE3ikOKndJi)Pc)$VCD_>y3VqZ#ji7T){0JbtAKv>&7;JjohMO^_Ild6y?{fbW z3+FfLqWa~fj9ly|0sDdng+}ipP9l?QA6u zdw=5j2|u`4qrqYKbK7Nw!8~6bRR21Dh=r^n-BA1-{h10!P7Dy}7jb{~Jhxm~eqjWf z-wJtF46igM3iPd*KW0EVv=3N-)=vtxYhc?rCr-6-^zW{|pf_qb(OZvNBP!usAKo$W-= zvkvudFIJlIeUdZ5aNOsn_ahIA-X|?fFyr+;XTn|G(k6W<#-GNeFnDlJ7oDF)PAsV2 z>x;%ms~@C7!&_qkzlh@_{YkmdW&uI*86Hv$D`IB~@G0h($rsDurc8fg@pGRqe_-uT zS1#U?%`b|lHA&0Cvi{rw?EH)I5*x@l@&=7x>v!5iuS?(2`1QdjSLo1Akt@E~tPh3y z@n)P4w9b?D$0P5r-#y?5@$qd?{6%b-L5k`gaj}ot_-I|}LafphKz|I|f2G_tPVG#qSd(ueAql&p#-Bp4zyAW0f+8y=gVB!bL>kK|AdM7r?;^=zgQ&?^rP7LvTT(G&wNI6Sbs-ipInFLD2;)_FQd_#}wk@Y_D==~MncgAFD=_Qo^ z&Ejkz?8H}8Umx+ahxLXHsJ=FS;tEzeEx6H-(??&@qiy~z41s}r2%w_X`t*;(Ax%DKs${p$NyJk!*r&2+DDn9># zoo0~gTV-5D82kKu4tF7Mj;KLiKlb@Km*WaAXKJGRSK#0SJMG(X*!v>)cKE@mcDm^K z?=>?FLX!HT`)3#t3m2~#qx#dRE)`y@0eU{449x`&tkC+H);bsRcZdco(`L`#DB7G) z*1Qh-8V{TFi5MSovhe|0*9HFTkH~*r+;0OD9Dk$dCwG%Qg!EA2u=ka2zs`YJjag{^ z_SvCgXk)jM>v6H!zX#l~lL3wzk^uEJsU9q8Z+ zTh40>{F9hpw8r{Cv0(?)KfPM!C+iO~;IQ}e8tua1Z_5E_e4D%^7ACYY=N8{=<{x2w z=ga9-Nb(+o=EtUdFz5T+E`rGEY;x-x+^S(E@aC0_3 zW}ll*oPK}ce5SGS5i!Drbk);_7T@IkJ>vM+!qF96)Y_o>xAhJms5sx5!@h4YXr~`c zKGlO8zgn)J#QC!<6Ipx`H5lcu#J#alIerwHpC7a&6>N8m=Pb|2@#87FpRTT%3!5wE zqWraC@NmBU_`3ppDDcAXKeit}oNqPrE_4lJm{iFi23DIqKsbx0?_`{Pir*E_Nb$r&jhyrYbE0s>rNS{erdhhn0zq3&1Lg! z{OIkRPU5`3aLT>e_?ghjg`BNy1yxmS{7km=0p}oH)W2Pk@yGiIy*ccCX*C%>4)-(S zu=h){*Tll$uM*V1buCDR{Vk@T{_VYLE~t-NBER?za{9$_G=Bah)guS4p63eJv;C8qn=vU$yo>6mp4+FBqd`A8%aL;Y zi0g+pDz=fHC2e7U5gR{CJ^et@*^mp3V)IAa_F*urz!c>VtC6wLpArtcf6yj46{h!^ zj^^Kv1?RwiCtLLXLBx+caPQ=1fxZ>v2y*YP$R&PxIURJ=o{2F@Z~2saF-`7& z#P#7DJ*ShJ1r1yu6*hm22--&8p6LWb)7kvd;q!3bY~L#ZKdXrRd+7J!eEGpwU^W?9csc>F@9``JQtv}qh<-p6tH7Gvnx)($1_B#aehZrBPdzHb4E&I^- z6Rdt$L$@hmX#GWNv?ggAd=fpMndT$-@W&OP{;8VDFCkVV_-WM@==yDXxdftBwNU@H zZ}K|W=iiRQ^7|bVw!^NMx+wnc*!sYv<9)bmxy}3~tj{lee*n5&8^U4lC!1agg)g5+ zbGO>a_eXp`b*BuUVJ|KV@`K|0U%iPj`TXaFfS(jZ`TeP?(@Eh1MewP)(Ucz)^OM*7 zZ6sUL70w=zp^|M(626slcjvSF z>mo9&$g~V)=#$Fc|Jxs($qprba5s|gzc{`scOAjUB)@~l^?#V>?||nBe#e=2==n?O zm)-RG&g4XWH;5X=#>bxA5xkbyXE>-) z%fv_Kml1q7`dNSvb&-D?67zwJNez>Jo!44kzu*MV=PP(B*ubIrviej%_W4|9odcPF zx1#y^&VTMe-#fnC;Ma0~0a5?S&Nr{&+0;X5|4G7zY8ZC)7@8m1qO3`RyPW0LjAX~R z7WKO1h2c%KK07wvm`om7g`VGi9kzqvuHGE>{^q%AZ}@V02v&!$LXGWm>qJA?J z6z`8i<5#t3$3d!Ujq1;<Jf;hi1YMm8H-Kq|j0c?CdPje=bv?t0xKWaws zGh2O!pMT}}N)yEwy$6rv2h8}6;;U%x5>UL*4$XhO*}V>22kWBew`gb%q?@^-{B+~h z9cbHcFN&|Er>|j1WiZ;GGHrP^Xhp=L^&c%6zC5O!L-TJRzUz|t7jC2dZO^6~6V=Zj z(EiyWF)r}7Uq24}KFRzi-ryZ?gyu(%mLGtUUKVKn|9fdDjB%QT*8dcL9f$kB=Arua zr)DZ#&RH$!pBMKJot)@QuKD(XRj=gtkB^D;%L&OyzQ^a^kl*TW6F-UZlVUrP&(f_H z;741;Pagx90O#I;!@j?<&}tn7-qA<%A73Bbfk~-`hu&cM!xZJG#jg%P@No`}&z$duLXOciv_GWv+2io_lq^4nyx&lD zJ_YtA*bDecjGs%La=@ry2YS9QM2+NEj{XY|Tox%&*y8=`BX9d$OV+gNS7>c!}R~9 z0iiJH=?v6AB}E>G`chkT|0|ECz}s#c1p6=cPb>6tfGqVw`ws`5l%3xR{wTkXwR;We zlaHY1_uZF~e5H#58F8VZ2|pJ^{_CmQDE{1D1=9R}Ya0>&ET1F8kB%;iAD=esz(2DW z%0HtrU7%a+U{pWYCU`@V`3ST>)acIv80S6)&2KuGR6}%pGODjLZ)=dR_0=18#_#6LrB)=_31;yVt-BEmIg$mI-z{X!`wWm?Wy+0q-!v!9HHAeO8OzI7t)=1I(%QKq;P^mK!&Cgvd(;#723b+-Nt*;8!>yk5t zuLSi2F}{LQjmQkQMigJE&eMn@=)msU>rMVotgkxkcP2BvjiC8`*ES;ldZh4?>n{6# z>!<{_|E%4A988StQGGq}ND6?ByFgzb6W6CJFTtG`d(irH$*bECTOEwnmug@<$WaB-;)dctx>-UaF*247j1JU~SeQOuU zG&dLUm$<)V*h+6OA5GBylJOx2V947kD1S{J9}3%hE<)>n?E^K)Fy9+!{=0gNF0t%a z!Bvfu*EhxZazAE7)?8JD_LtcHvC@7TnGxL)uC+iZ2$m$^|eiY4I;9A>}D1H_#^M=E7 z$D;bmX5|4m^34j(@6|Yl!jq3SX#4{nMnt1g8Jh1OiT#&!$u!b!d>3fZhrR!h;!NIO z94_du^%UvzR~3t4+oV1yKZnn{1m6w)xcTuT`vLt#qsG#+5TQ@qXu&y zu+R6OcGJkWExIuNjog2T^-29zXEHT;6r6XG*Pq4vJOA=x$Tl=Y_jk_dwV=Jg2<^|? z*4hQ$jJFWrA4Ko>otbwDrYs9U>pwyJZo?KnQs6(t_;{T93Q8WGMB}SN>wm-CS6Qh4 zFbdZojVnt~eYiwjmvq|sfr}r=#)r$(58NKBv(kZsDD_geH_NFaz^_PPx2{H`N&(K|HSxF$#W)NZzW)In7#kg{wxO7 zp94_-?&r4_I@p+U*!PV`gl>b~vggyA^M_*pxyJ7mY)nr^_wWAd-|)CgE*d`u*=rDw z%lFaq9sac|+3EBjx_>)I8<8+$b!fi-B<9C)TGPmvUIx%dmCcX3=RR=l?a!h6-=;hS zyw0pe>o2n_V}Llja=ZWa|B1h!;i@6aPu2ON_m^x3U4o>%K(xQ7KI}F;QaOtHzd=)- z$%735^&{o`4V%(H%<-+Fz%-MiL3@4v0@yVTv!K6~$Tp7X5iYc8w9*YA4; z^UZq``kF5trND}Y-T3DpA@GmUXXZdPzdzZZnc8kCWP6Pu>*rRFwFuEN=ix`lAN2+S zIM{y@SwAo7ZikwM19`rx=03r-{#j&wDgFKh_Nj&Be00{-mTY$UJ+eQz?UEkrR`!7_ zk`w2TXMK&BtZ^&cOcCer0q1R4>6ETmQY7VXp+0kIThCdko;K5HFRs6AB>b^(%W^Vb zPkWP$q#0Yt{NkeNQJfkSOzuBR`;-S(7QxN47q9P*8?WQmtYi{@5#7C+&X6%YeIdkO zr@nI#@^K(JAJ%oBE7Eq4BT=C79SEg6PAB>iJirXJIo@P)*WtcDR&9-%_w=kR(PNqpHI<9CYV zr(Z=B;x2lU`9gS?{fN%@CHIpB-p@o@qh!A4zxUyV{_wowIfS;2BJ2CqdDk)LXbKM> z!v4q8tTn9m>^K~*kopfHKD?_Xv*C&7%xH{ zqi4)`E;XWgev^NH^5EzI%#NH+;%D=-P>kE-MB`_GWOi%92@*d$Yrdewv6$2^a#k(b zv=NU<{nFV-kM&Fb&OLi@;osj!sBgd54Pusk+8{VooPP#;N$~TcC-jd=@gvlak;kHN zxq}y}Po`f>M&x3Daz5zP<4nAe3nTT({SoKz%wsQazFD|Gx1!y3w5mQx>cjoh8@SGk zE|_)PttpC+VQXA5R5E@_GL)HE$8cZ$t)wVohUw9E_X%HXGZ#)PQSfTd&Y*WFZZhap|Z+>)F-!( zgu+U537IdJyO%X*D!MK5w7M&^Zhse{kUsCt6{kP3_0KKQ}G3Ntgn&t%O4Woa`*Qa zn=Mum=a-)S*P^6y3h#cJP`_r~^GCPvIb^3R5_97-+FT>j#asn=ilW(6q1d7$b9eZ z{A8FJ29y5(NNgtF%#I-Q`<@zlY|Tn}94rv$hvYefSoyg2Bt9nAO=Ldv2H;h!lplon z82ZtR#VAgNWY5cg`h(wJy>;3VP1d7He0))KML^hivOaHFqpwDFK99FHhI6T?w&H6QdUp;!)d?Xa*yk-nf<&g z&L5ZZ{1NuVnba2pqC#=9yC<0sm+pwd>$|=re$rf$5%@QR)Mw?snJ5^xhr~~%j2`1Ny7c;Axh6sOg{M@+Zh^JK&`9aKoF4*aU z)g=?S$#0tTHU9f^#Rt9d)8CGx-Y--R%0v65DJ1{geO(46uWW8|q_n;W@e}S_4XXtg zNc^mw`UNil|N|7Vj&C_XM*P39Z>CPd+tuRrPU9xX;^%)-q8HQBuqV%de>8BzTyB{ibI=my&w)D~p|r-F^l#rE zx}g8xiKITexX~M7L9@v3>vh5(zxpj9=c`Lys}VEqGFd++F8l(`G55*yZzuVFr{fyQ zd~((eUH02ZNwQ-|{QUIQ8^kt8>!JC6k+42n&yIp#)K>C*uS7Dos)v*MD$F1gBbLSR z`U^t;zIS{cI-NX7_Sa%hmEp1M39i&f9RHfDCNh;H!$^GeWnSz_$}9|X5kKEsE;ewj zcHc1@+oQcGK2~MBAfstA`Tf^vd&4%+k<1S}`1oVtoTa4xGVK(K%y@5df1>V)YJ5Cb zOrGxww=dW?xQcw=vs zHe5LhKXrmg|E~8Y39WN>lKJ$X4w;DdjN|!tA%5Hz=b=sOG}6C+3MxbOm|Sk0yEuLV ztR}KQ??*ssgE+rDyt()Xu??-SOaspq~K-y!p( zR@+_BIo+1TmrNgT%nF-F@{8Uie|Q_Zlk)-PgF_Lgy@AY!hC5Z`%hpoz{ZR+!FKE=P zCf|=->8{MqCVVC9$A_)DY}lSw@Lw;^KO1ikWa_@1(Y&8Q$UnN99O2i}lJs}g?~-se zc{iCatE*+=@0xw2zEB;R2Zzo_$oZ1vTg#wz^fa&jLU4a0U3VgzJzx|{7K!7>#dJ06 z;5Qd5qW+uz6X55;zW(MizMa@=2XXw!H@xBAJKZ;vEIAV8r_BB?$nG(N^f&W5c_VYf z0y1BUTIr9oksf4yvRD*~!B;ku`O@q6d+_JRHu8K2{(TJdJ7r{jORN5j?4YOQ`vLuo zmD%A9Ke%=(;`2}UR_n52dlmHBCdHSKzkZ$^$R=;>O5$s7H%BlhE3*D?zMF(r-jO7} zjumB~yG0@|pBCmz{ePc@V~-3nU-H(M)VHFu+(-*4KMC=*NOLv2gZU(WY%|TxW2y%8 z=8qtl-@SC@9p`lOv6|X0OB)?ef8puAa=nn6`;`!5EwTVn& zrzxo)bZcfK9NQj?r1!rNdf0Xo> zH7&|;rd>V{KSF=dpi~Vb-y7uppR=W_*h$re_~a?hPi1Y!nEM|Z#>1DX0AG)eu7O`G z7ZN`;fBg{AZVl&M-Q3^c-%tLl8;W^r{mA<}m#0Qy{)O#apIOcM8$W*nbgrxus4;AIe&k+ zPxT(`VLM3wkzSev>m_^1`O-`oWmXa^3u^yqK?_~BcYj-?OcnqBAFT#5xA@+e)>)iC zCX`sS7aok{59{%(nEt`VNK_R+Uu)OC;~dyyET$LO7S zhx8|1PkzF}9d+b>ord%==5pgrNc<#d`$PZ7MpB<>p9{f^tgWQJHH_Yan!0c@pZK{Y z39|>rlJ&i=HUmE&93Wdyp)@(|Pu_Qj!v5JkYcEv~&aePEfe#ga` zyd?1v_H8y&hs_}O2gn*P!O?4xONybPyBq|el^Ctp?owCKgNRkq_Tbw z2H)L9e*a>pBovO0C%^w($?p4?vT0n?2I=__`p@{0XK}OP1UY}&Mt&e`DDDd*4RQW> zwb7crn`}YiW8UAD%));e9(NJPhsv0XtX;x6lwGX;Pv5oUU0@&F^p0C6_u4F1PWQi` z^L{K-`DO`jBs-J$kKZe=!TpY&WdCt^jUS$?`;hs@g6|>dTNcE<_iN@KKEHq2c@+;N z?<+R@b0NNTMm~m-+yl}-egvVINT+H)Q8vuQU&*@uSdOCW&F^>f`zvoRE`g%;ViG^yFL>eE?Nubd zT+8#rC_i7)Up&1S0@rcDWPdWAy9!_JQttR*as8sD@fclBO3`9OnC-?iAE1kvA5obvJyuUku-6$DA`lmh9t(l>`HE+H{*q`g*u#yc) z_eAPtar_J)w*>Q(T}b^>wbl#og4U4zH`QuCtQ_f2&PSjQWqCF_? z8%@6772G-rF{hGAeB|0?!1hHZS>Gy4&cJMV9_b%a`(8zvXBkf)2>s{U9RrwJ%pjCC zT>e*og!$es9c#8`m<`#VJ2GG;OJ2B|#E;vLJT{TbhiT*X|Nj3qc?GUK*$cBW){*}7 z^kF{?jF;^9A@=u~?FvDW$99r`JdQsC);uNkZ*T2Su&w(_<{KyGDX~6NTS`1$!M}e$ zpvwFAKOd*V2AS)DeJuR%_iMxZ`S;rmT-%u+&AN}$`S)`l!Ty@;wGObkJeS-*(z|3a zEWRw|v|2USXMX?k@RLM%ZAc;e|Eou2pl?+ciJys=&)|edKFKcyuS&5c;X2QM3h|Tj z!jtWA^oI3easF8T^c<_nDukZ?j{p8X{O@04HO_qDT}$5i8YJM~;F(@n;HdH zkokTqnXfl_hd^C%2Z;~G&U^4CXD?a*hrIX*3z?rJJ_egAu|nC_NVzGFj{qAT<~Fk< zoQI3+mx85|`hRmUdHz)2Td^Z0lgaZ}(&Gy^W$kaX!E?Kb;;V6}0~Yt2PwJmm6^jvb z$DN$7Q2v^ZmyOxH{;x3qdbZ^ZE@hu5`KMPwDHI0Z;^9ZAAHxqk!pKF>$o#^rz>}F- zu7_)mIKCb{9cP~L&YHxJSA>K=UIvl%XLPp^$^3XYS%0pmO7e~LSaN>;>+3|x`{@VC z{_1sOB{t-Y3cmdo$HxO@9rjbcGsz!Aj0P~x8$;n-D$dU;X;v&()0XUSq~jC!L-PLg z^zmIp@saap7JO=)x%U=Qei7yuwc8e>G24UeUsN$kesO3E$=?%~p232@7fAnAeyJ4f z=56l$EOCA4wCxefJH90MZ?#(c5&JTJlljH>Bu~~|eG^%q6x=Q_Z4F6{B>dS9c?R*NTe~fd}G4ADYUVlt@ z{zmC5u}PL~K=ohpyX&yMpStk!GhzS5?ni%Sk}({=4v6C`I@yYK*fgEwp9fLzxaSJL z&8*7A{j1?(2gD3pLiTSO)-1;IgjFQ}OuD}s3y1oW{-o5%4;Kdqll;H9&l#|vm&p0h zh4V|%`QcseaBFe=l}>&H@9lLYKmC~X5hd%J$oWC}6Z!1y`YRaVsPbR^)8gp^_KDh5x5`Tu;A-E+ILFV(1awD;(O#+F(R^Jk#bLlYGHdq{g zWe3ucSAUY+A3RS>iOs82BlR`+SDSs@-wpC(rS(sUzv}n>+4-}^B)=88Suwv8c4Ys5 zkEtg+7PbX91H|jY+E0yK(lZ%uZ$rob{=U3Fzl?LvEZ7>jlJ!x4;9}VKUPJOyP2L)A*!N%(?b&{`>Ru-G#GCanrn#^v}UckFem)Yf|5~arlTm zLuEm|-yPBR0xL?ofuLjJ`IJfP5PVCCB=u88Xe8!lCzAg6$CgAm7^jo@No{gE>VKai z{jX!HHdD3lf#m1n`r0|YKU26d3J>;*^VdvRv29~#k@z{M?#Vo+`l2CB96w*KF2c3& zwdDNZ`}M0~Cl^5S(|~?{uy@!_`j-HiQVc)vfa~$S`TO(d(~q`zgo^qGvi@}#_7Q<4 za-jCV9aB0?+EhHU?G0oWW|0f4%&pSZ3zc+I2 zeC4>+gF1~fZ;Plfq!m+I5_ z;dzDR|JYsq*_<*{vi`l2wPN2rXG4Fsw0|hP|I~QVgE_|eVU?>meuBrXM%JFKBtBdv z_{i$DgX9P8Rw4MZEsD%%^UA8Q-oBBnPf9~S;*XgEM%#(+2kcg@$V{}_k^Jp(TAOv_ zdhz^=kiS1xzvE`UmE+Fd(-ZyvtN+eISf3T-_s`q72_6}7n-1d^1tfnQx_BDrDz1_F zNc&q?&|!Kt&)*935&5DCOu@;CtUo)$Jebm+t>~8|j*l$wW9($aCG>9e`FFmaf}fx4 zEIQ6U8<#-;ru2OQAC9jdJE>h}{fr*qZx8K%|Gfr=OsE6{oVl!q@NKiv$g!nccG$oZjOVH4Qk;{27cN|8n6Yon?`JfHDa)n=PnUvxVvj<40d`?K3G z&B^+(#OW=!eY_&~ccV1_72->#VJ6lsTtnu+k#i*YYU4-x;|^C>;iG&AnU7w*eFQez z7s>kg&F?gJ&MqhC*YYLa^;F+yJp2jyEn|KaQn~LW{;n*az%=t0lJi%+2YE27A=^m) z+a{C6mZ=q^yY`lU{3XPnUd{;?BDv!!d*s@G`h(AZYu$s<;eI^nk8|%vV9m-j^8Vz* zhY4t1aDwzNZW4UO#kM5*%hN}Z&6}Z1>hF2l+Dt~#kj(#H{xM{8a>kPWrhLFG?3}ZX z%vWY6EP`%=KiU8FX}tTgA@({TBFo77*i zE3d$P`3s)@65{KOK^0o~|0MNEmoXDqYOf_EzQW$FV8N0aMftn)Mn~D@g(dhIwn-FU z))IUzzJ3EWFU9etKjGgZ8=CzCe}1R?`v^QAnnCKXZ@CHB zy6H4oKRd2Cf*+MdQfN&MpuQs1_foX;6kqPe{Nr~iFFfIt8IwB{6^?5ZUD zTU#Y>|L!t+&BK?FzaG4Nh_7#&$oo6H;u>=4|9&pS*V@iQ&F4(FWwSPkHM=$pDeSUDY+ZIiS%Db z_eUW2dM24K7cNOa-0-vHe1rXjBbfE7goiI-e?w(Ydp3BA5y?Nx7a6kRvsNVkxW2Yz z?qA%<`k*pw1#_RU9cKnh&!_PInCFCrFdQC4;%idTO1SI@C;91?QLZG4tcCg)Yyc#FX7lrd#UaeNJ_J_hyX(Eo# z_#-PZPDqfU+jWpd-3_tuDR)~e&BVC>bmY9zJ&V!>yHBVLiahms>Ja(aQG1O zhsiTY{LNxR%)4jJV5hJB5PhFYGx8NzIkGjktyH=nNQlo?ukGRH?@QwIeZWFYuG&WC zQ>E<^kn%X6oZpGReHdQZW#s!5d48vmccY5Lr=nSV<`g@W#ODr8Lv}l25?W6YufOB= zSh9rm9z6aO*58J-`zuF>+{vZ7A)#dS8_hgcWnV{ z^Wz1AW{Bf+xYZEz^(r$-e15oRkKvO2ztsEOK{5;R?ME;$g#PV$&?)TFttRtNnS1@%)}Sdk*iRfkODrwfn!J@feiPzn-_qr5lhsZ%{gV1C zVg1#5SjV{rsq*xR@ceCf=Yw>EedK)m@CVy4A>t6}uMQ1~!1-r6WdCxs@zzzg(`k5Pw`l$$aTi#VOM*Tr|*RL8qn?( zW_^3Ytz!mk)Y0B#`>ju$ojfJrvU@feLcv*9x0P0?|&2e%kQK!X5?=t{k!c+ zPn7HLA@8?cwmpmw+sb+S|9k}ROMH8siwmu5Nqm&amB2On3*A50wPe5Zy~+C%E8e;@ zAKeICs2BhKS4JLTm(*|LK;9Zr{X6wXKAUR$8V7a6&u8j}7hLGRHeBEr>3&inezsKm z;N9XR5|M&X={Qh3+ zm=>&$T5oK%6xV03erd6YfukT>Db>G1f1k3ZAKS8PI_9?%uMcfft<4L&ZsPHm@O_R$ zpX^}o7RXihmgXD6`NZ#j&Un#!2Z_H+TRh<$5=G+gdVQ`WTYXOY`?l|kVPo-~mwzV- z_Dfi1KfvrXCDMPbdoiB<{k)Fs|2ZbPGmrU_9vQ(uk@`p2leTx^P%p)w56AESwXDo% zGd8^?{g>UL=iKUOHSVLKIQ|wGML^}uY0g=-nSc5Bw@2mg!+^{pQa|(9P(1&c;J6KqOVdgIZphBX#@Lsn{;qN{-xrE#=WHS0Nrqx%F z`XP0i1Yh0zkoE0Yq83x#Ihxd0^~3wIok^06i_ov{qsB9%!5a}YMckj?ahqsmv?6m6ryoBS{#4Itq!wWzwY6(f|sa&?{gua zO&IzCQ@4xb%ca^5t<8c-d@cOB0JjQvlKw|0YBw%j%p>#3(SG}IZB;4RKWX_b4c%^4 zlKrjsTXXUIMjd(nwR^WrE&fX%#o zT$mrNGI`Eb&(+}ZzlZw9KVI?mftv0?5`VrOw_#fHQIa3?^oo&p^Dh^X zFXcaBewo+j0j_$tCh<4n={wvQrc3Hu{oG|t%X%+tHj3lVqs?K~O6LJ)x{Bj3{HYxb zkA;x;_Y5vAfI*MlB))zu+KnW~e9}J_EAB(Wt*a!z+5Jw#$4?JP|DC@s7vq%PaMb%r z>S`@mYzITqUq&s}Vp;NxtgovcNH*}fIFj{skKuUMZjukin~3w@&vUih^$zX0=J&sZ z_$qGciOAS^az3Gcybmt8A0p@5zUpto(M88demkmL4E+N#Xr7-H;w$yreO$;XH1mVaqahATfr-m)Wqx?6G79VrWG!RFE!f{>z9c?;=RM;JziD#K?+*&`5$@rG^IRIKzplIqLd?x<(*Nw)v>VT+o+tgY zvVJj4UrYKU|LyN86zKQ9srS+9p(>g0lzP6yiuw*D{}?tZu(k31$@BMM(qWeI; z4@BSJN9H?yuEpccnj2(3UE-UDP7#mE`uL*$BxIhxBmMiHl)lV3)d}@u#OvFH8VlxA z;K!T47S^|_=Wa};HWpQF#QEQB_cN|CwLMw?Vt;MH6RX2yet2JD8_pj(PWI;>PTURs zH-+SU#^u=ixI9x0vz^5C{h1!`ps}zMIiI0>U4bdv3?%VoVxYxl?;lJ0@7roen2lZy z#+;S&O5*_}K0s@nzXCA1*KVkoeM`?}1$-6G?pO^+`jW?-Q;n zPRd^p-+J{I9^e|g^dmSKENH8o?(-k^yfl+ymQhwKht?0iI0Y}wcMl_ZJxgo z^84|1^C52>&B=%7{+BPw@%q!B(mkNoEtz~D;dMJ7bRCsW&S!Kud=iI3Kau#**jfZr zV+Ec*=qkX+kP-LsXPY|7|HHcXW&P$aM2BCO{{8!f`w?VKEExAB071V>{`>vZdB5Mq zZEmbX=01$*D~_Mclo|N8C7ir}>z5pa39oWVe4UcnjU~G-ll+spJ|36n-X{55OEnE~ z`)bJiH8HUPy4|{x`lv2cf&E-KnB*sm{hF+}bUd0|rT7x+i-E1v+3U2IxLzc^A0Wiv z=73u6$a@_gzJ&V|?sr+b&he#ZyHCH`jBescb2^UE!`dnJR!*Wyhl(G>TE#22Sm zguMe>pgG@pD$o}ylkQ{G=eF1oAkP1X-i~9Ibz9N0T#6rIe@uUh8&i@=B=K`~>I|5i z+ezl5-GA=F-}%L4{^Ds7kJ@&3Nqyw5~xKNcQaV5N7IoSzuKFbFo2PLujH*8C&}?)^s2C%$Q4gmZ3+XrAv;7w}W*uS&eu zZAa>dZ~MlvBaMLwJ|xADP#-N(b7S*ulAzs9oPSnF9btd^*Ws&;biPcO58B^8!n$m! zgIA{b`TS%&1Dx`1n!k3>hlg1#>2Ctlcj5T$60(1>LOx!yU!j6~;Mc4V`0v|qf0c?? zM_!Ql?ANIQpCtWPYQAnse+3pkY8W~HpRiVwO|!9vZ<3V1g!MC}un#Nl=7P#v@%k_| z;RR=;)0v~*_t^M&1#Vg#B=lUNh+gVf)fzFfxd z2qj*96!KSnMI}bh(IoTfdmG2G>)P8;k|)KVkiYt!TFN3rlCkf%^nQr2zwg&Qotdk@ z!LeT(Me{)n&S1snY)>NSbpE7B>&0k)p6HsyK&Th zA;bMEB>OoIk@&jRW(#KNW|R2JXcvSg+dMMgYxDgCdSCrT*2m=F%h(>QOxDL;S(R{4 z(jx2Q`44XqZ_ty}A1~)FWhr0xgR2q8*Ua!fXh;_F%FIo7jEj)l96-+!(% znE~0NND^Q5O7jtaF`mo^{hfCKy~;>_8`v0!t-BtO`oAPH6&p9!^YA6~M+QAK+0*h# zy!=?mPm@>lVH-`C;m131eww2`j(r{+3|CL-`4!fWRI3%3_bHXsPlg*d!)Hbg>7SoJ z3&h>4=g9kA-nN%<^lD2UK7{_wenurq-?S&|-@@x};c~tgna{ksFV7xKH755nt^DcA zjLZ+<;Bj&MtbCHr+{zl!J$j2MeiEmiV-p_BvzWf(_?h{rmg_gW3$On#)UP4kX24GJ zKC0&{@&5K=#rY^4oIvtd`i2Y~K5X>zRB|F#ZL)A@KhAxS{k!P*jjw1K(tmu@% zF0S~5-PS&$`00Hu`a>V7Yd+AnO|(FsXsl1Tjc9$AjOCr8Ns&9dH`5tDwB^hYI64&lX$_hi0s zCHw?7I>=(0ue3iXod0`OcM0PRRCx74h_4Q(+p)$U(|Gz^m@mkDHeh!<;MKV7g`g13G#or?F7dku+eOo*s z{m-QD_wcq#kL0hd=5G=Fy$^Z+tX6H~kdXP5#D{Ij8zi;qN6ruBbMkEBJTtgui+_K+X_E8h zG6P$NNd2$yeB~V+YVLW}kHURlOyR|{XP$|C%@o{12J=iOCB>B5I-hf#*c#-@OnKp)P z^4WpIkBa~OenNdCpX|a;4m*rbL&WhjT4_2Sw~8b2WBqd;h6kpQ`H4mTP8c-ZA^V>V za&hoHRZHf3n=c*0$sM1_`Kq!hZ{R)2ki^e$34ds*N%m_H``ZJ}+OhMh_BcODiXUP9 zQkRqDBNBX2@B5unUXDNAvq*dt9@~U`hqL7UkyfJv(eUvydA|OX9mn^<3ZV9{#SOm% zRXa7v`b+U6^e4J*_i$xcCxk|c>qpES!@g#OqwJg%A3}e%FmnlW7;psr7fAQFK=A%p ze&1Y27{eRCkV5@(6ll=Vc>;Uuia{T!^VZN)jYB}!K9OG`D zkNvX3YC+=Tz^#j@T&)gIODR5t`B{|L zJ?t*+j3kI99>D`#~~>eaTYJRtk~xI#Ls7AM;}72@i%fl_*1zY z>#sA0tUo1BG}wUi4(P(9{2{DAH}woyoZ@;!TounZo;8^>qdPk>VYm4CyLNjc{&dJE z_3K;NK=d@aLgxDlT5I(A4u-k8gXSYdnI{8 zD(;Q+`}+v^!DHHUZi0S4&gH4}{B^Y zrROV2aJ~lk#G<2p9myY~{~Uzj*dL_+PaJa`KCX(O-Z%0)tidqV5l?!FfB%Qo`ixa< zfK870_t&U0XYSv2Avjg~{e|^8MLrNS46bs~`=t4caQ}vv&Q7FC-Z!c6YQ{HTe|c9| zz{Ii}@~<_YU;h2;pTA#Y?2kdD{=Oo~9w$|dCG&$fjf>f!zDIfWLHPX@F2CeX`48ZB zkJA;^SG79xpr>}2tPg>D%c0Wg1b6VW`1f5NxDi?B3dr+u==ed@{{BhUhiIGQ*czim z<_8(^lJoOJgLi&}{5kTt98>CVLDrYw5`5&epG(#k{}cMmHf|G%4|jKSW?sG=7)tx9Se@Obf&33VPs{5KeKhM`)#9UQPp8pl{%P+}n z|JePK{+538{T)9326ujqb_GVz3U9_IzrM`qx`a)s$-UqCH)MaM>!pLZt^J4ehkv^qhr$kJ5?_Ya z8Z0$<9uixL^T((NeP(`Q3t2yE`R&B6&lCz(-!)c*F+8a=u%nzrV0PZ&_)J?ymdE{77#7RygdrLH2it zTo1>(LDi)H%kLZuozey}zm&D9fTc_?QlEZFtH-KyYd?YPuViTqFgG3* z$jb+W`n|7g19wuvm@DqxT@+sxIm@7U`V^U8KaAUe?B5s3{(!yZL7ZG7gK;@heiHW2 zf_!rDY<(+IfBcTRfZac}Q1jpYI3K}$&uk-o7Et9&@<+Rqj0LbLSdW(ShtU6pe_qVI z>T|GSrug~mbI1ZoUt_spMpAtuoUgmDYm4CtlKmYP(w__cp|{0cgqLTK{B0Z^4%PEd z$odqg9*cgt@5%ns;Z61Us6Cv_2RaUxV}DAm$o_YPf(Enf?o8@Ck01TbXN?OY@#CWN zhC49On5$FkDvF=V&dX47_cWPb*Ui{~x$c)q{3y#xX0zgNa`soG{#&RIgA;R5QPY~t zpN8GMfc%}>y!tJ~&+oT)kv^_BsUPzydb3-SH;{^a#ra3agR##OqtV(xiZ7wQUAAR0 zJFjvA(K=Fm$q4+zjxH8(c@oFH`S1NnAMot6Ou|B2OdNTT>`ywLngid5nPk4XATk^} z_iM=cij5~@AhY}fS^rIq4&uOeS?E5Io?qeo*)-F77%v?`;%{$9IaV}lBB>uw{%Fgh zzAoh5e-QG&&9On|Ytuq__|p{Rn|l>EAgy&ViJ$Ksx57EUob-=>dgdTJQw7xi11n^rW}H~xHc&W*d6u}h!i@6SCLOJBbiWg6o6n3B7QSx9=o!JDM|Pl%63->EpE zcZi%X?EiQUEaS6Cf3ahq8xjVcCFj344hcs;$&8+Mxb*u1e1FBJ#$fQhkDR<)^UwMD zLUP6dY#t?txS7(Q`v~U8w>+0+pX+T%{^@YCE&G1#oRv3`{ zaaFAzPJfKa{$o;LZ+0mv04-z1e?NVB#x&Q*@c2bozm&EvV!mT@ks2tDAG4^bFb_*5 z^)Y8N2j^0bk@?dF2RHbHR(9zv^e_!OugiJ^)Wy(zm|~xV`Af2EX&`=)z_Z)y(aU&aF3fhqQZqzYZ7WjJ#na`ZDmhi_NSKjv(@<&0(-pp>pR_KlsKVMxojzzz! z1Wq+c{QLhMF%@xl(nx<$H*h^VI9w&`&zyY$_&NL@+5gC`*?}D{FG>D2zj6nWdi}`$ z#sL+ot=$G-_^)`;A~1E%&R-_@_XU=Xg#1UyLQ-(r%#37*ZxB<_G(KYOs0x| zUy}`B&#uSu>aUPLm(+}bQD7oBLr?tsudJJbN!JdO`o1wN0FSlrlm2kx%^i5Lw2t(L zYoG7MUhnT@e!qO}9rT-FNcKm^DA%Fto+;@Mzps;JGgsM?^VL%iII|l8XE51Jnr{~h z^l8`qOR@Ied2+rW=i)jXcv?ozAC4Sw0K4ZZlIK5jPBx}|RwvKDtxF*Sl{%65NY-e} z<}Y&R^(Tb*XmP6-TecwxzOLf_A`B(?1(6j6I@BARG$EHJc0jg=?Wf_2l zK@Uj&TVIoctl>%|e@y6*jnl8&lKTA5z(Ta^(wW4EkxMV8Jb4?!HO0SwkP=vY%LI}i z+S@s^!iQ%uaG3Ob$T0r<-bvplBSSlb3o4d=U!nh>nBj=lR=MQ<$zP5;us=q!W17(4 z?Ihm8==(2nzGQyPD_lt7NdMKglPudZZw8qUh1^qT;jLDX{Q7O^So}P=pDXIs{QL3X zE7Kv>72C#MB=^@pQd@_*b2rHMOL9jCAZ$bx$)AUx9mA&I8szuSR4>H*d0j|<=JowH zLaq-W`LoQh7xT0ThP$#jKAxQ5SjSF@BtI;$b!Jc9&tY7UI6hXch54)ZiR{9gSKR;h zi{BFL7oW&Y!Jw0wB!BeDnk~tna>@If+K<8{+1Fbx_?tA}6#BOTGxtKa?hjdCa_*FcX`If9?cE_jgAAYU~ z@bfoeHj>w!CiVS0=89*rm$)S+;{3g<^Eqia||9ciXwZt(k7}thY~a0F zB)$wx)mh?;RcQJx&Oc_(V_>3lh~%GcZj)ixl*Q#KO3#n5zPo?+hVk3moOiYK=fd|3 zuBZ9q>ft9OKEf4t;ACYZnI9~4I**zY-O2Btv*0$m#ttUuTMQ(3yJNz}kmpmfI)Js` zv7gjG&WoIx?SKntv0wWAA>b#2@lmYh%fC2kGeh)zHYrB4hnh01P3-A^=TlNkcmm@6 z(AjX-$|LdPZ0d@rQ^lnJ$jFaIhn=#Z?x!9dl7g^atx5c}T6PSPL)w%6RCj|6t6Mvp z#MhDrH5R+g3!93?@wGIhC;OwnojiY`5o7RqV=Bo{N9!h|DL0$U|Nn&gW2Qq5S^sjc zgu!avN78@B>)pok4?{@&aQk0EYs@&Zzx|}bjOoOspr5joKZO42*Jx+Tzd9@zbKmYy|E-NA}nDoppiH*Ag<{N;h1KxTli$ zrmG*33ZKdO2j7Fyc$y@KAYT8Lpa1LR zmt$wkVPyST{N)9lM_G{m(`|tai)t~4^q)p?W=!|!0Uo}D`pNLn0+t?ri8r4m?4JZ( zh+V#qF>@Vc|ZGn>B=p+Yuvc5;BmP2daa5BHp|Mmj1#pB8Rf3uPd8_{hpv;)NN zPmGmYz?Ak~#+lFm`7=TNy4^aO$@G(FI|F8l;v=id95Po9b3?|9pRY5DE|U6umBi0> zS#KD5R+9RF>G@;Soaf|x(uQsOvAs!^r@tZSul+ojh2f@>_wD*O`xpNG9H-a<*sJu$ zx7p1<=l3s%XQ{E;ruF3gfZ>08uurYRNqkCJY!7xTFC2;I#r=g> z8#8wHyyT8+oj5+a_Lzj#y1Asj{dDKi#nh(>=Bmn~sa)%WwZ^mYyfMW1l9D zug6);yhnUGIX_Z*pP5fBOlO5ruetx_bA^I@rEa7HJX>BQ`KhvgF*KX5ar)1s^+A}A z>y>TC;_#njzH50b3K`F6{N1Zh#+6hxa=yas>2v7puqOGdg+UY4;}($jOWjMNS$3Tw zo0v0O6hG>U=9t+nlf;jq#w4r>K1KG&c1~IYzsFT1f2o}HLzmX|q<(r=eiSQub|mq& z;ch-IPU=JI>qmQTq20xi&?NejD0v2}-kXkosasY7`VdDuTNI6Z0b( zBcH01{#U=?IqEcRNPha$x(P4s7Lxp=-${*?)omgBZ%%r9SqDpHw)&T&D87_)80@u= z^70pe7Z1q1+-if9^G}oa?+!ol!nkpd$$ajvogX%{*PJZxeDdGt>}j_h8fCw@GWBNt zz@LBGP?ZnO<9&JagF^pS<8}*rolHpov*34kR+cTXH7m@m@Q7^bbxBK7;v zRW>j$KSS!%k4}ELJ3{jQqmA@@3g=I6v+cN_^@r4_yI17nZ+1Vj{(T;N3nSf35tr87 zpXJa0w4U}HZ1yBFzq2bdWvQy^NZ%%oAJ+sYraQU}-xS69Y2)L?I9OUv=4)|}ywFGG z3E6+SF4-;SU7tq9|e=_7H-`}c<^uGhzM;nbenk z-rPj@jM3!xZ}s3A3L++>#=RLI{P`Z)9j5G9rwsD@cUa}bG~=$3{Nd%q(E7kJ@_g** zz8HbGZClzk+4~KV7#SyypF9rcU(&Nk{;_kh!HO&Ac=vmgAj>OY zXRpkJ$=hObzUt1?P>cwb0kvOZ$lX0C-_Q~>Oq%Nx-`{rJcoXG0lKm0H`!zo4&mi}G z3aJkr7Mrr|ER)pFS?}htF=^Map;kOUd3_TI+>yjsM1N!8nw&MWa{Uc%hUbOrVe#$Q;^CNxBHmqof zKk0wp*>-1(*Y6?y@2J}ok#{Md$3H@RbhtJXeFLwM{zBJp5#m1FA?tU3PACrA%aZu1 z+rJ0icCASKXmq%Vi$xsyJ_8r~3_)vb$^31IhAF#jdX(fJkBjrzo)$OB`g8O=(CtkQ z=`Y%Pt;T${XJme6c+eLf8yiV|xA|BS>{e=#`D?+MOl+Rfjl_>?;W<<)59IBi5aMTX z*EX!BasXMMa@%xg{p_Pie=#C$A~ai`=k=eT3ixBw<{Ve{Ehi9m*Ik) zc>e0qavrNXR?gecAk4>HYGat+LUpF$v``d3+>}_>s!W~XbdD%~ewYETdYmNrsi4Lh zhK1*O{#1tX>woIoRS5h1f~E8oky!{@0e0f@)gQKGniLZ-M zH=sJzoZR2}a#c4rcIaMYEfvStiiIZZ=h9;cn|)B{QM1UAIqxuw`H16i$w7gurHQ%>8`=1g&h~gkGTTM$hUTC4CTz4@HmuFW@zIbwm({(#P3p(mFV0xq?g5F9{Y9&garzZGUp}?{9vsqd zL-wcrHIk6;q66xErXDhx=(D~jS^uAT*J9r%dvgBaVC&zQBI7~gt0-KR1;z)G{v+Ef zmbF!B$8KC-EQ&9`53$V7w;kKH{DdgJ`b@Tlf!ReK{|NQN>$CP)eEvFlKL57#MQqJi zvVYXFRVe(66+rD@$<58fcfTPdz7n__*d)1QMdce|J-V?~-C{}qWnMjs6>iDF8%uF~ zP46?8y?lEIi*}0plTorjYSAfjzNYx2Ga@fMB{W^3oUP&a_ zt2QM6k95hytiYjUewLVW9aUGyk?;TZ|4@UCEoPDR!A^M;OV&6J_tnz<$wK|K=l&d) zhzb&4LnHw~&BxOuz8nrX!$tiO4_`il{VeBnS7AlWYm(mzB>1wQp-1}PXVDpm-`tzT zmz>KlTl~GDy+QiHnRSO*K}pkZR5y%?S_s7U!__MuCAi^dvG|8^_tP1`A(MB zHzEFN!>loKX%TO}P3VukP3!-ZcBiZLO$MOEN^nO7h`0o>$?VZCuue>MO(In1a z4#j5BTzrOiKT)V3yk|J0Z0=(ozJ&e9{Y5KL|K|;fuj45`7?t;fJijVy6S0AlyuU}} zcWzxXpg3J0{+FftOt}9g+$ax2PYxsN1AFrmj(t|+$s%!mZ&sti_Py9f_J^ld#j!DY z+N{Ta^SMHNDHU7ceFw>Y!TH!B-wx9~%gOx3(K`g1LzT$-=Q=bJi?*nf`O4(` zXVE)mI5~gwox6^KmX;*`(6xSN7vhJi_LRpTAJUc($~QE}Q?~et#i8rgyQ!`K&Pi z59#2H>W9_bpH9v7pTFPoT8j`k9a92z|3>3{1Uf3WMX$@v`kbGyG(EkBwZRiee>U{w zQ)m@9V!|Bp{Qu&%pD4QEMV_Ay&yAV$>yxl~Eyc%E0sqLKbz~!++(+mXaeO>~XNF_b z&yn@*l9Lr)NhX*odrSX5J_7yV5hZzFd)zzD`H=MILjAPV)Cbdd|0eT0tDJP)UDSun zS3VV=MJHKfvOg>DEU9lkAw2vD?;kDw-Gy~d+z0sq;`nh2nSmhNJG}dwLVS$NU4V%{ zpOE}}`gsKI*=vyVk44!D_;S4?=4eUzQ|NDB9lC~ng;pd#+_ry;M_=Y3Yoa(l{ zU$TGwZp~Rdl^aRsE2p5sMy?Mf>yzr`F6{N;1oRpujxQ7&vwEC@YG0}T6zYQ^t~0Rm zMy|a(KTFtQ8WMY`H3Bi!1;mgNc`=&mH;co&SZU8Z+wD?8S|iRDvqz| z$9`Z{>RJ+CtGha~u3lA0pC!&O{XFB@-{cM~^4D@vd}-g0XOEORGLwta^C9H#PkYSp z>S_TwKWTA%0*ZH(^5zSL_!>OO6WjbhkonxTQ(N#ftBJ(d(ez;GENuyDeq^NjS?K7D zBK^zCHrFt))Ec@v&3|8h|Nnkl6*ks*JBhFP2fDDp=tQ#q&HQ4_3=W-!d#My(J_7!K znJ@$M6Yr7vKvCm-JV~h~`wKOzBY^IjB)(E(6JV;-h4e3p4(ZsQ+>i7x+|MU4edt8a zKU{YF0q*BI5`WdL9oeHdkC3uo9DhwE@$8;@CuZQ}A&S3Y`uo_q6`k0+6zTl5@cpwh zoe|N0>3{tgBNc{XCUFRLnW&8ed5<*F~ zWK&AYNJw~JRAjUyN<&FeA&F>Fkwcf_b6n@8daoL{-g%Mtr)qptVBJMC`fdAr`Ti+0PLFx4+(Op(s$bbL zyB8;LRYhEX;q$Xv+6gY3MD=gt{7HS~WPI~_N&2TxQjs_@_zS7;TCSN;e@F8bth^bW z^Yu9X61@3%Ih8#qSk#-W@2SK;!R)V-$^O;Yd*89ZZUIJi6^@_&x_NBDc3sxtZloYT zPFh1@EOUjUKU;YIDE!B0Oh0m$tgqbZ8;{v@B{5vH%|CJdwZ2X&4nLKL^u@OL%dP+B z?>>Pd=YeGWN=m547MWqB{)G3^V>kFsW&^1bu`vzxeif+{IoC0V;4j9*^5cy z_`ug6Er+2kVNnoSU)il}$L_x_CHdN06~JzEdP>eW#msZWfrsU!KDj>(MEfQ6 zq<>oQDFWFk-^lv!p0qq9&NtxrcfS6d_1lfjWBMRM-Y78H>EyOj^}ME74Cu#R`<3i37jPaa!)(|{>Bi1!=w`8vMc9j7N; zg7FC?bd&M;zr|LS*qejGcB?&pfCBjelE ztAR*!Z6N)@(kUqjb?t;DYlY*RSK3;{q-l`#U32d|#D*J^-{)Dg#FJBRIR1g( zf4T0Ff|1=7N&mEV@>&cH*Ch4ni*g>W`xtTf;`@hnQ>!rW+bFU>^}+NpwmD8G^=r@M z{>)VE4EhEN>zD7EaqM@@3({X*I5-exvoDhMyFeRvT+_J8;ftTYush+{-_T0(rMzkp zwnnwbuHRz)=g-HVEGxq3d6uMqx)pRBHVZ-W75PY>Ez!#$?)}FPU!VGQ^Fhe2N1XjRe0~yT15tYOEm_~I=)4xXrdnkEe~DxszD+SE`@>(l zS0Se7XmY;JL*g-p?+GFE-z`neu(Df1`iECfY}olvB7PKv`8ldKj#cEpB=cj_nQrhC z?N4soZ^q~2g8L%;9w1HnM_Z&oN~1GbA32y?gl}n9Wd2{HdmJt)qWi6g^UJ4FjxxwR|wmTy#ICsW?C7e?L2~EyU$| zX;L2+|4l~ljm~8Mq|u`YKSlE;)O@#g?J*Q=cOm&;n=7H%!xwTg;`|BV*4Jd8=&;cP zcX8%V`0;0@ZGYx{p^VdCIl(;aZ;K_%(W#;plM_T9f^e)&CP0baSvlJ(_lPjX=RmFA=M zZ6OYxup#%)-Ol}nOP+~jeO;|ij$QIv$Ju|yfB%a`_oIZ$zaZnoqq`H4Km8NQ|M$7c zSP`sDzW+~6YefB*ZunUz)<6FKkMNud#FhG^ohws1AI#pnT zQUK{c3l$zBFLyS%e<6NiH&z$C2WQp9`3s*P3u7C$W5^|Pe)Ujux{%V1o| zyvNZOzQ2DRFbk!hB}sh=Y@84IGje49*G;xiv_Hm<)Q|WzN72#No$OED82uG9hb|}k zZ&@00EPTOwOjs(c9|3~~;Pmq=f<`O)`CN5rITn_ZO@9B1&DyN1<6d;RUoNii@bq=$!~uv5yvFfY{P{+`#}h>JFU{or zHu+UEA(z;W)W_U@Yq0O59^#FJ^`WMD6J&GE$oxHQV;%0Sib9=Ao4@9s?@zk&1??r1 zNqszhVGO%v`2kulgx|m3>OrtQ^MLdI6L|Uiz4#HR&U;PzZ*_(FFwj#V^RMfo_pdo$ zjnvP}$-59&Fo3Kt%cva1>J$(1{a4(+j7v=u$o(o_`#Z2N4jYh{C;a_~7HhL)<6?Zg zBFx9cbkX;fT7k~-!trJF14G0;_uCz`VT*UQwp1jE|yXxKcnxb!~Lv2 zZhmR|ez@^PXZt3EujozYcRthV(AX)Oyx(|F)E8J@NGAPPJD)Ku&g~=e&It3fw9_D* zD5`UAlosm;pC6YYBQWP(1F0YW)8a7ih61S{rM;KqhnYH=zrVa#f}2}CNj|&}UP2F- ziO5P8_V*>@JFxKQ8=yU1%!dST|NPL&+AQZ=G4>o0=A$~OAIslciB(0ye60FukNi`j z^9jWLeMO_kL*_vX*rka!barD$%W=QI2ARLvUr5KEDg)AgJ4KY> z^(HT}|M|@461;sTAt_q;{eKwHfi;}jh~Mer_s{o_&4${nrdG7SfO!AoW%{wE4OJ*k z6@LFNKkSg&?$6x`C5p~h6aM>>`X)Ge_aXh~ z@aH?BykH<1f8Q*AfX$xs;3_2?f0mv345{9!r2kqU?aO>(n{aWlFds36qWe*HHj?uv zgPH?iYt>4AAG1#DV>OkesjIXkCJb2fa!C&~3hm8$p4H4ifVt!K)7s zzSEUS?c9&)xx)I8Q)tbOBv#{Us4yQbb#|Dw>K13diSIvZ*Sg|||6`Jmg;6uGAWE9l z2k(QiNcZbR=J%Re8}a6OA3RGFAW`lq{>?Zo-vj^zA-cE1OBl^sj^ld1R&?JKFI zKe;8}fgM<}iHy&B-F;c|;m>%HEX+?+{&3{=^J5(CiuwajIQcz4K9`!$z*}<}Ecqc^KbG-|#pzCpBtI)RZiJ_z1*tFP z#ye4GctS<(~ zh|W$m{p93#{Qg|Uj3h_}Ymt2TJEmjGEMxL~s@2*fXg)BUj8CIxUqp}cDI9;o*O%@N zU0Hs}LHwO3tS?=gtXN{&RkFSu|9UjL-tQ}!|HY};AtClQCqD7{`D^S7yPHo*ex|+- zg-3%7R;ah>M|+Nb43~(-*jtKZesEv3JK)ek3pzg*?T-HT+6fzHx8+aV{T7;mO``eR z6{J7;9VyFJO6QV%toSwzThl+1`jOEt0LwIfllpPfIthJDyOMm=yS94)~=#+RLCTZq<*S4 ze}dX)`u(Ol%Ce+Kxuk#J_C|{t3_gU?Ny6Wc`FdN-8(B-{Z^omCL1yMB(w~F`j6+wc zKhBN+?hoSUcX5kWL-~;j89%zIY(&EwOHx0l9=L!HM!_8a%GZaj>i02u`9eN ziWT!ZbDgXYJ^1Ov_AYP6j%Z;%0&5xSJ)b-0?GWa}@JtLoYbufbrDY9?i2B-ipTpXue^1(b7?V|fNPqrO^#XRZp9X7fVg0;Z zBf~IjGfvMH_6KizX|V~%4{;*E^8)o!q8XIG)^ttnau6ZNQlj9z@hChZgC;wi?;t^Y;5%*^`m5|4C`o=k2+6bKF0jiWCf*1 z@LpY5KWs$3PlJQ^$oQe)%h2%crSr{KVt)AXbyL=KjP@7ZpEpWaKdOd`zMtD&NdMG* z?A?hPTopHw>;CQ+V`pN7Kxe9X~gFDI9PJrL`Q z1h4CcSiHy}B|hV&O#M6=b+mt2t-Agmvg zFW!aOxb&&4`HB&AK9Olw>Xb0GBZ)KN0=W=B~3PJ>@ft@3+n^BX2Im2+$Q~7O22A$ zsCh0MwrJ?T`5`rqey&mJkF4cv(wNtPl5C=z4pyTP>~Ah|7XNx zWPhUhtv@#TO2ILvEk1MiC*-VLhTH-@GQYX`VI}63^&<6W=*@G;9z2WWBkA=W zY}Q@M$^ZHBdDue@Hhu7M6#WtAC(qS_{a#y({ZGX6{rvcR`CS#uQH^1n(}nq&7-EC6 z`iG>yalG%0+&*u}{P0xBG~^EMNXDnE8FNvXp-T4u{ z|26Of%D=85>xUH)((Hpt0ZL_sr!(6LY8mp1^vV8Tq}4Xa zU2`Mzo8cD^;;Z*q(%-*pevh|1GsyF2o!q3^xW)o9eh=R{f;H{_i|hx&?|?JU&-3%fvXgv(e+9esJUSxsrak#h!5VmCw&9SwF07 zY7c5Za`xI_9NOE7)Yo{EmFV8xob)dtd)LGNk!XJrp+7lK%3;1Eg5!S^oVoMSGY{9I z^yxCv-}Ua+mvs)ghy7{7`tnM41WOn%!M0`ye_v0lJrHH}lZ?;hALn5DdUaA?7B??N zfTAHee-v}N06vvN$^KM}>p^IW?l7nFgZtatv#e>`QTJGUzLnp98eO5z`sSU)$Ry$K zCtRc-y~>|*{2BlKpL^Aw=}_g-N>^v*d!q5B6iKfYD&fr+B?Q)=>J|HjV`cCDWSiy#ehenK}%biZMaAvwQz z=lcPK?ii2!m%{nu$s^_1ZWPIx@8#>SLsEOz&V7eyeoI(CUe8u%t0$DAF;JMFv)!xM z_B{*O+cIH&IpWa|=}Vq*@<%>j_xFxL>h0&sd7ktwv;giQK&co4)lS{asA%0nA)Kfz*$suH|Udo`cuVg#F!izxHf_ z=1wxcget4EE2^h3*+Q6)QxR3H&&EaU`4dmU_+$N`iplCOX0Oh*@y9(sfA_03KIc9s z`N{9^gfD6zNqy=VHWi;LJCpvVaQGY~cxaOSf%5%X@C+G9>dzC$0?`UoPm-^wF1Jw= zn?#_hb7c*hLNxtS@WWkuMPn;6n-%{Qr+7Cj^7r)Us0AJsUWPMZeRv7|RqB!xLuTOqoq}b=} zq8Sb%zR6ryV~gI?{B>`xV$OHs*|}NXg8UWtt!9p$6PUu@Hh#JMIo@%^(~+M@zK(|n zAy!oh4*kXY&OiUyp)wND?=(sOxGXaZsW!|h;?{@52%%%UHA9&}lH$1b(Vf~k!{UCgO z-)B4&Zs-4U>g!v0_h+{c^2OU(vY`6c>m--rQXdo2KfU>$25oN((mzx`-;bP_No0QZ zc77Q`%|v&A5%tyfSEQKJqFrQuE-_4v9f&;*^Yd-`#qHmnnqJMc6qd05&xQ%|7rns| zb}3C{ep09}+C5dRMD}Oq1w`U_o)*oQO%~+LojCnFzJH3|vlVkrc$0jocB>K9ZbkP) zn6;fx=hojppAen>nvezUxx#!M^X<)s+^)lyt>XSw0&o9X^D{4&vY;J1d`rB)uZ+jn z<4M*y^6@3-d<>tj8s(wL-6nw*|K^+dd~Ngcg}Ge^j=u5z>Dj$YpnBDWte+jcl!hs$ zqWvK2g#GEcwfiwCCXnPyU%d)AL3E*V|O`u(p_k^YY}ac(Z*N$zS-5TlnahOzscXUHlgD{nnHEX0pzU-LaBleOttQNic5x?DHcl z>^c34Gk?M7t5$O;RH7w8-A}b-%V^~9>_F<*>Zwa`aej9)eoF64!(AgQ(!b5>(%Ho{P;`MG}ecI7r#*W^62$iM6-)H>DD{SfLWi0&RNI|~r zs;{s)1VKTc`cqex ztvI=PILVjZ+cy~Vd_8>D3hURa0a7fwV-Xg-6V9)@9rR*#s_of?9C3W)^L0GR3WOt~jH6snyKWTnm4LFOBk@Lv;&O-NFcyKS7)OY7V zRW`q487^)X=I3j%87q77h}8EBPv5Zdj@j(vn#O(el`p+2$X){hd`RQ&7;LOzQ9ZK4~!cXid)V zjP0=wN%?@n6mk6G$N$#bXK*|wmeh}c&bRP8Err~_G5nhfixcgi(V8O6NB>J^?0(D> zj=$vBXTK#ku&8m_Y}>@Qf_z+?HV}KPo1LY*xAj-K_t&At4O>InarofJ|Dh`)us@+2 z>5rCvNWfcDQ!@UqpS}gX6GoE#!Q#+;7&JSG+~2WH{tZStZy@zWCbu0^2-%IXg~I%t zd}@i4^$lcvTGe|r6x9_t{XxFJ(aD>PkZmd?Kd&#R;!JWs4Bso}gI|9$Gg^m>RgBcv z?aR)3BL3Y!&*$UVVK1g6>an)f-}w2*p=k|l zq3QmOs_8DIf4pgV1`}S*C+DMnI^D#mYpJAuIY+3lE}|Y4rC;9z&DfXRXK30Y z&X4(g{`75NHMpnj* zJwNoEe81CkJlW_gwpv{k7!0zQX#nGsqG_FWzzd5uY#bZVphG*-G+Nx-<|; z6>4OEAbvtP%rDY>O*a!gKUG^&f9fY@qIJq3vOae&?KBSPE+X^$hmtoiaDN)!To%{Y z`SUYQ1-+Qkt`|7CLReoSq&=CugDlHv{+D0y>LYW%zGmZYZemNm3G>%|$6yQ%Xphi4 zV*V0%`XjM>6#8DJ`AZE7gYqw39Gf8aU;O>4TRJ3QRxdMBzs!H{#j45E5$P_>SN9A_ zHegaQ8Q+RamD#z@7m#i#%+KiB0l2pR2ibqSZybon{^}$jhHuuw+EDb2i2W$7YWWD! z^CjoIt0uEc1OS{Qgsl zU$J8jn^@=hZv_3bQivtmMSpO<+*zDo@V~EFGX`V(+x9U3CguY?J`U-R!t;KeIQ27r zf9}?ac+A)BP0r8g{Y=424Lh3J^9Hw{|w%Kl4%zv!PiiO>@Uqy3q#dYJ#s!k zee+t#%M2m;dwFa#a@&s~o7E4NyfK|IU@c-bC7N-tl#>wz1Ww-ugLg!sdXrm zbLhaWZ}9ZT|MEz@{oDze5@Npid|c`ukC0b1AHxe%a9eZ+o!Vbj;I$Vu^Fm4eShW8X z1`moS^A7`gNjC1@KE%Zf^HF1@%qEmxM3{*%A6g>^KtugE=l%2R6VV!j;j&p8O)72r z*p6eM-|9`m*aI5m{6oRjS;#!8Pv)ofqS+t+dqYV7Gd^lFmMi#?`t+;v8jdBcB;!w% zR6PQea!Eb{r}ku(1M3mV*-y;v58XI1lxe=`z*;JV^~pER5|(jI&bHd({F1LftGAED z^vjB<@fYUjM#5suOfx6r%M8O5tPHRx>+|he_aI@;43eM9-ltHnlz`xo;`q$(KN{bX zU>|b!lkw?WMHeJp?Sh55ox3ehh_=Ua*XPL5_zras^`y7U(I zFX#M*vSD-ONIpidvA~tuCg*Mc@g>0;d8(1*Mq zRlj!%W~B@uE^{GZFBkEx(uNeBTb=OY!q?0;xaBb0nBs&jV<67uFx!1zp&O zftT^(YuoSK{^309LAZEMhK$cnK{H`@)c{>w+xX$0e?E941A#l-$^Kv5jyz;!`jhnw zjq%rz_i+_@zh2gySGct{kF1Y69X4fedo|#ux-cJ`ue!6S7CAD$lzUpBSpJK1m$_nn z;Pc@wX^(;}e>mqu`SDplWdvexcP8W0T+!W>2XAPS^@)zsi(%>0m*nTy^<;#bJCON9 z=jPow)HoB>XT|(TfXk0uZYh=xTtf1*(?)_7wj995F>QP(a`@9%?82%)T!!uOw%@t@ zw7zx4>L6J%KK<06iSeTOvPrSR{M_-)fQijevVNQsnFoX1v1ER!8g><9ZB|2Py;xuQ z`H$z*mzZj~nanTy`MI;l$?{AuRXDy#WcP)`+Aq#yKZyVRd_K}^?Xa%tFQ@;+=VOBX z2>2~lBK75a@&sIq(jxhoHZB=S`yI&mlOtV<>qSe*{VU$rmDq+S64 zqhvxDS$|sV{SvX)H=qbqs7ew|)2TGtLF>*urjW+2PMgY@@L zPMyRL&!yykC&%Ge5hIt5!>z*K&xv_Tthl@q0Tw#b6?XB$@JBEl>Hhh^LN;_gq0PT!5@;Bb zs6upqC^5ez+4={H-iKh@BF=C4^UoL8xUuae3e0(}uzti3?h9SbW-`9i=-AIWtYqZe3I5C>klW?li^e<+HXb7&vmF=gKr%?F)#L?f99RP ze=+1F^6Hk7{`Ggm6||m6C;Knm^_AH1&?j>e>!%_tWtCshl(( zQW@H0ecWc=8k}gR-~X!)ClNVo8Cf5hG5QL+8>}JoKkb^%?B$SZ^8Lpv_h9!fHX>uM z@cWN|3zqDVBlV+y*l^hISBA>LfBp^J{`Tnp3vqFi6>`eO?~fmU)^A^qsliUp?$(R{|9n1D8=gb6W(ygg;s!rZQR zWZR|+^Kmw{4}Lj)C-o&a-xjg~?aM*!OUcO&Zu#u=e-J844d^X{pl{iQn2 zZxA+8piq6+i`{RyWsYcx1H8{3YI6ke5?aVrMxq|)4!upbXrMu|< zw0DU5xBr$OpX~b&!_!)2&iS=1Jbsh{7T{w$Ytp}b-kO6O?I)7@aVNA0J=`NX{SQ7L z&RNgVFK;WE|E6dE#^Br|(9&=F`?&rkM`8%OVAqKiYYX$SW}PiI_me`{&Nltz&Nn2w zyWsT(c~W1iG6InOk>*3rClp$Xx|8SY<^QB(&RK8r{fFjPLw{Zd=|7bEcV;WzT*1xE zw!fe2Kg=V$vlkWbQBy9gA0H~rvHIC}Qa?YGGPwScN8A0K{PyK5p z<|FkI&Br(Ie)Q}Y zw)81M_8VdUlGe!<12U!1c0UbYABs}OVX%!3dj4tSr#&Y>OfwBZ>&fn9|K{}mbX?y& zjC}vm-Z{AQjsAX?H&>z4qYU!nHOwd7xgTafVgBPVN%=&9|owZ85Ba`j=*Mutb16*%)P{O_Y7avU^_b;!sf|d>^>qj}iH^J`SBvN0`1y-SP!dkqaD;ys_U3ms2g>B^d7xh9D zX1Mz!XTFdhAI|q3%+zKnvT9>te)|6HjpXy9{@}m)aDIK@#se?tXQ`6&m+gPV;Zu+e zG}6WXf$vZDpH0HlN=E9(z8-~$mYB=Y4}N^9`*{o=gGJ|q%EbLqe*HOM<4-JIbrc$h zh50F7smLCzx`tH?g!ze58_lwtwAi{%`v>8?A5qWsF@`kzhZL+vBA}ftfubY zd^xW_wllIfUa$R0&NpZu_d@AJHBNn!pFb*ekHhmO8!|r{ZI%S-zAj|_Ay~c;YbQlx zxcc?^GBl3*Ywem;EuE}4n=W5;l;Oqjou){1PO)peNo3G=tHqYv9*+Lc}C zwctPgDqJ)g33%@5NcK+>pHG8SlPTGMUGa1^ zK93kl&NqI|*aTc`Rlx+yI7z2`lc1*g?fE;vOaM+c`QDM>yh!{v52p{5LZ&)R>$r_ z{F`V}-}XctgI)A;lCNpAe&ET&W3WjR=4=DVrhnZ15$D#nqHyYQMB54Tw|_w=Rw9}q%pmT_B)O|ca} z-;+Fjn{OV$Y;!GG#A;!E8}r2(+T9dM|90$dFtn|Dk^Pxb9;;E?G>X)()7cx*JUWQ1 zk0{=*z<$yBP%3}Fzv~I|7w#bIXHq|mSbF_u)MyCv`NqeU4W6UKvMT?@N8b6Xq^>q7 z7$ZaSb#J*RiU(?N_)yKPOLQOCT!XX^OLOWj7eUKWPdI^JQ$75y-59XyEG3b zu6AU9(w1$+TbHTi`yXggfmwaCQ0gO&|NQ=3^r$D8&|@cA|LA_!i1q39mDHyvE-vgw zt`gh-L3}<;iTD0@e;LM7ermDuWySyLQ<@9cpSJGq1I%fMJuk)oK7M@rlF<)W56N)q zXA->mtX{63@cE;`nJ+2h@ssWEkGS~;q(9vqmx%hN!Q_5@xgV=gaLtGO{$9M^i6txI z$n!-?9ggDnBbu+HtG`3}`3b1~o8RX5H+H}7$UGx%k@2yx(h2>)D3bAUSGQnvziLL# zA3dHi54(EUi_WKr{RKb&8GCjWoVSf8=VQA`ZbU`*V6y)czxgtn&t@UjO8kEL{2f30 z7!PW8lKo-VU5sh#bYb6)iTUE6A2x;`2A}x(8$1E>sQVTQh;_S$kbJ&eRf4e46qM%*>sRQ?j%=$(4H@5j1{$#qQr{3|D6H@E20Ni@ zUT0FjwpdKXaOK|Qe9Fx^8}MBe<0=n}pD(|Dziz@#$Oq3S^?70M$G986i;Pd3j<;aR z!jt$WDXh=6T^LJW-i7JJiuu{X%ipdwc(T7+L_4~d@BNRT5S~7*j0t0dk6N+c5yJee zuCqqxC$gOWGoO#r^FuM{fF|esumt1wN6dTr;ruc~a{j>g+%lZ}-i(A2t&u(9jWWFY)~LZTxZQc{D##cj`*TmRL3Y{&v%eIxyW z$ty?9`$_ZTCNmXJ)Xd5L;qA^bu$ex9^p9udHeiWphv?PK!hFSD+JRfW7LfB@YhORY z?;(X`{+7101uDx+k+o3#_w)CEY9tx5=f|31-AVZSS$zY{)j*jY+aczUpWhk#d$6w_ zTI}|u*#GzgPrshk_J(S#6ddl0-ydI}7Cy8_Kz;{K|B=t1%$YIpaWf+GzvQ%Kq9c~> zkeb=1|J?ikbWg9uqc6VL>e=>ux%W5O9z23hv8g0qE;5(lFWNy#%?Gt!YexRtQrPH- zpD#cDS)5Q{&*$7G`3p*Mgzs)8GX6=l8wyV&E$sO>f64a;-FHVrWsCzyfBErmQc^Zv zkD87b9&LX=cfR5Gq#dI9jfI^0F?jP|n_?c}&?A~J@9u^yWkU-x+ll!};O);aDFD;I zr_8Rli20G=>6gwLcXsQJCR=}I-hccg^70e!@7~PweK+=_X2#k7>Vr_>#FvNpW|$Hw zg$aAb@1M_?ca=5n#meF15OMy<=c`_R47Su7k@??+DM9clGbjD6zOHD$?M-)bK4L-E zN?iUvhMa%Z4nG1-nKaVBtGZu;a%48CZ}NuC=#g*=K3~Q2v3&k?!W7u?fwd%mYH&wF zmKJ6{5TCE$^EJF~F0Rx#koCRK<; z)v~(}F?4bf>93Lp7_b8;T2QMg-jBrR@0}Ug#%U@Xf6wP{WtAHXv(jRVt@r%LpXjVO zhcCA}PuA6=8}mG}{XhP;i1x9y{Wm?vi*+sQ#?lT3JBj&JZ~Ix|bCMT(U)_z}UZs2H z|9^i9?taUrn^x#qD95Q^^ZC50;)vsJT}XZC(QypUR2!52%vn7M#w+@e{&~dTrC4}s zD5;;Hf>&b1V?R!O=AX}xymA<)#-?G>XtBQY>$8G+XVcQE}#n?7>m@6*2Su#e~p zwGra}5ud*gH>O~=XJ2wYa8mSKn6Dm4#@Cm9vhgK66z401`MgxQ9X67SIsJ7$pYA~q z@kwi^&0POM>sDsxyO9DjEP3}K4DwV35Nas2(n z^KbXVJlWNkIxNL&hdBQ7`fnrGd9tu}x~$(uvHk&E{VO#T>Emo&_NV>7`0dP%-}Nso z@io3oGue>XoFK_$)x%#$7N1u&RX+?CLFrRYI9MJq!nbi0GW8H9Zr8Y+& z`Fze=9fhZ&`y;9TZ_uwSd>75gwl=rdvL{ayY~Ii??U5A*(=Z|Ccu%?UlGr}2a2%QN2r zq1h^&{SN&3i)GbAV5-rLlV9-p>JdB#6Bdi^Cv9odFK&J3kHS*KD0q?mk1r1Ep*(69 zr@kuzE`N=~w_%inXvYL+e+0MxJMsAg1RC!p=aar{_yR|-v#>rO?0+Zza%7cIV?j)q zzm#Qe?9bkAEYn+@zs~0ICzI;Q+FjRUgT{#Y1CKwm!jbH0rZGEb67x?Vx%xJtG=$w; z)t^ObRsQ!opHKh6mdHJ(K>EK=@}uz^J;?fRcIV01XJ<+JyAsjepAP~8Nc}Urc^*ct zn@D|A*&xRZpWZ`t4`F>PJFUmQO#X>1DY5_N_lHk-55dn;E?<0qSAHQ9IimSbx5vVK z#ftb!vG<1c^EQ3r=J$`T7vObq0{TvD`<=_r4BJB}*u0YTAD2fwz?F=>q`s*dd_jCY z&6m$SM^<=4jhXZn=IitqH?~Ahml>ZC^QFY&tMHizOZ3%e)AWS-GN=t<**9%jOTCyM z@bZroj#Z`7dAp?kh(k^p-QZ-z0Y75~v;WCjCcUT^0i7hm+^eY{wPg z_V)zjbIw&p^+KC3KnQgnYusf^fv z@cGR48~}%4RnGnoKA(Ry1988|iuB(#e-mK(!<+1%&fArS-qI7u_}qEmL2Q`63KJ~E zeDU+w$dYp~?~{X!mEzy|{_mi)9Q(ZO0j#}*`D=95W7;QvBRW=?KfQK?v1qpr{+<%o zU%<;hc3vEX9loZd|FwBO8+W#Y%s(bv-HHc+OVIgEo4#`SG97atfsHg@UN4$N=da80 zWu2HWetoH6<3M)ojXJ4+M@9~1_L2td*DWz$3E=Y8ck56#6b5W%p)gE3{;nVvmP#{JwMi9v&^;N1lKAv$_dKtj|H^zL-zG{;A0hWG4eP*a}Hu{oAi4 z;_rq5!+K%F)xU9YA*WYBK-W-cSz7;9Q(97Us{%z5{!r z@DRaL!upmNq06F|{zaz0Fn^sE4nnJ{9w)!x^HtJr6yy)|B1IztH^VKQIoo)6t zWcwn8`8u!a!FH}UVh!7c`6~E3ngs^*W|@bN{L3%6_2&?ezM}o8qWeewozLON*Cj6Y zxaFqKsW0&P+Ba?_UYPVE6Y|9TsOM!Ak6e`RlpQ6~ia!k@27w>G<{Kgm-T2)^1Uc&QzGc>m5DWEejJi&`Ui344%GKoeE-hy7uh+d-3^&1fIV$ zs_To6rJb=#R_rhM{K;$EW2TG-Xa1hg-({1Dcs<63tnYVqOht)ZAUVG@$73CSK8i$< zW!v-T))!_!D?{S~(GC&9zvb?fWgpi*BKf+xU59C=NielO!hBtv;)?d#`lxLY_HUBs zM!@t~FS5UQ`g}Mh9d#x9Yl#i zng4z*{)iPFFOdGPWXk|1`Bsy4e$=+VpS!=_Eo%^qkT77~Rt5djFK&GVsZ-h6Zv&Xz zhKhf`bM?(Y-wxNzG|2qGu5vsEjJF~E+r{fCaD5%f$xr$7CBvR)BK*J{QlBi%_CxVU zI=pp-zu&8i%P_N<=Ib_OnNh%FxVE5YZ!)6rqcpCs6~@8bF}zkaglbst=M(3w-e z7uYPy7pB;9aYLfb7={z2}9r}}ed2da@i&K+1`o!mJ(b|1jIdcuP z8^rp=*Z->uWys6hjGlR7zWDzC@D~|2#q$ZNPd2BzG2>`SM%CZi&F_OTQdpJdx-!mP_&vVZ+!#aToR$S3)+ zP`Cs4{DY*wy|_(=1t>lx`C2)o8{2+UlBwMn)~Bh4eK7B@66B@}=QkVVTrj4J=4;Kh zSx{d$nAD#`Qx@ZMoe%bJ5`RDZ{qGCx^5J?V5!y;^zjNywi~8@wP{j-~|2`UD3s@XN zl$NmmG`x6^3r?3f@sH16yI%IJXH-`fwO^ROO=DbGu$&)?Q(QrRT+h%V z^S^}C<3#;!JF>s|QDYWH3>rfAXBwlEu}*F(XTFUe|9%c#i->#Cq<&pEdcgaeUtaJI zpXXgB{nIaJJJvf&o7v_G^S4flu}hZ?**jM;fBg74YWrm7pzI{_xWfE3g!aeAz^aI@$5`&jHh`2F{IQ*HKAM|20%HR1R;ep7Gg1SpgJkJ&YV_AMh)-=qt@(K@jY zthc%X z?_g(CLGq=3%$6ez9l%fxTVHuuD>et`jr_gv}E3)i` z{g=;|_H5Pl7cgiPKOeq+h1+yx59_6vTB0ytL5IxX=&nM}7d+YS45OpQWd69Qzc;%5 z> zg2l$S*fqQoBmeD}=GXT}pM-P%Fe#+@+3dF*$@8a^@iF+r8tnCoBmMiy!aazRT}SGdLi#Cu@hyP4 zhcI8OvfH!bT`x(#dRA+(KSAwDzFMrzU|gcYnP2ADx8C$|Muw{i$yde%FW7llaOzu6 zd3=ov2*u#Cp=5sfbijNlfAJ&Z>4*q`n4)?w3Ch4m><--$i#Z_KRjNC@VSca$bEt{?kK0~qifg4;Y^7?$g5 zd?eoFK+7$K^#8e%H!<-3Q55eN|NVUaOllkOKCqgMpMlE#*r8cEtR+sEKaECfygEtq zp*qkHb7}^X`lB&339n^laQH~zoga=Fv>Ph1S)_kjre2Ea&Gh?^n=Qp&tf@z*H1Xfh z*PpvFnk+Iwn$0s7_D`xadck_X8cdSK`5QmJm49@^&A~lLK6)-6imoP>I9)0B?`6FB zHgx@Te6IB*^=YzFEKYwOOU~!KnURiHyBCuByj65J&)7XFh)NdLuPt+KV9c~*q(0>i zZ$PWc6^=jW>(lBY4R&v}G_wsB?;lA3_x_gfENgc5g$_G0U6`L&zpZfmvkoW!&a6=l(Gu{$(B$4iRPt~Lwz^M&gNnp;o8WAS!UKh8XRjbn9JIPstV_XoZg z-JkiR9<8Qgz5uSi92M=>shF#d$k)RBEbQ(G?L|Gv`K=S*-JzOiiNnQWe)#^|KzTaM zH+zxu57v+8VVp()>AxeD(&4pm5y{VVy&Tbgq*PL0hTOf5goa}XSlagYbNhe!eXQB8 zG+k!BQuzHRc5z_6qfJ=-ukruICkY8|e|cA52bPm=!p86Y^WXW)1m6AfQ(yGN*5B%6 z{(Mx@8m(7!$@rCU%NJqgj%57$eL4~48)kC!iJ#wnj4Q%}xbIijyWMtvj>}J|iU!MnDb4P775=_{sX5};Y*WOCiQ^Byz8+BRF4~Q3h5I_< z-}(HU4Vi|o*50K4n5oRe=j{QcKMF2ijg^xZlkt1~j!js^BD%M0_ zIr019>w8g^6`a@V;l63x_sgvh$cyg284zj>$<@NoH_yWt2PZm_d_A^^!FiqWq`ptn zOvK=;GdcVD`TWISEJV(Y^{8AWtZ#ESoj^?H4*WC~|9$-a^gY>jY?ey{UUTk`qj+*ZOT5Y^%zB@S7hb~g zYxmJ>*kyTw)St;;>#=U#HS&CsdS7)mVYduB_DbA8yzC&-^bUV zi;Yw9dEzjf-_!Q~xaZI2uaCyrU*pO7|0j1=!L~7;+^_Ptd?Ui+(#ZVYzuh%BNCGMVSO<^X^F{m^)b9r{P*+y%evv)G)ok+nZd`I4IjK8g*&_b_`QLYqNj zwOcg2Urr$7OF_gcJRg-n?x!&F*$BfYX=Hw$sD2#gq8*M@{9P4!6+e5N#MS=7d{hoq zV<+azGW$|tK2pzHGWm`MEZ$z2kHD#x2E zgz@2=`VF6-197`>%xwe7kLT!DSX^;~bN-0$Z&eK>nbNtp$ZRiuK72kVw0FScZN13+ z$Js@+J8X476lI9{NZ{o^$~S{xbagnHA4@f@gh@^Ux&Nl4>_(IXtswoyoYz-i@!%x+ z{a?^jW7oQLVD?JF@y)=_l1+*+U{Y$r@Au1E3%G?DaQ18RzyDCFA!rV;;d~$9{r#Fx zN5S(V{r;6MN1>$uB=Y_LQd)-I*%7#GCjS2U@nNlKKj5j-4cHah_B(e!>5#+6F!shS zGXL3E^%6tkZgTb$@b$yINP@`>Y{bP*D#T^lllbutpJZ;qch0D7`!Wc?XQqg_~@!!X< zpA2}d${rPVAoJga>nvDkl>zJY@BR_Ke<%>uzWvk<$@sBbbiOfP@_&4NcQ{vn_&yn> zg@{zj-ja|M-uDS1v`eK@A=+q2s3asw6Ok2KD$<@tLwnPwrA5(F+SB*^uIqbxpYy%W z^ZTQ}&PC37?&p5)XS|+Qf1Z92;^&NH6k@y?TsqD9mry^nm@YsY^{FJkzCXDVL2;q5 z9xTNNKmIht??9DgD~?A=pY!qayJtQ8lx~yfcTOx}XJh-nw;c`D0dWK zJj3-pcgXpt6NmdS2dnj&cU9u}_`9qRDj5T^|El3L0N+e3$^N(5@TmyBIf~?$dhJ-G z$gmplq?CX7@p&q{AH=tsw!h8VLLB%^`_JA#hhS#72f^pL?ZAG^!e;G$X_nLjye7b0>_ z7Rj#@-yXsRrD9Sazw7fC&Y2&OeuDcxLVT3ec3~>3+A|Z}#QDQoVvnANeaQaD_W>^O zG;ko}lZLuKN`HI?*AlPnMtu#*{2*xQa3pVVBkN0{i&o%p=0cKR z*K96;T4NT;pZ6q(U=mYI)(=Og{z1xukK}wu%GfT9opuLa|3av5cLw&yiXfIl1Eukg zzn@xb?_fBcrtM#KW(tNr8bk7f_VIc6axeh-(c=8DNp=msw8r87Lg{n<`H0aQw_xv$ zb!-kOea@e+&FpXy`8wq|m@97o^8HWHIXT2)E!p~#5#AJt*Pnga`S*6EY>q(GmuH!-fL+ES-u&VUL47&Uv;fn>wvqhM zc<~@C)%KG0gT1;>@VRX*Ip315@CS0>Wbfdn>W?xn8H`sMNX8e%Taz(? z-H}P@C(l0f5Vf7%A-`8@Uw-_k*^q?LsjKkVU;3Pnk0IUJ-tvG{+%uFu=i?)#s2Uq@ zmqY0qXMbV+Ky#fcqxXUKkC;ss%#iJd%)L-?elTOTWsj*wWPP#QWgonmIE1wSb>rn| z|8)_0{v%=gcEsG?2KPVQ`w7o4n5ZAbIRCw5elu-Y9fpP1BK0Eo{zCjmc>iX#Q42YL zSfOXZ-cN5t;$JDtj@`dbi(iwZ==a^FvgABV(WkY#u1QS)^t ztyG!IQ#$hccS8PEjyFf$NcR5DfBVUW`sAmF4+2!&$^69R(Hv;EpF#Rh&Z}iu)jfjb zm-K+mNHtzh=6?z*+cDB48(pip?m)s-yb$pmP(;>u&sq7{0Kf7PsLe8i! z%vXxXpEqehcb!4J`5hsCR&AMtH$^ml+TC3ZBhz@2KUS%hVdQvre^ZTAzjfrzS3ewo z0jEyU_Rp*QiA4L)JpCmjm_IppT!lG*q$3$$IuE;lv6Op%q5b6@f&Xd;k^Jf$ z>5WS>-O2huuP?JvykrKh1akHhp8ve?iQO%}C4!gV2;-#0b?i6MQz zko=l4ScTbb)QQ*s6!L?Uo;kKZXXo46i|dQ`UnF>%??~$ND|fwc@QphnS9ACh)~ByL zn+2y+Gm!O;`~Ck1AHkb2>F#=5`zw9UkFP3|@=+woA@%E*=jRZfSBb-#oPCA-nYrW< zOc(qIt6J{4(Ei6`%$V8)V@7+Rxc#d~n&YXADI8=t`w0C<>%9#$tgT6Yxplw`X!0QE zLkxBN(74AJ2cAjapO2q2>!Y!!T_ov0^-8PJIT+V-1K!Fz@PQ*tcI3tobA0n)u9Z5{YFeIQ^hx`A9_aDV8B-AHE!ymwK`~%Xz^dg-xZIv@`zD}sW8sE)C%;%Y8e>3{C36sqJqx7Gb zZa<`K?1wj|oPP=Dm*y^*fcmBhWPULARsu{-5=nkdY`+oL3^&64jr9BT@uju21hsOd zr2ZT5Ullaj9l9U??e~)r?AK|3=qpT9zhRn>`1k!)*qO1f@64NT5aKU>o+5zoK?*z|Va48xrx~ z#WfdqI^>c0!T4wQu}}6PnSWkhWWsC=F=g_*iu<2mn|{b!Wkc2<++K{w?OhW|{&9Cs zfO}9PZ-2j#e>1w2;ON#;vVUw9P=)s_2bo^w^qtWDA0ofNhP^+Bn!j*l@6WE5D3kim zIMW0^lg!Ba;_)g+B(VFvrRNuf{-^QP14b%dJpC_>Pc4ceka;=_k()XG5bC?qM@x{j zC<+1Xq|f>M)Jb&%20q=0qoo`^h52*Tg&dq(mrj6G?ry!(<6A zn@5x1XZGKCST!b+`N3k3959dbNd9hFy&qRP9U$vBgSve|3>+M{0Pb$#r0jsS)G_`W-6rpudgy@=0}+^t$oGqzdp?v(}T=O|5~-W zFC6S_$@pW=-o3c9ivB(!YkcwKp&uEa0)PNRYdTv%ipEMyHQMi@_w!y(sm6ett0X z*$i~@pF`@qt$pKhHIIJ3;#q9%>B%NCzMRXefOg1vbUMx9N65d0S@$q&<0GW{iQ~uO zPe(>SS%r+hX%t#XCmk;gP7xS;$lKk=_WeA+iz47AO zzx}g<{NeH4#aOjB1~>lAR|)Z<-Y*+IrTI8Jhr^GMUoE2cL8eC;$sdaS?_p=~V;uO` z9}(u)ilLuyNd70xpK{+%$S<983>lXhX3V}^@$b_+!3rt^?MVMw+-nfpR)dURP3-wH zO_#}J{uy{R2y?d0!57~71Ac!XscIEQcTOVxXVv3W48&$s-jm{&um5f+?n6jn85#fY zn^qvR{ROx^A;rdc!|vbmjNMsz?r_cRqz%W&2%%>1> z``c`>!XNMcoUy`OB;%jA9IkLzbX252BX?nlkq3> z&qrK*_Zy4$bM_bJ*H4diU|cV%lJRGrx)CndS(5$Z_;d#p1b*E z=GUi^?+2jAVHzLD4Hshnh~*fWA@vWw{x1q%hf#yKz;LnjIiEkDmuJE2!*&#Sh~wj1 zpBe=Be}eg|xcDNBKS41D%#ooM%tIG$KeVvFZe`gAl1}zy{dTSC7?d2N?LS~g94-%9 zL+bMmvBfxLe~7HFCCoj8o~Nrx{tsO75tnQKkoA4-aUGan{krh1y+7ibq4 zM``;n3(10Eb^%_j7q|b|)2H#;fZZ=e)K9L?y$g4CMuXCCwjB%@`v(?`y}vj<#w1z7 zdy+k=zn+a94NDt;n3qWL%h#{b-f@_4W)0aNl)t+Nw-XML{IE0e1MJ5ACH+6)ZF^>a zK^Kz$o$U>=|5+a#sN()Uq5XUMvh#}xE+qf;`rv|?S;G-KK-~V%e5PYs$52u~1%?Rv_<;^m!=*e;pmm$Q;R7}I(P*A9v6i$<9{a5?xCoeag_-#fDza}WMSQIL3i*`#6s z^D}+O{6FtFJKv|{O5*3}m%;dcWH>KB5%R~qwbQU>TPS+-`k#FL{gRy>uS-wEz9i}Q z;m3!@v6-+6EF|^A?DA9CH1QJ2ufNRNGr2KpE{7teCfNDVfRywAoY36 zijg?rJ&n|-AI61Z%q$u|4bEH9L9+;9|K^v3`ulnCZsZyqA@kR@wd~nJqvvFNHTm)m zKU-Vb4UOXbvg3^|^LJez#=p1t_cM>{4?8_KGQT_BGy?q})9>G8GZoga!bpDk8XJqT z?bnj^`)I4RXc(4`{OMBvWpSzar~67(8G1~CHZw( zUvmVEbUg8|UMBHEsWXWm*ZlQI@b27euocRvx=E^YA{8gC0{H?LWrA6!+NTNQtA$>Sr-<*bQP44d# zp3izW!ym7ghm-tp)FKvJ;@6V(o1WFlXjh$1<{#<{r+tqoG$Qwmmzi;X#27V!{2kyh4|23a1-{EU!d7XJU-OEdW(>6G7Pn!&E}R4b9SK>BP%cd z{`1Z4pw#S!Efb{p=kH(pZ8{v1!_yHE!2Nwfd?ak0f12cRO4U+bsK`(uw=~g!+7M7q)ljFc6x} z()tYF|6e_qU}4NCIQ+YROz8h3y39jy^h#1cye>?Km+ubJ|DOfzM48J`+?pn?515BH z&|apV$N$3m-m9Ru*gi{^q3)+UJx+&t^vjBoXo%Z?=1*I6YZ^k%7fszZ3}*rYP!vtr z|IK8CouuvWYq0`bby6UAP5Sfv`8&s&HR!Q9gXI6_dpmIVz)?7i6#qVv@y9Xf$rWCF z5auWD_u4W`Cv_$Jw^N&R(2!+Kopz;^KP$x#zkZ`Wb}qWT zUdhYPh4tMQpL9ew?jZF+tKJQGZLTN%|NfCT7|q^KvbzU2A0*`eE9JeJv95iY_$OTb zPFSA_m)p;bx2j;G>T3S?e5P=})2!j9u-!O_JYS;J!xmG!xs&nb)(;=NHDGI;M1I!K zcrvQP7n1z3K5{vJhNnR3m^gkej9P=l=NZ^CNcxKXg-4uGR6d&27d7+eAj&L`%nL{biisar;n1Ag1l!V8DTS@-NzgYy^!ebsBi#x}}<4a_;31prOBK75|YfgyxJQ_@Z zIDcd>n~nPUaio5zSet~=XX*F9=A4Gd`8&z@qk8Ka7GG*0`NgNS7ZYV@&FilU`J-Cf z1XmLrNq&6X%Fc&*c<}bu2wC%bW?@mkc&#&J+PMw8wIdPc%i~D}U`d>9$`|YB=i?sjKo<}jVk$!(| z-)oSKe2E*2#r3DMaWAItUTY?}Ry@80t}}*i2PYCANx}V~Uqj<#kCqqq)dk|(4DS7e z_*haL4XcoK=p88iK74)gQY8uFY%@uIC@e3;j%~+DerW68h~=$q80q<3VSLrpRAdIR z_kUCKxfgo&!^DlAq`tcF-VqA}$CCU%L1rRG99#^|9n$yX+ux;OCOkA&!Rg2hVsZYCRYctwi z`Z1>G#PLx#)EE;goXGxR$7*(d`)d%i8o0k-X#bV>qA>N~I_M9VejmR5r?f9bFPRgV z+gn^ec3k%g>)qv;k=w=VC+futjQUVb(!M8Ld&BFuEg9c4yE{UrW-M7>Dvz6h3yULg zwnqB*^X)79H3SP>SE03@dw-#Qi@qmf;>AoT$Vz{nuYc~#jr9 zPMrTHUAuyBt6q`%V4e=U+d8cu>Hnj0j9}c~nXKQYjIzf5pPsz>lZ;@$m!bSnG>o0W z(+@)X&r*!SCL?yoH{t)yg#~z@d4lwBm0K^dWe0nI5z+r``7O`%nWxD_MsfN;IR9&K zv@gp1hm!Fv?BO8%EE&g}{}ASnopz1KJ+&nyzrRWh!G*`Gpf;AXuP}d@c`*?MVQdeN z=Q@<;C=Fmv`_mxHR%;yr;KZb~ZpNYjinGkgw zrl?We|21zKqUUI5QXjQ;@&wtdC<-R5mQdiRuPsQUOUKPyywc#-+b+BpNUc(*SZpC>x_VuxQO>A$IJ!ML9h zPv&n1nF)CCCX0;EKI1l_WXvAYe><2Q!kxo6$@<6btV{T%(?r@o8ZtREfu%l z#{=D&-yLn42v>3b^*LsM-K#;)|1I9y2cvd)Ay!wsKHPS=JC3n;#7Ogd2>jP~Ndyi> zuZN|fxc`2L+latv#bo~!PWdo)JcWXH;{07V?*(N3lV_y+m4y2IeV;yfG1{B-?_P=y z_>oTIkU(uoHRE{O=TMI*ar3k<#bzF;gJz_t1gu{r?_M z)<>LW$6}pv6zRV{5rMFtn}9p2QvC7zFJ&R|nCPEP+Gp5>4d|IuOy z5_s`f$log8SK)pIZU1v)H(;XrUNZigtT=!*nYYRO>BX80DA9RC+P^ABmZ{3nV*Iv= z+yAC+H>R$)Ei-(9)W7-X8|E13W4+p7-u_LY{nc7skvDu6Pd^L&H*N7kOc}8OK0C$j zdwhN_YS*5|ect{&zI_iqKaW*eZ(zxr@8I*3mC`fh9#&wa_qzz~zbiqL**(veIp`+- zegn4x87=LB&?eC8B<dx zGED81?##&z;`V#0s>xjMVaFuLi{n?)Uk@kP{iM|WGTknkk@;>>O(D zz9so7!%2qe`l>tAq`dP@ocQnnB@OT(foW%7r z#=7A6&X3Hma%4tg_RSbH^pWZ>zI~e~#9=`;ZQo4mRNUXakL2HL z3MI(Ry-Vt6&D&>@J^vk#pM?37&)HUFg!Et>RHgRi-@mrkQ-kU2)1T@6Tl$FWZ*1 zU;cMfWZoW5;xDMc7UKdZk@hppW%pygh=I~-asT|f%^yGJuIAOZg!xZ!@k(quoJ;EK zndR#+v)6ty{uB@257*8$BtI|tTm{dXckr4auCIrWYel3|Pev<2YCpbxhbd?<$@2Eh zhMAnchT#19>)ASJ-r!2^$9Ilpu*hI8l6|D#htJP-N$lMKKATAYJXEm_PQS`Y{akSW z5tJO-GSc&%LjSycuq&g!&7Mgr6aV`w@7kd04ZCBFs9(-(8iwJ~%Sijyou2}iL#xUD zgTl&{u#d_EwVz{Hz&b>o-cR-)?r-0Rz=bu4YvS@lp?+FArV8!mzsH*e;`W^u`WG>y zdouS!#qGOrMsJKRaV7KHukNN$3>iWChqWPtTIG3UeIxnSeC(}acdQZms;mAs{1{U~ z#?KF1Dxr1#Jvw-azn_i4Bm9k{?cYbfEA!~NJ#!$Ov%fGuoRi%RC$>A1`)`Ja+F;M& z$z*-=f$=b?^jc2h!|wTHjBZ_xE!R2x3*%E?g_TIZo=2Wf>~S##tuiHKejTf{kBu+v z8MFuD_|TpA2RnB4WVZT=+rL|v-uN5h#*5Do+;36)p9yYv8A;ABou34}O`S*bcl*Ed zkl3BQznHN9g;goIkW)g|w>&Gd;89;e*0-+xtw7A`W)lAgn1`^v+Ln>tKPTh|@6DQ! zk8~vGQ|j3Md-{#Z*yfs>W!{$E0BCcYG1y7+hY=o zxQu*~|8JZvMxUly(tq8|D)8f5Gs%Bh#lLVUNt+kHh4$aOLyf749l$vK+y5-&zY*`X zp+9K|>Hm7OjnQ~xBw61+c+MF=UFVbaF~>f0G4=p$--Lur3_Dec1y{xM=Y+`nI5vZ} z-}UhtNVjz&?I-JQjav;<$ogo!sW)aNu{+F{NOPoEY}!?`At&(Bx1ylF5^m$g z?XQsW9}2d&W3-lw`|r}(T@kD4M4m65f0n)9Dc7I$-?eMK@cP3FGQV!t_k;7QHDrA( zMt21^Ox#Y!?}Nva@xG*#jNe;A_Q3G|Jy@M0`2Exw?CSlI^#8lpeqgFjFP{B{{{LY~ z7v`~s17mzp8Xx%iSzLKfY`1bJ>uZtDM%Yw6iuC{V4Nf?JI26h&r2fO#_bPF-;gGn6 zjQxNyB{FW59fc`jpFeCNPVwx z@;h83d-3K+g!a93UzJgebzqwE#O>>mw~aaDQq9y4>GSzK5AZm6$=v z;`Y72Sq-gvPLNCG{(qr;yVUi-suAvF|J_z%h5qZNlJ+0oegZzeTm$oC|9-#V{sN;3 z%MkW$JGnou$A4>3lX8HpA8zlx8|7F2gX%shzWMii|YN;X?hqL|06GZLVFI4kMi9! zQLB_j_RsR<*|RT0&f;;1I6kJD)?(#)_Wr1FaeTasQbQ+4XY%~7#*OYUV|Spr9FoR2 z{`n?Fc7IEZ^E5Jk1nlv^5cYiQeH9KL!t=q~lE&lw*krQ)(@zqE2cru}{&>Tl->~Xf zM%D-BX6(Z21@}q)I3ev6+Ele*wv#x1HtT)EqVc_X`VoTt9mQ8w7`dqf8Kphq{PImX zi&MxFu9nZR8LGJ(3cy5V-Y>(lSr4&E>^G(w|eepY-y+bQm ziVuE&-D!Ukf=88+`arvBC+64OC-uScx|48q{)8)5;`Tjy^$Q9kdNU9IoqrPA_nV;# z)4pUNuYNDg55C3eV{70T_#KeGA7B4%Iz13Jzr)G+@V1Kw9G=C(Z@l#V`SD?xP6*b1 zNhA9&|20IRX-NTje#!Mg8mxMqBlY96)pv2%v^`TZL)`xD_Nn5#rZYaOaetpMenb!K zj&m11$obq%3rn=TrtNP(eH@xku=m3*aSC;sqo>P3$-hexug%_+6+EXOynSMazR^{+D=e2ZEnJAo=^@ z#1nYX<1?v$^E!RT3@aTb%80X{(7q%3C^M5X29f&kdx0vP+$H4w3zIzckhE$n0(j^9 z`Tl>`#Q`QV3(43TT=hv_jmRWUy3imh2;FfwS8NV_w*c8 z?Zx#$?@zbU>vVhO;6!nJ9B=IgnX{gxe;+lmz^f4fWc=^)cMK9@*OL0M(LWMV2MWpl zy5-o_C@Vck<_DeJcHqR8hq$M~@jC?bQ@Ji#;1=eM}?0hxb#Grx9n?0=g3*Z*-u+8L`*qUM#i32K{d!c|WAQWk{SSY0#pRZjC^3<~Ki|G*Mg-!gat7(& zJuH^M<6R*c-XsHC$^^lFFzLAzx#R}T$b}C{ns?g6*i%9WPJCH4uIRD3^IQU zT_1tkLNO!Rd2e#Z>* z{6S@h#rU+ch&*4{cfckTC0>9#Z~qCuKhve50QE_aNdIk`a|8C*J1}PzIQt6iKPuuq zszP*_7!&Tf(Ed|XHQ+GSi&x(k_P6dj^oL{9BHsB6;rxkQ(MSv}O5x>iLVahWo`9oP zhe`X+t~-K{ZN8E9dtIN7%$8&)#%dO)--P-*I=C|$uY=_88|!;x@s#nTK3D2)imulJ zk^lYRzx@?_eQV#x1v#dx$o|z!heg=YX$Q&A58iIXHm_<@pUVUmV65?DlHUTNuH#_) zj*Q2e}3}TX?UQu zm5g6Yi{f!_&tbAYqo{QR`f=Y#{%*a~f$^7j=FLY6?SDPG6Fy!Ao@7Y*hp)dn-R^}; zMdQi(e3x4$7*iQU#;<{Y7?e1zBJ*=w?}eBjOxu6wmhDIhe~iR``+0=(DM_cU;fEi) zBmAAXeUD9ei`ut3jCLLOT@Zl}ck zzow-lBG?^kQu_<}ecB>p^p6OF+&a#`Wd!@PZF?}dF=rL2&+O#c{kWTVkmu|Awcn2U zZR$|IoX{ud-(dS{U1qX}IR6eFqmE1V-nf@0ZoiYNy>Oumd;gJw6yN;(^4A7ic-So= z=RePMoQjoATgm?7!tJXNv4XZ=Lf!^Af2k(($NSZX@bmb0vVPih=PCx}bYvWAIQ$CZ z)5kOI8Lw(*QlFm=>4@sH3<{1)-=FW_`sGIOe;5S61>*J%T@2j6N&9b?%3+u?X&u~n z=L`AyiNS(!Xjtqd=MSIz=A%Bmju)SW`R5g#tMGnJ^S7V>8yqsyV;)zF<3p=T4R$+d zd`wxa4a3zmKH49!LE6S8e<4|FU1BAI_G)*Qse zYu_>Rrqn<9`P;c3?U`F<5;DGfbm@qvVS{<~M+ow3qwz*qbY=#AJr=irQLF@NpV%`x zME@cFrVoy#uEYHI9KMA77hx8LUgLL?`fcQnJj_2)2Ok&d`|CA);~=u; z{y>L1>HG2R_q^^hmi_L?D1?an_tWJ{jO#)P?|hChe&6rBkujffh57aT%Kz#w8L0F0 zO|@SKY%Cj$nYEmKg!Yd!QbWfcJ|uruxf`Nr_Y8D!7RQHYku&aC$3ymq^!M}gbD8!& zSo3xr?#pxfUx<$$n?o_`G0hJ%e&^!q&?lHVO8Wiy_|T4O!ii^kOw4U@eAvJ5foiRZ z7`a6nANc%#TDu=cE{G)Y@!VoE9QV=wE!Q)SonJUg?(d)fI~8U#E|K_fm{^9R&wr5q zUDa?23k})(C(Xt2(LqazsqY5nQo4A2R~yg)_ljJ|{Cv>LF3@9V3@QCndCdT_3xmn{ zf8T`dZL#O;sr)WZ&70kyoQkYU4j)4Mch;PbU7vU2*L@Bj!u<>BlX4*`r|sW1xDjWK z^_i?Par<|=B#&=0gAifD;b(bCF^sF?x}di?g)r960a}c-*|w%pZ+Hhn zeGxTsDVg7uC^@0u5mv)L6W|$Evl}C|B)F;^XpR6`VLXjO2gE{d%xJ z7J`H0#pC~=FCJKzkqWQQ;`Z(SU^a$U(DuE{&h8|hKStI!`gmu<@ZD4V=*rngXy4<> z4VYkQK=OZWP+P`z2t(F49pvTkrL7}e8aez3?H}f^gv1lBEC)#K!_S|zleJLF-tR~C zFXv5R=f5hV$oxV6!XVg1B#`m*-8ObVS%+<8e9?W9g4@Hckmp+(8ZSV7LuV!>L!2K5 zxvHSWe>hp+y46_^J4VbT`8{sF2iB{v$ERR%`-i*C#*}fp$@re#xB^B7$4UFM^M&}l z^clJuirc@pSqVmL|An?;(&v1A{bWu(ddxOpv{!TdFRcGOKcdJCO<yJ7c6jx`6_#JP_ZRBxa!oCKYnVjpi%E<6z~OroSzj``IS@nB6G(lX zd3rob{AheI{ZcUe$Q4M6IeZKEZ|SRC!0yL1KJ*qS~BK1KB8F#q8SkKE3AeevcmdnmR|E2Mv_i!Ih zJo=5KoznN?`~T4s&#}qOkQX0>`tZmF1*Rm1#z$3jTYTEh1kf7R}1P?&B=^8Y?d1;*|2V6s1Q@R}mjU(o!pPE!*< ztfr9pLv~AV`0SrW>ZdK)0}z#-NXGx%TfyknV-M~Ja^FvwA75baMvA#~mGuAkrI{G8 z`Z?xa=J;QzpH91;MZj!jrmLE`KKS4ugOFlJNOp?*zsiPAxL8i(V@nqcjG7ul_CMVR zyJ6AX4ZQqN=>NKl$Flc-ZNp4w>HG8bvBjDgcppDO#*Y`Fd-3$YKO{fwXYUUCyVsD3 zi4oTakyY}H?F1Jl=-+-XVg6+HTLEdEhQQZPJpL~j*&DU4vq}BbddVI-HxkMI$$Qyg zoK4z8@&j{k4O~61VP__1UtxR?{%3eQXQ{24|D`(d%W=P|`R_+W$>j zF(&E$CG}xvb~k0tQ5SMP&26y)wxqeV1qVtGo01r$YT-SlSW4 zRYqaoE%Es2-K-6_Zga@^FtgPT6AV^kEbsnaetmtIRuHcDD<=7&DKP`{KD{98BhEJ~ z&~B;<>HlL3>Ttx@hTEicVW-CwiBiory_4jyW1>4cv`YP-A3sj_?tot-N5N88`kbF% zTh8hUpJTNBr^nf%-BsHD^=${Eq;wet*90)#(_QJuKRcCiCa1*LuKz&Rnwpx>A!tWAjE{{w&O|9v4i*Y1zG` zeyGlkK&HcqjWq@@kYb$q&~Ds-er% zsbv17lxd6v(-kB?blzZt>>qS|%sw+56{m9$*($|9KYwU`orukwZjk$*3VWVGmu{-e zji2K7cl#;JBpn^X^e`2-zmaNt+K1+d2HhOuh704_u1LQ=2N7; z31jb{S--XcTG`_E+myZ&fBMQW?*H!R5cU^$mps7E6l3PkD31Sy_D%3?gXwA>aC<7{ zFFwD$n%o7l9j1}z`wDXUq1q@3JGV;h!`C+xw+@3tV-Aukq|f>GD=nFd;u(9%_?GLF zh`gp7v;4&+Sc;@Td4nD+>%8ddq(+&w$wg+`GZ@JnrlKww*_9+b9 ztjZ)m7x#aCpRbZD_nhJI?|vkq{VP`u8HUn7LGk|~L(PPFtS#>Un;y$B`?k6>=|1BA zv44Ur)CYT#`q#IuDpXr&erT7Yg=1Co5TGxve@At1Wy&ysEJB~UQp z@F~Pk>y@@RZ9WF?E^_ZLJYVp6s3AJl(fEn2cY?}576Zim)$rDEY>qsQYm>$CV?3b< zaqsE)aA5B}JPt77osSU4hk1E2c(ufn$1T@ey!=oG{PQJg7d9dP=Sz(I zx1U?6kM>_bfuKHJNc|9Ys1*$%9*kPJI6idSeU_Zbl92rJBCstyAB-XMhu&cZ&}b8j zKZm97&(E*zU7S#~V>7foIQ$9Y%jZ*JSa|a^PI`&sV{rFPsCRuu>Wg^=g)rBVWp=7c z{e$11nVDaUb=f9Nb~}z=gz@F;{x_15(;QG-&plru;f-&}xT(m%;XaM8UTeBxM*C2* z|71JQ3iAxskodW@eiDY{>?7kxS@(FnJaLP6znKspLth-nlgV93ei#_hB9UZB*d1b0 z`|$JUpi_!aG9HVwa#DT8&kq&vDr53<+JDS0>7&pqmdu|F`#ECj!_8!WHvRHYY*EO= zrZn#FTLHfRc$^8v0{t^2J~R?G;`!xQqJpJV)|WB8ihh0#AF^&fuzsZsb*(xS)SX-344*ZPVm zOQ!K7J6IXai~zDeJF8I-u5mPf3^N{t+l`ya{PV|iPpomy!`6TNEX0rX{`ts=qVZGu zb35`QWtqflQvJ%uN8P1gsQK>BF0Agoy-%n`&g4W-XX!iW}{2@~R z;_Fwr-x?^m7)sV>6>2TfxSO{B$MT8z=ue*y}TT^E8Cl3GrhhO`BkZAS?4xi`z8-n`X!KIzC_Iv;tpVvj}Ve9)?vcDIg zJPnc{?VR%QD6f#qnVn@e>Np9%O&##l;3m zhW7wmdBOd>5FbAx6tLts?LUtkG;q8%l+>pg%9iN+n#RZWrU^K6Za>-I9bz7b!Iig3 z{rSLh15TW1B>Ow@7Do}%TaA$|S*-8>07V|uC(J-H^&ve;87w2b{llg6%kbJ~^kYyUmIr|Cg7pew7 zuy3UYIsfMpTQ3=tHUNHA+|LW`Z&~+VQW6Jb7m53a#6$s3r^b=>yQY0zaWX%Qt2$8||QnZNCF zp98s#<)r?Q*|!pTlkSlB6SnNh!wx(4et9CkT=qVKwliq|aj*D>-9;Yc`5cd*&m^}G z+M`;T)6YVDnMvevy>J{RycEyx+Oy|Vum24r^PkGo0}%Ie3z^^ji1o!_ixN_Q=ryDw z^=uO=zj62%<}cN|Z(+Z+8Bd=J@$vTMTM6UIkny9W`iI1V@xr$_aeUNI?Fji}fnrVqiJo%!q?I?|u#>({Q&W6@^$9kTwD{v;PG zr?+9;%B0_iuRltC52InN8WRyK&aVd&zT)m54`z#_xIP)C{ZukIz#iufIejR^hx0=@ zgoXN&{lOM(b-4M3lkw;6F?%$rr;+@T7BLRvSJ3!)?lv3w?JDqiK8IgneX+$N6^m3~ zll|qQikoOkGb8H*4F|qU9n4&^)`#)QL2nF}mn5`+|_K)!Sg1&=28GBuE z`?sxpBYCv*|KmT#a!9Q3CFe`-_391B-L!vbH1x->nQ7$t%)e{LBJfcOncwQ4nTg4= z6`1*v!>7>xIpOPYJ)FHCk(e**xZwsSm6`F*-wXL8qT5r+ij4zMFp9&M5dX`+f0LBN zdXxIY*R}&>p9PWnwA4)vmD%A?dtdhNd?bHAg+i$*roBmKzmYh8Zmx2L1FJD9{%~Hs z0!upHCHu>#4;@4sJ$2^vR&ji+>iHSJ)_O8OI*a22$6refdJQJ)1EpiyU`?Gb89yd0 z>4jw3I5Pi_yK0A_k!h&j%)P&`{u3Ay!q(R-;BZph{uvKbQ1j(ASzqqCA_w7L+K~DE z{J86Q&}hauo#FBmAwD)F)Jg182H?$A?*A9!BlYQ5$?Mm#@!42d%*E7k5d0(yhD< zm)+GFn}7MMP`__l&?Gq@Fqn+Lh842-$nI~U>PK%LY2)wMI8uMfeYeG~YiYdsOd&o# zB?M#B0h%9b2c@8X)*Dh^?2FAtXJud5GP|1oS<#nFrfWPj?ao(WPTX?#35JQ!o1Zb!^( z&i=yw!|9u&5cH-53gDhsfRB%EhRdz6Seu(O%T2}cQ8n!&o^%~b;=|0YPICFwKr;VNcKa*|U*kj0 z?^qkD;y}v+GQM1zX^gAq){^@4W5Gx~Rw>0I1R)5QF@#HN5$5q5b=$uSI6t zx8(f4_O()6J+98|9v~in&St-q1m_Nhogw%C3-OV4ryaVd%z&w(RG;ztx2u(U!ggI8 zBI2Y!&)4TV<87cbHJz*v=0-7SXxPrH4+{O`-L61PeOrN=VdD7M)SQJ$(Q-^sk~lt2 zX?(!=p+lMA3~_#lN_;3$sd6CmGuu%z?ESvu5mzjppM`sk-&}v=r(8=8J{?U#}32lts!^O41`N?`L=oe9zrw|`KV zD`;M6&XhZg`%k~J28q6f3xb2B_T~2{mL6!4bldJj>UW>X?eNq&n2f)kK0Tm!k;c#H zML?JS1tdNO76xG2)Jl8{7srQzc^0r=j*Ktw6q=z}GL$LWBaV;p!yia=+6=^m_uTIn z>W?x#8SHvJfvo>%H7XeWkT=(6`O z)^q>AkUzGlew3WaWbcoW}YRi$`Xz5vZ+7s)WPzN3Fb5jB_j_LTuYeoQFU!Us2YhZYe( zqSFna?U8~AJ#qiAWOwWTsiyhCc-Az`_)&?5sp9spjE%$~y;|P+I-&jFzu1cJ0rE`n zSI+(bzy1@Tw;vl9bS3%KXVqKijr3wXQ^oNy?ahCZ^8SPH?udB)tFigHa&KCK6qks01cP9|6hoofe(_f zz5E@?FZzQnB6^Jl^W@+CkwX1$*{xX;eR>!fKV14K!fbd5Y#8qU7v6un_(eB#4POPj zSyFuP^~a1s2H5#Dg*-n|am)#8dld5e+d};@+;a)^3Tw&u8`zM6bAj@t{&+cQANEyr zCH2?n0dJ5O=f&)sCXSC09iK}^wR0u)*{4gtBo)~cN&Oy}Y=!O48Kiy7b*G}%ql(m5 z0|zAGi}ibQKbM_rHI(kq_8obrRx_xa5BCfymKk4DXp%mn{m*RsTUnf>LVtqs*89$Dyd*j9Q13dnOfIp*$MBt6_ zJ#xN$ghvKDKQ2%9r-m)wi;9mle;oMG1jiRNJ`$3iN}{z~(Qr=cAAEh5)c>cXwsa!2 z{_SrR&X0XE?1txiX#Yu0=mYJis?|J+E zg#CpFh8N(ZZOKSxa{59TUuNvQCs|hINakl(BHv0*xDJO+ko5ie`eNd3dEELFLh6g1 zmpfv_n8i4EOdLP1K6>bFxsI$4UaB92gv*6wefgz^7e4Oe<44G!OK&g2ey@AH{0@To zvL0KCp*=){bXcc} zs9y18{ZKQ-5|i>WaM(Z`AJ^k2qdcVw0XMnlLVVo$lZg89&E)>xX+zU-AeuVL5Lz^1O?aD#C{7$I9T=%?@^lltZ_Aj@ob%cKXV$8lHj*l_ny3n1pj_f}a zv}5HZF(K5@L7h66?lB)@FU+k-kU z4d(d2`37PAaQntrh!5~))NIA^bHlezGPR24msVSO%+H$%r^(#kFO1I{ZfM~8I2u3Q z3oO9g$sqR!y|=nmPOKKv{er_i3w{z)w4&P%edG#S7zg)O`TQWmu5TYuj zzn>qU6qbLJgiZ0ozEE-h_&L1;GQA^6e2iG4gXqw8Wc)el;fcqoWxV>2(EhuU79hF% zf4u&}3JHJy)VO{(@=7&G{i#3iC7h4a_B9;vSTfkbjm+N`=)9K5cOOCO`z#wd*v^^> z*~8rT5$gMnhr6=d&*E{wp8LMS{pZ zb2R=BUtb=V(-*y)q9TdPkcgyAg+gX)9VsPLk~Eq^=8{B-1{#oPKxveuLgq>;O0!fV zrGcbx#)J%+y6?UB_j=E{pR?}Y@5gZVe)hAT^{lnmPKzMx4*_6}a-sR?@{%7PN@<7i z(aVpl`hyp+=ifYC6pm+OdXfDf_lM=-#K99ue7x3Z#n>K8m?x_I{5kkjCCrzfL*nOM zOFekn=wsPA(f+gbTk7skFpsdoGmXOd!_{w>yL#i}`FluwUHYhk8#<4X`Sa|gh4^Ic zbsX?-eis)Xx9&KhVo)tPf6lr)2}Ao1CgV%|t~PkIU*K^P{*TkKdEUJKBMsv{e-~9{Z_&@2v&p^vlpUm%Pw|s%iS8YlEc_sG7p_}%Q`gMQZ za2)#g7%JzB)|bsM;(H7**jMmAl%{BX*!8F3zB>f3toVPt9tIiJ6{;XJC1 z8O*%iP`C1wAA5<A8!27xe$u82TGFsF)#Kdemb*+*(=G<5B;ar!Tfvr z=(#|&KkV}_E4Uw!dDE8E=l51fqe8$QGXGs=G#syO3ntHh!Sr#c_>vu8xcQw;xIX^s zqWR&x=Rqu)`iYFc_I=M|+2+BFY?9DFNkk9H&upDkQp?*50n2;Sc^zCp$Zse~1H()B)?=Lr8i_k1+f z`r__{Pgs9Uw7=~5tNSbmty(8CzLqwToajHD z()AZK&Thu+4&nE6_rKFn9@WzQ$orQQ<`2V0-(XUo$@HIwi(_bfyuGp&JKXEAd7udY zZ2kUmaERc2Xc`}L#wOyOJA)ZBR(~`5{>OR2Y-EM8OPN2-{P=mU`4mC~953>Zy*T~- zvhO}Zx04;oFIuINxIuj{?wcZ9KQ4X}EXH8+=17)4<>JSBtsc7i-M}DoAwIbJqQ=Go z$DFy3ssX~^x%ipT?SmbypUC(!tu|XQUuP1ts#An7Hh#o{9>9$mbIJJotNkUI3Fh-q z{!z=rKcGB&3s#Ngk1zcMcJNPgV==SpU2K!qp#(2X4V1=jza- zTF4(<|7Y&v6F4AMlI%aNopufjs|GVkJ|cXv@gY&%gc)m=GTzzz_|UC=BDjBMfNMqz z|NmTkjDFk>7bWaT|8T>y0oe1IAF1CjZPLK;XCle`z9QTlm$}`?pjP3(&)xrd7Cv}Q z`!hNJzxc@=oU&#T)BTr!{|(lb!JTb$N&bjQYlab9=>0#_LlP5D()ia*9g3Tjj+6QQ z+okhSrj_Q;u{Sp1#GE=*I>EpH6a0_k%D0lFzw>@u0&dqD!c4l(zyH$(ZzuWrFJ+4S z`1gO*^e14qc_GU`=I(#5KfmDA$}M=~vGDwJ`E%C_!TXQ(ex$y-eLx-GeW3ZFx=jal zC6dVdKRACG&i1&EvyTYzfhfb$2Yt)DG5_sn@_qY})ma!EL-WIajZ#obn#=Nkxbejm zUqH~+W#s*^N59^Km$*G{A0pxh_WjHxyI%N8(VdLHQ}UIt+lt0d`5+yVbbi?QczUQOmTz_^<{nzn}$7u(LFuuF_`J-iUJ#L<2!n6hR z@BggYM=*MzA;}+s&zj&^^)hUe7M)*l*7==e`V->Swvqb0^GiQGzzW1(-<`<8j zg16~iZ?gPnE`Gj#S&zCk&+vM@Fg|hfo2glGIHG(AQ*w+SKZ|l3;k<)6$)CO(e!!3C zY<>{q^oKY$%3{Mtf83!W)Q4REcxLe^d>D9!?2l6WJqgt>C1IMD=+Cq7|5%+|ivLY1 zz^?fse6sl?a^wMYEcim|&$xNVu>OP;ng2`Q&A_V%Co{3V`Tga+*XvNu&4dZu#ecp= zoveZ?!5v9aeU}@bM?Y%=)h0XKnJ(Oau0N>UDUKJK-SJ?H@OQ3$-!XGA#=oKYCFH-k zc;haOkD3y}-M$(1Xnc(y9|4zR(Z6d5vt~0tJ_-YCQRB1;^U;9+`;UDofQ6su;@+pi z{o$UEwA=<*_dqZMlBoaAp8g%0c5lOv`-JhCi?5=;eQ~UhKfZe>{QJ51n)GKP&iYK_ zM`zy>e0+e$PuY?n{CrD_ygyVEoQ`=;lbL&A{QMB0TM5d7{ipJ`;(-64e3m`A|A)7T zqi2W*8DCF<{S+AIXP;w>Jl9 zlm5|!qWf@p1CaUuZk=bq*e@sJ(~^gsknOu2WvhhW$K?<4TQb-%Ie^r!w=xFei9;ty z|8>+~O`Pj-fs9XYe+%AEsw}{y*TR3FyS|>!k6^csG#P(hynlif3r$IW?MN#Ju_i+@ z|5plZ0c}5fEN1xemGx=_mTN_!OqmcLT>q!OZ5BGj-ojr)gy);9FXSJ(W1qTCGQU52 zKMC zzWd1ddH<>+&Pb;DBXyW2dM94M>#Xl*>yJyTR}1E|(){uG_hFp3UYg{O#7)uocEC_p zeU{6wiYFgq_a;+jT7UldswY_v&X;L^amjoMgY;IB@ul!tA9UJ6f3U+~0`?i5Oy>7l z&GtC>Q$4D_K|PGkX_acDhV|HeZxCo@0uOhby~>JT>daF z`3vR`X#UtLu7F~FLdg7n>zNt&er7t!pBne=@Q-~1sXu1!4n(U`nm=NWoWbR*hcc(0 z^5ethdlgR1GG)4N@Z-ZVs}!`iE@Jf$ar2WQOKKp;$bzi@|Crtzzo!R~{XvEL!_lHg zG>MNGneq6ONhagxbt^-xO%uF{%DO=o}(}3@W@$1*2ha*wJbtqZCfAX>tn}(S&c9s12STUmnbhQ_;>f2m=JlyaR z(g!-R{2%W5Y1$->U;fhk;h{MUyL(3C^cW$(a`lJ0%s5nXNhafOY5#?Iu!827vu?XE zJCThKZvXPWYXNxRH+{YaO}&bbpKCKcSnm_D>r?v=W^_x&qS+tiF{PUXkP#9oh~q2~%xf9r&N0BKDpl3%l~OQA6YlKQ*- z`54^lo{S}|{&=?jnxJWbFHDQE;-5dn<%c)#cjAG^Uon4&h#%SY>umV|R9e=Xk?JXm zFYNn4Uo@|v%>*4LewFBV_Wn0~E&>UE`h2)9X@t+mSCjeOI-j4QXS$!{hn2_sqhdt} zS)cl|Q5h|)qe=Z9uy-0x{7&QJNw5{}eAIwncJt%I`}%2I_G~CwpWNAY2b=^JrnZX+ zpDg(ymU{6K{I#d?@viYb3|Dhz-4EjO$B|}9^l}I!^@ol97*rpVLh7$jSwU}J1dWdg z>i&ZM*WP6Ql|3a5e;w3e4jka$|3gL(u{)MNA1#xM;JdXk8DFzP8eqqUHKaeh{{9aD z`~778lH(_b0S`k+eOmi$C@%Uhn!NwfXT?-xR5Hl=Lz3-EJfYV}^2f}x&KPg^jTL{n z{F;(^N-)1%ne-3uINkx2U{Kpm7~i@4=^IuBw#6&R_`BidTj<|J^NW+9{@dXZNcztY zPy>Tzr;z%iGF%T2#1*4wwGiK2ewn-64F)@OtA}iJ_jLwx%fD`e+7>2 z(}-H1g}-zCvl`Ds*w)aS>@Ta_Qig*I%$QF~{P^)xx(}`z#yIJfFn{6V$1&s?f5F;b`cr z%<>1h`R$@t7tyUyhiPWLZ^4egD!G}^t;nFvEz$n4G*u8N}&1UveYx^dwLz&|0BJ(C)#xclKC6+doY@N#*qH9nH7U?T}#OP?7Z_< zbUyM8EmB4K30r?{{~d;Usr3H8>`28a8dI1xi}>U3*#(*4@R?!xKiv3Xc=92no2(?~ zj}@Q)4?HTJ$@qp(nn@DP4KB0In9Z9fWYR-}^kD{EMWea|#vwgk7d00$w|Kp zIinV%QBTqLvHRmkOmBrtnmft!m-1H}_kkz;<5~UV}b^>b{3-S>t)P!DSm!>%9t=uM>H_sewzIczT%M0 zPru7^VO}=PPw!h>;9lNNQvdZ77st?jhspe4z_@|fq!LT&1NQvIuix^Xd<2DgUS$1Z$eKQQ zd$8br2%>(`TCIf|DVe0chi4{u-k}Lg(uDiZjX(S5gy7!A!yV$Y^{;EAp`cGZc6>*ngEa_i+t{92O@26t&e9`)_{i)y!b5L&&jgLNF8_=!j zJNDSmj}LVB#+e25`BL7Tguzu)m}b`eRyKZ$A7#TJ+r`-I%by=C@q7#tnGWRrfkB(w z!P>)%%nzpB?2QL^g^~Ri6^}LXc%R!OzbNT0#b2wMaLQuQ`myg6SEmE1@3acv!{i_@oN}38-z+MWM)PRF`w>L{>r`_EY&=f$>(7`8 zsH=0Eh=RaQw+mGYZvSFk@bxhfqIS|>vh?xrUHIiY+ zpP@Uh!?SUEWc_huToHI0S&{xkLCkYl7vw_fpEckAg7uHXWPjTgH5Ebc`bEr?5S<@3 z|41yIg*i%PnAThPJ2yUwR~e{&uo$P*K$tr$) zwE73*;Kb$%(IfrM-NOrE*g`9^zdB`a6LjkC zBI8%r!9TFv;0UQ-Bub@FEQ5~!>n04xT!)LKK0I*I7&V4J$MxHU_~FL?LY@6M)FL+cK6W_pWAU$gbW{IuH;@3n;Vwbr-2`)2rS<+YeeFDvL{@WAAX1pM7xoT6l!4Pi_vB!*|Q$$oRB${22VvCyR_v{denP zsb3j+zh&qbdlYN@fo=cZFGghht4WuS;_9t5|D4u2iCk4cv4 zg6G{w$owEQ9Ij91Waco<;J<+I!Pba{L2Q|1Gkx!%gG6u`uB>KE@vNAOzdaMHiXaJYkxUzao4toIw)`eg5e z1bs-)W$-O@BgrqDzP5nUZEw<_m~cn}E!EVd@xi zK8vg`l>S}q0a zz4-CdU62Zor52$1WYPbhb^OJaKF9^DVrw#gkYD%|ib`BbeR%!gSNNlT6t!6MCE4?L zr#$J4wS(eG|FdGj5d0ZI^K`@4?MKXRH#;uB@T?$7!D{=KmJx!|9^+ zW#g;8B?kX)pT@+m7X8k~*QfFu&?IR>)*oJomBLMrjb#3?-s>e~J@zL3RiiL*Y;B_P zrS(`1D<0DEJ@1zuUi|Wc)IXcl4x{%}6;j{ze3FR~Mixx#etvvSGo8<*bTlz4r9ymh z{qq&UDc~%>faIsHr8%&y*&6N2MEY2q1wf}iPvFnM-6Xy$zI=gsu186KEOg{x+*(HS zcX}Tk+$mm8#;-9FR`^i?YgZ2YKu zT!;C(CL}+tb1a6TRvXFr0e_ih7&Y66)X(p#WbmmOeZFFEk3!u)Sy-`8bpF}?h5W<$ zxM+GaiJy-;fhe|_#*fT8hM5)ioXK0uU%#8XJ{cM;$Mz{AErvBE^izh0dDbFqUzD!f%8`~OzI5ez`lc)|SG&X1pu zGm_xvw*}bNPxSAz@$**dHVm?}L1R;X{Ooy91n*BW-3qsywFXr~~=R~!dlqjve><-Q}x`c1Ey^O)I+&CDHdbKd@xnwUh` zUb_Ib0!81?#+RpKB}_ZxM#isT#YULc>Vvy{h4p!Ee^0`;zc3^3B$>ai8K;1sb1swq zhFQ%#EExNe?El(yeJk#F?#t+H;m5~>6A@V9FTjT}KR#Zx-N0+MD@gsg!s#-YshE=Z zh=vR}+sg*8oDzONBAdT&wdBE$y^du6!Yum_U^*&@tY7qhCWX^q#IyW+xcSHJUCXdL_$R7=73Ozbe3?cc!h?%Pko@JIbqgLeT4U@m z{_hXH{|x>n_>lEc{ea()|DDFiG{JmB75Ow$-;|io#pN0=@eJ$!BfEayp|}ONhxcXT z?fCIw7k(Xo?^(eZneoRLlc;l$uC0&JDg5Un{nbTq74(Sgkr4gP=8s|06(G@P56Qop zSKh(GwLxTluxYRq&Y63bpUd=jj#2lm~{3h-pmm0KR13k zWFAC)PkR5wkDkVhx%ByZnvwvw{q#xwbFkzd*bLc3_Fv3$tOKuKKBPaE)$tR0O%uHT zL)6zd4jX`n<&Z9BMxJ zWV2duu<<4JZB^k9_&NL(c|R~?V1JxHJ&nA-P-s64wGPqznLcSYcB{AGn!BR)Ve`w6 zBO5XJUSFnJh94h_l~?e0-3lgnC_g^7ho1$b7Jbrx=+W;6B)Zy={8}dHuQb%#L;9os z^IpTd<3VKqgq(RVY)PZ>V|Zp9njfO^)1J8m>%RTOF|7JH+du!Rb`sb1oX$w};KxVq z{1osuHATA?(fMHW=hyc+ur^{7nI9^Cs)5cEzNG#r-~Am@4xS?QhorI`HgBczVWp>x zC0DY^`qZS4Gtv2I3x+oH<3sg<4^C?zLEbMN=9z}WWSl{~(TuXyU|FcoGCtf>x7S}lo`Gc!J+(O3U=N=WL zzc9gaF<$cfg%Qc3^9w{Shq`9z-|NyTt{u0Negkm1MApk2wZ_opf8FWipFhF{Gz zep-^AfMks?Ie*^x(pTs{cZ#gf^;a8;ogZj?oROb_pDkL*{yzJ=g4&P7NYdXdwz!N% zc9tZ6EbkWwpQad)`lMLyDwwab!JZEM_~`yv3<`}jK1}smAy48MsZTQxOW<*x1hT%5 zKV+qJ8EYtl`nE!D7gL6`0czzenFAh2vV2Y|4+20U$ z@eX8!ZzkU-FwCq5zf51!zigH31o6+b{xJG91dS%KMJ`Ij#)BJH`R}uV?-Anf84d2%Sacaj%{)m&6 z#gIQ~WPS3|J$3ZfsUYk7eYMx(V+C1(zsSG;cLnq5UtXg3f3EZ;bd9iNoCompYyR*g zX!kH9`9r(0jzK48~r2bIAPde1Q?F1^i~^ z|6G06FZKZ5Fc?YRFQ~7HhRn+}Kh$qbgRCdEq&{5>g`ja|FWGxlHrayrJBas770xunWBp^K{xVhVftQCTV3#$2 zeC;1KNbtU64i>QHN3rW4v08@cnE9KPzjN`iuhOy0a5y#A2! zo+!wTHb8R&k$z|UL&x1Ofx}u`JQmL%U%r}Eg4|bMGJh+=4v1bz<7a)l!2e%-h1Bn2 zbEl&B@>gX3R*__nj&o$0Tx))Oe13Tx-G|H|_30h=6x{sAl1YEYkB@+obMRYf8RJ9ZvIyR>(m7RFOmG|E>{g=+ad|=KtgF z8{kjzKO}y({_#MJqVZ#J^bA~_u#nUrV$ai|HfuAP-<9;L09(U@!wj=4S&oH-SPb9Y3Fb`3suG^#1F6E25`VF1i0T9;5Kof=W`K%Wu%fM(aPM zzL?+J9g_-1lKr~_TY~ZM_8E-#1kw3m*N;OV&tu}|e`Q7;v!G;I{GqxogVd>eedSC(ni=Esle zjU?PPb|n)ZAX*=Ge32U&3F@;K;=PUh{5nxJ6`Jhq$ozj{**zE-<4(qBng1Ff1Uxf zf#%nQ6@vaLZ-K{4ykB7HUk1m`50d>W(GKrmLGK81zG-Tw6ejf={t6Q zvuDX})aj$j$b1s{YwZ3q_pBhS&!FS?QU5r&t+x#I^7;Lx-OsMW$}2R#n3$HrwS#eowa)lvXK;X#=ieew|4Fu^8zINvd4URQG8_MGjvQgbjf*;_`LY$DGYI7^OqR1^>t8w zFC4y*#$RpeaFo-pBIDb(qkw&U|C0JiH~a|dOqP9gN|C!8!jI zpI$hKg+KF_smz3L9gMv%KYpFtr!sXtKQUwfZs5h|aOZHyRWKy;UxSYGaL0KS*?(iM zkp-sd?wFDx++S{dEuK~bw!v(Ca^G)Id-@e#Jz~dK?*5c~?}>)-S4n?O-*6ZzPpBg6 z|EC3SQ%t@>^JmmobG#oT%gkORaCaM2p^P<3`bQ$*h*B`>2&(%9C z4Jy}fCG*31-7WCiC4$WVM*i%FDROto{;X`>3Al3Ie`Njc*9<2NUZl!gcjM>BJd=2g zo@vGOvJstMc6|N3XbSU9{1b`Kht^Y=AwxbfrI-2fwP5EI#%lT}rp}umpRYEC!PSk1 zWPV^}n+U_#ufo4yg!tmtf20KS!Ms&GSnr>4@z;5=01gj5MCzN5-yXw(=fPzE*MmC} zs2+8d%)h(-4#n?QRiwYWT<~@wo{(kg-iqQI8(#+mvr%1LW|HyS;nW$>Qa300Gt>Ms zjJ`zU%S7@%yizzs<_E4fzko{HInuu!S0js)3~Bs*jvj~KXZ=Uke+>NQ;P7ws`SYvU zhUuWn#1G=fr}k@YMpE|^^Vp3aUoCxfm_&z9%*bB+{HQunFnchJ#&7Uy9j4&vC+0;G zKR!2(3I(6TG(Y|-PJnXDRb+pZ?)D6Lyqd;m%7khd{#)>Vsi}y6*zsF^$4gLsK*zW5 zng9EK0v+GG-zZ_zl`69S6r^E_BhJe*UH|THaQUyZUjQyWJd=^QDB2%(e8-=$nCNK5 zlo;~!$G+T1$arH;`X8357r}bnR`UHdrMsUXad09FpWOIh_^>aYJaU)xhn75g||zsQK}Z^)l=7Dn`4h4p{<{j>4W zd0=dLh}1WitpxMOAJXxmsjUazHo8Xk7amwQ7DLPaW6gKs-j8c6T#C~q`Y~3jqV-|( zle&yQdgRY!5^nMDe^7P|jyq$;Bm@8cI~@-G7_V z!bO$&S|{>9*!f4I?g{woU_|DpnZBvu@M|lXe-%jGgTVbXKF;-f4q6yV`a5meVp#5c zjnq%&w=}Rk@jvqZn{nI{)Zf*QiDvaTu<^0bFB+>K)BEog9S^;j)ntBiPWvWAp7p?! zUi|w%%C`c-1|BE(U-iNVD7H={{k?PUgVEXQ5m_HNba6WN+|-Tw`}p^Frl}(~=hOUf zYOEiYj+;f+SGG()4I3vcC;KOj8j@kcN1FdKj0E$~_8ubpOI@WKVbq#P(x0i;?uI)5 zYh-k)as(e;!rYRQW+qW)rTeR5spdfeiw%6Kg2=ZEO}gLtM}p#Qx2`881I z6jWp`C;gkj#TP)|XB){M7xZ&rh`b-!KV~Cc4~0&VWPfRb;U7>byhhfy9hUdTE2Hj_ z`H7p}Xv8ILWPSUJ$s&Anp&ygwB|Lvz{A_(5iKl;BF)pt}>%-1Zjw>I7Z65{xO01AS z5ZU-~mWqX>yEOk;mR$vl6c60c$&a5pvj-5LAb5X~&}VBtyn*WbiKPFxf8;>iQ$q94 zj>4(f_M)5YFLYFMK&@Mt|DFZ-`1 z!8`NqWPQK4^&M~)^CR=8u`}!7-jPVMKcdJ&8mGJ5BmLpz52H}sqm9fTN=_Q$p7ef9 zy(K?B;=Cg8#Y}4wALkYa!GFO<_-eF>KiK$4E{ulo*=tCDV}aTg=)CQLW_S4UQ65+d zUoX-8l0Ww~B*>m8^~p4qUtnJ=c*BP9hljmZzyY5hk^LjBzEkk-Br%5SKb&{Z2Q`k) zBK2Fr_AtN7dpD3DmQ zhKxTlu4y3uV;|{%N#_+qdpfOOO5FZ~tcB;v`cjcg7hGhnlltDQRUYR!RFm^>H_Pkb z&z)inReu^DXMovxZ2iyWU$NufXdO3;Q9H`dFY_jZ0*`44t-bU7+D)Lt0yaF0Oc|A_ys2kQy=m*jF zv*VAM-(h$jZA8YO9lg$gy3ZO?|4w{)2?8WMN&VZ~tq5`logm}SFuPX}E5HvmKPKMr zJ7}6;C*!xa^8i$HttR#HlOGFE?o&UeYoh3UvGsr40WTCQo<-^xw?`-7lDY+1pY&Ok z05$iwlm2MG!gT0uNAt_o=hYzgCX%c_$#wR`{Qh}l{5dPAznwRHP3n_zYbIm08_lnq za_n$Hu`2UCPqaR4{+X2%jv4jVj72>^eyZvNf!Vo;^gkb8j(~e-*O2~aYurUh^zwYeD+w$I9bD;p%o){NcWjlAo6C~LojjhoJs`C(|D z1m4ljBjeA!-NW(p`qyOtL+Gc8Xm^^%$1XWryeKt_(Qgy24;vpD=L2AO&?2(_QW$y~ z)+w$fnF_wN(%$bq1;V^XFRy^BK}7-;cj0{Sz%WEmXNG#&|{w_n(^|mKIu}l>i@ZF~Z-u z^}`Tnf6%?Kh}5sT15d%lKWoVThWxM_pqNCTkN)E;!F}l&GQRFl?0~4u>ty{y|AH*O zX{;veZ!T(xM-Ip_9_vNl$L5FQ@$UG-Z8qsI%MK02V_?G!{`bBE_kDt86OKXmH4Cyn zQvT-xSd8~1{eg8|_h5#_3DRF`c+&*V8cF2)10QmGU|Dq@Ils88b^@wAq4)oaz9l}m zq{?Vl3i+A4|7j+E@V9~9|ETXV5IuDV$&U-FuYpUNA6fr-F!>=QEILE#^GE6Ju=?wD zGC#?Q8H#=LUz7UEe8N0TwwGhozqtI+7JUMlDK<tPs}Fu_2(%;u-9z`SwD%1jRwsVJ6Qe?H$Qu2b`?%k(feN&^#FDp zJ45QHHv#Wqo$d`%AEa*-!!M0AKTe*jgzK7K@UTx3mivpo zk3GL}=?od1w&gLYpW@z*#p>Zb$o$=>(iN|S&Susv7JWZkKP46&fmV+dbpCbs3>@jZ z0~;O-{R^&s+9h)Z9t`&<{T-dKQt(Tq^+U&-w=ntQ4RU_Ln6ZNX?wffyMOm~y?E4*0 zy9Q&y!Z&36th_u6_eIDt5f#Ee&*hJuCgy1OR+TAXy??! zL5+}lA0YH?F)VpO^Gl-QZ%|OoXVo9Pkd2SNzJoA!{TrpK$Q`@Q{Sd{X~<8-5Ai zpKtaP?k_h!ec1IHX2#th^LLFfX;i%UnCw51D^|zzK;vWWU1v0XOXH)*oIsd(Z3UUX zXZb|H3r8o``-5D3wEABJ15Fwq>qi&CxWQ4R{_JqA0i#tkzaDzp1;3Z)ll2Gth=Eu) z`}ZUWlQRp%@ zNdLL2As$kT_v0Q-p?}YSSgH~@r0~@J8c_{ zYi()#^xwDxHO1#JzM3L_WydGYul_Knwf{5{=$wg;Y*L8g`zF9-bnQQ z?D%razzbsAX?;>RE*Pr3Y5ur;APy?#A0YX|?{hk6nTL@1?PlEqxIa0H)OV>DUxAn2 zP4fL3Ujs?OY}h9xzsUX=g-?$3V5s>j%c`fL(hoUSe-Sr+FVx$HGc@Kft*WB+W8-IE zlplZ)NjiVC3WjxTC-D`?>rVzxgH%C_RDZABFWjZvVT4d=+>~Tp;_$_Bwrm!aw<> zKm6Ee0M4BMmee0FQx{>wBsFG$JOBRYoDRSbD{YxFW&ZsSS2+ZC+E-xxeBt+T`-jhb z3WI=fHa{Y#{-)BL1SxU!{vR541C9&~L8aOJ@!{OAd*CGC2N)*$ojpJMv)K!fx4%jD z551J>iQNzB`0?_f4nDS^_un+#5xsWKVG{a^)`xxm->dF}(MRa>5i##5{64pi?7x(& zi-ylbyhwdsR`?KFKhyC;!Tb~8totNC7(W|)ARR55AogvCv(D+b%>kHjzN!I6o z`Gvx=>rQx8PKXaKzi9~aSE+J;az6UK)?C*Bac zvWC8~HObpsY$rTPET0)HHMf#%O4H}=AXTpAxW zla4@zmIJBJD~+OHj*J(X|Lay=gW1PJ$ouQ2T@N67>;*Fa-_qU=V*Bos_e;I(RPb9J z&7YT>4De-;8mT`f-|_+PT{M2Sy*>fuc1{?zPniF6@l)t=4o*b)W0;=k_g<{}exrI0 zytql@=Xpszd_R1X^as5Rd!R}qtsm|r^~0);w`BiEqr@Z}ezZTG|2sMe-bb9n=ndxQ zj~G=y?A>I`EJV@o?D(5w;0AA=EGF~+okfA5($9h9mkmLY@I%at)aOB|S0Hgo2tHL6 z@+&t!ok}PLT>*ZA7YKjn`j0wa--FMS`{etI@&&^%P+XkkpLH_&C?BE5eEc`RjGMn0 zhI_-tb2NT@Vvob#Dkt2TF2V=9|6}r`1bEWoPriSgHS`XAt)TVC#MgE3vFaw7-wvHF zizjElqwBNQT3C3bKcf^OTtBY9^zOM9rJv7X3f_zQr`Yi&_{u>{skdczi1FiNh@&g~ zoUw$wzn5JY06~=wWPL6}F9JTy@*?%SQ`cp%6Yz`Oa?$^vU7t-5^p6BCrSUONLJaq4 z*O2}Fn;n%gZ#a#Q3;p%5DqW2!TO;IuEE*DolZf$wil^y{T(lX z*4+@YesQ;?5YC^xK<2+6N4|#cPFlZgQvVAFlWWNPpC1~OaK#)NKkau`;Y^9SjQYR% zW!(AZlEt3z_O>OS7Z>UmuD*T$I0&Atqw#ZBG7ikA29W;Z?l~E-?QawgoXU@%t`kon zSo#(jpQ4=lV8})qA1O-XG2?50W@e-C@8|N%cNGR-HPYv&q|+N0DcCVLOZf5A9_R!U zy_b;rU+cL;P<6(EoL}|5_9W~Uy#Lp_T9p6vWX137g{g2SH3Y+@MgM;`zntw=0ADg` z{FIOT1&Q7@WPSI=gdsRWfRAbr@&~uR-OJSue`?HS4*h$7iaWo&G}i+f+*gwM{ixWZ zaP^Thseg|Rje-7}0XWy5pI<7 zNwyGvKbJpOrFo(96g$Q(oqzww2W^9Q>z9!I?>}c9go4u!xPG?i{IKtb+YAbaPrtp$ z`4%o0lR@H62$>)6d6);gZeBq3i9&pE^+%dxHCRre&yRE04`}>L=Lh4H2Vv$KapvPv z;rej#QLHl-(>v(+{i>%87WJOXw7Ln`kIOFy<@Q3h>q;_za+`1jq%?Pu{-Szr6f~_6 zyn(TYA3yJsZot`T(PVzCd#D8luPz|<{kjk-oP6sYS^vCkITy1vMw9XPTEl)sYdgm3 zvhe%4{SVieEpR7{#?K{HUwC4>p6m}%+8qk(o_mq~V=qgS;Pkx^thgiM7dC%nX;wkg z(pzMI$aSl4Fkkg4*QEvhUv& z%~i)GCLqVH$dCuEN9#rnf`Ozc1Y zj8YJr0)3y~+4$RD2E^Hiwe>y!rJV$QzSP#@7RR4N%lf#}BC_3G}t0_g|}YI#$Mx zCjDoh-@EZ)sU1@vDEvO|{*V9R1P^0Z;?b8v{^RQN=uSTvdV|LI<(H>G@fICFhb~To z4cXCTes`n06at^n`r?=BN6<^5<40(fDjJ-jA6cc=TS1 z(l7b(ujsfR=KY}K=jZNYkYnME*&V_^&#g}^d~g=T=7*B{%k#@^crhm#vj&Us&+Z>u zz3CY&{!l>HCyGEEF9*~3cy_-(>eY!eGWJ4#;OZ~uYtyjs9L*m+`|f}z)>dSH_EG=6$`6c*#EgCoV6n#It{;;^E7$iT?`l8M2J=`g!<44@s zk+{2*jt{FqFq^;UJSLH)&)NP^uj#wcrQVKNvtEcF?)iz_zXmqUr17(Vj0ddDS&!qa zh4|ps@2nODLD~#&(tp-Aiif%TLs|YIw?E`R?M(RQNynGi`lrzLu7K5FgPi`Ft!8pq z)mMV7-%hzX1y9@^&8(j*#1A*WIev8u+&D-|{t(DCD$Ng=$?x`k~9BK)x9$D`CYfZ0#U`t`zEF*M1i&yR_@ z3YI;hDC|b=U`Hwb1;sz%CTLl>n9jfdE3<7uA)MxqSoysevd@oV?FK-7E0SLjyum`pg{)6Vxt{;Oi`tVsQOBkKUD9dse<6PHieHNQ83D7&3p^QeFufTMNnf>hZb@iobjy z`wtUlDd8$Dc``qV?mH26=BbnZkXF$q+_}b{Nt!5HA9j4%6=w;9yq2Pwt#E(2^ASef zasp4^4WvGCH}{7@7ifOj_$LC+pASW&!~FcxTkbB5+@6lrkwScP`wKdLHp3nPK4u>g z{w{{>{^ne#-Z&^jf}!3AIX!V9s$0?c_@=lPa_g+f`or<3`@k@h#z)}TV_>Nji2D76 z`i84d44x-|x^@h<{`1GU`E5(b6)1o8|KZo24?+ASjh}bFzrl*u4`lz@1OLHjG)tcB zuUk1s6XiCjll5QiJ{xhNn>}On@BK}#zO75PfG#ByGCyiqxgGR+ZzTD}vg8oR->2~- zdF(WF_6uXxC%F3dU1c^j9!e+u0h_DOVcBsyK5cp^g_BYx7}5KG-27)_=K?J77wG@B zqVvP%m;Sg4Y#!0^M{}7wY@5G}^p~C9Uxq~K6f(Xl&3XXccj*1!vAh!k6xzxCzoR)G zU7XZO|L2mO0~$uzGZXrVzK_ihTL+qhyrv1MKPS%F0;k$&erT{i2!_ACN&i@}_$cTf zr1`a3O5=nLQ#E z5cyX`@-hU{>Ojdo4T|fBLryZU>`+(bugzLk-ACq#aCq}%W`ETD=4cu~<))z{% zSD{p~Jrmr(j}I$>{_KdhCjIeqDK6mu$^~^+3F9Z%ANspB5PlzL>vL{=_5TtB^CV+g z^;<4}>K3L$zw~tcpe_1-Hh$_y)Pk{m9htx6ddTC6I9h+DSZ{VG^>AQ4jUS88UI69ZD%HvcYEfZ zIX`}WWmv+mFl$nuX(BO?Aza7PopY(QPP-`d;^N&vFd04ZPjz6A%^T1c+Dkm^`^BL(Ru~ zojwZv{?Pn0YO_GQZ?|XK{>>LbWXC5b84D;5pyTiOA=}~bm|a-R@Z(2klpoZk1hV`` z?)&a%nj+!*?-QLt2`(|AHXxhr*u0Qgu{%CIg z|6lG*^!O&oZ;1M~!UID%Yi5G3O8op2sJt5H2;$e^=fdyj`p<(F?1P30K4knVI~@!m zi^EXLS;#M3|0wLkISAa9f=Nlj-?{vwl6V(JnH7=ue>XR`f{J!KCWMRln|(ig0wab$ z$Mq!jdr{Iz>?5f`@=q5ogT1S*ar9cz_p|5Uy-L{v2TFI5{*m^YgOHRQh)Z(#_07}L z)6iZSgVTeA-_MOt;eD^dl}Q<-e!Znx3EC~SnDkoo=h^x1xjV90IYWV*e>cl_I!2BH zCQ+83UuG*>VtkuDGkk}Tf4S!;vcmvw|7SwZuUdJ_4lsQq*?;tQ(O%fL+=uj^Pj>{t zDn}YW7e*&Q=T(}2rYz2Z<(5S_u2Z-^T>V>b{|7ec(fCkFQ^8Pm8XqrAOiz)dFlhZ^J#pfE1Uw2KQSnmDEj}i^Bb@B%dl>K2B}|EraXl6iFIWE z-A(HjC{1lA{ppQgWl(I10y&@c;riw1Fl7}J5h}z7H~(Kzst0$rnP5bXXnolI0ly~O zK-+LfQXiMTafQQEd`NvGVR#f?`qKC?)QX42c_}y`N3?!ye|mm<7F_hC@li1AC-~XY z_$W*ohT1DMNPqgN+B95m3XJ{`{_|DzWidDj^l$I^qV-|(%W<_0pk&}m`j5lhy}?8J zFzGKD2ZqCTi&!%LTyMAt9ljZ)Kdo^61uT^MNczv>YJE_0C(SRmm1Y<>e-$%#4?jMP zf*9!ckd8l59V=mTv?E!+uvc*b32PrxzwF<67)H5-A*u`apBsNr@cysjXPQ5{c9g-W z_&Rcaf`9QhFx}XbtY1l;ABwVzHJI*y{af7nr=QpqyzR`!2e*FV;Y?9HI{NpL2FB+%#Q+t5ZR zifTvaUHtL+QK&R3Bq)&cdrhoN@T1cz#^&GsGA_S3s{mxznV{4U(fMKXOID!;?409B z#-E3|J7C`oA2f^;{&{Zx?Nc8Bm$GPnF*A;a9g|Z@f9||rG3<<~!#9(K-_O-=U-Q2} z!tS1A{k-Di5UdQQ`Q<~yWK0dA@#D6BA^b74#;x8${lTrT%Wq!|g&SST_>{4CA3V}J z%+j}9{9N6A0!$2JN&T`#HXU@zXnbfMdj{iMY5n%AQxf&>D=;?4MEt>?|0T74F{mtaJsk&lK1$K z^PA^f35FR7v1ENOW5RhzEvNNaKx97nKC8nz6@Gpww)p^aPW2@F6Vn9qNqsYEeU>;~ z6StiNW?{Z?eYp5AW#)tN0U95g9ab<>*%brd2=|}szf~9LGhuE{mrG1$6@qoV2Vx)zmL2B(?X_$VzUXF?)+bTy>~p9-~T_ZK}!>9h)P9MMQM1R z$GNmbT1GoGh0;btL!yi{NyDgwBuyF5>)DV(r8Fdzc4^Zd`dy#f?|r$>^}RhGufNaj z;(5-wU-!rTaeq9{xy1Kh?mrqHm{{27Pym%0> zIt?U+^ZYlSd-m!1Cf3|d;a51&Mr7I;uu{pM;w>?KQGIU!(mGt zAB%$vAt~e|>i^gbdj$q5_0jWX(>J%IO_!RW_rLeE5Wc@#=)(Aia{N3ys(^)irlI-U zRYylybYcbSKd0p^f^b1!X$}_gC6BKLnOi__dkj50LR=rYKQtg92KwGPPn(_*$L0MI zI!RfO_Nj#WoD#?7__^`wA2ig}MftO1TvxjOgWwOHSC5}*H~PcxfbnR4e{k<8Xtvdz zhQ~?xVDS^V)D`BO#PxSx%k^OEh{uyfqu-_L$%X>@v%jRz;s}F!)rwsbHN*tHtWB%j}u%G>qUe%UBL`zmxWM$lQO7!ggtWSbegiX%e_Dx<(^2q;WPrt$COS ziEBR6rv25g&lATdU|x*#kIBWR^lpp^H@{kZzvTYF@_WMlrcGSAV|Ao)7GEcf20{MN zX=r{IQaBd+%v_231M7?2K_d!}Utvu*!-m8d+Mu;Ke>wk5G};FRIvFVcG^~>jpO-(R z>A$4sS$xH`{0Tj}=%U{Txcs^!-ThC`eF%N6t-6j-TT6p768B1k@kc*^NT|2%LYO444EP1^&VG&t}2Du8G0pm;Jyn zSa}!cpC%rM;qv-xw81)Q{aF4vQuYv5ysOV`XeG^$J>O{Fx-rdqYr+-ktH;limgdks z7{`aR`Dn=Axf1QaSk-wJlw@qBe}mP>r(^s^DC!o=_(N3IpEXIy55m^q@dMeDmz;n4NA!i*{An~OPTYUFzHxXo0_?}EME!$qS}t(lB(87j z?^zGCzvJ;I{?jh--G}4H$v7S^T)_D^@8U&x(d-ii2a!MJ`esP-2dFzo7p<>1IA%e& zP*?7D?e}lx{7Zke<#wLH@zZZvHz+R{PoIoekDtoZgW>!$cei4lLlTp#yLR)EI=nY!mrqX@uPyFxvoBaLza#8Sib}gV2FG%=c^RI?W z$3puN0jR&(ZH6c8%Es}d=@C#;X3MvXeD=O3Mw6!OzoqW<=W;K@+*VJmfBBt9?Czl#i4!GJ-r zXnu8W>;W*le2xCCJs&04cMA_@!CCGTnjh5ncm=1H;rJPzRgY?YG(o@bGVZ<^^$K?7 zKIf~)&(MU<(7(Y%)ZZ!c9RPQ2Jeczva(=P-XbT3N0#JTg_h?;IHpK`-(AVT8+3Skj~v^|!_!D}airIDVYB>QKME zI6huq7y|wUD^dS<$IFdyYFG;DKkeQV1?H{t(D>PY&^get`9zP^-ajmlFAFm(;Q1b1 z^n90n=|A|~+!V#Xxo;0T_nRvh!kiCe{euIWy1{*)=``-5$ba(qF}F!ym^8(Msej1# zU#HVVC~X&l^5>^-OW?UnEb1Q&>lO;7RX9Ja=y(Jk4=P3d?;g{x!QDxk+^8=i|H;qi ze5z_e6W3GjXfyTielP2Xy-Lye zaPxB+oKFz)|3Y#9<^8Wm9yFt~jtTjnvHJag__7^*&YeJeo)!5^UjMRf+Z%Ro!0|uZ zpA+&=od1T98E`{;588i}8tV_b@wooB?6M0UPRm2{|JQbDa4_H#ZTVO|J|;H30r#MACC_KH-d!wDKcn>71I1!e`((87)a_^N{uIr<8pm5_*MzLf2fPz|5WIqP0J%G zXYyRcms~%Liq(g&-6zl<1=9P&=KqVncZaCO9!!6UoIfMY2;AryK!2*l=jHXYb#4?DxXskH-Gv(DMk6pFGV=aC#liuQv`?gQdAC zdVcWbj?VNzsVkS|Ev}zDzj>l*2sTF3X=R1_{AJR{eqi=tB`sejtqix+9+XA7kX(pQgB{e(%LjlK+|Iqtz?X@m?{(g{eW7_$e zpfBo6?;o4rj^CmOkE?L$wes>g@B-3XZNjq8)~&u77-9kDdvrh0sY*#&^6W+v@!C;mQp{xWcT zGH7o7M33*6#@YD1;(ZbHE))Do#vfwq^OMXQQvFOJKHU`G4>`Y_>#GCbTTVprkr~tl z>RWrz`g275$oa+m#31+>g2$)3$rE8QhvUQI>k>F|I)(nTm*&UT$MoujL1|7N4cj4& zv-&0MKr|R0C`J9D&rP$T^I;r6=LWq4GRlR{wld4h$f28*QayfoJ{WhS#F1d1Z zn~3<5zh8TAwScwXC!qdg^Y@(~`k)6|zn>UB0DdR~sD-Mgq2E<*#{iAWh{ndATaQ><9(;BiyO{ZsL#r>D(KMQ`C zLbaa{9lc#WexkGq4C;^L$8PO3$hd&>3pMkHAR+!>_!*eG8yutX_;Y&N5jc1a=bza* z1u*Cvj-Thj^=L?;;J+Rg@gc|0*ZJ+}zpJiXqfa6}<@gzI)eL?L`4d+EX!pwy>gM41 z(f-#Dc6kKQkG1`!a{aSQX$O;jMy~>6?@UzxevXQVGowG#VH(o>Sbo{H`WlRDsmDz@BaX}SC%b5U+VGPr*Zrrs zzViK#i)sSPJ4{6P|Ikzexbz&~fAeu>;Gc`frzHv-s2R40eoc_#Gpm0u_n!y5OY!~h zT6ZU$EiR=a)=0mf?LW9U;}mq=ugT3{EzV!=ACT9N;r&{C|HrhfL)(`M`N1~nc~;*Y z-_a8Ce@;jJ>0W(|q2!Pcs&9Yy90b}sL+DIHk$>d+*739>>}VK=);Gpo4}`_X^60BZ z;{4_M?Mze*ME?Fn^+Kg_79a1oQ zxPG}2(H68Dc%t#eJ+v1LEXMJXWjq36HtnHVRqFBKkmCj)U*P^r&cYSY#tYYXl}-^5 zlu$~mYWYQ;KR$Y!3jQ&goY@R|3-$#~9~_%~rmI(r z`z!Y+pDeiujW|72-yWaZiaNG*<8G9T&&%=gu0wO^IdKN6-xMSCA$x`=nm;F>=nhlA z5gb&9>_Pj#;%?7?mhV&Oq%YF^S$%6gWeK?N%%sM(-$#(^|IdkG@aTCd)fp+x zkL8!bb}0~6DEQBeK4arcmibSxuFr8no7C@rdyNJVkb=KI6$6?=+^-qv`O|$bJ3!ky zzNmh=+u0rrhqL&Q>)ZHu>tW92JX*@!Z_DcYX_b2+%I-6o|8zd7gz8>6e=Ml?02*vJ zMZb@_JFYpMRp!b?Zj{!S^{-W5>cgR$iD>^RKTa3MHSt9ABZC3`V9GlD{Yh6UAZi01 ze|98#L7h|_AFG7^49h1te+>AM2)AD2`lI*WFOc+%a@~ih$H%PhjUm!u1{z;V4ZA`6 z#{snI4>5ko^;N~7DKO+g3T=B*J^mB9wP0`~k2)7h~CG9WE z4}IYitgE8j7Bgv_)fb%?w}fT3o-}`>lz*}H{hM`-p{fY?7hjqWf%BK~_*rkd6I>Gb z5yQu~v%YXpFCWzxjzf2W;grwxS#AAa9zXtRrbEbh93S5OZo%OVrd;4oasKl7X*9Dj zJyqq(wV$aTA2&-Iz+;1%H1mmwe|dga_liFB{pdp**Y@Ab@lopB12p_X=+)Wk@$uAe z1Xy_E{CVidY=E1%zGyG>*N$pahU$xLrv?3fTa)`r#QDqh1sD4kCf4P+H(jK079Szj z|Hz;GiD-U*J+m2%8H4lV@=_zHth)*24?`VG=vOZit$!8zPk_9B$MN|3Wf>g#hx1Ey z@ODUAf#b(&>U9`=&XjAOBhFurkC0Oh=*OmRC_Y-X&;-pqTz}Mkt_#f<;PG?GRugc! zg7Zh_VGb-d;rOWj;sVa~ve5jk$~OQ`)GMPG->T;iqct%w>7gc9!tevjAC8MpL(^$` zoaJI^eOUjfW1UxUx+TYrZYPe*^=C=F-(>b+2edwxRYw~fFMFc>ML{h(KuF(BXn%lf zFLM}JitDq=GJEK~{5aihDZbzG{Qlr#ZwS`UN8?lF#&9Tg{7l!GO3$6r3{U zj>d@dm*dA9@GWGigEnRJ*-!YW{Se~MLvj9cd~7-Mm8_qH<70wLBRExo<6}%oTQD}?L|f}h@r(5jeQub+^!GSE z5?+snb$-WD|A(IUfY*?Z>emgk_QRN8nw-v9asG0Cjp~{M?*x9C9VCv+@v(YiT{@k^ z`GwBcfVD4XqW1^omo|fk7QQsLy%?Y5@kiOK6LkKL*SGd&4u<~5aa1_v^1uE+xqjDd zFbNdZnbf>Cf0gGi771%0YH}HU+FaaUxjy-IKLn;;!1bMOzZ4kgqQ{*bEUgcVpH>YX zL2+-6YosZT%kk6n-Y3$`*#WI@C^EEQ;UF)x|0pK8H4N0>gw{{Tn)iZbMSJL}Fll{Q z|0uwH1iZ99j_RAO#dD#`2Im*I345WWlNRb9r47CSdy-7K5@&J#a{M$FzP}mk=Ee=4 zFReeD-#o7TMQ(3r^@|2&?}zbmZvvOc`p_q>M1AuA;HSSK4DA|<`bR@;27<>%T;J*~ zo(KcpW>Up>asA}@=`7rj(K_`rJvmzZ{c?R*@IDb1uhZkcJ4*9s@lpR!2^{Lrad}Mt z6RTgICBG#XogC2f$#V|Xg9AyPl#Y=2gVn$9&*{MZZa6+FPMX4>YCON&c#MNLhj4!R z+{g`nx#IX}Vxdp)bO=$n? z5`(TVOe+%gr*HRGfUg(MFI_iHhh9E7e(D-6g*J*Z8gW)yUp9Uh{oMhLe`snPNO$L%sQ>n5n zrRm*DVm5dt>MyN$Qx~Q@^`U3&#r>DZpCvZBP(3dc?GFsU)&t_gaD43BJ_63P%R=?- z-nWy$e{DX!l_l<<+`s-O=-+_$RjB_krujkGIzf+HaZ-GLPIw1DZoLec&UpN1xIcRj9eBW823q7RObV?GWrIUeWN%u%c1{STa9HXn@! z=M92>c_q$Ij*qR2E8)TfoIhH&`b>7#;QZi|_>a85g2&%Os~SMkMw~xhY-sdUXnc9LCIu|ZOu62*{(&4H zjYnPuj}Zd@MvLnw*ZEXZEIPQB-{kT4t=$YbxTuV}tdpK+^+$*Co8e_kE$-(zY5iFJu`)FgVxOCGO`3`E zM~;tZqsuUOz2ILKO3$8 zfvyXB{=#$lE7Io|p8s~({e@ipjq^u`X?5W1QXC(J(~ThYFwU>fzFWdmA^uJd7k|GT zAHTgPL(5%d)O)))F82?H&I*9DeY7~Ud(!%`_!!ikhvGGYKaeJkv-|&|>rE1V#sTdw zDL<+MyB0*E{be2Ao5JH1eE<919S%-s^J(rb@%PL3e|owHEE4zu^ABImJPfB^nsQga zioaiu@41!_;bnU_?)*&g@5}e!?P@VexaUF%Q@>&Jdvn((WYK&tG`~GL_9J;Y&KK2R z%Z2*!&Z&5Owa;%40aZAEKI~ut<5y*&`Tw|$4&axB?|-W%>*3RITwjdt8Ud<59uh!^-X}x&*Z?p9O+4{xD7d>FN10G+dU$p_P$THez zwDdfyKlXoJ2AAx$IK5nP{_^}~s{IyNwnLBG9W0K^^;>398f=W_xSkQ>xEw#n_o+zt z{*I{sXnFD;Ik(OW&Hs(QeI%YKIRBWnYXk=c{9yWQVu1mydxFO=|J4KG!=-#WfcZW! zt8aBer$FiGDr!)B{zc9|%A-+mM8FTmKhz~3G=>Q0ziPivBgapZ;#|^N;llL4%Jr@N zjB?Upo-gW8JN5WQ8VUMsWgk)B%KanmcXJ3zj-#C`Bz?@{M>n?{Oj({q9S({3kn_*< zHp5}d8$3Q)UI>IOu{b{b+NXe7D9$gdEi%c_uMSkJ_WOQveVS);i>zAZh3fm>FDgl+ zj)Ca?L8Cl1AtwsY|81SyLg4gNwEi`rUVkWlj>o5^^Ap0GJ{iA0 z3e%Ty+}6I*`m*|V>z=cudpAc^-&#c%kiw1&QGZ%7{TcDOit~$KejO+l_~k7pz8`Xb zVA3~T=vamO11swH2A8~i+QVFYUapT%>CJ~qXDzOr`F;zFpEiFZU|Xdrx1Hf%7C+qv zT>zI+Zd`?-`1j@fGPkXgY>Z>`BRPKVy}M0HKKjy5o+5w9{l{nK?@2^JC|%?)j?4K) z)w2=w>yO8$*Yym++&7EP^b>!doL|NZ^^Fyis%T}7G|tB7Rxj3qZL}VzGf~`sdHiu3 zatJKEIPO>raa$WC!8Ho{qm^k6_T2a^UIW^a?<@X?jODR@Q3UQ!u_K^RV|=p zr&O96EzOVh7hhYOLh##snl@4zXX8&y$Y9W@SC0Az2W;G+K+u0dtEBm}_!&_i3R6o= zxdzPnT^2vv2WCOAP(Q6P5&yp&Km9(ZlM_8$8UIm^pQlL$2=_Efm8(BjOQ^NB2eLb`5&x8F=T zyT#)C<@(rf)hW{XCeAPElXA)UBs@O7@~a?R7M@>wn$>~m`tkHub8-LW^-+ztdNAb$ z?qAP&XAQCAtEkaV@p-v^tNQB=YY*Z3pJ)^fj}PPVCv?GCXlU=o&G{w8Pd0x0JxL(V zHsJgdwI`DlRpI#1vAa#0{KoSq%?TffDln2JnTqq1$0yro4PmYjpZ50<$L0R@h;TF5 z*03Cn-{!9zVX`aEFX!?%LCy)2bj&qr{aOCFYuggGT*dXv>&`}S_b(ow2QF8Dvttzv+9<6b8=w06x0+r2ImI(DSF(F_R{=W|0T638SKs6IIoiuep&u-OwJ%bKlsqjjn&83 z3rBOvo#ahasjuE&>G!9CG*{yL-@I=f@bpYY`?vPK>;ic;WmLPX`u*3tJqoJ)wYVc& z#QDkngI#C+;BKKQ_w}3fJgYwnDqhHdkrM?$6f zv;9jJC(e*7R=)JdaP{j~zWD|jsU1eo)f1nW>)W}D-jT7*;?ev$X^9>zX;DBA8;SFi z zCgwkI{z(1JlZ_am00q(D84r&O+=kfPPdD93E03Khyp5Z{#PmA;PRF9uQ zmP_HsGn_xdqe20Ear`V>9z}|JI-%#Awyiu!s+YQ={avdIb4lAW+~0lH?<^-0}p4v=_CkDI6=u8&-wes~%K^EKQ!OK0`` zu@sJwKKB=*{pIHZPLLjkeyG26Zc+x>F(MG{FYdnfIe9$<=hyFr^*3T ziTvo5is~oBM%rK_>@OA{s?T?Wf`}^mVTm|D`TkY}Er1@kO}Vflaa^viM?8&&6Z&qP zGxPm!Ha<86MUgROE=>QK{QWm+oJ63PFB(7Q1gS_yekgiAr}v&Ra-=)Xf4v+1Ba3qJ z{H#ly9^9={PD?*X_+tbOT4J&%dw^7_Rn?Ng*$&{w6N(l}ec==39>oK1+NUA{^4WBUVO z^Ba=A8;`Gbq8dQmu?463Z&3W3`?ZrpxT5kGQ& z(Q8dGN%-!<+@C3rUmuDhiQz9_YI#6Ce)e-I=Y-yb3m;L)ZA?5$-qfCDfix1n8>xiE_u1{Q^hLMAL zUes`$#2;*a^Xy{`DeQ{#i(9jEr2H$cZ#qTaB84uvzKO}JB8~m<_;j#oXLuTg^Ka}> zTli6K%4x<+>%-=M6DDm2FH@FZvXff8Pr0BV=d&FtmO# zxQr(*KDd7UIH8OTeuwkRqT|iM=N|rkR8H;-PN{m_=U8d}EIuk=Hnd&Aab6R|ae4g7 z*|vh1Pj^DkcR8-vLPCDw{Gl+}O9DCtqWb0D)Dxs{^C-0cbS~s{}29&Izbwy z;P_cFC!d`7isQ$w!3VO#wwxA}N%&{u(+dqvNIq3Xx0*@o!}?E;_jCrkYdF3dxJ`h- z0FJxP)F)Yd9sKG_dJK0$>#Nb`YsgxSMdaSw7Mpi=$c2N{XGNR&y$vM zI6qA|b)Q5nE}(mv@0+vr)rE7L!@&(&+}2wEO^zRxw>dm{Xv(dweZS=TX6F6*#K#H8 z$84ANgx~H<&%Zma_WW1Lw(Z2L6OIonNF)Ubxc*IvxkjC>5j{in7WjUaYC&M)_y^@J9GO}S^x z`2|+r7}(7u!5O$eyRK~rA%g#m)yEr}$B_XWasB$oGJ{z3%tq_u1{1E6%`*$=w%Z~< z$o=VRy)Wcc?`pI@8lIvHS{L=WlY!#?%i~Yd2LgA3IWDB1I4;*O9UW%D?;dVko!_E< zmE+^jz_H{^6s~V(E}lz9)L(@5Z(nb`f=n9Vhvt`WH?JqA0|RLhqn}y-hA4NEn*(tD zGpcSPIpUj2ul|+RkL};cd32c^@-3jcFQjpnUuJ}tkll{uG%H^mm;0Nm|J8+q5jg+6 zm|+azLVb10TycHn{By)VkX#xUhMxaA_$7+?ti}Bo=hY|4ONVTp5{3AI;Ul=tB$#fA?|)j&M6x3fe?R)(oJvYt;rqX7=>nqj-j{}&sLu~u zN3I~+LVqAuA4@I|A@f>Aq58$@K`e2N#q*;RJ8qJ}8*qQ&IA5B!f+|c?(LmwBiY9juAqyWTdFLq7GZWYMJ`2*wPwxWSkQez+9)B*!-6C!StI_(%1_KT7yQ;@6 z_K@b!=Fio!*3h?!8`t=hdVH*EHId9Y?Mv+o)$6bE+A~O?8O{&=xvj+SI{tpFw2mRp z?X#(G3-R~K^SeDl{VaSzIZZw<&R@>|PhM7#@0+x^wzc=8%lE%yu`x8>jq}676K14C z4z92EJQ_x}&Rs~KER@!V^^b;ottRH0QS>R3Kd|}R!Icr@`V+jrEWj**n6Ae67slrj z&ra27{P=qNGubE9cOq*0PvrW-IlT!C`GDiUfvY9-6zUr`Inw;t`q-{2b23ZNUtSxe zarS(eYx5!GSU8^l##@adDek_sxsQ7M*iM*5N`~V6v3SNJGHP@b+CO~n$VPHBIG!#~ zlkma%+s{7iCW*swec#wEjg(!)_3Ou~J7nE5E$&LNgip4<*3h6GOgM<+EA2~H60ir4 zKT{pY6Q>P<==s@JQ-etKL0mr_4n9CC<`mGHJ>vZ3{4niYCh6Isns%Ym?`QMZ*2eW< zz#~)cIMe^e>Tgoo8y2;8OuD|7Z2bSU&^Ot)CP6eV!hry-D}k3sHaiQ{Ca@_B1^HPCP!7%wVs&N|{Rg>x%f7_vc)U+CtLY z3#ea!gfBLKbGJWCTJ*>H=g{w0WTkMw$Aa4UFV|;X;@iOY$!^?{$Kw3t`R||>dc@-* z&Oa%%3%MSJ>-VAsLrE8NoPR!yn?&p!ja5K& z&8D$E$&jgm^qRT&yc|D^XAC2QjdA_s^?nAaI)}%v^i~^)r{FJQ_*oPkMS`@e>6B&? z{@D0c(B=W@@XM4dv=GPT_?e*79MXmS8Pm73o;D&QD{*}@MA?R1-jC~-#)}31{uoNl zlEnO3-v9WnjScbsg6rSZk@HE*QMmq{cW^VQ+>7hqMVT37uAuKf)t--%$EUzEAIS5q zIKOOr{zu_6z!~lD+j>o#xP0@Xqs~hF!Rp_4{S3)cp?(_6+;7eLLzTTP$iBgNd>S}s z9Ql47=a=D=y~+Jt+#gbS#gWPdTAbq;asTD|KlyqdSt8WGFn(#DTo2X>@n>6@gl|^g zcv#mV=d#?G`!nVB^&!ogk@D+)Xnnm!lo3&N4x=VN)#D>)$Pi*u7LT4EtUuq0URE|GMN|D$XzdZCVkla=bqybF&HYAB+1-8>0xBc^20r|5*;r#m-7jb>$ z{>%5PZxu7!yD|6o%JG$RQG-}$`=R;wqP4o@d<5=aS|95{cHY7DO|QUVq`5PWuhihV z%4}Nzv>m^n6dmtUe_EC+@$@d}~YW?&19NFFcr7&eq}#`iS$F zbPzh)m4PET?Eac-qW zn$!tH*BZi;Ta|zCSzDB8d4-J#KtAaed_R z=>wNes;6^YSde;rY^$$Qd>!nB-oNxF_kqHy0{0*4MOG=!%);^U`eb90z5vHZ(Q+eV zd>hv<&QSx&x8HdGSG3nSvRLpJu=>Tkwti&fd>lWP>3d23KO8@e*5wiFy2AGMAb_mI>Pyv-aDkf&&DT9qg2I} zn|S}m_gfbgebey#dqhl$Vrd|rfA607Tj9Xr`nT?rreu9Fj-Ni-UC4pUczl{!GL%gI zj`wdkX1I{St8x9)Y~xna{GBP+wYGjQ=O2?F#}uQJTxq>JBLB$oadneYabct%T7Pfg z{ZR36WEgsWEUxh{#kO4BpWE881vwpr`*UNDP*UlL`wtIwJ;+XhU$FS&Rp&IhB=pB& z{Hp&dN>N~o^Gm_iV+x%Xi_re|w)C>%;uahq#RJL|+uBCa_S;2#%FmbDP5q;ocLUci z7BSsOz$3grCHmkfaz)T5gA^ja%Hz-GcS}iNg(>&=vGo60e{aEt9i)>B$Gu-8j?3e- z&ZJ01`z~&%|NGB2QDLj=N1vTk&mS$dctwpJj*o4t%M@7$;^}AR`<<+Rdp@QGX`NX> z1CpiR$NCG4Pxc^uPdxraoUtRjh4VjVPsQiu@#pryjik(0&?hs*aryi=>Bb8FsT-%W zKzu*s{5rd6k7A0)LVBx8eSTCPo~Up?fcFp1=yOqF-8+iTteu}6ANqAm6>vF~R^O6- zAM4*8J@;F24YJYtS;C%HMCUB7-)1@XB0*ENxV+l_TseLsBAiK;;Lj-Ui2q;CA9IT~ zDf$cbRm`8-UKpSlEYuG$ep&JEu)@*>_g{K0S1Km&jHm4;NdKS3ha%#S!Z;T953HdT zu^0R&OrPv8=ugsa=yA=Pi0_XaAB*q0k;5Z7ZsA1n|I6`l?^_5-?u6qbeCs^L>{KW8 zeuISW>lFKh`YTpnx-ug|(Ww&muikEsP#oET^G{yHVTIOsJU#`E&sI#)Jb|9i+A!&% z;{0sfUk~v6p_p*2oNn1Au8+JvH?@6hVibtSr!TVxkqM7+d_l`NMaeU~|6*kpDy$u@k0LQJ5>GqA3kH6LQCHb?XSN1ZMkCE z=v8Qc?C}p<6l)!Eesrh`R-|;p*6ohw_alpd zoNbHi@5c2k6w8;nq34Tpe~(bC3|WPqA3Zf06hXOoeQ@9ySH&a)Jij~EYP}*WFPXyBZ2fH1*<*?^XYlvCQ^^&@j#YU6GTFX0x$T7GCwIDz!vDJ? z-BVY3zgU0z!*UbFn=d#&cJp>pv=izVSp7X=nvY^s4el>~w+~ZvyMgn^?LIMz$wK`d z^UpdBe6J|f>(1o&l(PD&ag08B+Qp6Wf8_chw?PBNo!zeV)&&XwY<)f1U0-2x#ScAy zKW~JoqJcf0pXE;6y##w!u z|IkelqE}776-eW(KXUnUn!=zBj-TDZcNNQp{@}>r;{4?JNwd9Z6+9dF4;{~3u^M#L zmlhhT*XKD^pRDTk52MAG)%(-&8Z8uUYH*itKr~{+w`clc4YPxYT3P^DKVqo!F}=7vdA9&(`z_v3fhn2|d5OI5*1b zS~8BG3pCy8@kZP~8s4zjswu_wdrtl{D+3|_$MpO2z^_*4kKp)8PHC(#{aHnGYV!km ze_&OsDT+3NzgXv;xIS|JdC@#v(WZ_YH>JON{IuvY&gxve8+!iKCUUM-RGu##Y^5GQ z!F$83QWoR-{dtRMtFb}xbWtbq_sRXC*iA>Q#!bfc%WH#kR#ig&i}ioaTGmpbo2sal+zK~AtE3TiMUo=+rvYKd% z>lck?mR48vqG;qy@&C*7yUCvwR`nm^_;CGXW0i9i@6TvxamvcwSBukN?oVO+leG6e zvRYcr=KpehY?^t)YC@4K7sK=iu=Ow3%}zs8C*b*iMT?0;@4dzSLya2yq1kQ2=;ml<2T7ReE zmowK!;{E}hYLvCW5AWaTsOXpVdnsODz3_NtmSrj)zhWb5vMve!3RZvrVcjIVjv*eu z#z$SsY9;6&slF=5*R_A{+2500x%#!=H`b8dpOChyBC9wV*FWx=df9b^`x9o@QO`eZ zMs&{B?uqMPcat93d@}AIH0-uCdj!Gp6|o{H+cXE)zt`QiWQXm?^M~;+#o4o(;rMuP z)hc_!JUl)H_jJx~C)_`S@lVB)<=K|waQ^A?Y-4usO?drua>TLhR>Ju&TOSeM^8D)g zYCe0$TRgv7{^n-(6~RB+R_m|H{UbxqmdXs_erL%)lH()x`5fh=)2>{XVo9H|{FAnP zTlTCpJU$(slbHSU3(h|__0DGBb;tAT7CY`|&u@4Ly`PHi|ByXpTs95Qmez;OkNz2V zQ0DHz`R5W}UpY;q8jaseV$77&4&eB?H{M^_MW5pq{Z-E|&$ph={t}P-Z)MTB*;D5& zMEf^7`aj6#LUDZ)dZ;ElVhHX(WVY8NMroCslOE7IFS^{r4>?LRl83 z$K7PU-@)o1$KE;0&i^R4tz12Rv}5Zi=bPjHO^*lKNBZ0D`pfn2RuZ6eGtQ<5 z*Gj*Shnh*QLfo(@&C*9$w7lJ zu|08qX<#%}Nj!aNM6UYv`H=0a?A8y*Pj=TZ6`C_KBh;wfaP!Kb=WRQab10{&2yAtIAF1%c(EJk8FO>;>tIrMK3MxCDVVx>i-wT z9r*;|`=u=-rS)O)@gvefS+fm)f9#FCl>1t^q5V60j3wJzwWyyhRxrhSv{nwc4y~Iv(er zyw5(@|3<8aD8H7RjE8`j{E=iiSLx&|G^(K zm$cxg7gf=pzS8e!<5S?Kfqa6O9%s+^$E-fl+q;RsGSHQC7^@y1+w2Z1V_x9-&)>HD zmD7a#H?i|&t!qvydpP6!e`QXd(r`7NKkKxAt+W!(&s4Zd^JDexg^Sw!lK+T5;q&|O ze{8k5NjcKff)Ff7_IWjyxF^BV% zYlQkc*5B1|$V+9!4&1-fOl-uP3HA4d)1~>b{F1ZEgjZa|^~-~26Zv3I93MTa_VSIK zT)A6I)#KyH)zix4=eR%l?slHiSh)WU>ra1l@VWA+J?`JGJXD`=FZlmxe*8^~Z>o#? z-ve)U;u}Wd{E%Ndif=qbi|bh1Un|d_L)V4yyYnblctHLBzdo}-+8o}`Ys66Qgu8nD+@7AUd_|qm{{8%J`N|;%3+d0v()zLZ z@E@+n&nm+8IT_QJ{}P7pe{QrB|LQs(Kde7);%AK4;}#lA`^(0US39=x-&8n%+Wfl6 zTUxquOD9RcpWXjQHu=ga{cwKtH?L6M(f6g}7pd3pc1Qmz4Ryol<7Mjg+mU*$_zNfS z_hV>Y58m1Z*Y9ng+VPhE;cshO`0qu;~h{PO+y{#SeED-XVNq?syl zedOmil3X7vuWrNjmqESX%4N#}>9NP+^YZgy(fynAJ^w?$dzE+PTM7Nun18h7=rDf& zK0Ll8+k5i8^KtwHTJ7Lx5IwGELvelN{4pT-AnzS!$_*PUj?4AeF-0-IvL~)j9A`aJ zt}4a*tDF7&uIwq?kB9X~hK|wZ2hGIeZ~Tf*d~hm`pQn4Q`0_ruetRA2!Ye0~)7H%W zer*1;C?=TS&=u#8@!c=*3*sm@Zkc-iuv$~D>^}pqZ}@-ss%-fm`03uZF@Mf9koq~O z$Iqa&4!pG;9-n!)fxOv&_}2!vo%pmZIRC`1TF)D$GO*C6JeBVK2tq@`k(o%?AOH!?f;oRP>cWW zu#g7qk?_IBpC^}E^MOKt$0l!SobB(hG3v!9{fB>D^JfGLhXffaDtpWGW0s_J^}7q_%d^8fUmhD_f% z9H`H)aL4PjFMM_QRb%n|*tmrW|D+G@KONl%yythk|1zV`OrCFt`&(bj-Qu?@%(K; z-(mj2;E0=i=TO$al=D;kp(ZNRvABO3*ELAh-K?B*su!acU!|Rz^Qm)P=|)%S{bKvm zrp+b+eE+Fm&Ea=QUo;r|IMPGD-;N-7Il@xhS)F zy@5DC#ohhJf0`rsm*(p671psS|6mFp-0^)>A!X8e~$xIWU38^xEM!0*rN z)^i@O6OHqeg+mbkZXM1~l{u+=r)Ic5JmUL^@37dEt6}iT@>9(|J=LbZI6uw2AE7!_ zT*ke5e(-Cf8o7w_TvsE=n4{%(LT{q;<}zTQ2P^3#O-gE4<}q|Xd~_gOst zt<&1TU$(~ctIoam^1;IQ5iosp{dYY7UHCp#pHU({<^1mOI-gJIkK^mq*LtchHk3=# zQID^9PM^;a`qQxc88o(-@YjUUZ4HpmPuW!Zcx4X)n_>&W(1ph<){c``j;>b$A zrEovvN?UPUUjKhncRTMKg6r>L-dViCZ%xj}PI{j8w_xpiUT2OeSJqt`XYuv)u#u{) zKkn~*9~7+`*s_fCIG`S19ljg$`5*E8eUWkiZ{8Qr-VAAHTU=kcRgK~o*yH}`kj``Xg*teD+pV|&{=V@24a`3s z#UJ9|PRI49-m0s7c>|okHqH9OZwFIu;!o-QV)3;+sk8HZHS5v5#xy(E>m ze!9&1ncwKmFX3G2JSwig{CuSC1diXh2IsG4b*Ayr4RL>9<* z3!eaS<#sUoiS?hZ9ZXeSoK(u0K1x)JzpncS@lDe3{Be2*d;X0Nj=y$E?);kZ|DnIW z1@hni<9x_D#Xi2Fpue#5A?rrv@Rdh#|K<3>D!$D}T`r%wKaR!MkP{tLbxd)7({i`q zU-ifFwe_J5KcG9V?-MvTzK;#gUyc#$`M*8z`k$9-C*Lvz*I(t%>AbD*ed!lW{=(wt z*}}*C84aAjDmpY(oos5#C1$I~&)U96RbA|^aBIyf{->`fZOib})DP*Z25ApDi_T(v zl;?+^{LicM-AlRMKh@)l*B{0o9gOpv@5>eZl#Y0Q`1DgKf7c4xj_;I+9 z!k@9n`OE*?P5yyf72PvX;y<>&IH!(=D(#mpr_J17$>J+vgNf?s6w2MQk=B>JA7JbY zqPox&e?NuKKk{n=@cRDad|e({~-RhaDNH* zeYB*Ief+M?I6nUkyvX-S?J(oA z>TRD=F5{AVe6`xt>_UG}W9#U>ZU2Yg3aZcG_v|Noe#lXr-#&Y6;0xyC^`~DmcJY;) z@cxM5KaTM~-e;lbQ_dbg%SSXSpjYom^JD9mN4}QufA-@1mb$coYSIgw-|T*wsrVka z{_p$RM%6_N$DfCw3tl|P;W|`2{@?mtkiGx@D_!_JL!AFCYUc1R|M2_Ec37<9FGS<# zhZV!a`TYMlKRj&sA^!I)Jb$>}v4D5h!sBa)!#{X~TR8s4{xneCcw)jC)_$K>9$%+^ zy{U?MQ_gLhCi)lh{L^~FS5?zL^{r>USXLWf^%(q(d1=GDr{m|#ro{#Eqb>3L^QPZE ze!;MK`nE*Gk6gc1%s<0F|DJ{R_ZfZV`NRphKh*C13%;{;75&>)dOunI3;ESlHT=9T zmpn)M|1AHFYVD}vpSy4aMo9XV)gQ_(8LG3ta=0Tk>haZj-(#cBoa?tp`%0=;zv%Pw>7GG@sVDNDw-(?jZKi=01=SNS#`_nI6 zj^~T*@&3`(z4LfiTO2=wE_~u&4aV{FNAPzPPjxwubL#OEIJT?mPNoUBYnnJNfB$y7 z%}_1Qap4|xSC6l^t1hVqf5_pYev9~$>z6dAS^Tf2uGGGx^gQb?*1fliUq1}*pM3K^ zm>)bJufK<$+sDTX_s?VfgT^nFe6j|vPlna6;FlGb(Ywt3`K-R%_^+X=H?PTQHkaN{ zHhvb5?4`PR*n}HDO#S+ujOA4Co8b7`)qXm!dmXROE*-v{kGH|~N8)ETrGh_BZu4EaLa+7SP+jq~FiRN7cJOe5<}VzQ$#@S5;=~a+T}E=jHx> zx2pN7v}6}9T3_0KmY>#@7pPjz%;8G*i1?AmzY#f)R2>V7xj(u`)V_a)>nc>%J4!f@ zD+m4;Kjr#3iudBzpT_-3@2&y->znxbl7~6re1%Yd!tO7)b1#|S(jC{wf1Bs>ms7In zX~rL8^ZUu)DtY^uGI}UdT0a(l%VL|Urd-7N3({>>$-jXstQOZ-?jQ9?oy%W&>PStW zNaIX+)Oc8L9bd5;Kc5Ek4)M0a`9|!1qiqke_(0+Qa;(1JbYvN?`jbz`yb|Xp_b;-7 z>#5vLaD25m+F7+dT$jtMy`MvlFEf1$mB$Jb?y#2h_gVcqecUpY*98}@wUs!3`T4Z> zdUsSAlP`1IOCJ3XKXUv{eeqf~``!a?%|`Y38gh6gZ?@c(o{g3MKFe>;O#=C0o$>pn z#(fIrwSD~1?@xD_ypK2Pf$Nhy4NvjcbmOTaS)9LIpB(WofrRg>e}Brjo;As8`RzKlo?mQ%*XMGaw(;e{ z{SmWfiTz0$v>x+gWrUr{YxVpGx_&Jas83HqL^Q##Qn+3c{Tjf<7G4_OT>q~ z{`=Umhia8dm+P@l8fW$EM(^pWs45me8kEi7g>RGaq4#nA>R+{$fBzW2Kjc)_KHhLQ zem|Fm@+5yz_&y_ce*2_*0l(t=aXR~<`1|GcljngS_-5L8|NUpuT*VcArhA`B&$Ige zT}XSCf0!n>r$`!S^~L7p!&LK~O*oeiBEIDK+q*hI)oGdwS5YDDKO0{UCzY$L+GKM% zt4nI*BkM0MF4ee@yRD2{7NH)0x3d~uhzotkT?d<5e6sn~vk!s%XB$_#Z@u{Y2kJ9#r=`Tp9hoYsns2NS^TcLS}*?F8TXGv257>^O?BLmRO#o1_|2H*1iGVz{!zr7-|Y5a z6TI>DA~sF@{<8it;NnX-Qc^&kwRtGPX9}Z#7%!;<&)Fs9)QLpN^9Va(|MQ{|O4PCI z6QZOg8^6(kN>n@i36bhkB1WIm{nn1&-tvl^oIYG8zQe1xh_AQYuZ;Ca1Wes0u2&A@ zQqM`>Pw0Q|Z95@8-h|JOS2|lJE>gqsz4GaMaYGTVZ@I5+50k?1`2C;%Q1}z6NfwUf z_m9Qz_{1fkbK8y#crP2jlTtQ_#}C8niwUAcae)oqKl(K1sCc0v&Yx}UK@4~B_@0~a zMEpqW1edDI$A1>T6S76nTN}@hKYY*zxz#v+SME0f(^TC4eXLz!vAGFpxXP~&i*NO{ z+hE94FQWHdy8lA|Yrgm+XoVLN_e9zFK6z_Bgi4nWC%qPR<+dnVfD?V}2AMKAn5_jbhbJ=#+V&fLNCr!53gM0>C~hWvirJh{09A2rCZ1&k}oe?KbtU0gC<>kNeoMxb;$e3iJEHSM}gV4$cqn#yEhBt0sA`F8#caKQAs^3loZP|NU{o4)N}C zeE#0Xttn!wjyV4qek4!4uN}@mYHe?dEiU8!dzi*2@v&do+_1Jh{#pNhzqc}^3;bL3~vn*AKSGri<_B;rt^h@|^hhc)WjZ&aV67myeQA{a9n_ z5An%b9KY*>JA(C%Yp8zu;=*vq@yGph$#_3V9D(Drbf5~|rd2{zj>z_}H;OdrU6=dh zXMCzme9qjVORHDEBwaLR`&aV}a~cqZ``3Z4{pq$fe@NCrMM?iz1k-=!J}pK3cM8rQ z8XHcE+m?r*^`QwJu8JE)xW1M1vs#?{DizhYy6;c|-0GF`9)pc0a#^@^TUiTa`b`1SrT7SArt=# z6Eem3{=@ZI%X}(+V2bxw#gtWvRqx^Wj>~Bj-~5q{^6Ow54RASy^ABAO4nEJr@!c)O2}0jp&DPnTncv_Rz*iP*LD!vFjOi@(O(gQ&j)j^7`1 z_KM@XPT}N7NPk}-kBR=YOB1I%;rN}BoiFaQG=!^mmfgR6$?vvUH3#>y= z>a!-w@OT@Z-+fgX2!nL$xJ65O{IUAvW}BJtdmPS;<>f>{bEbsm53KB;`!kh^;hE3B3z#f)szP# zZCw8i{AU372IBnd)!orBtp&fiFQw}%)ZaWRRzkk52~p`QeJ;fBo=jc3p?x_yZl5C4 z|85F1rgL1MlO>|TlIJ2$sGm(QA3+D^H=_LDUEOhUr zt?O(k9HvP&>+{c9{b6jobl7I^L1vX^O4f&C<_DhM*q(0unokZ@%EsTxq9bDc3|wD} zOv)E8KkAR3e{XO$MWa4+qvp%$I_opa6pC+5pD7|Oop5q{y_#Q0I5wCZ_>#w@rm&6ys@cyMQ zE1!tv+vEKchg|=Pt$wAV^S4eL=|bFYJbvZ(u!5ttU%7I@`9&dq(@*-suAX@Oul}3> z>zwUKz;S7O5!NrZ96JgP$}`A94L<*6@jXwiBVD%kEJ+(LoBuW^9~WP0xxdEjx^#bq z@$1B`BJr_KI6p8bxF@cC7mfDc*oS=;ug<{z>sS>HIHp|0l~zc9U#QQV&^CvsZJuyZ zEBNOuzbaI6g-;`uNa$t$Ig4Mn@My4VFh=WZgH)`j;mwaI{!AnD#B;sz^CAArUWs=v z+S)QSiO=s?eQNYfWw?73ukSPr>jiBm;r?&cGy-FK;Q6UrpCxd5lqP9EoqvDU|DB() z7d!&-{Qc+03^@IKDsee^q}9HJ`r`KUo#~O6XGl;l-am>M{oL}5F6|IiOdJO8Z2i12 ze;sxvTild{>jV3{T@?3Oj_Y4@>q^B>9*3akyWDIaiPv_(`DxG=dAM~jm5U9Nu8;8k zg7CH-AvPPYU)<@_6^>27>pulI{)6>H@cLxt`5ExkRf!1eBf|KvI(8HIwZZeVByKEK z(fEzxbN!ThansEtv_A7xuMK=?$#1avfp3=>!|SEEJ|gEm8WcO?_#1aM5IS1p_}kqr z2Yx(qCFNmk1e#}})QI6IipM`gFk z7>~V@&$IoTmL>gZ^V$kBWvg*3K85_~k4K?6Al3`*A2aw^BK~m>=a<9FZ;FF%;P@=P z`CjapjMv9&hBS*U7vb^!OL=#gW`XmkhFL@5jy9fu4%+Jp&Q^H-^v3ic#CEVF&VhV< ziD2sEHFtBxLyqD4wNlx0ad34s+P|bcQys>~;r{PRf*D+NxW=8&;_Z{=f3+?8&mh3# zXHxQ3X!FRJbbrAAf3|+zabzx}+;Smd&{9bf@#?pCwf@WXDH2?>=;TTp5YK z6feOKi@&9#22u-^yJXX29)E0qn8!p*I!XQkFR=oEj&admg%fs`f zc>QFxdKWmIj_Y$BjR%0)m}?xNvhkbP-~xX#as29d?SSPKI6v8VE*~6pUC8zI2V3zY zjL+Uhdi2s5oZl5)HK!jn%ZTw99>0{;mv8o`=bWyRdyPqU68(dze_I|NPG8zSAjVH* zri1-H9N*^d@lbNd80{}wbz>my=vqSl&We-iU&omZqaWYiB5vBU z{cD81EiM0BL0-hk#;0bU9sQk&<8#@_tKy7DUTA;i!{FyF^L_F7u9DUyj)}(O`!D0p z5Sf>Xp6>{`VG6dN&T$t6{f|O?PRkt)pTes+(y9-!`Oo8T(eU~)j=#+pGvSQLmfRcH znx8Q7{Xe%NP&ndDhINwdU)0WD6elH5LHjFBYafbxmErz(VPu`y8}R(_eNubqw+hb> z{k?jEjdL~^n=Q3pVSjn=*TZ1+pR3%d*7_&QA67o`fHz~masfT0pBLueJCv70A9I|a zyG-8=h1ZQyeYx<>b?CLwlZ-yiuP@6l3WxQfm1zYec0p@>o5`Pi-uy>rAGl1m%#D@c zpY_iJW;)R6emH);)=Z>ZKfEH__NGewH_Jcn7Tprh+3AJ$7ulr05!=V&_%;rf1K(9R zzMXuuVE%60{|+)UhYq@U{jW)NJlO54;+DQ5>|UBD--ikmY@Ha>^n zn+rATzoPY%?+;=?>4}D*zk=llw{-Hrv&e?zYVr7E@oT)|x_E{!o_{HHeI>5h=8xWw z>Clp2eqI~R1q|i!!OmBVY*vHq^KkzgA7KoQ^KgCS^Ll&8{%{r5?@hn1hQ2QqN&Aib z`my?)MchHqS#C_0?&1F*o4@%MSHSPVo}^tWzdo#gy*TR=9JUA{^}l%hM%W4Qd-}#O z>hu`MQ775>^`{)&=vzkqh-LHNxNv*gZ`3uE-*&q`o@UIfAZ?Q@QM8Yx|W zA-@2N1#n^oj$a?6SXh4t$8S%s0;)1Lu~N;?R3^VadJHFe~nD# zVNg7tzu6~hf~p&i-dB3Ga7YrvLt0^HiKr z;mI`vzyEB1{_N^s;{L{===@UKJQYau+lt=r=5tUVG<%Hne{^{21zU&W_*EIO z2~1BalDmTW=EC~SedSE>n2r1IA1ZHPqRK3?AXYlxU1%7-!%(Z$L7fBGNC^xrLi_fGuI%ac3l#p8$d@89Y>!y0XzpX7frfx~{d{&6JO z9?qUQhn`=4oD&MQHDA#D-M!Bq*u4wS4;N{aKu-r-;-bgf2aEsBE%TKQ)VZSPm!JNu z7r&c}>l@WIBDm2IjP@UHTc84Gf^hunm-U3V?eP3@u-*`ut%l?ON=u#N;ZB? zeknk4LI`)*O==%Pe!FI(7IYtn$NwIy`$E!0TwiGHHxw}L zq;!9T`i8lu678`vlsu?y^{gZ@|A6%`D-wG|JqdV zZlF96kN>;c4+PV)R4#e9w0}$3f6%{R984a5jw{cU;!~KP{T=QGZNsi|eOu3mvij!t zh)Bpfh2y)f_#n(1t3k%>mad-=-)1vEft`3J8E7aQzcG`o=zrg`h5w5%72k*#3Kr@?T=G6V4pK^^M}7d^jv`OxgxX*I$U= zUWT_p+Z6XNJ5t-x%s-*zl!I*lYyY+rRav@@OdTrSKVg1Y*6qFcdmfJO6A{0~zYch! z{hzA42f@plRKfkW94EwYlj5abunK!o7Vfo+5Y2vhr=++ z3dgU0-*2#&xRdZZ()SngudLH{^xeBG((^ZuU&`P&%ylxoJ=pC^fl zn*IQr|M4Tr@T1RYN+a+PHLSbjV#K%MT(j3U=w@aIoCPKa;Or6C~@;G5N!|4&TKodQ-R;^LhNS`Cq{3Cb6F@?!TL3I>56LA?W`Y4ZES<_~sOYE<2_1;78v#&3T&O*-aTBw4V6pKrHqYm|gSGh6VmvY(oZvSNjtj|v60#EY%gT?pPf1@De3U2>N3w$AQ z4xV3!_i4#5GQV&mCi3gc`tRdQ#c-MSCTkt|^<(pkqkEd+_pn(c&zg__EWXVQ+ftJq zi^y5KX5K$=-39um$xJ8OY1~Po`AIhaQ1FohXIn4s4&{HJ&0jNgltFoyKYBm4;c6YQ z@xb}TyiNn5t~3$t&o6&F9c(P|_&8zq8aRFu_pf(P?gh>HxIXc9UIvU(#q$@_K~LZ# z*bs{k{Q9!^oxVVmJ{!7*6wG_lYX3t1d|0^)b&HE2opjQH*9V0Dw<5k?tmc60n`eiO zgXQ%Q;y!Vm_@!#T~EKnHI$RS9ZQgO^5=#PWD9mPxWSXfMaJCabwQ#|DUZ-k8@Oq15ZQH`Cjff zb>Yh@+`qnA*c(!N;PXS~FR%rRk;3{C>pyZu9w1jyh}M@bJ&Odhu*Ycqg!mkQG2;}; z?r~E8A=D>2<-Gv;EF8bT=Qp+7zmCWMv$=yHybR|*Ws@hus*5;27xrHUuTAm(l2z+s z;iWmwU%M0+!@?cCiB&&-|5*R$vrdsVHh7RAGuilC{kj8vp1z1g2J`+e!cOS_mQ3wR z`~6r=o=lK!zeC--(HG*iTFYR6XE*MwpI4*1(KyMMApR_Z03)vfO zNZoyYe_8)K;cgE)a!@2Od%@2KWc9VK)x+rr^SxwyvGn|uh9Lf}?j{HFJEw3f21w(( z;ISy_Wk*m|Tf{BvE`2{?{?YHgK2*8j{e#a(4}}wjxc&S)J{h{@;P!JkCG zP<%zTHG*xf(dhl2BfpM-%$P)OTLW)jEWiJdG8L-ZWO25F^WDPw&swuE*e-|r=h@=J zAa9HFrvY0_;8%8^iVsVN6yb z_b8EH|CX;3IFQ?3o8j;nJb!W;m;k1YpHcm$^xRoEd{-US*GFd8g5ppca<^6gWBucs zK^$E?cn^6OwO4}A2u|q#jC;G$9VOW$uuisp@BE+yAM0Jw`uh?`O_;mYk23;(e_4Jt z#L5J8O>zG3?r00YG7{1Gp>xbmz_`Z=GYq0I8ny!6`ZdX&PUcwNr(OV zI6r#7ybRjD(IxF~@bhC>{}{hrg=X(|NA&~i4jth_iYMBCH)M2AP}~#3Z8edukFb98 zv!y<}B_jr%uXsp)A{;AL&>*DW8Kc$=?yV7Ly|3>3^^t}CP65C%k|C!*@4u)j8 zqWX#9xUQhR!w>C0J=)0(Zkgfn+3g&G!K?B7bGn)*%+<@{s$He_E%cv#_C><$V`W?~ zC+Tw`{w~%X2gl)xq_@C72>E$KbWbX(3nDp+t@Rhi|2^)|m*#4(Co=}|@r&i3HkE3i zvKhzU@0~m)hcY!d8Cf z?2k$RzmT6yh!R81CUx?5nDn_Y|2$B54U+fuAh*8p^K)4H93SxuqCQ%a$w9n*vG|M2 z=}7lX_aJLt^7;;&pYAlDOJ5#3K_2AE#%IYZU;3->X`*Z{8=q!3mEjd}MeolwiqM9B z?fkfhg89Ef{`kn-9KJe6a~Hbu_+j;F!`}{IYmmrA$4j5L5yY1|mATNXUlvys!9QpH zBW+p-VR1M7`sY1nS`WUgrii8avE`cvZ??-{SSU)Y2?~+`4&RlHaiU zbovi-T5Y(VD9(}Yzfd1J;G_ZJ*`BEW^!=$J>|Y;(_J1zW8V<7yaeQC3nF_P}3G0h& zetx1;FuYw`h}IVy!w*2y{?91?wp6dJWunX_Mva8~OF&bOrm{ zp1TPpaotH;7=Qkf#s53MKTvktnw<8NjekcUU;5cQha8!9SMvR={*r6Dl=fS8M!>Jw z`i&o_3QLk*(f%d9F+JeGmxU<4LpBbCOCxZ6UtjMC$L(-^`oUixSoS9q^}oB??1ZRJ zcznA+PC|hJUSIj+*^|!y>`#WZFXz{X>3^QKyeCcQu$bsI{o|iA`YG%mNd0o6$=O5F z^%vr|v(7d;KCqnpox8tve}(gLwZCdX&qN&GOU4>Q-*v%g|Htjl)-Y=uol*WF0l+kYhM!!h{3cKJ5=f7Bs5@%;HJ7XRD+G(&xvHTkwyy8goX z9_oo2^sg@NpG-3rQRR{x(l1B0eNdlH052w^{SC!S^xvfDdEidcQ)T;a z%@}=p(cPb7qgRYV^+V2ShNGjr^q zbTy9e$?ayrf5tdJIaSrtx7`x|u=8yrN)JK$44nUxjb%_h4d*A*Kiq-+FS?OYFJJUZ{r3V4H4I4d*$m+8FG77{+o;|&`Q;LF z%z@`8tbRD7U=U515Jlo=@}Fn%ZLiiHX87X%+kLt{yf(z^i-v1vgGyP7VE!k|KOPKU z0_v|aITt^ve-`E+4qlOPpWyt&Pdx_IvdYl&^}{x%!QLL9xyJ=k|19+1ZP#6g5ku8U zx~}xO(0?EOd>{G;Xp@{Ip1-jEJE*h*=6BH{Rg*8a;!~)cuUNPN1G^GuPA|Bj3M z!uI(===@jHu;Fm={yKENN1xisu=P#?XTOTyUsk_^J7c?7P>%h!;krtG;x9h4!(aN`XclwnqEkUE*}1Sqt~?uQcaD=$jNl z{~n9);j_0vLtvTU{96Pk%%4lDkHU-cT9jWj55Em1eQ|!FvbGW)8ETV<(`DmRr~4x? z-=j_JLR;$xTn_>N-kkmjMDjR(vubqcY!!DB`j?M?Y<_tvqz~N{9Y8W1DtP=e{PNiT z{xDA*gwAKG(zbzTeWSUmMg0D=`Qfyyqrk}m*DvR~PlH2E326Vvt9|R>)(E`5Be!EO zlzQR#y8WyO0+JPogD(I7*z+qPc5SFaoHh9`fwvzvKOcJ3l72fEPE5kGTGvN-exj*< zFs(SUh773V>u;?8-F~+Vlom`z`_D_V^kM!bPj0f{e6+AX@`IcSydSiX+uVl#e{6hv zkm3lxG-9~jpLu@7_CGDj@`cBTasS&p=#zKe%Fg^zjK#MV@{e|{YP6neeWCOQ+F z_|G%^{6qUsF!qoU@qf*)AIs0C4;r_pR zwS%6Vf}bD#RJ)V5y?336Qk2f|-`_=Gzw^B<;EQh%dcGj4&<<{j@czKtf88LYApxzg z#I0QkrN{92tnPFGL?dzg5z7NuFIFJst@YgqPN)x#Yf}y|0M`#lKs_vZX-1-NX1DH- zke~OlYe###S`&@g{Qj`^7dclO4xOKj>Q{yD`#^)sLawvme63Kws{H8(-s@60hvBmG z%iZ61!i2#%|F-{`4LeTPqWWOLuP0FXqYG(j(;#_2%HVJMif8b&T{n`~i^ums2Hy|J zE7*2jhpcITsdasX{KM+z7f?<%BBvVp^}i-OSpdAWRhNG)F{n6JQb!t)6i zHO7NjAMbB1`{Mz#uP1QrOL_mz@{ePOHiCO@0at6!KWFP(rAjG~-5baE*l!oXe3lU3 zYR6PIha<}CMR^Kpk{A6b9{s{fci>Hos zT*xN!xJMN5{zF(F3%%PNMs335OG92ih$vf#)*tF0Oa%QOThRD1>ga07UV+Dl0VCtV z{AMYqWyG&P%a2CaoP@^;pV9MOQ%636Zht$Y`ugjpXArH?g;Z+SOV&q?2=&LK0dGL3 zUYopV_ncop#=b_?z5y*49pZM5j~_1>eQb^8claJXI&)R%(AYCOKb z`ELtwKMTcQcER&#XS5vzSX{zc6B zoH;8y(64=Q{r84bPdM^&GFm??KR5uEzFmm+AM9401B1RNpyxk~oj?p4&j=v@Qug~Cf`iL3`Z`3CFdOSV@7<|tD zRs*TwIz;s&k57Ff^#9%e{DK}+jfly0+4xM$>`f1Eb|>1Mq|b%?<@31_^yiLHa!Wx^DXje~Prmu`&sltT z$aw-OFFT|9@ZjQ(^i{nTIzOQ8dVP2`1NYC9`;3L}P3ySojne-wjE|zl^I%DQ0$1ER zAB&BD^>3nJ&luc42dC_YPg$jc{(}@Ie{CL_504+>`0nuOD;yZ6OTKr!BEk1S2A>`N zYXr*)IKMvlvk$fSIE!3qi35E665?~rJ8NotFoY~QpCS2vj?oW4-P=a9`WF(B_Dsq7 zoD}AK&hG_B=!uyR$(sSmlFzgLceRQcoDIkEyW7wj9DD*fwJv;q%+7CbemfN|Jl%r! z-`w*EhT^U%g893we$Yu{J2>nsK>KGa3Xj6WrH|12o$ma74x!sR69=)>zJ>bM`uG~S z6WW!$e#!Gsj`2UeKfZ_W^SY6#xjg@z&G?_cKh>z72-kNHryGEyF0M8)~|C(GrTjw{qrYh zMcSd#j954F@$m%{A63Kq(GyQ+5xGX``w8vCV51$?oftxTWXQIUK7S6<1CMVC{5Pu~ z-rdv>vOjwW_y@-c^@YE^>|miuAbNkn>18uuz0Vfz_{7%rvr`h}udh;9Lib+>1@jMC z{0}tT0U1+pe(vF#0kypz3FdEcoUs4V)~pc5Cf1_oyH6=ShlB$iiRSg=t^P%5AJd=) zb`H@Zi@o{y%<{)TEe+c9ixpa*TRE;b1S{kCFMKu>G?pzy&;RN6m;{GY)(QG2Sp1)V z>jyLd$N!0&8$ihl&)=g>4uHj<5^m`}+4#5Vd<|UYi-<`MpC6_$`1c(A3wBm_Cwb3g%6-b3Z6uJf;4^$@%`Gz zk=7KhAx}2*pO3H;=09o5GpO;Q%_P4@uXTTg^XI2b8UR&yg!pFr&#M&dVcf_-E^Lr& z|E^Z!4$0?n|9-u4HI((m`SqU_anNQ2j&JMZS&&d&$w|*wviSaSq6k(w)}sAw`ijrs z{RI_b_+6?m3i17LZY{Kx??Ud(-H`GHN0|2pKRMepZYk>ykQ z_`>QhdDo+;|Fksn+%1Opf6V#8!y2Y=vNx{JtVtaK@!J-n^KFM;b%CNNJip0UwgmD$ zaQm2Bwh2zW%|PQr`q+c8&W#j*xrVR}~>re78r1R^`;J ze_(mNb3FJDcI3%JeTx@6m%? z3g*|BWB8Tf6GfW-6t}Mtk?m>lt3KpdB5z+DV_(&a2%YY{guI!bDAPVt6w;{Wz!v@8 z?1)VL{lRHV7{7WJdVWdKcnsW*TfyDE!0SJ3evqN<4f~#N5%j0B_R)AK3QoT~D45^K z@}o=QM2Hz(fcEDf(7y=zC7-xsN&Nn>_>T+u2(Lz}5nE-RpRxUWJtlvHv^-5>70#bu zVD*QR9oqE61}jv5A9C1|c5UNH)DmU;uW?>JwDxZdnR2tYWc?%Tgz@>z?+r92D2+IU z%C?Wjn0|2Mp$l3cORThmF0Od|P{^^a{^A?A1nst>t7J_Q~H zm4f*otbf`Na2Fo7*oTubA3s?8*w;pp259ONv+X4k`(W{(_pA*amS;$4I`3auepR+w zg_b0>@T*lk{?!=#cRxOowmG_(tbUsy6aT5)PzW74OVFRn@_&7=abR_P1}~WeN9eHjiJ{zig;K4Re$6_5D5mG8|d;Nl-sz@qf1b zD|kD0CRct)*H6fgHg^04a}VJ7*FV+>#r?YxYcsz79>Mr8g@EoZ2aGe>ks|3T)2d8{Q9u-7slq=!#hnpK4|;6LrUm6?q2Ks zVm3ZBtP6$NZ{oT0j(mQ}>PL@XYzM;|8EF6N`xm<*q4q3VUwL;k4cd+@;mU{e|NjLO zKhl!!!?eU^Za`Pr_Hli28+zulKDn~?n8ZE;7<^~swxikyaQlcDcud zNA=@I(>9$KlaFDt?PHYna9E)1!Ci0d&t&amr~d>Nl<@e@$ahs1D*}S@!#Rm9}op;kzWR~^Mm$V znqgu|i+;3=*N52p`|mUb`fQXg*%U5Y|FhXUoJM)iBKu8w{6{eNFP1LdO1m2!B^CX* zO7@qnKene9pjGIC)_0el83p;#3(@oO4vC)dC~h71DcOHEKTW^?4?630 zA&y;ne*S{#ZyIqyk!EZ5AVEiY{>bXjn$2x#lD0kxGnef@{wr0c30n-w>s;PG+4%Y% zM$mTY?!|NfN0@9W>A>Hdv=bR zs=&3RnN!;#8{fZDd(wlx!^y+nJU?dfT{3+fb(*k=Z5(jK=$Nwi$31V8NjqN3U*)G0ZJ^p9@kpUnM7W?{Ba#^Lt0^zu>&ytsv1^Nhy_ zYd_vywt!mtLA3vM`N9lve_xE+&(PZIaI)toE+m-87wf+VJoy8=f2)z`NBr-z{QbIE zjw%lCLVh^#_L0Ka$6!rGx?fG3oLSW*S)YLnfAP$3OM_PHlFaM8|7Q8;{k zDrfY5?c;V%;AD^cf3G2~Fz_rMpYMF}hG$)IeQ9o&DDVozc-T1|x3BJRlfiVw zS?;fbH2w(dkCVKMK;z^??!sPv|5^LmqW%mrpEq-BZ^*W2g zai<`z;1j>UZ2o((^9q=~eG94&Y39Vh5m#IvTJ>gd7nSOe@i+MTPYTl?V!Ng-?c1h1 z$*JJ=4YqzTab`zaZ*NG#TmK&$U+j{ssnV6{g87@QeLR*QPrJAEBl-bOlJ)19^Y5l4 zmTnC`OdP7WNbHB@PuhJ5j8_oq-zcK5m^^2LaA_{IT1d z3aS*3FZF2`z-#V9E@qx={C8J>36E-;xrzqa_}}qSgQo5=A=eMe#=m@~0llv_oJ_mP zW^GM`rhd3S@ZBT_YKw}w3C8^Q zv-tfMcMCS<)^L7ZdH%=Zw<=LYzvrouBPV%$v;IHmavNHq*p0Y`^Z6;q`1c7R9cW&0 zPjcgZu>>Ep8GS9Ottw3j&?7hO-tzci^iNH5H5z4x<9Cpk4K3I#8=H zTIMY#Dr=7N-_PjRv~C3K@9ct}Pa7NK3|!BJ=>0aSH{4*s`#{wHB)nP(@H7!-f)f zv_2lA5C%pEw{W*L`2Az?6R|HA5+~vK8FDfWX6!kO_Rkv~zXV^r9t!&JSp4*<{0PhX z$P=>-{O@y&{$AoPPf4~Knt#={HKFvzFmm=1k1y6gZtraa2j@GZ`crklWN_74fcB3X zE?*4is-n>T-Wv)VA+|DJFh7yaUmET9!lx(4Ilr6I_Y?Ma#Jik^M9X6C^cCJevi{Zm zttxH%syjK=p6}0K@wZJ|lMYbA@n_b(3)Ps?o2W0BjlYO9cC^!g$wY2ongoApL|DI` z#d!W>*KH^GK1=3oGNk-gIA3Gp$)k|I z1dsn}X2o#X9Ou9Lrrm`>-fy`bkNEh)`j~N05ZyO{3kry1SNmtxkn*V{Y9uhz3a9g zeDjWT|MF$yzxK%)_~;_^&mtl`e|G)zXXvSk`v=7*D)g>bS5kI|*Z0&I|9noa3$=RH za{hELZ(l5b9TCxm<}WiOYZhln{41Lu){2~I`&Dy@&c8#F=WKr05bjEgX8VvSU1BBn zLz(l}D$nQAAql}GE+~ZmyhwOHSoFr5Y7~Z$JPXxv&Xsnucf~)j1QeX3ShZcv7mm<+Q*0+HLzr30~cKIgU1)wQ}6=KM%WW(>N_7GNg*PAC})(teQ+y zd(0u{-^;e2?he!FysOzK& z=I0}@`t+1&Rl28VS5lb4`%ji%9Lir;n*D@;Iyn+=&f6Eq=r3y3+Vobg z0a_nF9M+wxFEeVHZ<#6i{gaG77JGLZeQDrLiid22|Ka}y6MvkEH{EeEfXGb^;{QL> z-=;Ot8PZ1L`N5AxzTiezaGgSA+lR`(DA@IVGa6s^97=@WaX7z9_dEgZTI{2=g6Cgs zd^vXSA^3ED&8a?2m%JZ~|3iJ+)2G(BzHsKoAo`)+nsjKJEBQQ&UyFv3)NYRuzxoV* zFU%SPnVHUL{VrtaELfBw#4pDQ&u8`@vJwWai9+iiH458-9K-P&vgZ(Z)f`9Xi$(0c z0UGNcaH}TE_8*&@KEbcCzd7xtJbpJZ_zmy&4NiY*;+&KC^Y`rePKV;3Fm$zuob8n( z!A}H(-(5=epjISD9?X#bzA(N#kLyl#;_&$KtwERi4eU*<+iq>er?5ZPYyC{RL~S0i zAloJT$MUN?j`Qh|`~YI_%j28X54Sh_(yFb?$*nnolK8;h4_AL^GF&sj@qfIHA83zU z!QJjD8~;ToqG8X+&1iqrr-i%W_RM51HjKwNTc5nL`Xn@KoE4m3WAT5b;5^*Dc!e8Q z$@_QKKMlS02oCjn#f|&N=WlF&(Kkz(-Z#eW<9p{JH2t|X$?7cIKBDK3p;?iWNandi zlJ#fp!(!@K=-Sg6tq;bS%!WM|d7P z*yE`F^Ix~ypz88~Tf|B6DU7fEpMHXy1AcHlmeon{H=D7KeDWJct^3E-_?Jqai0ggPqPe$Ol7B}q^^Y?@rog_;nP`5oD`_!odA$PFC-=K- zfD`v|{98usg;T5W{9^CfTzH^>`~NssfEAyv2>NeW{(D-j3Usf%;M`90{GN>u3x{-| zh0i*X*DY~|Kc6M6-#aCbqYFjOWN;YYU(4dVuz2+J?v_&?Nl zKXmSm`~QxI^5EsWe3bvJ(0vLo>YsCEO*}qXeAoDWfi>yhIS&ioe?>6<>*8Nk`k<&2 z8R;U$rx5=i1NCTxodG(Zep2Fi8n|W>x!8gKeKvoNu$)7qG<`@-mt{PDnEM|q0w+R5 zXPp1fs-Fj5nezqnE7|xkYJ4OdY>5wfjZ*vx&yT+OZx^K5#S6|yv-VRFbPTQ^7TQk) zC(N(A>)eO#j<|kt;BEu#Ee@ZZnOM^cgtpcM&1`(gE6cObs0~-jXDT?{wCDle@^nImxJb!(eDFVe_yB{4hi$6%dadTc~6}rpJ(gqtM5C5 zZ}}ut-x94|0ABNbxds7$7sjuj*P`IPF`mC1%Z-PTI(Yq~X+s96Bpesq&&S%|kEjRG zv%CV;KTb|~4hp@Wb3;b+{)aOC5xt)@fy2~B?s_I~pRE3S`i&f|9w$d41@ljZ{Ht-R z5q-GLkPP1?+x~_vvZj^R)+GD9Z2Os07)XyzSb^T(+P5H>>P-(KmMc~G_{7|=bpO5w zY?_J3pMG({P=8?ss_&*PkAXy`EnKNLk8f7r^=*>^bH*j3{gK7FB~Z}`w-1|lKj4h$ zJ7?V_+dg_-{RLJHKe&$G{P_#kKJ<(_)1j+65&0of{~(M%C!Gzcc(ef-`%wB^IR9>A zJ11Ix!I8|~xle*`5tE-EIl720RPht&gKT_1HhL+&eqk{gpBE-G|BG3_n}!x8l8)gU zB=*JTkG}6GgPZ*%w0>w(=Lda1%opfaZ2YoUjfOtIBGLN&!`MW)po`}>ZwD8`zRURn z{k`R=zChnqt*(S8Cvf|L&=;_K|5GlkjMwL0F!p1*QJw~PipXwHK7LUqzEn%KJ$dQTVXE3AL|^|lNaeZC@y9}x_{zOua~ zKP>&m9jN2qpXFaU8ULV%nb1E`CVy<6Vnm&+dXdm`TO{~n>q`fXd(#P>4bcAHty7(8 z^g}1od6Mk-@o=&ixNGD2UA_Bacw2(w_ge0H7}^wx>Q~DirGla;nbWu=Ti+PY6~Tcc zLj1D&#%!p9Ly8a3{*u1cFTrZg6Rzk$ie&%Qi12*mo*s%cZkmV``|c(=}%Wcg3ByD{w?+KZ?@;qm=~=`TNX(U|Hz z?}hTC_}4Bp<^DL5GbvfJ|7`xDNte;0L_gxVYz1#WOntTMh8gg;CI7(gf6a{y0OL-+ zg8p^Zf1lpE9pbiZM*FAt^*93Me#z*3RZH^=py?~j?^yr6>+Vy?pNsqN^td-rGv*05 z-c^T967&BFdvf5|J+*64NvWd=YKl(Hz6bJieSD9YajRCd;x2lw_IQu z-yd5^^aSzO;Yl;RnDK*a9Pv%EzO4NmxnW8RTkws|mw08_ho+7(Acu$Y{F5^F@$;V> zo$lmJJpVJ1;6K7nsDBh+^@hl~Zrq%I()>f{Uk3bM11Ahup#3oo4Y6P_Z8O^6Y|)$s z;}$2Q_s?+C0cMX9;+ysFz1&{Fx0njFKj7@$YUr;i^zSUbPdsl++jqqCXPpsUXq*S` zzvGvTq(d}Eke!=(|4$kG{Tb;>$7PHqxdsO$>&yC=8Ea;O?L6GSZ*5)T+m&h)+`hhRJJ1f3hLON&y#HbCYqtDUy5zhg$+F!q z`F_frpXqkOgH9RfObW*F{*Bcyh7OtqDKjRa=jTm#20^V8Zhv74Tj25PNG@7%f0|G~ zJmP-y^}{7Pd0_kMn4td3+TYyEcVVgP74BaJ?_b#Xk$0*AHdwsp!VIO)h5U8z zE_rIX@(1@PmbX8S;a?YA6=~?l-`v*Sy!{n0_P43H4UH^n;=Xq0?Msd6kH75Ip2pXT z(E98EV`W->QjTnCyehFD5o5oW8_ej^AU$F?g6D5+e44klFEtC)Cj*1ZB%go5@Nc__ zezfZx+`ju>^P+w0oXMR`Qwcsq%=r+tfTeU^qZjFrbx)$7a7_J5_47(9*BR%31$7HR ztcl0R2QBBLZYM2A>s!C=c7cOE&i{UnKMqI!96;wc=8U@xh1F*S{n4y_o*wrWbbC~w z=SRHlwJFKzi0X@hGaP8>jv-`*VP>m+3Gd%IvuY}}YCncVE#BMuT&OQ@O+QGzW8+EH z)Af@5WA%@w177gTc@oAzr`Q!Pu8ivoh5z$L*(|xeDDN zk|Q7dc>7`bwe`4ubo(+rvS1`{KM_p)IzPdj*8Axbi`Mxj5u7moomf7Eeru_pS?}ZR zo2~CUwOdN3S9=hpcbg>p%f>g0m5abe1&>eDSFVFC6PKg?Zz@jlP+Po-duPbUXI5W4 z-!Bv3366iCsA713?+n`C@c3C1i0s}A=3j7(KGpTT4xMnJBZ(65TcLh9VZ|sq+;1>B zcZEN{!R8l*25xj!cSkbgF|Qx8@n@LF9D41;B=Tk&AAcek|5Fe>2TsF8w7)^?au{5C z>LWNmz~+w~6t}^Y#W?;eDpFwK_FZUysO9ssU_bwupud5QKNr0ofNJGs6#v^t*T638 z3RGW-k5;0V?mxJ&bA0@vO#IopUWs;|^@AHJmTeyy58Bg3$D6o_k39cl=dW#@tW38h z{pE5Kc>J>Q;fPlU8gfO1*2kXe_NN`}^~eMp-hM^sK`w=nmC8)y^Fnm1&<#&A_N5ev|<(z@C)INmw z%hq`&!a)7a==_YqX4#&1JdkUP$CoAF!y#j>kKq0v*1kerx5J$7kzBw~o?o&3 z6$@q_g7ri3{OXR`IhY-Q#}`+dO32-GSuo#+jW1?SZD^a<-?($lkL>=JKd|v*t#=!0 z)%iQBuMMngM^AkC%?&Q#^|eZ-zHC>hOs|b^0K1F46r z9!Z|W+Yig%jB^Ikw3mA1KlkI3|F6dAH&35g&|A&=2Qw82gx~JeJm;wIqKA$c{hso;&q09Zl}m%C--eh}qO3 zVjQ`&OiyATA|kX8s+>+0T@%P0C)xT~h|T<#`$;FF_1(;t`5FhBe9-#tE3F-%YK_OI z&-O>4#sueQIW6}Ojd3_8=&xquQ~!ofpz`cKnt$4yXiJ+ff8!e8^7`{`CjKn_*Phns z{^pj%^7+puhM&2QR-w1nHE_S;`TB1JV?S3-J5V|EM()N9-hSBpD9XGORrD93^)0PE zgXy6R19DDR>Ys)9kI)!SJ>K>vUu&`?_=;fq@APe!gXY)i+;dMpKW6)jZa&xu)mF>V z`flLjJuoVD6WU*`9eWan`r!J&kiFO8v-ugp{3X^t>L))0w@H+Pg;IPA`y+-E5w*Ja zhPzI9`=N~e^zfCZ_a4`v_k%6=?n!^^s*=5D`0r=q%jroosoZ3H;&L=Wf`2xCgxk!e zPDx|QmI*y2&r=wFHfQQWIMZnos_(zu7zr_VaQutYcY?7-BznGJ@4+;Pd=)3SpM}+z zwQpU3pBl#m_k*(dA3XdEOijY$^F&UWnm+s?=+CZa@UMDQnSM+7$z3U_lHiMtFMT$5 zpq5$m>5o|kr1Q57$#Yi!mn#`cN2ME(krQRx&qUpE^j63qvig+te2XxD-86IuU7Na= zjPKG(vj1%VYLn+t>U1-n+&7f%A64E5g7>TGT*DgK_UD+k8LC_If0fq$YPLV=*oVEK zz8jBEWNR)2dE@cPG~gy2eU`_4Z@piGwZHXUDk1opm>Ydw8b5^g*Lj*8?KAcb_qU$c zZ;vtdx8SV;?W+79z5m*6yFL|psFEITQhqGVpBBaYQeW-y-5H9vFI;(WxXXRJ&*u6r+XE5SdUYIWYO!-0jPE^g0AXk0Z z}c5rvm4tg|1@FM9j1NbxNJTm#_#FLPuY&I zXUVd2JU#%_AF;xz22>6#Ce251{C-6Etv9$P%sEgho4TuzFr~vg)w!GC8 zVSiC+(Pq}L-*RDpd4mxLSnTI0;r@x;6V9`M4m2*`8i=Qw*I_s{5ar36r6IOrM57qbQS#1XE z14{mcs^-tmOAFY~*<$^5rPBs>rZhy@pK8!zCyNRR6V^u;b~(v(ZN>5X>Z{M$fSYoD zBp`l_Sfv5ccZ*203FpT(#1FT>0gbs((tGpS0sAgw?4{~8~4Aff0BSx}$v z|2mEA-=pRAq1pOM@>)Z+{aY5;A9i*(r!#i_#lM<7|5Cf-02r8OPNz2D`-kxUdhM+P zp!Yxv+Iu_a7v3LC+`PfCyERR!yH)!B3REAm_4R}Go9*bO_syj11xWwR3R(?^?)X#f zI?2-eV|{Y=&kQzH&q>&y(VxYlbcQ_~dpAN;zQ!VafI3HuM~ zq~x&UtB#Y(Cja^$$(g3o1(UcGwa78q)$A5eyp!FR_|gFmg4v(IrbDAx^suHzs%X=BI`CKSvFq<+b;)_ z%d*R}$iN5x^rc*1-Q8Og7T0`94)jtT-`snr1%r&l@lBtD_28H9XYw|b^DhDEZ_8b} zK#eQN6A#t=(>qchrf7U4_q}<1i~ZZ;Gy2ec{!ij<$@7=asJ_?p%|MuZ)ts(3R?WXm zpSAGBdm6oAyk8|hdVIbNcCYqR|N5t;^QRPO|NO(>A|e~-_Ajm)F>Oyba$uMZ*e z{Bs@O%dE3YvTVKt=Eob$e3rRBi?ms-njaVX*Mwm;3dz`?)e?Si|I;?T+F*9~wXl8@ z-n$+QZ(mNFwa-iU$0C08zE~gHrhOqET{u6|kbkn)*MsmH-^jzxJimhD*DD?M;oSG{ zq~2~mzX0cly1cQ1C&$d`ot~=sk-9ewy3X^XlMn7w$&a4TXS4Vh!-f3^$KI`Bc?pw+ z`fT3HIOeUrTy}mq#=q{b1lFQ>4I#Dv*+=>LBM(}iVJln23;VCw-G{8N@o}P2&c8qA z$LDK5+34!~vh(Tje3m7KO`vtSm>;c+Tf_A8I`pT3YJO<%cZ8%*9ccIz-k*v6hs72j zxP9M>ZrC5K691`t_Q8Z98|XXzm4DY?zQ1K$t&?zfVH~~Rkmtt<%0E;;Q?RZp#QfMA z9myUa3X#S4m>*BWQrYJiu|D3~^(vdGo=mnR@b$&~S>|8BQjTSkm)m)KhxMJu<~q>t z`D@vHa~$6kG}DD9I%ULsD@gB;^;=yvJqR-SLgLDKeGcol8*Lkcdg(V3u!Hjh&qtg$ zs1cY(R*@Yxs`a_aX9|0g&1oMG)%>VhWecCqx1uYDbA1?$?BCQYvtUT31D)B%Li)ad z^x4Anxoo`saAE#nljU~i-efuX!BqQ)y$2GR^}{v7`g7k+nQUdu4&nJDdJiA7!A<1) z3y}YKrJS#7zx%#Wf89~`ZytG~L&wcljemCC3F50eP{$Wh{>NT9 z08dAR)77gv{&D|Bhx%*T@?sz1{>Ye@N7zxbDB1a$*ni$pyUvO~?vu^m!uZwvUdVDQ z&XB`T`1}BjUkzn^-RtUWGV40WKgRF&*t)~yYoLwY$`lEwE&TtoIf zYH35*pH)G&Jv}JhkLNev>(Ur#%b%okCdY3uivI^5Y6@*<{~@CNU0OE>Lz;4by~h;Q z_{=d9F-1kuoeC@KBnuqI1_{RN5j?b5~qQj%fM z{>AoZvhQBDP>Jup9;)qs#i+AvffClxeXL(kB6465qRi{+DPmlw0*UT4VMMyl=S-f(qDopN8;e`9~W1B4FOq0Qc_j^DF( z2SB^MR`h}f=NFD2dYaFMIkJR3QIrH|rpTmanJ52Ap3w|EL(dhz0L*B(1;m z^&v#Iy+Li(vGuI4zYo!~`FFjB><^m1k7sSqD1`cU<-%huw2L^uKlFiee$o1Uq~kjN z{jh&(`$Qk&hL(}zYCL`jM)AWT^G0yG<7W~k%iqe+7w<5yk@9@I&!mYFk1y^b|Fc)u z2;h zKge&mg#}#Ezf^Fz4(%u zkIf)GJN%p9BG1n}S*;7?+bd!_isJ+8kIWMtVRKSl`uJPQ-}jf-x4z{BLY$I6f1^f{c&Jt~a9x7S?C5>gz6`FWG&;jC)pWa0iXSL@kvgX9Hy~tpX_{FZ2u<) zJ!f}^9U=3(^Y_F0HlRWSUOl}h#DAOl1~5pue%Y3M{cwKvw{K(U)#HjBBlAi%bgxOU*@Z)5*5cv}nT^!T@sA4|;aVcQ60e|RU3Pt1?o zDXx(AqYXV#!TF&^<^1TfD-ta2d}aA7>>tb*?SLa&7s&J#=7*>I8dh2{TF8$NX)(yA{-qTbui2(ir-;E7z+ z-|9%#b@61fS??b|<@)RBwnVl(O3c6S3r@4>J)4C2^_6hF z?O}SL39bK|=U*^C{M{Vjf}1J5U3FdhecT_ra*!*$`r3+CddEo5kNLA+kL-Lz9N(KL`v&~`D}?8R4mUc(&V`EcKVrZG7MPzz#*F9o0sEh$nRzUHTPlg) z#or&}|5`vT2wg9>Pj6C;peXPYSzNAqeP2^ExZkFlTxnD&;TQM!ftMNRdRCK8_EpmL z1jL_ZTg@TB^|vfO!TkB~!4YylwxCAYoFABEvMsus%y27tMA#O(rI?^Ks?=Vfm^gwr_xfyjt_mf5`X0-jB#+Mjo4l{jD2(9=Qxrvj+!W zfdh56(Mk8iB>v(2iFe#Owj_9zF#j9YX9sKkG?-K*@%6*;g^4n+9u*`ucj=j)1LEgr2d@E3Y(V5x}pw;DEqJHzI^!zx#`%tG5L_8^x#UI!|Y*}dxgY!R; zzJo7H_v89)%j4G2r?w$=y2SZ``+HjTw}Z63O{v%4`7yCbAA~J)fQEIOQ_G>M`7_XF zIRtzjLR-F9%^#CSTcEm+FZC@^ogdl!E0p=acM#T}7AWg7O>g*+yPx^@QK0$Voyztx zvu+CE`MYIX&$7@1{`nRcrAGq*q+?EBvn?w{C_+zJY> z{v!Y83uF7=<5p|9y8RE??OQB;Kg^$w9eP6W>^ijKi)wzniSdL(L2c;mT3y(G@hhG$ zU!i^x#{AquUk>H|0qfg~&(^ae6GjR5Kj=4#XK`x5WZu_*_D$Zu5Ham28!>SWnJYUV zK^|X3l-yu7w`>>gzjoPV2yM=m$nr-R-_JiN^=UylneWS=AM2lwr_7;=(GLsp{Hv^~2K=ezAV3+TR;` z8Puh5_S}Bp{+)&w$AHTT3%aA}zx^fh_<2p!aJDC46lu8Yu!L{CKj%~OPUcWFLm2;l zf052YdWiK&=9*jVq0M$-eR|rGXDs`G(kFimWq!_lN4C1T9Nz^9-?0vLp=U;pF#n`e+W^{x=97nt zU()*F{wV|Bwy?`xY`<%Mv;_AK^=L`ofBs3H-%e_F1;)E?p@%fM{YpUj(N&%Af=`2Z z`oz#(`aTLP`TWGo{qBN#(|DnN&rzOhWo$oMcz$3vvjq0CWQI_`XHPlK=G9yy+y9L9 z`{iXX*pwwn!v2K#W0mZP#TiodW}o!@rs#aIXJ;Ehw+;p5M0;Mp#{JV@e>8zXmU8|i zp!j#_YZGXo z*Mz!V;{3t(%U?Nvs_P~b>aLk0;e(*~B4f!Ic=yPRs%1s}{e8Lp@>~$c%6-NDVM9tR zyL`@vByISo|K;&P?Ij19ZrU=TzA>}8!+Lz)COjXk!uc)BRqFr2n%w?k{r_j34lKHs zBkVsrlr{(s?A4`5n(+EFLHlbDl;%M3ZE<|rygCQ=K{}{ivZO!3j^G~E=;B)DI+&{DK zV>_sB_e+>Rs9nPe96mRpzDHH#+v4gd@PB1Omkw8r-;U=z!R5F)9oUNN8&j0OjxL-4 z`US11Wq_yje7OIkUX3V7O>w8a%PpnvtEML3A04)SEsJX5Ags?hY=~o(S0~BxN7#Q@ z6rEt_Pp_8k@4)uSYHSYEZn9n2e>1t&d$x7282@cf)`L;=a)kQ*;Uhzcj?E{p3%P$t zL;36RN0p)XIbC{mm1=&N-?{@cFUAS&w`Z-xEM?>}Vf=5Kb&n@uo*BgLh}Jo|(6eQ|srx6}-R4u2r(jN4ylRNt?& zMVTMF^MTw5d@9}Vh5ElN#&>`rx2nm%`K}45{%E$(8LkC3rG3)4|G@UyEzcRI#x$jF zHe8?J{>EP}uHbpph|U{-Mf(2=G~deGe=JyRHKR0#+vf%d--FY<;9yKET7QCSe6Kc+ zg0r_q(@2-T9N#EEw7lOYc3K%fiRQ=Vblbyb9GD@j-xHrx%y*j@-(TYIu_38q``$99 zj6J%TO4>|UZQl!&^_OhJ91=g5;{*2>cS=maPZYipY+xT`@qrrRSJ}soka(zCX#Yozc81p%8dGmu-k*W_6W`bc+PO8MowxtZ zzaahcd-G@*GuxQ{esNVLf0mK)5IxU~7Ch(t!S$K^#*;v;St}Ylfb$2?`E{!zqgao2 zVt$-ExR(t+ID>dy{D)6@e!=k65w`NG`1?H{pTSu9Y7(^c-~ICZ!>Mx*SmK3k!usZ< z=AW3;r&OZ#PBnl0J{!S-iG?IDk=HMAe(s%VbEtjfr7(XnZl(#S9eG7Ur@fcf7wd!L zx;Ee)rb|C1sOHaTWqsg&_eQj8&Kl`{JYVUYt#W_m^)YmF-@pDB*(aC98`y{i4#NI{ z_D(z4&UurB`H80;ud+Kdl2|WN?SC@g6|?>i_X_i85sx%s+XE)#$7q8FaIWaC&_4N$ zXbIolKM>2?-2a#&et2AH2^VUXkrp|eUsyl2oZK0HEUOmQ_t(2l1P3=Wy6|~R$v&x} z`J?TMCPFi2My(d{{SnxIXbzhUZ)&!pr)^c^zkNG^)IsZo_U&s$G|L}0N_f7J-t#18 zJ#L0DKOJD4$(-Max&OfRmnXX`*t6UtWX}SgUjbAu#hH>WP}ICyn18-|$P3b+n9_t0Zr`!~-`r~pyE}4}Fu$NMPiC#&1`)Gq|L`Zb z-_#?Ey=F*=LuWWX`5{SD8^^=t(B}}kE62w`2>W|pbjlyz<^?6@BUW8M=2Ud4Kf}#_x{>t>AL}dopU1YWp&?Wg9SQQckYLJ(GT4f%L6L;t=?hT#p7t z^8V5S6dynMYzHk9bm^g9XQlfI(x+kbU0~7PMzotZ@2_b<<@vn`Zx1*Jk?zHus{_MZ}KdxU^j(Y+1EaK_UCp^Ca2>?6wVKc*z=n0p1W7rU+fj35B(O1{lmw( zU7>nU6$#Mc^@#>letyu+t=@1#$5gq$$6Z=KTp#>+*BjdRF{O!DH}UmD@xh`6TiN9n zV*C#Z-_Hgg5#xWh<~g=+#%f{zl|kB5wy7$P3{3gAzViN&8?Ciq)e0t@Z?`Vh6s*0A ziB>GfKR!R!y15wyYl`*B&D=In@%;m-Y{2o2`x|~OvV&jMI<)yK0rd4B0= z!W(wKzu101xKqW}Yl!XFu}2LddDdNF{-NcrZZJouid;O({WHdQ^&4+k^~i*38bnI# zgYEa2gE7qDt{eF++kYePuXRm5z_x1!3F~`eag!SG!lWb+*pkbTbYI}{Qtb?BiS{{1n2 zm%bkck9+9S0gbtRR#?gRCpgR+2@Vqt=$ZZh_8%C_45Yoj8;rhZK(DP zrnJij$;91kz*KKx{JZ7A3D)P%5@Gy1 zXYFnFt&!M1e_s2JT`?Ei=bcS|v4n<4h5MT;3k{%~f!KcE-Paww?S7C;?Kr+ok^LSw z!54;wno=j=_8a&A4Lk1(-ENrDwzXSH>xb*#&05AW#d|k0-1MJ5k>me+zk@8XMUb#Q zVp9sN`tvH;`7#*)Ly~e?UP+wr{I>T)Ys0BlV*8y^Y_6QIRz$Q1tG3^M%Kn<3$BT&b zIPTv7)kiEZw};L7AIMQVZohH-Q~q)oEV?hpKOlY5xX&nP+RuPqy36}huzhw>Oor4> zEhrpaZ}p$P!2M-$Cnv)ew-)r`FK&OjBLC@7I0g2%H>LXiH>CS9zoy*X#E#t_D$EZ@ z97|NrKlB#nhdu6|WZ^}NmFM&R`@Zu2srkR}u!u(+h5I**96qoC@AnAxxAn!}?Bd}x zq5k~X!Vq$P-x2C>ukyK>o}PTp z_XlA7*I0NH8f*xsv%`B!_{aUPZYJB6olz)HTwI#gh zSVa8$a{l1_b?C~`U~#S?b#zdT@0c3n;i_j7`l>Cr&uXYY*5|G-taNT6J3kr6uVz>M zAoWiRO55=G3FpU>?gfBeJ9GMEu7~vfvHr~MG7SbzGpE_xr%K-sP<_5n>uA=ge5kPh z)}`)VHsQOM(EjH*D*MaNFBZn9k#RX}%`q`QOoGco znPVG+`ZX~>HoNtQk`Oiec1F6iKG;6oXy6DgBXwxI&fI_F_-gQ&e0Z={USGlIOZug3 zXP*>e`+rUuH}u;#U1_6QT$H1YM4XOQ> zozitR6kmRRHWs!S8`6LQVbb~+p!hIoqaWmtk?YIoEPJJb9n}9{A96kzMkQadu;R+v3`FuQ61XbrV*3X zs`0yjcN2)-bw{YrYxgvVqrG#<_YJ&0n1Jll8AB^LTc}QlT(~8zFFwEJow*~N)~!n? zwdLPe4aHX;OLs8eDrj)`5~0=fwHl&23;`dXY@OWBk@1sq7!q`bLgz<@y?*kJrt-4>XIeByGu& zzw0O0=YH+`!2X?;q}ook|9p7N6CCvosPQna&vAZHhmMEhr;TXOt{ne3zs~IZA!c23 zI;8!^zx+Jv zehcdxCbs`KN9|*leZ7SF$@MvB*w2THgy$=zhCX0w78_;x{R9->wo%l8^*z#vej4Wo z&JPE@ZVLP6-VyGf_xEiHx&89U_4T~I7>W2{JIV^eeyY)N)i?jHk37B_5j7YbKWb2y zN!&hmMfz#oTSvH}?2q+w`uF|i`H8;w%3zQ4Zra52mUKRm!b*OA*ms9=__b%ZaQ%Pf z#Iu5HBZcwvkz;A>cQ>*B@cwZ{*&i;BAJ&fi!aS12{&h=2J)qssk>RcR`eXlb^LAVC zTwf&X56Aqf_p=LJ-0+@k|H%8J643cN9l!N~%+&9s>#tO4{c-jzq{D#zMGuKyu`fI;#9}lj|{J*nJ(%vxj$cRh0kbC4 z0BVW-&x~3zZ2pU(WTq|G2YCO*lfq=SEXYe3KNPmjVn@a<5}r??-Qgu$^D>rXD9@?n z@sB(|cWAu^^wpH}1M8pmrAFZ0My!8)I=2F+#ksQiqL?2oY7By{=YEmzHE&4kgZCHb z#W}&;(RHZWIR1UGJ{qCaz4z7Jh%e#z!T#e;vvjujOQ2By_&Pjdo$78Rp_}>pWBU+O z>nkf5u}7G{{dGVW7Bv*>pRjK2!EIcTu)m<6OAqK*Sw>FZ=JO#G2*1xeTLPI=Np_9m z@fEJG&wXGCCZ0ct<0|eyu|DeCX#%W2(~vH#=_ai&q4N1=hI$hre6#@_(URkrp!gup zbsB6xV@&N75fVOdeQ@magYfhIWSMTr%A^n;#(G#j$=+Tb)JN|wjd41)qTLP;)f26p+weKvu(?o0^ z1}W#4*<6btYJcqmApiMh$u~CoSE5iq^?6ty`j?#*>Zioep5PHsMq=YQ{&9XZu<;;h zz4|Aa?8f(x;QW0Ev4W?@zlg(=Y-xS){)vUttsvC%7a940_a79X{;V+TY0#H8quGZx zaQvbC&fJtk(D$2<5Z`4j+Mk~vRzRC!?x-HcIiT)j+ z`=>%u^tV2X{cq+vdnh`lK`UIgOY4v0qjw=g;k2_R-R%BOy6%kh&8TNXVMB~2t^RXY zx{mGt;MUHdo2yNKSaN>g_@VmSI7o`nqt7(srT542-?mG!>`sEcF#qQ2lENM)O_ZHa zgX<@1tIo0J-xd(_G2Fi5`I!d|pR&M35u~4?YX7ktDp^{cJ;MHxwgn9!c*j|x{^>um zH!MjjBYl5xe&G3w-Ro0$NPdxh>c^z_$M|kL#s>O7Q=oJzXOg4^Ow7_J3_1Tg~IsEa-s_i4b`SG&-wlfjIXDoCcxMMdNksEuC#s% z)St7;(FbrJfchH~-c5(F{zf$L^m=LiaDMF7 z%I(bijJ+_wHQMAbv)MgS*nf9)*LgOtWC0m^RW*L~onEl)1`*^~G1p%ONPlRqt!5>= z6NUQxux>*L?f{QwK#QJ!xk9=h z*RSdhn+Yken$a`8#!KH%f$*=9w}&0fa23Y?vA(BR%B5+-{fD4_hv|I_mGysM{O9>< zL%V`hVgB4JTUp;e`ji~j=JUOA|7rKQE-*N#P}qNZaIhtG-CIr`*7z#De=O>cx;DxM z8n&oK^&R>8;QpZ2OI)CFzgpC&^ptcz&JR?nj|6>7E$XVn*B{59Hrk^gK2n>;J{lq2 zkNLB&+#8-Wmg^JDKkatGFn6gD?J!)m|1H|HgT3BsFYMpD-8+@7(w``s|AzHT<%kQ+ zVcmT4I+e%ISig+vn9IDzh7;r0oPP?$ubC+&jF?1|mQ7XLuS$*Ito^`5vf}Ujcf3Di zzJVDy8jAI0!gO2ESzb*pG*GQyCRsUyfnQA;wsnWJzIgw#K_3^mR;L!-kbh6Qj`_3f z@jN)y+Jsh{S+M`?Kkk1`pO(Z{zH=4k53W?4W;@PI6Xp*Z2Hs^A$3tcFK@yPt&mUv} z=c==W`YvQpCkR>lg6vzy<3qfEaA}=x;1W?NJD&*K_s>DSV9&VMWWn>t();85@`J~{ zV94v&Wa-&*={laT*Q)&(=*YBX@r@Ui$M3!N`@o+M4P^Qn<9DLxOy%<#(e{a|@msYm zo~<{r7uNS0UOvK>v=;k^-Zq!mgLm_V`rE)Zm%Z=3fy^@H_{RC0M)hB_88@TI?wn-l z`(yw6U`uT{eJxd1AHn{2qjLY+(4t$y_-NpxArNF#P1b!D_=h|v80D-%Cr#(^5$^9z zJLLiwJJqD~yK(!2&lmW!&lOf>*QDqBar=eqSB-AFLW`F*W%zeS`gF)!SJ?WkCS6yH zzdzQuhaQXqMZOk&xQp8_tWUjS_pyarU4{K62RzTP@AJj{xUfHmUG@u=)n_n2_UNfW zzL7Y8(A=&O9D1H5tS?5^?E=HgUl7xpei{_>=1gK>FxpQ4dHS zQcP?PzL)OD{$o!_Z%9gbMOH*{e&POxOBz$)rb_g{V1wTC)$f6DSRK;-ogcPD!o zf9)snUwl+rf4sjxe}z44(y1oZowJfh;eMQ7SRWix+Q+8rwCLt=&JQ&dzimxRW|pm8h55Cz>6vVNX@Ic*FlzCA zrZX;7wm%*7V{y-17W8l(feId<;{02`eui*9Ad8%R$G<BaJn@6H{ZwG^n|k>ik%a?P%zFr6#SToRjF^)DaMJivOj6#I{J4bHNZCjr9zki(n@ zEU99pZ2m1EeYMUnmkrHZOI|GC`W*A)V1YW2i@SyS>08qqLo=5w;r^3f(|W?ys(iBS zF6Wms;!ohK-pctH#bnP{?muvU)^MLbpntQN-01vB!Vl)p&VYH~{-7znF^2O8$JgHn z?Pf=g*a_onrkww>g^VZLmh+DFc1;YCHf)j7p_G6J`q={<&yxpXnpU_8a z|DRrN1@%pD3Ht;0)9&EhEmyX`P!suQuOSYQJ3`DKlXW9uL|F~GdM?*bIDRhJH5$BL zX;QyZ{`?sKo%W1|MWveb_b9HfaD3+*>Y(3`rOq-t>gjN`MEJ59hLB#XRV!>=cx`7#R157%dCq$T83l@L=C9)Daz@%f3F3n7215v?5G|o6T;0m@mZt&^K>c?VgduaUMC5 zxI?enHR=9fuD`mX{-*{r$3mZ*wP?Mn)6)83|6m$93G{~7rS-n?`4!myI$2GD=YMqQ zB)u9Oe`tQ7d!;YDG1R5QY!ap4$MN&&83$RbG#8=14?n_KhKCrRHs>F+HkVe)=2u|* z?4VJ|@~^BVC3)OFV|;e6)By9HyM_Am#F?hhNH0rRKYW_n5B}s8kuPN&e|UdHn8gs# zPy9?GttzGW*F^Jk9)ETO6Y`TZ9>n#f8tVTT^DzMQ74@lC;A*~psQw!676@4r8_>3y zd!*|)zI%9aF({Pt8~p1=Fz%n_{Z&2J?_pD@*uIx!o?va9$CHp|oSzuqwR_!UC)ds= z3r6zmSpOSbc*jB(Z6t3K_DKIf0rhVlyrBzCjm7%Nz`QLSJ#bTK-*Yp1LnE_%@+Oe` zpRUM0%+hv(5yz@z@i9T`J9U`{tl6MRTixRJn;?G7IX)ilbk(AXei_pG7NGp<{Zo@* zkFr0+F)>FD$e+=nj1KmfJkvWri z{uApDZ=IoVH@Jcr=3kZ8kD&N#`MN+b7$e5_$&9`1y_OiCo<%2F*3)r9`+KneQx>{$ zrL2C9?E^%=XOZ_Kh3L!K$o=IRJ&GB>Him?{JH6vDNymO4xN<2?Xxq& zU*^Fnu&;hy`mD_cmH10LKNXC(*P}1ma{G++O_E6fs6VVnvs=yo`~GtKp>7-qRA2f1 z@?53&!}@)NGVh!5%2}vCPL$nZo1*8Fm}I`b*nX7lE@DR(hLHhHIKHvI4hpIX>X1O5 zJ>vYw`r^&~W>6zJQ)s_GS@wes7xRcw1iv5Sd#b@eFxgm4CM0qFtRV9GpT`#)&>#PS zd@HJu-XG7WPVe9V@y1_Cq5C!II_^*IRp11z&-@^L2lD(~7_v_;rkCJ}MIbHsdwwxN z_Wx+hee9L7ov=Tz>+TC|l2(AQzhlI>XRKL|m9p~%F+XBfHh}Dq!@~SzhWjT$%hBhu^M%t;f9mw|u`u?g2EC}p?JvfE;p1`eV5}zXIEm|Lg7}j(Vj^5BtVxZx z$Mf|?_187gQ{WVkE)sr|A)5`Vg)`4t0|{ga2< z)T0qubD1jtdcbQs_(bZ`H(9Frk!F0FeONM1c77Z7ug?4Lu-L5m!u_)y+rMPFgTqMG zZytYR`+v&m1G}UXLE2v0Ej=Ihzn}eTK`$kLniz5ZVg7g;HHWHG>6iAGI4DVaa*U!t)2(ZM(>tdQ27Ozs|IL&h|vCAb)!N%iqiA+i0)RgMChiW&Iuh zXaC#u0rhUr$dlf@eiDoDttjgUYP)ht>n;5Ey^ucnT&$y{n^nK6CtK$ zP5QGX*XLM&gv9&67jG^4$f}F9KBm@svi^ilZKp!7D|Kj0>n+lCjBmq%0dROmT^ig^ zjo**(y>{R<*rlUGqYP$C*9q!R^REtqnPYTi^_v1BuivbAvX9-h86wOte_fuzJm-#+ zov(xOUzUBBnQDstLtVWR=5u2W3G`Eq|AuO1Y?@y<+4+I*Pr&$BL}`I$X@XGy=eIP0 zeJ+`@`ED5hx@$YYx~DgU`MYZe9bs$gXHpu-@tuJ1eN;K0EhGFpp-F%Hw-CPP9`^*b zGIjd&1?R69(g*FYo`X+S-c)VLY^(q5&;RXTT$;uPRydOtUYx(UKlzW|WwxjDRAGI6 zf#Y*#dtf=qId@R{{@6c!*`yCmwZ;CSM6)j}_Ipb9T<80DA`w4wqxysW`CQ`m_xxwf zkFcf#VfL>H0@xUv?BvguXg*|AF)Sj{B#;^$l87 zq1{z_zeL2Jf}{RWJh?Xg+Lr5k%pZ$qfl%*VU3#w_=Z6>K$Kmn8(6gQ{-JinkzZ%Nl zoYV|~oilZ5_miQ#66te&G5E`;Rr}IzrqwF+aA|a)Nn&Vt!=L zb%7z9zmf8P=X)c5w0ux+hXNvs)h@Ru2ET9J6q0Qq@%pWJ$qpZ5CSfAGR zy24)8ohr-^&pGy-ZOB!S&r5lIqyXiIW3D!Y);fn}{jb=6SkV@6x3Sp1-0o@#Yh9iZ z*DUT|aR2t$H3Pu2Z7yL+s{PC85mrzdRzO~Q@%%96kI`HT>8*-M?-H(Wv41}DV-h^b z)uehIxc>nZ|F+Mb4DnxU(tYbXO8jv~{D}??fDit)>BSJvADlm$G&cykU$0B`tvG*z z5r0f9XTiH)KLHakqOHFd$S?J{Pf#CSuAPTIAMKfa?*Vkls-?mf4AYT zPb{r}I5F?V?JvfEkyCB>WtkxCKUw^v6VzLLLzus4G1V2yuY8rwPfI}fKG0$;G_X*k zQ)6yR_6^6+^9Fgr-o6^tI-AFj7~c^MAHvv_`PBV-@!$L9`-2WxJ%)h;7ty^vU8MC@ zSQ*On!}k5@%yFo*Fh7?x?JB!5&tG`HeDe#rto08CvHUw98T$|QyjLtZb~PDtpX+~Y ze|By(fLaNMgz?Aio~BU$(ivfV_wMpQXz}(1DYoYQZGim4_b&q>)-0Epm#XGZ>2NC; zdm)ePbL9R9$9Jn52S5`IZQA@S=T8Ch@8u)_9yZgaVX>PeegvcVeAxg6Z1ZkJq4!$p z`>3J#&Tmi((>`r0>|a@9e3rQ+j1}fT?tOf~Zr7hj!q@-v|MK|_8_GYk$j2MV)rVXk zVSHbnR0pbT5`_JYAK!I`D>ZKj>+e)FN_}&!}D25m4bA4Q>~A>H!EeYdaot}gE+o%eCD;V5uBKCNVdNR`-gpF z%pm)~8KM5vh#drxx-ZD#*Y_m+VEywx&I*oN=aMzk-%8hUeLcf~!XT}Da(@EX7q~ue zthWM!oDJ!P6xI0rzTzOuJ!UJkzeA$Wv9Ghn3ibW6^N(1!Zu7|Tzx^>d|Kk}~!Tho| z$n-nLr}xCV(5QQYaDIL()2^`oa<&kkpIt{mZhNu)UGdEudg<4o=^ai=>xbj7ZUL^*9UMGD6tD(Kj@kHRzMR@1*pHtEy)Hf{0m8qExf-Y80q&TVJpG*mLaYBs2X1#vsQy;q!IPJlp_6q zg_YcYxh^~b7p{z;RmFXz|BvVMjkdiATF)lZ$VRiJ`?3Dke|L!0*>5Y{-xpNCSof}C z{2Hb_VGYCQ$<7Z@5V?J=Fsx+H&V-XbMLfS;fa)JLEp#CE$}Zvgdz!I^aM$LLF#k}? zts6WG732Gm`&e+atRh?QIY{f{jP%tgCm-<0R;TU_Rpa}_Xdke>qfQ4Ia(rX^t8vH| zc3sk-iT-W>{=Pi_a3^6pynd!d%d=Gbzt3GyGPhA;{M)p<$=oOS3+o>=yNJ2JQpn;{ zjQ<1k->}{9LrHWpe}0UAwW~Fte(Ywl=+?jZMZW(yV4npTIG-UiwsZf9`B}0?1-FtV z{9^ofHVp+6YeVXOlk*3kFEjArRd_kohr0K7mwsPiB|ksFKOqO!oDGuYZ`5%9=KW#z zptsn*&sqj7t*0j$-s<1_)sX4OreB}39c|~y=I*`AZ<(HLD6zW4 z?GxrliM1xoY_Ww*)JWschwN8U?Rqd{)h=OwQ;icX;bP4*!v2mlHCy;?kw;D+;pc90ZK>OD-yhp)(%THv}PwpRae6{<- zaVYxfK+{Q}bU*eF#UE2yWswaz!~Wq<25+_W+2@(TUJs&n{qW!Qk>kJ4w&zS&Z=URY zaEyP$%qC#)<)9G%@s&Mb(Xeb`|99sB-Y~ZDFS059*x&b;@2`AQ*9TI&{2?Esc1h2N z`LU>j4|I3?Lt4G#@#S6Azx|`GAJi&Ur%Qu8|K2aJ|52?#Sae;JUO9bLWqcl>9t^}# zi@vX=+Wxm&ewz6|cM|HKU&C)R%g%m6{oU^RTeffcN-{Z>^B?0kPfHhud5QgN*7H_y z`*DWMzT^CE6Ayc+a4I0L8>_b8e(&wUjrz3^IxC6;q}YA$i8Q+ zUk(>*=+PqkB$*)-d z*9vlef@=F<*{vq5{js!7p`W)eQHq561u-zo4l>ko08$m3gQ6hFRO z><3{T)T!b!_m4P!9JV(Q4w-7w-lo@7;``O>8PG$m7TvvK<6nNr=O4UoKMTB-`x|b} zdMrIZKA*15o_SC!xDHJ*UnO0~@&BNl4CZ{?Nf@6xeY(S@^zsw#5AxG{&vtfNN#ZA| z=0{keE;u#VCCp!KtkVXLT+bkX9&-DK`LScxP{_&6C&sT-+vf=dLt&3+0ZH7Ynjen` zjDo9^Kak-&IX`fI;6l%%Y)63D{_aw{%$itv3j32{g7aAXn7KlIK5=L%d!h7?Ue{IQ zfBoQE;8b%9*|?D77ssC^JB*-m>OrAC|I@1vj4#V3hK9U;iSa+-n=Qn@cutz^*6z?x9K=vtXcqSWp-bq+rnrWWHTAlC}>XUZ54WM<; zUBdWXr>G5Nj?NJ3hlrcX{@f>TNR;s*>G^Sfn%x);jD8@AH#ol1ko_H2+Z#OIR+1r2 z9HsjSs?UUJP68k8D$;q~O@1Bu$2kor!K9{D#5A-i`%i!9p!|2w03V3k^^<77*dbk4 zAp7%FI|0m0yV1Q7-qP>m`DTlY(%HGIHp2PwVQ;S}4_EUPp5OcWS3WB@pDWZKrFY-3 zIyc1lU(ogg+kSQh8TpdiPwZbO>u5pn_07WhO*xyI!Tp|MeuVVt3yvY#FmKw2N1e^4tN28y(NS^fd*Lyf5p;NegpJAVu3Z~bEf!St6pUD%lG zdmU@JzByPh1L7ZR&^iX({u5MxDET!LZpPK5{!1Q8&xg-X(XO))qBkq+A7z|hc)n?A zawhvaZ#Y@pg2zv|K3nH$1BiUJQ<#6vEo%$8buxtcL4*D7uy)P|vTG#of5rASx`{VL z{Q5>hn;1&?R73cEJ#!MIg;tWXoLK4oaDLWXIls8gqbi~`gX0_P%QxxMAZ(F3?Yt*U z`u&e6zS*0*7jBvMqF3yE{{FsvKGetK$Ji-T8)5(TPvv~2CRv`c^WSm*K+M#8Y}yE4 zp?*y2T*w|I%n`j>l(Nv(ZjuyMpTjjNkgjdhqMkPN99DS=J8R z(oW0jH&|aR(C-T;_g^DTUvYi_vJY!qJfUyU2hwpD$2ZQO%&YGQPmlj39m4s19*oZ! z@2A1jXf+C}xPQg*{fntVP^Qcu3_i0~!tZH>-|TkRS@2U2;e6n)*YC4w7GnSBQTd*w z?Nt!>raXSc@p<^Rau(BO1*zq$8eiG*+EAB>_4%$@&7nhVifsP?t}i&R8wO|LIY}|# z_O%k}j~CO2gUhcxnZ9d)@>gVt6I>|IC%Y@SzPpCo1vjj_FPuE<8VL$i{5;Iom@xU*)>~L#Fp)ictS$&M0RZ z8p~z@F`&a6*;Bi2awJ0tzxKlnUEk8-A_HUp&Z zkMqAX?-jGko3mx-3*r30%S#Qx%|~p%Ew}WAzAbeWY4^ZxJ{7C}#bNd~J@ZY{X2=s=i$@15@|8V)984!Lz zjUI2#^@jr4@6Mq!;e%BT+VLybcM7EMqDIXHLuLQ5=GOO8{ua>wrk1*=SSSC%LVcpO zgR$s-!-e_VAGaQ{s;Vi%`O@a(6Dv_$F57>K`Eh;h7q+|G3i8O1$M*$@A8`}wz=9Xi zviuF^ho@~vXgJ}tEWX0{?=fryY){N3S-Z|j_`>)N{WJo4jLj3~XKRdfhKpD7$jsiG zr27f#&zf;l+5hO6PinkX?LSO@JHxt_`6Lq_N%uP=|5PtvBrNSxL>|oN`UUrgXXuXu z{j={#BL%n5IR0y;SPet6>r>CmoIhTOKTG=EfSqGJ=)y2wKg0efZ0$p^+<@kfqWa0I zm|QsLIGsl9uOs0bpC6&s=O&AN?;+H$T60TSucNbt`n2puHM<(Jnl$Rn^$-63Sy3(E z2T2k3&y27f0N1u%lbuhF<1ek#Q{eQ*3X*!zKze>{6dy$N^9Ng}@3QzA=g)KWrb4s+ zl_as(cIo~!#NXyg)1Z01pJao%i*#Lq_`fM}7HoQ@PVItuenSoAH?COBfu$KWsPhcY zUmTxBsh?-(+6@=x&t^=2%|jh5rg=3%)feV>VkVjG+F!Z zpZ=BC51pM2!2E2yaQ|zJZzpJMby`+`$Nale;sj?mDeH@Y@2vjwA2@yu9^e8VW^#Ro znEDR-uwfkvmO6_SRc& z1?sl_Osb8zz6(SCt+B!%z8(5X`kTi|_{REesohlAz3LlrZ^-Qn?ytAl5CW^0{~(e|H{`wiQl(g>1eKp#InVzB)kmM$7U;IQ|_N(g?=ijTg>;EbG`A^s`RM;==-@ z&vcqNLsgsSWXKrK4;j{)^FMdY~AQ|Y=X@?X1qOa%X^cjQ|o_fLT0 z2ajiuz&>meU1h-aAKw3EFfoJuD6tmmk9KWtGyC1{!v1ih@KUy(&KBke!@@Nnqv1O8 z?|fp+pP%!U{b~0O2>r|VQ3UpAXOqrD`T7&YpLrF&@ZR+^d3%WSXFuXkfT=%h-};5* zQ9B9$xIW`IJ^((deIq8PIlr(z-0D0H#%p~i3wviv{CI-+;qg2ed}{n6+v1u^-v{f* zR-b0Um=1FNi1`=2cs?}VRf8rD;{GQA@$0JlMV7nDQCQ#ny!{#TxiDGW-*xUQ(@`j7 z`Y!?TYmh@dNX>|roezciH9F7`8fC-__qX(2)djj;JSFo#m|t`9oFR0{GxAD@^D7O- z_XTCHz)rm&Z9Z`O7>xL3eQzYRIGjryfAIblJYRtIbAwyPdE~AW_fL3!o=$_&;M}Bu zz+PTIQy~64*x?TFM0vhjCg&gaPh<7G!13i<(rqK>7mm+U%fi6cygr@XiRT~i{MMr5 zXIR=}YhnFWFZd3N8zbgdQqCK8{qZcBe^Q|Sm&|^eFy_Wup?`Wj(j5G!i~ZB>eH7yK zvdOYNs`>TMWG0*(RxQIfAbonX(;PSz`G;J(#{Eke@-Nf8F0rmUV*k*x;S2Wh@MPis z(y;m8nb|VAf57-%F{d$f*%>c9|Ei&PSNJ*olq^2M_}trMBy=)-PD)O4d}4jnLEQ~> z>c1dSYgOa3Fntt|{9Iz#mD~3M6kiWZ9}PP{<`Lc39G}=fbT1qY_ssK2AmR9oMfmI% zGXY|JUXwbM_y3k6`~G{tWYC`Rf!wQGPqJ?~J}%kr3vrd@WbbNg={nBeL`(~SXF3%m zVYh>1zp(zkpB4bWMpuxGrLofeSby8OtpoKf^{G}A$3LDQ(OZ$pwsp1^_P@j#=dkE4 z?qstb&mZCZdr9?Mw%2u*F#lFsrzZGq7vsP4y?QXPRkSdF{$#KPG_gA%%x`)=B4D@v zsw}?2`fXpQV0h$`?XPcigekCA& zt=oQ?`Mh)x#{bR*FWB@vAL0Iqb=xXgZDWP(d^F6T>%qFv^>&mj{=oMCX#XZKe`35a z|2}(qH_)kfN_PG+=9g)2H&}P%8A;mB`GxI&+*>yoKI1w0)r#{=f$aY;B|kc?&LwK? zIlplJ*XY(5P*W)LW3@SdA`ySO%$W#B6JL>b*LeRj&hNunA9&W~9a%i-iiH3DD86~F zoPUrz-~(~$%K3%$#fXDbVa(!BB%!md^!>5EXc|2Yl2&{nO*A=waQ${#av)gkuOP$k zasJ`@akooZY=nhapXpoPV=sET3*(!?LGRh`Uo&O=!Tw{w#hUOWSk51U;+y_KE#aMo zSf4HXJs5h;zD{OrQtdz5HeLjppT+sL?tj)p-%bsvw*Ee8{jvYO*7+=)Nw=o=9O9+x zYHITSf;k(nu+~8i!ucmHcjU3~A3nnVmY~s9>}-3nf7zth6s}b55XKk772TmY_oOWU zi}ByL{#ZC`RzMbd@%)kk`G>HtUa;EZ6|sHH@rm_?U$#GlZ!04aBkN1}!uT8I75G2C zzC0|a?|ZwbWQe3v6q%6f%TnN>Zt$Qj`$M6hcBm$XJNdKr)b_qx};hP^i`czy)ECi3;|3-@_ACGZpMUAa_vzLxms zLf=5#u;w!?s%H43{J(g55KdY1MRvj=s~@D2{L6XIP#k>i2dJyx7x*og=;M@Tm8dv+ z7PqJ^i$7?8((J7lc-tMEWc?*2^8r7&le6Ug;H~`L@MfMNqVo-C{JuM^4Svjw7v(Q0 zzokv>fy1j(CF`g8{-e=%>J3QFmyhqyYo=l7z%tSOkVy2c?-d6uh^+wSDCXa&zFigN ziVhoUU}wF2{_2{)1P2F8+fVMlSlq{{bN$Vk{ZRk=s$~IhvCvjBei)Zj!@rE2Eg7Hp zO;*8BOEEvt`0Zl7E{@7glH7mrJJJ-@15b<2zeN&%`~7smAjj-&FtnQFXHw#L_c*n?T3fIzJU(U zS~uESUq8XV0JKE?Ef0z=^0D(cNqtq>rfgFyy2;8eMM`|8!; zh#hUD?WfBICp`N>HqO0n#E17zJy5b#U$hxQ497(M(0RF4=VjMM!2>KQ@k*X$#7 zij%fi1!x{*;t9c_PTSYhc)_FYq36fwfZIcyba*qe+^>aN6t^1+7$U(FHSQ5 zm26YOS08ectgm$4_MU&GBGy;b|75rO!ylZqTr&TX(6cRiTS(iFVV_>;WSc6=FV{kI z5&qgF*rn-%c2Fu^jeWGXF&NcaW+x*4`|K ztbfdY5()oixzE7q6RN?;6ovQO5&r#i&kc3&)PV22GGUzNUn<&fMt_<9YaYVhkEB0z z{F0lzsgkXz{zC0e;3?oUJfqL+4@s__1xfw5$CEPPm|&6|MW*H&cwSG zHSlIE!&fkg|FjQ#p|;vnNLtGD^?Ty~=dW6YC80{9`o98+zdL_L%)Aer*N-Ftztlg> zZh4E>>oFb@tXX}J;3NapVhkBtPhQkcX#o}M0f#F`{y-|i~GZi69TZ^ zwO6wGUA!>4;-%s;DPAi=-->3xE z1-`KUk6&s1=QPWxQC_)&&LsdZGU+NYHoT2Cwee_Tt@J% z;yM%chg3sGxP1GtUAz&^qFZr0u1yo(A4U4pIln7-^byAuuV(Qz-TxWfri|x@J4)(D zYxPh3ZMFH5@mJ2<=J@VNjOcz^8b4U(=%dbu-ID#u(?<2d+Z8F2{NwFC6r;xFh|V8X zC+jz<#atX|-vC7?1BCUX`s0dK0G`_T0;;0pgmIeRoctyLTU)<`T{by_{*EE>?N#4G zzTd}jkTFxf{SS^P=dX`+l)T@#rT$YMLOmt(6aOj|FlXU1N&Wq8M>|}zY71mOVEjts z+u_=MF)u}W{;sDx;jN>^Fn4o(_o@P366;`1+El{_%tK$_p%+04f8!L?v`mGKwN4=u~~!40qLV9#g9 zUsV6L4}Xm&tNpml`K*72_78YvU*Wf114;f#JoT9mc@-?#-?n~x3k)}x))#|Dbi#@2 zcT4K~PHMLJ>3+T>e-{-7W1R16h}p1Jz-KPu*DTxlxUS(fJo~`-mBy#DPlV$z=TFeF z)dXSw>G^J5vajI%)4*BwW%f_&!+{Q0d9SV@8DFkWz0Es69VZzdjcD_Xw>>jUGC!Sk zMG>!zT?Wgl8NR4K=@6!gUMsdp=5N058HzFOvcW6sgfKtG#Qt{}xnf@8L+BI1_?h01 z^EJU0|0tHgm8tA`%Fkaj-0+r6zr1PjP?*2(gnyT0y5s7e70~+_<8O-phYg;n=Ti;U zFBm`5^Opt;@xm#mYryaj!*?8sPqoeFUplBt>Cw%I7ssQrw(8F5uw3Q(76AA>X)b1EwQPFH2&j4I^)Du z()|8Ss~=u-N)g33w0~xPwCw!DJNa<`4~uW8|1D8lk6sGRIQ7&i!uq6=`)%%hy2J0v z87HcrP<@uT^*OJwc$Vb;4u`Q#F!5TXB>%SRtA&%>Zh^{k^7(hI_Aq=hI15rM(}ej4 zg3pXQu6XHSG5EJ<W z6rL|4`2Od=0L^XQLSau{@ZZ72e|L$v#)ns0OY+++?MnXi0S8I{ee}my-l`%`b?H z`vrVb`*^k_5GS5}22-!83gf+refU}h;jzWf;n(ub!Z_8ZFJ=B;XY~ts`-RyL&EKU> zT!^JnZ(yokxbQsf&+r=*hGsr*!8G}XwUA#U_Wxwtb$<6EYsvh>1p6xf^mYfy`r}ZO zAN-xc!J_^ZY9HB6)o|O@wV>dcA$%XTkNy>g=yBi(jQGU#0kw}A3Io12FOVC;WdT=gYn_iN-!xev0bz)V^L#xW}Iu zIZjkxq5j2r;7k77R}V@1c>1_0F4B(_^*>Vm$2&vy+2>*}f{{r^Q_80qAz@b1EUn0>r${W4VWa=aE-N5iqXq;Cc^q9lm0%x z-t#fy>T{^niWA0Zef`qu5WG0?1q2wd{a?N$|B!NYAvPQO8ZIwq{=<&=kF(Jc7~Awc z{Jw3`Sbq_pe>8G_3O=hhkjx(~zmv~9thbiTFY8^C)u*RBNcO*co&1yU8XF`Tf84yM zhLg5P+s}-i?QyA$U#0eswoovV^-mp<)L%z_OvYD=`S7HTeE&1%+zkA<^8p-;XZ96C z?CY>@3|1J+?vH*tS->ByFJCuXkJV$8xOIcr{$}cbT36oZCvxLN_uEqYdNlQwtp4vI z8DA(IP{PL-mP*>!g(qFG&DLF#`}Yo;n&Z*snb7||(`PikXi)aYEx)RvO9b0rN%_5N zgg?#?sDZGr4ByE_KN(tt;w8lfxIU8UcUnJrcPA9rY-s?6L0bfT)B26h(Qw@6^csv@ z!-R2~KVE%&F-{o&4z3?4?Zx(}zD(Nx_thDIsT+<+)(@=|reNfv>!SL6GU*SFTs;GmF5QEG zxaR`?sQvjM$bf?)7jLwgQvquy$>-OC9WnU+x+1sewtV}!VzC~hJ(_Yu8&(SckJ?Yr>ob_Q z&xq^ZD?u2i`Y&hG1HNYASjqT(VCZXJ@###-{VfBHl(A2{rIPvAW2d^}&WXDu_pcPz z%Fb`kKLt(f<=abI)bQu*ra`GE(@(U&QnT_mua^=inZJ$oY=a?|YeA}i-*CAOPPd4YjDLM!$?i8+ zKLREuj9;jJYa_cqy6E;bQGY)Y`~Azip~cF3&}z4Q`+Z~Jj_V)a1GPhch50ci_cNM@ z&%`Z851`pYX5Tcwv+uhX;<_^UdQ$%WjodFyt+NsJ(||ePiSkWgMHkMAE)ayz7Q~({@Srr+MjG;mF)fSfa?* zpZc#sFc-sQ`Pb8i^7UEerMY-}ieYWYk|y><^KC^rb>)IXWF^FU?$`=a=T=7&0;l%1cFUjnr)Q-tR!{#<1Fn~0;O zQ0B?-T}%9r=RRL_NvM#W|I6@A^>=OGHE1&P7re2WB)p&U&)%aC`Gx5=lJ$>UVek0z z>oX%c1*5_MhbVu&rPRaV`!)OlA-^zxDv8VX|@I~uCs+IoO)>?KxMe)MM z?-%!njE$X(LmD2zZk08{^E7_A-YozVBPv1dKJza$ewnMj5IeSbDvICf{c3y7B5-o^ z7ho73BD_C?;Qw7+1l~IS0+I{Q3i$UT{o!X4qOi@e_oDrMF~onwEm(n-(>{XzjB&#A zbboOttD|T!s*_}Vq7r(GH;%D{+=q-GsQx<`SIysUKN*I$ImYG(nuz?X-OPXd#^iaT z`$1@Y-!D%EwE~t%_8%;Z>45z@#X;Tp|Hc2}{jVLK48-P{V*8{1qvX{zOgESIA3wUx z#CCu0itLZxAJ(&#?0mrLB3N~w?LVdQ%gtpTcz=RSKR#vtr@StX2X}AzV$V_KaKxMKA4w+mduG{sT=YeO)6Qi2 zkk)qxYn1RBIb-0*vj6d;xPQ&^=zAW9&Xml5w|u9L_W5f>`I%(WKht+t4;);)Q?mc_ zTq%b`pJc(2#`EE+eWGn3_HJG!nIBlVIS@0)RYCnJ7C+JXxnCNH$2V2MniVqze8v&` z8hWRYAHUgBQXjR9R=|CU^Cb08c|tS%GINP!eQLB}N1TV7CHo&YzA{0bxWkh1i`FfB zw9LB-uN0X7P~gPpm%V=Nfyv{GAZ9tkC)F=UVHVEcRV1m83j28Cu|@Y}K_$y?)e`@+ z;FC8tXg-9&iSp~WZWrd@%o`;zz9)-sXnyqJ17Ey-zZCp#Gyj4FpUv{-qNU8gsAkCL z-+n$-e2()3xNVpsmtW@I{=l!kW{RqP4vX?X zRNwpx^1$8JcVM&LGwc86ht{78R(s-xVPgKI{ap@`bMa?Z8PqOd{6+U?y6euv^TVa_ zQJffv;fEf<+A!ANMf(S>?Sl{_;lDP|v3zc29*z*v|Gg#A<>WFlwYi{zQF|F7q$P`gI<_uaTneNvhSn%c1hw~oOJdfTY)72CSm<4{{7X{ag9M|?od9 zl>cWL_rc+HiIV!dz3LGB_VJMD{Qp{#pO~EIh?hrR7N4I^`2X{vm3XTB4Y-#w{tqVl zSu^|||LL5CWc_#j8QJ|y*E!HRm)iLM#r)k6(E`s`M@Z^t`!$`=tY(u)KPQv(_X0oK z;N&IJ_+Akoh{L~?Ksdik`28}{-|hHPw!d*~sVslT@Jsc_-Wx$UrhOT-uVnnIPV&nu z+J<1gX$8F34-?iun4Ir*Z)XJB_J0gxCZ-AFK=8NqMkMZ&^`D=NwGh59mGINS2a)(* z`zb7sWBF-{&*vGk3xvLngT!;p|4@9rFldTBzt0u*pHO{hld6gLcC8lmpHO^7mJC7F zwTDFUiEJ;1D8A47;D}k;mqh2M0>RI)KC>~%rw|r}GW-`1|Cpoeg}S3}i}WKs-*a1v z53W3LSCqd^Ch>{O^_BQ8`!zVuT`J5U#pkO>TX4>lrjq%MXM6ASftxHO`+ID6l=2p~ z9MmtCkKZM)zVf7E8Nj zL(w_L?=(K?ndyx)Hr$54UD@|jexJg7;Yw$ge|%5oSJvExZ9+;#{2ol=w`f`Z zHtlaIbnKfX%s!oveg4XE!n?;2o~N^Mbz-0C7vm9nO52A`RvF)4=00z@ zGW^i^GyCXwe%dNG$^P`q&syS+pNk~%pVz?v4ed5b_IEvh(id;oO5;DO>3Gyu&xToF z<>SB8_j$N8{(gF-^nQ4`N1|l@ z|JvapxWwWB+&|CqCqV3Dfu|FiyuSz*75^I-=hwVi`(i@BJ8*F#)5kQwb|GRbJ}hY> z>0h?>uHcQTWjP@U{d4&85B|y58It<%^ubp6Vw<%694a)xf1Rc6r@Ff>4!V>jX&=#= z3-M%V8R#LyZw$fj5`%@fZdsYAK4MJtjlr2Pw0l=BI-kyiCKPkQ@6b!|~>Ib0U8N-Ji!OuaRIXLLrEvRl6(r7=eMf#}oqdB;BVWDh) z5sQy${wr~WA8t8!8*Ur3`T@-kr2X?p)5&+?=-_{X{ZapH(Oc#pb4sAe*4@JIQ~!J0 zF%*~7l)$vDOy5%foo%=cf9#gV@2uk$e8YEZSo)KFKjr`2FHiWNSvIh@AKO1k_2=NP zKlvxoGbHm{N4~W}vkT#(^G}hSKc`UD1)nzGB$=O#I%J3)>vl-m|010Uvi&1jlKN<9 zCl_q4!$Z+hR{x;-^@{9#=D)qg_^0}%*S>JPIHeq(Okwp0dcKBQz*4L^R0Z$7S^P=Q z|GMztA^&NCxn%w~T}cJIee{>i58OT59`9UVC8^(UUKoZe&+Ugh_ZWVuKG0n;2iFze zgo?so0YAnh|D(KV4jPr+grx>dztj5i>JEN5+p-Wom;9EC&+dKwFx<8fe#Vax-fuwS z$B`-ic>lm{m^hu`pZ1@Q=n{y@SBoHh*>>T1r4i!(9ixH}-0-CshUY#Me!qzDS6bLY zZ0b=8(aLOpO$^bm?t8Z3gC0$|l%ICO^E7`y)2ogjo-qcj?GFmSPw}n3>lZ)i-gGEj z&h!;M-}k*{YvkUBOUAduul2_j1v@17H+CH}5kK{n=I>!|ozdm^1z4o`zx5USuggcm zap3DxQ2E8`hm@ZeSA}C={W5sJ;D^A!1*E^J#mL1tc|-*$@|T49q4DwM&x>*9;|h3u zv0NBWCiCAWZz*bpSHj*F4F8n>1L`00bBxVks}Y+&1rX7v!Ws2PeC$svxT-6kf9@uz z;3!LJez(2U6-{n!l;n@Y;lr_h>VBwhydRa?hsNqTsJZk8B)#7#tUt{k#O<7eb2r_9 z^IsVMQTrJ2V-B{hzX1i`M+nc;_%wL1FTT~4-QU%k*`Eiozu;zm`1s*XFphjG%rA|9 zexCEk9Wx4{*)SHr(f;&YS^lF};ay0!?kxO%Er{yejHH(*?r{4XHA-IM~7pI zoLQxO`_K=6#Lu#@0xp8_1N9F!Z|nFG&Bj3g@&m%}Q~SxE`-i_=I$hE~4B4!M17oH6 zZJehOraSJCjE`%FOhV<7Ov(D)fXUO*W79>^{TsCY;b9wri+_|tvyP14Y5eFuGXlAm zWpK7F)AvzCAL$K_MB@dIV9TXr!urwp^nTYBsPd%-a(`bH#%cV~6(921KZb!#EwgWG zA1Oi2kZ0>mCHbSs ze{->{XCX|mWB4y1`3w75viiuZ+oJO)Xnis?Wg(WFFNT4NCBppE{#^ee8U9x(a&}MT zf~_U}-9AH4I2f3w*Ya%J}%|5rbt{$cn4U7TgP3bN|t>(2#$jWD-9 z0V+xuKSqJ7h#-}FO~zYMnWFqY?Vr#Malr>E=b*?Rn}D0#6}kDZRqzK%8TfQH?q z{m1(NV_adhL-PF6#e?lIY>e1{Q2VkBnvNX@o`=h3Y<;Q!m@TV6CRSHN&-E<-Z%6Qd z->{k=QELftiJ2=udklA!G_LZlJS#%+aCBubEBw!LeGD&ziEbNUH5@= z2CJ`Ae%Gt=$A>Or{LuVySdi@g+PoW(megKYe|mm!#G(bb<$4jQKWFQoLG+~dbdxUy!%>W1sQ<0{@Q`2aHv~?NWZzHifBV#@{N%PH;o*F?|Az8& z^*#lBP~a-5KibxJz+}}`lKmGSUKpd%{sc+=@nzZ+)c$fxQh%6Qy5hcTXMt<1FDMZH zwd(4P;nS`_z{KH=^D91Ir@50iURiMkOxk-3ti2Cr^t}rAhOQIFDStQ?N2BGO zYWNY!@JaKFp^H|b-N?sK>)S$jo}MqNd2%&Yy4OKNK)&^V_H97os|8<6_>eB*^#P*q z-QHF4k$x87kO>-R0`%2)%atKdOqxmVeui=|5=v7sCe-fTzkm$Ng2^6Fkk^D z^%wIa?e7?IA`F+i+!O8Zk0STaTMu1^ZC}au|3@(Y97XKsvriNT8dd=IX8C0r|2;nX z8xL=B)%j(5==QTOah$^1n0P!l|n zmLSQ$4eh34=de?7eOsn5|CE1Eym3L(iMdezn(?PGv7gm~wKKFq+sD5Yu zm&QkJYno$*jjyOaOY@U9quZi`>q1F>e|MrMZrBtn(jT-w9(!E2zhh%Eq{1J2yv~Cr%al+pRZZAXqsuEFsgXV`l?ytaCtz_rt zZ(;b0Bl>XP+*No@cD`+3?-RoNX@1~!^&0$HPzTyI^7&;{(^5Y6*B~g?X8C!_|Aw=l z^Q&i!0QG6|`QM~W5lwWZ`9H}~4}UC`#_xiACYUumL9+ki^}ZQ+Yr=fd|WwT=8p;vb*AD{#Z2a!G!DG4=FH}g)Yl%*&ctUswYbl&?EGvX=aUvGm+?AT()h2j zZs3a_aj;fPKK@&rX@Q;F`bzdsF7Kj`ZuToB`;SK6H^r5T36lHE(qCC)?xJMank%1w z6pie$>~Dr-e%@jI47@QQ7Xmi3{GT1+_t$G@qnhbOxU66z%rCW{oTgs5de22Dnc^ml zQ+|KY-v_%aMi?@f*$=IsbZIpQ9f!;8r*|vid1^nlf9Bvd)yr^bDC=LN`H86xJFxTL z-;nT*;fv-^|9M?N_22s3?=x<4*FR=ZEq?&bV6~Hc`+2{;32NSTk*pu~F4e%nc?%@< z(VV`$aoy_;pmK=iAE%e(1PUfG zeS$=v7)*@DT^eHhF(Ce7XsdNNBC#G0r=$z>L;XXW@N(Xxa1d-rlF$F%;V*cnmD2dv zhNif5vx}sDxwfMvw$=5OydQDSQ+^VaiPbU6BpYy?yy?HS2v050X`rpgJADbMy46{9% zzRM-~wHpeXahBB^7@Bljn12t#@4@eCc>`55&@VkGyr1g#JF)Gs`G5tI`NtODd*jgJ z4U+vIcl$cvlei2?{kJS<32y9OBs$-U)*loXuE5<~33Qmn@JH)+ZZlTmk)<;H`7(W? zK=2n)8-qV&_dkWUVfdr|?``TS+4)xOMD>4q{!8$^3jY4FK`^IAK0Zq~yyR^LN#pZI zk5+izV~%8g>ge=NcsnavvVMK#{9x3~+b((kQR>8zm@|1ls8%rhHz4}(PpUhfTXqI! zL^A%R_$*!Fg|`=+2cM4e@i}aV54sP(2puXI|5E+3@yZ-D8ODRcW`<9iKkn3TE}rRl z8UA%<_@w;0YkWL@u=xNtm5Ky>z9;zHGU+iN+G{vOY0Jmw_IpiH@4K^P{J(LeCQfXz zKyv@gJlXk~uK628`E#njPn0^~+@=}O*OciKV{*Qmuj^7&a=QyF?U}x&`=_e>BQbA8 z5h%ZYCHy}H!mpQAmtjSI5e!OxE96Ik)bI9ATZvs;$?lh)94M8EN&qWF`ZKa~>K7e9~RAbGyS+)*|-ZubG0n9J}_`_C(7_n-I{pM(j| z+5AQk`)Jm%64Mr!LW2dvuL9BE4~$n~?B`OE{*EH}ElXODpR=F93TOHFtkJ%R-Mu?< zW4_4m?|(UbpTQKXM|?5!X1Mg!5_g@#izy9gEIq z!>waXe^dV#yJ;oXhdzY!tC_x_`H##&tI#;61nTdx{524K?yp{l9-nI9WAl7#dHK_( z`5SP3=Q_Bb#qbM+U&l8+ExSKW%&$?_?M3y$*PkEpYDOl|A%*#G%CFVkTBDtdk7R$* zKQzF?u3~)B{0 z=aE^m^S6idp!+CE7^nI)W^yPV{(Tj`scjU-Y5dkzcNtcFzAdUhQ2+Yp?IE1LO_}T8 zdad<;^H2TbShaWjESWwt9mnz`lpi%#DdXwWPOv{ue*I~5Pi<843W4X{*f`}+H6KI# z_<6l#eP*}qP}I=e1~cr~^9G!_{`)W30Z;WzgD-Dbd=^aj^XL4TsJkc|9-Wtu-vNic z@!`I+Fe2Acm_K@c%kd$y{J-8qP+h|COZl~pUktWrSqToMUxfLi`oy#@25%Qv!tXoj zf__LP_1l&M)}hwaDtL77n(#b=o(R9=A8kO_^N+!548uRw7jBk0xWPz+EAH>o`1|7h zS32LS_zrtaB=v>y_&Q#<&rtBl`QQ4A{bR=&-}n>CHn8Cl<9~oAqVJ0;ZH;T%`bgg2 zpda4_x74o?@jJDjZpk+I=xDM?UnmfLaU*3ezH`0+H-51FOH}`EnkDPsQq6}KIh%#` zqy6c&otNX=fZLFD>wz#ow7<9I>s`31#}8NuEI&c(H_>J(xblPwcP3fBeQ5Sq!Mh8b zB=^7MHfxV7x`jx_fBF-KVaHcnVPGV~x9qMz(fpE zCaWJ&ex9uAgUz#ZVOgw$Fh5jZy{%e}cJVTPZtTCO{M^0&M%3K;1Pluq{wV(@jIZXy za3FkrA)jBLnAGzJt_%U2?eg)ZTJf77J9|821~B`j__`@OU(3wNTT(w{*>uIVNh>7v zE%fP+M^o2J`oHPz#$wyA`=IGN`SD+HOFw+8od+$hvHWEe*XMBVm3M zNqyzJ);x6fy#Q&mSbV2W`Zo;*2I51zi=ZDPpWiKXqtIJdj9*$GD>FNa!~L6a`&!2c z_@?#a(eGy|M5G$A8lC5N!(G=l1m=O{4eDf;|dilP?N^DOLcopYnU&J z4{85$$P8J3;hn7zjPmh4bAba|DINp6L&t^rqxcS9?t$|)vf$~7gTgq)_utRn_luI768#aHAA{4LmP7k1pN07YvcEU>*LqwUSp|olWy?XkVz~Rfi6SPoG%)LGwqyZ2s}} zKgWZ6GMhhY9|?-;xb~r!WPNyfOCvN76Z=;hpJOLmR9?Lw#@?16p9J5Vhd(Z!ho;RK zep?azHuVogKl2N4c^~V)FCh7|?$1^rmv#r#G#S6r{^YMIsklN-gu-*d`OBAKI+!(PzKDM*K7*>d;%u`O@OlTcf9jvy?hnW2 zQ?^R#k1hp{*#65=c&(f!;E&?>N8t=CsyYch7P9yhNdEr1uQyuN<$&>kDZ=wKewn}5 z7w4?Vg+)6J8{aS1hYCKj^H(w}!EQ&jFh4Z^=M=mFm9A7mLJ!to7G*8g7bcT7qQi|E zFxvY=cwU|0-#oX5ci(Ibo?RHfQ~dTH_LTqBXE1Q~tiD3=n;4^j>pR$r?%$&L-Fi_S z+pqDG+g=GEQX}b~L*IqA*zme>Z?$~_-y4mc9k&WlqP<=l3{2Kh!O{VV} z?|(`r{IG6yGWuKo0eh}Yn4d(FU#l}s#i_TIxMcFtBP$LGN7BX<0M{)6JvXY+4+Ul1K{{>mS3XyEB*MC@33i*B!3o` zD&Q?nnm?O%Xp29u%!VB)%>I#_AJp$ecXVmLLbCpMJz)SA|5+!BUnsxEt4_qnZ<8hY z^-Z`F4xN2ei$Tpe4f>jjvt3j$^;YDqME|E5iIz{ES?E5@UX z2;&srafi?1<`2*4S8U_XQwbuWtVh~)+V)jS*bL31#-0*Ikr2hv^4cuQgTe3dVZLBed z99$==FHw9Z=}*GF7m~s9n|%LYujYh~?^0yv3p4!^N8*o#t&ZaEf~H(>-5OzjsQNE-%L(*LZ^judVf;w@8wZZ%aa5?5sJ^72AkOdfpV}N9HakehU!hzN zT%H{z86Oy%o8#g2TOjfX^WT&oIb%=kdM+Kj-Z1~BPWbWMa32i$k_l<+yEo!b?4Q?9 zo`Z1@vY>ZshF_{rQ%!;~`E4G|Ys=zWs-Il!7ve8f9zI-T_*EtPt8MHe+`jt~EE;o% z;g8fm_PB4soOh4me$^9UeS!%;KQof~x5Yo8?nH?&PW3^jF;DoIG1B~N`}H~B{iCTQ z|L$wn1h*d>2imYCLF+-t7FE%TC(??)ZdF(|7USD(u8 zP5TdbJV%T|Ev_Mi#SfH!=eE0qx^-Hdp=Y`ki{Hfe`&xW%j;Z~m@qbsTCn_zH#(&Fk z7Wh423!Hl)AO9YKvoUvnIvg3y;&&Q!!1?^je}|KNSBnTtaaC(sQEveJweE0OPizx$J&BZc#nMFTuC><87Gx?rY5ei&X&NSWRp!$7UuN?|^5=v0 zrQ_bwGJM9!$7iwSW1b(?AKr6^g!Q5RD}GH2+;h@iGXGopyeB@jj}qy3THi73V~J(M zwm=UB`T9WL*9%8NIwW*s_@nxuyW$+Qn0N}}FLV{YkJcBPhxp+dvn=rK!}vFf^oQhr z4n~{aXQ3{e;jfIuuYrF<(R9-}(A&%6Uz%T3ir$8w|J8x>O@=?puTCGf;r^5LaR2Zv zVgBj;b`!Q=V5R+3*$AGN~-Q%}kIu>R$a zIJYDapgF@gjgL<(HNl-1V!$XiU6^00A8sYsq2F%V{)tWU^+TndBc3rh1P4wreMj{} z$LS|=&kAME1=1h2$0i+h%v8AFx8(EdHv4oOJW7R|qQvkUO!`-}-XYHU*N*%8 z%vG5GT9TjHwdV={(7ZpG9g&akK%JIoGSFU9|CR;zLgkmsCHqfWyaL>4u@&yTXZ1B& zzpRLn#rJ-vAa{8;VSZIdi1kC0Qa{`rlnLDjO%lc_e`?*FFS|b|7j#xK{8Ijm?i-3J zcov#}TPZxRL-a%4#aH~NAX5n2CLdp~{x!vbvav9~BU^tOzh7FaiB@-JiSR|^r!`4> zIQLATC_bh5GLJOH%Liga`jp1+#c5NJTf9#)emdUM8J})C1n)05#)m|oZuOas6Fg7A zQDvsDgNc62m7Q;=+fA8M2{|m_gZk&SX6d+eq%sFT`ip5~WK|8C@t%x3mS`*#XkzTwx{no9crZnKo|#~^8b&77i-Ek=v+ zP5t|x`Ge4XLyTzu4aK)_^i)(BB8_k7*3&Vi_AqoXVE&!v2Y&ZP)b(h~Wh~if{hvOh z{Mo^^09Tx7FY+(6KhNu#;-%v=Mscqv9g_R})$%&t{X;((c3wU{$LeUI>bO~={0ZH^ zp^)DjmlrG(;gjZ9`|Yv9Zl^ZG>vWd?r}5YOb93=|$|)GD$M8k_KVP{8;H(~*@a!Yw zN7~=){bnILZcyRZ)_y>=bVA9u#fpP$^2mT zFMWJfHc!OA6rYQG55~84()b)1Jq^#)?Um%;=m#@!QO6^q`~cOTzi!I<(^njaPWG(7 z#*Xmsp4(gT-tuZF{P9?rKLCAEfn;$|CU(Ln2faNjfA1FUhzwL&v&m4v+b@KUlxT-%M zG)RXwR~px!;5+hmfb9I3Q{eezqA-6-BgE%p*@e%;uUAh&##hE~F~ooFlJU!q=E~f~ z8u|KU(ELpNYoW|(+?TIEoCC6P>qQkV=6J~k!9OTyiq@~Z(=}Wb+>Wd0$?y$CAD3BO z$ECKKoT8)r`~ysX%9nra3sFNDe^LA^U--)}x@!rYyRiAC_&>T$4b$qTO6Ko=TlU4j zrI8~4LGgXwdo;R!h=(927Jnp@{=kTMdsN%ISF-+N>*9|kK__8@30prJUk*C!kLG7j z!nR4{g!QBTC4cKYoY;^77hlQGe{6jbhFWU5uwX9BPt*8vROS*Kefk`XMWzMU=eEuJ`sQ@FpYjHoD$?tDfTvyLuhCa}S+b_&7#qX2v z|9FR!mN0b|!>pq)Vc>(MaC{ll2eqWXdRxL6bnYAvpNdWi-$(NkH}3_Zw|54_ z4r2a^;;;N}2u@DTgzU7b!t)tqetz^{gcnYqhL5Gu!Z@v8RHQG$dL3E+jt=8TTEAOw z8;PFV^1!%;;g{Y&ndq2>EjU^IT_XQ}OD7v2-B;pNHI7*S=l_7@haP8T<3t-}Zt5;p zAEEd*dEOfPHkbBK=XM)lUef?k{gdJsx(&nAUDt~88wLcwNvcjb<=7rce%#h&21d&E zU(9{mn4co~jhWkhFwy@gv^Qn_W7L0j&bo|ai&}G&KE?|FpW^d-nboECk@M}!)duqX1T>7dR7ys^hAPj$n_=vvF_QVavPoUgZqr;z{60?} zhTSsOfb#;jzCiHnG29J}CQ9?GlI;AzzN$x|Sr_^E)c$-CxAbqxS?S&szF&dVCt6J^ zz`lAK+@`inpVIR=_UvuoKj`;?H}eh%>qGrFcUciL3oT&ne);~}@r@1^-E|k`FR1^% z*|I+tR4)bqNmMmIEaPjK3xj{+fGg88&O3 z3*A*v;4kWbovKdbma$4)b8qH96-fNCd+Qn5`G!iI(Qd|H6rU^BUcsE*YFzW9%s4&x>#Q3K9t)Z|0gX}V3;Il1__!Rq>sQd+(o1Fn`j`tGA zY5nqkHy#U*H0K%y-mqr)6!ZIj<;ytWN=xqU+YQ1v&7UME7Gs5*t|hE|!enrzqHB!uc)GudzRa z)+gSaaK@3fyCHQN)2AL}e~8lfGkEP;Q*KIkhA-M*xymUIdv{aeye`%^&X3r?1~h4b zn-7i#o18}fM)tR)|5iuEPIi*{)#(o1P+P-alwYFwJNao2V%sCIBZTQ&%6~4Iviw_g z8W?ZdD6D@XsgLCNgyP-hCuR4eeG}}@gXHJ(T^Ha=({y;Yn&rP~eemh6a2$F56kIi9 z{7Lo8p@~b7o01LR^H&JJPyJ6t`vTl+*@koM%lMP#KPM@d;EI{L-2ALkHowGwTfQts zTkIglAL-v3QB#JoAssoLSO0|nN6&Xzod1&Vg}osEy8QS&HLNMB-8F~(m*nF!rcX!I zc;Y6RAH>B2F!T6gQT>+kYo*d~?B=@)1|4PnF;xF_E_FuV54)hjiT!>s!DkS9;&#ge zVDl@baeZ5e^jYWMxmav1a()e-w#7|t zr2Wql>+bkY$zRl;Lh(EKuq}F-Z4v1kYM(VpvoT!x0Nie!D*QhhUtjCxjafYp0+-Lu zFQ@gz4vXgF`hID!BT_#8$9XTn5q2{CC&|bE_3L4Hv~>n3L@XA5--GlA^{bcdPU@Zk z>XnRN>G`6jI~U$V?bNyT1q}aGf5uuC<0k#~T)WK1{$}F; zA`h41ldZa3TzIP0fBdaL^hHipIUY9Z$Zbk4x0c86A9_{bWUr3gq#y<1`)K|0o#jXV z?-)bT{yxgz;rdGWX@xoDJ!bf%@!7wq7Us71>`+d3Wq-?_%n@n!c_rPwE4httaVDd2bV7on?3I{aSD z_>tD1#!r2S#Vxcs^*-|X?P*_`|39qFd9^8#i?8pCTcXnUk&^Le>JvTG3zlC0@-+i7 z^UorYeykMV@wkp8rrK_yrr>rZ}~^3eJ}d{Tbt(pKi*F165%`3ue3M_9<~azRR` zh36HB{!#p=jQbkQz$#ikzkH9@N8jq{lKp4yT}<%wxJBUS&E{8uQxWn1^T%emeo-`Z z`YoS7+y^`0$E0o0>N(SI83aFlGd*xfbrP(~Yt*MCKAbni6Ni4;12_9HeL?lfvU^^* zwRj&)jENWKm&OOTr(MH3zPVW6k@)TN?i-kSqZL=6#{3_U`a{dbny7hplH~r#4u^W8 z`H4A_`JJwYlVttbn?>~jAo#hHAB+p#Qe^uJ*9qTG?+0r+WFgL8dkpN241{r7KXAQu zAMGPGxQ6kpK1cI2ubP!&>S8S}&6x3zf`T}Ha~WTXF-OJwL+JS**NZE#S05d2`EM4V z)ROq*Q*{M88tZU@-E#!|)e`)jZl{8Q*M>{Rzr&+jVdpL*CG*<{%{n2!a=OUBQT=pa zqX~M?4F`7xhEH{Z&%blbak545} zZ;e@4(<2F9ukS0Yj|a)0=^pXK9%J?ZI5K{VBKmrnsW;~8?1LNMwg}Iw6aRUu$t@iH zuN8NG6vHRgXXYweSTSglB)@6w>xJWU=19gT3Q3c&_Uk4H8_)QG;!|Z&C{7=i3SGD9 z3E!7Y>Zkin7U0$MsZi&#K^Uk0)A4*1e(jYB<13Veaq2%6|31QaWgSkhSDE#H{728X zpJ-HxLA`Xi(~b;ZH2;N_m3Vc(4wqs0TX>%G`4B;U2Gj{IO>V`KZ@}G zv9M-%Aab}!e@9u1&u{trNew678v!d5*!od@aU!5IrmuIE^q&^*t+3h0XlR(j=8x*@ z@TpE{JZ~%X_ha*uO8nz^bVkRZZSeDAM`3>+hKC?e2!Uwhdx%8Xxfsz zP;^)BeW^(Xci`KEH&^?l1kbAs%*?Zxz13fZ#_h+X+pt#lzGRmcOU?%t>}dqx;*S zqLkr_#($@BT~VQK8=#ZE@P1lfGCedMd&F#qf>k4gae97d%b=O~&NvZvJ!1Hz`GLuY zZejSH7F_$ZM*Jy=@wb|Lgd6s1aXr?RSpSDlAo|7oi8gj`CCz_kVSR9N7az&|#wEW| zILT@?th|#cd_V2qdOBbV2AOVx@!@R!DL)?G9EC&9oP_(Tio)|WzoDW07}uxhaJJJK zzeN#zsu{h-mZ!ULg+4Qc=c7pffy2Z$7&>l*Wd5Mwx&gY>xQP50)mJIE2cz}Bg`)V8 z`meBiGw`neb~yHjtsfG7^Q5;Mo=e#d_Tg)U?=v9$<81DRiP_s>#8_Wp+>Ye$Z)e^_ zRa=>U*JJBT>oY5sKf((Yn%vK~Oy2^@A8vbEiGA*g^)221eD{47wq2*qO+Uf(tpdTv zmq1liSwBoN|EH(Y9t%27ki5TfNxQyyC)QiCKcLcT4E{@B4O)Y;h5t|SbF$e~9Qkac zB!1kUIiiy77Rd047oMm2G7w6|zy;Q|q z6Y>A2{AKUj2FH!%MEMB?QvcBp=z_(5Vti43)c?W|oPTAZXn#57_YMPZ;?wrB^FK~) zu>Q|}>H43!ejCF#wBU^03I%?q=QDL(S&a94w&DIRYV3a?{kaO}mDoK{lUrLPA3xoi zRpF%{nj-#4Cit*e^B9|`>4@|N-5>Jra(kRvWhDVNlNw!t->0r~8gN zytPk<3%)9!e*%VWqWIEi+Z9VcIg9v<;>-H~(e>3~RW0B9s7MKjii%yB7)bY7n-D36Y{Z=^Zh9PyT1uVdHOuaIn2k0#-BI_P946g0kG$^QnDywu-^d*B8L~GwSXChCwm-;_Cva zHvi1xr|Cq0bvSqz%bGS32F{C-ar-Rw&rFZs#i1>m2&(X#tex_+_lGCwyunQPx!i|+ zAH|=;_2=kZ+)@aPDr5aEiGL7uqXx~pYR2cuI^zE9q4pB~r}#|$VuCMP2@?BC@u^tf z5hIhsCGiW2&xAa0^m~&n!6%aXZ{JDjc)3{#Y`rs`{oe;-A8((yfLq?{2vbtk^JAMH z<@mmiiBJ~#nf*VtkH>DBVfU-P8tvEC9~Rj1X_ChH*51AjIN`t;34c?4Frsf5?l_(Y z4!Rt_l)uh(SK^+t`EY%sE&IO`q92kcMPN--p~SvX|97cHB=)&kD8Y9j!T0!0QTVI8 z2tKdm_6Vv$b5THuI2wv@zc|@5tf93B)&lL)7rihPQIno=wBKe_s7hU*^n?+J-N^JLae<0oCuhhwW21>jy;$lA*ZzfKnOtNUULV2p7T zYcC<|vuJGu{@PXmzwNkvru@51)W;tU zT@*j>4|YPoK1!H3m&Y$C{}ep#kIj9uq2UJg_-QiqCPqaV3b98cW$O63UDI;$d;()( zRf7W7PUDkDlJ4P|t&N2CYj3c2im$9Lk8nbTsqp43&u>tETG*`tRv)s1TXod0A6?g$ zxX)fQzBcRkLbIKT8sk^9XWQfX&*@;P%i|B01YfgCd@!w^=J9E1F2~}FbKzMiuMeR3 zn=n&>bC2Y~tmoqyJ}AC6O%BKQ4fCO!Kj*(3!hd0>!f}aA#HUje)}Pwvg$@x|nV%1v zrg41I_)p}72-G^94`y8=S^q+UPmk%5cx8A2eDmY@r1dvhHjVL!lT4$&Z#L8%2YpdU z_^E`{H|!q$4?b`*5W2G!yE)++T~YmXiEb?wF@&)VrCGZIs0L+eDD=-?MjZfEjyjCHw0rKPMHo#BK9@ zG}_0LAA4cl;zW)4=@M%Pd_Go+FRJfq4uoKLAs7Df=kXb8AD5g_V#UTh=(%D7n?Guw zWG>-Y@HG#b*)~#(kJko~7}qNwIt=CbC?WiH&pZ+@x#h$3lM$>xjjzaeM&kA5`Os?; z&)?Jd&)IHKIOuIYq<3&&{V9GkL#l9qc^hGtkCL@(k@!T}I9=7H?Uow(O}J{JdaUg# zJQ>)Z_t$D7nO|o&LmboCPGkJ`SzHsWJ|ly+fqZ>Zeq5#98SS#A_@(@qkm!puOJ{)n zJoWro_5A{7+^i?O&3!KWj~{7%&HBkDTywI%M4!?8;^J>t(e;9^(CqWyyg#wO!RsF2 zp$UzI@?`b)HEDb+^jPYnG5@1Gvp0UOOwbr#?c3V{FWyN5Wfea^fbyTADhywp&eeGS zWn5x7#`MjD3w<~~gGhX*d}{>Cjpl(_!^Uj>(uw~1mLG+WMEl!zm_2K^B>Z=1VH6$; z&4g*B(7wZ4#t-!T z>E2z8FvZ0V@*b(TKMmJ6!K!*PFu1|(E5+BlU7ayOTQk1KxcFiBAu}}EUxVr-Og3Er zCi+X+_tW?e3{J&`+KXXX_F?w@Krd+odJnEdk4}w*i;3#-8TGXlcK+C3qyFnTp$}GIg2wpjtD}zi zZrlhM-Cn(YZY@(_^_N`G*~0Z9vhhnN_?+k*i5|=IAp98T&me-& zpJIIE$@)Af>B0Gn?hp0Ui^g`B=7D<`jz7weiZMpmX^gGL_{OJ}rnooBO=En+IJpbn zT`Sk(49HW@KZ6=8P}eXQ*3RPdPv>`F zq!K4S$puS!Z#KVF-(P*F#G(D>z=X13)=uZoGAbOa=FNfGT~@JnI)8&6L}17Kxv-@H z=QoO<5rZSq;pJRVJT_tdf#645tbcpZsSuvMT3Gvi()#78Wu>Z-q2NARU^b}7Pohr%uAVwwqko(=SAkm#b0p{M()^5`VK{!x z%Z2ZD9ACx6K27Zzj_zx7;bK#MJ`2T<`?_%K{UH~uTzGsjp72lQ%m}=fJqIq&HD>sr z`u_XR2;6;b4xD`x%G#+u`{#8W<{r$4=iRw|qxyeC7X#JZmwklKA;W6tPa0oyZ@)=( z_sa#2^59ShUQUwIFm(bYT+zJ>7hP5pbr zfXn#cdR^h>BK7#wDY${Ef5r2I>^c5`=qD4!Lp;*7q3}ddAHN8!-xg=L(TqQj#(nYU z=Qxe}$-q{e-%~k|TYEnb<)=C?!*QyE6hBlS_pph;DT8xi$JWtoeyP3>2#vtMrshI_ zVmXV%@4(6sq!IN-Eb^)IVI< zs3GPg*huOJsegnv&9K!aS9myFJ^!4Rb;F2+Fpcr~CA|hF6G^w8p!;(1uOb9=jYDZ#W z=UmYHWXSr{_^F*)6wWNqg(2FUpW;b;ASAG6A>MBV8-JR=Ghb|iOwwNV ze2On&Z8v#9;q?UHI|0g}a;_K(fIMk$} z(DSr6)9+d!jZc^jX@@nFy&?V-#}BoSb6Z>Cv!Yn|HiP4j#!nM}EAU&?ENGK4o4ud< z58KX*`J)H3KzWwiPl~_#Pn0<8!z`F)&FdQ}z8YsnVAYS=(B=-`pG@uFhJlgTb6yVQ z3=3lKze?~iVq_EsI^}}FB_q~O_uq9jkH+EKbD_p|9BZfi*j>EeX5HjGIO|iw#;=h0 zKV6k3*z%^eM*nSPyXN?Mn+q&#q@KUx{ko&2d8o$ynOi}?)(6wY_?LS8tsWDIi?gyc z>Z?8*Zs4nV+CryC7i27cK=qiXt}p2A+~>yHwWRw~26uam4#$jyJ(h*6KV4rH z8ILjlvyrgeklR06KR18IGyHb9p-{Dt`)_oA;yl@Nd>?8exSS5+_|%f(Q@OD@_Vdy_ zew&`PL&tCZ;PVFc_;qeC*6%vSK%<2`{$(Q6m&AA4oK@i7l$oFfUD^B>68%-PUy1#+ zW-e7seN94AOc7ApAG0^z@A@B^!vq=k!b#THh8uj#oB`i zKbG%~#wLApVdNz4KhXGT#iUr=D4zqBf8?xxd$PaeYVSsv`q&zbXY66^l>c5d?15Uh zLp18Al-=&=*nA||Bkxc5cl65+LYw3)Nqm9wUwrsYoaLe|7~bXhqxYlt7waD!8|w>G z+vLkQ{-pZzXmfQJYxuJ zr}#=&De<)XO!(KA=eMaoyVE%wcTS%PHfFl4KjqKTI}sSYR5Sj)zeb_$huLuV7S{*y zL_cor5rbL#a-i&XIUj$L|E$+QN3~)_XJOaN@^Y5CKJ+Q4uh$MeN z`*8`2MKYSiPS$4YCw zJ3Sioo~XyiiYwyz%11Lb;v>4L5~nuKhTr{XviYI>^thQ4$27@?IWtph+Z#yuZ~7x8 zhAhkmf1y8Xr}582?%`;EEnC8mG=JVDD;y7f&xVf$I;=nS9|~-uaKMgPP|%F)2b#b7 zbs`p*zR3Z9qt&cG<+pOZcsz167i_-XWB8!^-I?h7%1`9mM(| zoBcy%-2O@Z(}Kf|F?PGPMtztVZh@xN!5aOGIeDIFzB3(kN27PzaaGlW~J*B4vXbijyJ zUK;JAPL?%(ZWRR+E4V(R_Ho+m5KJ8{#UDLCre#wFUf4Mup8W7&^GESxqZ035Ydr&w z&rM>n5{(n?|?%EKIA=hR>^AB8KQv6kIPQcMWa-p?hCBq-B?{@86S7rLLt#Eo) zGMgW2U%+{rDrCcTp)9~$ZT#cZgvNL**a|k*<@S}@=SAl&FiROM;V+v1OmpzUk6kq5 z@1lMsF3Z#t618{MexDS7AB!HLb0Y%*J^1;dnPmU_>Q|4^`6K(J;U9u zhC+DLVwPXclu7H?3sRq9ak`;IKhpL2?c^&Q+M%KF%K8@jJ{n&!ywU>CEOL_A-%OeG ze%mny9Z{&`r7^ze`P~}LMn*!9+WRXhzVFFHv1xm5>21)Qs?QffQ{V?h12$;7{J%2jhy^XCm)fKMK;`~VC zFY^j2uyBufzm@B4hCeMWDgKtXe1;K&8VFxL*2ZT@eUabwmWUUe;L{7vpA=uqrdVUQ z5n_GakIig+D1JKD55vXz85;fn!H?wl_&5e@B2G<*A%E9n?bQD;8x?^gy3Bw* zlem7Q@#ktW{^Hy#8@^5}X8l{c>r3>5apx#JYLg8?VHX)c`jh>~j~6#XkMXu3+jNli zr~LNhXiq#{69^MSxjv%!sJ_t;vwCR8$M`PgIL4r^aN1QpJ{Gm9!00t~CGiuwKWlH; zLoD5(D_nWN{R<%eh5Mc7czI0&L4WNR8P^Ze{N~izFEMbFp-{X^y?^}2s1^2jHcNo@gK2XMjofwyd4vGfJVrg_#-Pa6Xf@Q~Vv;5{^51XMt|; zLe@_8Ti=lpxUw`0?jAp_79X))BJpkW>99PRM{eHa{w)ims((QRW z#aCM|Z>;xw7^IKk_L;_~ZM~l1`Ud&}MD1eVmr3%Y!9CvKsAY!2>sRXW(w=R)ANPjy34W8hAE={ z{?6u)>igdV6*x+F8hkI}`~Rr_aA24MD@~?pj8C;G5aZLMGa$k(i@l%P&zxgQblWE4 z@BVT2e(Ha=e=F{fd6of*ClXkH%75#UBd}FPro?{J{I6+bG#YH04lZd+SbwU&n#@kb zY2x{vii}0<{j~n3&+N|Fd$tGM8_o3##n0GFy|LiU0FC-9^@b;IT969)fjijyX@1o8 z$V<$S83=1X70CX>H|3X#n%CHLc>}?7@*dWX#D4DSQ-#$BjfK)F>er9Mc~CX1J5X?4 zaGt$ClbpXjC9*X-3J#L|FSVcjob1K(4V4mpqW1BGZzz^sn*g_7*|XU(F~sT%n)s=K&<`eO#{ zTF1}dI7j@8Mq+*Cj;u_0me2KHA<=(ENzu6UT^0=8y_mh9;>R~F0oT@K!`fgIazf_<7q=P&Khn5+2)gd{F!A9@Ykj$sHv1DHI>tulwMPy8#;WD~hr9 zxLsQba~!#Sqxkt*6e`|tG#++c8PCR-*7u!g6^1qgCV-Bi18b+}^GwPQ!(HVQAkY6J z8-E%fTQ*#Y20>Fmx7l9S|NorNus;H08)d+=K<++L8IU+DUoF0- ziS;?Xr|An_wf~X*hp$SauPVJ? z3kUqQPytq9>hYt}3&SaE$H8=KjvrbdU2PYJ?<>YZX7GD9euX4IWGW9s-I{T*rIUL8 z+8v-o|NKet{Tp9jK6xmwe8aQ#OF0Jc)4*F#HR53g@D9Aly8kyGiG-YMm5f0{k62D z`D>GVT~K$opiv*$E%n9V;Gr7h_fu@%U?*>V;Y@FizY;;pZ#8Y-VTV)$q30~Fe`tQ; z9lpcdzYK(1tGRun_UDe$^QAnP``H9w_=Uj4E8OJ3GWpUQ*|A6G*4SKdk4{Li# z{FdU+yV4Rzj`x@7Kk6SF)_1_$dUE*HTfKj{t1t}vKNt(cp7Q)Q#oy}HVc5KCEbN(T z$G(s9SLI)FObHneTRb`biwV9WA1H9&YSF&t@%kQW|CUcz;-JKd@ao@|?D-UbR)9Y{)(-(8Vj@f#qoA6X?~zGxhp~oL1TRDW-mWnzkLYQG~oPA`DOaoa?~I9 z6P7J)!Jc19@<-NjFR|*jj?l5qHP)U<@VTN{A4>6) zeyuP5ljg5c|2;3T$Bh1=aPbi5cWVDq>igrXv>|Xtss8_D`@^vAu`!@nWP9Sj@um0~ zyT6a4%FgXOB&x#yZsZFyPHVjUr6xx`EFO7UH}^X|1Cm0yzghH zk)H||Sm9oozsB=pdYCz4`(L3DVyd2>*6GV})|AoE^Rf*aUmE{zy-tp?eaFBgl(Tlq zFItsyY%_5TOfh(;R$sNBDDIEzH5Pmn+`lO#_^Gf_;&Fp-)G%_DL0$cgYLat-UBN%VW%*Vm|bPDcpa&)0tm(MRR4 z-eIF@dcq`!?QVSjrS&<@3qE1H-VKD(7aTu8@S`983(a>m6qXFCk+J?-()i`6&04C@ zU785cGlYL1@xR{W=&25PwieRD_RqBWUE`T@U>6(Y?VM^RKqL)|frmPr`pRe$suW z3tlKzNa`zTd~3k?P#o-)4o7?TW#3QZlSlsv!_s>rq3lc()?P{cw;9Lfc)RJ@-kYYdEbDm)b(jQ~7jk~1`o7V@MBLFx%sTbvpzJ^V(fHH3{eQ4n*+_7)8qdau?w?%Kr90}Ll}YqpCOIGar-3Uj`y-d^zoqkc z#V-KG3p6$A!?Pvr(d>vV4Be_;|GUk!#+ci_6919n$NFOcDyF1reEuKr5R~T*2hYB} z+5FM`j+pqsA8*9_iLaZmc4~hdMSdH1Xe8`78_L?LeS4s*z|!XG@ z{8n7{340vS7d*2$KC}owjkf!Yjy3wi*xZ}4|L_5X|JwOhi|79tOY9dA`?XB<2kn=c z2$`qHsKt-fSn+nXm+H^LnzgEXiw+9Y{&HjW1Ju6=U2Bc` zH+&%K4`2TjpBM56;Mz-rH0skQCZTAfGaSZ+aC}nz7KLH>@JAY)+|Y>OYZu|SGBG}8 z-76hZVz~XF{B*6A0{i8qLwM8CtUrz4C%G!H>)v$uQ1p_`AJvD3so^-?b~LQ)!v8Ow z@LP^}z6O|%2a7A*f1vS=-3_DBbfnnco7-Q?Zyf^Oq1om7!jL1}{?h#NqZXgBy~uC2 zx!*W`i2ZDJ>NAd*tS>BYT*TU`|CloW7p{mh(um)RaW$x0r=g(j!}*c=Cnez>P;Zuv zM*Y>>p$8V+b<@a?VOL#o!r(9nZ^73$#ozqPI;w=T&4hh-mel^ARA2s^V}rxD_(x1@)1Wf&DVu*n_?pP_DYa({*>~^gwGw&u#1hx{PVT_J@BND zn?zqx`)X?=;DiQB_)^a8Bdz~`b~6U^_lyJAReXKX|6g=00Rt>1gV|7C|3dR8ONLqC z`|qxj_%eOJx2-MqbMcYHm;Vp`-Ug!InG}uo_r~}z%=|tSwv6WZDK`s`l@GO zDi~f_%)XD>UxV`<(LmQmqkXNkw8KmOK5)+ZfB4gu)Sm=6xnq1&B|M$5n|&X}XU%~~ zF@HA_I;3&?LD#p6<;QtMV50ug(^}KI#4k*E1Gq66>mQ{e|rc!foy;8u|5XQ5a4Y<4=nNc>NdE zX9wPeVZY`>q2$*v_J1^gwYQ-hZ@3JFE*1@0ySBUZeuS4z<@nTNs6-!7|0n!_5(9-a zNHu-I=AXu|e>Mrn$6M3j?D-J(e2VXnW8RAUuj>i>Jo>Qq|D$h)eZ`h0dcw(vJU&bD z^D= z|DDxz1vV4!=Y*B&`9pO`fj=$|g^QK^|LFKVn-h-X?hJ?2EcN5(BIb{aucyJ~SA6}^ z`iZi}VtlkL9sV-r_@??juv09aw;TiM1G#;o_^$tNJht-~4~<*%{B|jc&%bKf6J@Jh zB=wb)pIhwlz^m>GxO)){|S5I(T&iRklr*^*Z6ZO{W3x~emV)&r;_uS84nBXVYziJI<>o=X8 z57hQBpU|5N|!@01#R zc*j6kcEpqYAN79*;to4r4s=!^d1{xPGW zL*ee&CyXCy{&z(6cg(q`E4@F1)Tib;{6JNWt}ycJ7B{Z%r18HQN8MD)cY(sB-`VW_ zw7zI=o>H~YcBt@b=qWZoK;m~Te|N&bI4h0%@YQiUGz{+t7Na@8XbDpL>+S1_9~Q{L zdWZV;zwdAe_FXYhWB$PZxf~<9r-Df~pC1!qf39jN@TpfS96mg=c6_Dvr*G;gu^@S{ zB)&rTAB_4f>Z@r(pnUmbHvY7}@%g<7oK-wb;y=***rTLK9M*d{{9en~C*{}5fCN18 zY77(vtB-%Iib%l6-^M_1oulmilwZGn`ig&7*B5TJ+fzF~()g*h>^t7yqa#3*j2 z+orkNDvK`-g?}D%eL>?ZE}eVf`MJ)pKVT;tKg!?k6`nZ7R62juzKyL37SB&hg2vZ4 zKhX8HV6{1Z|I$~oKcB{La}U{J3vVxYzT=epY=9!~1KK z!Sd}4_We}fm>g8#lcj^ecP+=ycj6!F3=GFh;|4>y>Jb}%8vkneZxlWZ94KgUc* z_35~%PYdPj|ET_QJ>3~!2Ux*{>3n_D`Mq|&7tZ!}mh69|_!?O3g+WDO5`94N6;cv{ z=Eh0zaT~{1IpOaLpHN(NK|H@x!~VSBOLq98ttYH~#r<~^!cPtAh2jm{M92sJ{Bz{_ z>vo3X`p=0P>qBh1$nnJdfv~3|$0yBC4caQlI$e^%qAus(5)vPnGAbN9JEThVHLb4? zT^x>Q;!+{VX9*jB>OVVt5$jver9${zj$dj&7Fb8(`ffvD)zoy>pXz&^5z#ofWSHds zHOgPkW540yZQ4TKYGCVw))&|B`U4}2>r2jOrSXXekw39WrX$>X!0}7{$FfaYs>3=4 z!u)I8|D^cz4AW8Vu{06ZrzF->A; zOYwfU|DFFs@%iSH7hXFPs?mQeH|&GAM>}cs&&(g$;nmh2Fvwj!{!ShW#gfAbuwx*{ zUnap{!lW=9n4hRo-<*n-;415=@jQjiofH%#PjhE4T5MN z?%z>;o$)ym`)wZ#@t=77jqVQ_@jVI~{5=G|Hc@Z?axJ3KvEEP^@NN|QKAOMZFfs;@ z4ju-TxA^`#itm=+>#7dzYasZ&{I_=grS&;+pX;f*oG}#K<2ip({i4v-Q;oK0B#bHM z`F~m;v8=hiYC>>h;iJx6hHo05knQY@-CI~n?w6+gw)ajybXgP%*^fE@QUAtsS|1$t z)KQW@r}!GM$R0f|xWlAL>hbZTh3KD`#Y4{<+`lL#_z1HU^WQHLG~y$4s{#kjN|M;m zOrk%>c`5Ni?}5-tP|r`(o`$2(mt-ir&+RA0hf`4mKHHT7-lI0L`K9rbFCI~NeQqk; zeZ=)Gjoo`&QCz>XZM;YbW;w79TS(b=TrYCp+rk{B3e(FZ?vD`gZdw7 zGwP{Yk82=YH@d^xY5abbudXUFyPwNvSC-$vG zJRe{{m}Y!!Zoq4l?u+iR-wbT8N z%QuAM<&=T&`hWfhv42YwBe1PaGPL-yi1m*r`bhhscs|ClWVm?t0b8Fm{}X&C5~DAr zz)wqFpOi!N*^}o{*r93=jCweNJ)g$^mt}m%jc@A;-@EOWasNrGuV+sDi93GP6W0F~ z&DxRVC(Byusyb(j^)-3-Yx_(2>0)mK)v!yAgm^jkecH`rCwkpB6~* zGjn4XG-}jGay}#FpY#Xbc&nFY{Fr82VvoxX8ueG;LI+%5C`jxR#ZRJ`Ux~RN2jx#X zv+tw$$ep6V83*De{6qJb#MTMN!I6moJGlL!^;J4;Bk;<+B)BW*_$ed$ynIsxuJ1Sy z>gRHN1QC3E2#vyzACkehB7lA0cfyZT>qLw7BPkG`%>BDkQeW1fp18kaM+$Vgsy=@7 z@l`ZVEFA>SXE(Fw)A&owocb!gdWMqxofgSIYt7eHjqPD9JS*n-C?Wd$?Jr%`y=BIN z?(;=5jz4L9a>~rEctTGzf5ZklVxEnl(SFR?)E^g}4VLI@$}i(~#^BOcgP_rU{(pw< zx{~<$*YG4P=`$P#Chh0?kN77a#sA;!+&~!6ipPI4Nqzp~sd}o&aAU#uEB`+lpWX6H zU*+_=p>RCbn2j%uPuz^_i#yjkXw3hV_VW?<_i6sW*ft7m^eYxTv()3)?wkV0?TLeC z)k*CAR3FDRR$`O7@o?nh9@b9JPixgX95-7fK)fZ#H;w;H7til}RWAuJ_AVPg8ece_ zDAv~(CP8XApBL-w;Qf0>#fm0kJ{jfVt5LoyQtSEc2||SI4=%X+e~Ngk0<=zY@T>Nh$0^J zj_KEapEQ54LcAYv!A|k~-N1#co#x-Qv}3WrA_bybaQ$iSF1;V>e$!Z7xPPVm zPhV_c=OEeNK=oy_y*@a9a*#w{(EPsJbp=kE8Vh6A^7TRehdScregXN-@4VxJ@i;{SOE3v-MBoOPMude(`yV_vjrYPa#4HwUE_Gqgr}}HVNi;5>kN}=_`T0lZh`#yJD+af0 zNQA{1i&_6NqMs72V=#VeBD7!V&)RAHAtXKl z_;tPQ+A7mZU18w{?my7@O!G#1st-vGgnq{A^+BPvzRIY`P`EOmjc@ zs|x&35(yVm`Tll_pJI79o_3JVKjo*pL&C91U^IMv!toPC>}#J{;dpFlw1odkiGDsN z^4rAvG2qmdT)<@-M>|pO~{Sl1rtf8Ro5{O@=t zC)CMs*0}yJold}gDM|4B3+D$KUr#kl#%UEP68ld1(cUN7ZT(+0B zQ+&KwRaezKt)37T%k%GA90bhTag#UMm?Eyg%pxraRw!gGK=Gtwsf15~{_k+)W zJkcNiV*I{(Ml@I&-e&8E`mgf_#$boPV&F#uu7BzJd%Y(Hzcr7AQ2{;J`)U1nRcHbR z-b#S-+nhho5&kULnuuo{l3-eVFzZkK+liw8rF~gfxHW~3FSQRAF$SuAa|{Hd7V6hW zhNmsMd)b14Bme&rq7PjUTj2Zz&FjZBPKK?nxPi}Ky#9gK@AOXzzzyC3lK2bVKWQ{1 z0WU9(m&7k=d}-XeWIX3N$W47Z;1CtTnUHCefanm5`10R z9EtO{M1a{m9oGLU!S50Ae6irxk&^s}C5dmWa*IL>k4TCCO8qydz&P|wiv_D_9zUV@ zbZhYoKb8G}S0nOe|BWy8Z*nK-t8U-d6O4}EW$jcyoN+Q%>5JzJw~jSo-%sPW{`avu^;BAG>j*i!ti?wW$M-$dn^+MZvJv7F*nqIO+tL;{j z`^%B=^O_F<*uSGM#J1)95>L+0ewQQ1JO2cO`(Uo0N{N0jEEV}lOCh=6br->3L1hHK zcT_<7N{-(`g5Tslk(gnuge|wY{-N=yKEI=INldte-@X%kW^H(b-t%5S+$9AYKN=s& zsPBoLngMJnQ;&}v@&4hOP`TuMrcCnv9%0e=ccv23t@!$&_1j&JN8{MnN|;n_&hStF zZ_0{Zn3vdHqkVb1$_{@_x02jXLg#0jFaY<2`asHMUSF0@=4X$1zFTbfU~q8f^Mho5 z2I(lVs#^%)`f;`2C$%rl<7SBG%V$Dmeo<|Gy)=L3IpZA$RK0+-7D~0_d#GDA7LEQ2 zpU>@J?Ik3CajoXJxc}xmoGwwn{Ec<_oukD$U*mhzVv^_qLwU-nBXWl#Ue(L98&}4e8 zJ|Xz%D4uVevq}N)K6YaLsXks;o`_d&M1$<{M%GT_KSN?`u)gpOlIPZr56O=kwfKW4 zzJHUPZ$aaaQ%=-Z6*m*(lh(IooIj-b(-UuXRGp!o0Fl2Kf6@KnU1IcAH#dm;^J2OF zqwA-k<5rdZ!HvR-b?W(NaMRv+`&BoM_#RW&3w^5GB=bl4`O=gD_+UhT_$x_0zD-X! z;P6r_XmgR{gRT#4vA%z-JQx=Gk7wgc=l7~A91Z3LL$y`}YtJP3$ektDPXub7-;*)X zII6Q8syB9I{ptK3c8tLyk^iQ?E2w?G)c#dkC*sX7k&^rsjSuB~PDIuIC~yel_@Msn z^4Uq~(LWjz9eI8)hwz_e!B5QmSp}twx6A&Ue<17cwXcpU@p2uZLpaArCdr?cm>a9& zrszxb5#9g$dj3|`?e-gmys7Hvf9lIV_~>$X=pM<}C(W;4iuXbTnVUxYoHl*{s{Fm7 z&t|^9D8FTme~X7Lo`T-ELvH{5A3Z-iF{7=@e2tlK(&7XAe=YKV6E2JdYRgGUE={FB<>SLr(rFhLZgDlcXdpJrxQ2 z3^{&j{^f)7FC6Nl8J{J_{ZRL?t3=;Zeo*xc#0}UFZl6+*550&)tT!_poL(E$exEcy zy1Hl}9^V%U=ic!AQ6-7*FQ1)^Pc}xu--kA_{?vb5dFmn_G(8QYZUo5q`jW;UR#h0O zZkOpw)(_1;2HLe(ou1l4(C)mN_17Z$w|I{e`cAfj-3@Ek57B2qPXqCFWIyQoL;e4I zUQl9u`vEX#_GtF~)PGnfp5H3_Jpj60cVO)%#Q)Pajlk-Gfv~N|7S>)#@cC#`4Eh`n zg?%kK{^ND_`|6Au0b>sdRk zPrtuB87D+W!U`qlUm)u%_}nEtWpEl^e&P6_@sq;$LFn6|AEZs=_KoUm`!{mzS=SGa zpG{-$r}5oxV-?sj#}D4@;PIP6V!uYei@>Ju27t*GN7kRl$2V_{!WCZ=y)tj0904^ZjZgT0^nH_kJ)RPQZ6LyM4| zGIjHtk*A~Tc;OFxpK^<}Q~pjk=&kx|rmJwbHvUcH17}}3 z1-vR*$J!}B?&v%abq*?FO)`)F(fX7}XOi)SUxXz8ZAj`jwqMXv$s;~NqNn=tU3t5X z>Os^OseaUIF5&O_NxG_~-~YhXYCirnell;kuByDgmf-#t*!R=Ojf;=hVKgQ8}agFiWtC0 zDSp}$ejTzV7VpS{!EFlneCX`sISi`yfPS< zHi`zb!lkS~jn7S)s;l~%Ujv%Fr z68n@x=GWLYAzrXJt#-_%j% z{`@4xH>n@2zUG93ihE1;Cs6w_sDlEB-1LSqzlW-Q|5NdNi_zcu!`G^&tewV3S1*jf zhF$&OXARd66n`Htiu-?Cgg|BukN+UiR|j+x@wIm-bhKT=o=^2hXFD;zHY5x@|JGye zw7#?ZS8;!8C%GhlL+#rm_Y{03>bL*ZH!@UkkJ9lc{Ni{~SG94?Z%AFPo?jAP_s1{ooHfR0?3;$*>JJ_g{-E}= z>y@adobI1*yyhP~^7S;dzsLWd`oG$)Kk?_Nm#`~= z>l?~{SK3r#h~sN8-zceb+cN5W6f zqUGpW?WOVm?ynWk2a@%JkM)PJ{xp9W`df}i7WIQi4oz4)wO^+{MW98zFANUKVeK^k z*Fh@^pTzq?(Jvl9Eg|~Qx@97^=otd7HkR=3C-LFdvj$?@sbP}(MQR@#&rQM7p$hoe z%a`@1`H60SRpX46ufS>#A76U@k9~9<)k5nJkoaVWjN@0T9~b;nSLOTVBPi2q?_VPE z<+>+zRTrG9p^g*BC-skmZ|kYLde%VCy?p)B`TvscgZmdcX~gfN*}-@z*j;kJE46>t z(;cx=VF8n@YxNnK|54)k#j`hhK-#VTYQ=oWp}yJLS(Y-^Beb!CsKQ zjn~%#(Z475DlkU7ADBjRd;rn!Gv-C%)e>JA@QBYp<+qJz6VPX_7+;&u$A|hCho2_k z&C(!=eWUwZ^#3H`icKLS|4`Z{wFrL`3ww_!`b}P z^_%mh8qW@V2`dXZet_tc_8aS}R`#g^x8c1uzhG1}0cggu=G`=xtzYXr&+Zk#;@%}Xa;ArQBU*GkBpfrvTYQOxyhhdeC z2V|T3u=msR(wy5nAwW8)AN5a#Q4O!aDTX7d%p?A&nB@xzT$#-f7Ky=zl!tp>c>5Y7wNV9P0qhwIOI3B8u0=mv()3`%A&d| zlXdUmOMmtF@ae6u(tGj?@?LR#Q2o5e)fdwmIl}b*e10iD1e*}7SOSv!DXD$?@%KOs zFbRe!3%Nd^{zHp-DVTX61Sb68{s*lOG1MQ8w@1Z-X`?S}eQA^Nwf<6pH>dq2wckWP zt(|J7N=$4Zw0)5*gAhZ`K|}^!dOV1r|2* z1h=E=^~3QTvHrB!6Q+G_%=%OPo?;V@zZ|{b#ufGJC*^cBex2bXv7aA^{qzTYRg0BB zA!Cht{QRifP<6JXu5fu-t$rrw$1X5+!OQ1+z~kNO$8X*tU#y?+pb>vvd!^#EUm@_s zt3mDfN#kdZokwG#a}1bV_{8uNPxRy71Gc!~k~y4eyqEQ-{Po&06vd;zCHM1E`={4P zJfEvs+vk3jPbFR1b3`ktO2q;DRJWy^fvY3=?Vn%{i#Fcv%b`@-7dW$gJTWdFp6 zqxz}??|wk}AwIu!|75(<4JSUf&{!XPA>B{BKhZ&>e|ju!5V{!zOX3gdg#T<_Uq(Nz zBM|-7U#4#Tn)}&e-4UH21Z(|ca{pt_ybye`-W66{&13)fg6O-7dSSR)OC~x0kk0S^ z9${E!E`yri39LWO&y<#n=S%Mca0|?0?bQBQuUBB-k%9ytG(I!shgd(c!yUS%@%2mN z12>E#aq~(~NPS_-o=@{PyDj2ydW;YBjoHH5E6MsCD&9YOVaY2vUN%qm-}q7eIp%@B zYUA$j8sk?j4;!n>&T0wM?(^@X`tkBI8NM>;2{Gn;{DJ7d_Ktpd=cXOFX7hGxKR(Tl zMgNW7V7O7vzMtj?6!&7W=NE5S7QdObQ~b{Vk%Swz`$MV+k8jcO@zfXXZ)pIeJm>KV z8XpavCW!ktZ2(G>Iesk(|2%l1z&a}cru?*E<3st)*1x z&{GoMr1)^_7Ke`C`$^`X>c2KK5^z-qA4vDpV(%{@{P4o&ZyY^&KQuqZ=ZE_Li?qyC zLHl)uH|>t|@z;|2SC)(0shs8+3(x!T`JwA0y2ut2uXND3Kjq>KQ6JT}k=(yQ=cmt( zQ1l$(BDw#Cj{m8dVc6By6(FRm+VQm(&#wygaD|W^ynd7F-vu}2IC!ud{A-cP`cwW% zsu0iD>m@*RZX?!SNc^LFMp0-W>hGlR^{k!RcS}VK4)OPb^Txcsh}KW_T`S-qu|7I# zCfA2_ew&E(15dm7fQ@UN+V@NC^SHRncq-%|j2*6?-%}IJR1;lwg~(QX{-}Sm%(}Iz zVvB*0?!8Q=j^73@u*H`b+e_{T)&lAMz@`p2CbbXCkA&jS zXlJ<5jMqQX@xSE}hCUU}U}nVgkA*}Z95$EZw2dy3`K9`=V2KhZJaU6cRXn~)?Yqw7 zaC~b5aN5|HjW3NK-EfG+YyAZ%?#%N?w0`5+nke+0?=G2tZFe0>eBJAZfHS&TXk5Sf zA7XI%0uMMVapfW(nDz1k(_fiHf5lXqspeMd2Sokl zQh!h9@5HVEY;w~EQa-DesKOYXs)Iy1|OJT;J013;7d)hu*k}=f|vJ-%stcZTm<}Hju$$ZO%X4+@<;VXFsEH z?@9q?yyE#IiXWZrF*wZ49WsaU`_ZUAbo13#JwN&!E`8zuNBKMShApP{ZU-Z4?_Z_( zd65->yEa)vGgFQqx<7Tow=mqD=me=-1-0vIk(C^Ei=8C*!%_UK?koBS)0`#io92hE zJ`?Y^)pLcn%hmIDhv2)obQ(hJv_RQ^{8mEtZ@;*A7YF}BxN1C&tuG+?&7KS2W7_;{ z5`1J5|JdY=EzWUi3%3(@u>S+XkGYxdSahg6j5^52hw{6Au2>)9k zla1elQGbaY94>RN{XVJxl(|5TXRkYglQv)fH2-t)gaX@EI!We_>MNVCO3eN03}uD| zwa=HHpKxs7ZQN{s1X{1jlKnS-bp8GEslXj8j>6ZKE^e%yoG-ej@qJwK4?^N!eEu`Z z{M#(B!*uPo@Zz5O`O|Igfeqcd!`&O|=PzQixc_i~Gb|2W#lHU>@gI(5i|3OmrT>>s z{HF^m<8fSpJCx^|vHnzl?=(tAhwOe(-Im*bB>HW3atfY5;0^mX&13!JiT;eX9gK?| ze4+IW9$%yO!|lcZ%-d@PHmUso==x0!3&Fzcwy<^xpMR<^n@$t&&sgsO-3I+{f19-a z>Ch)RMjAQ7tIOQKqWFjq_eUIS>jZ6kbNxo~-{AZ$)Qvs_v%L8H#|zT@%CT7$c;e&{ z$h352^IuHnziHk3_-N+|jqCf_zWbQtk1*j9#|PyH!_{`!qiq{#SCjAipj{p08}5jZl%8CtvZ^Pgz_iSkwq z#?_HQ*;-51pZdqU2gZr@#{iZ7vug1rtxwc5jK`N>0kVHJtHqDhzNq}JVB*C+@NRdp z?7#Iz_2YRhFT7OU4bseb{D<<}$ZdhRZIl&6m2-U2{aF`|hhVvdEfjlje9`>I&I&QU zpl=U@ck%o--QO^)jU3N-*+a#rIkn#}<&S|cuHgElJ+SeF`tPqOd4~R$XT|%cj@AC3 zw0<_)-wu5~wSpdf{uf`9>fbfmUfAt@SEw4Ke*TMG2B5pKrFad^PWFA2UmM;F#jtv| zaJQFB?e|OhHSI?j-uZ0{=C=I*sD0O3CdZJucJTHQA0N8^v-3;^PKmUa++Rr7U-vO$ zeMK(^@a=3+`+n*CZ@H9?gChbY^(UDiJwGHS@)~+C*aOp>@%yVNK4L4bp>LhN;G4kx z6Ux7J_x_9jZaoZq(;Vtsy1dq+P0L|@OZ3PX97 zc>l%5T-HwgqmJg+@sMl}eCW&ZLHB>U+`Nun<$K^j2FC{w`+V8)Ccb>W4;H)all{j( zG{5rTuUmND?Eu_-oLSp0wGSOj?C?!OOSq`y_$eX$Jvui8eV_D&voX9rlKOvf2g7jk z1#6gkmHY1{1RpCzeLKFc4ZQ8m|DV=xH|!?v?|o$}!5@uZ{QvVyFB;fuTz^$*5qRmD zJ;aaW_R*5yV~t}ZrY&)R&s`JQ_@|TnUY27tPLn&qv(hZq-k#`#H3$BG{jq3Yy1!!j zkmirDcR#dk-xd0zdVUM&9E9bU`@pl=JiZoB@Uy7PKY0DuZpcjM^Gnyi&d`4_#cmIn zRb;UFD3|Nb*I z2uqCnNY3Y{_*hkT9lclXf<1N|A9VdIoBe|ZZ+C(JNRAI6__((B2EO;-1Dj5$$H)F- z6IC1e)2X7fw+Z@hSa&Wf#l;bSD<-(*SF_x4gbUYKbG&IdU^0pX{M zJ(bwvhBaIt$n^uQFFY9^j?wpQVCxTVA1Ob@y$?s5a9d~}t6z&hsXoYR9)o|saRAGg z{CqLWA9BAK9MQs2!awPRe{!9?@pkhr8tqef&Q0w6XE&U-;{2XT=09xtO|)yc2TuRZ z@uNlTN8ZtYac;^1*kf@(#`G)MAMzyO9;()rN%$k4@JH!OdtCg?Or!lU?GuV0y~Ohc zZ`;+5k5s??Kf1m;uBzvG|I$c_NQ;1oU5JVT>Y0m$ihy*7iXHg28@mPULJ_e=0lVke z-5rR9sE7y%i1j<)pSyVG^Sb)!@utmN}c{X?~mA-Gi1XNNoT`KA0Y zr&l=kagpvfzOT>TkJg7}z6{68LoRTC_$!t6!C-SN_L1zzdtol?pG4-@YV06vy&2%Y zdFNSwnm^vOs|U^<(x6)V5_VNuU#2bL%T~U=fY=wYU@LypSO9H3%h>bdmBuptwSS{W zSP_;DKPGbgQ2yvOih1@x> zPX6tmO70)`uh$MgE-{0YZHM^y3Tm?V3r*^PU8Y%r|0>n|(lF8wJFRXZ%U{v>DRHGA z4!F<)qAvTg=Tm&uZs(6`-Yvnwl;hKv_-}Wz{ZZ>!OIW|54(snr{EKyqCH=OyQ?>SO zN`p|W2yX*z{1>zSRNrXcG8Ciww}At@RO3&5csQQ!-41kpIsT}9ve+~LUF|x7Rn`4J zRNwGv8;2&FJHg4=ayI|D#6G=Q*8}}WILh{q(D-y&&H$XzwIe(YonQ6-^7uF?`w7+= zasU*4+p+nLSDMP^Z^^)yIHBcHa4O{Zp!ZL!&2NjlTbn|x<3aZP1Ty~~O&b_iZAZw=Gt>}1cU@uitYC}z4l%i?#cPfoB1#Ud|f za2d|yxBsah8`B@5mOC^*@|DdmtsgzO#}mg4a;(;V9DN#xgLFH>=PP`EDL>VH`3Ohc z&V(C{dH##WCmnnrOYaPC9?;X`9-xrwi9lC_Y*ix}s5`1r+w-`U8z$>KprEc}z3VZQ{+w-%(a9g5N6GO;`PE@t0Jd7%LT2CS{v#{h5Ii!_3Cf!6VE<43 z2W6uW{F2}V^V+Rt?KFOR+cX4!&vpW@$y!zY<^DyT9O-@$>(($)i`%ytg1?q0qVRJK z7wLRUu8&cDd&7E9>@}=D)M=qQezAP^95ruB>wDKCw!UM?{61`wgNt7ugvu-2e?a0t z9FEPwgT{xTtnWtQ@BGsEM5l9GRP;0fquKob>HI#a=Z>ysma_Z-)i*kx@WV;@O~Iqc zf{hP7zvt;Le>Bc)CX2tQ|Jm+W0Ont74#mT`|3Tx!y`DkX@Kp=Q+0%hNpXzUxn$rI1 zfL5Tri0|*D{=>+%Az1fzE3gjb^GECBOnt-gyO}f8s^s>8`k(i=hND)5GkBhTrgD9k zKZ?M!k!@h~nT_oIXnsAiAQHcJZ3{^gX0Z0l#Q!+ly(4dNbRiU1}|O=Ajxt9wYoQWL#62)4`H`Kh=MmN%tRg)occtPlvJgR5Cs{ zJp%A`!)7x3Lh-Y{O(2?mX(sa@X#D$4x-zVc4D+%%9K> zik{{%d?gV7U|C*AEIe)@KmU^GLo3yLVcjhb)#9U*=?m=hCJWl0R~=tIZqgQmCK$t) zdRhGaiT#hV_Q%uKO`z~*Yt~NJU)g^FIHY}3(4NWXkKTXebUgrVXEv>N{yyhR`tjPP zaD9svdp@=AVHk*ado_cGx_tg!5FO30?g{KX8muI__EFiX@6Ah7GQgT*PkU3 z`%`)}1RI`d0fX!~e^CFxZE`qX(sF|R`kWuAe)#2WG(OqW2CgsR=g(97U%R(}k*6#n z&b?}VkomKl+Y8rgR6l=7(_c#QT{iS@!PlR$QeNM5`OZsh*7N{$dd}A`<^S2M+Ms!@ zns6w!ieJe5Dn|QZ#kxi?xUv-+Kk9#P=p2Cc&6>#gJ)YR-z>fjwoYq8kKPz3ItBWN4 zbw?AJK6QE3{L1T3Hn>Uq+YUFC%`f$@bB0Uz+q`TFKb3w}{pIoL?-L=YywDsp_y5P* zDSz~q&ezy@rMYZp7WbwH@ ziO=1%1gyK=0-#&f`Xck6GQSu0v94FG{l97O3|qPH1FyxL-|7DRBekF5IoJmYj@LVL z|4p8s$ccH0>yBkX>DLVcv;QE+&*sov>_018h96(z|2;0xMQil~0K1Me|09>gj|Kix z{P4mE?CSCOR{`?)(Y2)?E{SOf#%Eiy`LQSdf9prm{-Gs}VSp*O4|M%EmF}l?JKh*l z&vE=xeeUC;AnaDu1m-OM!{(3r=ZVt!0?p4jdjm$pvEPpHU!y(vrCWW;l!N>O% zZLw=RBlwuh$Dhvco7lcM;gKWEy4akJj}w_+$IAiOW_=^@d$W(VClGz)Voo4Vp4u3; zr}3r=qOPa{|f$ncrv<}9GiA|t1&zkk8_?ao?4=XN6=UYt~$=Ydrbyte- zW>`0aq#{25xx{|-ZWfN#SDQmhR~|pm`L*~Fg-c$y0y|4y-$3&#x?iKQ$8INZQs?{< zL+ty+*#fQ!sD6HzeCv&hczap=m`due-@Y1wW1qNz#{3QJ`{@6Vs2qVFpWUG1#YMJ0 z=>Afx`?+}kL?(dyX12Z+WPR`J{u)Ch|G|0#w?C-_AOAJY$IMlSVg8i|!e4%gSIY5~ z7u*(uJq)3ZLN$KoU+jxxn>fP6%^W{K@bhF@0FD^kP?rCTC-`}BE&yFuG=zvJUhMm6 z{Z)63KpcEgYA-Qo?Gzt%^rZbY5?FvGJq&W9%wv|HhNX zaP!g#)<1#xuhWNyqGv!;&_AsjU;EcY<2v6~0I&J^-0=h-aT^4*pJ66DzY2-{c+k`f zSEbp>>T@YR+DAOW3#WEL+iIJLs|Sn^B+6j2H|m+Ml%1G&i}42!T8dku}t4eAol0AMhIHeZ44XstYG+| z_UD5Xzox8g3tie?!j?nmqj}wpzanJWV-%6a+uU$6lef*M7LI%kh&-_+#D6R~S2V zKlo*EeTwSeOB%Purs4YVeLB~dC_WZ%_e02afT0sPe;5<~DD;%#m)QCczuJ?HFSY;L z#{zMfe*>^^SB;O;b%XHa)&??sQ2nUPDF}_E{jrX&2pMPavz&0%bl zCsq6SefJ~vrm*?N?rzG z%Z?2ocQ(gI0>Ovd>=2x>pds8pKD_Gx<@)}aB_XJv)DT{5n#0;Jllh<2ISg;TZv>v> zc>N`fkA0lNaq5o7(5f<>^-m!D=J+)n{h$ft-Q)4I0ofnWDK82KtZfGNV;?j8(D-Ol zVL7_3J`L+#{Dr^vBbDSgjimi!8dptV{Y<{TDE}Pa&>LHL+sN+!QV{$kx68ri%XY)K zl^h?r1RuGOgFja9hBiYEvj3;{YjAQ7WOTqZ!th31 zBN*x)&-zpQ_3~8&PAzK;hpWziTubmXdq^~9lr{yYpS-@$l;EdmW;A}%X;y9h+qMS% zu!Btth&Sf$pbMVoET{3e=68pu7vg?* zdHo38zo-)^-Os*O53F`snLj zfoL?)0Stzivi=mmZ`%i<{{sg&}v^Apui z!=(B#LDH|@*00UR7l?h+dnN6ETTxGTzhDyazvoN)r<~u{1E(FOD*c}`KZ9^&yn}T9 z)*$wL8owKLjK(d`8^hHH3t2l|-_}xn`JEq);kgx`-<^cNruC0S<3&xOh6#_KssEHH zoqzS9Ml;wrf#2^)_4(O%zv8OphhbB}NjCm;eeZ7h4YM7O!DP*|o&U}ctsgEwrNl39 zYsv7XP|EAK{k6RD$=Ev8;_Fk`OZ;#2PH>#X`AI?YyXGfy@$K|oP;#e=Ux@u1?)Dm; z(szUNS&pw9A-o=@fcLF0R` z8~zyj!xjSi8ngMM^&R=o1915bJGj_gHU8>!4Z^i=?7?4eFY8b3n~`*XZJuO*b#won z4&v4J$H$}^5R&3im&p{lKq?00Iu}s`x9vWQf6TU&M;^Qx#zimMeXAcY5#k# zo{iw}9L_&9ztr|pG)6&V@O<{5%Kpgx^PXFk=vrV5dw=rrwI}${8sLrfuUW%orRw<2 zZ~O}!QLzoY->K%GRqn5Fmul&*9#1?L2P1c|C(~`IVTspy4X5Xm3@JQOfdq~d?o)>p#{b_#MIxh%) z2H3;zXpWzFVt+iO_`j!9J-9ob+c&CTXO&9zD{bpRi_}f*`BZ<{TM&ZoCH3HTO};Kea*JwKE9haF5~u;o}O|I<%3{!*_fL|tEm zu=@eRU;auU{Gcs(pxsPkXy?Z5i*y&NY=Ra@=clKAvXY&TPW1&XtC!eO*bXl{aQ>q4 z|JkT_*yh)6u&%@P10?*F@sBjkv+lB<~{lNWl9DF&M9Q?uYkI;_ZxHa6ZW{V zUxr_*fA;S2S*jn(gfefAUnKsUFse0%FV}##j{oXoWRF*Pb?YG2x9GyG7(PDK{(@Q{ z#@4o#*f&<@luf#yM&Kmgr#zQQ!Ig5bEDQ zULoD@s&5as2XOmqPw+MRa4?=}U=Pc(Ilof;`c4c%)8qE=;5f&xfrmW*Jy5zICVWUe z$gxgl?@#ru$be|v@x1}qFTGo3|Ka(q(%Ei*Y!;>X=!_uvkDKINym<36G0?0xXrd5o4%nfIt}K2;;(sf{0WdeD1>wCETd291*QXeh`I+B77*AiZ1x^0}?D_P3-yW{g{n*!R;pU?jtlgf( zuN6}L!Z9uDXBtO%r zI0An=)`ysb*HqfiW#@jQ&eIdHG?L>-LE^VRgS(*i@tQLKi^iAf2fgu?ucb_%pz-CC zqW5TWYd6dfQtcldjQ@<0ANN6J@+O848s9a}amGsxG{E2KU;U+=KSq1GVtNf-$$oME zp!o0};)lr{tzqQLacq8^2tK}i3BZvJY+&Q^CagUd^1-m<Mrv+V?gX7suKHRNXJ@OZ@*sicsv{!4A?c z4y^irx&Gx7D&5~a#SVJdCb9N-GXGW^B5?CpiC=DCQ91ve++xuxz5x_Y+EMjVl$k_47YzptL`-tp&U?;o~1e^eLxWZ*k_G?XYb<_n&Ee7P{jtzK0!P&~&Eocm1Xk z{F&K)z->vpVc$z`-zYvhjQM~!C4B9=a)kA#@nOb@&lq|x1M)gNVC|Hjekq)>|4B9I z8=qMIjRnLJJn?E)V?*C6NL4nZJ^!mB~|_9^&>gyL3nI}jm-XO zddTy~ZKnj|1zmp_2Hz`ZH7OpUp2`z6-&wihW`DsKJ@-Mei&JOjA9|R{2+VYUYaElUfLFd*?E4fTYgXVbSG;~h zTjn28etUOI+W(kt30?1mvi{V6`7Zin%}^^i8EL@UslHTxT{@pB)(URk7+=*c-+w(r zl+JHkT?YaNd{)VC76XIPx|WU1|Ia7{e%MVlhywdc+Hn+@V z_p1TnugZ~r_$k~HEIT@~_g4`6J~8JF7N1C$<%j6`Gs^IH*y!FiDB92QmrCM;*RS5A zXT}bQ*nC*{ix0|QFM^A3^s5YL9QKg4Q~tW%$r+3KD&W)#)%aPn*A?&PXvy-&6hCft zrTep2)TwrUT4aP{w+^;&ayQTa=9BqZBi-+7e@fDys{B(r{$=apu*s?ha66LgN4dm4 z#qS)7lLDJSbMs7wuXu7k(kahwxNUr4-d_- zfQpOtRnA|rrL=$VsfDCp@%2OF)8YjI`1_M3*k9%AhvqLkj|@bs)mBhYV-kBltzYtf z@fO2k(&17rkKgF|JgtVj!_F7ep;xDCoFB;jx$mCkVfXvn;PeNMA7kRb&$#s-kIdZ; zxAS@ZS}KYEni}NednrGSV^!lze|RCT3fcpg3OIjJeC0&A;oO;8)%xF|sX_R5xs}ZS zjwkldK(ZefwpqinC%f4AQ2nW$biRsMZY|TVXnc0BiFCj5CmYD0!1sqy|0;A;Bo0|? z3!m(^u;)|zGiY5j>bJI+<$vk<6Z&@j(9O^RGJSb`Me9?qIM)=nHoPHQ-!wl^Vb%uc z)ltA3H|{@B{!T0DhAX-o%J_%kcb$h1nmd}p(E_f2#1s5Bt?!TZ6&9dg$ni`4huOpZ zv7?IxTPT0 z)%K~|jWF~*RY#@|Q2*&sax7*Zu!rD|Tz|?W{5L0~KMoKaV8I7&zbO9vTS)kN_FGu@ zP&L1wZ_*umZZMG5uTXv5&BX_=bgB(oLpi<@2)DBI!SZh>(hG{#XrQa-p+c)|Ci_nb)Xr;Roj3O^H{>vr&w>hB% zoqz9zQ+*z>{!Rp6gVj3X=EhpkLCO6?iZ8?TP&|=i1-~1bFnrMZ?A!;TsI4KzhxUAa zcM|)SvNjf-cH7D7(}iAjFBc=aTxi<9&S4F4zPr-|VgWK6!mf&3OSh*U=o@vQ*FS z{4+rqaLxke?BVN=+P^!Og7M*OOQ<=5uRoffn%r2rpX{n7_%-1A3gz!hnISm8g%!k~ zo66pg#^1^2p}2Q~6?Dxktg`>|{KHjvk9`_$1xt5s->ClXT=pJKcW#yK-=O}}nC2g_ z#=LYmy;wEB-7D*e-ajHL~msTS}um&f0f-yZi1!Hab*LGkbt8z0IqA-3T-)6yFH z1|_iP8x#JED2zl42OH3E;`N)fKI`}INOWvz1I^ZP|C-`E{%0(jo7jQnMSi~_&F{U8 zu@PfUp2NuFJ=y;Qn8*T{g(c1y5%WXH9mw%Z@m;@B4}7ylzgqiP)71yZPp$=dz8v3_ zzwW#bM6s_q>}=nV{Xfl5c>I@-wv}ns;^X0l514UdD`YO<_@MgN!^BTmzx6hF)|l&8 z_Jn^9nG|C4%I#oe?<4%>HwE$U1MmL82+V||c4@3Vf%s?FUTce;W}kxnj*Hm)Q+^m7 z)doMWs}%Yy;Nu4*KKy>ZBYN6sR?B}GQvKYpGIRKNj^l49$v@{x=R<5xvVa)N0+smM zUN-{AKDC1GnJMi377%_c`y7G8;w60}U3GnFpRQ4uGq4V98_4lR^{M&K`{9;Dw($4} z=TBPyeWR_mcsb#O%>SbCRZ2m3{3X?AoSDGm1Imx7g+6F%Rtp?=ar{ty;K&7kyz#g; zECPOhHpNe{PXNAhH-+B)xjsSt*Xe*lYH?4d==`ttio$_otzl*EVAh}V!YHV*=fS>ap>m`K2@3 zAsC`#1~$4LRrr+ayHUL){%>yv+LsJjJH^+;VIf%RZ3d;|^V#?S(SMcEq0;?jX7Kwk zA0HauACvUW%U0W9{5D>Hr%=fC&yUMHqS0p-8wdp*z+b!F!})B1u@zxv?CI)u#a z!zgEC_`ORt|2?q_Mvdg!5I?p-)%eQuW6vb}*7AOBcx%DWkD~tRsmUSeG0zmvPUrZe z@t3*LXH4mp22ZtB>+5RMKcnZ`G&%o}`uq7eig3)^bg0Nm5xD;)-@h4Wq$}ocIu0A2 zEv#yn$Dh7^R*H$?y_F}o463^SsHSZEEl0M)kZI+D?|-W8Pg~1QnA1e9T7FAT48!w= zW^hu6*LTtN+e*rx>^))u%i8^0|ML9Xvk@`aMv9;IT~qBpU7OKQ+CO0p$GgpC^F!BX zlf-`Lz1JFo{5gK@2|p^02jJ7=b)Z8Z?%z}U+-Fq}TzynWw!eYaSJgH4!AIW>;NvpR zZ&bfZ{m&oA8ySPgNY0-$z6q@e!ixDO@b+V8_Wsm=(mo-bFKk>JY*z5|LE;HNWk~1e za4Z67mUe8oj`)1~{#jxv0t693DlU1tn%P?PNsr~K7* zskFb%&IE3E7TEjK`wI?l2*u%vwV~lBj(@7ZS%!w;$=ar{vj;!Fk@9c1k}w=I!?arb z>`aKnq8{d;^Ni~kbpJx#n$hSNWdQ|O#47%h+rPNivA8wZ3WC}WXYZd2^88~!tA5yj zsTKIPSi#z<{~l)>hqmkMz}su<+4CvBQW_7zy~AxG(tUANe|dgs|LS~sKMqkHyt)hlQiQ$>K-KfAj1-u|bHAZ2tu1zd;Rs@G}^|ZWoSEYJc^b_+u-hnlk?T zAAF{blg^KA2wE-Xv-kHU{2uGw4!z?_tL5jicO9{o+8^O%R0iu${U5J&v3T9q62@69 zXYKTUgD(39pudMTM7&z7a(vf}8-l%8)RmpTkVNAD+-t9J)cmzju60e|<14q%@$24V zy)o-$_19GYO|f{7!y9jeGPSzw{Q%_lX;#PwJboYr9@ngzKXQKef}^(LG24frXwZv) zKhX!?Z}r68*R>%kmHP*D{+1PbtS2#8v?gq^7#p!@e#ww}8QBZeMA98SuOWQ-5p)#l05n{iNf%WcF|JgJ0-#X*V2= zp3B~k;-k^-PB<;{xA1TO7{#}3*CE)xzfHC0S1L3A!#}SaV7AR1_Wv|K_FUHv=QJx3 zG#pjyAA#e2aP2xhXf}`IgU0t=gQfi!Wro$pcU?OLqUkClcwJ`4{-4for{q8^zi9-| z6*{b)^0!q~FzzrghVG*|eyIH#79WbPl75xBk^4s!ADfPa;=aAL;0^NnXPW=s>Jo|F zO-*5DtBxyLb4E<413T7z=OVFMjFyNvB5_qt1^laB>s3uM~gg>ZNF^ zw-r1bdHom7Umh9r4TCh(VNt?Nw!VeAA8@+98brRyX5&Nk+lWy;v23(Ua`)J%)LUjpH;4G#lxl%o+;cC}~i6u)atf^bnE zBiJ@?3u~wRc(1E;K9gNdn7p|oYp3|_84`+178}FRtT5JYPwbyk@^8~(YQcaJod2l4 z(X~Rl|0Ki&tfz4MpG4xX1?wX*WqfT&NZ|DWG``=U=79^BDxk|bKEFux`HcBJG4PNU zI9Bbip!u(L$x#^FyS6O9^O)$D6C7jF-@vTe{qbX8_QPgw=5TlxKOchT=UQ~n!zTyU zf}gQB8y~7)y*>FE&mBzxt7jX8zw3kMFP2{VjD=_9>yPsH$N9}r(^8>fcU?~B`(Nq7AJFk{zQhNc)T{v>M|pmO;yZ3Y0J=vQK-+oTzo7Uv*c6B*tqs9# zFSif0e!r`9zRml)hOjS<<2!-WPX;{-!eKf_()rcyY<{SHAO1K9o9G%r!XefCzIlEK zewXUc#;*xs{i**qbxb%eYgP*aj&c3Op4fkkD8-&_w!r6{FKm1j3VD6~jbo)aWwg{@ zRUb|757anZj^6QG!SUN*_Wu-L>w`UTf6eOG$IM3q@Z@@PX#bm!AN3Ct9t^`BL3LnO z$ySyA=J=xZ zTiRAZ*kQ8)1aIf@DaFsqLBV)@rXf5voX5VO@>hCgFnYZ+gn`+*teyG?+m#_0V`c<9 zBZFBx#ZTh-5L6#&1Wp&Y|3LQ-YPAo=nJ0{(;}3p*Gu2me4o6|;SQD6doAW2tubTX^ z5+{tf3LytMztj9&=4cO`zU8-2+D|pVy5+UUhG9k3>K}n6zEb``w_5+a<@Z25xLO~4 zeYpLi^@n}y24mxJ14#1b>zCRmcjsVq9by0lB0pb}et*fNU>v*702;pH_76$@cGitx zJb%XkoUaC|9DfJDaP(?bQ&zuA&#y~f9*(JDHQ~UGg{(ilpT%-sBre%)48Ho@zu!sh z%a5d3oZ7E8oR03z`qTM+d|X{zJ#05vn)nN<{3l2Bz&n1wgn#EpQv0|3Xm326rCDwM z!&*B3eAekgVNHQ*|9L|zKb+NG7ZOJE_?YT9jwb{0#%eu)48DHo_@0jl!e;97`KA8J zgp*QzvWLD*|Do$EajkTI?uW5Ubih1-gx z`FW&NACWgsADngTvHo=bMxaY5ZdEsc=8u9{JH^+BreSEZ%>Yc>a()G3zhf{AgLDlc zGkGlQPw^F8CkCIdHU_&-oPVkQmb)efmrMFWb^HI@MGnBMp|xfDE{*RdZqpa%{x|?9 zu3i!tKM?=y(@P7nxZoUg)^}m=NAc0SUl%;0{X;n8!1Kcw&6AU0q zR6W0okA`EN^HTkl5!avX2|l{$MPgZ+Aw*n@VDINd;-iVLBc=SFkt}~j{m)9r7>wOt zvs(VCl^KUOgKJCYcXIyON#ZBdj6s;S!xXZITxav+OXAad6ZJ)do!Q_&gyV}$cs7u^0;5Pj`* z*MZpKs|mObyv*L8##f^*e#FaqtHJ!oI)*PAKk1J7j3F1-fcndBjGy9({#fBtjO7LE zA#V=%KWY5*x=|TU7@7hxFDJ48r}u{rKT?5hYHx-IQM1|qCy?_4#;5;6=$Z!SL(a4R zS19D?i+0}Uila9a2s#z2!UtYHeMzAjUVB8k-_k%2^dfowh~`HN>V>0Pnm#-}%K1@2@IPB!s{d(c zAhW*}#QxrY8-+Ejjo{|6Xtq8m|9TciVJCYdP!1GYMD}NkRwJ=juIKgJ}#wmtYMmW)~i6+1XT)A;Ssv~pb1S|0z?`trFAe_;5M&2aKM z$6pe`U*CPdvEa@Y_%%9};ggUVtp;)oG0MC7`3G-TevG+?Q_RB&)4tpw%LF~u% z<4nST1&i)uz^l37Sk1VOr=b&8HG zzX60_w$+csCjm8N^&>mU`W)Oo5~s%2fFoVZ7w&HPONcY(_@VLR{6hhlQKV6A{YB5k zdH84dGT7Lh`)>+`JpLG2s3GoLu@$D-@%TEIyubc29r1bKPI$Z5h`k@xH!H&2an+dj z)#7j1!%#fdUmFH!y0ZRMpVONYj#tO(fK4N={~jgw>%`JCtO5D$!&!gIAHSsgKRXYt0qb22SUc5M$Hm3q zr)7HZ_AJLQTA#{&MmG~xoaVN-MIzK=iS~l2G^?Z4K;!)o`RIXkMmv^oan17{^*Z0-clJ>u9FM}MV zYW)0(c#ktXEd%FWQ`qx?;Aic+0#wdS21UW#>hlG+I<0`8*$MpriTyj% zpa=&aSpg1{`TkuX``64%_lU=T`74*V=~q=>D987l40qfXpC`j-0?B`PN#|RiKc)#L zaXfyAA^eu+7lyU(Xu-pms`d3Y#t}IDqc*H^;rPoZ{Ie$|0=ctzsVEFDN2%JX9spC<#N@K1=YbpA~P)}P*w(;+w-+yB&svGr8f z$3M@O>Yt(v;P>1F)}PwPFx@!xS!nfB9s3Vb7tJ!oT|) zDLz+y48jq+H6Z^Bw|`V0|1zNjM_*qF23-#`d{F;Q3(N4({nZeZ=hm6W2lD!z(b{{( z&KZ8n(tEKg@lmOLP`ofVLb=|lJ8P%)!3k|UV$*f+gn#>wDSix-LvZ*T4QO0CgpD7K z&rNrR;LEQX;Pk#7YX^cay?$ZXK}QSz8^iHM?Q^njBx+}A!`z1)Uo^koPpVIB|5F>H zH*oyW{7#8gG z!{bovn|`(UFq;vF8x#hz{RdS4XjFR?_R}zd()XJgzG!^ks!cwAyt5SAJFaE(PtT{> z`nWrGS@>1PkJNsu4e5=$x|9o^i#Wb${Fk>p7z?{-KqJpR?E9$yRl{roj?p)l-Or1} zzwEoJ1gE@S0dws*KB<4`>s*eD>#T-b9cQukPaypEe5aatJ}CvB=BKLszO@P3VuN{G z;mm+d?EPqbQ(D7Dyr*><3ifdOO6~KO-|NNo<2x#2Dy2Hn8UJ5cCj1;)u~*a{<)=)$ zp_)Gv9v>8;W`xqU$L6a4m*4NX;^{&0O05WG&=b|`=S{YexdvCTS@m%h1J)9n=3g# zQGLcTTwN@QN`YjTErKfh|D#EU_-15Z<=G6?`1sc0khs7#T$x>}dj8#4b;K3()~m@2kq?GzvFpN3+7i8?HKJ(RUm`)?gnj`c%ULJLd&eyQaB@}n)pfS-q; z;7=yAzX^g|pC7Z^LVO=|7^XbECH%!#0@3flrmi@y^d#KWDQE3;f0J=~hUhupSLvLu z8h-}OZ;3m9OjKU4?Ow%i^8D@cE*!6VJ_ipPfG_vxKvFKRpP~Bw zroJ;Q4EcTQ<3>E|t0z}^{E=LZt~yE3*M-+HZpZe98L z&6FQZUU;F!@?x2P=0x&CQ)ULDv%@dpybi}FJ@tIP6x3S!@{_(Y<2kd(jgsl(@o;J2-MEbd#Y1)gE5*Z+EtSge6s;G(&` zs=qwGd-=s$e1883c(~tX_yfX^P92VlLx+Vaoj3Mm_@VJh;}mziIQ50F%98KTr}$aB z%@Yp|{amfS)O&ag9vZ6&XAf}wj>ZqV<0bnzSrZ}#a($obD{60IF+4;II&N2OAEzuG zjFxdV;Ntc{?EC5dC%un@F(9ReY=1nxzaxFw5DZY$1E!L6$R0Fy$s+TE;(OYajz7UUL-=@(}!3)<^MXX%W>tbWUvnB_@Vd9eK)N@yPL_d zwrnQvFUa?|UO8HUJ6bJ=F?&_xtARrh)=jMxLO=5LPyP2Ejl=PMu%cT2x~(3GO~$Lq z^d~z1ww95oA?^P@8fM4Fm*S`Q*C-s5st(SBMzi*{g#Vy+3`Y8BfKBo$)=vGCxXv-y ze~1Rm)93s^&zHPEHWqhE^>6?7kJ9}KHc6g%0X_=b)p>q|;^T{+H^Pe|!OoHUCv^SA z-73LBVUm8m{1zL3y8k1+$2U}SO|16(nFVGV;v1KBkW|LwYswEr12skai|e7^e6H^+ zKwf`k)=f+Nd3^(%yvF^v1QI_#jnopoK5l@I&o$Zj(fmx&I4$v-_C~nsIEl5Vf?S`x z_1O(?-FPA-cjfv%U0>_61M$z?3PJnNHrAioKmFI?7+Um4Fs;SwQ|SEP3yHuOK>-&R zwP*b)Km8sSfjPYtux~woe|mmWx2BQ!`J@8I#LQv+>G_gdM@C})I|Ymyy_~gE{7mc+ zjiD84@N1Up{9w}e7+k8Q0h$S~8Nbu~@@)NB^flIy)dwaK{5H3>5i`~uf@w+Ieo}p~ zVT+zvd-exe{??wH-?DX*HwM1=BE0e7_@nVv-vz~(w{;1mZNDk-_*lNb!*M|c4r-bN zuCF*hC`f!XZGxtF`Nld(xHXgAPeIT34_V-f_r!<7!;ib!_|f^lHYpHw*OUqKyj9Qt z!^fex@!Ai;Jkg5vr~2=)gm8>K|4Rrp;O8??`~7HiB(~I3K|lB zzcRJz`EviI!N(}<_)!6QKipV5)i;-EMdPwc1wjOn%0*rn4m2Nch~^h zZzl8iC+l;+qpjHX)nRCDb6?>4S)Kncqy7Dv?(QJk?>qqw9#-;paz4kkC!W}6*?Xb$ zEMEWNMDTYt%^Tm3E)>GFRO9bD&P4q)W>DFk>r+%;*!`^>zn3qQ?JuO~$JD?13oZIB zhaoe4`1_Ibvx=Ry#rFB@VfP_{eSa>o|Gk@Z!i#B7gq*3W{mXiqK^VLHn-H;3H9q^# z4#U)+l|lziYxaDK&pL+TxN7qcp-%h6s&@JL4E--g;?Bpvg$CBD@#kg}g>Iey2>VME_27nSpg(OyK;&BW(R9fc*THS!&-f#&d}rpJe~5+wSie@N*d~D&hP|&+naR z_5*9)N`xV&`T3PJe$0FP8-M*uhTOC&d@JPs{f#|Z;=xYqKw-h{8`Z}TwhY3sHl;Ft zrT$r3+fbBl2om-dEMebI`O|kuIIaw-6h>a+_>L#>qgG-#=FO=T8Yoj(f2v>pd=e?$ zFY!w-*3n|^wEm{!>L~nK`?t{cE5ARL+Q(w){I8Qe6texLlz+cX8-PKx)B)laRlUFb z{Cb_5ak%P{I&8Yk{S$hBckAI+Vs7a^c-80ye?Kz6xY=6t3eJ?zufjsckM+yzirTFY z!iQ=11g8H9a{jEn%}$(Te;BeKX0vw57nb#Z_r()Cro9!mh&=xACHPI;=!3D73xpl9 zs`0xucqqCw(1HaK9KV^we<)o29plTFg7IUHKOpvd`J*40)g=+$uTzb`?@x8axWnsV z)}d)^d}w`zSH&jLw4|-_HVm&?zw-TkzD8N%hpj!8MNqg+}<==&)Mf`kc>i;*E>VsC7Rtnl5Z8(0&`eLOE~^qo3&H_;pEhQxM7(Bdf9V+rvB+Zzk%5Dy1J}BjOq^~Yt$9D-TlA&kCgPti<;1GT>(PzN+t&udh_m zT0G~nA9}dIWY1S9>L1jcFbHceSBH`$&hJ!z|1f^mhmISm){U? z3^K_VYFnws*CfAD__eJzyg0vt{eM33|80g(z%wuPz+*HYA8H>CEKI?)RhhJqv6U;;N^KP_~ofo9_Sn+D1>T7q9_h zhVuHX1VNtv`EF}24t%u}u14<_xc@H4|8TQx(cM|Xw^N)-{>?soRLt4uqck?|!P=?* z`lV-QjEa09#D}Z)k6n%hp;@gWVe|>UK4^YLM>7ojJ}(g(4qng3pX#q0cZH$DhEl;R zn6D2SUtf3^fs@`%4GqeiwGW=l5$<|F~KG z!PumhI;_r)WzSC{{@-D7D9%}-Q7yhtJB+|l#hUQb&ztp6AnQlV&`x}GJqvP?<6A-W z@B98evB8#HK|@V7fByRAh03RIg|1(?zDD_TRh#kX+N=gVDdGMPwf~>KD8zx+65;J9 z)%d!5t%f-G`a0-fpwHevmDJysHa8RXw{HiR4SNJt__C{CM;sfQ0ZUgdt7@0)ho+sf z#c#$vl&2M{@u%Z?STtJSTe(GjBl~}<9~9)A5t~N@DOZ2=QHf96C;SJbnC&Fs~7RKkDDT`V@|dSBr&>M>nwdr})U#k?Ow< zONDeRo`0tES28IQ+a#7&>mRQB8HG=}mkIyQkD&Z@V?i`_%PSN9?O#qH`L}`@LvU$b zHJBIA?XSIu{CuH2>HLlPqt#{jp!GR-)JNb(8x63ymBha9GO>R-t?G$GaZ&jWd~y@{xVOc z{nmc<2eoc5fs6h=?E7bw!?IXpn-->WFJYFP(lydt@`W1?jYKE3}<7#nX}HGcB?#~P*s&?2BxDC)1r+EWQW^D>6v(XndP)<@2K zJsis&)Zw}>pFiq<9eU)6>C2x9Q|)+t0M&0yTYBS$b+3dQ%{jg(KZQ39#ujHj38i}6 z|DgD~9XkDB1WNT2KPrTO`*RZrKKd06#PEDce?Q%b zeZMd9zqUmV$H{*baCn32`mav!M&hZV>QMYPnf0gpAF|TMqSjU|*l9MFwF6oIQQqsY zTc1Xduz}-`>Tk;u6ykz7qQ4P+rpw7>@wKa+(&_4dRqIb4{|(#aiCc@F2;Zk?u>X%C z{1&3{#+HRIg|g+`K2m;LzBWkG2R;bx)Or0L#b29gp*ZbMfiTQ}ZPoMT`Gp7mGw}9N z>HPVmL9AUt{Kw#-b8wBObU*p=MV!ABa(!idhNbBDeH+AY2^IeGH@)AhVtO61qSh`5 z@>cDirK}dk89shW^O?RX{i{*xcSL)K{>qb+RpWE`MZl#NcZ8F>xc{mk_-uVR8gI5O zmgyt3{^a1fSe!e(R0xUJt{NZt`5j9a^~Z^m$^@4!D_J|`zj+~2-S5|*!r-=3Sv#%& zOuREp%AfxcramlY;}=ixeJ?*A-|bfivq?NYr1ml5&VSedHDvWc^!)9^-NxefL```5 zjPnD<@BX^$@nTs+(A=xf-jCvUnvqoBKX5L@^jR-(`zz;%YpvA815M@lrsum2i_j9Y zFbOnAtLCq@+qJ}2CdqKSC$De$pZbZ(p19uUu`oVoFMB_V|MC8P@b%#rLa%79uTlP; zaW@dnTD=#xo>uK2_SXtSn-`yi8H+joseN*FFc(vF)8Oo<#Z})gx1W0+T8PKrZiO!k zRL8eVuVjmbrJyvb7R@BWyLz@hE`2x~u- zGJI0|+;iJVTs2VvYbMWP{qu>w`?_+Zbbf|HRzKuK;)8LI$Kclx4R9GZn)RpnRMXZF zvDH$!zD@EM4~n$Ju~A77u!rND?jPP#%Nw)uo(mCAIX);qx~~erO?BQ1Ki>2DdKy3I z%?!tf=ROIa&ZySU@}>HZ+VejP_tP!e`x_Jcqt~*w_~LE~{B-B~tAfO@^&V!6t+xrv zv%#wIu~)bwK8cM{HaAwyZ>8@ai367mQqC$+ou4|kN{L10w`BI2-v4WP)D!3acql}k zR=vKiB@e<{(dB}3*&6nJ3rPL`j)No7$mNglZ-1vfncv{UBQamXPwh4wA2j}7I&T#E z8!4dl;dh3w$AteTyokrlt5SZj%!mCyy&oZ|)o8p@u7GQm%UL_M-zmK&V3eOGbX_=} zwNwAy`}cY*UflpLR_Rwj@+*xWXo(xc65(V%ug^&kOM4|QW&qB~7o*$$3P3KrY{H9+ltUaolKl<94itnZKJ(nd%u>V&mvAB8EKxNyy zs`+uxh@M!_#F z3h}Ew+4s})eMHAmnDy?L0NND{zefpvyPq0`wU_)B{?$(!ll7tBcOo7t(SXjYRmYce zpDY*K>)I%nH&KnRjBM`Z>2h6ZlC4&JZO4AjF`|_Im<&eza$o(6_*e6QI0q2 z%lcD&HSe?^T7JqAR_gxCpUU^IHt7?AS-~HKvS+IC*Ht45H?{jD(1j3IR$NQtt z=&yoL7WZ%R3BTO@H~?>+Di$u=)?njL_0t9c=fvna-pYjbs^35A*kiGQdz|v8p=$he z=-3Mfrah3I?@i;oPXT?ffyNVIQ!^gFQTs8YXMg-U{);eirRw!lFn$=045*OuA6&nu z_BCVc2-L`|6z->R{fYXAGgpnmL)U%^>7E>4sRUmi3P)ph@E>7k8b4o(;%oST2^hUa z%D+|RuPFbC+tbAOd(D(huc^k*kQxWX^&L7Xi|?wgzt^492ai2}Bs?`xJw9I^_+is6 zFN8BUHdf7_96wuHhGTL@o-F>L{@0-ND112Lqo6m~s;WPU{|lqh`Q9g?_WVTFPVv(- zCKgu>_$=fZv}f%{N&K?ol8HFmemz{UT_o`JBlqu~C`?6-5gWi}0k_|@enH&W3kwh5 z7h?Z#{-OG%>&xMI*1SUSd&1*is(eg>CZk%g257&S#M*sH{OVtpCN_E6R2lU`_57#V9S~c*a#woH zRz3gq7IwP}w9G|(mBrUNDt?0_) z7Y6&^U7oUv6e~YNOaA`LFQoP7%z(9|cWQ$~Kez$>!z1l=q;dZ%^l$z6DS)s46jKtu z_ci*re^?ywKfRqy$;rpBCH)^7KtBrhQKxe*9mi@)XGMO%_%)(fiv(?YAn_j%|HFsv z$(4!U(bEeI-;O{Zb*Qo@-8Xzk|MVvqpLVZzCN8u7Ag}idB7U$wJa*EV9E<#eqHEdy zDUcsOHfGMo({0Z1(Kq_>fpsx#9{Ra6H z-fb0ep8OQ0Jr5GU5Ax%J?0okTl~2*izO253`O)G<>&Wkl7pO>`eIL}1wk4R7p2911 zC$FXWe8`W*@6_qQo-%%nXZ(QcqYbOHNMzkTiGBm)%U(BG|IFP|RJ@1ffB&z3y|jVM z2x&yP3-cc^euQ`2NIF(EqVtia;`^xpd{uYZla)bV(ZBv17+>}*b0jldejw*jzqtBC z|NWli?ZIYP;SHOg#2|keI<`B#;}VY}{TY9tzBnvOnfkm;z)CNeehd9)s(KIl$}bW7 zM>GEo>$l~e2kG#k!-WH%`TQxJeTD|_nkJ}y=kG6|7`g89-L-P)e6Y;^o zKjq2JXKVJp0o6P6`ImFujQni%N}`Xd0RMEqOpBz27NMg9Sp0$f>fKR?wCz^fWPOo4 ztt&lf5QE38N<%FEN%b9PJ!Lv2DIV**V)(-T0WY&2w1uqy%6+S`_dM=zQWajblE8TIGsx&TaGQTSj?o$O7Lm|Hxzkb-HzJ~OjRf|%8 z^6lTKUbeoh<5OhUljUbEXG!~CtJbb1b3>k@1YHgB`=I{WdD1#!8d#6~l-c|&oIks) zVon|(eu;jmwGr=!__dy4PExPGl+8csvGD`;o1eIW_=J2!|N3M6!TMCoYCD48HKOWX zpSb#r-V}RMru7*eIm_}(xW4%K7%ieY?+!|-Ix7A?)Yq2X&>_n-OV9-8RPj3WPeZ%t zlaPW6l=_Rscc`B8Oqig`1B2`lEQreVQ4lFIXIzB|J=3HBjI`F==mppeYGrf4e_5*gHHG4 z*H_nM=hHT8Q;U?xGycN)6$jb+-p`k6k>`EJ-(=9=ml0?}F0ZLWDp@SQhV|J-1Y#HrLzRCJ4J9TIECycLk1C(fK z?`W)hh|kYK!QH4*SPWME5rqEFe?oqmPUuek{)@$TqO!%`hy0vh-Gi?C9*37S7|8FJ z_D^>#I7IU~QuJpC<0sUg+%#8{m->&<-$E82(?NcoJy*6rl54f3zcm7!Uvlu>I)dlb zp|I)9e`+?-s!^;}YaLw>akw<3Lqze4}cUxfQFbQl^# z7gh8ST;pYVw75TuRKK$_&?0dcZ=o4$n16Ht`cj?qG7>ZRL6h@u%DR5d72etr?`9}U>Bjtux)gTf{)7VRI_7sJUq zVy#yz(I25c?xAK)zJ8YF-}3V%lR))H^E8Y+FJ%?9^sQuv~LiTB9U&&y7VP?1%`D%F+sm@^ddjb3p-&{@< z>hGh2`E33l>O-5q>5=oJOVQR+Wk$5Y$rEX{Y5%KPelLX1@iOI7fRIocqG=SWc~}*uglJMqhmKmHFMEB>%zr`ArG~tC&lk*p~#cPT3ttxcemc>8F zzY>4h{vQEPB>nNH0DoQcO~~&XPf(u&i@5xpJKB<17}leI`x`=jj(=xEhK_%U@LR?| z1(1J_K4VW-b$^Fm7k&`OAM#HJX_0RkH<169BjWGF{9JjQF1hpczN9}G=2!0NdSu)B z;wJsCWsgyG>$4+x$>wv2)!)+mUDI$K*>vEsq<_o=_}}#Lrevqr6SUrx*)R03k4?-- z<(X=f@qyK6aQ-miq&W$Z<!Z7zJ5RvjNbrDOX7a34sAEi>(3+g(2ejoU8mfEbGC^QV7A^K-8(0{XTwianV;yRkzkKqgV2Pu>FCu(oIhnD_G z7vB$q{WT6WHz2cBiqTMQmOsPz8l1469MP(l^w-1uEcowwvgcGaa<^V4J|Ftu>@0KQ zXI+E-olgYEzpj}DS%0<$sZ3|{XA!`DW?>6r*jR(wcCr(n5B<|=+f5`z^9|ad%KR^! zA3p2jNEYh8MgPu6fc^VV)_W40gL&5ucGiNFlvg8siskoSAip=iXhCRoH6p2uA22`YYimhr z!fKF1Fw6fHp}v`5Lq?K1ly8N^_lp4WeYBP{fc++3NujmZ1_?NTAHNeCW%C!O#tQQ)jk)+=`I}E&*31$d3i$D>yp1-w-6tPy zN|MKaz>m4I{?WTr?l$Saf8dp*^Xdoau4=OQ{cwNz>nlvic&Cac=WoBs*0-K-UM-oQ zh4wq7z>;h?szwIuSp5R=$;h)JZ`pRM}x@t5xZf2zN%|M74gT0U72ubTjTW@v68 zrulWK_<_239qOZRzB-c!9&eE9GL~PZgZ>Yl#LZ-*awAe`@lSt|u7B(}Z=0&YzlGk0xsMU2ylVpILqb=I3K>DbwD%yYQH4tbTy~6=q#h>9yY~Lh4b*54b+2 zhe9S@7&%6m8q4R$jJWHxDqRq2CogCIA4%uG$0TYKOYLij{O0qcov$9bH~bDNpThSa z==mxV=wFPCue1JRsGkhWH6hpa9-_A0S^q4|f6k0HB|T<7M6L_?{ozLw&B>enkI;`= z9dUeNd>{JLf*Ad-LKzoYiPx*Kw7>1>QET!#r5cU-!1Nm!|FNeH8R%Gp6lc#A?}z)7 zw^+V`Y?|{FdH!}4ufzSx)H^wlu*P~c@$5+PI?NwRTs?^=`XI@FPXYV?{An|pl>HIC zoWkB8_K$pBno8TYR*}R9i2vs{nKXRiXkn_r$3J}14O)2%3;Fx__(!Z;OiWK+MYHxE z6W`wp_=nUuJu>l5p(Osp_%SA_cy+ar?VtJtt?oaAJHF0Yw!~fL zpDlFQ`b4OItjqNz3VYt60fEeaLjCQhmmg_J_>DR$bQhlw<9GLoeW{~QH17Aq5V8DH zs!t5=l1A-a1`3L@J{}fdrTT8!%uK4-ca-o=whsWiE{(tH!8hoWT}Y@;=Z~-MiU+jc z%Y{O2n~C!KrTW>isj~fjZr^G$KJN{at?&MG9|gWSD1INbue*QOkvA*L(41UmUr@h4 zm1Roib}Ea&!6>)OjuA7Y6)#w!o5@cdL}dcUT{{Rk9)mWtC|9v1#(>OV{@Xm06LCyC0!H zoB8o0YK1k4Qmm5X=a65%6J5#5JulE|y$Ry;;rdU%G45nR&?}_!m^~lzuXINmy;eLx znD>d#pUc*nbZftnLUs>6e->|AOitBPssBaIBn{|kbM%Ooe*v<1#_Druf9<;(liIEi zn%sY2n9RRA^e#o3$$WmiUuH(qCzqk zqDlO2m_MLhde0a1{U>nk`|d0~f)s9`-a!mMsIPoBF(%t@+>_u3?R&DF88JFjf}-}Y z_z3O0_xtr^)37oWIBSXAKBV~(-fBTMrk6|VFUap7RTku9tB0t_WQzQLseK){&7l=sk&_aZ+#oSetBoD9+~2u zk9I9${DAg7#$gTVKl4tL`PG{{>&eNbCFpbJ9uYs-AFx1nzVsP`5;QfO=_9Z{QtM(( z%*-B2@^jc9aCfyesXhJ>DMqP?&xiT*;v3fFNB0V(wvg!`Fn_K#vLWI7E6~hk%s%1y z$2%i7kY41Gq`vY3`TMRDOX%Cp1gkfk7Jnb&+w;GTWcTw*)a!5u@j8rO?`8ejvnSP} zLrMJk#oeRaNTSIzG~v%K@qVbUsEzd^PgUO{-2-g@6bBIB?#A?`8U7L2zCfN|fc0%h zZ}+Fi6C<(CD8^sdUodS>I(`1NuMpgU&p%85v$VsqVM2K_pMTG43ux;6|Af%L{QRT- z_yg*1F-MrJ$>(Qug+7@cn~$#LGJOa7r`3yO=kH_}qO4{7{QkPzdg2!LK(;>>iyx3* zCl;9#eZykZ_6?t(RmB$M#hnsK{}b$Qn|{-h9L+98f!+)sSRd}YVnuLj8Tz+>p##wG zv=-Qq9lah(;y>))-f|$0zP9Ql5uF=u<>i{Sf09T;F_E+l^G@Jw+#OvG0TW`0CeQ#Q5ABl>LXDuMPF_1wMVL zt3fz!ag_0o0RG+V*`E%&7lHTQ3`H#emG%dIy!C*7{WVJn?#SmyZ)-jBD)WkD{W9c7 z(vj7q*{++C{w5f|DrNdz{(uLlYrB8*2h#qy`$H^AhDWgk{~N&m%eGsR+jokatp5hs zSd%4tOHuhy=Yv6NOMeZzHD(J_}Ze@eTUV?O%0CRyA#MeM$MQH6;I20doD$ z`imgG`Wr3C&)N5prUxJ2@L(&_h>9iq^T7GBYsajKfldjsq-=b2K>nv1Z$rk8DMkOz zkB0ldZJ4ojeF*NcRIe}N|Ut&rP)CrN(a|C4P0tK*@#aNB9| z{o(qI{iplUm-E8#U>An30?2>Ta}CMVXIGHZd#2Ao`!rc)LKOboY;yk)joFsOVZ%LS z(~9Z$aDJt$vK46P#E0yd?U)0$9HltKOSFRS3rKR^1Wb5AJ_-x?3Mw zSRRaLsT#BEVE!d2q7U7y6@pblYPkKUWiEZGR^L!Oza{fekRLhb{pk76p?HSC=f~jD z>xj$fn@!diYELamzjZ|@a3#ZE2h6W6*=IwBHQYzWU0MAL&rct(w~<&_mmsaHe0-WK zJCM7d%21uByZHTZe}$j54rEwHIWoOFOuP>Hp*GHmggmG~TVlJ4*P(vw741aUjIBgd zf4vj!3;NG1NruF5&Shlc!ncoOOWa8I-$%0git)P$;6G-r4{;v+0xb>SDgJ&osBdHE z1duyRKBA%z=f&TL>rW$|^`-U}A$X-Z!%qRMFD~#IKs#R9iN}VoL@Yi_^{LGX1E@>+ zPTXZ^x%m5#Uwf7;r)R=)an#97b{+65_Kz-|^(zm1bgz?Nm+DtzUDgqgM%nzXe1BM| z-)X2=l3hdZNcMMu{^4#1E7|znK}Q5Oe(At}dj@SJQ`;4ze!ZE#3ibKHNp_@9>k>o^ zjKueY`Qyn7NAlrCIcndV>8lzbzAt>@NQS>HN7<=w#PNsqshXcFc{BGB`e?2!J|E_9 zK9|nXiXVf8)_wT?;hIq~E!jImXxKbnULQ*JJ1=8H@@p?aA(iRk^P&HpvB`t9Usi>F zF68?cy=8u+K>Zb3c1d2pg7{_MZU^b^`WgkbVfP0D{(U$WNWy!3LaPhe`kHDijW4?k z`cm%+!C2LR^;atZezY0hk9G_S#z|ZG{JeI40F5gR#S!EBiQ|jG`Fmk>06qRF6yNQ@ z`00hD^>wQX6}sbM7@oV)2r>Os%J1y~>qtQGb#%HL>mP^w^RhN4$GhD^wxjs^hn}Vt z>2~NgYCe?l?*`zX&-o2RxG2+CT&9coV31$#FLWZiMwd(c3)H7x<9PpT|^%c@-?bfctlEwl^e6vo4`#d-?p)9qL1FuYZQL zhP0RezI1-^@DN|JTH`r7y){g{4)@;(8yG@r;y;d#q)Us}U%xOj>`Qj@ZViZj?lEuJ%lCaH_82jR6ok?pG}Le4-!fn z`S=$)>63Y1FErWT-unG^qIcv83jAXrejnuT!J)pyS*Bl%p3Lx%1OA~~*iJH|)i<>D zE$e^5z`r~?7)B<4{f_opv-we|uQu97kbA>q=cnW`eZ>n&{Y&BM74*V@92}g&>a!p?Wtt-iwVI0d~qUaOlu?a>4W9(FU8k+s6O@jor9yt zY!>;AvDE)HBqUISnASq)ZfAYsW&6n98SU|};CABuF#bLN-jB}x9Dp^?v+;%fF-sKs(A*Fug;^`yx#MrKBby#c8Yo0R;qz-qNHHD# zWr~m&HBNrNG`~5XqDwTEouU#4F}|MRWJohbeN-}xC9 zU*P=5!S`E9ic1Ab&g~~YALgHGqrFMA(PQ*DiRHhLpMEy|>0ILgtY*dVhy8npWbx@; zQULCob4GkVtS>C~4WRpN199<{o?`w6_kSEzd6a5fbrU)oI?C~v#xLdHvi$f_f1zzY z)1P7fa;i~wKD5w;_#U6RCS*x%*X!kT>4%12|@@bx`k{T)PCMK-^3kMSSc_vQ~FBq-qxQW9AH z3GsD*7Dfi;eng5Ue0;;k8B$%{bGYN9EnNG36%$6k3m>sV#a8h;%ugPMBvStgEd`T{ ze0-~A=YM-oRT3Nr@%jI4Pd44zw!fsmwi=x8@k#9t-MVqCa3oDv{`*pXCDmDysSQ_} z%x_-zb|A&=ZXxp?tiJ{JCpC<7Cyib2Be#vre?oq(GL_A*{&|EZ&R8SzLjm*;pATL^ z>ZfI(qa7IjUci5!^)e-Er(Kft??C*MZ-$ZYG4D~Y^NfG6zV0_Hob;OV0o8Qn``^jh z(X#%IA82AN({CU?zryyBHy2xDs>AwAF?fHE^@dbUISU8gVE8M5_}jZSj4rKvkL?C9 z{|=w;(Bl|woX}P1*Mg7l(uH?u^tdrXUH~7zNLl|_{KG2}eH+Gy2h^Ty=v9DRT-p3L z^bgiAJ&5PSd#L0rvkwQLFMWykBFclxQQYkRp3wemiDzJfGAQ$ho1^i4n9_9DX<<|iISOKHU26WBKTp?E*s zpRvBbF1a-Cw8Xz)z^{;{W+ZiO9;zxoB;FqZ_D^_U6iPHzU!knRfAcre`c}2)PBJ3l z6>`qmEPsD#f5H%lD015I3knZq{nyaH47z%ZZirG8@HIaEiPbrDQG8$FkOyD?>79Lt zei<-YaLwcMWA?xj+R=NwV5r2;pI$a|Bx(x^(7*G6;r!E(gKos4=N+`yfW-%xKRim? zN>cxOfa*r?5WoNb;cMVaZhovly*jb{-wW`=q_-Ml#*!pI|M<0Ivs~2^QURcHYP(1Ycobdg1lWK6jxA*Rp(0uTw6BOS zJYUpyg)gzze26lWS$s?e_#SzvMkkF9#1>2B_$o;2%TuT4)7LXn@Qpuia{H0y_h054 zk|nQBOZIQ@Lel)+z);qIq?qmf2Qx-Lw~huCe)hn`D5>KoKF4GSvard#LbT<&pA(T?dmO=UxNJU9GDQ4Dv_o_w(r{%|lqBvpXAK1u1{jx9ZWojwf+J z`?K=v()>sL>3Z_8;{}wTnj&6@`Tx8EYuWz#mzwNf>LSwz)wQl8-;oS|s2^V37fUog zeMYW?=|@oC@;?(!R~~tZe_8YKkFDK9R}E8W(tlL=9H&ZmI|;9w@$p~2?L4h>>(wOw zr}FO7vX{e!=>zn*`Qe#pPvUj*77Cie@&o7})aO>noxDzoXcTEZBVyeKcbF zMm5Nvwzl*qbY=ybrMW;He=j7>FP2t@kw?E9P^0!>IX=?(Yk9seZPjNhez2AC1I7=R zFGJ~(xIk=N7mh@IAIwjCe^^Ef6_4VH^(=lteXMkqIXUn%2PM=ne!%#m*kD6e?8!s3 zV_5wGX6 z*)G*#G%+RsFR$VAN3p#-h;3u~)DZc70*UQ$2oAOg`nJ>`g3rwGM0P*LwY7AMN`VOfVXo&9z^{K;V z{itGxE!gV>vmdDcrluy*4t;;)?i2a^&|GqY`v2}A#KrUZVcO#YOyVa8%u(^SL?PK*R^j|OZ zyh!oZ+bFP$F2fJ_rcXf~e15EY=1JCfzK&+*Fnpo?-`e6u z);BAZ;OhnOZRqJuzWgpk<=z3}_`v*StFAZMV{%)9Kg1t4i8w*STDBJyt@-v}J@5iG z`O{6(zX0=36|;ME_R6@N;>)Kn$#EaRd0IljwKQKfZkuOPsu3qvr();`qVue>?RgeQeN9P#fYb z|30Zc|F!0xYztI1A$W$qcpdh4-s|Q=9*w(&PVD0AORKsClV;7zk(CM?e+{5dUp*T_ zdhV-0VMg-$N0FM+JNB02BgKDhYh8MM#3B5=E5i>1ef*%N5v^}_82`v+ z`iBCjA8%eVrWQKKamOS+zBU)#>4Cch4}HhScX;+*YH9VQNqmpBx=(j$4i-B1=G#Zh ze&!^*?o^ZOEAM!1ASze0nyf#TtGSX^8}d+}dRCu8{r*T^JXxJKP)H-6Ijbv(hF zG;YjCa~&Bzu>Wv!Z7_Lpyaavv!t4{yuPA(vB2)i7MMj9tA1MI)R3EmRd~EgtZ8^jI z3q1dPP5la*ckTeTjI3n%0{k|#^Ptq}5pRv^Lcva!XQa(Q4CzaAK1BVEa$HvN^FXeZ>su?+X_qb&LOAVketIn|{ zF_SYT`V@@c->10{d9f`@|KweM$A_ywZM@Xgc5|J7%9yKlybn zh`jo74;{ZBE#4mi{Oj`b(d2;AQ=}cj`pXnR{2Z(iPiD1!iAL^b@y82E*Y_#sC6KW$ zuTe&>+&=^Vn{LvA4lG`POOLVqLjm~T{*%n<+prUO`dfxC%)chD^q>ox<>9g4*mW-? zt*>y*K6*3s6Kp~Yr${|KYnS^`*dWhL4uksAAi>+rPLvBu;Ay<$A6%n zEg6@Xfl`Z^{sZ&#JY^U1WAb^4J`3%$tF<>-{q`yf2x0bD4fI*>y;sQhn(o;6T&5g< zX@0R`M1Sg0ogq7DfbUj|1~zklAf+RflUqk<@PBZpZP01XstyqZhec-pP0w{sAA&>9Q=#V zpRc_h(3*Dxh2(HPKZewV(cWcLb>d!JIi8R21g900#O=fF7FMwFL(=|h3lCFLJpTyN#B6^R zi0`f$!K8lBT{Nx_`+ev?EDT~u<*;frXB@*91OMS$x|CjHKpzh% zz#S&b$49nT$G<<5`w!@_to}k)4Ilrzaiz3>!9alwa4>`TUr5 z$&_q~PDAFcn13OFADuj6$)Dzr(XVDqzl8Z?UCnONs9KE<`!oNM4ESMW8$j)Ru4C;% z^7jY$_8EMdc0Sr%$mqbgfBfSD^*qyFDE-XuFEgH4O!d>RDZDlMe`zTvKRnPKYSRdpaOdwxZ*P>AmnZDx%?0@a~ z1X8fA7Il2j&i{k`uZlsr6y>)QT08Ld#|GD8TA|lhaOlOySM%vc@}SxACh^-No4*)p zaT@I?W%)JK-3s#0(_`fMiL^dVO|d8CrN>apan>IL{ZD5nXHsE) z3aJS!zk~c;e#?vKsGdjv&WD5XX^?gRNxXJN(*FhHQ(Gm0YHNnzuix{;@lgQv{i9EF zX}{}XxaHG-`MEUy7a!22j?VG8#ZLKk5TBNx(WMSv@z_0{&tG4`hW;6K7+Wmj^UF4B zGwplrEN*SU=U1n@0kqcODjuiF=T~G|GA+E+fTxdQ>k|~f`V8G|=H#4C3euj)`j0W- zS5dG1bobQf`1LCO{mK(FWc$$ztsOdX{JY8dBow($N2oI9H~ba z?~cPCGx_{cOSPf*x~JolR($@{=4_^==9$=I;lKBj>JwTjf%M3PD_GTm&z~bhqo~mD zL6iQ;=c_sS-t`btv1j~I0Q_l|V@Ddd$?CTz_CIJejU)5El%rDZZu0Sw`oG5=O6cdb zp2DGKeE;%t_e-kRX{g}&j9>p$&F~>vG+UzYLVj4^3m~_u2)dNW;v3WlvNdPX0|$ff zq|Piqh5EyaU>#~&6@}m3@M7-|>J#I4%c%FGXzUO;MAN3Q4NpZY3*F78F~&W?QiD~zJ( zCi{EXUz;DF)_ClvH}*WkOD^#JLs1_)@@{iFdKt&>fBV(bg}jZB>67yP&CNCY8@Ju9f{XH=ksILH(mNYDF!cF!N>oGu0BnSj>Q#6 z`1s>lwzP763ZA%yZ~u!9Y@sHnPvfzE|K3k(|9u7q($kTb@R0s|{Ab2QQNO~w*xHzn zfAjtO>E9Di@wQAp{{F3UX&3*NLizr+B7c)Xd{tUuN5;=hlkfx1AH^QrO>$)WXMZ}$ z<`1BMUOz3Du8L?OxF2KBuLjR2W6J3LEj@(Q!}#&VyOR$&F#jwXKAYvoP``5j6GR>* z6Eq{A^|!$MH~#EAdTVtswy9$HVNm}SW-p{eJVSA;X&SeFnLbd5&iWRC8x|ZE{Rf<% zJg%xsHy1=h&UbS5=kude@2%7$_!M56&c}bURUq|Smxpg^$)6AE z)6UPL=oFtjI4_isf0f1oIxo5wW2b-X52W)OE$Z!vn@Vbv`&-?(?M#ju9+8}{4(rQh z8op%AxU=YfJC@(V^~t}>0?C2#7tz=Ke0{f-ratwhQ8;x58y~noNYOV#T6Z`G`{ZfL z{kJqe7av?rZ70X!z&4EEu>YniVvS6ni^F@y`Lp@~OY4X5(_3lCn3MSTL;m;`cnL`j( zn(}Xar2f-*?Ls>6elS*VlPcN|++U&SmM(33C9+9hW>w*hc9W~ zBNN5zF@8b+e@!)rRJF}To-g?Py74KHo>+PTuh_-M&wgGs-Tw3@u1MtDkNe>R)b7M% zOb+wyCw1Q$I;!OtJm!F_eEg;Q+2|#?wBd(>kT8Y$Kj>diI+f5q^Ob~5dp^Ep4rNq7 zrJK=ZM)n{H{{~I3{eHvvOiEUmn{|D!9v|LwG%PrA3YXj4- z;Q9;IQ!A;)p=i9^`#-Mzg~b`su5)6rLrd0w4(H!`e)1)w-e;hpZy0{if3N)RPmtO< zG_V(2KMCuWpt#clCbR$fBcsw*^^d^2b%PsE*o9QkUpsrenb1(x$T5(f74f}>+AF4_`>+) zZoGi*+!}zpE@k>S+`qP2s4lH52*(j0_92$PO83WW-BzEzE{wo!-TCIEFRA^;pDCl4HM(e#f0!TjZtX(S)DEGfde&bF=WjPG z_90e}PN1r*|E^2>TfT1+=$jO89KVXyxBsudXzK!+Y~_z1OqcTm?2i*4t4GPKaGcVT zkN?^&j&eBvw?;v z?890&`S>@B4?#KRzp5q*hOV;`WYw|Niz$8C_b@ zMYw!~&!3G;9mp4leG+{b`tR{~ok>TZ15NG^e*CO2aT#|~l7B^j`sjl5d@5M_;m7%G zehluvFnP)XYVpDk&!5HY3;Lfo-}Gqj0b#hm8lOLJ;Eu~Ed@YOr3Lw7^ zuFRx$?r(9z7CwGG+U8RH{VP89U^UnOcgr&+iVe{yf3c7Fe%-Vr&iDx14HoZ8SM9A|JmJf`c&se zXp{J8svFReHal^tG3&2}^Dh^AZKrb|r{T!=|9)TUU*}#5qLWR|;+Bv2_Ek|AO~VIY zZPLEfqYhHlm@+(mB;USDZ~Bo#n~qD)9|{EcKF~T#m5W~EJ1_Y7m6TqjrLDi=fBVzJ z{Ayfz34M0CLzDgC)>W3IMNKSHn8)%@=)a?f+mS~-6H%-COn-#_+qGmnneZwV6(=$M z0P?ru(gJFb;)Au<{u^H@z7a?D=xiCjf0O0o3+hMrEBdsyGz9C;o5c0MBR=ZW9iKz+ z`>Z)!|9x87fIjFLivP4>_$Pz@=VSd0s8!cc{7ZM0ct5nyY28=Syj45#_*JaG8m@n` zczTeU|0uy~u6%sEUaGy+X=FE~wl+$v58(Xm)$p@4=Iu*7uRF^h;rSq0sTZlb<7Yf| zH{ZWrj|9P=s0nKpmZqh$a zx~os;?F`0_7mUR5!(e@DV!1vwjS9w%W(*%M(BE>Vg8_}r3~n+%Gcq!u8P9{UQ4*`~ z;QZy(frd2MG6Z)X%=!}{zSB+{QlI<~e8%%M8y}D#6nm_sj~9eu#c5l(`lse{bGqqg z6!yQjNW34eUuvCOdui%}uE?_?Qp7hI=*x{B>&b;KQ7AW^`R8;{pIDzUCq`Q%QK6fj z_Nfv(}>N~xj=+krkg7B!Wy_kJ~`5A+k`t-x#AndHk$2Uc0e+4KA``qU9qqhv- zTed-%l&)ptkEQzaPJaVx92kTzcV+eq^^GTq2DE!@5dN0MkI$#uSf7{lDnA#3M!C+`mZclR;Jn^yT6} zoEIbKAJ7MW^HM5 zd~rtu>L2fq>*nys$IZfk+T8cY(X*i3o@OX=$p9QZhm8-^ zPx_3tr_b)i;Kg(J<6|5WOn+q`$La0l_6hLmIyIIqbIiqi7qayOaQ~MPH?rxrb`5yq z#YgD>>U(&;wZ+|Rx>u z*OTyPVJLPg!yo3)+iseZ$$P`m)dpSh{k%YZ=se1t7_yKqi!&Kc?#;`8%%b9a)`CIP*i)sBr1Sf7brc#{R;`%#JoyC3GSEwXgzY&~zB zHYAPR58`j@>no@S^2JW^#o~1g{A>73eOg}Nhfi#2#3?>kmh;&DnhGHQ z8`-d(r0ORjMZ)w=I6v~FGMLuxID&B>{`k$NRjV<7mQpB&l2y4`p2_QZX|ksELyuu?jM2u zD|~V%KCZhZ`)BEZ`SA~Q?GJIiu*P+yq-cIzztJh9u_+cr2Yu#7U z&VPMz_)3O9%uhmpIgugfBhjzR{p9#b`~QlpJcw7fSaj_u%l{!h^JV8FRT?KWX`gBH zLuj+GG~7X(kI&}eyXlsQ@dxoasz{HfntI`MU;g|=?;P3rL;ZK5 zB6WrztZ!&eY_Ok8v`%W$gCPX<}V*# zJ6V4wUZ5ZpKjh8ao0d`IQ2|H@Af?`BM;rZWOK($4>*` z_n@mSNxUC|zWMY0?56&NcjMz@LT#QANjeDf&La6!CL%3us z-@bMy?xtCV8Tec^fBfD0rP91VSMZIS{PCZukxjR6e25*M^X=={vs`+#`4imPg^fSV zPYd6c(l^z=vEf<%_&Z-VCz&b%D6}8TKjHXh1zV7c_yD9dg5|H!KPH%2kq_qrk&!Rk z9}U(Qn@p`q|K&l*Xbsyxt0mB%OJwKMbnh4}u}?2he?1uKOiq`Fqk3m%Ul{0r233ya zVCGJA+{RnPAL3(|B3oZ-9F9y>2gvP9>R)I4bs-ut;b_=vmj6Qk+F#j&1l#SB@B`*Y z5r(PMaPZ|O?I&Y=HZ4>t!&i?m{E|U_klvU}2c$j1kC!t1V0=qgEu*PMKXF42A3tLg zOEUSsKk697-d_>eN9=b?(q>Em@|n!nADU0KBK9i+kY_7CejnD!&KGPIh&q}ear_`Y zXKO=fNZ*4vCX&zpV}-lv{O+gmgLi!XXP$H>--Mm$Vps|ZpgDC{niAaL)ydS*QM*9 zQ-?Z`1(CrhSDX1K7+)q_)1}(4o$-XRtUmJs^_gP7I2yI>Bp%jZzCHq+FR-X4m5xm& z_~xPQ^6!`C=W8=9Nljlrq%w`Ye=@M&O;cp&16%o_3Evq$aD3Kuu_fW%{854{`@UpQ z-%TB0OXl|TN9Ru%iQf;X(nnf^bZ`E784*iGbSQoOa zMX2O_3^;x^rfwv3@lIsu&{{tJ()pz&vqI_T#(ntpIX?e$#>G*$l;ik*SN`}a-bke< zO=SIXQ~2X+8z4Ks;=+Age2V!G$Y14Cx%7uu89wF3^jYXXG%GDg>qShM{t2*78}HalV!=Z{{ieU)`S`4D>qO>h21)dB6HuS5-MfnZn(cOO!^v3uj)rmdC=U0RHt7x%_G{5GLJnw6W*I|A0 zBHf96Qw&5E+nb5k;r^Is2D^|6F9VU^3LEh{v~MBXRTkfZ(Dr-Ge?a^EK0=@NJzqwrJc3RBR}-#f0o#>V`-UrcXfsc2U`a z3_ZOSt$j9C96yL}@C+-mwW}9uwvmk=wEy=`4kRN&Jp)fXZR`r|Fqa)4IRn(QH z=HuVn_!I4OptaC`tFoMb()^>~tTDmOoKb=g)Bhkp7Rb)`-T!wp^0_vR%a62VOVan* z7Rmf3%>Vbab0p`q{Lr2nw*DO2|Ke|sB&Wy^WoRmh&#wmfuQPKc&2#-xU~#E@{H6SP zzQL8OqW(?JuPC1MB<4ec(A!K$@%b3=r^}BxdZsEB$F1b!m-0J}YRk?qxIT`LpKoC{ z^|@StSC8c5_s2Gu`dzq7&s8 zH6~h+uXgSzD}?Vq9A{gQ`t9y$Z#eVM1mxG1nvP^@oe%mwi0Ln|KlF}leWikmA5xlc zCE}+D@at3POqwtAL)q`|Gk$>n0^cAPqI%vB&FRGa3*^`L8W-~4D?ds70Qu=>6;FS7 zr{LG=e14z->9nQm*(Ui>)FOvYD!7g_7V`Pg?PD3eruza<*5uQ6m7NzVc|)baUqTeko6%CAo7?Hs00 z!u(DnLROzVbCu{TkRM?>He~2a4|L_g4)OgOK>k%CJOB6cz^%w#S-yTA;P*3UBdJT< ziaN)Q5byT_{&{|$9nrbA4VgH77V%dA=dVmz?@2veE+UA zp`7k${TxT@@%iDtrjh#vkaz^`fS$zTH zM`esP*=**Dd~dV<$oGIhhO+&oWA3{lorAet``_(rPrUDKLFtdah}WV0|NY@gX1MsE ziT?e?_lNb}?Ta$}f9%Jxm-zPYy(gWvJAWEiujk{xcR~*BqkRQy4rKVl{M}^9Mf&m3 zb(~z!;sdnb8ljx_*Qmq2#_{pjfAooV%2E&}&*tOr7NkehTug9|9UuQc6?*jVEfYN8 z93TJPRwm@xeQQa60QC`SXhHPHIiNfF41Z{!D@I!r4^5{g>-&qZpv-3sU)X;iang>o9PEMW+sgHK+(r`Ll)@c}v({GRAI0(y1yFwsKI}-WEw-ZW zuYPm+(J9r9{4n-L&GHt#mr&m2^hOXE<*Vzdz~DEhsU_0m%ADM8X!NI5MWORJ$FTQ zEtvho_%O)Li6kj)MmM+iV*U;E_Z)C>CPP)WAipiFzYgNRenpXF&e%cg&8=p5}z^9F*_B1@N!!;Xtx7ozai8?E9*L z{a1O(_Q#*^jy`W<`6a|}ew-`W>$e#_TFmrg1qG?T?>;wy&g&@a?|;w7cPKtgmzx}G z65o9L9P0Bv7jJpQ?=MW*W=tmOnxT6AfBm~s{bhr!KOtng75Xt^qKFT)56{UfsO@%r zTp4v&ybj~Xi@$o*bLGk={r_b_pH}W!iJPD1c4*j@vi5tIr&e}*Sf7v06$427)(7r#~ zY$B5vIicw%zsvoDR6iV(?nsiNoKYtqzP>$hrW>hW?txmrl;aQLgWB44?|&WyN| zT8Fex@bx1lXEWk9(G>aY=6`>zh7B3j+ZuVMvHmlt&(&UhTEm==8e za?=jeeE)PTT;=2U>qrjm=#$+fehQyA5~WIO)H3b8I6egU*KTL+NT(zlq_Q)Ry&uT0 zCogj(Yi8M@hIKdP_e=Gc3M*%_+}HsBR1~m+3`Y*JfTVG}K3xzU%nOKYOmkjJL`=~AX8Dc5n56mwXU$!L$2P{$SQv>mS z=s)Hw>eI4-WjJOaA78Wmvi|lS%bUb^=2_YPCnJ{QGbbOg@dNvV4!oH_2UYFHtq1V& zJ$W~WD!OE0qawcjE!?+}q+GK=FDwJZ=R^MX>|jqWYFMH2m#f9=1jN6`NA1bPdsb-m z@RRUWfI?b(#LKwewnZLXY`p9S}b1Sq|tmC~VuH-I^md4M)MCE_3@~U(FFU=2w(5F6h|DM*u{B)6g3@ZwQS&e-~ z`U}T5J&r~~qILkSeEL^dUtIri9PwFccJvk5zl-fZQK0p2RO|{v$J$WSF)Tmtiq`LY zXAj8UZAT9}F?=|L&ows>h<|5CpYC**#An?!A8^0qMCZn`{)yX2e;5QDg0riO=+rA+ zh39k8{*lYwRQHoFoy>jv^q&5gpU3&h7VE9~;fkhN$)4(-XZ&Rw@IPZi_4HW&Qi1sWYNIbKD6^wRy#j>q%~KlalSM&`JOO8JpV&;tob;fah%RiX?~>STk{*U$8ooV zr1>$b+b88Q@2Wcg|JXw}fLT_wqGPPEzWDqU8s!CBkIkfp!AyQ|eQSM3AIO+Gn_lTQ zO?X~`?B|bl{t%vPOQRo|3FBCPUa0PuTJqeM8q8}VjAQ*Cp%Dzn?>f-JZmd7W7|GXy z@DS)}s`7uXrc>7c-%*smS}-#d4mWca*>9Y`^sv|mz~K*WsUI{zW(>eoaYMZ{Nw67$)LT{ zkB+zhSCSvYNo)Q^UL(%+M4+($Pl3+Ye$wBX-@M6^yRlW8Kj*(#^O1IAxV{Q${>Ac#o#1fj1nL;T{6nliXQ=M&8#rhR9p5rWz!%GxMUF3gyfc%U z&eRgdv3*!N!5^$+W>e1}Glg+{|6^RoAV}_LE9#HSMf&MbvtWq*V@r>G>m@voo97^n-<)9|l+RAyA^Ia0O5*php)D+Y zY9X?Z9P&Su*X?0Lyd`~8I79e9EdOJsdV&Twh2|D&2;&&PgJ=EWyL=`MoIgt#*G2aG z;qE{<_j?w7kxYc~N`zmlbAfP4Z#Fem^|-PA1F?KBc^(LDOlDK#e$2k${K(qUFj!Jx zC#qjy`;yUOKlr6>rr)0G3*VO^{hqDAo^SkkA-80YG=7$kkMYUAJGfTQ7pR{X_cxp? zjRBd9Bh?#nT~dC>4Qa`15e?3@QK0&H@&3`=*(&*5Pq{gZq~-U-A8Y=C3CETBNaOFD z<-nIrwdAIou=)=^|6#*rFJ61m6mHtkBf|G_{(Hom8s*YW736~L0!jW{DRzW&MWbo) z7M7pD`JE?io#D(EOFG#%RCvDu;@5;7?y#i$1p3QUrXCl^M~hv2;i>&pniXm#jN|@; zKCgTs`p(ok^P>wN2f&TR)9Kjua^ZOyx}UIHS{T@sSl5}~ezmUz%)W1=pR^f2bS=dF zM^2ApU`>jh2ww%tuR0u3<)0$uT>mm@{OaAY=3|!1xzUrQ@r#;m%kOzgxZ!^kZ2stc zwqag1%KD+#iM7^zNqiE+>>#x*p~H5t`lB&g|I)cm@acpFy>#7Lct4IGzhCtNH}eV9 z>go_-9LwiMRsE{qzy!K>2lJ1xezi9Bfj-F->C(mxh3Bz;uw3l}OKwi2Jw8qq#<6}_ zuqqlh+1S!y=NUh+{q|lE4{P4oQODA|>i-wp=Ygtyh4W&(sC`3qeH`WYhTpX23zZ|e zcBRtzRJ66>4Zn}%0%uF(Gxy7TW&NR+%`oN1}<7xB>w!S!iYWyP< z5;Co*o;J&Ga43F*QDI>4j}pY{a`gw8xRpiQ4*xS{GuI+zRSbx0#c@SsA zuZc3{s@_TCt2e`j*U2#DmOD%1+i&1*zWnPl?$<-sKacIhWz8C8MfOGV@X$O-{JnZrvE5vdW+@vF#d!8dc*t@OB&aU)!#Ax z54QL~uH_hd<@f_(eg+8Nm5Y2KOm{4``;bbd{O2PXesJ>TSh_ZQx`4kGvfo$l`Ga$t z@$~dmZDE{4@mbFYad5u9H7$64TlhYXZ?v-R^1CAra|SP@@h`cY2YW8gr%zvX5Z;gR zOc&pHd6UjdIn8Qm z{9}F`Wb;S-D|i_2U4sq%mLQPep; zjY|2?VWol4wvT0<`;+*4fzW51CAGDBsg_@HeejU#{Lp#9b?FV|1f0-mzpGvU(DsZd~xvpI`xBl!F%PF`zOejVd?7miS6%G)xJEx z?}Mqc16zMxwEnv0?$C3mDYXq}^T+G&Z{Y!j86)UBf7btk>m!pkc*9>CbE@yC$^IYd zzl+bkVZ};ws�xFpl--y`TVa_TZ>&D~s=OeDZa4Fibl&ioUKN&hX>J{ih)>ZR&9U9 z_Iub1B_Dcm9XB>YT0U;SsaA$gEEnl7EFTy9I)mS`!L-~&SC}85{+6ECoZ)4sA++!} zlMkG~btf*66f=aj{DoA ze!sW6z}}SusJRwfU(BC^F&;2PF^I1Bkj8gvst-JPZbJ7r@D|n|=P&AA4uC*MQ+h3m z`L{TJJro=Wr|+B6^4`+?nDRamGT)A+@VgPiS0=Wfl~pP5di^9izQHR2UqJY7xn;wz zb?H;5eEZ(D;m^7C;o3m~dp|lK$mq}n2>jBKp8iLgA8uQ1_~FM4xy`+#^+(|*TYgY- zFD^HEhvfTP8E@pL4~gRRPf7dFGs?>N)1Q}dlbYWUp2z3^CRy`*&z~!}!p=?9?-!pR zl@WWHkNd5<-^(Ug(*9Houi{r+Dde6dN$Ve@B{fRNlp}TWbE>r?-0a$iUTVPj$07aE zdbukMOE983f0+Kj^@qh>J>aHd08N_7`X>#L{mn4!tWN* z-bpl}g4N$}e3n=-0dA$}*U2B}3$~Cu+mMcH!}N15lJ7IqZF$ePJ?f0F-`H01FXrs# z_NPkY7ijoF>26gjim$PLne)p5=D8YD{c%kHWBl6dxPi^gzVuyuD`EXGev!xBp!!~4 zI?^dp7{~i((p34G3zz%Rj>lR2fc=BknI2$lVI zfzWBn5W1qH8b7qZX!rSKNFFna23}|W6~=GDg$!sNGl@F3|DpDO#r{R+)rnBAUVCb5 z5<{i@|AgiD_?*F8x#Bm{@%NZBReWjX4%Pj|()div_@ErN{s7VHovHr5*#G|7-5$2& zccacej2|50$G}KONcZnSmoD=c)(7*uh3fnuUS>!w$0*qRQT)05y9+$-+>6@ZX7<4q z)dx3saEGboz3GjPM#B5Cf4FkL2L%7>Lz}vfRexXH|8Dfi6V6nr_@V9(!1Dd*kq?*} z_orjOG5;U)VmmY<+!P-p#kyD9JwqO-ZGTQ`OE z!TLKZri#}Yx}6*4Db0^Pk3J}UOiPH-YH5BDLuWYlq8q(x$nfP5zFxmvplnhP>RHI} z#qvAtpgSC~H>8GFr15napgRBadvBW4VWK3y4vD@n|4?5VzFh5pq4+KQqc4=`_M^Ag zu>3jp-*%e>!u^c?bpNAJD##a#4|?^EhQP){>4lVE3?GDl^Llf^X8sro4orUW{`|-B zGx-FQj-2DjeD(T^>x(JBKPZzg7uUJI3wO+d2W1`Ty9@J#`6-b6y`*-qerOjucfP0a zeq5hv+c6JX&kv+c)0lm5Mf~!7l@G&5goyZs{mbCn_jtShx!k4C()#76>to*M(-tnf zn=y+&P<^B8))~-MLytZh#O9CnheJJQ$cZ+ftJ+EP=gJaSFmUNcO|6;z#`QtPYFE(r z>_&|WnE#05%U%_3kZ#po6hDR{|G?hQ16C*Wpc9Mx3+spVOTKFV&a^YVY3=?m4*3UK zVSW&+;wNlvC_In*X9w!~!|RYfG)t55i$nZ6Ia~oTZAa3=4$MEr`ej+tTo@QUnnoJc z@=t6ZTsm%nHnUax3p%p?Ed|2&E4KyKEC`^%WlVomqWf=qc6-b}G0LmcJ{Ucv|R(E=L49lMyBYZr!`M|A%J*du5O<{gmzdvf>4;Ar- z)cIS8dVb>kOv&IBC>>);*N%|(zuv~r1Jf7_YN*BHdwlAyCQvWLDc zI?(kUhpX35Y`+$IZGl^jeCf9P48PSD;{0}HZULBf38sOj?Ei`p{(JiPz=;!G>FqFP zzba9Gx9@siSbnJ+J?78iC#)YkyiuJ`)u=o5jA!);1Sz zJK_7rDF3kOfep;!+fv;dgN1SIU+#XC4~ZQ;Xm}xuuQSp5Zm}$e=*^Mzc0h^zKmGzb zpRnQB`~1|h)m+~e()*J(?5^VHD%Nw^-KFj8`-j!a=cl(3#pyJ)eG&U#-rs!TsDS}J zeVO4Ciuir_vp?+3>`F`Z4TS&8Mfg~*2n5$c6~4Wgeo-L&@64V9>-YAfM;uuG0Q;wD zF>@h);RyPo+fQMBG8Er-469K_Wp5#uwn^u2BWq@Yy=4np-Njy*pB2K#di-oC8rG7g zFJ$pO&L0>#dqTs?jx;ofjRWd08FpbEJoKJL?Q(w!?^jR_QGUs4uLJ0XwWb3)v;G6@ z|MiY?g6v&wsON!X`X9d7e{pT+1#5rm(@QT{{uuMWIN2BW+IOOP=_c&^Xnx@Z{@{ME zGwm^+)lU@2f0$w&0*yO$6Xl<Eklml4)5EMJ#CY|Y|djL(i~_V6vP6@B3}O!z-+KlO)igy}zK(uox^X8+Op zk8ml0T`xju@9AxY=QELhBAsfKoa5#?`5$QF4x1*lr9b9H2+wnfKTR)qf>U!n`f7NV z@PF99Fv|3TKa2Hf%dgCSr?Y{cZBuD_$Y&Y;ow4jQU5*0|IZCy*mPB& zT6JOmXD*Vje@en(?2@i@%YAkK0+OG-p7&Mfw=d&}N=}%46#Iv*O>2~`ziq5@ecohF zhx1RgX=n<=7w5MpKedI7*Uf3?53K(~hWwvKygker)Pl~nnJTQWF48ZJa~z<)vIV`w zCkgATK>oeP;=SlYDNtsI=Uj#M^CRnJeXU!RVh35SCl)6yi-kl|DL+Guz5>UdN7jN53HZ21*rOS7B!=%ixP$BasD>8xeJW4Zb1ix&lc7f>z`@b z949@$sk?o{+EIMwGw6{C?5a3)Z={q0#eL zf3Pl+pMej3;23Eqsy|}>=B_G+;XSKPUKVklW{9EtNs{Fw4 zW^}(5)4$k$CG>QL)NCCpEAJuvANIe$&2WQ;1-dl!Cnt>K^*7z@4o}is(2Wb!>xcZy zmFK-x`Ipx8T3Eb#{lxY4i{U=-yQDSM+ovy#V*#CYpCL9{x z>p(Myv;02x-#2cu0RyT{{mv&)Df@D8WQ}s7*&1SPEp7j2-1UVu2U^mcq0B$cMeFPH z)DM2TwW2vutUmnyULM)}oB<-(P9 z%Fo2JPLMUf2`$!<#*dD2hQ+s=P~%T5KdX!M&%K5&@ZP2=?beLR2O#~E^TrJ#O?7B& z4Lcu?L;7{;{W75fza2zCDrN7)(88aT~5Zs z{_h>=wh)%T!Rxc(dJ)`|M}Z_z{tp^qWl^5pIYX4!hsRZ zsHNQ>wSE-$ANc(6g2o0qwBgb@O2L0X>jyJc{eM4o=o@-V%`dTk@6^W++8OGK>N7bA z-;%F>FlvV`{kl?`-)5}?psRBWI=BVX9|nj&17*q3L8Ak;oU=)izw5$MRQ(N|XmIXw z_4TkK$IhRV z!E?)3Qh8;%`uk#huPk?h{C*8-QY`a7ar~Qo#Ra+FAo*CR?*ZL5G^R(UF#Cbyg9B9_VAWomj?b_Z-jDr*<1$a!VWdrcuSE&tIKFB& z#|x&kYa)uz70AB|z2*mVFE*nak{G_&KWU~B3?+WLwEDmy#vgRPC8-I4n2jyy(|WIk z@m%CTFGy5CifenCugCNkApMmRlLDzr^{Hu#J?ixr<6CsRTIpbrO^&Qc5#EpM69vVS z;pp)XB>aFheis+`!L>$BXj^;f|BKKG0KLymsAI?@;r)1jLhqUYxS!mV4sMw(%uj~$ zds-g@KqI9oEwp6u9hUELj{_mRRWp(PQXu~+@&0~@3z|*mX>Jqn!}xb9JPzv`xYFLY zCkf*?|JVCM5ET8^rd6+5{>s=w>>ur#5DM!Pn$iWG+4(g1`#ao2A$MU@>bsQTSBdbe z=$HZ(quS9jhfFm-;{4C^ohtm^wxf@4F??kRUu%<8ShrM(h2GH zec<5?8D@V->W~28|0_AMe+PS=Vel%|_^z44IJQ6ay12oJ!!o*Z6zf02`Nj2rJmIpe zKGnQFMtI%|*`LHls{4i3*B9jnu>TkvXuVabl>NV$ z{{bicVWD?JI&11fL4RQRDcKMP-oe^5@L-uRj^)pOP#AnsG@`{n-w5N_Km1r84*_dc z_Wy_U{uU$MR2UuHlJ@qNmak)%s+D%ebIH=4()#nssF|=T>J3?&BrQL(ZL=V*`8yKl z!tllMd-wty=;~cV@*;hO_2H2J`}mAKq;&sGB2Fw2))&iH+*Ny6HsCWc*)&ub=Ma98 zl}<3@;5Sm+Ux@jis^bD*TmB%rBv5!B*B2U}a)qwVei5sNHtP3_>%)2OKJepKJ=*JQ z3T6I-7~iDDs{WOldUR?f>ks9S|2nR*A3Qy;AC(sxtUm?kr<0ylD^0ef)rnt&&9mWl`;#;M|)udm5>t9ior@%n2& zv4h4%??~`Xrr&Y?|B$u=9RKy6xE^QmBi{dBdcX;m{rx~@?VB#VAMa02QT2y;?fy)1 zUIYo_IDcj3<_@ndzmcXDeS~rB|2m!ag`|YPq^|zk8dE>G^!qP4S&!x4tq?vkMLf9d zZA6nynEvCCeVel>4cZLWp|T2Q|8RX!+bA6lU(}&zyCtgUFV6qF7^g$VH61!Wmc^gg zK5L$?Ru0^%Ab|%If_!8DB``X?dyONE zHhN3GEuT-BeiHl7=NdSJT=|YTwqy1S?|*R&bBDfLK9b3^nSYAwFGF=a;KuY%#J-bs ze(&8j4|xCM6R};{PnaK;&!8#ZF!^GY6gKICEU-@ZIXx6ue z)SmCv6!n*%9N`70x7Cnu_oIdPhoboMl9?C$E~p{a`ON-e{cSlxwg2Hz4KaAoUw9tp zkESJ5D;vFuCZ;=+CFSGPw;9l2(`~Zw;#^_=*#2}jb^wbRRm3=dHv2#1|CN+Eg4MUj zWI!IPui*a1lqPQQIpaAoa%TMyMgVJMgJQJAyGC=*U z8&`Tj;P6*uuqj*rT(tgUC;Gs@-QE#PpEzNCaQvouGZ0MbeInh;{e^Mtf38sZ|8|W& zlT1%(`M9h)pSqL5A96fzzwkV+zuasd1C|wkNbUJ#SU$Snj)fzRGJ5tqJO4o!^;dV* ze#nm}UYu*7bbZaIOSN+H!BDdPWuhd$SFNYOt!|gd(xtSf_kmqlY7IY z@f-Oi1fFYrAnTum2=l}KagBd8_?CPl#lM;U#{Odu%XmmV{G0TCepOh11BBoG(GPjg zZmwM53TgZ*M!w)Xn)-92Du$^0L&f=(B9m(6hs^&u(CB@{rW_FDp=ft@&|xNc;1U*fkn0tUtb= zb=*~V_}=mnsXdRQrX~ObzuE_tp>=^*x;5m7F zS{i>Vn;?ik{F1~HhCj|9{xS-NBTHTptE094t=NCvl|Kj0_WMGPjbZnX0J2|REmNS! znLp%le-PhVmF9Lg`G1qXre>n9?9 zVE@PSZV0@e`iyJ}*(!WrhV;wD&U3&$;ytO=-#GqU>a2jsuV0AbKqK~jKP{2=y`ZM0G*~kBK>Br4e-w%rO501B9@LAhkxEq`a ztFNN|v;wzkWs`K*I`zwwiJz4=j$Xt$GN17mwsACOtErS-$GE`cyQ-~l=IiuuQY>brwh213n)2V}u1KjHnMh(CMk2SMz(hotuW zmr9g>-cv6c#(a22ip|*hs91kgZI}Zsf?ko^CzyW2@zY!FB)~fo8 zmIi$wruFv-_*5eO(s1uS-aoh(XVZ?|Z-n^~6r?_e&l zTsnW)tNwfC*v9tc+=|-s|HS#dq^N4;$Y6&$`IRtgDy-~qjGWxZ_=EM2t(_B0n|6*2 z>TXS0{3Z7Pol4x{lYDpNsH)eb^6{e7;GNwy^rHG4d}T zt?>tkvlT>lz4ZPCUDf?+{;w)X?f!MFzdC&ig09tf2&rNDIjn#3(?dYt?;dIG+C<Ix}{ zVff0XyZi_4<%Z0)fz+9@-Oy3^$n|)lWtm(U%eC5-xv3f zI9;#;`=$qo{#t2#OB0>oqc_wkzcFV$;9R5Aq;`LcD_Y;)RCPb1!9RqY8z`&~wjamW z`oaU7bL8>s3Bow`A2X7JA#uZH(jzcUy*}dn<9EGKfF@Uo$?A0Bc`FouUkM0?8TsZ}D9oQj{>P`c>Cm9v3({pJ!yn7%ykB|z5Wi+z(;#X5v(CNbt$R-5D(_4C z2mVE>{)gL>>eSzZ8_j}!6G}+ZId5Tp*#2*s=?S}%d6KHW|1T8j*WwRekoB@$l;1E$ z@;fPB72iELO|~Sn{9`EM$DhBd`yVcyBM)aV|I-z%e}7edPV4P?a&I5Q7snsRsp|f@ zlNU(tVRe2O;cNab40<_UB=!?H+>355mj=d?!2hMLEm@pS|Ry`&1DCU1) zeBSHk^FyyR=GH|@<5MMj#m{X%mh1MH;Uh!-+ug?Vpl8h^vhYx`BtLxkYUNCRY@PT; zZgB%WlOrV5y_dj$oL@9>_l8F!%Sem0w!-^y{?zKWFSMHh#P@-_@O&;>e+N~6`4lE{GbYW*hGulep7VA<^fd3ck_S1z)D7rN&2&fgnw zZn4t%Exq`P|J22TGbxnTuLe%lN}Dkjb?Vpan$w~Ci0wo}hsE!>KCYKB6S61lAR87j z`NRH`|7T~Ib!1@?AC zxnB4`jQ>>o1StA-j-;LUcBewSCit@8kOVv-sK2y=E)nEPaG=jDKnaN1y|Ck=tdS!uPR%lNId@9lGx! zu13ki^D^Wgb3a{RrF|i(?N7w^SEIrm`fMpCuX3dEKNF?eU)p0Y(OJdzC+H%4b-MV& z?zn?QQ%6&nAGVJdJ_NzZg@=iO#u#CKIKR6sC<0!*KTevoS|^NWqWsIqsZpR2rX;oZ zhscnBt8Ehlb}f1GY0Ni4{xLt6osWZFw@#36+TQBhB?<6OKS$~xb;d6hwJ3Rihla#lS?hlBK^j7763&}o> zvBLXtd^+Q;Kb+XQm-JIG{jNaggWNkA0Mn-IBem!20g9jRcMAs39{WjLTjqarXnpk; zhCs0S0pdN0@uL#u|9j4gfW!SuN%;Y0A2Oj#oLJU{JsJ{9P+*sNa{;)q|7b$gP_{l89{%5}wEU`Od@;uHp9BQ{dI;GEzPzS9l)hZ_`!x{-kvV5}33{7`L(z*B9JW{lWIL`_*Z`PfYZH zePOEo9e-_w|HJtsYt{MF1I)LO+WsS~Uk!@_;NNB2MfF=r#4`Z_3ujtulWtXde-URjUKm>H$Qou{&_!N{k+(}T#>(@w>tBO&YV(vKDXFESRzyL zOUID3&YYw6PsQ=~%Lyv~$!G)FvdmuiKOFy*hkHZ9{*9vgF!t{^xAcJ{JvWgbTsz@; zoWC098U!cS=aY&(DZ)7RA2bZZq5q$4#8=7qf$KkM@1kJ%?j1ybVN2n8T;FT*HX71g zcM{FrIh5&Nv3~ZECqm4fLh?A5;fMYAg>Mxq`P@eq4RsZs$Nd547pH)WW(l$JVf-pU z{IdL<0$rDvkh~zq9|iIsHrTD?^(S4R6TeC0*ZJ&z-uA&~deTiAzqEnnyl-1gF1%-w zfPWsqIMIH_pTG=$FTlsy*~)%{n{YX4;=EZX|GUtRy7No{|14&uk2 zf)w~yxtq+1VEoEK{F3h}1>LguWc(7=-+=cI9h|Ji`+XQhoo})JCw%{7qW?<%@3vEP zrEGzu{y49HfG-^Mj<((;&A&07-|)d99k>O_()?;~U#(mm*nznE#!2dzrZb(PUT!wg zi1b&lkGTK&yuAmk`>=#$%fp2AU5)UK(D#AFz~!WL3G)vze>BGXz={RSMfMNpXSMtJ z!a{=;r1tz0-2e7*do+0O+eo&U842IV`5`b*0>}ON4ufzBQ@+sJ@cn%OUw+9jL_* z+SQNV8@NXOyjcGy+|%McOpT~*t4YE*zCUd3xs`mopJnusgET)*JbBIE+}VcHGLy#t zT%KxwU{c#U;}7QuTljf6gP8Ah626c93u{$>&yv9l$-amHD&(J0fBXui2aJ22MHYCn z_|F*WpY9R9kos~l$$qLQy#FlnPkwNIkR6yqoDVVi#`de|lpi$VbI9tQ6WRJ8{gkMx z?-_ARMezlWFMnT-25X%)6Vx70u{S}*P&hqiF%g|Vh3v!(D&4B9sPmzb2+);GlGU(9;Hl5aux(v6|g_!kX5!5gRlOLc=7{@DL`m|V#Z zX{yO(o}aC@FXH{zliR-Ko#UEt+bo8&`Jw#txU_1eWoDB)?Z=)(XQ=F$OnOZ4RSNn6 z{{Ql7f4E*Um$X{T_<{2qp}kb~QP25gyfv$j>!SWjSQHM! zy%&!T4kr`8IcyFs?xSi5U_Nu8S6tW**Fc z#rPNXi~)y^*<{9MY5%1`gE=sD_+p~htgY~V8H$g_RL6sNbq=Y$KLGo`Ij0lgY48%2 zePsFx$EW>&r@-i<7376wrttqbe|xm|UI=zko&SDAi{Xp-rzJZAp_gxw)V3^s#OLb_ zQt@xCVke#9E6u-~HYfO{@9)#-CDQ!6S5(O#8uf=R{Upu55&7?xe$N`H`s<=4{gZ}4 z?l7ow4$*i|g!RMu-<9?JL4%|a$3Vs(yuT)=TM*pPOe2Hegb3>+L-uRmmSAXCnI_6V z;rd0xX`x_rEuE~lVeyXw`KK!mghTg%bIC4`#lrg)NI&dt90i+G=8;P!()`kz83Xk$ zWs=(a>oNWf-D2S5%}g?O#scC0aeeEkXB-%2Eg-3FSpNdVY&Hq@iuAx z%v^hdx2?WTeVmO-PXvqNb3pdzM|3c3J{V34KKTpl zhvTD=)JV{4Jcp1&+t~Z5IDeTI8Uw4^Cy@P|Hl?pd_VGtE|5#(zj2?ed~v{EdM>^_ zvybTft0w*q@SyQ5a_|@P&#`>;OLhgV_I4uuqCosOH`EIZ&N+$tBQU;CRr&mb0ymNxT>U)@`=rI1^`03PzyL{$|%ar7?`!VtT?%Uc`@#jo#(jTVM{2Ke=9pB0I zG2Qu(shVHn{;SdNT)^qfRN|d5Ly!*+#XsY2xWoR;>BMm=i*G7X{JWs34=i0co7A2U zZ;b5AzdDgH{iPdOGkBixer!J+=f%Lop25o1=3&n-idJQoIj~+|6$~h zB-l4Gker-Wq2`Y`|6UfG3}xkkWa5oZ!vEv_Nx$6{koq@>G#wHn%-;(6hrbtAD+3a5 z*U6t9+fVZCCl^!0d};nHpIF6zZF!Ea^p@sF`?v4-ceWKY^oTS+rp0)`j^AU+r$sA- z`N@#|a9iO4NA$)K-$3TS0OE&1u_wsejThAiE0KLs*!#eo#EC@bEsIZ9BYeg=`oV`u zlS#UHys&;a{y#Jz1QyMoF6w^;#NUnC(eTd5mR!ohZ%o#EyVfX zPOAMG#UJcR%W+IUVg5~>6$i#k9Z37rYWs!oTec_x)-QD;drMgSg!Sv!*9oxvxszyr z5AN^Ji&VhVBsWrV#zk0v1=^puS(P73?ch!{0}X`r!TQflL!N#_DOe1|mu?#!s-gLgrl{3{B0 z&yP8IfnMu9LQ+3Pb#epWA~Rx|W-k06=GVFT-f+sABerMS2;(?@I_c;GSDILm+WQS$ zk$!qHDgbOfEs0`DlJI;}ls{PR6AHsGjVFcrTj_u6Cqwo7b4gJ!-)IVHtIzZkwqIJx zIA~Ego#eh^{J`>U8Ik}$3}%w>#p8tc0(he;zebz)`t1G49uZjU)RwM|Hl-;zl-P?sH@H_w_{m2Sax%z7PKS3kC3>f{+nUrpOE9ghuA2ao2CTN;_k)I`7gzqcR`4`_e zRx8gZpQuy+728ztBmN$s4c(>n+qnuCm?$?UwfCPGp!mvXvp2+*4JF0XSpPoGUmUUY zRrT)-CnsAn|I!NSrvuad!0F9!QfbWc$JoDmvM>v#FWkRae@+6d z3m+%qpB2)7hn^>Z^@VZdZgM>(v#(hjwX@1!Rq(a=tsYI($rZB%8r2o@@ zr-Pr@3{u@y%|DsgK3AyDFT9gfTBm=1jdOx|)4P*CcQ-J65PsuT_3ch)`-b zzEkag3!X$o{K-W8IcSjrgSSvsedeZM|B8`*a%q$XPiK!Jo9eUpr5N$YbWFYSF|SWh z*Ma(K`y{@fu(#^|u01|`>dYS`o}LZPd7a3TgK>;MGI4)X=*3g~qej`P`@z}$iP-=D zu&at++$E1@7fI{4SAMGVFQYn=umVs4p} z#f>eYU{}?f$Xc@e1LkK{WF%;B?nh*2S^g2*ze+_U6z}Lqjuf)^DHQ2nul})cV%h+4 z{s`TFc>hf-T)Z=Y=*}A;%%4O2{<0+=c3w6n2Rx2%kb@eA?KM_YBj$fzO2AwfeJ$MV~)Uoz;~4jt2IQaZ%)a3KQ&Q77c<0fb z6w8d+`XPS)2#kkmRy{~W@43SKG5@$t39z?QPjY=8<6kD?U%!$BXx6VMS+s)jI~VEK z9z}`J;6_i9@FhxkKh}?vqLN{`W-szx$@p1}_&Ip20*)(tiTJ0B_?H9$V;MhhBYrxTrNXM_{m6cEravl?|CzWd4K58fBA=fz{fq5)!Txz* zb!ZSd_KEpVIDcffX%9SJ;z?|CCkgAHi}*Vtq7+iwMUaPin4N2OFv4Tc+PDQT%bqRdqhCe>39$n)zo|h~LWbLGb5JbK-xVy+0TE zCtB;n;PJwiB<*6l@cnAkU$dqn3|xv^lJt8$gmD?-_nj^gkeb*^RDZ(p@k9GKIP<3+ z;hs2A!GA>j&eThSh?)ANeg|gXbCG_`PfvnNEA@%iYsUXf#Q&OvWJn##Bc3E z3K$C=$a^Qo-%`Ziog);WdA@^)|JBHUSgz`?IQ?%&Vlsg7`vu~+vt}Bs9n*z4zhe3! z7wO-YWob~qzX2&vV)Y+D{5QWc7q-ZHkQ?3D`P`VF>*^Q6mOHaZy3b^`{)pdW-yDM_ zK|bV4L^oj^^Y<+|&G%{?O^2xZVE|a#1dd%|`R2~BH29lbe<0&8?r(9*_JqUx|H^0GX8EN`lwXRS;0szZ4bt{Q ztnhz0zuea;6zXqlNHo@E3;fbW_0NQx;qbbJmMZ==6rRWRw}{0NP?MlVGM};hCidSi zw2Xsv^QL508^*s-#J{-II5?Nklz6^j{KoN3s}Aw7{zg*~zpfyDy(vwAf6AMYHY=F^ z2E_k{(VX$~_`iFPD*g)6 zCB|EPUr~hmy7t@d29ykJ=BH_-O1`RxIWbNR0cer(3aSDVdt0P z{-R&Q3nAmSCDA+2_>KLKTP@09P&*r9>&)~I-ruxl-6=k2o;y7^T$`{QpT|L2Tv2wb-NDxd4wSilG8 zmxr|qgT&6?NgX5SV^8NbEKjM&l_1_T( z%B}TC=4WaCAD$i$L;uzz%N-a$T@gQ5mB<GYzt5IO8|2|KB*10H;rBi2NS|B!4#z z5<&B`23dcY$xkJcpANHB=NI45BoVI6zI{XbdHWFsI9W6xtH&_=AVc!;T6O+T^Gyvz z{x{BVJsFB|&k3AIUX_nJ z&in%$pKToN3a`#ym)G7u=!*P<#)G_|+p^p8xO2GzfARhb2i5uSKkht|b6cC5|HnTW zC%zy1-S|*A>+nQgdw(pT{-o%;VbJ06Q~8@AYt`=;_s^~H3*d1ALPCx#|!_Ti}uG< zUR1!H!Jp(J{~YBHhuNgSJ^5#OZT`a;`7ggC)8XmlpK_z7&DHBC&hJfC@%!lWUvj;d zEPsae^Viqg__&0wG-NvKkHGQah~}ldRnNh+RgpA5f9yWRUvQ)Jo?KdgKe(mZzgp;2 zr+(gYcMe$fy&aKwA<#$B*C=fpGJ2N2A>xn!tMtwdC^51UMWWdL&C-PAtErs{v{)FUy zrTqGfU1<6V>Gk_N>lEL7Y(Lso6^BXrcd~OeO5?@jMvHXv-a{-MO$K|bGvi?bI zpEmqJy3Qx&TP0geKeg7=7PnM?sFl)hSx#{im!u<^#x_>#w zE(Ad1ygb-tjqtn)>W|&$9tMBUUXYIu9w>|}s5rm;et8(2{&Ybe`i9vrEZ->|BcV&5 z%kq<#dI{@``y<-zjD;5l*X6bKMEc9TX*9G5I4U>r8O_E~d{}=`9IUG@lV`uq5Z-T$ z^xI}teN&MFBKg7jhZ1cCOtw5B&x&ICUEE(ga$X7~t~w=e+f{9UW#at!iw!C8<;W@d zt*UKx-!`n-JQ8eL)jxWB#ZQaip~jX!Czdxd&jY(KLvtmgg8-jeq9vjq9U z{T&~jOL_gA=G60zwEUg7sZm}$I=D{zI={*RrhM8aue~1%`-fJ^Zg7@gC4ah)@fYX6 zYRm&+%HU1%+WW0>{BwO`5SYK+B)`(9OyHja$(Kf47#LsAlNS$R{xjxZ=bw?Vgxe}F zxGrrUj}%A4o{(*FT~DT;6iENAT$cn(U+x$$@t+%S{&#guE zoq?fgz;E3vf0M%UKRABy>lDcfL?g>KkOM@e|vx>(5s6i}zn6 ze>zCx`>cN{U!wJgbO335U5iigcU`pVj4yTvtImhs)kz+CCPt`l;`6D(%ceocx8d@Y z7g+um=l^E3cLJ@96#3&z((%I>E)aBfED+&eiTtliSs^fQTbA5@c~^noc>lwygCTHC znI+eo&F)u}S%~}Z^Hu%BG1=Mj7s)I?hWAI^bchD6@*H`o`E~(c+`rImaSZs!FOfS& zwPNyx`0?#`EF835Dt|e5z3@Ds_e+q z{pC?rGhSxVhb-=WT=+irKjwE{#0O5^L5fc;lH|vuZ>#yhHHXM5BWZpVM3(Z$S3Dq^ zKcx9_sNghztn?kJsAm3)4DG+#+Py}(Oxd{3{K$>lQ&i_~PnM5(!Q|)v-A{8p1b#mY zk!v)aDf}OfKbMaThgL4(^5B8e_T_P51RQt}A+ODEV0?AIM}eVfw4Cc5BiJ9@UuK`B zIzRY9tbG5T*24EWgl}HGIWXFKj=cY0ICn=E_h0RqHRb|LMlA zW_;t%&B;Gy$AtM~{(MpC5C0kK$*p$M{P+}C$`_tKMuL9V!4J0@rOlgH=5_VYm~9IK z^XO3`{{{DFUsv`0m70&2gF}gc51{zz;lHuaJ#xI_p=@=P6xx**7EFF7C+$l*7tZb zerC~gdHo0K^_7YD7sYC>;a_iyCr?bI*SA-n8fD7KW9D`BXIp5c@e#Lrl8X+D)$%R= zzr>zv_&nJt(#Bf){pU-!^Ts)|$PbN$!t)sa-TSMRejS&X*VX^~{+AQvSvHpM(`NZi zTz{RZ69&b;ZR8W1GW(9@Z&JN*@T}ifUYlRX@#}l%Xq9`cCzoZV3HVnc{D0nvhrVMv z%HQw|KinU3X{PFaktbc{OSftZ`qR}yoWK1$H4S=n?=J7Qk@<&L5Pux6s_<>zQ+@^1 z_#*k~uZmxGCK}2wY-8UKMgFC8O||mN!%60K^}qJI5egp@u9^pJPNVrjD%nAH_R_>Vg5Z{zu)DNuuFE++*yO=*Kz#XNVUHyxzBy`eyg&X zd?5YRH!2mHg+4Jq-H)xGE?U1e+tT3el7G!phO_(})?c^mGho$*7v^>4N5}5VfIA~z znj5uX`33C%z0^(PW3RlB=Xgo;`%ds8ew)otc~S>y|3_!;c0S}+Yx3x-bbLPZL$xwA z{FPZ<_}rAaK-mgs^V0#0-`M`A4|j*2Pu$Fxe_qel58Y4eTp9#34g{H>eXv!y-_5{6 z?0+XV3xNl%Ldx*TFQlY7Knz=I{DLkKxM*FjwxpQX2oz z!bSYXQ#o?pLmK~%xf$l3o7jIURpGxaVR)VRcN}63{km*7bJu6_CB}b* z>i$E!eS6KgK5YK@eu51o1XhkdYBnV)R9IhpzRLxoe1q$s8olShSo0HR$CfhtiSwUd zmnTB_`O{`ObD9b7H?|PxFD+E}BW`+s#w>41j({K5zx7o8M|u1?vy=JK{2F*B70iZS zG}B$uO^DyHe|~392K33gYIfv4;}6bn)x2uLFNk+G@9(2tf5e|}4r%;l*){Wt<xcA5^sOLx-tWlK_hS#K$HnJkrL+o#X5Wq;9bjHt{}i9k@nTmP zEai?LEtq>)h|h8nzaq9Jf$82eM|WB<{IGtgu}uMk59f|viwzaNkNL6ZaS9x`eEz70 zjynI1`fGlSSKWW9d+DfdczXfgN)(?5olIBtUtT%7aS!vKaejHm@EY4G6|6of zlZpKs!zNn%vx&CHQfGG(@WK54AHF`PA0Mj=U*CXF{PwS-kN--OtML{42Yt?Kl)pJW z{rESzH2&ZJd9U2{TI*PrVU)1GIR3r0-Vyj=DaTAR82$z*Kj?MA1KhGQj?LJj<}bqk zfLAayuUU93?71}lk3NQgc~#c2ku9b1A5uRGmcLtktj9cN|78gOPku>YyLQDfyQb3k z7v4&O%=;^jh4T7>{QnbO0rv&71Ay=-c6yMk%SN; z5klyF&g*7n@4X@;yRt|8?)Ue(=iPlh9{2tCdE9kg&-2>nTuZe6_3!ZKcl_R1Qmh*! z@PYF?YI|eg`LC>!@~qa9@(-$xg%5GrC3XEGf~B@(Y*Ipbg2{!uZHR z_N~+XdZjt;oyq9Q(tK>5Urjr1o>ihM{z*&ogh`>dN-oTkmVd8H^S~?pZb^F==3n9c z=aKyX+YFE2FG+lUP?#UNg;+mSjf;TIdLK&;RWtjK^JiZoA|ZCdrxNQwxdOi)X#eP) z1+jd6@JC6j_H2FP{(G0OSa>?`M@ec~eL=oBzrBEqgZX!VmE5z85Z+H0`49bW#e?JP zKPBoT+5SH4zsmGeAT>x`QSS=N&*Jsp&1x<9&S<6>?-|d&ALVadXKn_~4s8`@Ix#+S z5FZt9>y@57&7aNVBQ3u^^Q!5eJ?mAsO_%sUd;Hx_T8HA3%eBAOW|(G z<{z)$2;&%da-xr-%GX=aA957G4eXQ)=335*Er~}hr2Nmh_u6xgCr&FaH5e*GA(pkG56Roo|f$w?^0o!3|wI#XP&d!t)JL z|Ci&0AUM^_PGM? zlcH=?obdcYq#wB@F;MYnsv_)67vcWpDF3$j{$}Ws7Nt1t%lOCfS!7^i&f)trh07;3 z!T#a=Nb`;zxbqRe6ea7~{Nwz(m3kSM_GTBU?VK*WpUhI6-?r*szjV0nL(=7@^!nP} ztD2teURk2bf4ZdW3BTreD2)Cv{}HdRiU!_b?=@c$TK}-{e60U6RtG|Edw)eaNwHvj ziO;`#!v(|aX@QE7w+|_=7t1e{-~ZOvHbf!+71{ef3f~+aWoJtPNgUo|*spq+c@TguyJYwTi)GSbhWhx2BC_psz`mLgzZ`U&Qf6NlYv>X_&2OzM7q1 zFGu?EoZohs(+w2vp+|)I$M)rW{AuoJ&-cW01baT7e|5h8KW^m*qWk=fDdSUI|BF3- zj+>}frBXgCee0Lr)apX>%$R?J|34kT*Jli?yC_uEXD%M~fTE?Die2rPd@NCX()9Zr z(5#oGQa-uImqN|k?TX#A>*ObvPiKFBu)3bBn0}yC(EnIJ4bEQyPptA4qjt0W8D2lJ z`(hws;bBExe>AR-O|prFFtZ|s+wh~p`oQO3w3rhMYV(T}b`6>QJdpghEslkAK}Cw@ zm8`!n6Yakk4Y9EPZIPm|yiWg%;}7Q-ao`($RI%&y7=cf`zO~1!gmS-P#n8kkVI2EE z?QSK4l@Tb`nuZAD<;Z_&V80R8Y`L!JXw3WzY`=G=Y==W@o+xsX7=Ji_Gc4*1*JMT$ zded2Y{gCN%c#c-5N@pwvpzm319!sOdYCF<=?KKKLfIo^At~} zu=*E{f9mz;|L^His4#P_<43&y!`zm_4DAz&nGNg4#e8Y(_lHHaM3FQ2w7{1Pl;W$OG+#>sqruDJqQdm|Gl3tRKXb5*fo|(ADS8fN^;zuy7Osi~_Z?Rh_J$gQ z{1Om9gZIZm(c>$MUB{*QnRO!$LJO}c4rMWZbdi5i^m`>F=-pD-?2Q)gZ;1ToA@vgA zoxv@I`N)OBIF5hSJ7j`!`3J?Ncov^y|0XkcClsAhBc|(*Sup)0wjZ}@zH%*ZkD^`; zEF}53&)Wx!PmXllQ)&C~@{304)0uPW!?5 zeR!=t-@n}Ko+8(j@q_J0jv^eKCp}QeyJ<52)gn|D?YZT3G_z^?}aU)aA6;qxb} zcRW=Ltd_R_pZmnZwcQnpglSAac_6-aC&t3{X)hGXi=_GblNJZPd%jXUsu?ZJ5B6Ud z^jQg;Ybq7n&(0IZvHm%KcojtZeo&;lGXK*O@mE~E35MTLC;ErCGx?zNT@U)6;r^x$ zpdS7oCGDHnwECr1z2{Tw?$Y`tiSK_i{Nkoi<-b>jI74{odBu(}#z#4_UulUm!PEPy z!sCcEAM*X4&}aHRg}idIAio^sU+r%Y3>$6VDpsdU^Ybu!1zcBrQfa?pj)a5!Lbak? zXMw;M-X9~2F1?1)=_$WpPo~{)KF7S(}zjRXZnpQ`q()@rF@bcUEts7 z7mE7Fc1W(z0s3B$wEMjx=jRN``S&Xg1G|9wx`FQ_krtAOuJDZYUfzs=vsQyYY*xQ`^TFll5KHufNeFE%g){;yZ5hL6m z+xIiq6G8n^Yhr#@ojo7r-x@h>gx-U7$xt(9-?986hV0?ojt!zBC+Wi#oEqD`z;{#4|ITZ>Vi@NSxn+S<4k+1EB!cs`Dw2G>Tz?AW#>Ta%s7;)v|)Wsf*89N&SgKQvpo-V&XU z@pMTXc+BiTjF0pa#tqT>Td^??G?F@y>=Uh&-!JaJa?@T39uu@kf=iV0{^I|e==f)G z9%)82_9E-g!S&h2u!pmrWkVwxvvDl{@ykoO#~o%<-OY`J`(ydLf#-3@mEgZ1iU*mvpm-Et=Xf70A0B+yMd zzA)SD34WT*NS*$bBl+*#y#i(q&?c(t`$zup=VQ&$CWfDa1^o)BzF@UF3LNfrAr<~i zzvB4ewq7*s$?8hJj0zCGAJ?DX*+)bA)viQyl({hOf%xfH91X7~>k{q1GnC_vMg4t; zw#S2uWly46Y9Nf4qx`kn@^zs9W*GS>E3jbxhuHsWb73Qln_@=Xn#Kv^GSpva*`@(! z(=3-9+jCmDKjvrZvt&-b-H2|fsLPLu`Me&phqLJFOgG(>)-TV0R?)<9St{i}X~}7B z?AIXr)r{$9%$J|`b#6~hG_A`o$SlSAg`4-DaaPNcsKr&*zm5B^hK9JnXR4`^FPP{G z4JWlCqVp+`{VzH(4|W!IAlGg#lhiLgqIv&L(Ua80pV+_a&G-N8FX=~e0~jAU$p3M9 z9u0*B{mI(cnZo=#BK#87m~Gy%N*-PTYQw}>(a?nT)S&A^h-GNuQ5N563%fN zbK*t(;QW-up(|Y3h&9yXqn0p#SpPj4<_f=-bs`_{O53LmpXb5sxbDQ`QJAFvVW+zS z+`0}T6Q;5E!+cDc8Ut-sj39OWyEs17J{Sv){7gt){}4WZq}*~P*!Hp@x)bLM?~na& z$6G6*@V5n7lFs5k?0<94iSQ(HH0cw{^bfXgmm-ruVQ5D_)-pZ->7QP;8IZni5=m*! z_>iIc$fk@fAbaCMAc4KdiXN_akA-<7p1p`+V)QhlGv z&jaa?wkZj)$aDg6>Ags}9#H;g#nMC=)!&JpFe{Xwp5BFe66tyvsmfzWS z=eRAmH>i}~{z{F~Yv&%)e}&Td0p}7Ac$zVYydA*&2RYL3#x9FtL}L?T`L&f0U*h^w zao#d8x^GK-Ivp{UpYE|^hTK+bnGUOgvf`Ie9V6l1@qh4 zlcw{V2=XgO`x_f>jDehoj%1i@wIm;Ty%L~k)N~Tqjl~bRem-pQDoFk@gG97lqP)M@ zzqn(P2zOt*5hHtPK34J}^ zRj%)U{Q7O?y^4P7E-nAaH|IFV>TNW|TDm?oYTysf!1z4vKGjMxztpAeY#3o5iKW&tJi2XZfw**j|Fqd4BOY^1vECHGhm`A1>FBY!H{kii?SHqiy3yG2Y z6k#0epO^V-pyszX*`H=2jN|>+|DvjCL9eSS`LR+f;UfEOqwYp^{(-pvFY)0y?uvUp z_3GGGS)Ua5=V-ZH;#yfAp!#Dr2+zm$ z+^CF(q0{FRRp)Em;9|i3*#e?|u7y%QV)-|=PJsBvex!Mzw=jQPeA;EK+F zK*kJVd}*Td6C43$@IeC!b z3z+`L`-{gMT?|VS=MlO0PZQ?9i0cnyyZJ%Z4{!2uVuA2{%%4wcC>&boPwMtBVg00b zcp0Q81`x}dDoOp8z{z31+X`Z{jM-;gUwP0q3Sv8jkwabc1^#?d|I6S$(ZKbO5b=le zGsl-FK&p2faVlf_3Fl`*7xDhlta#G;<0RqxFkkxat3mFtlDy&=pLl=t*l|hVX|kF$ zz1TyzJ_q^tfqY+)Re2&QnJdlbwmE5V)j63Mm1+vt>!SK{Zb2Hn-kMCVKeV^_Pd*-q z->^SvaPwm_>D{04tBd&Uu{8rK(^AFte{_D1{iRG;3hPM2x9P(D@&1u5TdL{5f{!Zs z{$%!(3pn(H8m*Ale{J@Az=i{!q{T=k-)l(!^-Nq08JfPtvSB?*{iiq47k>W=ASuDp z`tL%+5I9r2ob+k z4ZPU<A>yEykB2;w!pW2H5sqFX9WI&&1_qK-sSK#I6zRAIJMMZUn65|DUpf zT+yv%_RB)tzhcVw2TcC(Q>FdBJ?$qqH%ATpH%s&P-O?SxdoCdvMXY{+&;J>$zX&w? zFDF&$XUzUvUpW8U+m7!)`6VZAIs1kA$NKNL{c8b^m{qVzc?l) zz`C1hLIg0U#^3xmNrGn4zEOKk|YhiwIfAM>> zGzglqNyKj%(vNwGX^@h?NyIPKk3}Wvp!p+P#4kR-u2Yi?$R59$oYpxeJii?64^dyd z7Rc2tB7QZ|`A5rJRa3hyYD882YtM;u-0U^?>9ror{>v@I@yV?=E|9j@pVamLV}8T- z@c+L{T_y7GFkcbv!{I@jL?XZ3QmG%s_C57mIJC=1B>i+xO7b1NFA7d=OCf$u8GkrG z)ge9sCM?__;wuy7r_Nih0w=RfGP27~LB9C^N`a=Uq5G_jr1d&xUvd5_Yi<&>tjQ*J zZy0~ND1S9zd4u(zhcDC%=Kw7 zy=WV$)?xY&^RsGBI*iQTPRQ>ffe%g8-}x&x9j2YyF5;^#Iv><(dpc}*v7P8uvGaja zk$+=iycVGS{ZHBKfj zPG2PT*PAb)p#La^1fOI23;TDbd2;A}eJ!6qGZFZbq5U0)XGB5nj&-D0V!Xgt4$@z% zp2xw~2Ajy5%JY)^>2He%@@f;A=JilHF7EHz?U(==uQrpgLZ;vH5Pu)}|8DB_&mkkq z7=LnfzKdGO8fdj+8ws-xWcNq;(8g8z*8 z+i#Z)U4G}1+$PCv+(LYQb;OVqXxMfancPE~Pp2sdUDpX_pF{FWhpUl~O8&h50K){Pt@e z0NwVbk*ZPb`PlxZJB5PRyR|CglVSY%)iW$JiTq4^rXLZ%YFp%RdVUsZs_b9F@x}6o zaWL^=j!J&rhQ`C-@!QDOmJF0d%Uc+?MEp7P`t^5@Tyk53`KLI3 zd3R$K_$zjjJI5r+l+h5PHDc25Vhp9hHM*!RLX&To_lrh}1Np@{EH6d!#} z&4B8Y2g!|vjNiuAV*ga{@H%jHDI#wTS$-l1)lcHwt7*WB)VI>^G3g?(F+8|63b{Ld^Xv^0YbA-`GFU_`v_4DQ64u zU7{uM?~C{!Q6z^Bk8(&#N}M2HZ2!Ccl0)H;ZN$>?u`s{BNPo<(9}nI4?k1CZNb~<} zU_A7z*iELZ&lT>E>z9W26JX(leDZjUH2>K%Rzbb$e4=g6_{aL)^3`ha`cOdTI5Yk| z5dYkyM3_Ji5WAj?fBb)=v5S(RN1ubFYz^bz1L^mnUy_0AdYHUy#Q4VkZF9aqwZew) z?@^H-x_T)U!orV`-I+{(%aHy~eZ%{=Z;z7VB5A(I_@_hR#$zO79MkXRmg4i>`V^!? zub0O}d|M*E59nt=)A(Z2tIA%Oe_a1FoSy+3ZWfc;AjW?s(%(sbmEiZLHMMH;R=8en zAK_T8oCNugj*>%hj9>i!B>fgCFt6uvk$%Si5AnR63bUh5lF}{G ze4c5R4&!tbq`|pm!umHv{qtXXX8@l*5b>vr`1>~~1Fmi(q;O$|*?-@cip~f5YtQ=+ zWrVZ|WBmCd{wnTmfcY0rlfN65Dft!i*Q&*LXy@IHR%E>p#_|5ow}CTZYmYQS|FQiA zj)=d;H-q5elO053z$)Q-%vb4$U~tXJB@5Pm6TaUP)o-V3M8odg1)}&J`@g5h#=}g% z!{kGSw0^8;w+gn|9wRN=GkyX2w}T(9g5#5m$%)Oi$G2O}g z^ASqAJN`TUZ}lOj*IJS)}=wvwPKG-zOH&iL(haFG9@lS;1Bb2bYu(! zD~^yy@7Vgsd@T201!`%8l-=@S*CYQj+oR#< znQG4TuekrYws$qyzUV^-xBJHQ3-W)x607NeKmEz@y^%`!i}^V3KM9uoTuVl5XY-5u zQ}(z9K)pu=q`Cvkzu@@WI5-+g6(`8OV~h`6e=FP)3&E8N($*_Xct6ZX%fe0Ek;f0| zoE&9;C#vts_nzcNZEFB^{g=3Z&TqzQAdY9rj9SKzBjV@FoYhd|c2;EHERlYB^?fyr z8gY(HpTqhi<%rKgo7ceAer4orIpa$c@uhB_1i>j62%LK%=ns6p#P458a5DFzh(DYk zdK8larY|p((8Y{DOT=Hz-!$mC>N=@u=q=12)_*5b(jn9J27xqI|HJzeCs|~GmHSPS znmAP8M;D#1x2eZADBxa`?oR%~{pCpi1m-%x;DMQB`j1SD|M;^+{Y$T(2f+Cahsnsz zj1O#|&WA-qgIFMS`%^I=N3!DJ*2ptt^(9Z`_lf(1;@T%b$e%J%eg)@`r(3Ruj@FmR z@fvCQ7w=sSzn)(rHscxJ*uK2IwFYW;UJ>~>fd0?Wird6_c~npz1>+O<|84kpk_(#N zL?xf4e10q`$w;MsPU@cq!6)vJuov@%@6SQ&cdtu2EQ!BIiZ-_p)-Ry_!I2wwK*qWn z@+v))$q$_m=>3fEKX@^WEIuNaT>pyLhA6cM4uE+l$dN`w+?yNCYX+MTFS`1~*#YAmOo^U;`Pswb8pdF&#Kf3f}u3XTJ#?$^mHw@6`J z$6CC9C0D%*w=gb{W@zOo-(P&bUG1|?+?z!;G>)$$3HH}Q{C=0c^Erc=4PoDCHjev$ z2i{k3^-J5ph6&RA@4ZX8e~#@`@}2d56+9b%Pn17SK=#eRIvvIqyd;&4yeHmuM7O-Apc<|e|~kF%9178&r_ESaC7}gyz?C_ z7~kUmXD@EH0d53*A>_|*b3y;3^WEdCcEG>q4XF7=W&Dfk1O6*_L5oI>XpJW0M~324 z()JDXXl_pRO_ls0|JPVs#x>KQME%40HTM7U70&O(##hk>$)i=~ceI+#fy)n05a-4@ z!uR3**PaC-;B0+al%L0ZbqZJx+FPy?`GqS2Ux4^(bgU~Ee=M46>Bb83!~f?gJ!Z-k z9n7LBiYrR_iuFt8Ai~Yg&;j=Y(){?3xy-d_-dDsA-hUL{w~||DYXRGJ+?Deq-v6E4 zzLuMv?g(YiMhoLI)Zb-drCw^}@clnSZm8_!l`={~uZYj$fYyc#e@l28Bm zjc}+{ecIY2&VsG~PNMuq-^Wym`UBP)>qzN>>qV{@)z3q z%%Y>xZnOD8`srtjYHGjTNu~c&ywU?+mz)yyXP2Y+=)!^!IA(KCB_D|y=G=$Vxm4{0 zvoBbFI`=KPe{>hMNpHyB56RDB@)T}IRxw?Yx1Ein{iE0QJh_&;Pt*Bd(uD5^6yNs# zzKLr$t`TUMrwZe8q~A_P=5wQOw}ri{rTJJAO1S&(Jz-UYx^c08ui;$A4gE0yZoO@# zd_VF3<;Rp=<^F{jtJH6&ZocHw3&+5X!P0z{1l4ls<6U5myEH#f&qu+lffc0g|Kd3R zKJ0A*H2U?4)SVB3`$sa;R)J@)YBDpA=`TS2O*3pVKx>Q|4Sf}DA=pRMKV;ZzJKWjU zlC~`f623nZ*~cq7Zy?dZo@RwA?H}@=?A>ap`rPTHad5O?fAIda7HwUjeW$a;)P(hy z;rd11!&(^n!Gk)sY#_)N=MV0*YQQz_?M?l9pB3KE63Kr;t_8O=VK1$DSf9xc@n=#x zh3he!(BcQ|`>_9b_2(SU!|VdxP{H_m>}?YVX@@_NCs!kc`NQ^c()!iV`sq*d!)2ER({JMa(>K%7 zpvCO^)XQ5cy9yf6#P86bu>tQ52v1qWMw3_!?|$oap>< zNy_&V=MVI5)k5W%`SempX?}+rci|K z=gAdrxkkqZG5%yoKYs0*&2^lm0WTA!_2b(#!d>bz5Vj3teB%DnhMnR;e*PO#Zx#vhd;T_b^TYWIwwiHWp)rxjo3`t-Ge zdlT#aA0p;&Q9&g)EPW<4(2<_s{mJU3&)$Z?4f7t#`4{_V0}cnnmF<<}bqR}q9Z~#y z=?;H>%&5;~!A{oShW*P!rE$>k;vaHrvs{>;ROFuzKN|=4uKyu_-RBD9cz>1W48A{m za}!$Ml<6OQ{`SyuP3c{$4?md zK>HWewGM*X%s#aBm#xA$wqIBI{V#Dg3&@FeQIh)0tD+X>AM~ez^;v!y+lMYu4Y@9J zBk9Ya^UC{+^E)FSP2gIeJ59e%1or;ue5`fLXL6?BuG6VESpLfr`Cs-a`J97ePw>6L z_`!Sy9VgtM$HSl|kd0&gF?ZBi&RyRE%7<$R&&T^~UcCzf1IG{KyN)y;cbuZ&?Yo~u zk-+k!xPQj>SRAN3s?j<=u>VthHy*AnsYexV8!QC>2JNr?c{T|SPiR6{KT^i`DE|m; z*23o18lwHvIDVZnY!gi1+@5MsC*l71|8Slycfqxp-Kd&6;}`q)?fCqpuHF)o-cwrs z!}45VS?~kWKb7g99OR$p&6vU6Exk=g_hb4O`!5=WGr9Kd@6yG3d)WNT#QHIQiVL^* z*gbl);+8Ou_}TM&GUuOZV9vHTXc&$mWLK}O|2m3&-y6$92=>QRG}>y+{l z@2?*4b|usls?)mtb#kO%CiD5Hf&q=Gw~4QEe#G`|-I^r0KEFB5b7TDA{LY7%40spZ zS|vY8^J-|Yb|9HLHAZs%>rHWi%Ab$Pt@cd*x~RY6mg8;MZ$5?gFK6{@OO$`QHc-Z0 z50%s9H-{+SU);YwYj!qw=w)XZ(UAGKSiV|o0${YpHzMyYU0)gK5Dxo0%IMTVtbZ8C zC;HbCpz)5TwCzroU%~aSpIrZ zqG_ST;FYxhyQ7N>|9`a#Qulu-L&Q&bb_edlu1(bH6N}$*{yXe|Gnd=&AvN90{1?2x z()__xZj|j~YWFi&nBN>^KL#(F!M*$Vl-@OE_s8|0#E&z%Tk>bLItM#j?)1jTG>iZI zLtNjE3tA5!t$WbaF|oq99OW-uqTX=78;3#OR%!V*y;4o%!(&zI=WDf2Fs@Z4d2}dM zxW5eL=iU_9aAsrf(VZ=hD&Jo$-_HxjaMK+g()j!}O8-Gzf6JXRp3}*DN?#dd3fJTF zPxtCif5yr88ooG3Y8}sBn9q8~wdA&G3oOaR`T3dc0M?sp;plkl1)=r(S zy21Q+?7z+T4uLiY8&fA8=D%Y9VOP~M*wD2p{kw6V@O(!k-;D{&;Y?6d>NRJgFpl^C zo*$J0jmo>w+zn9{EI%a9zem=jz~Eh7>64?`%5kxOxOYt&I0bj3TPCvpMN8BlKK92t zXuhHs)zM2=UN7!1?zC|WMB5nBAA@~__rv|+PruFJCYOJrgj(R9{|sHZ5rLoS zou|{-`a=1|ST36z^}0V8$mE;HS|%yN|HM?R>_YzfA(a7 z6SUBHPh1ihpZNTnhAnPEk5`N7vUaJ;?-R$L-KzdUvuP>xM5VO<+3u7(SVjLPwaHtB z`SU>bN!>dDPIqlWL;acmiS@(P!69(Ru^GMghV|!RexA84gP&>5solf6{D8QB!Y*qW zOe<YU!koE1Xx;vA z%n!M+9*oZE)BVZP{MfwChRFMa=#_Tf!t=5J>s&gTYqR4i-O`?&Z-LkMj`}WK5Bi;U zF8U{2FSih{-!T_lxS*ULG(L{;h4X9o4tsDbHEXHkKrJPI;`+#q8T+^|>#f1N0pkzn z2X>d%P{p{_q^5nGBwtHr-2p4-Kw6re&fX9CXM@ZGp~a-;^w=0_`|uHh!R%5CYVE}2 zkMl<-FY)`!)imf@9VUNlA709r!J0+O9t~w zJvuv1TK;a%8Q`p;Pb>16{=ogurupmP@4o?5bEUNWD`uH8RZ2^`HS^`S`%09 zUu7+QQpx0p{hM2>UAfeVzjWS+{*wBo^BZ@r`4$=EKCj2*i~Iw__8y#Wu?!+kc2r(3 zmcRF}H{7<@@z5o54!a)tH?AesG;K?wO8+$AQ~{J*jOG0+V)37TmLvODYu${?Te6*Y z+Iolaf%=#3%xKNkzqps4ODt24i~WyxQ`>MkU-PMDTjl;-)ITt$>3lfA*Omj$u=oY{ zf9;(T0KQ=@scw?A{`npd46!bn^iFlAz&GZt_C@+@Ah!&zOm9uwr)aVHLH)5o z{Qjq*H*Q~6J-B7g_{90o;(}Bz?o?lpXJ;t+6W53C z@%?Ep7tV$Qf28f-nC@@6mU*k7ZJ9K`Mj@Z+k4dQ{{cgOZ{#xJoApif^NwjdxbqnTS zh|lM2bGjD(?O#ue>{$I#j^g9nA2hk8p8M!2@?1GTV*BYIHVd;fSOMx2+S8or_1OJUerL*>6mVY9pT2Ii&_d8Z7UKF; z%|?EIZP5UFXCSK|;QrPjmT6Eg%7D%v<{(^eiS|$UK23uyHUsIu1=8y)r+Ef!K59t& zuQ;K6zL=j)Hf!PO5F=V(Ss;w#{@o+$S2*r=FnAfS68OjKBkxqB(pFcuL&?XU%Jm_R z?+hwy=
      V)I?vK8L3Nh4^_{{6F}lj%G zi!_)KHHb#oNX!4=pLA&RVX#R4IKO{n+gf<@dx$uHEEAvK9Xh3kem7dD(!c6q;mPlB zY)&sm?pMyg`1}VA&ACwWs0FS0&iZe#{hQV;00!J_PtWg`wtw5s2Ew|h9jI)Ew0t&n z42DYnY~Z0En0&4w`E+O*0+S|d(J+It!u#R%{f!@g%8zUIy~x%#+F$C|DFklL(xNBs zNXs|MBm}H{wP@mqKf?8zs6O|>Jp_VQYSEeB+Y8Uf{}(V!R!_g89<+@AxqfNULl?KdnA4%#YkcRNj}lsCz>A0u5T|F3n%(9`J_d^Qu$KU%-{J01YNPG=&k;057L+EAz2h06I8ukYhuz2MuhHuPwFY5n{6l|Ov- z)ls>=b*~0Mbkok%<>Ok(`5iPb2+nrsLiKvE^^Nm$FS3GQ`^YZTAgxTe-UF@Q&AmgQ zrBzodUvp1#e%rlDgoXWv(!jVpVSaQG|KHx%&{ff!RnC9ePIq``)S5;`7AxmR%;yS? z*)X|R8`{!spK@G0f1z!>;NF0Cbee^fhh}Hn(pja_^SgBHY_PlD zj=B=*`Te`l6Y7obpmP0lrxt;6tq%2B5G}|D&#&{B02q?lUFG_3x-|%FN_tSe@w&qN z;{EZ7PlI4lWe<`6n}_Vv#1_GzXrxE08Zi6fh~l$tErVfKV?CPl`HaA?Cfa}f)+`w6 z_0^+)ciS<(ko@%Q_;Eu$I(|pp&5> zAH4spgZpP{9Jqrt?vo&_Kiq$*o4o;c_Zd$sZCU({<-6P09d0z|<)dQ#DEiHTnV&n- zF;7{30{ed)c*2Ml+B98Pdi|)iT?CH3y3$@1tbT^;PuhI`FY&V;)v6vSd>@Wa1D6ND z$G>`F{fg|{fcpXPz_KS@U^`Lxen)h^SoNSFxMb0op;0dydglk5 zKjc5mw+ez}lV0@WX~tJ3TE7c}f&kq4{IIKml3#KEc71;Ty2iR*BK|57f64s$V%Hz{ zQpv|YbAJ3?FM8`1<0}>MMfL^5;^Dn%*y+6j|8gsFeP9UhAIC=brtyCnU%0>Tctt2Q zIMs(%x!)D8ceE1sKj-lO*Gf;aphc~Z3i84AMLVNpSQ=_Y17r6HnGEhpQ&kwJ*0o8 zwEjtbm;??RY-r~Xj2~RzeEl&AP8_nKYrPmhGGzb%zL^bYCU&7Fr%p=p(Ob_GoDI9u zdHfmmf_=3R+xLdcBgCZ=PldtWO@GQoiTXL!s$T13H%0 z6TTmx-`W4rXZr4LK8XmGUf=l(lOSRG80wJAM`WMcZ488ChYV=s1Gc^kk^W9N5eOC+4Jh1dE4)A6KRxOkAK%|HpzpTk3(rqQ z_Tz$K5d7{okgs1b{e;iA?Q9| z^NSW<4~B%vhIFU_(?8gLMU{r~``-tN^)os@$u8|P9kOn}NjSxd$z?q7Y(+pk<- zL%QG)^PjN&%IEt7cSIP{2|v#W{3Rg$G}SK<()tdfxu-S=N>cjhIrl$vq{Hro#zX}!xf!Fgv)X;aOU_Z-|{k)UU$FFUS z=%eY<{(t1NVCeYENW_;M@s)Zb1fmNDQ#zmd=h%NO81|W3{V7!G|NLv01b@sX(#lAt zALSO}{BS4!|DJ;kd(g;r(tOQo;R(Gy_M+RTGQNrtUwIXtFgmq2T^uFN&!N8aV3S>6 zI?jEkl3#It=1I5@>{&OEY9}!Ji1l9vuix|&2GhkqnSI0OOE%^G^S|2%)9KCb3;LxP z>8BO1`0M%kdrsz}(Xn%b$^*ti3|8jW!c(|i6-9@GCqZZHC#?Hnf{bz~l z4?$}J;b&iC8q=Y^u>SG+Y2CX9!J&=DBEGPHM0*Fp&>Ulte|8P=Wg8v@Z_15D{3IZL zxK%+g>#ea${zhnofEwSMuxdKv%NLz5@7N&}F5Vj|>Yu^&nH=9Q^jLKfvEEbHKP2|Q zhuIWDw~x`Ze-a4akL$C84BX*lbT5_psfnNFz;~~{BK{H(f4W(oFrc!pO8wTW{ak3% zydT|F?~sx|vHzC0!Us-|GNPxpOY?Vq74Kj597?bDmzG~*W&m^_G?XTHVEkeGc%mo( z&W#>Q7teDL_`~N@e>Mq(o%@HO3YYr3flZyCRf05@`XPBt|hxKo2Vh|V|97bCY zljdi~X+D4QXqYI!j_rGL?_jX#Go1R4XZ?9Nzwh)Y7_<%#rvpZh5%|IWk4<7Il>Z$; z-4f;t^M~u(2e*EvvfjtYrRl4M`N#PS``Ozd_n$wtH#{rcUxw^+<(fih+bfQ~za-6X zQHlq+dh1h@`_l2{qakxZx2PYD2<|VupCjV;=%%@_X_f&UbxNAg)Qj`rtKC4lWXdk# zdR$-e{I>)w-x$-2PSX5N+u{S>bBEB5Uw2A=pWbPIxU+pYZD`8)mLvbjyiEY)lnF$4tcUz~g~1Tz@1rZ^`l}c_@GK>_`x7{xp(0w`2U^|F@j^6$Cy#O=y<0p)kLg z&(~dpVX3tV|9?})XECz>CR3Neh0|uVtl>i8dfZ>AHvbEK5p;qq&`Ol#@8#P4aNubi zHArUpQQRMwJJTKVdiGaYAL--c0i$IDXn8$-;rY6VuTf3s!tOjn`p{aMuLpi};r=f} zT3b)rKDTgR47ZmJr8Yleg!^kE|1W>eVkin5O0V}~eBt^-f!rU)O*5gI7Sen@`Q#6= z2TVkKVf~psI{?l!F{Qpun10DY_DMTE0L%?dRr0m6Ng$}Dn9{(NlO*+Tm0=)^*>6hw z-B9|k==|R?!vjI9$W&B+Fhu^tmPLVZ=aDJB-aF9ZKm9F3{k^(AfpGJQDJ|z~&{F!n z(bhoN*3gVzU&;6{N9TJ?{Tc{5j6z?_ff)S)}u zKZgBR-`OXj$I}$LeLV9I@%hYwwqNMKW(pC%GL&DNI5P~o^%+GQxA0N&C$4Yy?&c23 zVFq-)bsy#Ti}yeM*|7+^qztFM-sTGPmw@^=AL%ZJywAhw=EsaboWF0~(if_9Olf}S zO~Um!zJJon541j-(vekth3Dh_4-pgnK)Z_>y|S#8FplHbli&x>mYebYIjO?^<(A_9 z-V%n{1;ucel{=U`!ly%(0hMY2z=xG zQ^n&z*z?DNW>#zz)-U!yyk`c%I}b~0SN&TUw?z4i!V^KTWWOaXE{_)CGo0UiO+rCe zXA})Q%JR2(eT*ykOka9aqCJB7x0ru>%S5m#aG?$_1OgEpLkFIN}cwfBF-n0h3he2uhira@OV6} zJHMq0`5(IL65;-Q4?19IvLJuFf4P1?H)!|5h-MGzEsW#-80az^c26BbPfTnpjB6tP z8s1+Bni-~a_~gdIIF3&m>3M_IbyIqFVze+WM|}BPECQ1fGg|)%;}`#5q4(t_F!X^1 z-50?4!~H2Gu1mqWmlfTyM;>Q|$t3 zGllIh!1;p~O+3KA`!ITRAoE`_pV2Z;h~74WHt4|gqc7s~;+y#p#_PBACh7uzx+wqh z$Y>$Vxo0k_&tX10Z}x_vO)Tm10>)<{@;^fImO%ZD)*?P}|KzxzKHy(8ih5-+KJ&1C z?7tNHKOIHC_%J@@h|lBUeo%bFmaed5{NVGEpQiXh?K4~Y!w*_&kEWfh znSRVf`q4{`_phx+(~Hqee_{V%aW{VmaT!gsof+SN^s}0$KkUvJE#mhFir?;~`@@@) zqec8?B7RSv_)0&PohKKXrb_bTWf}zDKkaz`jP>UM+P~q-*C%b9$I`zR*~0ajDF6GQ zmiIs94%B=}BSHQ-s6V&O@<@o-Fp1w^vr-tx`g6pUWT>j~rmGsIEBO)ouS34NffqNN zdhKWap&aq&GI%za~FEDNi zbThD3$zS$*AL!5jd$M-|;}7e{{^xzb!Fn`3;V#YJxOGb*plUQti)QoVi}d%1k$#Xi z&5qg|OY=E#0?+3>JCXgyd{TQqXtU6cnv7?BV*mK?W2z?bmXsr7XSG#I6ge<>JRpgV^!MkqusyKVYL@k>Nn5eV0eFJ0@eN- zV*cO#4N-k`8o$5L;H(2Z?Qlon(-QG}aef3GTQ`~3{lBjq>BnwuV*9)wcxV-Hg$TDD2(I%f7pWcy zcXyAW{l_xfvTl2{f_+uZcPa2ymsX4KRHT1#rvB| z&W6M72~%m^`APk))kO`Cvu?-2m5m-$JD>G8%MqXD_gBHR@eAn7Kk zs5fkOt?RE4^Q*bv4g6o2iS%m%(ywb9dBKzQ*3@~knk1k5CwoEReQR27I7k@Be9!P% z0Q!NW>9A2OzQgh_sagmN&yC@0xJ>`z^8>RtEruUm#?eG`#wWJ_RZV>$Y&PHj7R30( z`gian9~i1Nfu;sCKCyqgEXfyg)=d=ghyBMHTYbT4=R}qKIbP%S>p^=u&yML&Intk( ztNmd475;q1janA}=`UO#O5*MR{2%rz?e|DSK7ZHHfjVuI<}1<4A0pa1sH~4nNm~YQ zBB#(7R*MAr;QYK{PB=8woFU?`BjWGV{#q!n<Qh|jXNUVMCL zOPe=f{Necieh)9`-PM+Qzmw)SpxJyFTr`IM>nsp0OBS zFPcE#50>WhPuUXaduSrPu$b|Q^{3Tx9{~RRO;!4H3h%$R{Af?r*ZW)i#}D>TO?CX> z^)5%M^?>O|Z2!j&@P{26C#j5IvfTV(`I$-dcrWH3VEx9%S2Snw5w`EoeEi|_%}FA@ zas5i|1OID_DQdJzk${9r=Pj-)N)cORWD!PHw^do%xkcyYNIgE{@+KZp?weL!)U2 z?N!3Krj~*gHJ!k(&U>u!u>N5|BCqwA#2+NQGYe&_nX=xnA^sl?$_RF@gF~!-|L?j!NL#r zbYB<7uN?KiY?t|f{H&wMzs3BfRr^5U)=6|;64S3Z|CFt_6b@aULM zxS+LG*x!czo2V1lIOmk3aM2`5IWFG+Ubxm5BDE&de8Tw0`Gs*W{osS0vq*p9_$#r! zKR5?D)6;z!|Ar`jiyG<=-P4_E9siCfzIwW6IgBxMq3Ii>`Q4?@$46^i>GixgL4LTt zT0bxx8W*|Ik>C7;am@EM{U)4Q<7yh|$LgE-e5XxaTX0pHKj`O`()?~&)PifD`GbCY z<0jl6pFi4T`W#q(-;Vw|lOT-iBEJ8~=fJtYcJyO=#xJ(-Q+9a4q3Ut;R`yQi{l)zy z$N2p%vf6PXzRS`6<+h@~*{p)-ATgYk{? zpV_aMLb}Nmy5LH>;Qz_d`EEuZePLF=snooJ@r(7hi(((lzLiP+-JFE)$M(_JhU2Da z<-=zm>Gji*UgMfQDu#~Jq}NZ?Uq4u^H;pC~F#iItkM9Tg`0ng9dax7I|Cs+>4gv6b z+H^XxF3=yoKd^^(5Ul$(gC;I#=X2rpakJA3I2-IvhfiSn zC0t*4yj9NsA95}=9v>>qPY&{b>qj@?ma2cH>RX+a^C#B-6aMo3=S#;^-&6x(T#o9u z{x|19sqqAr`u*`@Pk3HBfzJEI?1Lp*KhHDgLhTuQs_oK%Js;_Jn~QT{?-zS|?QF#V z(e>SNJ$~>1FC-z!&W?-_vNOwGAv;Ohdqy@wGXgh4) za{+j_@4?2W`Xg$QJ^E@cgc)Bmb^q!IS7P4`6aB-f{)^#l2-gqP{=PEN8P8u^Qm=je z&B+-Le_jG*=lK4LCjR4}a%b#nwiFiijbZzPp8qpB;)0`l7=rUR`TNVHryKV6Tn5>{ zLbQ?-wj$Rx!+2Gy#JGE=!Hh3R>JXHzDzzcVt>cI^Tw;8<`Vo<`^a@%6CtwI zXD~P=>hMkfa~$dYpN{vM`=@yRqk2A|HRlJqKSr#v z#vSGhz;azz_Wv|KSpD1vHS!k1cdsbcPVKkI+4eY~b}`sDu|7NPW;ag*4 zC~U&>$JGAOOmf3LcZ|Uk`S}AG$^Z82=Z-gwSHS0soc~oxe$B+&9b4>O0cW~#{-@_> zq9=Lbx<2O6=^pq0=>77|u8Q|dBv?r97p46E_P~1VGTsKJL@6=(Ac-G`I0-`gRYx%X zjePw5DXkQql$2oNk+3@ZP|EL9I+@|n_69I3hsWP&{bE~d3tT&OLB03KXz#VeS8GK4 z4DQV4NBMK;VM`43St!A8G~suLiB@>F=^_|vET7-sw6euXCze3_>+b+2;%{A~GfpcvhV&F}-_ZET%9k#~ z$5_VCWyF4Yd(;&_y)%KHLwWr;#h1kyS8Vas1dKQE_#VY?&p~cD&3q+v>csJ@P2zjM z28i{CJuRX6hC2M|O5dMV9^r-h-K-?_Ulm0E&z-ggXZ5s(%`g3!{Ahe*)fDmW^LKWj zFpcAn-v2#sZxdk?{Dg>n-k;v@|4P#WwHGdeL%TEC_|*TquWN~GRxXyDKcW6#>riW4 zx@9R$`N8=skN9`bRcx?%8$;0j#O>oGk{^gUZiDlW8bZT3jvs2jm)x_(xGT%V`&F8< z`4td+9>}o6^hhH~ewgCxcryolEyl-{^<7y12%?|HEEEK%3rEqaM*jZ%Uf_sb<5$4- zEcy66Gs+pCd@+&WliCOFN-ntd+)4;q%}(L4bkK>j~~$ZT6g6tq49@D*rZxMzjY0-7XF)2in2xy zjQ?chexkH&GaOd9xZd+|mA=+^FvtjuuiG&B(){s;JvR6ub2+rgk&mx4@pkwuXoVy` zM&q|1w%gBZv6S#5lKREg8(neWWJ`&C>qF`j zi;Ght&4DSx%^=Z6oIykKZL*FRYVe@o6c6FR?bgcIuSm!R<%zX3&p^TbOS zJBq&#r$_QjAA3~^oxYdipibd(_3z41Qw*57wBGaMAtpsa*46@?;U#~3nPZippY;r1 znaLmDd4UziHZ+E#jjfq{seR#p(gwGinLzgnj$dm34T`kGfrCvY{tu0h#r<+XmjrV- zlRbfruTJoL?0^%#o+#?4HoX2(o5ar!e0Rc^;g(Qd$@A}2{-K+k@jq27$otLpvk&o) zzKQu`4Cxe)J*uTw~>iW23x|yR+!E&hYe0jX76{zG_JR_}4`nJnCWw!__yl`B8ku>Di%mrFp&l zXjJQnZkg6_GqZ2q`bha{#}g;K9BczsL*?VE^DSpwxYibiYecj4qwh=KDRV}Za9b#8 z#_cy5sozlg?2MDsY$f-{gb@Cmi!PXCZwEJ30@?U9zI#eMKdZFQ4%7#HVfdo@Z-lEG zrgn0GS&evoHpS0~d^gN=bO5Do)9cnxTA#f4ojVTP>IkbGczp`BFEd`P!dWrSAe-2c z^>-!sI{afJw%WA@dZu}@_V0xMqR%xIa#kqf(%m~)JH?Nzu&MCMSrPS;m$LJ(dV13P z7jzaE3FS+!VdQ4{{I#&nJK@ZV*Z6C&qg?$wVq#BWWmGr(nUc-EPw#hqy3h>IB&>jL z$5yiTXoA1~4rXX@a0N8-;P|KZ=e6Ee7{1C3mY=ArA0Y85g;93sw8cuof2PF0_>%5~ zotoLho!t}J_f-l1J^s%Ld)nHI`A=Toolf@ugcr^@f4&2_kKp(;CHywChYNPv>;V7X z|EBismbR|AG|*8}pH1z%#$xF4tizwK^#14%6Wr0` zxHG7=XwTQ5;Ai@54{UMC1)`1qWB5)d_MQG!Kh)^u3+HC-)cwm}wEjKxN&qJI^M`SV zf3f~Pq&}tgY?To7^fh)B-+`AGzp)pZ2sT3$F>+ZNpC7q@akZY3us%l-)ra3<7 z)<)s#!lhr`uwkEltUtY9uyKx=;MT_!Qx$Hq`O9Qd{?#&Fi4B&UfZOxfP*96?jNCF@W9 zYsU;H%>U*H`Qw+fcA7sindyur8BUV(2Na*PPdQ^uduMRX=lYNGpH6=loEGW~aeuge zRVVgclMybsEY2C;Et8LLV+%J7Ds+|9-&6Uo6yq=M+uR^Pjn~g-5q#DB@xyoD{NTwZ zjxYLt?d{|$p|G?P+dY<#p8!QAL8qk>w){^%ey(}-5VCLez%BXv+4@m@yjC?64h=HL zrg%g5FFq+gLS0O-{kN5%wU+Bw>VF2QnPKab=JoQ^g$?HDG{6!bPUZWT;>SbN3j4pe zhPHR-u=!E_@4UknFNfGe)~+$Eo%$EvhwZR1!vV(42w?5hzG=1E5m)*+Lzku;Up{32 zXZ&_Tb2V3}{Ir|>zbe6JnOOff^0+IgB=P#$EW&>;AGu)vChqWLIM<)51V7WKxT2|t zJM=mxA3wpGVtur!2jq48!S;6^!H4=L4~)IO8fx$cYe&K_BOLtD=D9zV_UHJ?BKB$j zS5?BN&((NgK!jZW+0tA|Sa!K7ZXULsuP@=B8>cjcIeq$IM~@oTPVZ0tsAVR2b+f|3 zZ{*|W`AHKjEHQ_LZ{*|W!Xk5wO}CcdBZu%y%5rnWJ=XQcmsM6<;g#2Ra5Z)=n;)&u zf0}HAhMJDh&Y#D3C_auow!;}g&X5A!f7K@XFXpxrZaU}=*$TY=&y?UNtd%pad+!d~ zoj5*n2tMXGx#Bk4)evUR@li(ZU*2=f6}^wHhI8c{A2fcqUaap(nBXNje^W;A(bCHk z!_KY)*ZKPxeq{u|s@m)ERjCi;d?;i1@gecy&HMfF;fWwfX`9LV=Mek^y{{5Rf2+aI z2J-Qv;r32A7xD?S?49J=Ki97WqjA%4(0aXzjZf{v%Jz}CE-4xeN4;V5ODFNi-ZPX0 z)%51*c11ou&F5$cLwEMY!#@u)`BVS()n1X`X4>N5nez2tsoP526(HK@_1rI0erYAv zlv)FH<@!TL^kb*)W*Dq*3qv=VvhQaR{7y&{{fjnE;{BlWSUc5UuLK*sZ0G_lZp+7K zTt8cUA=)Q**2w3-vZdnrvx+ZFOTJ}G~Vp6ZGg7Hhz#P(J>2 zSBv)fac?ka&Fv#<|K}C0!P3({pl7h3%a`EKy2b}B!UF+kXR!8Yg0Hj|f%xl9Cp;>(WY5ke2ow}eF+6Ob@ma_Gy?_W(^ zV@jtUe0&VG6z|tlv4iZF+&-fIU-3Fq>^s&TbQj6D&kF=IoUqjaip$K{_i6m1 zM~oE~=D5Jd1soqp?Asf5Hn=X^4Gt!8`-HAgPY@N|)@LH&8H-Po0{FQLZ1Nqb)`9T5z=o*WMvoa_(@->Vw2`MVN+>(VC} zf1HSfk1?Eo^hkUoxn&6Aktonw#Oup_bfxvX5%3e+{nrSGTkEj#Y5uiS|AsAK9nAp7UNjwu?QbOeQR&Ofe% ze>88I;ca(kiTITN9@8cY6T)Wrp|F^X;wWgo`+ClP$4?=VB%7H$%J(D+t!Lu))Y))RgX+{gM;eAMJx zV?nwn3~kN%huTNp7j3c0>owr6wwU!-qxBCH?Qo;ZT6lCszI|?zX^-(=yrIwHKCC~j z|C&?fh@qYvAY{~sI{hGhKVripXY7)+2^P$4Q`f(lq`toOSQku|`G7(;Uw?|Pu`A4k zCW~Ehu$_GVpSn#DTDQA}{X-M#>}P3x^oxu@9Ow;M$r`XM8O7RZe0)r%El!xX zu3rDEySF_KU$#LaUz%UP>@L=)I&FlbUEax+Z}LrNoY>YEj8}8{QvdB}jWZ7E>nq_8 zs-Lt>)}u*E2;`}+X7i`j_X z&2`xZdL}&n??de8cJ8Xe5Y?`@Bxo4>e?5{v^l82nKPA}1zxN9xCQ0#iF3%iao$!LM zTjcAHSqCk!_SzayZ$5&JPvbu&Q>?M-=sK8YxS6$6{gor;AD>U&P_O=YIn5qtboQwi zKhdF%m}u$?nzy)o*Ax7|jBrFRb6*L67!duCC-O(iK|cvUd?)eC3E^(oZAbvPPVKBd=GI^D86xh#f8n zQ=)F;sa5jv-DqB+5Zdnr3cq-KoZ|aXm$yRkiUxwiz<>2)()u0!84K{#VH>!)kMkQ6 z{if(;jxp`LAK^C}l);f5)XAhT;uCzY6!)|Lldv7DGdBO2#O89S^o((Pv z+60RYx&2Jz(|w=VVN+dS7}J33C(2*;%|!b|I{?ft^YvAlB)z}HwU0Zl_#6mvPdBmo z(foVI0q)r7TOf2%=Kc@GXKj%nOtQU)%H0#?>YwSiZwbX;Ut;4^eEq5a+giMz>FSSQ zP^|1yhd-%)ydc)snBEBig_hfO|KgLL53D}!g%`Sp!qIWgtiK+y5AVeU;=I0b;6AP) zYp3z4Y1<>P$$%7yu&QMIPVMW$jmko9|1S9O4#ywmr*4671^udqg3%WF_?ebIA9qLD z!8C7<9|gi+CgG-dCf6Hu?rYc0Uz&d!J;D;B-)w{iY4Y`-=|O8uDf5AdF43$%#ZND5 z8yr5%7xc3@e)33uEkfpqhVT6)`4j42)mS>BQojJ`rDe>eYW{VTs5!e7}PR-tEn2q>ziv3ANYaf?@B(~}`Ewjqx{Q2%s5fOx-w zbtqH_+`rNz{JCY159SPvhV{F7{RWk9x=tYKIK@Nui3aTdC_YZSjY5^UbcngZ_m2;W zj~yGHEAFGX!CCVF_k-mcKu;dKC(j)Za+#d&*CG@$+%*HwUl{ z;`k{c{BuEke`48(4KVZtKYwOG{2y2G{N(k+KK0_~r(lH_kN8UN@1XgIofg)Zsp<#5 zGLA2*AE(6H;lxURNO;cU7c{;(@{kj%%?W~WGHxGHd_0-#f~|CdK|5p}TR-X_>bCH} zulAv^`y%%*sQ=x%tp`>+hk|DtE(Q%-+iI zS3&Tp{yqv}dIns5%;ld>^wSpc{k6e)z3|RyKE90Tr&|ev;MV>Tt{)~}{vVtRh0mX> zu*X{Y_E)!t)q-r4qF|@>k3XgQ$-YB_{C2vng?&{E>-e{|#J^b6)e@82`+@y6j!%k@ z?m1TYsG+~){1(+Oy646FGgbV-C|bUL`f%L}FSPN8;>-J({HT5In{9)=1_nUkF%8~M z)<09M|2w}h5azbz_6POg|7f&y$CgvW zU`u-$>reI9m6h&jx+)C%ZsYi(@nyG7L1O)5GMvbhj}O}`f}nZz2~G%8%3WbA5 z-r>HzT)tHQ>6gD19%MBU4v&^E-?(#D=x#0AcX~b8{G-YGY2CL%#nk~|oyYl+?%({z z;{J^esCWOWx!7Xz??AZt`T&;?u}|ENIO68O5OD1@g|*Z8-n6++So2JLKfIp(J*C_k zor*#w`P3sOBlJf z2GeJA`BMHqrBW>zYd00#*2bGXX*UN5l^Ajx=F2a(Vp3vkb|33q=J}0Uy zupLl5);LNr2oiKSzxxpTbLCP8^c@-seT*it z@u~br1UTZASD~OVUcUa%-Q|Q+;=(|qGMDwI{BY)hc>i9XYhBAD1uPzlsB@g|I`-gqVZ!Ha^}zz<>jR(O1#-~UbH^RteIV8xjoaCOu+-M{}&>)SqN3xdjl7x?F%eEb;REEMch zzoPe?fA7ai^8;&~s)gy(lm)%t^6^t`SReNnxA@}^BhtWo503ke*P_8uaU%l7<aB)mO==M%^eB;`M*v zGdGSOs$Y6KR|{=#wh&x3{_&I4K746fBbaY#Dg5sqL%x5d{)tJGM)_l-y9nuMDA#_h zxN3%d&IQ9_d-?H;i9f{p)wLne%Zu}uE3r>*Rz~BPj00et`C;2ycZ1IiU)E0RCzcl! z3bEgQqF$_g{C1737OHGp3S}!eetpRM-X0=;TX%0IU~><-_+7oDVgBxmU4`qzGUm3WbiL^6_izVvbeoLnY^*D8KD36yFzJ76z){?b!P35cvk}Y$|9T=!4D9k7xSP zmE14VWUhwb)O{L;cj5X^M&j##@->7r2dCkVE?e06^nQfNje7~zf2QHH7I#=Xjo-UI zD2Gmun?nB-Uf+*|zZJ$=VcxiKXsEo9^{4OKToUcSkaOX1GjJ?xr~IsS%^G`*jDYR} z$3L|X!wu|lnOziw7W4W88ecLJ&nM{kM@!zvp!nZ*+6})qkA-Q49RJk6pCrEjeNN0z z6?EhHr~H~T*au-q3aG3sYMbnY&sVvBS3~T> z!v4Y7sVWl`)^hyQ`t$vtLd5%R_rUcI9RKwGrk?%H@zK68I66^&{4QCnA8U0r48~}1 z{-pN1*OUxwa^(`_&+5tKL*wTeb5(_niQ0H!4)^bAe6sI}f0_N4q-yi3smu`_Pl8w)qGIX-B7q-K#DreBPQNdr2u@wG|(Xk3LG25TgMbz>f%b|v;>+n?h5 zI%krgU~(YqpGWFjw7RaxdAm};c9=@t_|p1--J<-b=WmB8Z@B!UiGMTAJU~1jkO}if zN9g{Qk1LU%s(Sz?T+M`g8ym9mDL&GB2jkLlS@6t{|35vSoH1PxmW9<|qFz#+{U^1* zX5B6n9{g+|Br3<$wM+e%F@_;H<@{cl_KD+%-aj*9emb^ZQ~)WzIKR>R+gJQ(AUu@y z6yI2#!RAl(UubqYJS}TcuYc0>r#Uuh6$KAdI6i6p;Ou4=c(qehz5dA@4GVnLKMHgj z>#*-rd{wlt!5ul#;Jkz5E1K|6uy}v<{HF2s;%nG^XY6JY4?2GB+4z)STK0EGr;%SZtWZ>Y<*THcY*N^mk+1kDh zg*O!%Xw+^d>re6ZG^mmAIjcA3-J8z*6PaEciT|7ZzOAs~(O4|+F^To3`nCD14uVsL zE)JHRWA-17k6i9hBosO|61Lj#{X_k?yKO%RUs5^L5Hb2U*Zu*v(WfBcq-MRmR#Q!-V#*Z#1#z_1dYTun*?j*`50XBMZ{-FBx zjFl61pOpY#6Wg)xQ+(enaKoFuwo2|tpz)iCKa~k*K4_rQy0z^4 z)c)EZ*+5uV)C*sX9mnvgNAS7MQV^Usf59R9u7EpM>_g4<_?@w4;W9W!jFtX$PNb}Dd9qe((gLu%MwStXL^Mn24 zoUnCuB6Kb1_=+a}_b)NO9Na7k1}&G*pEfVt@wfdpN&PPMe_sz=jTfs@Ah18j2hA^a zyeh_b7NkP2t=o0~;wzf)uSY{~v{g%o>1CW>Y5dPyZ6n^joB_t}t=Ruj{#==}6TjXm zgmH6ueTD%!|GL^w%unZL!mUjlUr7XC-+K6A@!j1};>_`tL+}+bB>+cf?uDa2-RizC zjc=&W4n38OmuM4JCh)G@>)?Qm#3Bdu=!()yd9bF6WGNE}!M%E#}W!Q%Z*-QuCs zCN4i3pEr(iz#fW8FgIu=8=vMUqi;E)&VwYlZ!90*e+r$kXkapADe?F%&0n6l<%+33 z+u*&wFB_lMKPX4JV{TRobdK7m`xn2oK47M<7sg!N4&?*WSv&P#I)|)7tyD3;yVs3tEzcC2!6&L zX(W^+Yhj;hDQtc;ezqY~L74P-Aj+&vPXFCMNY2*}9aJow-`Z3tez~QNU!?v|P))V) z>V9XT#eMns%Z>OT=#Ay{-wzR3v8(`<`?34{@;M$ zv)4jvEMAxhVP80ZQGBMDI^m}dDR4%gpTDR0o8sk)QwODi^W{$L`;>o@1UK|;u^o=u zaek4J`n8!iJ+QrNI!x&$Uw=jpT!m|L(&21r02`m`-_ZGM@aFoR@UFiRYxg1c=@O5% zxLYq1tlx0`OY`#)<2K>0epxVQEXR)z(VvywmY_LC!t||N{&fFmEBWH;Hv3>>-TN}s z{;Tlu!yhfPL8U#{kI^JQ+ILw9&ia}QgU%|m`6o=0-Ve0cGz5SD$(8VzDZ%g5`{8); zU>@iszGwO~n(Qyvca4ObA%igM4WBh?C%}jKqgc zP0jGMb3D{`O%-`E3X z12S~~?r)m^+ka3)xZYx!$RYgy=>05B?rg%uk^3OQmE()@lS^aKKRCG`K0NTNTc0Kp z|1mMt4+ma50BxIhX6^KR{Z9zR!8=bt%0sT-%7}ie^4^U4s{!lw;XenV&Qn*{Y-TK zq%By9A0p!+Aa^Sp-*lpszj|qzkqY<$WO=NmYohIqGtwGHPt8sF<2Dc&!1E*&&=xcx-m*S?_ZhNW+Iz^he!eW`x^ z?c;{`+h@QJU(SE3g#V`crDMz7d*b_AoS&1({`GV6#B$L;eB6)YGl$@_GRX(EE3zf; zYnT%ItKh5;HtBo-%qltl(h0vQsrcf-&;zil2e0p?{i)$)J-=ac zAQ%_#KQ75%(D+OD5rQzPNkie++O2i?kj4iGv{`{pljC9Zi%c#blK*d#V1l*=3E-yA z@!>=8(RHsm?(e--qTjR$KCT2>p_;}vINqB3H?AbUdar|6-xjhBa;-RiXnlaoS39&B zomMY?HdieHqEjk&KsmOC7Qf(AUk>O=5z;g>&pcF2V! zo83(QG{1K6cmV$HcoepogfjV+5dD_u5{T-Zk3n(2Caj(2&vdnd(7VTRC#%D$4{82BZk=QkmxtcFQ(%ARaX>t!SEn1 zKgu7`FWm6d$X!r*kMjo-`@U6(7rGAE3(n~rAJo5c)=0*-FN+{I)2ra){kV1_IcR7Lr~a~=TB*V zA*$RL*9wPW)z)w(-vYu<-#Y|ilS#*+*N8ACADVyo(kTd?4xE6}7>*wUVjsng4nm8P z6VUoCmv0Wi_ZjUtyy1EcE?qjzzF$J(H}1{8Vrhw{ct6Cy_`dZ2)*fAfOSUAzrG4`8 z)p&y?R+y$jz$5;BS|4yBz)Czno+i;>H2<{flUQFO`bHs6tJwcj{u;Sky#J-&PB5;! zAB)DnT+0#=M%;q8%DjFphv=6@eeMX0j<*svPv`e%>yi2b>)~Evd}tr&v^v1nCx_tg z>f|*TX1O1(X7l(4eIMcQ?6nxtJsZ}K<^G{E$uCZv=!rZ|@G@aC!EOh=4k3|l~?7eYpd}?2p-~EkWL$$GR=^EBf<6loj{5Vx_mGDzK z;itixrdV-co1{LM+CMA4TVipy?e+R^Crcf0M~h5oH&niU((re}p<{MI%vc{jKf-U_ zwNh~GjS?_z!u`7tf}e9XYw_W!1EBBA?L$*ypNARxqNmAG*qG1v7mZI0Um1X1j^u%x zr+ocU8XSW5ndhKrCzmhHFW>DMiobmU)DLN~`P2A7yR1<3*F$LCI#u_t{X*mSs^h~j zw4DG+&o;Amnx8tlJsi_i&%=d6&Yx6&wWtlp>oMoy(8O%kUp7hl{&BzMEAYUuZ7`&O z^8=NyehV|aQJN~TZ=;F*qLycg>0*BEpMOs66Ip{8tP!q)t6LQNe;S`Dou7==ZA##G zGLL_o68UvqmVzd=4?(Sp-+$;s?jMPK_5<~94#NJX6WI9b6Q%rTqSZk7d1E-9G353c zt?xK;p@C4kYXoZb<@lociPKGNac4ya6lnAMH_C58pX@P8)Q`Ql@c1XypO?@0qSeXc zFla2VUojx~bFKBmE&+KEFesPFhvqNUKl^Pfo+Ceh-*` zP4QpzI}p>Ko&mq~rmR2ZuND_q;IfY?kh6xb54B$h>xAOmU;&hW$jA5W=uiw(%m-Vw zL2P`A?`DTWv1VvKxDMp_ru;h6Hw<0O&qG=JX!id!z9AbQfis?81eFN+_|73iE9;p!OHn4><(i0SBycsOwHh9<`eNUpnERJ-cmj zPFW@-)J|dT)PMV-4r!pHrPF>XHVuT9Pu zj%x3LFKQ1+@~_IIzG`5r)fnb-2)o9goV&_u;!O z_s`4px=P|lnX$F#Fm*WEdg!tFA+cZL0{+9!_9OAkSI)nbpBISr&*O}DK{Io1-%xy9 z&9xQpSKb5Px^Vl9?!R~09;jY*2*UJwvhV8=es)V(gPxmn;f(KO)=ur4PVd*?kfL0O zpTYS*hw#IYcfQ!Y>NGUpdxWhI<#*LzeyG3hER?Epey8{t_jLtc(cU46Z-x;0hDVC^ z;oWva;Yq$fXnbjkN(j!DU4%C4d3?x#;CrV>2&N=lgi>p6pHO_2ZWQmGi@yeGDjnJX zs}uWo{nZ$}<#HP|&*rfI(<1UWo0N>Uzn_B4WDjen@yo@B(lIXZ4VYf6^FK)ayrb1m z%yAuw{S>);ssA^7@E=SWJsL|VPG|F@`05#bGVP4ZvJBP_tBN!-@03|MZUrpeWAa?Xcj;6(UsQMEW2fcvZyR* zvVq%=6n{aA;{6uxhaf}wUwm46KfwFR?&A9vIk0(iAp1WB!ar$&{@C^nK=mL#KGhF8 zQOnV$DjnXnv|#=JzxaUG3VfrH0X2o3|MdvIK5h-ci@uk^uQR`Yyo|gb<2f@FCxsM1 zuk)P$Y5n}3=b`x6`3l5G1hDVZ^L1BehU1!`Yw$+FpRX_Bmmzi$IBWO~C>$&we>&eI zaA>oeaDDXw*1wGC7xM`T_@Lqu^lq_>wW|{UZl}%;%vtyr6tp?N()!+MsXs91@JM{M zvo8Nc&Tlw(t;M6NqcCZ{2me3fpOz%Y2{&dvz`~#M@pHV!5_>hslJJ))$vwxW# zWJC7b2sS>oFNf8N_g8i}40%TK@w4-uF@B%8Qxd;cC-QYJU4b{6WkShT8#cZv;jg2i z{?=!1N4BlG^%4PELab(9IJe@xd z%eSp(0?jL#lo!S=*%Y86vB|z(U|Lhm({q_a89p{+7g+YnjKB4u^ z`k}_yz&aE5rCYK8r|&eP47qI`Hr_Cvki}L())c5^^UB`2!!F9F4!g zo&BF|qBMU#d8tfLT%n8OHrMeh@n6R;iW9Ok9^)5<|JeMge)-@1fJN)~N$^AU`|jNi zm@3PGIPr|u-~XrhS<=Y^hn_qJM;~+hhT`Y=_w{%||16waIh*yT`OymV6s*>L18N=l z`XKSo2Za0M3)PFTqngW~>YvB0g7LlgRcP(R_dktqP2CiV?MK{{_DF|CSeFcx+iATv~F9wd?6g<)8Z?9NQNcfwd#oFFAx?nyEzKs-DHLXavVc z4ar|^iH*eQHFqTWNyPb&y*i-9bJyY6L!O+@f_bW!Vj*`e8l?we0U5C*#Fb} zn=a=0~WS!;fPviIP%0kiYbRk5a z;P_D^_-QmQ469}q!G{rP3_n!~b@(IxTdxt3 znDFv0q#WS?N9)7x-`|XLem;Q8xe9E3vdI4G|MV-Cv>uE5Zn<#$5dDPTzG7bQu_zlJ zQ`audU+RvC6M{U-@aq)$_}ZRkiQ^*~(tUvXi*1r+&fAc&7^Lq057(E}jx|UbqP;>5I zQTwAdT=b7MZ$Q-Jeyl&ezkT`FVDbFhEiiws%GwKw{ji}b6yG@(LtG~={}QtQOP__| zh3ebjIysp2Pbc*|+T~$5`Q2@BkLB{G{#{(3I4rg)hhD1OzgHsoySX=32={qbuYb|5 z+6YfL?~&whw8{Re)Dz!NynGPGz2p0z%5Tg(2NAzVVc2voAL@U!-{_2QN{++I1pm7A zQIz=SihikR-uMF)&P>+*t6yk-zV^shd~{?SzD*y``cr;e-1eQ|-+!c_bcfep(E8Sv zMjO$6>3NvaWEksTLip#`V?Vsq=L!s+yNtEd`18a?0ocm(8nmkA_$VOuhhcFbb}GC9 z(>%ESQAq617D~aWmUm0yAJg+Oi(SKTQ~SH{ry1Y>w0_`3LKyy7a2KZ5)%WKS{JgM_ z#6|@VAXPZS)-R9nLz6?1Xgcg6Xm{<#{?CWt^8-d=^1O#ox%VLJPyL(V=oq|YPzEWk zN~}MP|EldOiZeYj&gj__~G5(`?2v)1^oVk=XYp*W9R0L zg==%?;K8HZzNPg)GjdTdIo?*#zr0OueTP%nZK1h=hHy>&-~AR+`>j*k#n>!<7o7jf z*H3k#bp4L&ZonB+F2MIML-_g<{7${N2{%u@1apV-`BVF+^8r81Id&C3-{tXTR}!BI zpB{k5lWxGde%$~2PVkM50&$nqP1vYt%DzwSx0{)vsCMS#rNUsoI3oI`uZcTv4TbOm-YHbo%a~wY~_8D{2}!}lUiA#cj94KHc7tz zu|DsB$-)WfJZdxhKgwT^hl%x<0p}ojv@&a_{$;|f&8Ts)6z1BW)BVd|G(W5{Di)&} zzJwRMczjNW@N?Ric-+474b+}*#l}}9_T5ChEzE;n!i6>R@pG}$1{}ZpA}Dkn%KB6L zJNm5;s(W04SAr{Rr}2@e4gq+i#VvT3&gD<}P32Y?7R-DA#&5a&q6zyal-;- z6-VloZx1C$tcg4cW@os3X?(sw%No_?Wg~6>hLV(0eBzzthF{MOOS0AY}`;Z>W8KIo}J%DxHTB z`#3(zNc^VzWnb(XeI4#q@c0z9KX;4m-^KRP;vF@A_lGh$zdi4E2$p@i4=F{dx_{gC z2)-hIMB>b8WnkZrkek-~FdM&yCUr6Nt=(0bai!FlJtvEiY{+KW!0FN#zhMO8Z z{zdJd6I+*|k=+4U9+||xPwT4#Y%TDO=P@uB&jA0$2em(U-WBt2=4W7;a&%pLV~Ksa zw__9@wkn5E6ONw>62BcaGZy_HRDzMN7VA&XA7-}Sio521hI_+0vi5Y6Ke&258Lz8- zgY-}?KOZ8$=VJS3vHkPyEZx8JcP01^Kb4LKW-{@NX$oskC-=k1gxkXF2K@v#)qm%^ zr1ry~XC8R@zkHZxI+4wUo&fQiZis`#>pZ4eH*w1PdN;`O^KZd2}rr zT)YgKsr>$N8o&D5G8m7BmcZlt+&`rLwWm%nj=Ww1-GA`>B+Xx6@(RH%B@dyz@mw}P zZDQYaii$+-Vb3Ao|14V{>i@LWT!`b+_tuO5b}bFD^3VY=(Mn|F)BBHhjIqG`HOIlx zTRy(7xkO{qyVp>ip25CP@4s`=+=4^$Di(?%Ycr*Hwhqj>(5#@}^IJuv;`1@IZk`NNg)hpxL9dgfdPUrmlL z${%~X1Y^6+4`I|Op8ufnUH|D~`@M(IZTf6Bf7FxauMDEw3RA;e@QxmDmy!C+Pqp)L z$gjQd`FbkrUq<|sTUAT3&BudqWu|<57`3&)F_ZJaD?vU!^ag}t%(o{ncRsg|C_W-i zMBw_8=V1RjoPFPv*x%{@Z5HoWeFN8aas81*?4xd#G1z?dTX@kQ;c)TC5=eCvV&B8%>dm50~sV!nda`Sg>X$Yp3h`r^-^8 zJLx30ys}F7FTcrTY7+hxmO0`#8A3&S&JWZ-J8!#MeE;>bJYIP_c*S2k7~mF<#MVTu}v62B0n*pWw$mD*?CZeuc7oe11Lzf3ByJF{k-| zkTssaUrGI6qxclGXf4Bk=QC*hP_ZBdkBpOHALD)O`)x`7GfDd+F8MVT&&_dU|F1{l zi^CHf@zN_nyn>3aFO46ErFh{e?Q0VKMB@Xux~#{CwKu_F5RdOr`*mvX4VeDm7G!VW z`a6felx&p<@=%AFwQSj{@s5s!GnKt zp!=N!HogxzKXz%fITi$;lK3w)|I+1oFcybBg*&$bSbrq(!9C*pGYRRh;qw@-AL;#z zHI|z(QTr`;|LVp1)AOB&3O8fdS8t(D>%+Q#@k7tI=zK}S8FPL?Rv&J^^dj=@_v#~_ z>oo)QE1lT*RKBZ=KjU?niP>TQ{41&c=_$V7@pk5U*i^*jPx;}Lf*1O0U6<_t5MqCJ zUFeHS&F{g;93KCr=ffVZ^}{iL?u+pyZvRqzWN-09!+s@T>tM|0Pwl6nr#}n&ZD$FS z#`v=M4&^_EhV${5;{mYW%;ld>_J4Per8uMJ2q|8`Z0#ATn}K))<5e`+6H8WoAkV=AF?A-8{NecZ*$L|knC3rbS= zF!|H_ui}-G#q-a9ptP2s@1pmoUEffHrRCG{L{}bvlM(wj_UT6qdNC6-Eu7i>sec>$ z;}f2b@Kl4+mm1L+-!ZUn8EE28vmVNV2(*U&%mCZe1B2@z-W~t{;IqH zg^GNADZbvDcw(i^4LCoM>lex|L02|lQ{lGc{2>zlNZ4Y4i{~DMXY;xIeTe+qcUg-4 zKIBUHpUQtOnB&Gknnc^>VX#ysB3VH8K2s zPpUumo5!QZq*_>?o6P1%?Vm^UMg8>XCw$D`&BoUv{1OxT9>c?C;Bap)ABr!vV;}In z*(~%t(v*##PV7I!lOOT?gxRPizVXcL6QX}~SAW5*=s6O6(ff^d&vC>TBQJqh5Bd1{ z(|t95F1i7(CJ}6WYMWJ_UnB5dcr}#QG|)}<*~RZ_B$kWKF|KYkk~ga_hPY&%?~J_dz7_P{I2*Ai{bGJ7qZXMpE7PrSG?Ox&00!56#3on-$srQTz=%>VOYNU9MNZ zRee~619fk~VK4dk>AJ`d&%AsL>gOePty6)wfYBwtW5r3O-~q`DhaU zSa~@XWja5hhb6}c_0P|3h{qE{e#0l(#X9*)>pN6W$K#Zg-|)HnTedc3tT{n&Y2^lLR6pZZr< z3(c{%mjGWIa{GenzwlNLxX82sLVUS>MdO#NrmV(c21WJ8_soh@@!(>`dhxM1wn!Lu zbg0nzqx|@D+GUme+2=fj;>&t+>(_?+8(>`M5zy<$hi5@{bU4R zwUhmDd`>B7+VK5B^S9Rq`eUP6WpHl@kKa@O@91fN%$xK~Qa?ubkL@*o9B=Xr4sYQ5 zCxr0ZUb`TC`S~S0%9oGdAGbrX|A#6meu;mnb|(h6e*FQbmT>&i_`%QeEx5GkCuF?H zt;3h}eAOqLc)Z_LhB_TNerbLsN_;LDK=Cx<$qZkMZ|`BpwYEbYa6_4JD2 zQ#9wNbYg#>6ysM9aup=_&msCr2h&h}t`gSP)#sHFetCGMNH{!bxX{}`etfg#!1*{j z`luwoEF=2s%J~iW((fT$u?S-Ls37u*EcV6iN1uXmJh$(ue(e|+faiA20jP<%Eksr-(b(^&sBlGUS_1)ZlqV}!!h*(T_ z_zl1HxqhVgmrt6Rh#dvUCRnhxR%S`FQoM!ZlmU7@8-wB zGnwbtDSigM_r?YA0Q_~if8B-H$F(j#xT)z=m{Dt3hYx9f(D$`Jb{+W=c6Z?Vjq=Nw z)&V%o?`6I9$quK&u}AMuu=z6IUsV59-?0|hn<^S)`3~}GvGtluH$B&P$ z^!^Z+9cCz8x&RLja{q$bZ`W_y($qgI*E^u zgx?Mh4#J-rRSi*?Ns=x9? z{ipn0hFz9$ekvgOvz*znIAuu#Jfk&)%|Dvx*9E&`F>iMRls(|~AI<;Sy-mbj8yaJm zq5SFcmb>37 z?lojR<@IS)zioW(kEX#DAQbrU@d-YLDg@w~{0iv!ljpyw|FG_90OroEgp92`KS1^4 zs~J%^$KWS4Q|!aWr}4+1iqW{(^EVhx5_IM1$BX_kI3!kvu?gHhsvz?3S{8$8uVm*8hYLytD6@B?&kQV@uQ*}$+-KQ zl0^T}`o)hQ((#YK3Wl6fX8%v)7uw}cf{%4E4vKA5$1l?O=#?|Gap&}7@O1PZ*58N7 z-))mOt~D!#Ez`LFjl@1%cghDh=DmO;QP4H|8aKW7wy zi<^A;KK>Sk+xGni!wAk#^nTn+S7UM6sYZCQ8`ppIexfHSDHwLXIey#2^%t!VT68QE z(=^(kx^`Q(K9qj~`dJHK``o~Dd*$y z1ckZWf1>tz>+Jz}@p84~{2$F9yNVAazsIq{g+%%I=<}>vXmx#&P`O1ue|D?-B1~*# zEEwODkDsfy3i-Wj9RJ_)2sQvBjYlolu6-(mFG=CMW z6^6@yeghq^u5A4bh<=h;hGWX8TJW^w_BoA@j=mU$+eeD|wKF_ETSDqr8vcpGV-7N` zPk%Nr-GcLj8sXTLTz}H|m-*9e_)u3FS6Og;783nd?7dHzqu)_DIaxlw(w7wrIrGO0 z13M(wt)EoCr7F(GkF!p|z8||eeh7aJo$QT!_dkPe`#FEr5dKnWu?{`0%O&SKsD2wW z*bm<{u7dx>H%|WY6Rj@`63@RIySxQueO}*2^`DMq0B-I49&(WDFKWLBg=Avf@V00^ zyPo~IrGwCWM+j!$;Q4);pSU6$E<6j)z=OjVv-!znQhYsb@J?7UcZsm$p?v%rwE8M+ zO;{nUR|}}y-_rNTbcUJYuO`VxzCpA33_UitXk15gL*V`pyyB*E( z%Kb3bPV3)yUfqUEMzp|#?i`;;@R=^+b5wjM;e)??e7?Fc3tw5})r-HJ7T%cE<2gLJ zARm9_r@gV+h369dxf1@HI7@v0@WWdeIFj=l)sOb~{IJEhYS41!_@n%`$kQK(_IM9> z>h4#}Bl)%&E4woN8*ngmJ|z< zUQQ4mER?^0^}2r*{%l++EH;#nzwNhHV&gv7p>PZ5N2*^JR@!3tkvsMBqr!nuEID2a zBU8^X`KOck{vy9{Ebj3el$ZBl`-k%9>F!bZ)~5j~26KL-_w&8giO1*Nl>eCN2n1zcQo&?QhoZqN@ZZ~W#&in7V z#6F|%Yc2}%#>lZR;m#Xwzti~CDUf3PZ`pd}u1k+`!sl&SblqeHGLK8+NJ)3hq{=XN<0bSNxRtkP<$Gyt;Ndlm+=4S`tGUekQ?hlb&;7-K$ht9?au^EeJl}UULw(^jd=7`nx>-+7H@4W01#I zVd*7nVJuYRx5TGRuyqd1 zh9`e2!+Th=?+YRPZlI8YoOKn-M~XzB{!00OjTKpVv{oCv$~pf7!DqhSa`f3=3nBM-e1o2ka!C>Gvx6Z< zcdNoDIiK3uf3lGA?k-}VxmDp$dOkE^WG~e2a8zl~j_XJ2e|)i+gjqH2D$6c#{89OS zhA51wc==C!>UqsUZ1;D{l*(c3`>FnPd8k0G)K8N0Ewui@cXK=f4L&Q^p5XB}T0aEQ ze>wiUR1zOi5d1DM-6}M_R8N?5MK%6*?7lAa+|otZGN}4|n3NyKuKgfPJ>x6nC-V3t zjsKj!?1$60t|(7Oa{N*KSYRdghn@aQxiLsJ{w{n@f!F6s<(W>ytJX(aKU>fy6}@)K z@UQynZJ7(8SzJS6UupceMp_0|7HYzyC6CWge1%-fzy~!g^sYKzkWcDQPxvoGUwcDI z{3L|f-!3bbL$kjTE(db_QGU4Z>Quqw@NF)-QZ%3)YYyUm+Hr!r-NZN z`rbeBH@0OI-nhS(*l(Kux;#A&ZyJA6-u=SQUsHVbnHY}*k-zmU3SjF`?^he{u?~Ur zE#dd5HXEn@|2x?YA!jW%|+- z#MhM}x-YNqqV})b{dAbSX<%YQu75HKzn>`f$1(QSz_D_rC+GLl{8m7R4AhO$Lgb0w z?ECD9eovKWBW}1Zs{8XEBKTM{cQH04>Z7mTX7+rVUwGEEjd1e9R(L88^YtVBck2$H zC|LHri$t|3HlOBCc4SNyrZ;_zA4#h5le5?lllokf@LMW>7n~=dQTzktg5(_b`&56e z>N^ux+rCkDJImus)W3Z!UxD4)Ca_U*e9MXb-~SwywF`( zuPNq9;{F#HruCOmC;Sj0i1&|F)d$e{eP#bx$ka=e6@58=>G_>?A7hb`SE5|CjN2!g zzi9L-8Bf&zC}Xw`uKIqdewkvOf_vM=`0U2IY}|<0$8GmganPp*x~}5~8?!pAO=^5xTB#m4%D>{?hzLhHMTZI+Q3o)*r#1--7s$I{o5s zG^$itb28^o#U#Ju-60E2X6fSfhid;o+TR9|i_vMh0jleBX@7~lYs;|cnlZY2a(vPL z5`jzC;M1@=uv}}*-jDV_^KElO_?_BQcoLx+U*@Zl@laESqWRqZQ2o*Oelp^`WXSx% z@j?0d4e|c#M$gnyo&U@w_H}-%bOc6fqDLu@FVOv~E6c!)7CH!WHem1XP4q|1q(!)& zs*8{#oc|OP{&U4K3*$WXP`vt-=U;r(C-)QF30?x1U_;Cp&-puzKlpw0!-3T|CGlmd zA8a=U<7xWP4BXLx$->=pWH2#{Yz6=LTj4_~s`=9iF(5sU|g*F3UqUSUn zmG*6Z%Nv53QEy?v9@YET-g^$(MwCkWOVj#eqbqYUH@iZqyC;~fubkkwZEPaq-~Cp4 zzU29HIoZF9$w{#J@<(|r(wxng5&1vxI2oRO#r$1PwSOViAFqq%;fq`yJIA(T^Ycl6 zxJ6UM{yV2Mp_9V#LGwR`V*f7pG;N3hKDNJ9fB0|7fcJ-*Xm*P87mANl!D4=CgC0)o zH(|g3n&7Lwu8Gj{b{foVlG!+|A2k}=QfTC~4ehje{EXI*kJR^vna6Eq|35rGLG|-2 zyI?G6U95aLnd67X@5-Jd09 z`#XG<^heoD^poP|T=bY&shn%g_urfB|MCd2fBA+#%KSi6wmwuptbLvg;|}Uboj0Ru zT}a>5@TUra?yQUCwYsODEv{Fo)BVf1A!RQHdh_-GKe5Y~HZ zLT1PJpVnV}oRf*#hxPEZ3D=MG{N9vdt%NA29cUV}h`k@(-+ldV2(vHr5i$(8e?aZ? z?M;S-+X_;JX-#`n$*(kjb>O!@W)&1EPYvMpZ?wMeKwJ>QoS!H^*5&x1{NrJ#2$59gM}qQLetStpg&f%|2Jjy z4WXS~KcTO;>hF)fJO_DW%KnM3gD(?Md$<^Xp3C`TCdp4u6Z5(U%>O9!;&}ZX#h>}v zxro-6;b~jWuc?1tbTkPrm1^jn6T* zFL#wkTXB3)`*ZK`L_|10RSwvl&7M#3p))xfw^kXV^H=BH;xag zKV}wh!@%-}u)F5O=gXw;|EpO9{I-4ir+zBC9E}3+Z^|QwxO`K7U^aOUdVl)vcr1s~act4`&29bY^ZqDA%i0F?uCP^?Hr4GBp+&(FYeQG;54YRN5NcNxl zzix-jgw$DC=pptf{wp7pKQ$|M5dy|GfbjgS0_%7Jjj7}sy|{iXHG zrfRux8)b&>dVxpAD_zpGrS<5BB`cM1S8ZnuB123Q7NnOu{dE>L(zgwHnrj@%^Rx-NY~f{o1Nw zbH|D7`9(y357TuNjCI$FJ;qP6ahXgSe@oYCB3v`thBEycRpV0oTYC0};B7rfm@##g zO8+|cjz8ADf23@l$oG%(x8;FKkG|{t8{(-op2f=BL~JPRG2F z`tV86WAih~{sf8rQG!MpAg}@7U#g#aHq6GiH72M&-$(n;nMN*0c5N$MJ#x|WFFxq~ zTWx*AarxU9iGNG;1J_FCz~k(1W#`az_I?Vof0lz4Nbe!TgV|%*IE^2iY8H=^jnv>V zAfAo4ApFtYG69yB>UiMG?SC%8k6XtS917GCYXCd3`LsV@+k^h7J+)Zb^%&nDsy~PK z2*QW1Z^ZL;s`n@0`+OL?i21<`NA`RJYRXj98N3Fdj4I%ViF$<9h{4yYE~#o;r5Hh-XUfQ)s_~K1E(lu^#rhyu z)%JDt#5A$C)Bwr5xqQ?83mcmQTWt$mw&&|l`!AZe9V5K*dVwp^zuEiI_`t9J8igjK zlZE2!X;t<`njas0Mcki_Ka>WhoWE23>(gmAX1mK!-M^Ij=iOE+5IC}iM88t`v^_Q# z#;dh(K5rU(KYhZF+)u5Mb=x!_|2INTg zhmJSe{#|%vIY-bH^Q3>DPyOd@Q~Ys2_k}V=yuSip>6yo zoU&WTexL5|&5CA1s^MOYTegsm%Vg5}t?nh`g)Ud#VPm(tRo^e=C#Hr$NNo5~={rF+ zK0S`kK!aK3%A5WiACzBT&X2*Qk7}sy??>gg%gfbRV^bd%oeJ3c6p;An&3FE=v3;d1 z3dm#cPuJhdcrIc}weWLS690ap|37R^LbKg9VbeH*jZ^=6;kaa&M~Lz5Jv={ome>dT zU#ZyJ*H9vVAo2TaHEo4qXV#%b7=J%nf2Zu&R9KX@2PuKx{QW$o@^x7Bk3R-~`se!o zemMhHBP*14kNEl)kov@5=OWQ}@*m~MbMx5qseKF^I2&u~iSf%gu7BkueyQP;i}Pda zVM6f*&%gMh{eR-mF2k#LHW*vZ`Hzh7k9+%9AnU6g+`2VozfaHa*1fVC?|U>r_;9|z z0c3we{U!*nettm8C)N1-66}u^y04Wd8}ap}`)@sJE?PC#!Twp?K4+5sZ(){*Hzhi7 zd(Go3)c-6RGauu#Y9VaT82$3_UZq&z= z=GWNoQ+(!#_umDtOUCj-7ykRCzVLWAf4HWQM?`e)jIq3!xu7;n`?-poKY9|T`T$+@_& z)fR32I6mn4+?QAZ0~<%Y-^ukSy`SxeA`esEIU?oC6;F;&Tge9=E6m5ns783*+MIts z;Rh~qf9yAZr~I~$>lca-%`pmGzNCe~=G_0M`elcGDyH=}hE*x|pJ{%;@m(s$HZ(y+ za~>a{@g?t)RD5eM)<{Q+b$ zQ_1&#>0~D?&)5w8q&EEfiT!bW>>xZHxeb;_QdQ#bz>=GSeWJe**KLhT{MF0vjH62~ zDUWCG=IvG(0p%o{eYCe)oE`d)S9&kdk(Z@^J)Em*9&qq z{CrXQC}tObKH0w^&HXX%?0cng&6RAN+TWKE6EW`kH)VF3>ir!wbviyLRVwq;cz&vc z@R!M%Q3#fc^*h#4?D;hRKH-UYKlI0Xc+f<~#uY?t7Px{Do0p-v85oYU~|@1%0(pUH_ay;!lCD z$yi(45a|^o+56M`nTNMYhJGDGynQ!|jnngS8@DH;+j4PSm*dBq`1i#R7C;_u0k@|- zKUhTKb8j`Rghln&Bio+igVyhQ1zHKF^TjoCbzu5KE|=<$k6YvzI{32kh?3(&LGUrI zmOom!e^fT`;`pHYQ?KnroNe)4*?yyHeB{VNkTOMv(&ro>XDL4VFGRNz3&afL_{}8v z--2w|J*$W9pDWn=Q+!+(>l%wJ9C35SF}A<7K7ZG?Wq3WJKBlW*X5+N}V)>ty&^C33 z-Pc`gT;VCb-%-|~1S@ANP=6Bl&uRU1f&4c%rp|-as5~}bCYRo?m$z9aY!mMQib{>* z`dcoI|E~Q#TBtwt143OZl+3=7`m)p;Q3&d;i383YKbwhuYT{Tu2(xf@stpRLx3Jqq@-=gSEHF}+?#c&@nt$D-|2;`em( zhQg@1dl7cEik}kxHFLlZp-;CY!RKbGN`9VnL8H(qd!bNN8pg)y`8@d?IpjfCl#QNn z`H*=@?O*$|elRWgq-;K#%Lmn;ZyhGW=JO9_%QDsSp>=Nw8V`5Cl6hRe(fGRMz@;$1 z?|>H9G^_9-wO?&xmtm7<1H6rE%*JW_tzBv!x-V;lnTda-Zx_Q5_)#4{zi|7! znaJmXd9#qZSqnK{-2d<<_&WA84#Dkpai#&+Payu|lBe+q_0h+=n%sY*{z>Bg1Xy?& zz-JQo->7~J3`j(Yxgn-$4rAX(`PG&+iSY0@gwd6De0_-i{I+=$dfsq@UZ;DWf90zM ziNE+OfFwt6@%LAD-v4!`lacs0yz2Q<{Hc8N)JV{97 z???2T@u_$;sWgzppXmO+5bJ{)78oLD^b9ut5V5auUWw>;&PY=Ku21eCzZss0XX?ht z@o&%OQ~bSdl!UhzjS&#Q`K5xyuY7~kMB8VH!s&ZG|Kf+%53PO)9G^BAukUbtQ2cBf zVJ;|6uZM32k00if_}10V7Q%o3Z9t_Vw-3~Q7s~yh_T`Im%o~oM0Mh?p$My+GoB3Pm zuq2m#AH|Pt%2G@ScEW?RynhIdFYcO@EB60sh!~%mY(9-2?RuVzu#$$j?Zojx>o2#P z-oTgL6R~vhb+$er_AmQ}m2mgS7W8Rzls%v7XI}$5;ZWi(l0HI{`TSL}b-{|=Xrd?FtUA|qgBp$(gjTz}B`%GHYs+$%MJ?=V;P`$a@QZJ(9^ zs|$t@%BthT()^g3dlDLznBb9FG@DP)htwAP`y}d^!Xw6>jZ^+z>?;$l_gsK_zc_x1 ziGJCBQYMT)x&WuZvwH);Y`d1*ym+ct*`X_OwKqzm|yy) zTokd2jZ=PQ^?W?$4iW1^8*_Zwk^1?cKT>(=v@5S-w2i8IsUx8r2K2?+gx;XbH?W@$JzW8501Z>-CB=Y-|s_&QLBuyUQp!F?YJ?5ek#%SAlD4Q=Q>o@kqTx9e#!N;xb*f>4k7T|6m^j({WT}dgP zf7e$gt0N)MG0n|{+Swc6u#)?SG`?EweM^}AV2ZH8X+6{L`NTgsa^jw_;7yotYs7i> z`!eF+?%6OJ@6yVYlQcPggjK*&{{%HS~!%cE=FvS@s9&r2x z5d6usffo~pz|M>F2YP>b(;N3O?0Pu7b`O9U7sIkl@Z=evpHKYb{=E|6cfU4{t?$5|Py3%8z4jhUYb0W9 z36Bp^`?#j!GaNr9qg~>%s`Zod|ATAwg<1|Pp+BYy-*PFwkM%JYd?&0$vvzga@6-HI z>8R0|RO5#-!k**Pj^Hz9RT7-XiuI8>quG3VKS_ggIhZIoiFb%|{Tf2}(?P{j*gSH^ z5p|BA5Q3km4NK8R#|5vq^kvVd@y9<`mg0R|7w9~?#J)eD@UN#Ql~}T5D30~y_@nhB z+jEPsu_z2buJiaD^*^5uG!=SW+kkOK4Z!y8|h|lB2+?Nc3Y#Dn$YG0NF zgkWU377pIy{D|6j*NAX@_o*qtH}y~E*HU0mEhAVNa{GRk*!Rmx%P^r?6NIck!PcMF zSJt!0LoeIrI9a6Hzt?kmha=^4@ji4Zn{VeO#qXltUlH4EKJI$&W8-piK2YLu5obbU78Q{d)LBaC!2XX{7fN6o(~(8IzQHkmv=K>L&2Fq?}T z>9wI77s2M|6MikkCZl4u1zMct@$~{?pQi85gtgoe)-|o!e0sk~_BDNB&a_pyv#?5j ziG7NCW+XH*T8G;Yt=N1jzY9m02u}~MM|wMsA6h?jv!SW*<-d*Saziz~JzjaB*P1)Z zV_Q_?v*+m^=w10lqF*UKYuSZ}_cLls;x`n3^D1Y+;zdn-J#7dgR`3r@qRPsFS5?k^MRAbi}zy>68)2fW^8>Zf9xXGf3H~45U+D;u<;b4 zf4rA1#Vz;768lHvGl{iUpkeFgs8s`=fBC~z!mqZLufVEqEhO>VOj3Vfm-Q7g@s8|Q z%T(ig<24OoPv0fzIc^PmKIOMjJN1Ne@s3wZ7uEPU=Q|n$+y7D?exX`_+a5{8yb|4|Aj^- z!j7m7=x(nXpSC)tLe$|+IQd&OJ}n1&z-e%i#J{2Xb766JoErC38DqcYZ8HGWUW&B3a1MiP9M5dAricGx-e1Y^LH+9mZ&tvuiz{LbIe#!B_zUf| z4$0Tsi8)fvzi9ne|DE5^>}eW&yY6Str~0?!8()kYP@&v;PBp$7Z5oH}`_&P4LACxh z+mZ;YeijHn%<)I#tGD+gLNVL|M%R3+@F|T?SsEnaw_t&>v$_1z^UrekEbOb_5P8Nt ze^*5Cxvnwtqaw&MK3j_7CIOaR-O(XVy{-%m%a#eDVl_;mOV!*4O+hwCF{f==gb*xp~o$4UHP^IBgt-uqjkKaB|g zZMJnTWL6e1?>dX`FR}j{FD0R5WgR%I;r3s@vlPGgy3WV!-Swc*C}h81Lf+4-Xlj`Rh_s3#tin@5dfyei$|LcEo3eqR*VEz*>KNP>e(nImOgC1V4=J5sUzb&5= z0h>hz=-$SQ?H}zAvUou>qBD&!P|5j+oZ!3Bk7(pvF~Xw>P1t;@-`_ll!HSQ@Fii<& z<3^;u*lp|_%Y>e_))&tE}kzvskWMp%Lx99KkY|U zhd~(EY&m;AwGYkj975rSA>t+R{Qc?qji8Q3g2CR6`2Kw;n_n!ql*C_ZL>mhpPMZ4Ztp2#?L$pe z_a{)0_-N9{5LjQ)L-qa66kk0=e633s>pQP=d{O@N@pu&eL>i$$#^W!Ugdg+?nT5em zj9|X27W;l`|1oNjSlikNb^N(})BLPfo5cuz-2~n~7ny$=;3bWpZ1i4^qhDHLdotgj zLj+$gJ}WUgsSPfkzrps0>Zj+?fAD8?4ob$U#+T3YiNdHXEy3xT>i!Hr*9^p+J71LF zd#+*MmrwAQTz3>q+We9DcU1qjxEzO)?WPj{jLN6u%|uL0x5D}1vF!OYzI@a55Pl39 z3UgQf{R(ovNNca55a+lFircF3DLm?kcLN_t@>i69&d%rt+p8}n{FCBueZN2)66?#V z^AA+NMTqw&X=c_$b$^urg1?#CA+T$t51pSpz8*s2Qy~cvI4jowubRf|AL#k<>6@Z( zz{eOSQ#t-G-NGJP@SKo{mb+8GV$zPL-cpA$JX};;rFKu7GayMGopMrK56{1 zT)7C2U!C!28Rusjou%>Xp}Vp$*SInCcb{kYqw$>%{d3S*))d7C=NZ293BJ3|ErXSD zCOn>Ven;zHel3|Gq-@g?Qktp8XI}4tXi@%Ef=`*3^nMA=@R6t`_J8TSdnNmRicc%o z80du8M)mzpl;4kaRlxp-nWVnpD&Y?vFH_(*$qxPdaehGWR}V`}#n4d>cpbZ$eSa?b z{=gM!(A?^XkhA=LI_lrLeMrYpu|6Z@4(DH)WdBB{AH-gbVF<3lmR!RLw7{N+|U?Z4|Qd~PwPkgYDS^e z6JuPh&*f7=>_eF>8tsj1BhSx>%`YPSVM5X(WEQ$0_Ys%B7KA@1yqqE|7k!w5{sw$~ zNqxuUwgcfizf9@AhU;e|g8%vz!;viBkNG4fuWJ1?B=&o+Nj%p668*dTJpWANW5$`O z_!#1d^){UUP<|VEI$i8f?F7ZZPYmCb-zu~ZBH-jOls(_+`IrAt{cX8TfZM!r==>qI zYFrv$?BI3^wX!DS{CSRFkoaOs_;-{qUxbvQoF9Yu2fK|cU@GOrt5aQDJ1<>(U}ztnzc*Bpo1`^57{ z4LE*fBtO(QeiHVt)y2UUS^W9LesqkV25n;lxD4X>rSZ33;{E4SFB`&lF86PW$^E<6>cL zw*S=somrw$IO=PjFy)eJ{jfSiyq|i^cZvR%6a2pDKOC*5$;30*s`1-OEgC&*nc`~e z-faC$iT_r-IvR(knIe6wF&n4+EO2Kc{tK)Jzlu0Eon{I(*>dKjBe z`vbn~YaujVxfgH0Ok?jaC-|)~-a;@vvKOtZ;ycv;dwjSfdM_(h&SNGNb!4I?2meFfZjjxyJN>x%!oI@wbEqvel$LDq*n-9SQ(;XZAUgv_3QhGp@=m$ z!oprrY@Fiz*`f^8$#=mKNZ8f4QnFo)3DfT;jQty&p*aNAEvxc1Xy_C?B;8e)!;>qm;e=F!1;_CODzKDGV7S3tu@Cd^*`JZhj%%3Q0yMY=F15_7yBe5Da9UkKDuligx~i1@Ci+d zGjORVk6%##;J8CM7ML!<m2+ROD5J>Ph&MJ8VDXo{j$oIiRK{4QR-2$w^f!|Ap4d|Y+O$GSN0)GVb$(~7}U#^J)g$U0~Xr}UE~7x`6se* z$`9sQcSWD8@0AzgRO`=82fQ&UtwQPl-&!`G@`GItq39W7jIoj2K7jC_L*o6hHT6xA za+KHK(D==XVY4tN%N#uq1hMDS{x5TDMdM@*3%t%UVdKR_|C$CTVu*_!EEj08af;uq zlYYWu!xH4J=lG=Yy*-LQnCrJ3mur9V^9a8&l26gO5wk_n-K!FBoKP z#j<`?_?AiIb9$v65cB!jKlQKmB_9-B7yF~m5V*IO888LDln@|0(#yo+JbbUv?or0T>rTQU&=!dnsA@IH- z*4H_Eu=%uq#3Qp%)QvWgobSme_^)3$11%buLOzJ=ZyG;Z`7{C=v&<0tEs#B*;=iGI zesc84I>_3^^YheyO{*spobRqc@b^<@=&EFCz0Wm5d=ckYNQcU~w5 z`tD)BPx--_mVU^erH$(TVibQpw+Er7K`m6@-$?N{OJ@oUoQ)*>liL4h&*x&{20K)K z5n?Y!D&hxMQ6%c+{RzDM6OPVA99gmNJ;5Wu*5l%F8#ew5T*nEXt zdOvdM+7oCoEC@fMIew{q`*`XE2F3^Bn3HP%;nVG#2>Te1%*Gtw^nR>Uaka(zlD#mF z-p|&T)+e7_+XYWuJ}E1eT>nyh+tnO|GO_=DJ=YCvKE=20q)uPw;eGujPnc1e?LEz3Co0)V*KWt=imLM=lAk;4TRF7?Fdcf`c>g6)vte!bU>e7 zFO?B>RO2_k;SkK;B<9De`g_s%R=wfZ%i1{!DD!?urSC-2N93e5R^r;a>k%xRrO5&8PLp&*QSOt!Znt zouu0TsdN>f)_5vzhpOfeg`EoFIcpkz+*ZwhE6&sv^y(=wW$@c7|3P}b@%*&TFmLlo zS$nnW{J2B#6cmmyM&fSHuUZiOd3{VM)MHI?(|k6=2gT>%-=UaSYzj*QCpLbF#P8nr z49C*J=15-Kjg1!*ewKGU5>JaQ{>guTERVyt=z3^#C!Ec1LHO@=1DUY@?n<$L{`|G`}Lxgm?BbQ zeW~jHwS!~Ig%MaTl!*7F^Zk+bXUVQZ`jq)=q(%*IQ+r2g-;6<(Nj_>*!`<#x7y zcBH=J-lbkhYFnDLndN%0-o+8cUp)R6Ll^DFBAYP27UAR|ruxys`Q z0R-RjX#x0{tB2u7IlpZ|;;*O8=VPOf3)})vdH&sBsy{D0PKD9(Ca`R2!M;C;oWF2R z%*4X~T4BjUZr^GAz;JmcCO>P1Aio-HK8=sx9(Ee*{32i-uNvRaI#~;EoePmNN5SUP z_};kX<&WxXGW;L z|B}{kq%@d|9wV9;^f*oXj#bP50szIbQ19?v->AL=juE{TCY@Oy({zlyMEMv-eC3~ zJH#4Fv-``~IMq+>)Bd0!ay4XmRrn_7BW^~thyCO?%EtS7e1YQIR@WP^UZ}yZ(R%j% z6yJNF_#j+E?2l6w-=X+EFn0`YH8ha$hX8`_#&HX9+rky<8QlM({B_Q)Ok5k?8j*vz z{-pWeRr^ojVADu!AFCRlhHhuELX5FLs=@IuBk}L}VtwI)RssAkas5l<*OOxE2vf?G zcsF7-`~G}Vzu%#rO<}a=8KLsCYW+I5ha8>DN|g8Nas5i`=aN%;V)~X}$|85JUt17- zyX^`>_cO+l{xSuGUs(+m>zC|Ik$r{ZoBC(vyF)Q3N9=FibHXG$ccO5onKi2KC!q1)r2EkrHoG3OrcGz-NBMJE(=2>2cZZv$ zHXBzE{+FKp8iB7CA>nqeC)Xd+_|H7=cjzYGQNORaze;{~#7idhv|ocRS)4!1h<kbEy!|KsM;!G=-3B#KGMV$25E9?K_QD6gMVgZQ55>Q?mp^_i)W>0OuHO{||DVPC z!F0N}l*IQB5q>hW;563i&qCl09{;8FqyEqn?qU}-r&QsW#1B8bs3TZIfTdkqw!Siw z|1PgtSJ>3*B(&Ul{0ao$8^>!DPPnmAxGBux`CT&qmA4%EF{R4Rt5oCL(Yz<>udYzm zuA>^?>rV&4=77SqXr-DzELD%d#m!czOl`u}kH(i3>d_egvYw>>2+eN{YvPS{ zi)%>yQ;MG@t%ktrp%!#LaDL!T_(72G5FGxlg}Uw;?DsrzA-4f|au74^1rj+Xnhu-djdrQ^$YCYddxN!RC*$#~sy!)s8C2jIVuU=my^%qos?kMho7iMCArlG3w zrPv&VQ44BI&My@c{pr1YDvHjSqsggM_I?y!@3u}ymaQc$HMoCH_1pYOVVElBw>DaI zXY*-(;#_t(+6}HN!4LJ{`ZSNk5`SxGEt$*aD+oRZPM?WhE$U&_kjYi=C*`m6=f8&7 zybPvwx&5c{#k*#2VQ@SL7t{Kw)Q>Cge8=TwE0Jk7*OTd2az5xmayv}h{$7%Qp#0#y z`2cu`{V`eva(_ir&M|5 z*jDy^w7zKUkRFJ9Tlr7@c`G0oy>-oSz2*`&|0=#=c~KX~3T3>o*Wa3-DOo9fq*G2xgp#9C6nPy3(UJ{keHhV`I-sae(UOV3w* zw0n%Q^o5vS^QY%u{K-lDvDfb}2r|io#?ymU<8>wbU$4?v*gM2PaOr8o?USc8|2^!W zM&W?zTZBegaeSQEuaK8Eg*VF13r>xjaQ~#U)IT2O(I1aBHDGg<`*&1-m&Xr9;_RAe z*LM;7zFeZ8JLHW(yA(aty~FVlLiD@a(K*PR=zyEvk!=1|5`UR>FCI00oG^5SCL5>q zP5b}MN3@nJbUJ=ksox)0rXqVtOLXqQ@lWe#47JYSu2n4hEj!HCH=pq1+AGS@#W!En zU!`nZM*N4)zjTDsxLvqAkIM(;&)T2r2*+og#(x*NeUK4;(fOH;aN)%TXnp4LLGy2; zUbe*!zYqV6FD*G5 zw)>7vj;nFAKG*+pQh&Cy#8>ccTuabhs#?A_?b0aB57{cz)=;RFufiWTh4cDf6#A~` z@})uKt5NfQ&}*WB*6LiosQu__I|_3`4DeWc16v=;uQ!Pet{ej!pw<~4Kc@K+dyRNR zbaX(VW`%qBO9Ug1M{AiW`NaG`| z{Kn$8mkAzDTE*Uv`X8yara*JAC7hOW|Ag9)jIgOVwz>|kuB*@HhYYu0j{jqU@CRQpq|DpDw#5uDU|;ocC{|`M(8+%W&Y8RQ`*J{QJMI zEo^rL%;X#&RDZu3>4E0UzAJ0_srLU;I(ElYD>X5Prdt1A+&Tuox0~RF6~`y_Z@iNy z;QD(r?16+a9%q#q9U#{na6@#Q2EP9;sFJyE0fl>XRr-CVx!7MX>>6$zoX>ur_RrJb{!3W8e4Vhl@nVL5>VN%tYEx)-;IiP- zN40#s&FP1idRh{GPvd`YyNy7Dw+0Bi!Sy%gH~rR(g1f>H_lnV9Sh@edZ07P zHF^Ap@|$t(QxUV#O~PMj|Cri6QW0^`4VJOr82_R1qo$KnA-r;f^#RTwWrSaLDL)1e z{h2VSmCx3f*1v7`DZ}Pf`FPrp+ea!NvRAc*|N03SvX#pR2*25DG+GF#Ya}GjwB`1Z z@YAGo?wHuSr1_bZR^8CbMGYkmo7w)$N&IkV?gR{YVlL^Q zK>gpQF_RD%R|g#zbYkaV@)`w z4z|Nii`r~lLF$u!{tn0PMRr)6p2)^&fAX9)7ci!45|-Fzdj7>fNd3&9!|tfD>GMDB zr|zWwh>z07@+X`>Q2nf>J{anYbz$9LCHsAPe_UBjADro-hk?GCRpV0s^^IXPTKsa9 z^v9#}{r-CbG=4Ug)DISu`i<*<<{|b(OT@JJ!0?+%;-AldrQo!&8}|F0;ondE*Aqpl zSeD%e9pu&gPRjqz+&qHI+aqA^$?G#H|2x&L49k|RfxHvPx6Dg=zNV+Uuds89kucUs zHGaEo@_@qfm*o5{#pjyV-SDu6I!+(s_@w+>@n8y$TUblZH`4g>hPqP`-`QGne^MsF zSIx0g(JagwPF_5IRzmpus~VxGcx8j~;KpqKiV1#yzX(OWcw0>B#Pc)x1fNRpaJbdC zM`2ZcAdS!D+&crWCkbe~mibmm@(w)M8UE;ZZA^vS+d)q>{!`B3@ux4yrhw$&5^Zn5+ zO$VPYZe+ht_50>ZZ{+LgqWbdHjXq_hJ523|UwYWuG~IY5aRyc_^%s>?G$$sDF9#br|9r+DrO_1Q2|8x;z69 zPTEWE@1^|Q%_tmKO6(>2m*RWn;772G%Et0#br`;7G7J9k;{STz>IkcEUBF3O&TlEc z9}RR6PHW!5>gDNd|0zE?(A7zB>i+<(uRdhs6#tjCDug86O~RlFOH}d~gN+)6;~wr3 z1_!9d{}?md!j&2~gz!ro|M~>~3o5$e>2Y-oDChc#`cI~&{gF|wgI(cVKB)aTJ!l|; z-Si~+A1WWGauU&MU<*nAg+oOD{|*rASM1#ob@Dya|C@>aUwUpHF70wd*#VA!Il=$x zd#PCUuq~`M9A)!mq<^4%-8Xb-v<_JVxPAxW_d}kyL0G{T$^91;-zLT)zH@&o$Nb^^ zgW~&jhA(X1n&5K;ug~!&@;~#!BrMrsjpNyTJfG<2Zr7(E#@Ggrs`~rrll~rCj!r}C zF}9e{k;hL8i2g5KI2{d2ZBaR(2g47Qk0;kp!enLw7Cm0T@Js8*mj>U5ZD~obt1kn6AKMFgeG0X&H!A1i z-o6&N8Nv1cSt1{w(vq<2R!fWv;PL&lL_R+2eZ!qg>m>SHLGbe+$5eqJmtaT z2h#h6zgV~x z|8_(^Mj1?i@kA>O>&X3o>fdS>O~$4PHdyN&!=6v$gT^zb!Zpbj-Dfmn<1|0Hv3&~e z&257_0h~Xk5dAS|?RoTmJ`a8SaehtfM;1)Ji9s0)q3E&All!02`1`}Y_n@_i$Oo|x zYd$>|`@=55hN}AkY5ux%yruAP(naxn508&g`4P5g6du#uBit`ljsKR~wuOBXZV7qG z&6$0m`n_SDeyFUhiM#E%{-*q9Q=&Jt{q-gKo8sT6^E4zH+e!2f&7bsN8iI{G?6G!P zFSh7A%H)*q(;TMGeopP=aUVCm8zRX;zl3#c|)+js@wpS>goxsNP3BQil zwJlu!;1d1E*g7hIHT>% zdR6oFCH(KWR{|!?Zh`cCo=-&!5-|MJt{$enRuJPZ~T%%co25GxHqVADVxS zDS9sUj#-X`q06eqrSadCH(zkjZUg$uIlrOuu{V2|V0y_|ke#f-_K)h9{AO)1yzBRW z;y>KGBNjdXqugf0^*_xoxogSMYoR*c&Ex!+;(y8qU(|kL28#|H|3(D=JHp1n$)PS@ z3L$KLseP?jJ`Ua8Xp~w!bk4GaWvGD*RUrB|bs5!kptf%t$8LdBYIUNb7PYuyBtPYz`?ZehJ z3f$__9C;x+Y@D9&)7yF%9)>yp=g>a50tu0-7)M#Lh%n}~Ir}k&N?s$w}YAvxp`J_JQ)B0p= z-0F_XCaUF2dq*JQ0iYt$BsSKPmYTzdbbPTB$F)|~~nl0BZBze@W@ zmj1YaQ`6HV@=4Dh&c0$PbU1qz3Hvy{ss0Q9;UxGCd5)OTCT#s=GO7QurCWvIov>Zd z@2Fb7cBW_)PVco}DBGu6zFKVWjU5kl5qgyWzMRwt-Rm|5<3#>6p=mev`!xQ%ZuAt` zoUn)6>4j{Z`hSPxLg72I0os_fsG2XWFEKKjflo7>B=IN8zaBeALTgncs1M}wRY2l@ zUy|d|b+0S7Hstn=`X{Ch?&82=seH+ae;7RbDJ~g{@>5m6O8w8->R-?^eItCkaQh`A z@-y~}8=gn}kmLub{1_K>z*H?Y{L4RyJUkf9yBQ<1KbH?0pNLeB!W8j-9@}>-*!t1@ z@b_60uyVc)`o;774fRhpJ(z%yD>kq^5LvZ9()?{dpCGv3wZ+rho^1RO(VzFl{s^nK z*r9VM_m3&RZmySvWgA2rJ)NI_p#FLWq5N={yb=x9Umk2fg1gH+(#1zy``Uy#9#Be=j|mi0o)PiTu#~$W-xs zd%rJslKMVcUo?F5Tm+12ji*03zB5Vx1rzc9g^0Aa_-f1LgXW)Zztj?pyBtBP+EBK? zv_D1d&^p3*mz#LJiTl^ozW84A!t3r@hz{WKDT@CCM|vWwy&kI1r&IhJnuH*szY{V? zb9~eIcEgb&xE}8$$uC-Vmii~(Uc_Mk^yWzQiDUSs_iHR~7l(D?`ID%pN|pExo*W1B z4zBoW#`zW1|2Py6cS|>D+~@YWfUNJEL$}b`I0wD&ZfDP@@kN(`cQC$%R6bg-CK7%|>jPZH z`0c~g$kNiq8m1GT z+&)P8(|;>}!R^pa98|7hN@qCkD&-FX??`nnj!i6k-3BRHKL!;{hkn1e! z?@pY5((j-8c05iv+F@wb{SqN0J|5O87=2?MU~9R6eLwXN>XioLm3aSP_4#!g|10P? z71?7ONc)#taXoXR6za;#L;&=Gww$N{{hWxy(e0@oOqei(NxH0eF``^#r7t3_4B>43v`oFn$ zAUdnr!f!|ze?IXa2J8`ghkUR@Y#j$SUO@79MR&)ewyr(=`|$b_Y9BPc6tH$}g(t_r z)|c|5f%fr82y;W%6hW{hz6S*5-9ECY3p&X&cV(i%5Q_zR@%^`{sm-YrWa}(ELvM z&oJzXbCKj1sDJ!+&McgC74`r4*=#=5|JEI1VBOdiZ+~(9u$l0ed8cAg|4&QYUdZ)7 z^{?HwT}SrjZ1{iW@ehjcMLnE^TUu{${;og!eR_X+uh$jAIq%)VY2)Q8;}>IJYZR7_ zJ0eUUmB_}634gg&*9~^le@pbU!c(fB2dr(2jT-8xS&!>y1;O{ZcB3$^mlZa4(x*Z#*`1a^B0lRxS zhX-K;Gy9i_cN}_M!b-R3>derw0eve9A9wEprmSJ$#D^ zL&vb+SCIRA?MJo5pw1P_8ubgR#wFV;^L1^9uk~x7y1tX*X8}6GThPRU0v^Ak_R-?p zK;(@!#fD_n{)?mINOX&^LY)R&{w)c<>NWR8{Fl1_jNceW1>$oT`+wr^oH8Ckv)!Sd z#QASNiGQAbwhIg1{2N~;Atz8&l8nlcJbx@B^*#Gn0!I>3pkC`LTYuW0#oRQD>Xt5o}czOM!#@ltJQpIOcJhw_K3P7|@^i&%da(}0bG*bnQq z!Kibx0rVg8^`-Tx{pw9c>wb;kJ2r^TZ$aXdcfL)>mH-!Y^ccX#Y5(~>y(7@4YcrVY zTC?%4L_W4piNS!VR+9Qo$`3}qevT`Sa&$X;3b-M^P}a$n!q(;v@Y*X!K(bD#4**Y&=}xemuSjqh*LS%ffC zE0h@U{0ohL7(Ln#ql((`KV?}VaBT@1KDo-)r;MEc+3Z+P81nom9#jqG>qqe2=9)A5 zsjK4gOs*d&KOT@g0d<3Wp!F6P_WhZJpWZT^2-o5ssIDB%r3M2(S+YF?-&8200X>;=jWrBlKtaS5CzZK#z|CL7g zL+h+TSl_BOK91q}dz!xt-{6m5-Nmy*?uz$Erw9A-Wa?~*eW(7ffwz+I{8T=U2knq? z|4kYnT5M5Yunswal8X8~zb%)Z-jb|?8&5}cz5!Oe{uiHZBr)JqgCel}pdobQe%It*rRQh+_|C$y z9ma_6!tqV{N9jl%VR3^>v`!6V-$(gt0~ZrC)Tx7V9mV)LAz0#(O#}R^U#I-x^~!;G zKD8AbCjG;Q^n6T#rXRXA=!A%F|LmW%{#x~1G)$*hA!6k}d`ROX?XN9Fr?1v{(72p^ zKRy5QL_Y@Ye%Xq5gw@24iGO7KyZ~qGEXEzZ%M5?izF+881(O5082#}?ja+KK!tVaU znf8a#!)7~^Q~xyOO-8~+F6fS_MLfP)M(kJQ<8kO`uPeEK zCXMLNCVJyBF-jLN>Tvx|^QRW&lf?X9ZwbGq{hN&aCc|4pALS)HKS%w;Un{2JrPx0< zV)_rZzKu!!a94|&X!Ft-c_n;((un?UVq++L9`qZRm&{`GL-E~gguAR;{rB66rb0YjKj^>x+u}OX0d|JHaL08GldCvL^<$mniO@3D!^K#G zn(@;7Ve#!rVtu#11aY3nw^q7Y45SfDs#t*mzoBy(q^(nEmEAlvEYtcV&WqTxKs28#}GexgqBY4tQ3U(eW}c<58M zKT8NcKg1k^l7UjQr{-cbX|5xk(5OtKr`@O%-mofi~ zS_#E70&?tB5fwe2hHEw zOgWFe!`H#}t73dyO?Zrvn|EMTwx^8YgZO_dOdbm!W;=w{v(uUVOe5zbU->^4?hM%> z>~E#ZcR_IvFgE3}PKhR(c7-4482&TN@zrL<{!+X#K+0 ze$&z3&=lQ29%u8LLhSS94Uq``Vuts9>(z{x>d*JtbD`rauKygq{z}AucPc-L0j&}+ zT75cuKFyDqA3hJW$VA)==Jwr-^nY#pqKEKyMimU3oM!K*_B|=|k)XY8htT?gUk(41 z;y)(%nb3S#rl9P(OX2=<*lva4KWoQF?;pw! zoRTxKp=a&>`^t!4$niOb{`EQjY5cU~q&k95FTk_MX*Pcp|4Z)G6Wp(yLU(x{_uokU zXYwyQj2qfaf^Vw-1DCr%DZ3>Ws&jro_5btIAdFeiU2^~S3u51!2&1rbPEX{Ta{SZ! z&CA!s`14{he^A38sQ!3#Xgs<%HNa3q4Yt1LiT~c;cml#F7$9PSCzI3j19vt}z@K9V zlKM7k|9`fdjIF)J7{1*xHh)xqTfdl!i-SzDzvI9BiZs4BIV=(?^(=5bpW~nAFLb`2 z#4Kg;j?n%!_$Ky$&4IIUE?I|$erwqKLG)W;|Etj7xB>fLas5W`H#mQ|hv1R_9V>?_ z#{a86h})36mQU`?1~K z3fDI^LElA+_2;}T10d6GS8IGL(AWoeowaM-AKC69&|9R7wWqlMP4Q!E7LAN>8T@5D zK0))ZD|M9ww@F19zFcv9HTO{yp+WjJybaT3_@Vx*_U67=a$FU@4Y+?w`LX=DGhBO! z{WWfL{ZIGDp;MzUXM8V-ey9FZbKB7{U#_yIJ7mD|%w0+wd*A8uD&!_yS=XyINpHjt7eO~`S@o}=m34(DeoNmPNLHWUv%YmrK z>VeB&c>b5JfBBmrvA>%x26SA;-cR{!*!^JCbLuJf&*uAs=0`_bk4B@+-pK9C`2($A zdAn^i9IB-FN+a>9oKfQu^~6w8A4cnYZ+Dyu%SUF=+Nl^H!Mam1s=^Gj4{`n=C-vE% z)=k9;D{~y*VZ*+U@{>=xC(*`yEmjXvtUuj0o<>HiL>Lto%Kq|aEy52Lm7m6u{)sr= zSTX(_G_K*E<|YY0r1A49dN-jvYYXlVf6Sgw&xg$nuNDk$6bXA0wkp)0gT@%6{tfYd z({YE{_fdT2XIsL#s41qO>V)pcB`x zw7yaEKRX!RRzqhUu0KKg-!D7V4DUb1scDqTq{6n)mmuVD8~1Ux@Vwil7wmI9KU6RA9yBT z!NMyW(a4$eKRJm%Y`pVSte?w5TxVY2K>1YqGv^}LY$Q89mLw7d^q)N53${_g#0Am;t( zh>bSuYvxy)zgSr>0FNznaafn*`#j;F3l;^#=Swft_ms2oH2>Z+FBtRM>mkd0Hj~ry zk((#)!Og^l*me7^?5}>I{nJ%$XF+>P4E{`3ygxF}iuv&)Do~B#_J{6oeT}|oQlXCd zKNatfmA(%6?%Wawb9w%EDcK)(Rv}1=)f3O?bNi%2>OW2&3Bj@#dMIoX#J-Q(hr(Uq z7~o)rvT+tnPVpQ0ARObu%n-We82f%DrOuN4SfJ`8ELmrUkDJ=D@sywUNsh$&*)}Mf z)Uf9LQvc9kivYdl>tH;K&Ya_pe8uW`-%O7+9uTf6W<9*qg%w`G6z zZyAXny>F6*l_O#$`y*N=?JqLG-3Fb;s^edObIL#3{*d86otD^M$mgH>Z#$+2LT{p8 zt^GYu+zo=~lHTaBCV>5as$YHI1Y^x8ePkv%Fgf+V9<&&X(tgI0^BFY$+&yd}Li5c~ z63_VutuJpVpNbA6tR?({o-fk*egcz6uZ5HLG&X+}pDVgQMGp4kdgDzsa%ui@yn8nx zR{IZjEaCYbn!l|-!4T)f`Ve8zLH2zVf15A5Vat#9X#SM*D~hl6hJ$eONf&IB^Y}6C zZ`jVqA5Sm#s?|R#xVH_(gJwf$^PK(vXyRWaE!%1dgoq9lXSg3LTkK(IOnhcFkw?u9C`ySdA0OQ+w_~ps{ zJKEpsXKWDu4Aw{E=Zf*A@hu1%`}M^;47vTM{B_0q5UjU1l-#f5Me4)C=8cAS8)N8R z=lX@>Z&zM7wvCVu4;%khK*~*m$P_wanM!OTJ5iUwi{ILb&&Y?6n|kqyl^j18ygZh{-}Pd zF5iau;yEauRf8{?l>cZf+J#Z;7NW@&#ro;@hb+9_zZkzZon`o<_3ekoh}`7!HEch; zr$#Q_f0w@7KyQl%GD0{%r1m#ry-Yk`+6spUrL*~`@r4(?Jh0?xCp6m1<@EcP4++3A zvHySOT#i3_K6r>>Amjt}v2=J;&GV)4Pqn3ih)dRoZ3~W1n%|hM93=V|`fxV4XXB~< zQ_32Nn=g&<+MMeL8h>~=XCk)$wvg~s5c}LZXCg-GT4I$i=btGgK3p9?9rq*q!fP+* zpEQ1TdZPf26n)-NpzISgyQ(=F7TTYsPs5S$7$M$& zS)b#F#z!rlk3;4&bEppB`G4x)%y~Tl-4>I5E~-^SmsB-M{6mwtt({A8{6{qArZ1iWv7FDJPEr1V#gYTxyykHWMaCRo&-+i!Y)ebnR$$QfjX-kMxLQvbY2 zykEMf*dy7tKF4nu6f=9u5UH z_*atVUpw^B5w@MGBlJ&HoWJ_>%nSwn)g|#0B@!R)qU{O~vAVx`BkKu z?`HEu&&RHw6aQ#8?>%TSt32zMX zOO@+?>Ysdg93b{yF_PRLO6#+Kp9;kE|BMhdb0vE})xSM`f>B^B`Y$#2+fnpc>2 z#U?oJ(3_2?_?+Z53Nc$v(KTrslT-V@CT1e846(s%&kju9lAMou++_-)+R5O%ygrlD z`c>=ACoptzGOn8MlCk(5ssEp3Dj*?j19A^>e1r54iM1?7*ttx+`LLdir}3xy<@Yel zZy%17@%lU3pYQkGG6+?yu`ex7??k7Lu~44L z_b0V4-I`@!xo(_f|Iqx6=Zy?}J{Kp}Z}I(UMB-xyybj><VqKgixs`OUsgHi)0z z3PX|@hI%8{c2lf9q{F2FDs(;`H@a?D-{x9}nsij<)CQ@L+u%Ca3jn z{reSR=A9HI+Gfc9?jMRz&8fF=&Sp0>?(_W-P2#ih%B_W}{CAk&M=^h1nQSf`(9sY! zd@5(}r}^LVwNHfUOAZRT4to^lABuy_a4M}iX4Ra(q4wcefIFPkv@!49cJ_RV|MzR% z;bJ59*M7qBuTJpqW;|Ss|LIBY&*(tnkB?vbU}B{K&el~N-^yCz3&(InyqNCG-cRG3 zi6(vs|7nPN5BUC~@zHgw<1l#Ca2SMg`|R(aDv7^W-A_aMf3@$Q{IjrSt@ zSri^Gb5}qBeiv{_Fop}j;YKGkJtI8Y%<)I{v*RdVR8KO(i+76s%lhK|PhZ-2p@T{ltN)<*tN$wvvkMoBJ$ShO zrvAa18QT$lzV`gZh#%tF)O&GQ;=%K46raVyUKph=!;i9DzCI+ssaEtE4dbGhGmY>1>~O-dFP(AMit}sgA7wZ2N8d|*kZ8YxtsgxHu zQ2VeLt8Sl?asDdxpHs4SVX@H?IGdF)xssCf{*o)cN3h{q64ox>!Q|9_UwCVchE;9Q zznfzHzxlfZ+MVcx`8Rp|hWZ!t9`_UPSJOhlbIxDXN&VE5i(_H2*jD0y()!}wT_(e6 zw*#ubaQjB}xAME0n97`cwUFAFeOVbZ;h9%`~nVFRj1VJ#T{a zVvSn;S98G&3B!Bg_EA26H2$*SlMj4b8l&tNk3Ud+PZRuLzQF`;O58uA@mu{^e`wp8 zV(|W8_Wx-7&vkhKHi`W+ns?#vr~X$(w?LfQWG1=4h~j&v#!mDvSd5W1ZegEEl*!$`HHL3d_Mu#33@7UAt%jaKu{`iV`f7B%P3+P}nRL0~=()^5Gs+fO? zXbYD^2l)4q_@e!AM^q|l!7+)ipBBNVbFd@ED{CR6ipPg2zQ+dy;a9r3L_bshomU)+ zC$={5Ds9c)Px1Y+^;E21<%GB0l$o5y4}W})L{x?whW6w4ORErmXB?J>VGCpM#)%N%N;+2Tb6Y-lA51 z9sSq~F*Eff=ij0Ue=bt?!R`=a$^FnTNPc*hx-YuRO(gX;I+p z(*8LqKLfB^?7{x;d@Nm`%2_*+dQ|M;e3avp*6$5TI))Bbsqk^(^(WLmroFbos9o(~ zcrjZczItdm;?V^yguLYVqWnQ=RX?n*qm30kxPJ8_^*is9gHZRa1rBPAWzVPeYazEo zFsE2NgJ5pN$JbLJi{1C+gqSWo7;CeiQnbl9s;X| zhER&*{u#~xX6pDrX@v=tCoZptqE%t%DUl?s2b?OV3BH z>@L>7#ah9%$@rT2QM4)Xj6jUVrB7=}sdj*|N| zZ3({8`X0me%2e#};rol`*Onc;hF{&XP`RdtUy}I#CQmJ4(TVzk)eWBCRwDe-a9HIV7`;^G}xS79og(-Dagm(G!YvfYe$)uu<1A>U9>(cX0gD_}APYorQ;k8VHBJaQssKvmmdxu(FZ5P^G+* z^B*PY{W>4F>kD6Qs0&`L%xmx~<(E-L#+dq`Wv%rO7r$7e<%|xHJMs0C6Mp2KJq*h> z8Ke3h&mU0zJAQ;Wc0V^o!-w3zqW1ZnsSlRzFhk02{(T_$%oThw{)f55zoPhlHr^kv z##&13cLJ$TiN5ZSVX#Es525V)Y5XFmFc7*Etl|1upUEjdO-l=bQiZL=f370&Px+cT zaMd1+6_5G-@3g;3`QS8!Jd8u#fETjA`a#`ZTK_TTK?WS%R$$Ao944pn*1unBVxPpXKEIjx4XGkkjouhP>hS znd)bkSA8%rwpFe5Q+lvQ8%yzi)NP9KnU^^fl}C-CYONTb$_d_h(!pHPe}%@^o1gK) zUR?|1mT>+^^=IE0U(66|y!svK$L5#TkG@Y8<6}=OkTZ|R2SE61TC`aI;$VY4!3JzR zJ-_leH5hMN+QD^aSdCn2f8z^+5p5`*!F<8vn>0SZ*&z*YH!sGg9F9K_ev)Re3j=eO zOZ2yvy_CNf=H;QpWj(&H*v{6M@|P!(htYE920T-a;rfU4fBG4ckExSWCG~?K__Dq3s;P-adTfsT&y{tN%jAVN8VTwWr5w(`Tj^C`nzP74^)*b z#XC+of1>;A_eLM&i2ZLDHdMSnu0Hm`bstMfeM1`2??#;hkgacnv@zWN2NU~$=UgC) z(rj^ary-jkYX5(Eig!Q6uaMy1h~WR>josL|W;GV>&tvnSM&if5*AC$0(L`)coy6o* z?4|wjLk{O4B`_H+Pp30E-9Nis45VufU9Mo?N9~`^L=B-(R)yr9@$C5&zad3NXg8vD zt@xaJ!3x2HI@PNGjg}3@hK43E{K54D<=29$H%30RkenZ%Lh$RY;tSVJRyd-vn*Bc- z-_29=h1FIoN&P}L!RJ>aUyMF(g?76Z_=Y9Qy$n)DE#y>ee zQwTnLTqwX~i!E@D;`l5h{YOqEIil^i?#SD(7@s?xouM(JCmPP$$>xXhm+ony`1;fV zm%_{%xPL{F4%ikM-H3CA3ph7Ct(0`#|w$ zP$<^Ec(lfdbj~lLWpyO}@6m88WR`crU~st-;m5_@2gC5D2^JXs`#x!Xrp?0P$lGlJ zWev`MvkCrohx&^58`wzV|K|z5J`M6i`b!&ht6ZoMU$1lhU?HHvFC)>>?Y98Mp^`pkARv7WDGqTtJi_g`S?2qhU z1JVAKF_g`?{h|4Z^`+i8eBK&QKXdzEMfma3JRjJ{+eqrW>y!EkCo%ppeS$4U9&lyr zPx*J96n{)@*B4W=Vwjxj-;aj^V5KQT;)01x9!>Z|oN*v7E*ASkjOfGU38a2}es~BF z>VPe(JigVK)R*0K%fbk^MD$fUEc=UZC33!e*`ETqiZ!zCC%OKNmP!4m?BJuAy(0~U z^CQ@JivRm7i?G!|j8Q-4{E_xY@Nrfb>`{eAb^q}{>G?&~?=6H|#($ucHlOK7Imv%- ztS~@~U7K3<-zvESnrxKr4&p(^lr(<8x3Rvt@jDP?8-GoI(YC>>{8qe=5N%KQ1w5;GVQL9$`t{Wgn zqlevVjlYk*?+wGVHh6M_=f9}_*8k>%pi{Q^wk?7Ef65;YzwyQJt>XE$_(e6}FFhZz zOswzOA=aln@ONi&8sG436o5txWZ0v}@k`?y(5Vm}Ncj)`Yu(qZe$?Sm5WFCRx9$GGV2sNNH) z&_8umYA#%i{aGvj3@p*dg}!ZSwGX)056wRGlJFObZ;$;0k-Xa!Zj$@Or1rnFidcUk z@|S<{Lz>@~_k^)qcY?!Z?0YRUYA@WaBQ zXZYFsEP_>n*#1Z(``)5Q}F9$%sPqaz!fa6Yd$Qab$0Pe}7eeck(`bf#Xidw~dbZHud^8R(1oYrSNKX(SUxmkF*CP~KZC&@pr z+G_#t23;ii1sb0icvFTOVY+BqvY$O)PVCdTiNo<u1W(-?sBZu$CN7_Z0JwlSzIUv|5gf`zEmeN9#Mo4hCRulmi;-n=m=$ zAEP&q!MQkh7@XH;a#}yIX81nTxw0O%k@>Q}^GEyJw*0ssy=*t&dJe~*oaon>IY;5L zWINtly0Gzb;@@S=DTH#{3>e*;tWdvBY;yta60)KGGntK7C;sDA-A2N=7H_cQou9(z z2jA33zqgvw{!7IF3Od^lJ1cu*YSylzzu!mw$LXpb7`)9Gp=Y>%NAX#wY%-Le4aWH- zbvB-!Ux_S^!rL-G=%(`i)|SM7Y;K&6NrzUUpXojJ|D$En`l_%yP=r}=ai?$=Qf){aPH|BvQ>CLIy)wyo+S;V;zx%=eMO^n(=t zbbl{6F&xHy#U4~cIKC-==_2OO=ZDE8{d3ER|7jiLgU2Uj$a}Yj{XZJtp1RKm7B6Mu z{q&0Yjj_n@r@ob8oaHz+K8@(#QI`WSBSWmg>B;K@X#68AD-^vd+~9mii;buE4}Nys zhlV>-pqD>h=II|r)y7K)I zP4ZmF#J+Z(X94r0 z+Nl1N%id4%uhXV4^e^e6|FwNgPV>u0T6;rnnG7%FW0;)gk560spjf;EJ6?_JZyLWI zl;sDz>kjDtegGR!wq~lVpGKMg7CXl{siXcQeM!=J=-i{p6$qbV=QT=VprWd*o7q z*uQQE7s-bxYk)H`N5K z5)|8qV^Py#x5^vl1w8*x<1_R1BjMJ;7b^-rGJI41^6t?VoEam-vQ9&O`YMV4 zO6&7J*relrL;|{2bNix2=C?!h3~VV$#9P?~HvehFzO-2{-rf928$Ep$?~j6sb~t6w z6H$qZ_eVsGBNDC~V6_t0AJo5Dv~UETcauxvk92=bEgJ#td2$rK;QNdErwi@9G31UM z{%)NAUnlX;&j)OVvCyZ zllI41)jR@U#Tawr-MoI`2&o_6V!a(P`fJ4+)%)!KQ~X_V$-o=Yzlp~|h2K~Gc@Hu~ zez_`u>nG};2Pi#9T)Qhc()l0%l-6I*EB%gPP0L`gSMmG}NHvFfX;+-m$Yb9}^}k(` zEpCtRiEEt{xV#GUt~R|2a!15C*^PT;RAVmKMbA2@k!&?r^Wo`*6aNc^D2>jALSpjxA~#U)frW{2QfK~FXk)z zqhhxd-|vZj{_Pfs^Mb47{u+zggfH>6 z=+S;SukV6K*SLP6^WS!76dD)6x`bo{;^s#@W)zxyA=znoF=09%`$M?#%X zOs+)u!~Ri~aCW(a@+?*M|LFOw4HjbUuh^gMNTp)^8vMo{`@M~@xSaogs$Yjb_s6wF zR~WD0`j6K4S7`>I?HO0h&za8NPvax~rv;)>V|TpWW5wjuKXi2oMslGCdY$UT>K4@jW_$j zCE67xd7MAe`Z>?5{_x)FhS2Yd{hx{$u|C4x9i4kDWACT?=R>2-n5D8B7dyO`ar-9C zf4WTHf&Cwo@cD8clT-fnyn6<2My5#iM;X~4A+MjJ^vYFCm|s})e5w7+RaFv%i!Wil z)~7};&ENT-w8gzvK9~@1g9@7n#vlQ#!q}O77 za0fS}{4rzypT_^?VtlpgxEtz)a{EcoZ>$gYN9a89j_UTq*?8)|=V%9@g_#Fl{fcCA zivOlM0q`~VK;Q(9Pg>vHJ8nCczfOW>6vrQ}Z`gftCk8f6!TX(IY<{SIeiC#TT~}t{ zXix5+)AQy3t$Kp%XRe}dM~+Y0KP$Cs9YM+D4X%3lvga$2_*BE&HfWLGTM{3q^<%?2 ziris?DH`t%TxR%0hJ85cd5vKG9)!2cdT#b>VP7?!QugoPI-FFn--ixV5UdX1uzjJ|e5y z1d*M)W5!{{_--F!Bc9LIm#h!1KglxpMbqtW*dNXHE3Ka|F!#g7WOqsbJIc>`7>M=p zi#*VB7{@oYuYQ36c)i^dAMbgy|4;Wv(B1&pzVXD#l{`K}@t?dq3NK8?;6;ymY`iAn z*Rn>t@#+0WB)H_u{^~DvQXkPTwGdg>*%&fG@%rSnRu)=}`3;@5|NKv>|M=3XpLn+2 z3~p}~YFf;2O{U4;mje)k{O(vP5jVS<1ej=Fe5GlwsDW>k|H;MCwx$W1gV1+6{C(pm_f; zy4g6mDf+>x9z{4w#{eS8|56-s1gIEKYRv%z;ioZ?{J{WM`4WsIE z{84@yd&U=yY&=kRCAaSsf2DE$X#T5`^C|wur-||Zul+IH%9qKbN&X@3d?0Q$ zABb%hE15iv-2dl)A_!f?8l)&~p5LJU_3q|Th^spmx{e&5|C3)gQ5K>a{lVHd9ADIa z*`+iQw%<|`G>u0w`$*%XD%K{jmWlUg*Ak!JWN0s*uQx&0o!mZA{kr^zGjvB;VXd`d ze40j%$1_(Sn9nn0-`|_mA591l<3Hs=P#xTs$*F(U*d+>M!^R=ZvObg3`rWK08}X>_ z8Vu>r`BgOWf45)ThQ!~=Vvd2^w*<0(cc`Ufk@b3b6g=Vl)LzO@J5E0VBY8H2PY+~& z_dm^_A6L4MT^5%ydpghm(EjUlw{{W?cefBMmh<{bitlkdY@i%!2)8xa?E5HwKXj2J z^0)~emvQ{k`7a;tgI{VMh`h|@ls|m=E!L-Jdmu4@`zJJiP$|}DwyN^P{*hMf{WO0Y zG0uPU-*h(=$j12nE&|xP9Xelo7EUBn>hlB zNA=ivFM^Msq3I}Ez8-EHCd#<}mDaCsn{)_vdw0WT0OucRgg;nctS97;`HBu2Icz-L zA2%;F5Plf^fL3}jlPi(@GA6h{?SeHf1}Tp3jINGA=L6y$8*WraG1R8n5X&%=vG(LHKp&wdU55R-v+`d!)O?7bqGW5NWdD5=t z`O^5~&x!y{TkeI3f;mi1^>@cAu|92+7d+N*{Y>%uxnnRoW)H^dYaG8z34X5@jmCto z-Z+1s<5!2^x6S8~QOBvo__j@lyysZD*CDUY)B5Y%q!azi641f9}gE z!=o>^pkh|U##8@6$y`Smak-tK>{hC9{6ew!cSpG{tZyskujkv_K&!RbUneMsjaMS| zH|n}_ENpC!apQM0ImPd$Oi_28^T2V}9b@=mX)d!TEuvgEYS0f4e`Pr+J}p z-E8)Js-F{P2BFW$A;=U~Gdbn2ZI=b1Z^RIZex>=RYtuu}WzaATZR^Cw%SrsR`~E{X zaeXg_ZRYr-`qTZ=QB)t##tF3=`$x`S*Pm5SxVfqd4t|R9`E5-f6m8M1)ql9xQtW*r z)@OX}$>)#OU%NgXjBO)bVJ6YP(*77F#?$b6>uAKP$k_K$e$iuf1jbg5h4suXOiuCd zzF{Wxo=!m6PL6*XKL~c%4wv#&^vLD*h=XX^9Zg}H`3yWNECFkG#O7T0_WEOlrhlw>#4cYrCzt>Ekg~H%)Xx{C?=N=;&^UVHq{U+v(9w3|)8$m8(M8|C5vYpsZmkLXUQhghQ3wzoPzSE4eky ztxZw?r{eXG2^fUt4(>R*hWjsc{Wq6*W5MA;826dm54!&K)cjESY6w;o^=1DrjqH!I zmjSRlH5>^&MlyLYu`g#j20{Jn2*h;d?>|rY^Wu!TIQ?Nd+$*{N;Y$3c`E?hdrOOOx zyj5e*r}!$}9EVwb7DDU(7$&Fn1%_9Tqr=_9xcHmTKjq(A;SZr(dK(iGs$^V$O8d*` zls`hI+g(gg=J=%ivztyG!KCUtI^<@v@znk#f0!cVwiqu=>Tbr)r_uGTNYTgoR9#7b zH;P}!WJiomvcvZxj&Ci3-@4UqNLK0xztfzbQu{OYn-@;~c8BaVpZ_Uj|DS6(8kg?{ zApMtOd}s99iG|bB&@$~Q|2~pm^nZE-<*Ao2>F6jn|7irjF{kcg>*yOe8UI<~{3e{g zirRk|G$jb&n*iJkd|@~nupr3_+1*g-#klJ2oH|} zY>ZaSk2c*bMCpS9q-f2pnI9>C&AjvmC))l8ne{S-a($B@_%!GfMi^aXa>`%JEtP~5 zv%W)aqZt3K!=?zz$`b_Rb*&iwY5eQ`)!w3R(S?~c*UuFHw?{i-c5+|nd2)V0{jaP~ zZkTNBgpc!ie1YPBZOefO4itTin)*GO-&NXn11;xYM(=@&^>6PrPw>O#0alnluK9i` zzUo;%L+PuB68=i_=X3O}u*Kc1R{ea_!vW{w#rs#5DBj-(mU-jhiy_E&+Em2+Z=yd3 zUI@f{Q(x@*Hk!%hME_Rw8HbBGqp&HBkEi+Rsp7q*a~sB?!?$j1e0`GtI5K`8vbXHU zfBCO!zF%5Do3nF267KCmnCUzgpOTaMs_UN)LQOjd;nVi8@zDg|=O-4RY4RaxZfeW$ z4TA3{c7W>0Fsq#)k1`FGl%QoL(=7X|9vKGE~fKRZ_-K>I0%wi{OS{nGsY+Y(E>(lm$D5U$@S zKXho|0H;V9npG*rU)^|bG-xvn$(0;GG`^tf7>NDPeUaVipZ%4_H{LuMBlbre1&=oy z+4pCX{Kuy7SRD0Q1aDUdCa3X#UyB^92-%PJ$1~aYf#4^pK^q~rqNQ+Nb1EB8^Pguo zwh;p6wi0gl=lWSr?1$0v-q<;*7dj2(-%s^VW)rdYC)Eims}VQPAo6hVdJU)sdDoU!qkf~?tO{u zul}L+DU(a?!oSUJ+;04}MlR(~mPOy;t^N&*!}l{ehYV(fZdX4-5pS zG<~6C%9kR(zS8)|-g6cR6#LuVH&d)Xf-i~K-{A%C&AZrmivNhOVt!OB09%80)X1g% zO%FYfK&Rm8$e*ove|((~g{Hq};=zwWY`mQ4&qGQJVG|sUnC0u3oW{43w#J}XB?kS* zbz*Yb|E@uYIH;_N#nskJnVjyQY2yCcxIPv)J)CQvFRf2kzjGUl#udZtn__+&uW}db zx825_JOA{PbbfDXl;iEGrw|PP;akctEN!a*&2P}$!}*sNx!<9UnjYkDdLbrRG5&w6 z+2g=UDZbSSzKhIVpi|+D`j0t&D1X{_d#rdr@mS1r-@?A1;`hY<2=VUg2yA-B*RPD| zx7%Bn!m-Cv%stkCjbBRi&$UmT1kHV&gh|u)GdcBdtF#7TmiTKE%kf3ew^~&{#fJA! zk^bz7jNw;FI)C}ko+GyGIbJk~XL4HqJT7%U+HRVUTkY1c_m>d<^sTelyLh^IKSzy! zK<#JOeF3Pa5s2@Fit+8XaV$c;#$k0$|8qKj!@e)VG>sTU@9xOnpH0p;EbxrM$+0nb zTQG*nX@8*yuVQgsJq~ksaeUJFV3T*TXxAzZYC#;|wElEpc|5x6EyFlFW%hh8vOZ6i ze8JD-U(hY(ij473Vt>b*H5IxqZz{C=*o2Lz@vE2O-R%nkdLzG4jeaHZnOPI)BKYAM=y++JVa7ILE|HvD@KU^lP?PL`S(%({>i}U=<+ra>#Ml_Q*w~@ zzx=Qz8t?loLde}j_Wkb(zLX!uVtndibYH6&A0K0OKy}VA`!};40sN7FfI6rNS@}a)B041p%8NZ7r{_owT z$MB|mq1Zo=`?oaynB7uM_}-G+(`nH_%dGOX>2=m!%+5cB3 z`SFX>Vv+KCFSnuL&KOVA#QU zM4XOf@)WYZpT+%mEFuH@8vm00)xY$7mHp8?ILY#{b@41FS0el4`N>i^2RuT-o`+0M z`&+aPe2koq&+uhSb&XuA-?P6N3FYM`LRRIBn)gfn`@)o=Lhw{?;YGRP{kL{dFMQQ9 zsI@=p&z5qySoFh*_los@*KcBMIoJ(@TXOqL`QdlJF)%Zjh=Zwoe^UJ)+-*9xY@7vW z6Yl?Kll{4@VmZ|F#Qqfa>P3I&m+qfVD)(^p*F)_5$@52Yxs>0@F0~dK{MS}E9m)46 z#eeAPZo(|>o_?^j?TbZn0Ql%H!|Ue;M3A7HT4XqbfQ6X?@-^)y3#B zAs)k9bNiZ2@E>ll7*5OMp&Qhb{l84YFAqD$quu!xNSxS|$<+z}>$WBy6WXrCjEMP6 z{(|g}C!2Pl;et#|+@*MbsA(L;gKbA7@jIH|pKzrBn>H6h!%&SqAH;t(*m4YK76I?q zc=!E_k7#>of3#_jAEBagIT9}O{X@?;nZ167+fFa>I_r$=?|2%&E-UMa@wwvt$F=n5 zZZJ=VADjE(V6o!;;j-EZO`CgQQT$%^|LOiv4j6+0d&4j#l*b3?{+ORT4bSqT&}Rw9 z$9u9rj>VMVbJim~YNA+w>=@cs*u1c#Fl*xi_I`^0>cicI&@p<#r8+$RN%6n=xuG!c zt!b_L{gW=QPr`GtjlCS`E5rdS}BsRW^ z@S|t%#k)(|#^buNCzDhE=FaFiEKZ6S@2FeB5vO zKY0~y{^0hT;y*L{5FSrDh8KO3WPkBP<5zF|594gt;}B2KGWq}5=QjCx{-4<6&GRP1 zuM)Zc;C%iMq#4x_HVwI{aJ-;3RLEWCE2yseS|gY8EBoa=5jn_E(qD@5<6b&4*iLl9 z4c&kISn6NpRXd?~p(h%bXBGYZK8oMN;REsN=5Va}$@LrM#~B)9@F-QRPbpN4@2MW* z{ZNaeF!CbjXB6Kdqvqj&VGMe;TnZ?|#{#~8=>5gvC7Qy=Cmn^`2{+mE>HfHHq9<%@+DDkvFOxl=#wYLG zGr{{%>ssx@P_Z{{v;9uB>W>~>h9K~qujKp&^{+H?MU)MqEpQ>3d!>#buNF2cRGqukt z6IWt<@mjp}Tg=8oE?u9>ie|#=p)G_Fsf7yXclG;bf^tv`Az3f6CcY`X-*W$}R>JI} z_QKe@iuvoL)je@P#HiN#!vBgKQ83#B4hI$Um){osk(V({ay}%O@Yg%(Q!ruRZ1_Ls z_@(ukp3ZZzHz)=z&#q(NNBz4i2Y292f_V4N&i`cG{z&s@r)@98d1^84$PC%|U{Zhm zJpK;q4t_(nT4S9Pw{|H=vQhF^LJCcW6s-cRvo;w<8C z;bi>r<@lrZFTci(hwRgI)EUF~FP)#=O=I!>fXF{eJlON;`M7=VvGDp75AD6YzK!~4 z-v%s0|BwV+p33>57U3t2*Br&M3n$U39*=*~`h(c3y2#yZRBL~ktd4!~b(fXo`~|K5 zJ+sUaCbK-T%!=E0>YwI^4?wl8H@scA{iFU*K>U3CA6;J^l|}b`k6nm>sHlL5h=GAc z2+}A>s-zgGs9>Uk1tQWVAuXtgN?C}V>}$8a*6V9`cL(Zke(N(A=X}>Q>-qDpnP=wC zzWbcB&$;Iojf%sKSY97V^~Ir2qLDc`3Ht^ni}Mp@C0&2K^aGAV8ZhTkm#sKHrTd5dpR{ASmvvZJ zA?HUWQr|JdyC<9F-k;TSo9yCUk@8;{hpPw z54_SQV1EyePnuuRo-i3P%5$J^&g)yMNPcneqEvj0&BBw;ZN>R5wr(Y{A6i2Hi`ZWK zWbH?zL)&3fegMzZxc#T~Jtoh#!{_P&jO%<^wC~nr|IlykeK1{k1b1vXK9y{w`rZ-G zeW(`J(W7yk#pJ6tj2kT2TwQH;+~+r1GI zKM@*9isyImrVu>0S%O+$p8uux+tYIihA)hRWfzWbYQKY~$DmhHGMbKX5$8XE*r$gX zu?YDu1$P2?{H;XnhyRpPTn^ZZqD35^QKbG{|M6DT%aQgkp!*Mv-+x1fYXjD;;os|} z_+D9Q#Fl?EV>dV76!A~}yV`Ms*vGGy?5}?jMe37R`gKRsj{T9)kNa0qR?`0BZ<8%x zBAkI#xrgKbp0(8fa^7r<%qOnsxt`;n^2^bRKosqi;+xw4g4kg6`86L!pSb^AOyY-m zXOrQQy8=2BTPwu>jX!;{HdfffGp|Y;vL*l{Z7(8W^IDXGss?U9YxdBnnwqk!Y z|Gsp8^xM2{2=(eOyMDfpx4;=)N8GgM-;aKuLn~}?(O4nv!;* z9M48N%KGo&+P3&2^alu9q!=F!<_UW*l}6+ARvtgm`N=;s2|D5Pg#O)%@$+@vZ2Y#4 zLUkms9{^e3whJ;aXvs=wj_3L(t&hzal!F1A*Wlqe&M#CyiYPN+e`fY)zZWaU&-x-m zR`0Y4OTEeQ6GiG1+Km^^@2fInpE4GR^GnYM=;hZJ+D$DmR-fz3lwX!NF^5A_C!AE~ z^H0~`>!#i)+cgK(}0uAF7`XD_x3Al_ZSwpQaE$4Tb!w&b?He z&s#2zQ~luD!bG&sT!FJs$BN^{#C|<-*odPx!SL2~SQSzxPNU|C9Q- zrcT}9)>+V4n(h$qPw}^o+7v=)HC!2%pw+{-XIk^Xdo~StjD)jC}F_&xk&C?sp2t`{dzw zU%o!+`tn;*4*xql;o}x2KL0(EA1I!;348VS;m#yDatp{&WexCJ1{I&e@N}y!l+8DJJ?$ z^6!~wQMwEX27G=fKgB&?jFAF<{&V2?Q6m23E0=66TCx`QD}2QFqx`k?Mo%`Ui~RR* z++B#Rgf$?SADcJ88@(O|Lpz!C2enV%-;PKA^-v61&Gi%d{h#Y6;;7IccYH_w{4~GW z^WJhK+7;qx)pPOt)Bd~jZ&xC6TlYOEG>e9-u(wlW6e^E2>KIa8dUizGku z`g;cIWvxM=#(#D1FV#oKs%2uL;J+FbjS#QjL*{ovX(=Wt?Z&7q#r$}CX%&_qb9_?$@NSn@Of5mk57gC1z<`xpDtDpUnTxebZ6$Y8iF~bN_?d zSDiPDFyvd3#J*B}y4{F;s9!6CMMO*S`RV#}iC&3)u9e8VxK^A$Yf}IBsBH<}U9CpQ zu5@vn#s?Q7H^CwG5XNk)tB)Z4M~bH1#k;gG@U^d~yT3HQ)y1Pb8%fph{+`p#&;ZLUwMBQG4E#ExE`7b8;e)}{7i!+L0pQLzwScD!y z+@$L;Og<)F52BCcnyawIq1tS5QfG18n(*_%Bo+4aj5b@<{zKikR3G&+P-U+RIx*+7 z+`psw`Ic&iP`fe&pEmsE52^p1&}BFdmaR)!T4AfWO~$qOV8lmm;Zn58O9rTKzBn0g0bq_qc@j@1LP<`W-0S9F zs(-l}9l?vF|1iPmxHxW2@ZI`iBNlu?gMGU(S{$eSe|1{4V(kZXVsU*x)m<;e_xF9R zS=J(bW|PVJm-743etK-6@asQ)p4I=pUoo*CRZ%_h%EMBEe;Qxy=;VZ`#Q|tOkK=>l zzx}C^xVCCKg3pwS&qw`7$F&QP-ZL5Jbhv*=es=+Tji2NCm)i>OpZVzm7MVXsfy2+b zacOpW=7?FE#dlWf%6ceJvj+{)Ou9p73371?{tn_4_9O4#Ow! z0DLRw_@?zaM#o3M@78pv&fxf?@#|4x?|r0wvP7Sy`JHxg1<35T39H+ei0@ZS{DTL! z>#=m{9z@r?7RTxNQwuePy`z0}-m!F^c&u)593s4P9mVtwh@z zEmry>+m7=a#pfX3@o+5&M{rZ_Us3&Hz`JRvj*FG>TNT0Qdfhm@J&}V(#XSE-?R$$3 zDQLd22rlXzpGE|q5k1n-zke}GdvgCqm7Jfl_*XWZ)XHIdMKM0LJ~Modxq-9imUDb4 zN%@T_A4SUZTliM`p3kq66n~jLj^SM2JNS41Y4Q4Eg6}O+$}H1VhmG9A<2${1tQ-{|`GyU>%l9I}?!cbZ>>%{-=DlEjXd&aB%% zFa5s#zRqKlnkBQ9I^D%_x__$UT|IowlwUs^epo_psV{yd^6x|AzX@97F%=PblE&8u z)sG|lPlN5h^6O)Hixh;WtinY-$2xpT?Yre@hG~OtLj4KHFO8onjP%%u&n9dExPMFE z&vQ~2R_JNQPSkSzQTu!#(1=A2c4Sos^ThwB{_jP%o=Ebs!L2KtA833Q-E$D87`Vyu z%SOLp!v5un$k@Q`JJm=1j(DJ*|4fN}r}6V;jWFmKrNFTTx9=eO^72D*u(HX=6br6D zgpl}o_Ob$O^w=UfACcC#PKwsUml0;N{$ZN%{Zse)VaPcC{`C9XbsQ?3%{dW~H@W?w z?>9GmoX{U+2|PA%e9-tGRl&mf^l?!C#O*uv4-aJt^#xu@I3AWQexH-%{cnv+#JCZK z==AG}xW1ySr2VbdPDw`g)>RVwPxY7KB`G-2X$_oGuZh>w{q^l;WuwW&3UoBwSvM}N zFF$uJ2m2dugv(bm@%f^xr0XwUzW^QXZ-K^9ZvUwN)zDWs|G>?R{kK;!KEEI9ftdF; zvi+}u=M02$k((qwrS&syJl(OQ{!BEz&F7!?S9RSJi_#Z)nBAM>D}dnV&9X#%@GpW= z*;DcTslKS;D4dVn>>yU3AGFnG)uRS7b)`$<_oMntgi0rN zu+W&DX%)rmlSu#Av88$}{rF&(V;m-4Px*7{?g6;@!cEpbKj<&?zUVs>|4!!fPve({ zy<^d`OFo8t%@gN`^4HUE@mM;$5EI7Nt#7iwO-VZm4Zo~H^W>r8^%=x}3Nh%6pgU%= z@r&xd?r8nZ7Ta1?i`P?rzwvVjj`i{v&Rcuc!EXF?0;JK3;;{ zn_R!3@$ufCQ?VjA4kNyC{etcf+-x`(1@BWN`D@DmV^mU6IcqK2PVOrHe^Xm2|Evnh zz`T{ExcIf&isx6Q{FT*ZC7fGS!*n&zPtg7n|0tcs&iI#jn8o9lD6+ri{-c)6zPJn1 zxUU$WnoNyd(e2KDPKp+vkLC~RozY^ulm@X=y*WOqes?lOhv_Pt$l^2lMkf}#!jx$) zD-++3?myhSvJa~{?j&p9hu`myA3fY<_ZN>)cf+O$v#>*%ug~j5UmeqT3=GYeO8g(% zKPU5PG^z^n@Oimn|9{o@HCX$44-9{B{xu@?11jljaZl*6+ScfA{!&_>);ClaJ-ZD? zMK>P*(E9#P&fPJz*bZ^S73148Xb3)^_ebnQ#rSSJY$$x@Pl3{&&Eof?_L^oIYpoccCl>T)JLb8w^+D~#|EK)@ zRl7fQmbznMFaG_geSe|iiou1mFnTlRR~nzUKH!hf+EGY<#>Xi>RhmX&Xww}0=)FSx zf6BjK_r@cv@hbe@VJnVD5q>?nAOWqPufop9$>KOYpDNHS3IEkAM$*@-R$L#G=5L05 zDM!eOqcA#}EsiUZ`03p4PG~!Fuq1y)@%{QsH*D~+$FUMVKa{_{o?76)gfY0H$;YYx z`eUrn8;nhX*$l<_J{mX~FJDOUtwHdeIBp)|1q{mJyX)Iz;e4kO)Njc7nc}z9I}LBN zN>N+H@f$_(yQL@{h9zaNYr9>XABx|CXdO1atr>G0r5InGbUQ&usPFh&|3T-k?L8y> zYv>MLBfkDAz5=3L@Hk+$#DAprd%*Y6xHe0QuMkqdP?o<8{V(Rh=0uK&4~nlvVR5)Q zuLxhVti^GPugop+c>Zz~-UM)b?IHSkL0S?%jTg?yIeV>cex&$1w5kNtMjpb!xfONe zQvRH9sT|GrAH&o49DlTbP~(zr_@Lq-yMHHkj8MPZSvcc<0LK^gPu-5$qW{Z4Nqj`} zck`|U!h2G@#Qsx!#Xp&Y?~Z9Wyobkklt0tFQ&14I4lmkw6X!33)K|40pCZ&QuEVO3 zqvHD)6MPMBx*UsBH^3vYo_IagHxF57;LNlNOnJ%iNA*!B?N%(|cQ>Y49VK2*?YsMN zE%t1XDf1~W75|^w=a4nptir^MDWyd!^gl642d6F#mObCa!l5tn1Kp5U#`8wV)fNn4A~&y*MQ@f z`v3ZxN%(zwE#kD&#rcUM_?_v}4c(4ANcK;H^fw;xk2$RNjYStX#rQfu$__1`O+m?Q z?tjw!L733n@8tY=%uMI@`6AILO|3)FLo-d1AEWrXQ;>w3sU_&<&Fc^7`BPO7lF{a~ z6kj0tYI-0AyMC_6#lAhn_s=Kzd|Z=`LszBv3LyRe=L@wZeu!BMcU6MT}y`=2EE`C%aRk9oBU2YPY) zOzR&W1SewI!?jpZe%R`N_E(9VKc6{uHFQ(< z@<(Z~*ubBk;y2}UDoTUPaMr(p_|ln32#=9H;&7=KLtYPxIZ#Kf7O? zKYD)3qwo$ax7dU=U35%g|FqekwOC@oV3s*iv3>UO&|&=sTd>dtixu+U$IhMDr$Iwl z(^g^P|I_;6^;7iNV?7&o;M6dM`hez|zU)nd5$yD~w&MFKk^Z^$OpRICJ71<%*T0k6 zznG@lcouFhd;Zg}+CEsD?jh-qN9(hfH+I9^fG|uO!u3IAqQAR08I3)v(USE+`B&39 zO2BWv#DAdcLld!R>b)AZ!#Msa|Mqzt3;&qa7*omD59Qy4?gz_3+hMEY2TYAG(vukeP4-)q^*S*GG}{;qu=fLHpEX3p*=bA6xfz#a6eWvima+ z%@~aIo#SNvi(cn#@blVK=nUcfPuI_Yy%VuNC;`LtxV}a6Q`-*A!ZTqFqSV+j3L?ojEZc>dP>G()S{ z@v`>Q?W7Hi&4Mvcm-9cZ?>#VeB1+pNO7g22g#Z23X5+|erdb4B3j# zR$oPY+@t#8R82PD&V;2U4X(?dN%ht0F74T|?xxJ>++l_Iy!yL6(->eTi|=3lI&5c@ zC2RCA*Ker*yJbKR_HeT^s~_7^{C-hZ(*5llqk6MDPd(T#mnw1G+FD&wUs};^Ae-~c zmsu&j5Z{mT_wDT+@%*c~?D?}#JD6eX>hY5Jn8q)8!r5=e215U=vmF1lzwh9yK3MJ* zjr)Zh|J1+nR*yts{{n2*=l*jB@o$PZ#lpQ;F=E%)i|?0D^o0_qcvu;hz$k6GI8OV^ zBlii?XY z@a%3M@&5OS|2{Jy6S@!O*Vll-t6(hDciLNU{L}hSt2vtNmA@&=Xu}k)ue@)X%)6d+ zebM}PShWs&sbtNZM^{*JeOtQ!XK%}a?01LJENQOd^`TL(Bet4bV6r*qH>!_pFE>Tx zi~yVs;^TCE_!#(LO`#P3G{3pB%@UZ!7NAI7G5$3c#p3njVhkPUAkHtve|(kDpDefp zQ^s)oD-nJ#nkDpi@?HneT#kQgAD%m|#lXxX(3r)?X@8RiL-djVW|(aM(qLmlBnvre z|34g`)IRpfwt;Wiba)l=amwGJAj$F&(~I(Oux4o z)9rFpAwF;0>aY_T)+{}k7D`zlFmhaQK=OpH$ztuNH%5^^1{OHciB5 zl$F#zHtH9HdOd_Q{2FurC4}(z1By--#7M1 zMnClmxZSGH|DSx{ci}0BNUB8aoWA1tJHk(1k6ysSqZQkmn#u1^`iGazt;K*|9azRl z74dpnzm$Bb3tX2wO7t13FS~5-i7<~5m{NB>09_v&Ers*hggqoB?fLho`b^5!=`irh zz*;*VztZ}ndJ%g9UXhTz<~X& z*n=F!`1tSkCtM0_%d96f=J-%*E%Cp8zt@9{aDJAYf2^m`6AjMEFC>YIkO zKek}ZpwHs^P$K*|r&k7+hHt|c+!x1beN5nQEw($zhTV7L{pqOw)28bHw&lkdW)tvI zyq@}}!#1|Z{@+6+`W(e)`~Ce;E9@`*+g~Sy;B(J9PZ$aPmHzS{)ej>7|M@3Zlc3y8 z@%%hUT!h871^CyDs{FG7DsEt4~{_)hAj zhw`tEvijRdLu=G%&%(w?jz5~;E$HWj###1VDAzmDSf z*!CW1v}Gigr||iu`trcZMo9PYm-L^e_?|n@6AM*h@v((s{dlgRO;4JWj92lB@tr$z z8SFO~BO@Go$W zEyuBx6)(l-r}_CK$2IZht33YIg!6sZcNizzKeEejM~qhvM~U4=asH@(G3MVT|Crg_3R`k#WBWrH z{Qen+1mkcxKH~lXt^XL`ek>M7CQIyJB8jhBYX+fHZl=UPp!ip=oq;_Evk}!YMSOov z(*LnZ(Q-HhZ^NEVit)WZI}Pv3s-Iy{fpPF{zgfILE9H;v0 zo0aR);Nf|ReODs;S66g+g8PZ8Y)9_j{JhjYsa$=J8TB-o(oMzw>#M%aS&#aCSle#V z;{Q|st#Z6NQtz3<@5F9#Jj$w`#Qz;xu8Zv%!)5vTLDTNoX6-4<&!!QUFzp$F&$S%i z)c^e&JPghk!=Y2l@lExEMB}k29G8M~4Y__m@jX>VIGcuLO7hzmiT~T&AQ<(uv+!nc zqWFGvf5#1>H|k@*EjaGoR2--ILl(s_>-9%e#NM{z{4TAp+$H2Uyh?4^mN=fjvnKw@ zf}QQK^p%ygKOBkA>{ksyaM&bC{V9$Ar&f=Irw{|(DChX5{_oPRW8v2(6{{GZ9}lwr zJGPHR;*Mh6C`%CEkH+V37Di)N*A0kXJx3hZBKxycAAg%QVdsY#vYvM%`2Q1qyLBfu1|~506VGV#_E#KNNq1{6-+tI!@xBQvB76U5e9D zLj7hz692x0Uu!o-!GHTYtQ^PrRf*thOJ*##o+!t(1|H(|bpLy>kpC@hSb;qgyNTnb zr2g4)XB>3wE8(%2^K&ub=lhr9v1iXlsGQ*X64k$lhgq}L>q6PMfFI)g)A;rHR8_o5 zHbo-?#rRwr*9nQ4&a(D@pH4TFZ1lpVy7L8Td@v$y2oj#p!LiMJ{%L-o-HoBxYZQqF z{dxYE)+a}P8jIwF<><10oj5f>8|TN2(9nMc3em z?k!gIffO<0pxIcQ~{JWm8IU<|BW9%8vof z1no7g6elNK6Y)XyksX6$kkzRihhFN7_ctQ=RO=mw`dcdTY2YYvoaTR(mOcVARA;}N z?hx-!@mJaVJ$g^+z&rw)iPzKfwQRkbu*(U(nMRK&K2G@cvaKa^oji}NSO2c?{x5#1 zApDdGw#Ducuc!PwrcozYv~`g^|L<~~0o-)FW%2F5SLpp0I2W|U2C zIsc-H*zc*@)9`0PEYj+Q1nq4(ce@%^kxecG%!hw#+#6UH3BC5}`6 zyb$yNg)7xq+Dz_W(fJR0-3B2#Hj?SS{;ryOrcsR$4rk=<4<+-E7h;2nEXNi$@(lgucP>U6rVmt zDtO{+ipNJ44Rv{_%r(7=J=%gSLyt=EZf+YwTKE8uU8`e<(tPkLVc|( zTW`nXd%FMlqIDa1c-u(ySBl^M@kT;#%Rov04;o*o1-PSde7q#SqWt?}(|nxYy$1P< zd3>cw@aa2zDgK$W0jFnieTm{v$#EG|u$cNeJ zG>6+SYr>DWLT2HKej&c;aQ{1id>Gt@oF6Fv<{CJ_%QFgl-f{magygph$GBm4d^}E?a{i_DElzu)aN&9xG|vtf zpFfuH=jlIDm}y#$`YS@kaeLz5zF)r#4s9y%u0%0@i}%MO$9OZ;&c7Asm+rsa-tZ3I zE>mTl`YXnF|6MI%Hp2{qy6zPJpW5$^YTDS;(Nz|||Co2h6*FJi{UK|ond5M6D8^MP z#&7HT_BiAgg>4h~{8D{y+VRm?eJ>5|&U62i;(J$W0JY)0 z?7&7g_Y?0=^T)TAYqQrsU0H{$MdJNw{1s!Ufy)lIviN;;xevxUO_uau2q6ALPoX!) z^YVBkeJ&OMpT=LS`-Z`BLorm&O%TUT3I1m9ScY%LmH47!AdYJg|I~7I3>u!^gjX#% z{^ec2|yAJvDqTfKtviw?~Da1-(V)c${I)e^C*&G6@uV*5YKNejb- zca+=TRZ^u7gXg{&7{u{M`E`eZIXbJ($4eWYAE)|~sfHbv%#1?s4jiAfKDnFsXq=yx zj$g*>#pkE>=d=1uzzXGTN&PI1pC)Yy#O-OhaNNc5=|TASb4?Jo85UrRRhW2x>c1_I zh(n(1RzW}D_|hQ!lF|DBUXK2Xqr-UoMf-z2df$}Icsqa%8ZwiAA0#2Vbl<5lN%mlpFEEmTqKK)iN z5c(gj!#l01;&@Yn&zAj`!6~*9RbRS_;}oB^9?K9f#82gQ=W{BP`SJhvI?{z6rSE*w zt++lbtq)t5`v&(XXtTDgg?N98&#+}?tRga$HFjzHrk`#}ISQpESPDSQ>z<^RgxSenV2< zJ!tAA)Ss1$$4(rdlt2GjI~~uP6e0T-=g*6TKYK2jiTTc}FyG%-oIiTLREyGd3~X}< z(?;|C6G|k%HE-Yw+)HMt)ZqL}T@u4eN#dlb7}4KRU6TBLSbw`W$r{`bwG+c^Hb1M-vm-~lQ zKhHYXhq)>Tv)$(0KGXgQ)gPNm}iuMmftu({U86X{#g8amIXCO?%&b)#qGpcgok7!dBGHMerSJ+ z9UUj&^Zs1SJ;URh0D`}@or95JSA<$0Pw{#Xeeb1e3~WrdBHG$V9H;u5X-Wdr{dZ!I z&poUE*$)qb-!P#+rFVZ|x8?zHobsEWx;j%&uw$p!)!~!qZy!&ov$Uo5EZLvqllq6J z|Le&dR3|e#UCv+h`%b;AhQV9q@oSsd1>qz7WzTmT6>f<4!Bfztfal++fB7xU1-kA@ zn6#-voFB?xdX*7)u(tw7L-p$BPuhPZ{c3OaseLdT|C+~#)P9=iH^&y$!8kTaG5>`& z=ztcz-DUNkOr{6Rx&DZDrh+Xi>>VNp8_R}f9H4Cp9%Cw&sh}Tp588x~q zoBC=T8<+I7?s}%1b6y|famZ#j$O)c@PNpa|#fF5}U|nZ-`o)5${ z<3hxGdWhp8gdd9ns-d&sJ=R5WeCd+?k^TJD*s9<5?1NEg-TX@93;pYDSgWqi?7^9_ z;{B<<_U^DMinHux^~V;kdSKK?DZZ%x<$B8+UjId7l>v`GqKN%jd|)^tP9!0HsbYNj zcA1YWZo>Xxl`G=&8xej_+O`NyPglUvjN>nn=-=v>7eh0<5?W>)e>6VRRV_ldkC*YG z*@?ROk?Lb--o1gwB0aX{({i!Ci|+rjTxZBU>IXB;X?6Tb>Jxu$9l*?+hce~!pT+yr z{KVOj&2X}>xvc#+d7uesd&ufPOR73!S+P96PdqlpiJ^OiBDq z^KVlw_~Kew7TgVDM10Wtx|iMk@yRs@qrJKPr~BW1K8=BYMy`Mn&TrH|-L*bY$X^yB zB5;Iwe;S`Ow>gcef0{}3MOt4|;--pMh7Pj%9VOo$SR5tnzjfmFlj75IxHZN)#Gvym zj?YAb&p(+?Xmwf0p|nzr&-yDv5#PNGy|-Q#zc2MaTHK$HO{^TL7%ILWt-m~S8Cs9 zjq}FYTPyG+f0;Oc)V>F_^2fbixrjKz^$F^Kj{h+Rg$a3R|DNx!qxJQkkrPopqY#+r zF5aKo_Z z=^y;K)QY8@Ppg|>ss3}KwmVzfHi!*R+g&$*(s7qxO;B%zxvYPxv#T8@wjLqtA9M*E zgx>uYOY}#|k0a7X;%VbdN&HRm`F*Mv%v)yRSSZIQjjx|?7>(%TxhPEz66crJZ^tel zgGajg!ugnm;&>v_&n>Da!1`n%enfG6J|p)3tba>ZqGrcV9h_S?KT`YdZP*IazsU3B zL3drWpEnk{QQSUI|9nnKcbuFNEU7Q@Ao}*9w^j%%iN*K^Rdw&zM5155NN|M9iDX&- zF|11{+B_)7$!v$Z_m|dR`gqNU`J75jN!Jy}Y5k@BmJ2A3Y{h&M72`+sv>xm9Gk^^) z=KeF)zw^qPKx>c%S|8=>kLo*J`?W*YtP!&HL9>fHA^GH3+5Uu8{|$t*QaGxY^ZBLm zc|g=C{9L^PC+qr`Q~$Cyzzb<#vXJ7+{Y$F<=_LE1_H8ayyK#Kc{Z|D>W6>zJ06SW* zs{208CEusz_5ir36iN8+8^PDPcgn0d!%lYn9t^988=eDktm`iE{!vzv+bg|@P=QPL zp|bwt=#$;BE;ksv>hMGHWzxV3J1)ec`ZDJ?n*V!IDV+VvQczS^e@g2w=I)sd+cTwb z&$wj8<1cA_e{@n94t=b|!0Q}e)PD@lo{yC3jksRL^M}-aUw?ia)`R5vts6U!qla2C zi)fBdB~rg{>)DwZ^a)^NPdyQzkK%Jm(Ap$APnlan?FCnZ{Kz*==|?c+4^7iKL(h2Js4BYb9~bH z`eC6Zd_Cgua5(2jir?U|j<`HN6)^=|pQiR%(|ZD%E?b4%pWHt#C+jmKYbG4rOX2b4 zA8~$YecRc9P`nzj5u3_5zNvq??L{bb^EM)Tzmxd>bpKqBf6u}FV=Jbys1CnMQu}M1 z-i3J`3S=Gfo{Rra@q16RG1`w3YRDee@gKo&{EapkXEIV2zf)TbK(9&R(EqZHe;HpZfR{%DyT!mfH9ADJ`9lUoYY=r(?TjMx?(*ANW zs-bAEv`G@bWRUpfONf}wD} z;4sDZrSrB%C{-GQjdt9AQ+~AW*#@^#M#{!7K}-ANy-|d$|JQw&2i^}C^c@-fXUV5g zSWuRO6|*>gsQ&Zi=O{egl!NY9bL#LZwZAG)ys%p>4+evH{2W5?XVBv`l%&e4Md5PTXcp5L6i$_S_w_AvG1 z^GoBCo2#|aqv3d2efQ&mu6R&8P1e5e|7eNjrU~$S!ui32#4n|XhQjQPlpm?S{i$Fc z_HEmQFNS*J{80bUDK!j9T3b+(;aWF;Qvb5oeLa?vJB4*L;rOHa{rlWLEZcK|#Q&lF zX^LC-V|O1cW>Xr~SaJVC%8$PN8{w>%JU%ruHL$(yC|Uly=GPB{wId|;J2XES`o#^K zKd!(Xn@sWjq6ohkeRqfTwk%w_!{h4^V!u_qMnJDB8(%7U{1QdiRttor|=A?)ZdVZ+)`EIPR%WT$lH_s1J``PYd9~N%9h&?cj ztHYNxzFTASyQa;uK?r9%`S&OO%fwR+@vy$7tp7NEpaxD0`x|c#;_I9C&sbMwgyq+T z9MUare`$PtrFJO()K5cKC7xfU>$6uAcbs{bh3ls{{%HK{n(Kj%?Q)=bf#Z+X-^3St zV7*QbdTL~g@0U;TJ$|$oj;+j>#MiX`zbexY8+H|9bwjTIQhl*wbsW3~*C1gi$DgW= zw0?5b0pa||Ek|%5=Dvu(dt`s_{&NjjPM8Htj7b*z&sdZ5;cbj-YwUgx#H#GS^(PYd zL}__q3nX-Nl*R9*cr7##Z1kEUjz1cocOIdSPv@qi<#X#+@&E3T{jc4^rEe3STmw0_C*uuy-el#LGo z9DjQV|4r%afr=wJlK7hDr#HHKAmLFCZXMzHD<=5s)^QU`V!oo`x9j5j)Ba6uyy~;y zx#mpWHrbNfhqe*`IB#`i0U8<1d%*=heASS97NqvY!^fyWVtherbLx{a-&!_+Eq+`rN+K_@ur` z7j|&ebY>s*ioYM}|Jd<<1N^vWDan6Ck@!ISjJnW!*HhL$hVAHrWsx&5PKU==6#qL< z_eOQO5Z}u57ia?h@~oYn4FY@Um=Ib5H)N9^Z>GIuE3 z=HkfSz9=SCK$>+DgQ;o;JbbVf! z+Z=uG%HzXlOh;TYn}8ix6!S|+Wfz2;6k<#j&i_ipK2EbYN6hC0L|F0bjR=0;&hf|o zR%>8Cl*bn|e>t*W9LyRpX!NcX@j>ITe>w<@{#CqwlvNvGfuJ${&3{n*x!S2?A!9j^m5+)6t*K@QlxvPjT) zaehoB@!OIZq4sa?8cBYW@?#)7Ecjk3lK6t=H-9ha#Plu&vA`aRc%#k`&2 z`XC#x!?^vW@ki-gSA;E=$M>yX?l^if4-H@Q_?qtjFKRgoLwB!){ymN_n*Vcjo{sgc zHo@@>&o2ZJ{#;lTf*UGTaMbE5;*;{Hd*_W<$9`b`432NwKiVj-7G+({Sf8Q+b@-O< zPfFKphCUHasLJE~Nbwo`vpu#8=kv+&uS@n|xU@);*k_7AcF_;@uB^eEV$QD=Upj}5 zqFrUx1^-S)-*NMGh1rNa{4(YG4Xt1Jb;unx`UMyp#Px5Q z|5J$`fh*xF(LXy_#0RzSuEVF}YqQNr?LAB!k0SW2oEL(p@2W7kn}Ik^@plQw?y+@n3vsHmS1}=J%)csN26@jd_ZvV11v2VY#zSOv8NY{^&wIqB{ zIz2!Y=P!H7>YLdcJ7dkb*%JFk{kLoA36JqhB>m+mzfVc9gZtwQXm;T1i}HKzbthyU z$dUDr)#7JBzv))w=L{F;2L#{ND)XSEv;%$G7>eT;NqqS%tsF-h{ytDDujYHok>H47hnpI>17FeFb4!;*7|7+T+NdUH}b|<>^Xd=O{l2SX#c>5_w z@ZLp@%|HIuit~qb{X8A=3znbFnesRj@%?FiVM3%58*4gzpj768($%Kc<UKQH z=po*pu8-$AO>pPtaLN9dVzNKxoRTJtf+xxP7jIYfz!>HL~;CxT< z{WD1Z)7q^yd+a)fUH9H9e*Y+fk1WmhOuyA+_I4)EuSb#d>-PJ9tch?m7GglYzA1k& zzg8I2(nq$xu#J^2f}KKS`PFiP4HoHTqA-ikF9<%S_jQE2pAf%&@|LpHiN3(}j z(0%P9zCVrMw)dHZ2^H0n{yH>%`)2+J)2gNY+o=6%nWhAEvytV;f)9-mZRaeDuiho? z(6m(`{^`!=57rGO{80O=J8IuAk@Q!NBJo4~a5tQ5Q-}@!#Eb7o@l&zg9lv@PK_{Na zS5)848Z-h^{Z^sNe?{W;T4ev6mWLl+m#o8%U>|Y3JK4Xu#qR+ATyM!*|4y;u{3Z2& z0v~IzU#bD@*|`VeIK@xzj1M(guLS!%mA^m5&v&7JM)*V@S$)0UsZRKEGX#$pD%Mv{ zxOK;mA(0rT#Md94zuBH9@HI@vgfRa9RDU@bWQ{P}OpNj1_@nwmC&TIRUa}1n!(7Gr zq4v4Oftjcuz8!i)x{Ko{iG5C={->t4yN#@V^89pLM2rZOjlUb3n_$+pWW03d_L=&B z27??C?U#p`_NC(g)A+IQs4H~06{4wSf;dj`vtNiG{ZALk+Rr(IJfKmq3agKC{LuQ) z=C{2u|4a#PUF7^j``f(s1RR$2YTT5oYjawH(MO1{@KN(5ipBf16SiUb>q_f|B8FQ7-_Qs9gh2n zpav$d4iukye7K`DRznEMAULu{F;zqNROioeMr z_1IPo2U-02-%?}iCy!&Zs=0lo@yWgc8mz3|MAkn_F+NW&d|Q*W#~2R>E5_&0^hU5c z;4JaKDL(bvwM3h9KC=GVUQZodcri!TKg<3;2;VLUJt7ZqezYd~o$*X7d~;lZXd}+A z6u%j+LAWt?8}58{7Uz$~=Rdv#HepP$X_*s8rw?pXVib)KfVpB)F;dOcmH^GL!NGwq<<%k@A6}YV%|e3 zztZ|s^_K2J?{uO6YDBX5eiUUn@8}Kmf7rOi`7O$uL8vASmrs@91ytazh*PUb~_V~L!Gx}4Z@cfa{ z2@To!9@6-q>br%{-_-a8o1hSi*N3fPBkTxpk@de;6)NN9I9~~W)BOGG1Z_;#pDU}M zU2ir>*ngaYRvQ$rkGBskG5!7u{Mp6VhX>*J^H2OR*F@<5G>h*aqxy`t%~UizzD-j9 zMg7;@hO_WNXE#!R^b+xNkN6h>1F|u9+e6el$k$I4>7Ui{K(_FGAK}I3Nb&nA5&wVm zbB5G68qCh}1OL8O()jdJP;E`iG4ktc?imeS&73UjzbrX#fca5TIN-?hk2F7>5b1#N zUGkC8kozyxzhBhZ9YGh?z@n~yE6uN#`ITVd^Y6$G{8xN_ntypRavg4k{6s(t#rPf* zumQCdzp=|ovHkcFT83U9cmZ8%+t`CFo%xNKj!3I@%?H1 z*4)SgUrN{Fa`Uy~csa2TcKIWabfN@)PU(F9$o%G%Ps8)QJ5l`~*GDo4e^@&HnExcMh53vt9{;0l``=u`yZ%vflpLjmT5|gH7V|ZPEI$eU_ru8S|l4rGK z|25@b!{Jk~&3`+t_go;pe8)lb>wk1y(Hh6XrpW4}<-H8>x;7f8+m)1V4Js-Lde%S`7acD!!jS z>7UogeHxx+?LxrWp5i#ouk84c1HH=UXyXuN^*{fc>W@R!H{;=uCT!a)PjQ^Czn@$G z;Nj|FtoZ9t@&1%Qb@X1=B)&93SbN3%xNKKem4Z+_ppk_Ke`6) zVSN7;#i!#7H@w?Wg4HSW#rdW2xR>W|8QvIcG^jeHx{|f{4Mu_uE@uxiN zMa`HErs%zf|>vw`_N->Yj)d{ax zJ2prCr&4~W`pLKf>geY@RhA!f`gX;q_-KTL^6x|KYo|P0C>II&PHFbgA? z7o|w*vnl>=w;u@uhf5DnK8xbE+AdXZ0(BC2u8R|RHGu&Mqw$(O#=JZNbz zYk%)fZ-!Ej(X#%9g|R-aq(ozCD~>P9Uk`^{AU-Y!Cw}quN%{YWo*mA0EyV40<>K>E z{0-EaivH83_@ViSo9k9#PU;Udw&n4c66xQ0{_1xOzBrU!TNYx)^)0DBV(0V|l|P3u z-?@DLDF5GI^sHutznLU{ru??PtRA#tFloyo{ah{1-*w`j%$X;gJ$9fB87HH}ak@S&Z2h4ood0*Z1Hayg z_&@r>-pmJoo?%atV*IUXw&(xx_1$qjy>IwYC>cez$leNBQN7#4DheO7$X?kpBO?iA zWT%XTRJN3!>nN0VW@ctaw5*K$&hPa-PtN^&z0dFO^Lp3&{haH$?(4qp`?(+S?%;Yt z!=7g<*H^wjU8)14J2w%+jlN3H>3oS6pTDwY7j5C$_JZ{NsQ+YqNgJA@#>nR1QT|Ix z)q~@6<@G(huni0zu9MBbqxdXbGyqd>%JJzz;>XQ)HfYdB>_1LDDSf|45`Qf%CSz#8 zMTB(qk)DSUecSEPG^pI-5IVM-^qj`mizknuSEs77{Fc_w#!WbmofEW#sgbbc_?7SP zlimgF_(^4azImmAUKfYT<~Py!ds6H_a2&E&QQr;l>W)!gw;-Ye-`_z*-<7W%jCN0t z;<)h<>G#q5rF+~K=ck^H!N}7bU$p zl0TV?*Ya9F>Dc)~d z>7UW~Y3*i)X$5lq;Z5+P(b)!ZHiux|GQTEzu1yE16TAC5PP_X^qki3iv|VZ!H)twea-a?h<{~}e*{L>nu_?_;QW?3Kku)o z?GB`34AF65#T^}E}RHq-DvrfZ#e@$U@)K!cBJ%>tuej-~Z5yL~82s?g$ zkv>oPYluS`yZl3ruQ1a8vnr$pqNj~jjGynETH~3&AHGKL{YCK=H^mHd(?U@A^xt!B znZP#HvO$q%C~AD<_@d`eYOfoE&6i@)HH6oP=>Ge<*ApS3moU1;a%uf&{c*PGG^}%u z$CXbUe{?=^yu&P9iAlt_{k^5ndlP@eWI`}?ykRegnkmNLZs-28`MZ_zS1`RU7ROFkjKAHT8X-lT5B;w`PW7Mt_0Cux9e|F1 zczv7Bx9s!432Wnz;%N`=FBOycYyQL?t{G=Ae9Qr9edzhKJxje&Q6&jzJwtj<>*Lz( z&cgn6U7^(JwzNJpzvwxsq0s8!A|bdIlRi)T18qG@nbl!CS^ovaXWWPC*m7#DjQ^;= zKW23+%s%fYn=eA+XN@EMF?PTnbZN!?DLuk}&*n~sS=Tr`uFCyOil3(9-Po_*K|DX# zU;6$uKHl^3#_}e~*cd-kdQR(OLc?GTn_Y;)0UTc{g0D`;cB0mqVl+<}Qn`L|eDw(r zLGFpK@c8U4#TOSVd4Kh{f>%t}+f3#!Q~g(9U%?(c9i~|SHm|6IxyxqYu`OR8+TZ7M zvmwH7EK%gYP4zn=yG;N>_MDM^KaIcn=dH2qWhgRpqNL}0Nqk8hGz6z}Phe&Y&+lme zpYCFJ1YL|qjaIxrf#TDWEy0{IsfgIuRQmfa(LHwE9y-HYrasJT1{!5DQ z*Zr#_Twk2gRmqkoGnct#q|FHS9Tx9d-sD2x4T?Z9!l<}pvqywfM-;Bpj z93Npszu8Z+!mnGQD7E0vslJVM8Uo=}B+T!gsC>Wj{(@NpM&Mh~86;lj{)R8fANn<) zhvYHIcsI*J`aIp=3EdVTxa1}phR>6p`;+|FG;1mDpG`xT13N4Ke{I?OIURcz!@AcK zu02k(REM92=|wnbXeV^D3y?lf`7x(@F}pU{UJ*Yl600FNah%NGqx$f2ZUfxKAN3Gn4td zl%MP~e=*lxE{go*c(^t~rq0A05B~iqKh5uN1dW;NQK8G9Q+=X+wj*Aj-y)k2NBxmL zGp%s=&S4z&`Nv=K`6;2Top6431X?`h`i;&PFwmcmqjtAs_@MQLAIle@bXf|b>)1)_ zNACwnDPN2W% zZzZf9KBp3Y^7!)H`6C*O{V@lB@bkGEL|^LI6ymR?jS#ypRr>$FD*5@C%-^5crM=4d ztol(4Il0RG_P1dJ%pbi}QQx>O>x(_J_hQvu{(hm7>&t6%#Pg${V^PhO=WpI*f6oZ^ zfY-vSm^YR4AFY4nkK2x6x}P!HjpLWrH^$}UvmpxxDCQTAlYTLS6|T5fd47ZP--Kti zF#P;XS$w7aq0PNp!v2^XzZ#@I6w{*Kdl6eooo682iSj%lMDpe-&_G z8SYkO;)g!RZ!y7d`@ZL35^5m4*q}bX8dmv$2FzN>j#ZCez1gMk$a4~I)aLP*`eXY- zKC#FIdzpVoc!zwyfqu=2-Jng37glO>1yh`kwmQSgD|GoRqo=;a9f zei4h{TwecB5q!?q@<7RmcucDmBCS8wpBwINgkMFz?0#hvEBX0@@@ZRPW>$zL7r6hG zPxNKu*emF3*i^_hzM%a4;A}a&;_a#!-;cJbh2*@MivIps zpB8v^X}!#!p!$5Tb$fWO+XAPNJb$73ahI_QbE}7A^5TEb<@{{?&I#ieo<#GBJpR-9 zkq~F^OuUf{)qgXj^(`j&?$F;Gy&Y1~&yw@AwzYgdd_wm{xD=C)I)OVYKQE8(dIJ~1 zBt9KSLJXznu~dI*hrvO+y71U>ge8yva{g_1@GM@`ZXm3VRgeEwQ{G`&n6=Q>S3Uka z-}wSn_aQ<(joiw=FW0Y{k2EppjxxUYCe??J`7%X+?M1{;bPYNK)9UK$18=5J5a$=g zBYYF*S6aVg4*qa4d?UkeF~M(0cpyISFO=0sDgREt6NvN0g}|{vQv6Y={BuZc z-B1|VEL!dFUo^dtrRzH=?*G{ff3OAO{J^AoeE(AZE*_zajk>cG^K;8LhN!Bw0r91L z|4{yR(h%$atpZVD!2KbLZ^M1Pq4Q=h^b`62r}|6#j|DzA49C(|9RIXG@wNUe?CWt8 zj>|cJQ~gm^I0yYtr=UafHVL1UpEG97L!IxbnEAM|^c)1g=;)2y{kKu;3+I38-%T#x z2@A_|G-)$TT7Q2lIle6d_9AtwhA{kky!4#T|0&EqhT1K4g{2u0(sRn+6%(H^n-|Lb zRJ)BP(i%@toKM=YSAAUjwoF#Pp#Di*xhdeV53W_XzfaeH`&&oM63>|a;}<&r#AJ-C zsNco@J~z(qRDXDicT1Hml;hup;Qz$ai?B^^BINZblYT$t=TP^LY~dR5j_=C*cWC^w z4X=s*-pcr_(oF1sG*`x_Pml%l&xd2g1@-uP^U47>uTDa*@_xZs;vbboOu*+W2}u5; zK7Pf#od%1vWDKk~o&AshvI+lI%$m@CeQzYXUw&d*do---*t ztgC-9yZmY;e&qFs3b(^Z8(u@u>UoT>FUju*KYz?x6`LX9B=29O@z3D*H`b-ZRWU#D z@vn-fK@$}9L-%R*Fx0_E(Led|tUZoA--^L0ynaUW6aT9&cys(LyrVh3s6YD2Vm$^8 zd?Djk4}!0(vI{7y+f)%>I<@aJ_OcIVq@I%2pZ@+|Rv%bGp@U-n*+#b}T4~Q#jQ`cz zHb>FW4Kn{YUnTc1{HmB@`O1AV{Y3o>?_L%tT607^|HS!|_K$9OH38=g5^+(rSNi@m zKV=Eia3Jpnu${+$ioc)rXCkrS76uLA_^U80|W*7GICbgD_>$cYF&z zC_VQj{?EdP!Fd1U2ef0~Nb$?mTHZgT^q2QnQ2lBe z
      FUU!dn5r^@w_^Z(|3xh$r{6#gk(pZTg}_K3zZ%lGV(o1?70O8L#&S!0N+I5ctbaHvfp~&vVy$;_RG#nBm3auL<#od-#|m=GPHuKjQeK^?%Fn zo;cCsI^M-`f0E*FWz1AOb-oGfn;d`ng#R9j{R4rgZ=%_TEfRidd`{Rt8@E=bVO=rCGF9C^>)Np z=HD&^KMt?#;XM8{iu`zg1jUbUOBd*coJY+C>gzj0@2rFK=@%#g$4@@N|7^p}7=F7D z%U#b^?k_pNyN2g55BJ{q_Fg@{GWHa(pY0rF=kqAOqIy(;Q@4qV`oTF&8}>1?73+g~ zc1=;bYJ;qPPxardyFE}It&A_b1p~3X*HP5Dp&nmvO~u)F1pG_;+``H*2k&b}KU@)lEOI0)-z9I0G?dH;3e z8->s}7$S_$RiA%*t}bK6+9MS4_qm@Qj;>m+7$5JnYlos?+fkz--=BH}fBKglaCFES zGNkxY8pvBO#~<}?J66+%QTsWH@%7mGM#!kSUUoi~`k&1v z^+4p<{fKYG^(~FBt*d!pf1@OzL?+bEQDVjzCUUG zZz}?@aZCv!HQl867fI?@L%g=Z|K4|G?J1Pjm);*T>Do&)IASNPUd#DSMfk1tf2B->+PzG?mw3+>i=F#+QR9(d3$Xe7>LkhHd}jsF)u&EBwpa{F*4!w-le3hBQL&ZR=6E zhw~SWui3@Mh|}MX-F^A`Qv99!Gz1rnF5u@x_3`0wztBq zz2dW#_>sp49XEf3o&5~$txgjD^a%cHTWmwG!R2UX_o?#phBARN7Ta*Y_fL$-=Kc!J z&+3Tvy-puSDE6m&ZLWd&#dA=!lK+0{|HfSr&&PLLp{U+P%5T5ZPZZbNAmK8dJCEFyeuLjw_sn^n3;Biwlx^rCm`;`F`a7VV{g5 zwo}_pF@BFbRUNwG8Ahe~7hbG2Zs`Qc=I_$@J@jvXlsX@i@hjEWizeG)@1e#J#wz2NX76<>C9eCHE=Q)So`bP2wVXvc=q=ktmGb#`MK zGrD4m0YU2VdCdPA^YF4m>_m>Qe9~VPH1ZFdbH+o)pR~TP^J8sHUcN%vfBo7JON}-n zEQ#xLsxMvgyNP>uKm2ZS|4~Kqm(7m{BVo%$R9VaOH|kI6C5*#c{bV%k&f`Ble|hlE z2JD;hNrqqQUuE{$h?j<9e%xPu{C6$bgdfHwNMA5aEq*l|w!-$yPh3pl_@(oM4Z?!( zcfE$Naid=)KIQszO?fb0Csq-zcDrHmKYxkVFaJi~XD@6mQM*5nfAsz6?)=Q!ta4M- z54G!5N2t$S#roaYDq?@!#2{IIP4V65a(|rZc^qdf`1_;yE^xMmNl7$Zj&XcbfAMM7 z6r7ouj+q;|KTGj>&tNK&L(`G}X@Oe&w=G_Yg_~Z;_*sMS^T#Q7G4Js}aRwXT|I~lY z4|@cc71qM3Ylo%vr~0ee^4sj=GgD;FRlh%GxZ9ZHm*$^U zYBfSpvrSlQ!TFi`M`xqDLf?Kr=8fW?r}+0;ISA*1FCw9M6aEdExgGwt8p0WO zj&GX350AaWB2JjY@BxoM8dmcA*Q>1l#QGMvDe8}^=1RET8i^145_4xgL*$bDm)A1pe<2Re|tIKck{>!=q0-_^L+VH*;A3<4ffQ+yby6da^?9}if^Y)U9i%8KgJjE z^>rcqomV&r*|wK4=6AUC{i*(loVXTQ%iqcPd7yP8nSS*gxD|~?R$%Y)BFq2rBaQ!? z%5&L>(H7V+iuVUle%xwT$SyQ?SLDauN42oTY@UoCX@AZIRYN#V-h>;Y)bHQbw*3&% zCIai;^50L-zxK4Z#{88rGJd4_RrjM~aqr;`gaz>a530XPuT2)`mt^2WwIsPTr54O{r^|r&O(0CU9_keEHK zny+1tZ6!sx)_-v2@0a_-y*q8j>D@n&opPY^xqN-TnQTU#V?Ur#8kq3E^`rB7!^OMl z+y^uherlIWpQrkvuWt@p*55+LpA_G4{m6!2byqyUo>Wx}kGCn~`Fu{kfzYFmXhIbzW&72#k*@5Gi_9q>vI~miOXX5pZAojoCPtRZ6((ppmpG;&r zaDRc$5ApW$LeiKl6uK{wK2QDUpA7@?OREAkv^YQHllXM*U^XV1n+rcJIX_Z;5H;ow z8YNo_caQVWQ~#&2ULF=zw-e&$hDq;-#<%4iQrL@-K8pU?p5Py>!=g#>JN=J80Xhde?8w|Jr*Pt%lNyP=m*#7>(R=i1X~vJ{i8wr@#oVw;<({g zXoQcF^fm2|Xtyq#b&R)wYvueQivOb*-?Ilt+!gb?bBi^RInW#Bd-?iP|DxRk1Ek*B zgc|ezJ(t(_&Tegi*J2O6l7IVheIIig9{{l)B4^{!$}yOnu)DOoZspGxg?%%N`9S*$PEsapO^Rl{HGs?5OIb<<~@#Y z4YEI$S>~W)H%me573c3T!rv{=

      42>#_hDuR_lGEd-?mVpd*fJHeogVcZ^$4l*>M#X zow&ZI{2tb34Z1b`Aj2=!9|!zzvE~+iF{zdM`i#x|EcQ{uQW2k5#=m3JektQKEV?Sj zd5ZHREBk{fK0_NCpiLuxI0bNg(){76&>QyR{H94>oS!NFW~)XaHTg&qUioY1~ z?zco$25e1jCH&C-1n27>`2IE%Z%r3T&*^-dMfE-LyjK>IEjT{4iT`FOYRj=}vd})6 zpKk!sFORAOB3aN7?#2~c{x3dgkojL>Mw$4&#ayti$N3w?AO7!j7Eb=Q5LBUuq|ej* zZcxxyR{NnGf7HJ?bzKLB^;Rq5&-cBd$c@3W`JDMG`TfZ5>Fp5TWFLC0;{FN6XB{zj zU*s4o(|4A7{rka7H&S}PRG;P96|jYqM=I*)Cb?BGB*l4p@j6mla$ufU(HsMeIiV3*0ITMZF+ezP_)|Wptnur=l zGG+N0tuHn(oQzpZb8&I*F6r~Me@FLW017v12wFWjK570D)LZPY$gLuDtnMeRKRw^1 z`neMeyXy#=JB~{0A4c$dQa2s1tD6h6wiQ-Bm+NPfff-oS&O)YNDE=#gGoV^xA%u+V zD1Co=KR~)p7D^vj3RVyK{-FA0cxn#x=UNNK;oBwuNk#hSQ_M42*-$yZ(fqwrk1y=A z-ej46r~JN3Uk8_BS1bA>_Du{Cl_1|=RKHKT(GKTY?w9eu2gxt*iT6)tTc1VaBm8^~ z?VlA=oY3u5JYGKK{7?PECNFNV10DLI=?V4xUNS9%-4*X&nbnu?Px|}+8(Ia6`p#FZ zkGvjN50=xE@o(nc3vQ!Mz(41#^!~z#zHatxBzg@xxA8H7p6Zrm75&bc7MF>vMuO;;S#_KDTzuPamjbrJezhR_)f4r!gfolCN zg`g!I-}LhZrdilF#7dZ%6C~j~pWyp$^|$QN-I0p^)2r#)2qBr^6ooi`iJtfTbMaCgU`Y1JjXZn zx9s{%!2_QM*ww$C^nUz_{_`|ijk4e(#rN|dIGM$S^vCx*>hV7^>n}@An=jMPRDY~U z)5F|n%J}XO(H4`O4j)Ki=JKJRZ8_pzD0@57GK*2dnY;I5`K$ zEO$uwizNQ2&L|ID6l+KmIvGjNe-L~+1$*Mho_iQ+;UYb!{^*gK$8c>+Gae;`*Zo=)vtQpPE7q3=G^k*mf6Q0Z*O$BLp=G1Zviy+h>!Hos zBJukHv^>V~OV4+OWRF0@ovHZRnB$Y4e>v1zbMy#Xx>EATa2J-&Ngy@}F>=0cY<9KZPlzx4`lqN{_s@cnO+w7yjT=J!lvud}Sc z9;(Oh$4mLlKyxHkw&%Z}o{xD}uR0d%_$u<>nlnux1niK-cZ%P;3rsMlYowz8-*)Rj z>}-1hL)vryg8CDhZ^q)GZw{i&IDVwPIz+vkgngCg+*-f8!voH zQ6GN-Z0h2UYO|ugsCv2$R;@UQgPpm4p!j@mV2rf;Cve4pzdza^lyt!c8shn_YPr0= zs3QL5$MO~E^IPsudK3KWuUdr`%SsVa&dA^6SQf19=4WeqDIuFohxR*V15x(r>Q zxIZ`eRYUKIzGyS_-|wp?^UuacG{*8%J7oPO6km@@2Egg)1$@}V@k9A>r|ocD3{Az4 z8(d$}{p;RzEH;hJ#o+xMKQzC+b4onhTyO_JJ1>{szlzLhaleO&uJZuZ&Nz4?z|6y|(zD?!)szLA> zeJz!>?!Far`kl*o`gb(VU zG-bi?FRvvGoL(V4r~3SleKHc3nhV?3aePvJOb6iwH%ji%Vhe1=2yo8MgOv}4F3BZC4HbG{eS7vhw(~iDqLH=Ra#$~zn7b( zvhwP-=(eAKKgz!eW#z2MaG_%TUKLXt@fVf#(I>-3I6G{oqCS06uQQAX9mmU6++U*o zPyL^aL}cw8Y~LHi)YUgLHOGl}kKV_mUL5~)KFgT7K?vAbOW1k%PbI$O{kx6Fgkrfz zQz6=luMgFiol?P`h75#VEgqjK{#@o|v#1S&VCly3=S%LF`}FJs+v7P!(Z9;IzloxLqbV}JS`nLh%O|74Vp#*fIm@UJ&mT0iQauk5=C z-d(b_#`|EwiG;bxc{Ld`u^pYWV}sP3BLPcc>X~A zlT5udRDEVIq}b1v{(l(Z-!H4O*rC6Ja4VSOoAT?L)c0(|8?gtm(jTGzbd747cyL9T zU$ci9!8=76-`QcJH{pE=g9|vm>3p3B8?A9~4MSq(`7Y`YtPYeSAs$a_kJ2x6~XD@2cmAm6qR`_uGYv{>e1m zTCmp*P}J`OSVwf78zGxNMDba8X9#X-q+zUfnDqPTe9iYA+>kXt2Q9~O{-pjhEXH8( zu?J|o$wm4+?Vk%Z-UwGmE#cfm-ruQ5&PSU$Y(ysyEurr_j$dD*FMoIe!SUuox;EDb z6rZC?uOr=AC9K?cM#3iuKA-5OF#R+;Ol@{j`hJuj+=phejA?_hHC8=7TMm84=KPiO zFOC1t2UmsF8)bYBacKaj(4DgUl={yl6IdI-jKQxEK5eyu^{zD$;Yx&!wh|P^>Swnw!7>N2%uD>XLgZ8$- zAGc79`l4Rnev0mkZQ}h?|L_}2>MKX1$70LzM{sM?Ucw*kKX3nR0)pQ^#g7&ozurV& zh!|7qZ|d^71Bz-!qGwN@A5eW; z9%zN@!vyr(%<HQGD5;r3KQFWov z-BtSi^n74Y1AkQX*A{k!aDPBW;@c(h?(WAobc9;H`Tn8&J)*@e*w1wk7MGt)l;vbg4d$=;(z>2>&r8qZbE-;9bvQC zV+r5%{N>UP$%xLh6TTIMO3!KjtFpMkZVhvQ;cxZ$>>7WYeKjAVs4uSedd-Z#PnG3& z6rZI%G{pRAtzv%X|FRyQOxY#7Uy%BfRnmH+;O1q_8OQxu7s9`~Vr@F4SsrqI)Z_2# zh$)!yp#bO3*O2h1NBFf-m3f%?OU|z-x%WgZ z{@%}t!)&vGLgQ4S^6$(0*OyGaijHFaFlxYo%IEU)Yt1&rW5^T>Vda?*mCxnE5zp?!=OK?z^nR?jrlV1K?=g04<@$lvSC+eu#e$^oUx_`&X*fFdCcehuUK5s(sAGSQ6b&RmYr7B#XQha;0c*Pd) zohH*?G`}5Eub4&cQO5t)R@z8zx<%$sQ2YnnYzDugP}zL^Fft#q*THreI`t&Vy7Bl! z`}gMATjG&Z5`wij{we>y803gaIqBHElIsV0el6tSGIY582Mg|U{A-Z>-~5p;A|o}0 z?Kzx(DgJ#${=HU3SIBzJ@$XB{7n=oN!RIpr1(Ub?EAdP4JunXECz=b{Bd=FJm+udk zWpQv1H5Z2GzOQ^P$N!0EN$lw(NAdo3{`+bFdhv!A?AYRIvidK5e|`J>VV-Z4_4B=t zdN{Uemty_M`<*F_&%|MA<$QEKg8z*pN5VJaG2AlSN%)H-_3!ZUqcA7o32OR|l%7-l z@M``j+{t-@rQ($2|KXp;$H&9R;>w47jK8t5^6$&9)8gHN zT~9X`O5dHa{NLZF`tSF&c=o(Pg?aON{{Y<|^>?ST@hyj8qw2Wy_bI=O`T3d6YqCVK zKGI-l4ZIknygxqQYKrDf56kjvxxS<}3Qg_Mbk5K)(`CD7mu67C;;QU}h`ojz|hGD)~pZ+(0oX&5s z4{*n+DNitbnR@+b#!@mI&@Z-lD6q;|5-hWrZzd?4M==|cHqW)Mi z#SiH-YX}$4u9xsf^M@DDHsE!Qn!?gsiIw=2@Be$hQdpXX3tE<|$DifS>iDum8DFhZ zo502PFq)j@`7gy6&iBHbTrq|la(ztq_qR#r7}z^mravhDTuWA>Z6{5kvA=qJWgd)Y zQP-`JKb5~fy1&|g6j=XMCv3T<9$yYE?y?2L#=*OJgtY!tf1Yyx#9IEhM6rLiaM(|# zKWLqzKD{O0KN4Mkw=936@xR`eHfUfa$Da$qU(cxyh$_j1)ex?~-jVyyw+?nktGuUh zY1L8s{xtrt5zihu^?rt`I}b?DZApIcV(3V;{QL~tI{YU+&nETHg(5%B8~Pg6J-I%J zCHdE)dK=KdxTfGCsK-}y(q@=+t1Da>?`HWwex&|*!okbX*l8hrW$NQsc$w&bdOIrK zPqcbU3d_`Rg>N>0f0RGXBB~)syua_?`4p-jirY8AhBJp1^VdJCd&2NX96Y~qd{g|! z^c#qE%a!rFMbi^m(?8&5PaZ#-6aAD@H=cPPu)#uOo}W$pw4pP=&m4$WV$o&3R?k69<{FQW6e*G{a1tnRxN`SWO} zHYg50g`^LB{}~bdmR@y$!-s5ivE=%h_7^yM4u{w5Cn%o0Pr{!E!KZVaJErU8W9W)8 z(sNp$EOi_OhqxCoJhid%xjcS9KD7cttL67wsZ{dw+xm&?@K?|lg8PI^_@wm-ry@Vt z>(mskJMsKDjOa6`75w7(-585S7g1eD8|7lunY5i>pzMGA>%8sdQ(dD9ge9sF4 z>ppA{f-5+_ss6myI+vBM9gm`PzQ6UXdVDmZb)yP58s{~zm#9gqkP~u zUm2e*qt@cXDQ)5BPafZ?|6;c03KmYW7LLDC@4ss_j7RgXb^?y;O8wvY1Yb`&++v55 zhU0=&r1btMzLpLB&h(Bb$2W^lRS}pF05?1Se(8KNp+h6|(GX{_R^Gou@t3&O1g&DO z%Jjbm(f=i4f7#LQx3J!Z>pzOWRt{qk7gm5eMO;6H5d9SU#}g5sKf_eFj`aJo$^8h1 z&R3c71v`we=lG}myJ0z&i0T3?Mpz1y;(2_g{P=9)1sn*l6uJ!mV9DdVTwl75y2<{|8-W`M>hTr* z@GHwpQ^r@;#wwWHI{;sQbN`>>%e7fUd}tb`s6R)XG{!n{57b!0-!J92&0ky*?)DrD zvba8?`}ct6f3U7!fYqH%rT1%Otta!p4m_BQ?O#ffYZ@Xwr}vXj_~eBl?Yjp3x7p9nBC+zEvJg<0c-Ju?Tfqz^vMEeDL zIPw0q=0yJ#Ef|j@=RToukhz2(dOpQ2+Y`q&lp@A&xAdIWM;11pguJ{`*mqc_7JtXi zTxQs!iy4@bXchVSM4Me%hyxGK)h4V3ARd~$xaX$@Tnf93I);_r4@ODr50 zC7Vw`@n=2F44t;5V8!r%`(IbK|5ntoK_}x}eDmh|lH#uu7Gtx6GXHhzw;C6|Y6}jp z!zBEG)bHLquR-8e9pPZh4bpQOe_6;HEWWHGSl0=X>PsN^XVe$(#Wc6zrzYio-LF27~GJl%lKcct=zO9dv zoj;`b{^{8t2JcdEXbFEmlwYq;vPL(}JK`NBJinv(?tge1^a_6>(Py3X`@53*>Cbbs z@Nvmsbc}l_;nSbgKP?Rw;?)CXepXdqfnr;2q4ik4Kf=iV*i?NrJ{0Q+KTXx|j|2M? znAv2p2hfu1H>#gB7T#yox6VM1%KMcmK27XO*usH+GJg*$`T2zHo;C4dYKUTerQON; z;{E1fvinJ?{@k{xD{5vc>w|?M!%^7t4O&+A$J6r(qjg81^`$qm`U&k1Z!mN$-v9cH z)`7L8_e1^T#9d=yHmC@lFLL}B6Mwr^t&MQFr7x7#;rXKmiGMRsTx3%(*emMS#z9GJ z&3bqI>c;C^lporze#PcSE|cj8itk3w8VIfti0)%KKhXJ@V?P<9sW|_3nI3;m@%=&Q zhc}l~Vbz8E1604ejkUt@`F9ZKs2<hZm$O#-Vr zawvuv@%>Bj?Q!rPv)MmWR{x^@;_}cUR`Q>p%zvT$D_;JH{D2TyeVfM5j*;~+t5vwn zzoPiw+q(-2v*H!=`;&0O>f$E|Z@*Vs-&oRr+p^mPBSV)NILAK@oEXAj3wU;cqi4Uq=L4Y77J=`LQ?<^BVm-mvoXuHs<3|iY>9t;$@zlY)8;`xNtu7^Z#;!tIRk`#xlF<@DRDW_Xva2^8;F?EP>3<^IctluzvG zEI-BhU>~+|{>Bh!_IibG|MC7t%D-og#-j7AQvA@- zlhz+9eVINCZ8iZrv%jME+&z`=NA3?U*|ioqpX&&nPmGY(7sS82@+%ETJv@buuf9m{ zPlNO?s(PGfHGbP;sU}|^iti4G1a@G{NaWs9&%deu`D{vOA4Pv)SlvHt=;%OvwBr0q z`Pb~cK72>Y_rEWxf7|Fc$E?w3Wb>Cm{DUgCeNo*c4WlRU{7-}Uds^=-VQzR2r*?7t zr;z$X+V{z5z4|u-GhF!kllT?CWI7&a%J)YQsV}5&5%0&mpebmNT_mk9olo<&b|hRD zmrJ(km5JJRbSLQ zn-1Y4UmvLC`QKt6FT8H~7a^~?KJX{_>a}``*gLHutWV+nFOdYFn?KD)wOR7~P=nM5 zF6*4Y<_l)R*vIPex2NtY%x*8|U;6n&6HdeQn5ED#pW`#1^!LYEiFaq;wh|aqkIyDn z@vNHta4f6j7s}5|^KzKq@mY%Jo2`pJu)tJ5+4($L-${K`9d|nIQPj_tKbvCmE;)Zt zeHU%5LZrPaA z!Yp6)`k>{>r)=&GIe$`rVyWpbc3Pa#|L=Sg#oy!mb+JA{&Yx62bxiAksaq2i^^#f#VI|M6I=rt2kHLFn`jhfk=kg|4 zeDaLUzoGHPEx;1n20cWpAns4l_)$>J5!*~(B5*3_xAg=cK~2Tpx?Fw1b+r2Y{dmG@ z1cq7(rn`9mpJ>I);(r_QexY4HHbSirA0_^y`e(A%Rpu5k96Q?Z_)YiMqs&Bh&u28O zn{xk<>Qmn_Pgu_`%N6;r(dBa1;G{DDReezhn~LT5qx|>1v^~~*PEhn$jyDtU=Gv2i z-ZT04r}$g=&JA6xOVDok4k zkn>AgS7TUoj)S6q^6+v2EB)*zyMMui;OmoCHN?%@Ba4qTzcDFkjG-@-@g>p*c7^7_ zCynbX%0F$N+Tqr)7x=Fq=N~9uaEi@{O#>F1s4o7h11W}<1e{)G|P!_klhbY z^|i;dM=XBda#?;z`TzF3H|$NEAHF{1`ArbPpGH3|e2S3s8^zz8AC2JGAX>(6H2$@j zXn_ppM>t{0;}h*~=mUGy8u%L1i`4s{pC?R5=vOTvw*92a{U@(4IkZ2H)4j}vh);a~ zQGa?%*m118ZZ6EVpDN)`MdIh5vnOHdXDz&r=lIjGlJnz?=*#TGcxC*(F34czcW0xU zn8*LmKcV{9{J(E(cGYc)`tEjlEmY}!M5ga(d|ffPEw0~5z@SL3?75N#X%yIwbBj~PEkDq2ali@#3Q|MJUKw5vAKehhpC3@>x!Xkr- z(sLEzuZol-Xp%la=u^t|1N9Hy`W%JB!GXeS)jkP7RG$tQ9gP)JorK*ji>2pbg#R{{ z#bBlLAR*hmm(*VnM*0f|MqXm;&W@1X4@vp$t9=67b8ZYYQh9xY#@A0X(%IXpa}@Kh zqOY&mwPHUUEaUszo9yo^Uv%+trZWE4M~m}QCL};Rk?SAYe^5Wy9y6Q2#fp%_()v>W z!EN10jD7wC{{?dYjN1xJ{A2qe>g#L~t~w z599lX;?HwP4`@_mAotI|=kok1tlmIOEPo_w0FFP}-`g|U6OTG;3j0=ZevT#jptd+$ z)v-iV=;J;?S|4A6znD!&5La8Ak33R6zW%g2imYUFq4+Q7w|r7xuv>c+&w5+P_>JbT zMmcBDbAhu^mZTn^^^;;yQy46m{IZttN&Bl#1zlv%+Plf_=cD-a(MV%kYRyrMuj7Zl zWV>|N%i@bK!C%<)s<_l}uVQ|6$w(Ld#XZ`k6_3x99~Ufag|ux6@H?d*pT@a%7#{Z) zZA&;lwTQkM*Vz$qf$uTB8|RNm!k=qeo@Vw>92M&aY5Ixm{DTRYGJxZU?$0he@3XJV zRw%~bUG2-5-;!;z^KoIMK78P*0rtho<158){(ED%wadiWJpTWwKXu~!0F-7tL2wVw zAA5;EmG^WaH0o-~^ewF)lvZB^uikY9>#wUM{OS?>_Vo$JN_%DeuI_&vkFQ$^jh%RZ z48`xy@#5X?m+gh7+diq~&shcMSqBX_+5LMIf35bWvh{At_}dctf{hPdFT3ARkKpfF zU=`dRu~&A#FztV9`b!66g(Hgn3-{cNuryT}fB$W=!m!|1viyzCN7#3N7<&Bpg1{-e zr1hoei%dJ6Vx67D8OWPC{;9q@VR?sPsrCLwZnHNmPNQ2Kq;e=747XB+4a5T1|TE4_aj zUpE{N$MK&QLi!R&&*^*!&$Gv2{Mbf#Rfp%VH2yw2919z5S4ICnQ0!Y?y~PdXNBR0v ze1#jQFwgio`0p)$PW9cszWHqa%k?t<~x;8$lSf4WL+!B4i zCZHljJ-_X<8GuDOPvNG+>&O0Nf3rq5m@%sWz_^PR~s`USsNE8MScslNMKnr zJrwV!nYQ~5YuIBYYUli0A1#@`psHQW-0p9~ZtZ{iSUx}J+n0Li&@DzWK0mhUiVdB_ z8PQt&_q!1PJ)mS5T6h1Bo*lS?UIBA1xvI^cLy&Q+``~dlJ&x)evUZo+>@3 z`E4T>irSsbh1-32{H6M^&ctw-jS=VHJm&cY?O$158jf|ftpwvJ?r+lkqV@PA=(F8Q z@M;py>tCdPl3#Wdk5}0Uy4$(`38F7AjEO+t40{>AeThHYGvF*U*zKm6Kli(NljXfs z=Fdl4p0QiCHpuWz{fWiv|FXy1_R9P(njgB1ZGj<^uEF39e}7az&UZD#qAkzRbenqo zwsyBgz~>LxFrLp}xkB(eRGcg3HOEQOUpdFFGP9)~iu1Mg8|AVg<5nuh=Y+|hn90&@ zsL=g~Z#jOqnrg$K+fl{*tx@fIIIuMaqqlK>r2M&WY$sSWPQ#)e{P&v>d%(T;7MSWT2$`j`Cb3NWHj6THcb7AEE-Q<`*>|};qe^UHD zH8zCZ)@#^aIp3e+H+N2dWVL*b*b@H!DF52Fw8iR$g(y0COyU=Mzx~(o%Mg9MfiTDJ zhP3{^WPg8~c^qxal=t_*Z4vBgqB4KG?~G$6*&Z0=!tqP>>FcO$7Ia;izte`*K+V9T ziuyY{q60o(xDCwY`jYl%nHITX)Tuwv+|B((>hJ${7!T)yYQpYQTp#F>{;a)gCScjg z>OyqZWNH00RC534y7qqj2sRTwPE?O?!;ph$an)Ry*-m|a_18Rxop0-|n16q+k<3bF zD&w!(u*WRae1lA1()vKi&tEL)ha6v2Uv?_cL(|L3`s#K?Gn`6Q#@~tA;{AoUpX1pS z-e2QO;{T{A)(9C57HkLvMv;M&BXaxJ9vDf`DN4c zW4PJGQCPIIqx5-S%lfkTziaGqrY+9sP&z-*;n)@S)W;L!)70ZLt#KBsk+V`!zna=s zNAWgg{xzK49$mE3kiC-Qlj_r(6Ng~4(NA2_=l%qpKfY)2c&zGLLx{@s;`k%^kHPqf zcr!s;=sqJzdQS8I2!nknN;4Byd2xLD68^pQ_7HS3Rl=4boL{Lvm{)S0IaSP6^cP>R z$YX0eZ@?}a_52s*{*&2S??Z4QUtfy9Rrz&Mo)@Fo|FGgjAN)G-9F1P6=eJgq7vb9O z2Eyut^`+lW=P!5l4})_9TOnoT2TOJ5A4V31VgS(=>8IYX83VN)P#dqpozWiIjnjPE*??pU5=ac;V=j>|m{GiN#Z(lWq zNAWd9f6S>vJ9N}f!(n@lKgy3cs*3&DPDSYdoyRA-KZDyiVR7B>nDdM0hl5G~!lwK^ z;`Q!kg6VMe_&OxsJ2B#*Gj!AW`=|NiuYQ+V=3!6li{j5|e6YRyfc@&Z0d{rNT>?JaAQq>N9m*;;t< z^QdgT8uiC|CN;seienXV;`KhH1)=Vow;v?R_K+j)T_jAVGHAas?~XdnesmcL3%u~Ey)m`@ud){_Cd@B7-%Fj7# zHIdZem<<24Kj6y2#&~F%DDzM9RW)V!x}DV;?i-ZxUpPsH^uI;e*7k(-`)GfTzrG#T z)cgkjEjy*>R6h*MSOK51=ED999RKuwjq3NpnI&_EFpaMd#rKzU7uc$ilhEb^e@^+? z<;-oi_rxkieWYo1mrd=z0e}2?{bw)nKZiB=${t=<=5NDWwUF%^E35BP{@!b03VX3X zrPmk!_q~b!Z0S4;ZqfCH=>g8t`dlISZeO$q)+!63Z$0j>Q2aJOw;$V5tb}^A)${l5 z9S88Gz*F6j-=&2sRKHE;Q*h3@X*_QiP6u-Sq z6WPi3^AzU?)()+THw%x+@+XSV-)9;j>2RWAewp38HF~?G!{!&)4^+R}_q2dxhaxPi z#`S{-)Q=b>s!jt@0}K6=Yz&V_hY>NLF-d#Q^J^6fV1NHx5lC`;?Zf6 zGXJVlnThUdMg4^;ubD2}uGoK8uTdH6k*mzVIyt(C30LOd`{H~G+pHG|uk2r^`0SNC z6XgdCgjlb^5cVCWQ%CA$FzMIQf4De8gN}Le(UKU#EN%veM|9oOFI;A zmpaMvdm7)b8bq?hQf2(jz8=q3H1t-)U!NH{EHPn&Vt+y>zY=z)<9^Jj#5dJnHcSJa zpO4}1kbm(}TNd997dOD0W=!TkQ+#Sf_rQ?rFOgPRU!eNzN9}>wvAP&lD(`1`Nc?Aa zl@;6OaMg8Hv(I&|Ad4(OD)$9Mp zDslGd{;x1%yuXB=FWaVPjjHE=;{0u1-zp~f(&=~#I{IUUWij5B`&&L=G*9CSR0HP- zvvVIw&ozku)c>jb=IK4C%*q^e~xwk=WL-zkYayB zr_Fy^Wb@;S`?oE$QPcgbV*TWFT1yN`73Y6do}Z-n{Mm05JXYumbE9`k@AnGn&)LmF zU^U7{*xz}Yv_8~-x^*iA%_rFi&7--#r2J|pa#QFdW&CbCcn~w14ic6xSMLu5;W*1) zF-lQi#{9X$7KAAC=YUa}Y{nPm{IzlZC-!H~ewqJA`Lj;D`q1)WGW|*Uakhmqwj6u~ z&*|#%+wS{7ylwUk!M`|uYZ3h!Wi<cqtKvpGw<>!|s zOuCAy8x{!B^R=b-=S%9N8#NEIqT7QM^QXCv(ag_xvSR*JJT!?t)L5gKKP6>8VOPFy zM||l&|4Lr}J9FRr!Kamad|z31j8(Zi3ae~6f70_^ z`8zK&w%1!RKVR*a&f-7I^GoWVEPb2Hio60)E0ya%6HQ>?8v5$1aF{Dhas4 z{s0V5`wAZ~&JWbzwoJ1@)w>!(!5)t9SQ6igeyo9EzmCH4rhTOSA4KX?qgNhfMPo)I z?U;J}esI3TDvakV#{bS&ZnNGg8*oXJe}8}CkEon8{|{Z~9oO^s{{P4(C7YzEWM^kI zP*Q0pEhUjHdyn=`C@C2UA+xfR>pHTs_a2#%`L+rDUccMtb?RK-+w1(@?Nz;=&--~? zk87NBp!J9t+;@Ac^6%6A)1#crU<8W#ik7tn|M^p`5k7e+*VieHy5MY&=eS`d|NGQ` zW_NbObldu@L&@sO?=SKj*JvvC>aW9$zb7hxPWc_9nS#4)hO%f&9>1tQ{O6p48ks}c zxYnxmp|C=6c7&M?+qeKu3fZn_^F&fKr6=6|bB1`aD8!TQ>6RDNDfP2@lC zayopPI6|7AEl=462EXO{y*Lt~_lf1w`J>!#zhM5}Z8&M1YJI-6O9v;aU&WVC`17aw zTYdIGyfpJC{=UNVGwS~bR}8_OLDiV;xDCqZPyPSuUrW(>g2*qe|Dk6Vd@T0FiWjQ+ z&3b$Q_Bzj$=1*Tdi{X$_6naeO|3CGwF5NFeWak(R^yK`~^TF(MUxUp{kzd*$jM!Wg z@0^n72Tw~iv4$Q>^Q->G9Z_?{Q|Wx#ymB|xZm7Yc7q3x1KYISxjz!ZjHbIva{ava2 zxhe4vU3;Y9AWLgDCWrHjB>yjPOu-owt(no8H%k7fe`}nbf>uwgh4b5}zUw=$!S!dv z{Fv&q_K{Sy-9MbwGw1x%`+I_RDE7w|__Kb;wkiL)u8)~M z18`vLUkLqqf0*7+SHJUMoMcsv?RdlWozCYSzncm5lRbs}jrtG$o%t~Q`Al4EUbQ~N z^A+ZtJ_`l|qHwPp=YI#$?~R4$;gL@aX3ymOQ~lnnSqje;_s74ruloI>e&>H`h>9zA zG5sg^zcjxqeqe|LFFr=Azd1@i>HJTj_ej(+(`3cS>#ubF&`NJL+Ui@e2m{V9tzRX# zPsX;9*6ew{YJLOTr(+g6u-n7CD*ry6zo?;|fq@g8SxJz&a=zb^>^~V&YbUIamGfn~ zybvyHhe-J{(EJWNzRUBshKa4P?~$w6ZvcOOlpn7a129dy96x^K^+$TYd+J#$?4VYY z{hhEy`TeNA_R^V-!Tx#-oOymn<6mIpS~yxJUtbm-^I%x1+#l@rI1Tq$B+l!`|GyH# zSIjWQ`Sj~!u+vu6d>J=?2_eHWg!&cr2V3*i@v1|fv_D?!l>r)$c!HMB+&@vijPl&@ z<`hl#_9EwN2FY)?&0UHAVioyqddo`v5zqJ4X|fs*pS2dw52X6|#%(p$)*Hs6xAOWS ztsj({ti{O>MzG$RmGPbETVdOD93SJvKJ7G7$zOxwbUZoBnN1wnL-~IHPkqrT16L-w zvN2B*%>U;<)X4eyDJ@c=U+xHL{bEJZCa85mt}i?P7J#`yh&2CesP`4NG|HCdcer2C z|BaBxzng7Z;+HdW{j4$C6g`jp#@n8puS`;3ysnsi^nIhx7We1z(S+2$N2P5Co1NpN z`K^6!5%`~p#16l>KCdMF-h6cyqVCK6Z9TW=aC2z}TIi_ON57ovcxs9~eq_40$BRx+ z@R5dUej6#ymh5m^i%mJPPWk>RziFcqahtm0d=eb5NxN-e6-J&)~~i~ zZ-8M%V*H@>6$|Yac&WoRsXoT_>5DbH{>BlJRqszj$S-2Fr(;}?_N@OUp5HnXK6Zaj zft)rD()#kwz-+i$F4uqE_+v26O|JiQw=;N_9Eql0{Qsl*|4;9yuzx{@u)pU2)Sp&W z!{!Nj()vh=c{_|NlI!2_ zn>qVw!1teo5dCt`OTyJ3t(k8UkH0j3GHZJcuRKU%KZo)87ph+a^)>(mdkOg|T8exn zkJty}tY%65yT|8Mt?+l> zIBEY_P3I`M%#!n$ycc0o^C-O1nCmCa-$Qmjf%Ap(_%eW{IhRHEFKtQ z!OW*~K572YBXk9p4j3lA-^lP+5Wm zvP7dMwOMo*J|9B$ai-$@xHe&0tY=2Ll0TZC9fF{+Q2JreMEt`)oQ z&_?-rs(%4T6R^izYr%ig{xW<`z-i~L*_H21$tU%fH5aWw?_V~osy}sxjocNM0&7U=G>tdSXj^C>Mkn$UT zyqDtc^1?Tq5}_4~#96WhmHV36Yerq}WO{ZM`<*RV&&tD0=44S#;L zzqhYzEY36?!aBa?{*l&)+Ly+nt@Tir`cO6BT}H=aNT8hG)RPIgX_5`weMxnG}Z`Srb}{vh>s4g?m>lJ{Toi=cYrc$|BY&nHrT=Z2Sohx&GD{c~rt zI+*Xpg!y2~?`f}|cuVacCVO*!Y5j9qx5-$XVZ`z`a{sPI_|>x6jMqDiXZOvVRq6vX zS_!r}a(^&*PbR3li+t1iS6K7`=yF4@&r>&Fg1ehmW3dg-&uM-0U)gUsy%nAu|}8!|xk z{+bVcVsS$~D;8;!uFQW!ESd@HyEr@+!v^e7=erT$G@ ztq2x;ipLvGb}IRy^HpzZ)yDF34BIx~@ssj9KT@%O+V%xnkL3PPi^Ru$U4u}4xFMS# z&-H`uAAol&;OH+0X@A+Qa1+eb4wBYq&(z3=_s`_|Tk!k>*q;*lr1_E8lh?4@V>@o& zuG-&c@B0a5zWKuZ4%Oeg9kj7o;&n{V=IfX8Tl%&KemGo#ZZ|8RABj(z(Pmg2R)tLj7?F^-{ni)@o~Qje5uL#8${X100|J>Cv`1y{UKli3_ zIHrXy(`wE0D?PG*=-uZ$Tzff`nd-f=;Pp$ff7)d38fY=YTiX9n&&h@biL<5kCxg02 zq1l}%)V1aO=n+20J0Q%8PQZZOs`-rm@Ex3PE-)y$QdP$9#=V3ID6?&G3Gs`YfXzuP;#k`?i~k|7mn( zD|?41pAX$Xbj~LQHhuG!);F7kZ3C?qbENrE@5P6qMYCv}zKrvwMfiH1_Z7BZ&6oBM zi%+QIgRv*2`Te)9I(WG8D`EbD@}qv-2H#a{%*ot2}%LutX&u{_wXq$)wPI7&u{^buHR#bejf>lhx5!)Iv-NlV=EkworCJWynaQ`=V|%$5On?!E$r`8 zBm6Gk{~6x?lJnbtQ*~Swa#HY@w0=6`XDjSE;T2xVRjq&JX#+4Xs2)3%$KQ`0iC@>p z48xkU8?)4RoNt=H9*79T2a5B1)tous)IVK0ACAQs-4Cv~sZ$>Muy< zt2?De;~zI$HqJ*izq+$x@qC97thncUmHZmj%)sMMgP3m*7v=h(`pi1VLDNHWe_~d= z8eZR%$G`YHyWy;5sPul;Cu>f?-DWFr)PKCcMEQ4Nr=jRtGP>#V`YYA%UC&CO$%E}e z{T#{t03M4qa8>9Hyzo%9eqYz^g0(`_SV>#1-_*bC9Oj32E*Y{PW4M2#{BH{i#-Cq% zvUeAvl+TayuhDQFj5-=5%>Rdw`i|msP8dHcMmRs1^1XibCkVGbAgwRfJlPVhj=jQa zigU8LzZ3oEnq~uVue%t3v6w*-(X>fC@eO% zWibYvzf7W^w`xb@v`{-14BTH)e;;vc6=Zt)NaNetIa%O1YmPMk{QdGc%rX`Eq4kr! zWv9R*F9l8AdHspV8MAuX@6zjn=~-4F+uP@l%JD(A9a4H2<6)RRELnR^ZE+s_!q(pHCg| z2y)!z{EZ%_hPqcyO6$|7y^ZmES2b3w#`&ZDznA024iu<=Mo~vG;Gbg`; zgK2U;^FP$X?sw(>{Gvv49Bx{Q>Cd@7()v;Rll}0kUjz0eg4eGppZix2ML5!wy?Usc zPlqv~_&mv)eecZmk;d=MjUyFzi`lc=dfY!!{X4KX3a>qOU{-mjE&iw9)PIg@lLQ+k z_z3wWR{D^CUE>&A%UwuNn0oz}Da$()!fe=KsL)$w^^<3Dv)C zt&H&UunM8SNBMi_?S)Og8?liid4DQ|_{YP0qrhaIlhhxYHcW+~%_rckM6S=2zXnk| zU{;abUvG~(2}xJi;Dw{xmHbovkF+fVz2^sTXyyH&G=DDKT^EPfyD828ELQf#zvmmU zb{f3CMERN8YzSUgYsQjW^79+1zOC^L!9Fd93Fik*te1usYx))Ym9q8T~iH%)4`>^@|f0xp2Bp ztPo!^$^C_KyN^JwsmLGgFFzl44;rkN^JlL82OK9A;r?M<-za}!=bK`{`cfR%l*cE! zzQ@jLkD9yw;xN<5x;($3`|BE%GpPAH6`urE)px}F&aK{SxKemPI$skqst#T<7x|>|dCrKwXsp?g zz0v0ShnC{~V0MlZaY#aMHq3Xpa($Foit!<1)>15)Y0Y%YdHkjNmN_*P-<-5%4S(n> zKTq@PAMs(>dxbr7`osA|Qs14{P!WGuDfpbn`K0wD^{fO~q~hjcz{Md2^-9$6%f&kg;X z;F}kv_}5T1pVr$3qhbH%Y{KQu%I8P*;cruS%xz=D(ioqQ$RzstU_b;kKHwys4|}~l z8E#&a`$vtKZ7|}GTtAKM5iDD+75FqE^@lGnUV>SvoX@Tfwb3EwCO-JUzdz-3`93|= zuKovS{NetH)*nukF2%>s#r>Jo-)a9|in~ACu=dY+{H6Liqe9`0uZ&;;*LeIjA@!S4 z6XM}ZS2 z3x=RsT1)2c%=7OOOL6~FgYRLmHqJ>}zjbt94L)^|QA?f>dktA!tS-jwG5<|Vyx{%uWmt(brR5TcJeE#1*m z*O(o!<@ImsUup-(L55<3LCcy4EA>;H4}5Sf9r{_$mEKQvVEb+eS|Qh`pEJL~ox4TY zsq+2M{^{!I+c3huG{a$NT7^>HE7V1-UeKsu$!$UsKtZwi}i~srCm1Omgu-3L{hqS>t&6&>f`ZVA7(9%}U&^2E%gu0P zTPSW?&)>fm;jj44K?s<)3Xc!x@sqCK!>!sL z;Kas**uMeyx72@rx>^I>@5uS>KSCGR8U4kgTpqvl$oig@?}k4tIx?3Xe14Yt8;!b( z+Ux6~%+!^i-=s$BH_kKWqm9CUR_#Ba?>FL640y%K_0#NE8U*#8C)9V*Qr!Oo-F890 zql)>%%KO=Ae9qGS0vBtXlJakosD-oAMgFP&J#*@X?VD*aS2g~8>H7Zh$^zdcw_=I2 zRj-e8`$I70wIf?;*pc(EM$SjQ6^_x(-I-&*&q{u&zZo+%1pdC1^O+u<1Ui8erS+Yz z^*2L|Ntn>zqI?G3I|%zLR%5@)`^71r%iWK|n5;C+8mgL4+pgE(bh(^Q*Hm@v+w7J! zerq_j!P-s!VdDurzES?zYZvUdrXy?gn)65XbBSj#=IRV#?I!a1*bobGf9Z}5(NK8P zSEvut{A9k_T6o@ko=_j8d<7NmgsdBKz6PFo0>SYIrS;W-qo2TD|CF@y6@k6Mgr-y9~xGbC%}kAN#BTzx@-X z^&t(@O)#l_7+y2x-=D_!CPfEeS7es`90pS02gz_ z|8#e1b$mYS7B(>C`cD1lfx$Xh*0=&g73ZY~ODe5Ebe+_K618!=@Ve5_j|EK!c_vs_JaQUFL ze(@sb1H7DYN}4}E`2Y9gReK}&2g+}73lnsks+ceC$lnju&(!l~=-fnyH5k7``TQuq zg9>INJ1^%qsMb8Jf7F&mN1UwWQ=G5Z8axlTHnL-;rKG`mk@k?N0tg|$K+Wb5LI{cOU*VYd=z~f1xKK~!S>*j+GCJW~`QNG_D zx&%p6c1r7SThBazr>ErpcDjBwOrI(0b0(?JH=58I5A{=HX?EPdpryF~s7;^~{?q8p zrblg1K0nI${@Rfc^;OPqtDY$^&t{&qK9sgB8#;HD^ZRPeQ7BlQj=2Fm|D*dW%ND+a zCBdTp()v%U6%Fu*(;MM@8yf!yMs~x_yR=xoKj+ty`1`xN2cgqF9rh@Y=NFV;vue}v zijFlqK9ko!EJ^?2!joBec(AS1A9dQZ0H5@56wjw5{$YpbQgrL=%IkoTdBE*A>UZLH|kEYrJazd+BKgIO~Tg`a4`-sK4mpnG3ETl7;i} zD8D1-T!5u>&jc< z(8g=D;18(2ZmN|G`g=rwK=rlY{8l(UFiyDNoa(Ek;SpF{e;pqAq?*r1cn|7yI)r9F z`17Ow{Xxh2xYXp0P@klHw)oWr7u?liUn=*1QGI={KLPuV9n9Q&`YXS`9yvdy^POo} z)#7x_fuA37@T<{P-sl_iY*WbwcFmr3e#ix$m?DMilG`NXet z<6!-+N%$jNHDB+ytOFbwhJ~N_^Pzl2MD2qc|K$33BD5Ghw(peAXJu)Z!O&gu{Gjf{ zzcBLtEqq(qAEWv>`$r30c36$&Jyp%$)!itb)X%dD8yOocUXzLa~44ROR}k`~}QB1cA2eaGV~`@92DSO!6%-4n2U+r}F>5 zgzVq=c(X2U%zA@oNAdaqCB!z=%jqUbbr!aodsyr-IWcj z&H1JImxJM4c%;xr+4;;7Sz%yTI9gi2*`(;dXIY0y>jPt2?uB;!QiS^}sXo@-cNQXk z?3B*erpFXR-|Su3{PGs%_oMG`?Bi1C`Q;S$@#gD?)_<-BG{=Px)!5}v{QXn?go+S2 zYdBgspN{5Fdf#HeXv-vNeWYd4W~f*$kKaBihd{mhdVE;G{WImW&g0*3w)So5`g`S6 z2fM8m^^y9|pllaE`XcI^b*vp; zck9OLnDYJv^@pibvJ`s{;+e5&f|6g_|A{S}1&$6b(){t>qG<43JV~g3WRm%)?Tc4{ z|CM>t`f2qknK1W790pe2Z%_5JUjAVSf4LEx_U7@4`pd_2enMNf+tU2-MnZdBGF*dg zNaFfO`@0#tgRr-UoG;(9AZ(s!!!Ebue3lSC&j-)I%N6Hqjh61;Is0P`Xhe(tj?QN+i^zdC<5Q&m&hlgtylR~z%}-VaoQC=v z<$MnJcn&e`PD|@|Aq{Ke_?l%xe4^{Wo#K4fZ`#$Q`sQtAiqWszGJSu}FOvH9IlbZd zw^KJ(e2MqpDZk5NLUG*cG3=DX73KQRB=yfe(-QI6p}Fk*Z*}GSDIw=q+T_lFi03Zo zX2SUju@uH@)J*iEVEl_o(*DPRM;jskpPb*KCkG+6$tK}^Bg${hrr)8auUua%zSYFV z)5@^(I@R%i(8qQ-X>>!DHI(Zs^`ASm{czjM!R*jNem(%5Prnusi1jYWP8yI=hUh@kfd6l-8G*=2XDDP`=~WWr=HbV zS%vEOt+T5y{&CV{9v4;fU0$Zx8@nT`Jml&lW=|w<$po!7ibbA=YMOt9$M9JD9m?JzR&cu!F12=tX97)<@cxg zJqJ2ve0bmiyO2>+=w7eV#%(L#NY z@|%|x54kb(rTK%=!S%4{P@K>|2_f@0PhJ9qP0Nwaw}uxmnAByr;6JIqn6~{f=+2hw z_k|fXFnEkyzdtQ+ge%>vv6`A(f2cnln%xHr>*%wZ!1agf_ktvAjNjg!otdZl{roGN zipR2D*y^$k7Tmvy{ewQ2r(-WaHj#aWLD|80y`4LobGaLTzoh=1?>HO%=8a-U zFBL0)KkZL0u$%&2W+?Q37_To;{RjVWxTH5(S|4wxl?><9!|{O?|2*Yi^ItZ2X3FF9 zT8;nU$;sRJN1NvdG{24W*2RVj|5EUa*Uv49e?IQ#jr-3GVbv?|-(5-gZq(f$wR+jG z1-3!T?@#-~le5R+E7K9|$b?zS=VwCrzHGYyTF>(n{0Xhk)NzV~PS@rB+Olf~Z2KVQ zAC&LBU%9ZPuUsEC%z6mZ(nNk~{cwH_bvztWCar%r-rWoBTIn;)R?TP3rKx!IkQ=+d zU3L7*x)h9&3p|)+F7FRg{-*Svfj@40uv)CA^7&EyZghAC)^r-hs%LWkEQvq)_IM(+ z&UcaKw~w{L;ESD{zrUwe!Qo-y!ue?-M1S2qw*lNwk)HoPH>(grX6Fd?89G0|aSFoQ zc6;#R7ruXq>dTPrA7J)dIlujDYoXb)YOLz~4XPj0Z?(a=#SPiu7d$>vz8g%l!a93R z*ozzQ)-*rD+S-A<*7ju6}9=cCkU{|?-T-NA0Q{QZTH{)_$8hG;yanowU1A@%J}sDtyhHJQ~3t}m3| zo%4pG@ADq)Waa)Rn!j`n@I?Pr*6d4LcfbVkU z`dmG42x@lg#g^sq^+WlMZS8^T+pXD(AAEn^4x+z>;WNPLliWYNy&4JWwH8SC-)vf# z3YTo-h59<>cYn%m=)G~1v_53A?HL$`;2A#i}mFRib4v1*M?mT9uc zVVqyOzE?H%#a|xwLjREVXD&tr;Daz{7Iv2Ni)22V1&+gk=5B1}Rn_$&+r06(YKc2@ zFXH}$?%xYBo`g@&j$$)1RO@$-rVG*ZV-UN0%}%91nfN6DLRZWA{;$CjI8!R;J4G)M zoI=Be`6kNu=Eq6`>yQhBA`S#O! z5%3Y@`aJx43Y-s=^PRLW2Sy(k`7R;%8|*1O3$5`OhA-y+i1Pi|t{l?lycO<0qWWCE zwk3YvtjP@BRr7u3ohLqfXUFmvPEhJ6%^%+D`r}zef2T>$MM}OX-zK_a(X-f%Eo-Sd zf15dD0!}IOWX2uOSN?vnz7e504HHKCv8zL?_P>e!xfd4xFg?^&TA%(oWFdrWPm${L zuJU+T{vjMY8gf1VOsba9PQ43PW9P(>Ortg&k^qDqx_ETQ~;S1_v4LAoL{QX zxkWD^@r2xeoPJyv&tH)9d%0a#Jf7c&t&@w7{oDn(S{+J_&ac{F@qVta*FDj3qytNe z;Qf&jOR+xG-^~Y`o^fKj#r*ymI-hrZo(~qjb`td8lJw_$mHFT#FK1SEV}Z)`(XCY= zmiUfhIfa{){9BU#!jH8vw|{ z`TM>%;lln;%70PQ4bWis8r(EZHUAwl^WpQ?9HIY3`EPdMC`{^}i)ja{=5s{<{Yx=F z?NTb|f8mrm*x|XzKlR@qQaWHW{kF_|6F=X9?!T#h$P%qS^<#b3^8OFi?+d$^W0d)9 zcG+&GvOa1_=F@dIh2f$-3s_Ftc;)+}{jvLz6Cu2tzf}JR-V23N*M&H3A%A|f|CpAs z3Ov@x^}m(ob~suiQ|KR1{r{j|1h&VHVQEX%`rrN0Hwe8T*Z(PL%`m8e7K_POy?##D z8-;!TIIwv!6P5hY^^@l@3cJ`ivizBR{nGVgFvtsojl}&0bbXw^<&BSyxv*!w7b~AH z?Jw-?6o4(tN3pqYRj-es^Ty%Vfj;c?TE0Hi$olZv>J5jVxk~4&78lNjvo=$t^}S2` zW8mxOaAAKwT_1NHGhp~x`TEd3oC|BUcM0nwljNrsUPqwq*IXQ(!TF`}q2aw+`2CB# zf7UI@5QkLgG8=RLdCGqfnB!|>Q`Y1#=RcF|Kbzff86FIo!(LwcP&?xX}bPTWB$xG}Y@PFU%dIUOBMr z+p6Qo@5vtMblHiW=rT#UeyD$H($WhLEp}yjUC&gmFVX)b_VUB~DWlk~R^iI$PxIfd zdj4n@>d9JYW%AFfiS_gNO`edp(hYme=K4eP*AJ6sLi?gA()q%5I?PF`QM+L8|I zE7oB9O#b_+KQi984-WT`^ItN%Ccf`ko%syn{+reZAI@!$X|HtIs5d-*P`+y_V%zV4 zam*?FkMjG|_&CLT8IH`K&vX)1^PAar8LZhR*XIj?D0T%R?DY=KmBQJ<;5Nm+de zS_S8!SxfG}N=W|FqcuS12?dy##rf4E{QevN2>y+|i~h@1^Sj6I6I5^XPFjD_?%fzi z*l96irkdYl^)0Z^l>y92m-|N=A0LD|;^EnL>~T7uf1v)PW}zD0 zBjJ#4gjBy*!CE-{NX$<|$o|fXlY3zL^j$)Ioa%S{Q*{jOR9)!*Qh%a5ULT!r>9W{N z&Tl5kF9&G*awXrieia_5xO@2JBGxLgw(|3| z{~O`p0oxUKeAGY0*C$>7C5NVicAcrx`Ok)b5@2ba1Uy!!s{SSVduPYZaJWmR)Zc&m zasb*l&qs~hs`*c-CI3-;mbw}kW$TswK=r0QPmV3&wWKE?A1 zw)79eZhqsLk@{bieD8d>7*DTT%wmk|C_f)U=6B$ZD|{_?mG;k;y_o{TOhmrve46R7 z2$LgcI;qgJ``|;`I2fk0`d|SPo4joZ-LSMF|Nc~eryiLIuV2aYj|K-6 z{ojdlJ_ABhz|KBZ>c74p$ORvx19-ArHJ?92Zo$ZfcZK-_%4e0gZYMc()#MPWo>bnMtinu zTb2J3`D%UJ4sGT-vgk{yb<#z5Q@+|3Mt`h4){n{yy$;1NIll^|#g8 ze{gSEb*8UdxK ztb3?E`?H+q2bRRYPTy^ZL+ZJ(#vA#32=)JiJnhkpxd`=9H8t`6!wOpm9CO2sb?o_3 z$tU%*Qvdok zHW*raEE3L#pz;0G)F|+=k@M@KvksPimh(GFalY)79U{MUKIY)3XYjd`oZkv>9aOs} z=XcCtJKU(~zjmp{`+G?0|Iu~rad|U$7G|fK&s(ncm^9v)neHQCCtMVtISI4<*`j(AKeWvrLOPAR~Mw(oIAGQvF zP0y!dVHVd1>VGeJECKT!qQ9X0w{=W{F_Ed#`2@d%Ti{oTn16(j`sTitmm#?6Jz>6v z`iom9f5P(|x&Aim)EgJyFk@wgRqI>y4@b@1!6s^q(7#d}ES}#pXy;UDnXyP(fB$qj z0^Uy*{evZ$zdhrh20G=L()lgz_j{pW`w`*%2^xQTbvzDxj>-K)!uKce(crx_KP&21 z7jqQ*OJ((WwyqTpF)(27ZmQPjZ3VVCC2%CG?OIiT5c^vJH*ImovXQLWx5-NWObDNW zb?k8P;gQT{mTLddHs1kH9`R!JL->3clKQ)`tqW#v8O>^DZdU$&I)CQg(gxxix=ZJ4 z!e{z{$;GKceUkF~bofHhy(ri3`=*ItYn>|0KT`j&RB?Y-hq}9k`2)&tNY6bmrQ(Qi zz7KuB?;|h3%l>k{6Lx$9Lni0@XmStSvc`-}$yTk;xhd1IAYln>aYt9_zd|gU3IR@Q z;0(Mnb2%H9T3@LTG(WCmxg49nj~3%E=}+3aEAo@1G1B_P6Vu7C_QxU|dVuQ()%Tmt z!=Y@BT;HSSr7G6{X6gD_+vpfPyCYv8YJ(ra(JAlIx1cJ1isxg`iKvag)f%yLm#h4> zc>dXtNj7MHY9w1Zj`K_P*|>N(mfMbEMNxb{jPm=fg)RDKjbi2}c2z!KasABvV~4ko zda=y#sY@$qMb7^Ky?JnAYlL*Z zOglCnnk`PnJC*r2((}|y<^&L6iCFw0N z#KeH@IIdcswhZcwmb(3!$9$fjBI!?^Xg(PibX~$$4-HcKlMvFMz4l=W_U^Zg-Tqy- z^8GXs)<^ET5G;5eC-5I)A^Oi%?vBu9iRf=={1}xV1atQ;lIEX2yFy{;S}}gm{4*{+ z1>DRxOa1xqFFCNJ;ZfoI0je*}(hkF~duOHlL!D3EhnXwn>*M*Uni$rok+lAQEo~?s zUFgoNS9AYD{q>eE!|?1()7Jhvqfntv7jJFP!Ip0*r5%uW!_ z*PwhGzF7^Q+~s`FzP|(Z+a1MT`rN-!zSmUTf#Or5f2Z@8GaYK+*uIU}#D|<8I)C{v z&=Mcqa%1IfRr6c>?NE%lKZ+$3a(=14pH?4+56rw-gfZtggw#(zy&aA-5=S$$0bKtq z3BQGFEFiXpyR`n%Cuk(-?VT#UKccMp45-^T5^XByL#Y3@=oka%&xrXa)o&B$^^mxA zHe zO^oomy(w$nkjGETuf>l*yz0G#O%CDuPUmmT6BT@qQ23kM^;GKnfj`r5?6Yt|-|2iw zs};8J^_HCf@>^rzbMwVQ{!01p-gF7{-jN`kKmPG_CFBRo`TzJZ8y1f|D)o<@yXHfz zq5S>S9&igb{CG}xSY>w*{^TT=5RIiT#mP2s+zq8aH4x^9X?^U0p8;;ZYszkCasESyerq%dz`gyJuutzf|7yhF zbcqT;hk_;S`Z3<$rT+fc;c56~e5Am?8u9m;?QLMFeSq|Ql$_drkX5lr+Mj9Pb|K{4 zllz;oCs%;})XmcV*w>V;iuqYl|B=i;eBFB;7Bu)Etv|l|s)ny4>qHUOGDb(fwG5H#Bvz6MN_*0;|$ zoD7Y-M+)_A%I|Q+{_6AUYlZnrs_*gd*20L(yM_K2)pw(l`ypWbIca_OVvj;dOuK`H z>p0(3-%A^mg6}YOR&~EH<-4>)BYcVm%=H(K50vlmA02S+;z_KV-7MwvSF;r7Yrma$ z$Gp&)?B1YtO8ut&F@4QIT;DR38DG*+sqb;G$Kjf8VFKSFgzuK4Cu5F(Br{mGRQdT# zGN0x*!U}Hn3XtZv9s2u#v7e~_G`~GEWFCC|E$>g}d`*BJ;d1_ukIMqzD@U>Y7|s{v zKce&!e5&yd=g;Hsho1lJarGZ8Sk;IPuUYl{#r!sWc6+R`XaJkNtEzt~*2lKp9i+Iw z-jl7~dQSO%X#ShB&J34Cdojbqs@KOOD^t)qC)aOn?Fn$fKN8JG^ZEegd&%oC=>Jxp ze>%Kc1Lw}|7S1Q3e1A6C3q|wJ3H>)(|255j4({&iY`(o}eU6`?iLI{6{dNDAL-5ce zKepo(&(EpyTqwy`d{y6NA8qQ1{8dvfs=AWhS$6=&Sgp}Vep_9<_ zW)!n4;rB;|5Po}WO~#AH(d=>SkjnQbuCHZ>9pF~xG@(95yK;U@Nc`0GW$?|q1cOOP)=c$czj8R=G=Ke( zY=L=2e(Ys+{{86tEj=(88qWw2>dUnM(aX#ewuQ;{<7S&sSX6DTwEptFSqiLsBIiHp z%PyFZEb>qHM{MxXK({Y)eV%Y?Fg_a}z>e+X{RPT*t^RHpIewndU!e1K+nmMn;q26Zs`cOzm5k( z*5E{}Z_eKz%}+N)#e&1T&DdITPVxWvqW%BFej8z4^<#oQQ@;1yIt(Kd@8A?m&L{PU znFmk6=zb-*Es66@{dvdbB`|)W+&}(M+z&C1$@Tr{X+138Gl&Jdas8+MvBMX0*g9K` zZ?t}O&vGOrWy|>-mb47w>#P;_S5yDd$#gZW>az!3s`2MX^*Qg}PI$RTnEN&e9+%b?mxQO_kvb!M@r{=)^!*T zo7ARD=PM_U9|OPbBZd7pG=3T=_IF?Tx*28jD`Py@!$a?5sBwVvPyI!9@lEYF0?rSe zkBGf=9}+jn*YBXEb#ZeaIp0|m`r@h$-mHlk?~l>*tH12-kLi2-*sL}D@6-5`x351| z&-G)qN>uZoT+bXYwj9SUu2aqT?{X7(t20vCUvqS~h7f&`Pg*~HJAO3WUM$aF&J0`( z`F3lC`BbVOtGccO zv{}wL&e#9pFHi>;)HY)umhzud{+eZv!d_oPrT%QQn=gKR5W%u5`2JSv&qm%IheM3w zSoH#ZWqipb^Qm?F4*(y<9#{uO9qxbehw|Mc(g}=)ihR@jBlgThSZXHnP5aX)*G9s} zKXU(eMso$YdCK`;Zn_N$niZq{4$dFdZ>Q4Q_+XJC3-VU2-&fRnB3OAcLtkEBrF@(D z_rkz`UaXp4u~L8O{>coJKKN|7FWZsF-#_L5mx02+ofq|+`WLr3-C$~eIp1(=2sAPm z`KJDO^Ehvqx=YMosK4mEbv}IYm-FrUb}huN6!n+-hva7aL4VpEEZxWF)2M%V?|KCG z*geD1V|e|Z>hG@8cVHu`vscml`BVKZum1s>^p*2}H@X$J8g9lK=Bwuan1=_xsx9|- zF<##IVMQd{{c4GlU&?=Z<9-0i0n+)P5nDz;S-mAfeUQ1-471^F6xpV|9c{VgVueZ90<@j$*lY5W>cq>in|8A|(u z^;UGp4(oi_?L*vO(EPTcdoLUsGKM+lT~z8X_0PS3^}-yF02Ve$HNV4LIzsP}Bc=J9 zV^=d6x>T;OBbK|vrw8)>)~zQqpiZ=$-)awI!F{rv-;jh|utKrFqN=`WN%(y_{~8>7 zEa$gc-DViNT+VMseP=XyA?J7Z+tGOEWjuS)!%)dDjsFgJ#^RFZNo?|mu*&Bz)^B1i z^ngQU0n+(k2~Bn!XX=k*C%-}!ID zDhT;?4Amd2=KJq|8L%&0^ba)uyIhn9z1qLR@!C6->zn$sGbzvE$y9AtcNBkqRKJJY zcEqQ_-Yl&aug_Dy!+&(a+5Y~l^BbPul@Px5>vu_i{&^@rDKlfW%=t#toI6Qd}oeq#?7H0RHs`inTv9gz3)zI6WA z)#C!xXkCNpWph5Mzb(F30bBFr{F=PB$GqtgY}F8+KZKC|SHG^0K)nW$EWl_P=hH&e z-*)%h73XWmv7h52mG77O+rL}8K(hs7rTx=>w=H35g52MB>);7<6laiE-Ty`XNBR5( zuztQ=pKA|H0FS32fGyVO#QS=DJ!9+>?#mwcJXY^V+ zhRyn{y8p7gX*O^%U1u*Q zS*hmx{+@Jrc(E8CRNg;N^XE6k+hDoj17ZI%)$dvj&cVKm>eBP^uiPky{YMR@^9B3= zc7%Ox$4c`rr{iXjcV6y~?F>gkNk*b{e^K%NIj|)oOIklS`;Y)mSH$``<#TnTeXwZ8 zYs?$Q^DD~duFntQWtiOmdJfmbiC5%&cK0{Ha~eL1`3YV>wj_M|*csw;H(#b!#`7CB zlHYC23BWyz*RXDbBRQW$ACC5J3q~Up`YJgex}r``*rm`{+5NOLGi|_1Jxb_bPo4^O-fN8U_KPv>od%CT)L%7Jw?@Pgd3+hI^hwuwFN~K2UvL>evD9 z4G{UI{fi~d2Ey-`a(+*QxxkrCiPHJ3jSXjl#y&Z}w=fQle?KPlHz~gcihEn$COyEF z2l?}*>ld!lUbM&62S>BiQ(S-5i2k;?VuTLY0@#Srs^9O(2~Jq( z8_#^#L@D{PB>m~wd%>9ZU^DCSGFIjKsZ*;Bj6FP3I^Uk5-yN7@{p{>erLWb6@7DsX zptWNCRGrU9*N@?2Klu7uuHSpwgupO^y=d62>i5?Xet+uS6vce5n7`BYqu=xxoZRvU z_qA8OeikQuh1hcW`UxvHfE_#J{`aD~DNHYw`v?7vj&P??uFt4D4YoYX!s5^T`%(XU z{$UJk@+y$}-};%EU@-lGa6S^{+af;)a>th8K-v*<5+AJ8Ri=lp(y;6UBCSf%k`YrDt`8GWaV@}EWF+BSTTJ$iI*4LN1>fyD;zKq>by}rXj z3@~xQSk`Nm>h;^(rW5WzF`4z*{!h6+X?3U10^|uX{_VD()B-5ajr#K@*iw>x2nD=?w_~Fc?TDb zjHLeJ@u@agyx*6#t=zv){aLfR`uKfz0JCqen(ypk9ndIoGIO7-n(w5|9kI)wX{>3< zjmqaQzMtr#j?mONSX$pX-+wrm{E^q!^f!)&75C-&TV!Yi44hve)Q>5@t>$FFodXYq z^Svm)y%%1A?7wn-Z5Le&Tl6rO_IDx_vo|SoQd#fvf$+cnBb^`Cuo;ccTSdO<{-~96 zf^qAMoh)I<73KazOG|P8Vc^5Iu)!e^CyZC!-&7mi6Y|YOeW3mOap(?{JEuwKUyqc{ zh9s-K()knHW-DOqg7Y}F4c9N4f89T~1HKIUgkBA~f1~+FH{V=nH0v+UN#yYz$@%^h zjo*ORSR)n_q}m_-!@zjD_p44b(fWw*DjuH;|TADq|}nyPt7 z{aJFu4iLN~Sh|0_+MIzf$WqL2XnfuC&I%^AULoA?N9!NIN&_J7QI>RnT%dj!OmZ%e z`g6@T=}>W8?qAejU4SCv#%%H-uJ6=;&wHzm)f3H_&IvKAXb>LH`nE%lEfTCI5!7+C!?zzVG zo%T=TTFihp6XgD6eMUT7nt5KDAMPHT4Ywjcp@F69^>J#|J~&nS51-uQ_5Dn;K3uQ9 zfKX2(_OFlX_2IX(1#W#J&%g6~wa5AAr?Srr{6bLlmEA4OB>lh2a2Ar4nuiP`XK>d@S zaAW{~KQul(o4*HoTdJ{eD_&ov_30YXPodXpBbGBuHUCo{HN}%(<@xyp&;r*$d4BWc zrarip2BUQee?FA&Q`P&xK_@XkruzGFtpoHQohF>$LH(g)*dWqfQedN* zoZmf-)o@&*TptIf4#H3N2`u5dYQ9|eI^gZO>Fls|MkQb3`TmQtn?vbkQ6Fi2$R)cY zJlQ4ZC#{}2>~16H$0fiU+M8^V_K#*ijsg~PUg+;rf2{p96PjQ8gvXsF{OIq3@N&e%NDeW6abUE%nboja~89>-Fs6#G=ae zE$+`Q>(vkrER^$C_Es0HUj$<)Q_bJl)Si%hAPNI7@t;$DeSg{(EC;7a`$sLWP5{j$ zdHjlvo)0e`%Ig>PHm!nYqvU*cFD{1xr_9;(zx?^q_+2!h0zQNfW?fo_SDvpS?%$|; z-X7N`tz)OxFy-?rA^z=2xC5?ulfew~Y?S<3lKH>fzfO4n-Ujx2YgK#`^N-q1nnKUE zfkJ*w`QBG#1fSKGN#p+2`=v~m|EsCm3+QDKOFaU&S0ems^jmI8QO5rHBj1rADY=7W;~Va=Z&ZR z;AhYZVSfdk&->Wa4L-TZ_47l;EC_ri#uu9Zb{-T4Y31kfKNHpY+kb5{VC7dif00{H zz>;veelA<4IG@r?&xeGN`uLA>4?Ma&Td4nJlKqE^jeYT7W)Ax^ z&P|u=UqByg+-Q)&&a_s&zH4oB z$E@7#0-v-#xxvH}las~#iJl)-dt)tlb4y--e30G@n%K^e`cKQh#!&oN9{)FbSwOuR z^7wz_p$|MfEsy_YhH>!v_(NoG`SYdvs#~}X&ULB5^1XO`r~K8cb{(#LFk&C$IA65C zxnb-FX!FgSb$iV}Px-5;rvb^!MgC}f?sK>e^!hH=w`l&d`HBhj8n8mzpL{gb9vsGR z5&G+tzm~fu!{g@1rTv>eLl?ujnisINE?>XYpE?w-frUo@N%Q;g6N>)C@y4uk<@%%k z^TOmJ_;S4s8(n!nI(>e2eswYZ*l6~nr|SCG?PZo&>a&hz6-O!k6RnRlbFKk3FUs}t zNJ?XP9U$kg*8@Xnc{vLIA7AGkkL4Htf0fZ7L{yYYh_r{qeXiSRYiKF$XfKo~g(ezk zhlYw2$tW%EbFOnoDwMW{Xm6EKY5uP7@7u+7zK{F;`TKg@%6{!Ms#l%#5E(5Po3Uo3y?@J3!c zxFIz7evXZb17CPb~uluk4k*YB|W{1EonaBs?i zR!)} zWO`U_&qX~_dKLDUKZkWB)oF13^QUir@-YSWm!0FslK!>u{B-Q7738PjkLvr2*zv9V zW&_#q9@fV$x8q5atp&+6MwqgF&GHkdd5BwlCZYqEn4 zxhe1mtuH^H?Ls^^!us~(@k|mtHHZJERsa3c{c(SoMw9j7U-$}N@&B{&H4tSGt4f%^ zztP!byF*(#Bv3Vfw|>7QryMz&+Ct=))&Ewr)%lQeDSvE#TSH;}>dO@|bluP&b^0dF z@9r%6gLhTI`j*+OIhoZ@I758Bc>ipDXLy(y`FR!2U%p=GLry<{^{rF>DDtUQ8rZ)! zG0m6s=L#hACoEsR4j&-fduh0`e+cBcsRd3 zUu{T|0$_dnJjIHvKPk;W*!crn%#pA&N5TFF->|7+sKOT zU%>ic?!HuV@2LUZ@}b#i+!|2gRkRD zTE9u}(wEP879*^m6ZvEHZE*_+{-xm|dTO;e|IEf;y-l_FF!BKBC%SZMMnby#fb*lK z<4nnxdoZ8=^LmoVE3p1eoiUtfb%FVGt6oG3%?l*@SI+FepAZmBY~(PXyPvM&|G3-- zAzKCiraOmt_%e3p#q!S^cPM|XWCD*3zX z*Ncz48cQn^#P}M|0+nd<9w6&XU$%6~}KV zvp;@?;U8l4TG&7Em+JnVv#0#|Q-feWcbcdP{>&RZ--^aGCbBQW9>8tu^H*vA+_doa zq~aXx53_>$lk??A`9n>`&$IsU!o_jq{WzG-N=wGHW%Y7tB+fk zl#s*W9Idbtue0&@#r1A{>C;$hd`jet)wd6Co0G|j()huS&&F0ZB;y6FKMR+*kZ?hN zp!Eyuh4aOh1;X*sWOEqVQx1>6qDvQuF0!Puy8Y!?K3<^j#KeCp?LJfFBb1Z&546<{ z<`3pRr&ku%oqx>qUnK4MglC-d;1BE){R4Zx%rmM%cAxT*)bB%?{q+|8Xh~N6hR2ti zaa(dW3-)(-Zy$2#lawDee|@oLG%-zp{oVZ#fAV=0%+KA0yU3Bl8Z<9l_4w1Dca-d! zZAh0yi~O*By|=tWgrku_zWVm=%0GL)pL&<8uK&%S^#f}gdV~4dif_$GX-Kf7|BdA@ zdzMiD@PzfJ^yxJ6A_&gkr!^7QrKnf(W;@0EXZ`QA>)VOPV-33GxpvaUNqxKTJ~1S6pxb+4jI#{oI$>G#<{sZ@>798y|rA zu{@|t`kKT1)buqcIi@jS{U(lwN1!TdbQaIKEgu?!-ruTW{d;Hx=(E zRRMSq_pyHdNV>n@H?NNTiPJIkb0^jQ z-*d=kY&9144`cH+NYR*JaR1LSE=Hs?f&J~2CSA#zW(lBwm^0aqScJiRX?cw&IyVaV z09SGRv3z+P4JNS01vRgcKrSy_(_3} zq`!^TC$ms(Vxt!Zt{>Yt%8X1jf%RwnDi?CFk%E6cNE}~meJ%3UY%(yrlyB5WynmLj zKYm-t-)fjIm#In;Gthw^7_OS1B&sBqsSY$CRpf{DSLl5^{#-~5z4oZ~pTB4Q)y!`1 z@hvYYKWu)~qH!Z)9uMb7T{I2IpzKI+ec7_doyq5>31I#{d+lg4ZCwG_f1#(gl2rOv z^6zp*K6ttGe25)f44JnL_6JjqQpnkbR@6mUNBO_;jpe6C@d)cC!1-~ab`35&3g^e$ zf|?MwHd21r`t+}RCd9N=4A}qL_ir!K>R1}@V73?34-T zmw(rwWABL1N6zFgyPIJ0aD@YH?W3BXn_id)$JfnZ=t%s;dsbP ztT6MI^f$2mjiuey$i+;UpLthxiLsEs13 zc7D^-cR0~WkjA%oroQlZ(=zgYWhFo6jQIPk{unphL%O~*q-m|h>#YBLaHa!4xJNuK z?3E{uFHTy&vFdvdZ?y6N_mA&1;S+9f7Ut{20!^}{Wte1rAo@~qW=`uCr550dC*7`T6S=t8dZu)eh&HG$l_1^e?86>G^+Gfld=vi|u<*Pk@le3W!O zZ$9ekZhM}gn^`DIog8?~E9vS}s1{;v4^S$@yIi6k*U4XJK3@j9!I ze$Ng0fr+tnz&F+Y)j6j@7r4Os zYRA36i@bbzbIJJ`()yWCS2eQSI}Gd}KNg}-{O7{@`m~D`amTR#?HuV&%sW2e&Fl1s zjo-mH*N|o%H6{5y8^06$50MU^tf=C)YQBrU-o+0Vc!T|4_ESFLL92u_!s_PtSbeUi=AT%;-1p8R^Up}*FYE74rfngW zmMv+tlWM-4KBtk>MFZ%)mE!nj=kLh3bh6;51MP8A_4u|4%^>l69qI0^Vt*4GpVmLm zAhVjtX!#-4@#*2iOcL7(QN5vVb^0M)UoxzgSbQTmJ0*B)WC8 z$Uj>@Pj7eyrx{Iz>*pF}xV*hDnBRD=|ABo*g-O;Ivi@P(BOQ|B2lHKA)se_@;QCg~ zUN=Od6 zFNkj0h_tYW<9{CwBcg2&`%8y)T}g>d!GG+jT0cWvr;?K|rTWP7n>8q$*tcm3`p5Wd zDWvm@0knFZ$S+$TE?#hw_{TfYH#(~M^~^~lEy6gu>dHu!{7v-{=7l`vbVS|y1vWpd zJ!-}~2d2@_p~e67HljU=KDkMbG-_6#K@AdwRO)X&k?R2&UdG7=3Z{w$($>_EU zaDTVTWgevW8>#hmg2x`A^cixu|CYk|G32O zc-rJBe)2Mre>OiVxZa#Nu7>&ZZDm1f=Sb^cY<`ql=|p}B;}5ETp zX&=~SH!^ik5ivjdGv7xiEw#&j?Loy z2pj(gZ8hc(4ost;28sN!`e-;foHt%#s*H_k{ZBvH{@nJ(=W+fnVg4?;{`pG#&#sSp zjr*>I_3@%-Bci<>j?Z&-j7g8?>3mUGJ)hG0{&>b%ey=d+9c(Vtsi>rD#9%m!{hIC+!uV;4%WYLv~_ z2?6(CZE~y}?>_|BKlTK@!<|M)N!HJ>`Wa!MMY^OX@aAJg{blQyI&DnJ{!poYvibQu z_5P&0JFK5k#GeE%Z%KU?i1*LxMgJU@l8JsjV= z{ZZl`BYY+OmF)aZVuwfgub{8>=Wnw4PikIs^4cYxKU#PGHCuo84znbA35EQ&9il$4 z`Wex2F!2tr;*IUa>#TkRn@u7Myx{uP!^&_H6Wy8GO%mT98{aE_X5mTkQhwR`k&}M` zE?f)eKS!>=z=MXs`s&l-JD%`4hR?7Q`DFb~$wp)Ha51c}6BND3kLfU<>Pbro9}M$p zzGx45|7ZZ+uy&wI{cO8@43e!4RHdAZ9zlI0+y zq3<34@u|l2H-!FK$cL7

      !4`t`B9;C+(}7jCZ-h{9SfY;2oYYe`|B^;62fBe80E( z3!WPZ&o7RB+>mVE5BsnEBbpLZc{*6%AGWRo*|kjSKY3>UvO}()A98bDZi{gC~WZr2Tq6e)1u#Bym+^C{+ZR!llNK>yBJtM zCx><=HEZDf@7~)n#B8f3{nbqzzij^ZbKhKYD!L`r3lzsEtFH~dY$rQP2GAB>s`(|l z!v0~69O#2ukzZDSA1~ZNer|A}Ho`je|JBdV48IY3c9IUAWmN8mRPuXy+HBs<5|00U zKApo6>!ta5JkuZM;Gc)PrG|j(PaIdg!y&nF{loSz@}b0DRG zFn@1atR-9SccvOg#OKfItmmS+{kT#zj8B?zfflWHe~q>GI9s3pYMaVk(ZAL z(2}vL`5TqIjkvUTplx(j$N$-lBFUk{4s_mUk-u^#zn^9hC9E$I;`<%d{55Qpg3Uv` z!T#!UOz@uzFkd6H8j>-y;P|`AuN84jF67rP6rT?pe>=_VOBNrm;zK%%*UOpyfKl43 zh{vtYltifJ$3E#0woRMJH#=MJUnTZcty^gZ-We?&Kdis_GyV!bnF`Mz%q}R#se-E;ncPuoEfe_8#KFOMKj8{znS&_9BV4ioC{d;Zkr-_rd* zK6!5@V?H_39xl!*{o~vliFo8Mxc+-?#s%EyrL?~Gf9f0OKH<>I@c3=z{u_s#Nau$) zuYdm1{CSnH0Z9&!>K7Y7N1yLOwC+^#8AHYQ%lf}LttJt@oR;)UyvQFLKVp+&G4h7> zt5$Xr8{G2+*XJ(XNpapKI6s+V{}><3gX;&&tTjn!zJh-~Sv6m)7Pcc@pFiQpM~e5y z=Fhqza?(Emj-SfjV~JljT)#0-@Ff8sVSV2|X#?q81M6GNj19y}&4FIbRUKcAiZ+nq z6Vmuv%;;OH)<)u^;YeG(|ErSEZ*Mjdezr_F|5c`vPwk?3?8(gr&;M#i`DN=L6`D1;{{*=H6L+yWnM+~)bZO9qoNZ9eKd-Bgu>1~h zvXESiC*f7)th8J5c*i zs`-1>VJ*=)E#>b#!(V0SI-6aAfymo=Ke!%ZMQ^yWc^*jsc7uI0@g?SS%>kXBDj9_pg|Unpm2OHY*B=r&cXRt+0YL-Fc|hH zPb~~d)(==8@8$O5UwvgUzCI6*2DT`iAwOP zGO2#C{#iES2X=l0#~(!l4RZb-tY5_!%t&&xYJRw<_ulKn%@yiX3(mv(<>h`ETR(>NtIvbyI6VN)-zV>EPF5I|@w4N_ z`(xv;tFkL;drit0>+c43oJ=&W;qmo0c_~R0>Vr`J>U(Y}*=OlMJ#VPy)5_V0+&d)Y zkIf&>XZVt~PaWx2o%t&HGp!!Q7sYgx)UV5#{db~IN8=M6XM^i=xO<23DdSMEzs0uE zS-dX-=Cin>7@K{C^)F)R7aZ~e=Ce;!Yoght8uWjMf)OcgWJC>Ks^;&@nN9fgCRpEE zzTS;9p2GU(I`KG;jEDP=-F*q(^$g}Opyy-!G$);Z`c3qIZ2hxuOEnTG_=o!beK!9} zHMAn~x0*C;RXv~5`1w3xEQxlqrnldT_s{CPzvog{+&FZG;1WILxNQE_sXjeU-L^}Sr~QU-~5UivwrpGCOiJxK|=|j z?EK!}LtF5e!Lz~jn_1iAaBOafWc?WH|B@}z@aa%#e#p)r@KINBgWoWpx6|I>;v#8( z3hRHa+chE28kB+l=k6l|GRajMzss5YxkTNL)R-92F>3YiSK1#?vuQ1M@Pqwd)5FpD zo7_*bewEFiZ$3JVyX}SN-?e1tv5QtLIKPx+a0lmZg7vdY$8R|CEgV1I2>VODDbu8* zrqth`l;6J&!%5LBYdWBA{TRz{=%lXv)(`s1t!q^ClQCiwHcXt&uiq%0FNOUrPNkTR(W=qE0+b%E0_C za!7MRbgRMnjX@u}6Xz~Qv{I-3`APZc8a9BevncI>eD0s!1c{zg$20gWIErhK(#&| zF8zqV-ID4fTOZiz{Rgk9f$M)3d)knqmoR^t9b8DQr!}pqJO78}?|`utZ{D+ovRjI3 z{(f!^#nZ09^|`gBQTRyXP_X{nr~ELES`Ft9Tge4n{1~p!JNLYgvrA!pvVYf@%oz&j zpLWQa+_E>KJ4{sbRo%psypqXj^`U@&{Dg8+fBPVDGMWCsiGBzY;}6^4QE_xB?&Agf zzg4vx@b6OC|HVz&jf;f%+uKRxgRL(wuR4KGRKxN2_LNIFJ^{`zT6(^~`fZB9`9~aP zNLD_F{omeG4rJpxYZ`1NK0lV9 zKZE&jA8;KPRm1vp=WP}CXa~oyC7~UOaer8U#>Kl4Z3hRswx#GV*!`v6|8XO=2OMb5 z``>l?Bdt$fYvfM;-sI@SD%JgKv)sp$xB<@e+Go{#RjqE%msYe;M)$g?(qE*8_TcUM zNc}I*_+RxM-gsO~LH~gMp=&iE*tZ?5e_YcjoN*J*Pt5X;U>~bkzN>~9KiK)-@~CW_ za5bIxe=73L`ol2?9%8N|%;%a;jmSnXslQ--|9b!FP5kD=`lmN<5v~k{ z>u-lAZNP(H!TcKb+l2!HV1CKbWZXb2QL?_8t-pCH@^HjYDZi}$%3b&tXAFY#x5CjT zWKlOGdRnr+MH)XhI=hm`&M?1to+~L_>s%Gnrgn~R#6{WKGho7lH^d>|4q%Fg>TG<{r~Dg zk=Q*3_V+VNj^G@VM6f?-+W8zjq#>59FJ}2#H(TicN3efu@j#1AG}5AUpLl<4{i&^s zA(`(6$Jd4L9LS{)4)j9-pr21=`j6QBP;KuzZ2Ju!9}hLcFpY%$ zS>yaT?D|}~{+i7Xnq4`K_gi6bezEcMJ9yxnGCm+v{QqqIY4xQBq;E4VF#o@?MTcN_ zn6GHRzT|_jKkM9Xo5lVgW`BewHvP$tVK6@yopkuV4-AxNpKbUTzuEqs&Z9hV*>Sjj zjxVgld)~wK;fkq8apFTb{w@2az=!Ol`oh*nR-+eq$iZqpb-(!hSbe#@$&{Q@SW~UK z^0Qw5*{C>iWGc92iBinQ?Fs` zZDsu4y7T2&J^~BA;tDgV{;>7Q$HM+iE#^z>KkWLKUxNPf!uhbfbX2duy0)u3x#a6i zQzYv*r2VzC8k+Gh(t0SPos0kZuNh9#^N~=T3}3tn_s1Sd9*!;iVSSIB;*C?R>1jH`8-Wx z=mC$<2LXoU%q5u5MVvc6*aqfLv)v;6_P12O*#65ksax^4*3$cD^=YHi5qzu{tWS^c z^LWxYIR4dqeTx@%g89?+?LZ>a9q2iqy7bd^~0FfJMp0^ z*dJ}tNx=~=QvG7%+e`oJxUjIAFH?wovHIn`oZAB#;}!TNPpnT0#W!usVJ`vlvx*P@9L;{CJw6|hX3 zEO}r}hx>@vS^d6>T9JLj9H^~jU45E4f9%@nR^-SxY5zaFztr>IZOP(8&eYmL{C>86 z(ZyVsw;$9~8FXCKHy=jd_>IyBH|8u^WU$WzS;PNAQ<`9^_s%A=@p8)%-?Z3X@zVnP|FYEf}Bh8;?EYKjX zf2`@KDu3o0PHm^F3+(kkzkpza@A}M_Au|`fSGizr*9tBQqLD z+hVZ)Cdv6E_MZXk+XJ1O*wq%+w}DUeh? zK%+#-{!}bqFMIC8KNi99vF)pKSpOlcZ!Vvo;k&Di=(4)~tJwMD+{tG6`#0F1SuX8~ zk2LWE*JuBEI0*m#3j5DfzO!(jKCnOQ)^#mjmzUt7$dSbr9NCl5~^ ztVLU1t{*?r`49P-TD;_^H9fscyv~lFh7MXJgG%Ek>)*~aYa*Qgh-i9XPnCR~7}AVf z&vd3&2a4a%>f4j7j`&OttWRg&_r%U*xf2nS{5KqvA`Kh%I z!<*%>|Ckn)f_E2J^8-`G?`Pv<^tgL?Rw&HR!?}jIrxK2jKfhbx2iCAYJyQ(8H?+dR z{aK7k#$uyEaD3d5zZ?(y3+q#-xgprP53ElMpKQYgzVP_^-0M7k<*Y?(&x+57jh~hw z@9}Ca8&IF$y!wMrR5;Kv2kZP9v;R#-`$lBWIhdaZr(crtKQ_wD&jtVdS9>Nt2DdfF zV>ZG5e#%*EJgpDxzj~x_*yIPyS8d{CJbn-y|FjhwaYDZ$u)n$Ev)%Zj;7`JG>z`jU zN&j$@0f%tVWjMd2&iQ!cE}_0Sz5esk_;@t2DIPgi=zlI0ue1Bha%HV?*m~*wEgK(y zKkSMFT7~mV-`4Aky5#>&Y&8f6d&GkM&9h6q@bEiueq*h_4R>1#$3L3_hqk)ve&FgrhB@mL$XhQoZkxMhl8^@aKPP}URo=B4wuZ2a2u z+YLvrNaWXKi1Cq)U%9gu<5q)V{n0iI#Icj4{)x^13J>qbr!K<&X@LHDd@Bsrr>MJ? z_~8p@`c~54Aud$`CK8~=RAG{A2oU_Ok->Eo={ zaD8%Nh&jGl0q1W%b}~H76Q186;y(q~%)|WcSaJNZ^ZOr)X5)`Rus*+Py&3!espbQ& zi}%OIul6fX;u%UKdiSV!o%KKVy&m8}dXAFy%k22^`tk_Bv*l=yh22!f|Bu7V@ZMUX zz878p{ZhUxPgf`wT!!Q0lSd7)Q-UAA)3JX1NcVR#d1rw82=iaEsp9it=Vxb@S>fJ7 z{s^sKem>C!hiYYj{ZS{|_~Otkn6Jk}cjDcCT6AMW@%LH2?zYUq_iSvaEKj_Dmahj1 z*KiY8N6Gpe)?c|~epX!D4D;7wl{$WH2kR3)V1!#dh5fbPc3a$F1RTHoMi0Yl-C%v{ zKPec0(XZk4%f$O*`SR5~h}Cxs{c&T&>nvYUwKs5-pg%+F@@v)~n!PDe{QeIgs#{hmXS#6ydqBKaO}-tx#G^^D8x{Mw0lPYuOmLc?Q4#p7+|~ zkBbudq?r2gr6u|NprLm7@m9=V%@z4(^=I*&$++M+>|Zp0&cPR7!u~lmJ{k{AGon?J z_#^c%(W&Qgt)(=-WyeQI#YOBe4$g1&k16oE&MtIl-S}hq8oMT*&@ooZ!p>L!`A0Rz zKh7PWt4NN7>nphv9xA>rgy*kH27gmz-jeDQ%b#*zQ+#nG?BBKd4tRZ=3~>F@&*L(D zBf5w;D^kthlEmeB=?bYnvHmF}e?Q(a#D*SyD}J8kZ^W%jiiX1c%7}p?A8dXQ;#Y>EFK!2G2Ls`>L?G!UP8SjM0GA^v|h|Lrnx z9d?U>^{1%yaol=~Bb{!qdjH&@kQ4Y<0ir!-_Es6+l6#!Q;pQ&%#KrpGm&UhCAJP?S zf8qK;#F$HpMvJ8Ugfi=Q`>8)xoF5R*uk9c{e>T3QS^ZYLiH+q0){EEK{tm0xx_IwL zSidX=cENAg!TuqB{776>0_Pv!_in{^oo(paQt|#-ek@0)Db%;X@$2YSrQ#mL5366H zrH>VQci{cqMh#TMWQkP2c;@`ieJu=dfe-AT7A)+EV;{r(^jR|r*FS>7_(nt{0HXeYeK4G&40wd9a>Km`{i(a z^D%0O^>kqW^X-@s9&x&ex2_i7FPne-i0qHs+tlzWpTz5I{2x@k0++hNd^~=YqKNsA z_rJwPsaXG4nm@4mX%S5o)@R}Viwncb6j|F6`SDl9@xkU_8a>sq_FBvrrHSvC?Z2>n z)CTuE1kaDJ>FR_B_-fJlRpR}#`syAy94{+``8eHsJ>D4r^Rc44Fz6~{n^@T z6D}FzLakrc|GrdzmeVlBhH^N63tSkZ82byZ-?ok}S12lA{jlAviMwo+>Idt8zI`ym z*$y?li<K+@kPtxqhx znWVV%MVf!H^A}ey@{00laQ$L{;WI@f!w2hsmd$K}Z>GWiXIQNTHeaVj59^Ef$LdG! z5pR5Pq9YBft*d`A_4_#ib8v+LN7KjlP#J&xxcPY802li9hU)k4zHhNYtqgwurRnPx z7DE3z6yGELcPa*s4+Zy^YxRsMY#w1xF$ zWzViS`lS)gs;h6Y`Nfb#FU9-?@cN?oZXt^I8{z!n^Uo;7C{wupMa&Zwd;fzUT%k~` z=!7Nvi?aH1@7ha6XCBTkKji7*^i{Bb+Zfprx4LXZ`|hcK|5E?#GNm8RUur|Uwh{Sb z$Jd-1gu^a5g69XcaF^q~$A$df-&!Sqy&F2?n=URi;$i*oOZBJc(n*Rb!=&{g*54$L zU7@i4kNmaM>a7av{}{h?@)1R8Pnf^AqYf!#{}JEp&gCdl|AW8q?r#)a<{YMtPMQ>JGZjnz!#{V<-=?_aR>MEi6aOFU zk3RLuQbav5qAf|izDo5yx2!D3^dQU^|FtIPcvET=N;5cr@R{kZh|z)dWleWMzy2e>O>dv6Xt&*lo*O1UAC`}_!D)(Xxp4gQymv~m zE{3Dg{Z;c(z9uK9Y7Ly9-f4O_$MK6)pV|CWZOFHrQ#au8SK?)$SoI(E)jeO;6yx8+ z{<^ukmBKDWnxC-#vzNj^vGPa}f3#fWgVnFL>yVZlgYmMM9 zJBiPq9Y2Nx_vDQK1m~xE*)ch<&87Or#{cLJX*s)VrSXl;@0PbO%5j=6#s)d{+?s44fA&uSt-n8wP+0z?~nE8-24TKq(B?$ZYf@8`RlU9Ly>&P zkxp2rTA#vSj#D(BC;0bus{3!=beo>zw+iNO^r^WylRm=ywb$O9bE^pE&*%Q(oI}Im z`r7vE^g=!u=8HX5DjUtcc~SM%TwTDL?%9IXN90!}>MEX;Mzfk23y2 zJMsOq^+mOtp*iCsw5Xze{dH-7P41DKIZeZD=_pY%xjmTkXCI{sLF zQY&nGVd^P3zw?PblHF-u4X;xd|JnHG)9PyWg=!=E?X_yY0uy|4_HPjKkGlFCt52cR z9u8=63Z7r&%{n-Ej)&_D?E?)R?%s#{1JyznI=u6i>JwXkjbCT(u*fBYk8rQ&PrCn@ zk4AIHyCrb_QSC^)L!b}rpW4sLbtqW@>(l3TzZ|x2gY)|thtwTEo`CsylceFeAqB3l zsdee?=r}<-f6eCqJ(gKGUYZZ{;bynrF=HU?e{yGSc1(J2M8`|=OR4|K@r!iacFmFY zU#VJuw^r!eryRpL$80&w&xajxj=!!I@x4vN|Ig~T&65T)#W5|~y>5P- zjc>|TjbugJV1LzZF_QUrl+mrFs-Lei+etR6E22KRs@HFvOx*5RlK}hcz}Q5`X(rP7 zOSb<#)HB^N?HoLRbevvs{5A`&|8LcJ;rMnVoWCq;^2PDeHNJB>Pzl$G=;6j7)#CP@f$jexB8*&UTrOeUHNWG-T9e$Ly}s`UzYAJX!G6@u4uk zU0)wy{nLg?wT=^<;Q7Vm=*BXc8Jzzu_+lb^oDcJ5q%&VueNu}KUnJfi%a{I`O|oZO zV7|uv`sf&U5avVEQ%&};3EW@fxkOjyFZ4G+>m%lPo68z5mF8!xK6yUuDQmDE=A&Ka z2-(nQaDQ#;w|z1_J!9%G@dr|Udg+ubi#+HEp6{w#b5dsUL)d@yt?K=|rpnLD`WzSh zlehSMS$>i?G?eud)?f5oCSGUz`{w8w$c7b5{S(WN@?rQ_R z{P~d@*|Q!9JfCyb;0EYqBFtYe&RX^@6XwtPwv)`FJ*;0pawf^{I)(GQCyD&9{B54O zRQ65q?|m1D*I9q%-ZD%!S6IIZ?cbt1YOl=iu+)EsGW|Ip-zf3LE z(fBl&uSz>N*_LZ?eR7GyTQ)*p8sAvHx@E1FA;Et``Zd@sQdVgX=WnmC$IDD*(*7(q z|6Ol*PS#M!U!eN#vmFi5Y7=9cWiQ@8o4;)x(iZLf;Yjr^sE+^VJ9I$n^M(9&tCh<7 zTi^yu^dwWLAFQnZeyP85TV=s{^^hwU$3FVke{+TDzwxUbB^z=Q=4zwag9AFE%twyUGgr=)zznf}vW ziS5zh{Wi4iQt|Vwe)(lClPUYa`nAz!lPtF(JUwZc0 zVg;;UBlbU)S=GRNx%M+dn}zt;(pJ1bmap~`WN1f!8P#g2TA!Tr zIe+BfvcbsgiVMw;ssDZ{U)wx}ad?ef$=_AYmuBV)S(ikZFXL`oWtsZ0er=f-A#*T= z`!DYoT$8obh5gms+GjFFxU_!9>eH{W8tC|FI6q!u>4fH=fb}UcIZ`%q4xImWa6c&1 z{w$6EtbdHtJuPc>2Cgr;%Jviq>Eg6>ZEGEZtsnj^&SG}kB=;m$hNt_^Uq5I;$?3v;q^~i&#%i;d%*GGM(GDx zul^Z))!h2{DXl*|S*(e6P}rYc=S+~raG1Y0IWy5ig$=!$B91>+zn1MkD|;mDzu;9Q zUT5RG0Vu<=gCtSa4+CvL*$(TRgO1wX|{?u=r3HtaJ)+gu0eyF1m z|JQC7{~ybjU(E#cR3DCyPkh%Qr^Yh6_>SuM=y+!XTDBhMEAMwWaxZbANf*T5XZ=0( z3*)Lr%9Z2JspiY${ZUyrIn0;I#YEYVsqpx(>3L3OU?|lu)}Pci{V01g53c`x*3?8_ zg!l=~A5MGT8nrqJ$Ipo_eNfcS8otR!@&4KPd8KnG(pB2f_vggxEMHUCUX*DJfXC0? zsv9y(c{qQ_U*v=3uTjh^*~<&k`X}2T^!(#HS-G&j4mv++-Ya8tZVntDU#;tbZr+Cd z{RaIpXjG0Cy>MK-KbF6er#sNV-Hzb-uwF$w(FT7RZ8uJ}zD1whjn2wA+I~=1(VsE; zw%9)w-7660N9+3ESpH(}Uyz+Qf&ItdFU7K^x>A1F`ptej4HPv_>Mz*-yFThhh-(Me zw~&S{8X5q{$9@BcBl{6>ea7dYKg#ZEOzrB<*I@mJ&ZBcOgD8unV1=Ao9!d zQ)YFHd*U!aInn<9KYxFm@%OiT7R%^dxc+lM^Ns9nD>(l3BMlG|{0Vfv>5v-+C_#vi z(Eh1&cnhT61g>AqnTb%956s`er8CiS{~F$Rxp@Dqe&sZaK=Xz8;W1de&hocb{km+% zMfiN0^*OI(JwC$cgG}^nfC`293a!s<{;&lq83xDC9FqYkb|vOXh4}y2_}MOPBC2>< z#@E)>KiT=Oq1x+E#2Hw>D#H(>Rp(*;W~@4oDmuXaf0sNPJ(&#qf8%X0Wyzi3`O~eo zYG{`M%+L3<=IF5k&cFMe>4eHW;P_|M+Z~NQU&M2D&xfsV9iJ9}jF!NB3{TmET3EpP z^i++a*|oy>sukZ4JHCP{%Vie=;rylQ-EUdIUtdtaCQfONK32o}HAK-K^&bbTKx_VV_ zq;QA%+2lC_?HBrsFEkRrpB;Z=DmEd_yc%AkM123OzTCD=K=a$f{J2NnLbrapP%U-w z`&oWMR$t+!j<8q$h`jetpW_*QPSvfJ<&S~qCnn@ILABK|U;Ag6AYSNSgx0TUdv`~L zLVX#k@6DS!7;XHS4%U||@@J#icsPGKn79_L74)mwc=7qM`o)LGqO-TP=-_JcI?LbH z4m_HLZD`M8@jB~2cMf`p5{+Q}`WR7)ie_-q{xl|jzImmIZeEn0pUBG_NY>wNRcnP3 zEMWdV_p(7Ng#M$km+JFp>HZf}Y+cafVN(9s`Hx=%ry=cyu>PBN--$BfYWUlA=clp! zS>DP(0lkfB>$>sF#y4Hf7wF7KSidIeeB!9-FlA_q=l}S7!|-Q&Tph{w!|`!*rXecR zg#G_TH!C#!AsiofeUzaucK;C{Z6>15)i8f&tpd@HeK3E=wroK}0sFVTO^&10XSHb6 zWsxtIzuQ4K(4#9h)c=imo#ij%>N~Xm23((Qy1E4#svn!iZ%%T9pr0Q4f6N|>)XEK=IFw5 zxW8y*VSChYiywdVoT!iN{8*pD-Y7sVoZluBue1K%va1`~zc`lvoh4pp{rzgg`6y4& zFR1@xh@y1}(UtMRo6q@1N!4(Xn!5F674$AEW=6BJ$lEJip=y>W*4J zlAf=}=Ks5rT+qD)*dJ+H&qN#lCP?=G3T4*cSr1%`1}=c#|IcxI(EjITyvbbg{#boJ z{p1AdwXcR>oG)Hy^=Dbwb@bK>=EJ)9FLKdF^rb}v`QP(b+5Oj!?pNoc%V2#PFsU`t z5&E}R-WPwLonPI$r3-3#6OMmAiSSdsAQD>CX_Q!|-SS;@4*;emzm|h)SGb zf8K489hxHSujw&a{C-w{ybq2*{*_^%{&YMt58V;gA3^$~7rOy%vd-XprikCq_V=&a zw-2QV`xn%&?_}p6+Iwc9uTyLIqr1iD7tfp@Grie$l$Qnb^|_N8ceBujKGGI{pXFQW2U1!$|!Jt{!^P!^w=Sh@A6dqeKtO=pSS~+ z3Hz%+^<#^cDJbky8Sk(~ynj}o%m=(jf7-zMQ!-JHD=!qzKRu~dr$5s32i&IUbEY3< z^tgd)eOh|Qh})^=O0De0|IhN*&cYT|wu1fn=Y~$`N-SJI=yk#qDTV%PX#Rcm^A%`? zHSEvbDz_q;eg>bvOZHHK&!}NLL4`<}28s4R?K~j4nH`THiX`x9583 zxl%1j|Aln^bf;@e`PzN`loR`W__zOdw3Cq}KWU!P4?S{${nec}Zb<#PFSvitIK9~@ zYKwGz6YHjJjvp#{SK_Fb;lvPBb@F9u( z1HH5V^o3{qmtsf)8r~1i?{tn4H1k>+Sf4TL*NEFK)Tf~MdFwz2?t!rW58|)(bVpAA zjEw5MQqA8<6Kn3Pl`9Ra+rNUbeyr3X5;2G+-f4Sr}3me$8Yne*jyTSOq^pE2P4(2xBG&>G?V3TXay zOH3B(9|H3k)b2hSx)AoiOV$~4-Oj@N`7Ixfh6?Am|9v6GFE+mBYpqA?m%@B`ui1mz zS0_mJ2V(g$8J&tAbb(B!?soE)e+b~3|QWjs}}M<`%>}$v;OT*UQe!6 z)0HN9iQ}K;XI|bgq;Q4n2d&=BM1#gk&tGKy*Q{>~(9-uIVEu1Ecr-H8gX803jYPEP z9{m1Sg%H$XXAys6wRnGQd?fdtAzPt-4AuXRCz^2wvTW$zy7_O`UoHRZi4Ny_@iRM# z-_O2(&oqBzDCiGV-%OW>pfyR-{DtK|GVmZOXe^C?p^W~R56(h^J4*Rr`#;8$JLuI8 zxIVW_Q;k!`!F;^t95{CiSDL?1_4}_~u@QMGr1eMk|DV<0jF#_|<|k}@!*f9@GAo4N zUwBPE+BY8_zXfI$=!CF8TK)Vs>z~K$)8`trGo~>&#P`GUz4(z8cRtsK&aSIJui1jRtiN1qyPafz{?AUv5`UuRHwSe; z1M?qYx)!~QhW(%OjDyHf2hPvcW*tMNI&glm;$jwhp8@CZAJuQ6>v2W=qod;cXUG5i z1K&|jA8GxS-pJ(~$^?e#jsqg^%!^e$Xg&vQP#y^%1|Djvar_<8$ z!}>FIyHqr%CPA{l4jUhy&dovA=NIqhwcz@s3iH!F#Lu(*R1KWK z9q;B!Ul)njSw7T4Rw1t&Ui@Bf@&4KOe{AeFbZRr~-|hAtM3oz*^$9k+bNoDS}vI7#C-syJB24?j@(PwdvwYHWhAs0$snJ0Pa6+om_&#?NiWRb-0GsQvTTb&4dkIxkt_5`1EbySb6r0{>lf&`TzL(?j+6cp6D-?cl$6(S(Txh zFTbH{P?txrK6M(m4b3-&W_Ne?_}z*HLvO9N&8zsdFhI zaC~e2upKvgH(Xy>6Ev7}7UrKJzD5oWN8V9h{2Eu0UzVR$$MzwUVK6_nACl1|Z)tpD z^{G}r50zhn`I#E{4E3r}fc*=KsRrD6s~Y}L-TWoXhwt~^oQJUfjgYrS5#r z-p-ZI{$77wTAymXW3s&HMt|kE0+AmzXDL5tN&@5!KaWxhyHKdqr~B6HQOiP@pD(L+ zqRkfY{LX?Ii9&r4=BI&wHX1GDhujVE|FiRh>+|j*ZavJ;w$krt(qO6nv;HtU%YrN3 z3CFi7TSsz75^U&+@#62Z`gFXfFK1%vN-ds?*I9kCs@aMRykP&F=W__%5Y~@VZ}Ic2 z|LJu*14Yb(<6jG|5WRVoz&EHBKhMU$p4#tG^Y03f}m_xEx+zYh%&!6>2 z(fvHQYsX>zIi4%bpDcv+$8mH58m|fa<1Bn0b?pJqFPnF{gYw@dNa~v`A38THky?=g z>|flhXwJ>{f#Z9ZR%YBdiyHoB6Y>68eLBjyaHTDU`e!%sI_sYfng?;)+QItN$!dvw z>Uw)+-yc{0#W!_EpW4lcknb8aUa4{I{Xcy=&-kb9^S7btV?Fq>J;e9N`lrR-2hp_4 zKH&L~=bmJs&Ec><9X7j$+T_H5{Z~Cdyh1w1)4}<}5A!rQ#c()(T@hfwUG{~?XRnjJ zxHr+Tzq<5vIv0AYMET)WPqQ(GDBfpEtaZkxpOOKfRy) z7+Dp;`b01OL^IPAlKyShKb3Xp#2E|v1I52H4#T({p?}I`nRtIJU+R0;ar=6>(w7~@ z`aY}AeLnchYXV`up0->e-@DgdIb+<{fAcrTnfiF>m>sBcss~TqRr947nSiq1`$+mn zS$}RHbRNy0F0GHV^?{(8Vzfr^Pf+}OaQYJ(zZuSdorW~!<~hQAO&Zaka|_j?w>k0o zvHE3+=W@!t;26F2K*GJFX%|n$<;rhAnl;`M1 zF|1#*rwzHb9~JxwXYv2B`K?}FE6#W(Jbw1SwC1$#R7>(dR=-9K7|l6U8iDbx@WUo< zje#po)KSfs<+kv*${28c zM8==5=+qK;elOcgmuqVZ$G067hw&Aq-)H&QdU^>r_@E6PzeBvv@}WNF2#W3v z$2awWvuNt&VDS9T4GjspItz~PE$R@FxXWAMtc( z$CaDG_18WL9^CEb#`IBLeTCJZVO_Uy{r|^*k5J9W>jvTSg8@i+aBstZ@r`HnMbmSK zyyT#pGHChBfAOuHiEk%DcgWA)c9YZ}Y#D#m<6aypY757|U4zq5=5HTxetBlnU-VcG z`)ibDz~$?}{KRSZ;PiRv_=;!hEAw8h;35y((3oV^{OF!bLX-TZ`oiXCdDHXIH^Kiw z>(f@YyNz5L!v3h{Y8e`wB^^I4sefYQS0`O_&Xt4p zCwKEe&U_)Pzsv7Naoan?{0!W(RbFrnDPt{F*O$Umx5;(g z9U%W7ZIyc)1o*(kO*NSWXs}S_x zpX~c`=djctuzbaJo6c?iVMHB(khN1!&Y{ zsXt`r$EprIK+YOcePZha+}2mZufY`=`j11mexQIP z*gyQftHmJ=c>T@g(`~tr?_mDECOB~OzE|^cb^G_Q{=s9xdX6O7Q1eIP`(ydCn{^TS z2l?;=%SHdhj-S*fH__Z)Qh&(u<#DA9c|D2**Y5@O_=vQZ!u4IHvmrNK&@ZTeub)9T z?r{Gye$8$1|FQjhhaARmnf|ap*uQcIcWb31&1p3BUwl(z&Uc>hav%3vn4g6Bit4dL zZffKJ^0R;09{H+8a^?C!)%+ytpGGT6yd?EumXFrx3Oc+F9^Ymk)VT4B;Q6^mf0}Vc zyue6jgQm1{N93WfD4H@Fp-uomX$ZDlXcRSVXqVcRBhYdzum zNgHJt*HqY_V{VoBeAw}`vrP=wc@LtycBt3!CG8JAQE`Cl)KQo}Sf^UQwDz1sYW-k; z(Ym+@Jsug%yPOgEXX|s#B3`58#!>v?@1j1j`hMh=I`=&`fluo!{ytlOx%)(y+tLz_ zf7uF4Zg6s;q(42BnZHsL58}3`SM&4h=7(5*GFL9=x_>pI*`ea|W8+`&hdpv_eRzDi z_lT3rkX)HLQ}y_2M$=K}Xb*6Hs^DfG>hsG7oZme0q!hJmE#;5Zw}pPckXmXCzxIvz z|JnNQ(`}~QNEf(%;6JE8cVJ8zPfWzmv- zmy_v8`=qGWw=2T)D_<;qzS>Ou>+$WNe8o#nIp11*zU=-@VONgGf6jMRCX_Y%$M+j1 zKiGnE(2ZBK!1>iK`){L@<6wPTf8!%+{3}w@|IPBd=YC^ui=cn?^<~!oK3v^}TbW-7 z_Fqg`?#2Zd!1{K6P!RX=ixHhH=}(c)UwjHX!X-9vr2`j>O|14Kig@)dY1pAxz4btY^I!NcA;`z~j^ANDprAX_%j5 z*qsXsgY|8F!?oO8;rtqipMj=H++S;UG8Ypi zoKLzu>YskG=T9!Lx{Nf|&XV+3>N!c*@0w?nA-h$Q zZ*ITia{G8r*|@oC{$?#tksHWel%2*k{r7y!nfTx_f}p%76TtqXM(X#Fx&@rS*M9ws z?m2|Jl*XLqGPpkd#?F+>t4agc7i9G5%b6X9$A8Aw!QAP5SULXKV(CL#);3L<@d&= zo9N21Szv!NmKyfJq`56*vwhIZq;?cw@VgC1U7 z=HY7o?;4RWHb42jeG4}v7v`_`$LOX4t>+$JP(V+)w3n-#gMy{l)Rgp0ED- z=Nayo(BJO$O?-YVzaO8Z%3~J5{65>6F0UTWDObNz&2O#jD*6!s^BHFF6t%5dDw+Rd z{b$!9ztJ6mPiTJ+MVv0Tz8}nIPhox(A58=I_h_{paYq-xe0C~d!<`-g^Vc}x5XZ&C z`nmJLeWdermSp~z^_OYgzaX_QYe4-AchTZVcqF)gZ?|(M+*ey^{f^bY5f^)L?p82= z+w{k9=N~=c)9U&YSpO4jHlHgwUd{JBq?%9p_ed@P8_@%G`5~*1YMnE=@s*A=bgXLr zmXE){Ez@?TdH;{DGY`wD`}%lkGAD${5GsWXk*QkyE)|iX0ijVLQ-(-LgHlPFC8UW; zG*GD!=R_rBo{}jTtiSK8$8+}n?C<)n;q3E9oWCinj}z^aG=JS0 z{cLmmI9dD0u>1}P?`M@T@qLwIA<=d=F4s2^=d;tp8sp%tbI|$qn$(xZp;Phv$f`sZ z&NggE=leeW=nC#ld(ii{npX~iw)wbz{?ssqzH@OtW%U9$nuR3hvTn;&Ter9--u zPq|=WeOZ09>-xah#~#m*8+2QYowxXMcXtc=$HwQQaqXc_8lV5&593eh`(f&j8)la{;81O3Y!5b9|>%;O{ zmv#cyNbd*x=U-BY3RR!aKXMX2x0Uc66ovYg458-(_r;XKi@T=$`TDtn{*tcL-&Y?f zCY#lasQAzFt8t~6ESYLle&Le9FWcWVQ$0m4>?P%PKLvlw_NO}BxM3`7iR&4oc};r-m|2DEt5RYQC|1Jjo7ty^LF1`B^!)<2pBB(8q50*Q`dsd$U>G`5iN9VY z><`OtMrtNxOXK_0ByoOaYwL~m;#|3g^8%l&zDCIZHkP^Ti{|et0iD4>n!hJb5&oWy z?^Rs~LCC{&^!<~5g_GdO-_vOS$*IdiXkLx`^M)Vs@Hb!DUpg;5Kg;LyHK$|Y`&znS|`l)t~HYRJ}6mgUp!RR8<;-!t+5OUwh~3+L?6{%CQ|OXJB>{rLC(GTZ;M zDDDe8r2Jv`t7g6(1HU%l@q1awY*=G}_qX2M^MNvDoWHHUd64Ie>tBa{-;CRz^`z!g z*z;BQyFFakhv#=$N4kT-_FYtehK=9t&q?2pzn4zcx7qs8@H3O)aKmYIzU)QTV#tho zg!UKi=7vLQAN+hxH%kJ|V?B6>pThZL^>NRabFf-bdjEusIG-I?oQGp;jQBef1U~(N zj?YO8Dj>QnnmqW$*e0`>xjJYBy|MjHp ze|+9!_?%i%Z+!NT9aFSR{92g3W| zd>&Zs2PQpme`R>005-+y@?UDj^{;N@Z{tn}X+GKfZi7{4@Z3W87g+uOrmq3rD)*rC z!`lM%z&MkR&n%zcBc{Nx!qaH~{?YU0aC`_JpO+Twg0G!$KJO%^z(c8io@y57Q}5UX zSfy*k->?+t^XSzJu+GegAJ$ReQ-<-6V^XSN+#e(UL-UUR_#q6RNm`f4c}1Mh`RO%e zyse}>=(ISWXD56#URvZz_5WGE4!A49TT@?j{!qDHFVLJq$1hetZfh99#-uz>srCId z_Wqu3hvtLRW z&d(*P{TF{({WHm{BS)@HE#J{kJpO)v-C~@Qfb+FvdV9Dk<*VmA!GE*)Wr9H;&=^ni z#rpGc2S&r|82tQKRXV}NkC)K-lIK>z()upV7u&yh6LJtfXG;CiV1X|-{xsOUHg>;^ z^HtPI9v0nS#g(NA&&Tq0G^acK%-BxNXR`XoB@Thgv$+2VQImk%usrnszQ$+kA)_tM zSN@+k*eavMYkm>V7t7c3E2ltf6|V1Q_pgJJjuHRSPn^Fu53hs9Fr2^nhBsir79)Ot zn82Si!{4Mszl@iaxT5zPU9#;2=Nh-5^C!AV{a}bK?Qd9qvgR2;TqNzU+4%A4^=vqO z2tU8MFWkVp7UxUVFcjP?KB4sq#f(ho5G}2r^$_PvsrJ2b?@M-QeQMu+MbPev>sQx7 zy`V9DJKCSpl^X_=b8)`BW|_fOyFB#$oT%{4koM~#+CS}Wz6Z*rd^vOzo{#0rXUr-aeZo^pV{l^$zzi-}#S!y_6X*=$~iDOcItP}W}#qibnqYU&mqx}_I zKNx&c8DfuZLF-?-Uo}8mmDVRV{yqOY0d8->`BF8Q1Gkb-qx1F0H9g>T5FH=c`KC1< z;n3&KC$v6WI{pZh`Qdy;zWHKo+h~X8?_o*pApPqqv_3Dpqc`+eM%O=6nER{Vycq!l z4&(9haJQ-OcOdRhN7?!V-v+Nw=cep~-i?a9L|)*B<*V!Db5O0L%P&7H{Lb>#Z{vO7 z2O04}OT^>j9pC%lImC$XS|qM-=Eibx{gw+_f65)(4UV?K>rY+E27`+t&QG7Y#t<5p zj?Tvo95o+|7vlbQVe?8jx$hD>f8;xC7tFl)iL1^N^q=)t_CxZZWM>b)FZF%~J%1!S z>=9YJ5z3dvi`OT|YW_4{ook2o*Xt8Hf@GQ}HGjnBuZy+%!QO4Sew}R`4J47~D}{MK z!S;j|L`}%!_VL2=vHr8}d?1{weaI!X2=STie<+t6fGjCrnE%qbRt0v`b$N$B;(RSK zR0K)03pIbu>dW~kRq!;}!pSWZ{(biT(fAodK;=^eHDAQ)OTl0Xn2e|E>umgbE#m~& ztnvEfr0Y@8J@ONm&^lkn`k$Vgk3-$M9=tCI&&T?o%O;OuMt7$E!{jess~^J?>G$_W zHHn{};-`P#RjXiw{&tO{&&mw}rQNtc z8+Rub);fJc=MR1w9fEF;75S?(#rgAJe--u)*X8}%i}Tk#vOQRxaOOrl7y4)H{Lkyq zKCns;_g6RCkAQtOxc+_6maQ^m|ErDCEr@6!casIlD+YN)v@#o)FPzpyKd+=xH z3(wE$-%Zj8C3Z&q^{IKS{LuZGLeEBc?_0 ztdsKKy#SA&o=M%oWE1Ys4$RXA?=t$f-R_`T{9 z*Kko>ze+A;f(?)BSHIIY0ea&6C^U5>)6*C6$=?6gpFW?*d^*8!O&4muhvlntWj`3| zx&^H-m<}HegYHM5^W8eLtzdwDI(k1uVCZtt`+EwlFIsx z`DlMNb6hi=bd$!%t>S!59`P2U1{m|Ibwd4GhN%xaD=C4=AUuEUI=UyUGG2xDhl{7^ z!c!I8-zN-}KqpIFzseFE;BEoV5AW;`JIwL?dA)lgys^RkY5t5O5L>CpzjhSXkByJ> zC*K8$RG)@gi0hNhZ)NDIMDxS?v&aMu_)2hoLQ=-U{M!*!|AehCw49m+>HTqjG6Gk_ z&aQa=H|FO~7_tKQr_=p8aI?hu*>e9qR7^JFyR-=TFIzvpp3?$x3r%><@xuDC^Isvl z-yp5jgx_&vuApyBf6rG&MzVME6skTrhUt&o$dHkwm`yF8X7L>U*FR?8&yJWWD_LM^ zS$^+X4^jO)*{(e-TVsd5zu?)YH#DqUMfJbf_-kr09E@dXe*KyJbn~Oh@XK@$dVj#-v)(KaR276v>(p&!2PxNq+FPip~x2yVf|TtFUHqF$9}rJm5n&Re>Qc6 z&0fyv`wRI?2ZKp}oZpn9@$jPn*S~I_wxIVq4edYw>g@&J&zz#}=VJTMZaI51;-5il)-<-*y$(w@)4aKzn;rUhb%{J}kdA@8u-@tu4!= zdiE6M%YMN~c>XJx@@E{whs=m6&_e^)x8<4cute(5u>7)D?_g-BLB~gS{)G%khTigc z{l<6WWBAcamycd9JRj@t1GaRO=8tyh_hY`^Q-^UsR-*cDl{5)ndqq(5g{*!}`!yHJ zD$}U>7dF4V*tijlo}QxWSM2`(Au$lT`XTqY_5Kt#zwUke80Hh!g&$98&XQC`=nPSSPpAgoE-Tzxp6(rwAT9(gH5Z`~*@7-ZzA7`%HdBL9!VBW7t zJF5*Qqw)NxCQds1+7aht`YsPxmW1=6oF4)QO)haidkOxO&HsM#sW3(H6X(JSzyH7b z%(*I9JP|)X?gh_4^}7!5=_ITV%MZNm3~heeqV>P&@&lk@$|~ynF>HONxxv) z5V`<3Fve-$Z6!TkPc2_oAs(L&g!hCFkDRFY8(4m(X6i!F`_1V5*`-wgOTuaW zW$Qb}BUi%ld3gMJaU%>WzF$P^2g42?gon>RqWmN`UWD~SaDFn}UP8n#9sc$)x|R*e_& z2=8yP-~W17pg{CGX!_i|8{<^K=j)a z{&`KiR)0?O`FwO+@?*4=KiQK1erNSh2;KpOc2>&&`#);8gQPH2ztsXG8nKkKFfb;_+|Y$Q#fLdhqofg!Nc0NoS*B9+Y@6AslVzV&duV!Z+47?Tj*wTOhK7Idqfbu8k$m#Gck>Y&Ko!pi@u`=TCT@cr&9**sa zM^D0Aj%Y8cPpNx5lD^8OyrhRXU$5c@!t8O*)cuL9J}uES00X(r==_Jb`EmnvsxI_u?G*W{Xtfr6t8xbeAJp&P9$po ztq*&D#ofuhBu**T<+C5ZhX2)1*!x@8>-2$5MmV2+P7DXNO)IJT2+OCEzbU+mq5T)j zXV0S!5KxWtnR3n-5(nV=R=qeD7J6Nz>cjrb`yYFQ&qLM%X@50aoWF2Ft9@agr!88)o8>tY z^2X8nnZkTO=)`7oQ1HX~oLAxu@)Pm+`{R#4eC>|w=cudkU|)2RQy_vqvikWM4nk?s z12lgaRbB;NGjaV)T>BFglW>3MnxPHdZabm=zOR8H_;$eky`PQ^5$lH&$uTN2Rv@h!b=VE8Qujo&|BCxGQdTp#<#T!auK zoUfMbzhIZH!&lrB)}Qr%VF|iWD~J1gy|DnM{Wf!U76Sk5{H^z_IZ%FYCpv%PmAwHR z^>Kgi^dSP)e>+L#=PX})OEO@WJMMp%r#yp*I-IWwq@SUHRjvR7T2eB=T%8)jtL(yR9t^frt~C|zmxeHv%8A&lU6%WQlxHE z?wla#6FZ+2vRisTfu9Zf{!i{D3AhJtLf^kI+_fBj8R7M@7gIwZ>`4w+OU*~NrSglv zDoN1dj`P*zaSCi-ec)p2|E+&V>hE2S%aOS|bok-F#r5Z+`v_1Cc0&Do>6-CyFna}> zf6E`A3ArP2{k`M470B>3Zb9q)tE_*ww2y(`4^E=~t4ixAv~zrb=0|oDuY>zQMgG!V z;e4_A_xJ4XMAzAvACNB2Pv(GLBp}&@KS#v*sXEh#_;<13_Z(6czO^NbN>+)6J z;`~HkoD6;AHlg+9HZl${vU(>v-|(Yb7@XacgZ8h=HzvboGn|ju}Wp zLi3+C9h|}a;7)Y@FML!0xM|@2^2E;_@O?%OIzRO5WGZac!ueW0h=(>cA2_Gh_Xk+M zDyF`Lo$kUuU?A0QFlRqS$#5J z+M7fr0)J(uczo21f4?^^dYP7y}@Xk5-nu+sq<=F>t4pv3;1_}?KXBstdg%RSH`>4Q`?eE`OmfisGsc|W0|SF-{bBhy_^bea z$>I9ruy}r-uE-Bu%OLUiWwhuEv`G1poh6(vw!YHi=P*g;ds=_l``arj^x!Ape1#7+ z1>?@R|EWB;5R!)nbJttz!)$(W&&LM_o!*V!k74;`7j!kqLEqn+^kXkviap6i91+%s z+fD04bsKTgqJKA=coH44YIz$ zgpYTM73EJZZ31W&(0sA_RC9YK{M_S%)`#bO@Bj-dJipCK+YZ0uQmOtG>o2>U&4Pqy z)m#E~e{OrqABRk<2GvO)xZxlFtuO7L$Nl~W>g!ecR0m=GSiZ)7)sy^j#QBnK9tm0v z*690zn+!Bre_0%X}G?8i(LUT zbaztoPi%Zzb3PQN7N(;0vj;1aphpxQzYm&Rh8Hd$P=8!z^9!OK@co}rHi*PeHsSer z;rUs8wLD75AFD-t;&tJ7c0TH9!6-@Xc4_~hSUi95chv`t2iEBPhSGHD`*~(7(EG{N z++5+-?I5Z@%JOq(h(D;8>_+QjhwWp*UNeXDd@Gy}_Wi85en+53bTwL^bv^M6MxIjO zH57#N!|D%zRGA#?rNjR;`?o&I)cL$rWDG%pj#T}X)sLJ0b0AQ06E`$a`2S<;WAj(6 zh7FVG{EFpg;)oqEYBe68VjPp6x}ve!_m=GP11!WE{u&t1g)aKb|kA=FeFFHNx8+;%b7pvT9*}SpH)F2Ee18 zxc|yJ9|z<3qiBBeJSqo<`BtO#x0UuU;dr$IpVR6OSpM`AR7ik=4&T>WSYKAZtZz#F zuc>U&48mfmZR};d+(*NIh>A<98*6SdT|>h zM(sxH2i|50;P&GvT7NsVDGxGc;riA-jDv*{b=;!X`4@KmLG1>t{`H=VY>m(C`9JU7 z1c})Se6&PdADha$k=VCGcyJWwQ!QjNd@XgP?jK_N@1OoG0H5(VpBv_HfRm5I(fDfd zB?6{sXNPvGe$FyUgvYOs za%O!5{b%E+{qW;3avtqZIi~;qQK1=@L@My>M~m}ObxW0GG!Ef21BLZr^~d&FMMlg52 zHCn%%V`BmG5%~G~Y!w2wmiYd!|GF23#T-TJw=Y)|Lfu$;|JnR^L&jZDx&I#Z58=3&s-sd~8fw1^FBB^PxD- z7yK`TQ}s!fpL<G!K(`Ti{F{ASk$Ao6 zj>f+$fAomkX9@rJuW)`?e%hX&3fH9m)5=WXll7moj9tNKgb(`tbE`+8;M8?DI^XK1 zkpvT0<9t{roq%RJygu@A&V7(MhVxMxqeiA>4dJ(K5T1|KhxVOk5G`GN|IJPU$n?Pd z-$lzg(7R$8`u@t&TWesiRS-J=n~)X@Jszc?^~I@1*^pU=?|;dR3!pg;*AI`3PtbR} z0x!E&&=1!C{q}52HkWlr>qoDHMiH}@6288_a6VW*D$bZnnitrW8~DA0|IL4;F!vk8 z>rIEQ102!&CHkkhL66HD(fYokgFj3=N}nIrKgv!@2LG+Nf5{tN3em4Gp!JUrgC7FP zc+Z80{5yYi{o}4z9}*Uh^V6e#7Ll~LqW&=EwFG`{na#cI{O|n&D!r2_2(brSB|Lw) zbHWQ&nbG>f`n!3}J3x5=?(e|qC|o;IO4aXK{m4+h1d1JTe)6_`g%~FVzPk1O9F`xO zA?=Av0j@9ldHQ5*CC*Q3#!Og};K&tK2>Qa_Z+bFz354#$`Dl3`0Kvz?(fWPGt$2`c zN^ztUmo-|AYQK}s6UDCVJUfhW={F!IeP!) zPwf4ptMz8XwOj`@|9o(58Qk2q5uFbjnXq2e!_f7%r0!o2PD z`Qb=A>Hs^uEQ1+Q7ts3sjr~vIYUlSNryhm zk8)~L1pQ?FeTSv_kfd8m-EYC_PrUOr*mL(jcc_=}_iX++>FY1hH^SqW72luu>>I+@ zy%Rrwy~ucSeS?ITs0!=n&)kon<1$_1x^+%@?oe_5CO6waY?1>SzwTwMgoLP#X#I_s z&j0sZh{vz&&559J2ItSN3kS1(@%VKqr2!lty+ipj%d&zYooxNaT$qyvrAXFP0yL#yRl5 z+<{x-F2oPE{&3NFHTbl{i4FHafpxe#Q;dgO{Q8 z`&~Z%kbQL<<)2fS_-1i28rq+UN8e95r;`cVWk=Bd;w9JHpp$W*t1uMj$23lsICoRv z`$h=*%=(|lJqHu-V?%g5sy;~9?;GRnp?9+b>TgPBtb>-1-e~+9<{b)TGVO2J{82I^ z33eu>a7C@(M`Yud-LN9K-iMA~tp1*T-2@)q@2L758=nS_Rv}LpbmukVgy(1DQ}zo( zVjw*q0lLEev-v?%sw4TcALnD$rWr870QWyBUlzmWfpq+0{m;X8fskK_^KoWPEJOt2 z@k?dwVQ{&B1g(Fr|8gEC55x7>tCt-4{z@M8KjY&x$*vhg`2KB$^C9{45{sHC)KUcvoI!(8>S&9~*yiu1u9Af1Xy( zo$B}B@9g_W-q&Wqj*d7#X;~g{_k;%(pICkd?AQilO1Dw{88$v$85a+q7vcQ8mEP~; zS9t`jZ~m~Vf|X_$xSR{(`upT}Go;(%`aANuJdtUZ=k1ON>&xoTlbhN^dBqT3-$Phm zmM`=Ej!@XNkn%6={poEpHp1YE-e~>vQCc`us?+|N)t~LnDbRK#%@?ab%eR(7X`51R zU3WoWS-z@!--nY5_qlaXh4o?m-@zyE!EXCI?rfIu_pClG>8eUzOZgi_y+2IfPj!%! zketmDzW-xkeOUhVwyl8QXFVu?%<@sE5e#P{X#c{-AGL40VYyd4m0z**2X{6~zi-DM zLH+TnmDS+;q>8Ffu=Vdg;}yxkN_jN?&&Tes>CTyw)ZFRiwpIiF(+{@)+e^U? zDu>TP>oY4{T_8fs0lnY*n&K9C5burp|F(PffRb7~I$vkqJrA_kBr&4#B?IA z&&0+PbUZz%{tD_s=*7*yTuMcC)Nw-nBevB!0g}nn7Qu7(C zzW!?C2aytQv_7uCZZG`N!u{*Jh+{A}@d(%KCH()h`L)i?8fYI>h1MTpr+5 z39Fysr-qYfU2y;EHo=3qOI-PCd*OVs@mX!aJhjOuM~1={3*5hz zn`J=fqq~`QShyK2Pau1)Q{Qt z8*g3!IhIGz{P^MaYtSLMipu}k_|ntlJM__h$A#P%_+t6UNf|-(?rQVRv&8k`-TUQa zQy*9Um8lQ2zG+@p1M!%sX4lH8=~;&+3EIjrL?l2<^X8nEqm_f;u@i0p}yB(=^gFK&l^O zg!N(hSSo%0?r=HHhd;xI{QN-ZTDt+&j}@b1AoIiy?$dCA4>mr(pPL1t`;*c6n$i3X zuymmLVCw^#qkqBOr*FA;)x!F)e1yi2A_HD(^JR(Rd_>(?MTV=p^681f^Rs+B;1|OD zk+abH_fj`+*ww>>ntx&W*kK+H6Z_%uWxd=1s8WbW=R@Nc7C~E8+`k_f{t~{#;(Vy? z?nr+6%kxKC-*098xy4{B0-dD!&s5?0|KI-mE`v#z7Et%|v-^Mk;5K-gh424h**JK5 za0m5$NOu2E&dr9!RmoiVRbl_w_~~SQ9^y?)D1XkL5C8SIVWN}|{RjW_mG&PEm;S)7 z^tasH*84eFKDu}6N7h4kKBPumKVAE;A@IzFcMlQPhvlQf)CsC8W}^PIO_>jL$X$y1 zk9&7_g87JT)OFe|95FpXi*_<`W~t&sT2ZOd@F_{BN6o>qp=3?7Cznl*ZzGsXPyY`-U6P z{;QHrJoH#e`!hEFY@2cvier<}`jg+LyP!U#3eA6iJ&+-(j&ITYZg*IJGWTaUH2yAn zzK%quy71cT|2;qb{>P^~F3{oXOjKW*K1uKQ+qIO+|5BLy9X!-`LHAdIX#F~KW-90$ z#`#H@R03m`m@Ep4dM2^5Wo6vyh4JoKCC~}j^98I?{neLr3uf^ z>Pz2_ZlL3V>r3ucKX8m&O4X;?_*3*F65O5#a#aog^iiJb55DM~4$m{<(D*Z0;S?n8 z$N5OFtc8Zll~n%c&&*TkdhUX9)Vv`j=hvRmeLxdEV1RSRa<3`IX~HNwhXU zsI|XH2wgvzvVJYpj-vI0^{>voLg8-T4QT$`lC}qm`t3mb^ZT>&z-@9e_c&Sj|7ZEw ze(WOn{VC=a*$BV0d~B$aBW=vza-~22{Z7wsRP`N1l%ID)FCe6Z&u zd6^FhT#EBk7_dz8^sa6B=tQA^c#ZjfX8zPAV0(WicW#ovhd-h4km)`?0Ax**P{_1VDW={s6W1}-Hkkv z^7VMDz!&R}zcfxDcPh2{B-4NEOY>DSKMdre*Q4=g&8)qU)fe}-Bb$za#{^nmQW$-i zwEr?Foh;^7>ipw_?%(g|r9j?{rS*mNFC#i=620r)_^L+X`B;5f={bj#945TOfq&0O z$KRlPn@I;N7yfUd@H?wNvV&Jh-pSdPN5u{ooqre-xfH(Lnt|RwxypJyOc}d?s_(M; z{d`XbY@Ce8r&A$kVP!%#T3=Wd`3NiXeH2ON%EkLHJWR%F4kk#T5!I>>R&qvi|IQEX z|2JGwCG%uyf5M*s3j>YF(9c>_e}diLwkNid)B!Gh|JLVc&&OBODnP__-A4-+Jf}(h!Wt zpQ=amiQimYKmHhOf|#50(evH-Jsg(Qc%k>N>{%zhKSi3Iq<$0b4`=hkug2$KT>ose zesuo#QwY$jMC(U?+qESx?lg13!v%lF>gSvr#$-db7S*3%{e}ENf8sXCg|GcA@Xzjl z_a7@kPHiSyKRPuc7#t5RLE~qN%5FHh1>gVO*4ZFCG>!{z{eB$Vzi~3V3D+jz=l_uU zcPQI%kL#HroDbH2r6u$vhhEB|`uD?1m&k>5<1 zPQ&^5v?&6XU-3fw$9l@ike45Z*5CWu6oXzqeLh%!_QIn93YBU9z{ZEDY3<0;;AYOI zqreBNk9r0Y(wsr-1Ix#sw*h3YoC~k2bV{^8y!fRj>~)xdzCUH`u^n9OmQeW}>)(fG zC&1~=f!wnR!v3-P(5vwX9RC@M`uA$P3YegX`>Rd6Z$rs2Tt9|~{e**B_qdj|!oSb* zbF_;ZvA9I@!|JPB(@=8236C!yi=2pWU&24UAkNR4(sh!z8)lbRzx*bwuZb#UP&X~{ zgWDcBUp+fV!s#Y2H2xItNrBtZIA5vjO5vJRf0cXw<3ox1_qFCWLRd!{!DtP|;FzU~`q}_#X@-$x@)Bm_?{0F9W#r4T_ zS8tM-B**tr75o{?SLt;Zvg!?>{$%2Pf0&>?pPJ8Q{mF&HQIJyQh31FV%4x9H4UbRb z-k${7jR(;B(wmV@;P|wHD}E>BS1cb<>K)0*o-`l+O#R@);o&5~2tPl4XPA-D7%eJ4 zmSOzqnA1U|^cc=hza}qGS}_BifBX126xME7jQW?1C3|7?*8sHsBr_!se5+#7_;o|S z8v0cqM*W@d-ddP^`2^KJW%FwTTNz^i^e!6T+F7ZSZwKZ0%+~vPSbh`-x{>=;fa=eF zvp^VPKcAYPWckTei-C{XUR->#u)pm4?GrT*!otuns{X|K8||pmpgisXHQ&wpyP{)n z;P{6MuEt1QUxvqbB5M7cxuO|@KC%4h%^5-7binh&g@d<~`u)!QJ9BY;nOx-!1)($0 z`oQg&9S|YEgi9|Lo}aBx{!!TvYueEMhOKWO8+#1u^Kg9`pms@m{{+s5iJvU_l6IF< z3KrIfjZb#R`;r|S<*51+yZ>8fTaX3ow0N_Ng1=$U&kM)J#3>fnmwxHn;JDFzYW{-d zqjX&?SVenre@_eR!}4)^-yv8yKaA?1vV4r*bO!GIO`_%tSbvjtu@1IyCpd?t!t=A| zBQf_a=s%$O@VdR$of=3Sp%Q z&d0}oSK-4km7Jv1JI3Ei$gJHwh zdDQ#`s~@Jn7pB8$(u=bVch+x_6e5P&eQmK8f>lqvsA%H`?_XC zUg`JOYvbKff8yql0)?RgsK0$T{RFtU$8t7_!uqiO_Tckt@KG1%!)MJW$T7$Hxa~HO zIFF|J@Mq>T!k94hckK%( z%&p*R-2{GEe_s}=NZzU5<)+pMzq9eh@%tchQ&)~xOA^>XZ%O=vvH)Ce^=gudcT{VpDqaTB)7Dr{=Kij2g}dH)uE93Wgc3e zlu=KF{U+a=I?`K{jrf=YbuUA? zXEoyU1Mj#ya6TdntxpG={D5Uu=een^^S!J-jM$?}h7`W0{5Pwg4_;`I#m#LfePH=W zcx+9gFKP1jL&f=+Zn%rAdgsLVdHrvF==qbdw}H^Bw-s8yK65?>ba;2pfSXXE<%WI-cn@4@*fy4sd3klaD%2fp^3MC$dsqV?%+H`bB7cgDQK z6yf<wG{75n+PW38$!&%{XR$nB#8_4vl#(a{4uzoB*4URh@ zCvYC>Kc-8PKr4GK>OVAU^T8rCl#AXYt}ppzm!RX~B+9?B`Wim|FBtirN9)g;JA0Ab zjjy>^p5pO!>b*JSou4MZd7L;u7L`%tTf7r*|66!|mY>?e!7yyobku(=R*#3(58Y7z zkx-clMR)ws`r+z(XW;j~7*5$=h!3nkAEQ_YEdf~^pZf22x<9OV;0@$Y!})1R?m(XR zzJuofH;r}4%zJHkzD3}JgfB*T)2za52`wuPe1K`tREt=msIUNUB zjPr4HUybzpfjA!pIWpvW_a< z4%A1+p!2h{svkf<-7K{J+%u&k=~;Fg)fdCsp`?3G8~#x1{0+;;p0}Hb&wgqAN&0tw zXn&#^xeI=6pNsmFJN;9@)?zIhf1-XDz(ono2kXy!Ib4NERh*Am&2M4dgd%RPuW)|Y z{QuEiS+a5{%@6Beyyx^Gn+D+gL=GopRUEFb!;Zv~EB;P=%`$O5a?(RURSD-K^+f_? zY{B`6zn%>{Q~lBWze%|qF6qah{fUAbk6?1&EN*VNus-bjO)1Yi5xHQTkMok@K`Chr--x46rPXW z|3-N^(y7;ZuA%k$+5O*iN}W_cZKCvp^{*2TONiHU72fQ)pr34f-Du-W{Fc(^gN?7g zUE@ieDb9yNQ7Gu%o`%MsUtOZWeE(cD|1;cn6qfA3_2aUa^!o_UqEY>@`0)fBI%RP~ zON8}f`KVM?CYNU7d|bMxM;bS`;U6jr`3#@0T_gPbbnH?Lm+L~P{sha{uIo48cgB8h!e8O}+5CUR+)r>( zsfe>UE&R^%l_S%SOi64)^Z#F$Oo>diH2xs@pSic^CKPeK1fCKrE2cz%|TMtOOXnRSlp@3HZD ztm#Pd(1z9z!qgA19&;q-ZwI6C*V;T6u0{D%^&Nlaev*A3Z^6#pxIPqHd;xUvwI0MqZk$@Jqf5`XEE-`p&CI{$!1gG5@eioNvfa zAU)*q{ZDwg1G>zdhW4KtH^zYZP+T8sRvd(B$!pO5-KIY!Q2aIotq&wzehzl=nP~j* zRZ<|^?axv5A$I?*&yOO3I<&uF_djl{Gl?l1%%7bp?!P8G#KQ7Jb5MU#@?{@v{k7uUb8Td@yX{3R>@{W%Fl+NfzX@tqNadC+II5pB%mi5UX~^ ze4mHn{E_~NWQmFspY%ywfAS9;g1PPR`0c1v4esZn(f)&L@(bzxwV9|to#&!R7FeA_ z^S|Wb`sAw&o&U1@MESas0g1SN=+4;*5$4m-`4E#k`(ei1Md*Cdz8m>auZsIGSaT01 znc@2LVf%Nmm{N%P({%&75rbd1IQz!}A8h^b{kthd8&r6uHRAjGLTwufykms!@0pKr z@V;;k>K_i&XTaQ=)u=xUeRv8Mhlil~ea9V*Fw+>tJ5nOI#neuh>flUUB4oo5cD3njZnmgQlVNq5ks@z~kYIsQjLdpOb8k z1E)gk2b-UjPAP*d4|;vr{6&7xMVP!b8m%7<%Kiz@ED9-q!7=k?D)!yU!{fKm{>#$) zW5~~^vQ+-Yo{y0^mSn6Vtq*K`dSe_!D$X16NlO3LkIwI6$L)sZd2`VIzoSnUj7V9H z`imdV_u-EAey+@1h@WizCv0^S^ped)=kGQLwIxtnPWcOt$^YFe29c_USKQ{C!hfIT zXF=3rGRbi;zkH`SKV{rLqEYC`fA3r-n%{Rjy9;Jtw?y@0?b~Fi>$ixiFS7ic?Ntbm z6>0yH!uXd*eJ?|&`8XfW=juS^&OXYYvg@b$>^CS3F62zF3;Myv7e6~y;%$w`mouIQ zq_R?$st>XJc=`vE`h!ONW^HjkuEZq3MVmQj{WHs|Q6)cy6ezrVa>8By0B%zrs8t}ho8 z50LF{j(mZcI3LbKqv3YEC1=-Lcz*W%#hPvFRVp!(rNA)*ZeOXg`6~=eL z`IwUY7M?!JK=V7Lvpq?N4>!^Jvi0%_q$paJ|K584E2|$`6(JQ6SCm%}X?TtD76KZeM(eQ5ld^HzquNH3uBL-u?WeeOW)&2fI(`)HG$ z@~g>;+bS^Y8T4CvGKR;TryGD!})Mu7y~yZ;rh|@R5~OqqWNI;qhMeOxYY7ufz8HQItO+%>C7~E#HH#TL$XiJB?K%ZVzvw{`K9mbWq$*AKOsD@f*t zLHx~p@$*wJ6Gl9j8u33f#Py}1M=ta^>WS8uC*_|5xkua4{I0!UJ?vSq56$1cKb0lp z^$XDcotBCYx!Kf6`43hvhLm$o z8-@7H`uisb49QtfSw6%?cz%DT{$nY>gFGNc{Jvx2`y0137Qz~*qW&xW*Fo@p;X=hv z)_=*2sQ{a-?P&h8!222atia<(muGE=O&fgwugCQ!*+*`29v_6~XY;qH5MA;;9p__j z2OH8j8`p<*&S}Kvg#*8Gi}?Nz&)yF&W9-oR{xK$bko9R5+Mlbhz6AvtQE2}DIPNoC z+?v7NRQVSl>Heg@RcG?*Igj@L=PMeM{)6cFz%l#pVzQbf7Y*VU)Qg}0K4Ed7l85hq zg>44x;a#Zy8oU3|zfVFg#BmzmCc=WVtCSluTBttXZzcG-Y3Dq z)pqE7{{gvUFlD?aS|3a?tb&6@+qqG4fdA2Ot1UX;;cb5$Mtxp|?!Uw43sCQl$Il|wm*Dnc zFY2#eT7CnSCx_7fQsdMvBpi6Ee%wVuzyIF*Iw1!h$x!~1)sL7FUZliv5bxV8&PV2| zL!|8~2fqH5`1w#*9xJ)J;UiBvc(msK^!u5b&AVa0KCVBbh93sqRW4}#Ih&jT@7umq z{h7_*3_9EcvoU!5HSeWJ`UT&N?AsL7-^}*RhK6A{ zUyDX@VE@6FYgr@s504`-)BKXY5OKE0z?5nMH2h5Gwa`O9!|+IDIFE5s+3 zub|W>sL0&Q#X1WA|14j9On*Vk(L-qbx)$1%V9pU{6{``a!i<$tU`*}hGKqv5t((xHF*FH61OUYK_Rc37`M>r2~%YT)Hy znjhBRoQ`<|H`n9*v-StooLSGD1Riw=ugar(d7Nsm)sEx zA$}1iz8&#*AglM|e67ydOiu3`h~{6tj%AaLpBD0^I^uk7y*p9z=kN!9h>v)DyOXvL zD(6i>{dvpn9Jo>DM16ma)u-Q$=Rm=83tGP#_~8+BD~Lq(skoyIv7B%S?H>%&9Yo|h z<9xkPwjdTOWT^TD%U4B9H1YZ~iBD7%;y;_8DOenWsB1Q;f2y%7g}2*RqW=5j)2k4; zJ{a{+YxLj4tnqs}$u8l1a13ASmhH*0E61q%CdbtO`>2f}s%>$7dOg~StO-=+UsLbz z(Dkc<+kD9zuYsuluKIR_=$&7P>Qkt+J~1KR3C+)j%&vfb&o@)wCt~%bCj1H1gyQ?} zRWC#0-W){pj|oG2kY`Ics(!_uuM?vOla+_Aqxt=Xqf^Kg6PyqC7cpdc`XtIzx`mNfl+!I{ky*N06!mt z(<))D?`E{VQxhWnKA=}5r`90uU+VA4lBpLDqWzDKmOaT>V-B4kCCfC)wGG$N`nRLL zCGi|4!=LpN;ybG!8D)ON+HoN257)lWhu$}x(EM_`^-b`#45sSatp9!a@e?FBBvSbm zs}GSL9Z7ujF={@EhwGmz86_2GPd8!{~x-~Z!F zdy(GVInJZ?{#3TUeY`@8c&xjQ=HI_6rV;JFGQ3KT`2KgO^(VPz15tnH-#HnA58&r# zruuQPj>Y+~biV*cw{E85C##>`V!yz)!--V!7+c9oJYkiO9q-(i}-2kUR|xW<#_z)8Hlxxfdjk4|m!iTA{Xd~=XEAMH}Jp!u{l%17;t zGO*2GfyP(oKer%qIIgeVisZ-cD)$@7{(uK#VI>Q}74e;*l0o?Ou28&t&ki3pu6d9(Qw zKmO<{QGRX)rb6Qw3v~V<<4z&`_~nSkpG5sjAZgfy>dWPAFF{s0l1pm6e~zsm)XIE^ z@aeez)H*8@`@DQKKl19LL+T2zq4D=Z-3&4*>n}IrwD|e^eQF6YEyMXr^iLqs>XZ2I zv&8vwFFH=v$}i*xJrU=t@0KI*V6QdRe@S7!KcY3716>uIugjh9fl5;l7uF~~pS&Yi zfs}VVh~_t$kNS`U%g=J}TI)A#{7S8!NRp}>IF)hY@%_TlZDeo01{$CKRHcDgM+@|R zElX8t{iPV^rzGJraC0}I{{ENyE12+W7dOaK$ZuGF&e(S$=Ha-$Y}~3#ejT}n#%IoO zmh}GUzZ@2y11&tr(D2Tv|9yLJ53%nmjbHl&K3IQKb?_+oO|(Yyzj#d^<}X~1&c}VY zUJFUpK~(>Z^>+@qmDH6l#bkyHozoAa@wa%jcW+E7p;Ykf>e$Y1{ zh_rZUp#HVp$U^e%-U2>Z{%ouM(DhBP#}*Rp+)w<0XX5eA`&c@tZ81mdY%vb5|iZXXAXG&mBs(MqJ}gO%wi}txsh) z%qAAvf4L?1#r5ac!$k7-#zej}N}Qj;KXc%HCt5$)`yZ@Fo`dDp%Q;XL@*8%3Znae% zn5NMDu=UNGcYeY8PkX5RAcd(PxXAV+wO`Mm`f+cq5jnen=Hm%df2uQBPFw>!^V1fK z$L~{t!KAC12I_xC7#ERR*9Cmld2xL;)j0%(>E>wtQl+#6whhGfr>)ObSaHIK(jS(O zGu3aP`vF{kKIJNrwFlBs{dIXgj3iIR`S6=$Lt-BNLHU@%uOON(o%z?T-%nuuvv>b} zr1acG-shUY59^<&e0u<80YOxMgx&uzlRxk@aSzoWVfABYL|1ZoU_RB~X8qgBKK;p+ zgfmor%=(wc{l?_+o##~jo8_as*LHGhj0S&uvABPEnSFx1kSyR`K8o-E4PQe^ZSSW% z=V9BbFLZz8opK&L&!3Iz@8+%NVX4z{v_GKN@jC4A^+D&S&TV=N+gIUyboFmbEN7;p z^{1WP^~kH+SJD1j`dwSnl=X*8{wA&;&RYA4Q_@7fxIujX%@<}systTzyj46u*!;B= z^6MN>e;0N05lq+`#9d!0{5{Lh*#D#J&BJ>7y8r)XrBbP6XhI<}gfx(|UQ!xVnj}*c zg$yalT#<;PQRXra2~nn$eKJc3$(VUa?^K3J%J=p8{qCc^uj{P8U)O!Vb=G4)*K@7C z_TIKK@ND;1Qd=bGAFCfD613r4%?XsBS06YalipGDF`5$keUZ8i^I^TD1K)qMpdW01 z;f(J(==9kb^(R%0XJO!=Nqjdm@%%I4oSh`*pUs{#_I3AJ6E~M zIygU8{pz^`BXK?)cBw#T`+eyC;|L>TFmf+O>x1@T1EKoPT~anh`2KAEu^2fX>UCRD z|NGo$7yP%_mfxl*tS?qSMui{ZjvC?mdc0d9r@m|oI-mSu{e4c!c_~^SyxsefoAP}P zT3^QK%EFE*bbey>$vs^MT=HJ@ z@B_^K58nPGCA)9E;(PV-7S*4gDS6x)4(BJ|@H+SS#vD|CBAzyIdPbW_P>>K`*8gr@ z&>rO9>_zoOF1R~vv!U}htIvVY{lHEZ*O&QA)f+iX8G8cqYI&NC#e26 zo4<0F41(Vtxc=^6HVSkuyhZ1G=e$@5YoDw08)F51V)L{0q1~`M(3bcA*B@us*SyIW zpuuG#;{M&BtHya~6p6C3E%^C;MU?n%}0|-r!97%t8C3XQk)c55G-9>#H%D zs^If|FR|;>#veWZc`LpL9BwM2{2|Mi{b+v(*xZ8poAA*IuzH;_zu8@!ucaG~a94sI z(Eh~T2Sr?L^JFT2#W3>?8POG-OYstPe|r8FIf%KEiPlf$mpZ}CStro`=P$Lv&~Cw9 z(vl{8A69>dMn}NA1L~-M`s`F(##q}k6cQ#x+W5YN77UyUBw|s804bH~_%Tn&~li6tgNyvJ~MI2Z|)eo%x zcHJTmddD&;{bl{%mo@63v}G?jG*bBc*!ke>jV6#CRD{+KR^R}kC3k`h(GHB+@rb2zd`r}(`ZgatjIA3et zzvuo=T|@OZS-uV}P=I~2Gtv6A|87%|=oF#;7#=u+&eXT$#Vqmu=8TbvuvFiekKHHE zPkCrD47udbw-|~0KgF^3k~za(@;Z^?{LFODU$@MXV0yg~ zs!zJ=1cul9^EG(_U+npf5!w!t5%XX2H(bR1pTp$iT=m}3Xnx!1ahZ#d^0l0L-$#xb z@H=4qjLTRUh5Dn&DNWp~mx-jJR6M^8>7fB3Z}y=5<#RiSfm4q=Xn*vLe*ip9_(Oh} z3Vg8q>{Z(j{;oJ5F3Znx1`fFXq>a7H9aqHp=&tui`&ji0juv?AkU*Yd#^P9X~ zGxzODBD(*VP^SSellP$hQu&M(Sl=r{{ZZ({q;AeyTQm|xc+vO zF@y6l7t#7EVu&jgSHB_qYQ_2K@OC+DtW@LY9TmP0tH0}CmO#^4e?Gv7{PWLrec@g{ zM$)g>Oa4}|xc(HJIL}>v=8n!^eEac&OFFO^?f)#7YvFtf64Cq>^hgt$CgOaYY?RKQ z94HB#9?&oIxPi1vG@Xy(T`s=b|`e6Jg7tP-tru2pKEfrup;6Osy{ljR>H46YH0nDq<=;FxTZhfU0s}?z({Awy}>VeA5ZcA>YTZS z+}8mfq~NNsepvrF-sCGyVy)KgYi&cEz4&r=-r(fjyeRQYz$Y$mzD#kzH27C!Y z>({(jwOpU<)s#L1(E2<_G!;n2&fjMT;o-;edjUo>Yz zN9$(P-!!PDz))`^zCg3>d=&kDx8JJ6P#uT!Gil2y?i6Q__Q!7X*SXffiD-X=d-ICx z{xuTS=R9i}xHuNq=YUE>SiK_`^*`#`9xy--=V!^-7`W|<=O@Ds*Fe@~0{?B6I6uMf zTqO!oRlK8)I6v1Cin!cRcXa>eY2ic8>|6+%->*sU7xuKn^?Ar?70B$r1+7mF`|H4- z&U=WqufPY}|Jdqe4nHs8d`-C@3}L;RN%TT-{VAzVfy&vE-^<0|uYP3J*yT3im(WUj5tsmkFbYNgiHoAXPI;%fin^8#3=dk_tBiZAi z^XJ#3-JrJpVS4{Gsn;xcmHnIaA1!Myj@ywJiRPz?H)Wx|W+UqVGQJsuML#+}#W3@u*IMl0&M}-1rIuKT`=ZLL zpA-ImmXF-(qtNJU%}1HE=?mT8a;m%ma}+1=&Sh=C)BgBOI^p8xxDx|Mq5fg{(b`_g zg*t=~-EqS2?0k+xVFNe4A{MPbd#+an)4B|*eqi&r!)0Bm|Hwx7k9(~i0KtQCeNk=o z1huuV$vohTM&4{kZj4cj(=6jF{O9`bro+@?MODSfkr${b+W5HpqDVCeGdhAME-#+_V~w zSE%wyUxeRTeop+C1Ls?;_>6z^ZS4M@`pd`MkcYt}XRvtun*zRZUZAd))2&idD&nexyOkL$y|rcR)fluh3M z^IvR!y?U(&{MmAh+P`D_n}?2bP`;)VJ>R9F6$*o&H=*_8B7O~I9KiXQI5roiH(2qR z{%!g}>r3}pXSovBQE2^W-Sa88J}?;dCqW87xY|vzX#c#QhdS&?&Y=36tbQn!41z^Z zFOcY3flszR{Auh1C)d6rT#k5up|mOkjAj_}Yy8FeS>kXTzFJSAFkb z2mF_RS$<4|KXK=GE<*FiAR7f(LRTpxCsbbwqJ zTp!w9>Iqp+$I$-3@fQ|wBAt#u>o2C3`-1h6SE#>eTownV!K%F51L6Cy`Z)5@7HAx0 z$k(hC=cC`$GMHHI$Ghc;^U-+wGB;(o8!3M;-XHMY@r)}l!S!`Zg97Z5+lcPZ4v6Rs z8xP`qXnvN!@rSq2`ww#!=1cEC$N88u`UD)AY{eJYi1U#eaGu+kC_(Et`DJ%GlXDZ$ z{CT;!ntN-q2%Vo<+36QI-yGM6k?k~~b4QvVRv(7FGJ%~vkD>LQ-K+87(BTzPeIc$7 zu6}Ew*j1J9|3{n;#hsb(@QVRI-A$Yil{0ssLyjN+u}Yke1jDP`cttl-qu8cj^!*RL zKR@R#)Xzlym+gJ&`=HM@p#H))q6^%P%0l)YCcn7H$*h`y=HLCsHC*I>5vaauDKv4z zOJmUc4X!@ZfTYrNw7;~o(iB!a%t7<-L+SlQMPFZ{{%?O_1Eb0$BTd6 zg~0iKeD4NvK3Y0meDw+U$esh9l6HH?fv_XjT(Yr>fPbktwW(di9tw{l2N55b?a{;N52G{~>M zh2HP6v&kPeK6**Y|J@(S&VRgbiHBKl+oSqYDQvd0upX1D;>wwv@Y~^HW1h zUvl@i%p|^th4``coA$=vT);MbeZ+)!gPX&%(D@fn7fZPI{5;vHBYYp0kM!_xSPQ>U z|1o~`HYkcVK>gPT`6BM(Q=t4M0JS|O)BDu}PHo}@!i5QcAL~C9i)*_*Rr?gaS8N>d9S^=Ap47QuWqTwi+TY=_+|4fxCp z;`%aQub7*ait}TmRKfMR?MKf3t8ZC;0+!ctVbb?$+xCYEbN}p+&dRXU5$7Y&zaw5=BJ_Ccfbk>&QDWoG3Re79T6HX_;*%+va2h&`2+k=f3o02 zJ@?%<9PKZsJyiy`uL-`sa*aI7P(A8h~dQ=k(lHQppI{=F~C?%&*8ngGEeI3L~B z3!rh)FkbhGI3G(F-r{UzUD5faj-hWkMVT3BeP1f`mrJRRM(_VQ?yC(l?dkl>>St>= zYgkovj+#GV^UJy8Q($*V71;yg{h{8Ac7nUM0e}9QxISD7tAHo##`EVx#Q6^jC!FVC zp!^3L{~som+{5PasQ=J6{mQxjUWn!&&xb1D@gM>9?`jnWaL05vI$zSOxGzMeAEo>$ z%SZBgXGoIrG4Ph4zbqdC)r(%Hb&cK`$Q>)ymtO)uGR*s{ z8%Ze_al-}OziJ=*j$4!wgzkTObd!NBpJ?iRXEs0YwAX>w(lpAyvHWb`VFO>@okR1F zN#j&7Ppv}z+2x^2V6hhdePGfq@V%>#=AQ#k9>H`eU$rITd=+MY<7A#Jr1A^fKlD1( z9{wInK>hoxK1MLxayPpFTVUo23Ab;O0GYP>R+Y-%EeadKNerdyX$->H2(P;i?G0_Fhy=mlf zg}^r(|IW4jVC}4eDE(dTE%3-jshd`;cgN{~?*&ksoy zk8hY#8E3E%=U?UVcTU$H*N6A>R3SSd0o{Mx+1nVrba$isvkqr$VNb$2YJP^*&#-{8 z&|%I^;_*fJeyl!hxVIEOoogfwx#Ieu>u?T2Yb<%)0d4gw-5;)3xy*fhDZL^=LGb4+ zAJLtja`GADsrgRUfAu&e3#;F(LhJWlcXZ*2R~qWS_3oR)>#j%9{!exKbXau!1?oR< zzu5>iH&jr6_21+y7`H*6U#B6?N1V?SaFQ9%yH<(wu_pZvw|<=q+W#?+{>a&@2BG!+ z=do%K8jwJpuVd%$CpQ~Iz>8fdAAI(3DC%>LI{yO9{XfY&-5}8RCRx}~Tt6-jS`HSy z8_BL1aXv<`I}fWaTJmWV1U^{(u;MRsH~QoHv3G{FKRRhVsvp-UHFD<9!qEI`cCizb zo6z}zF!uxWS04c11|22Z)cu1hls>B79|4aH&yjBb>VLv~A2pjGSX%UgSne0sj|cxH z!kzOf{DL^ap96D$b!GWe@GkY`->a60*7s8^?{V&1U5IzQuzuM7&-IO;IO~`|G=D}P zk%Rk}rT4@C+n>v3=7(B8cZaN9I3Lf>xr2`EO%iJ&9{(Q4SAg!vAE!-f>8T5l5M{|*28r|0GxrMj{n$vN#!Z=>C4z-)e5vh(Of8kMNWS$(U7C z{$=@Df3XK>TI@pW|3cl7@VezJ$xRUQ3wu9h{;id8bLJ0pKB(Mx4`lV#=e0nbADf^; zxbto(@B2mYpD~R8T)X2c=NgLhlN$7b%joBe)^DzMO`MV@0QNkon{WIXzK)eR-$PgzZhwiToOIe#QoFf?#(Q{_bLNehMzWfOgToeAH@j zes(=8=b~br(fYp9wuY;`G9A^I*YXOWdu1isKT}QU4AvJ?QGa$lrzf(-uVYnFA~o`i;VVy-GALs{aI5}D4o9_O6_m6{M7f$FoabUyr&tO{S}CeFw4r&SO&1m|PNrU%^Gjn2d-Sors|`6pceKklLZbo72g zkJk#&bMs0n|FHF&secz38%FCZ>)!{j=0LIF40XP85OaTYoJk0byYd{>*E=aOFst@E zx<92ccpqH9*Nxv6Cay2Z()m;6Q+Cw;rVLQ_K*sXQOU`qR52_zQUz@o@TNj}DCw!F# zREFXD;d{*lu2%0PD?{7jPoH1+ZnoK9rAKDz2}0ykEg$4PV})L|k9G`GiXhH9qhUo92k-rxS}Ga${7SiDEB-FSfrJ zeyNt*(-GI7xmJpBH-81$=9K@x|9_UR394PeS2Yzqe=to(0#|OHq4qC;;cMUESuoWB z*WW2lvCzEpJ8^g>u0MZV_Ji`#ZhX%@;(Xox_KHg!fb$a((Zap$PxHg}2kad+!E^F@ za$rRpA4(LUarvf@aTw?4?p1H7XuVDztP;;ZUvDLYUbZsoPyUW5hF{l)@Vas0d?YyB zfRsem-Y?0L)f& z<3rAi$N%Sz*D&Uu4`2F0eEke^e8g4sbtdbs3G0K^U%Sn%-0ki2(fUVLK?_V2aeb+H zJOpke9VT6t3V%PFUp6WDLelx`qGVWn_RpOuD=oA-f)j+`Vjfe!uMhO2j3qk!9DF2RR4hG=k&*J5LA|e`V;@- zqafjT0d;Ahwedm*B@X1PL6LO@v09mJL>X3eWd4eH|&m- zWR|?=hZTkX`t~nY zTu@&AjD%bj*N1g6snBDzGOv*;o_~$44#7RcZoGD*xPBB=y#u3*KD_TiaemeWMM;ca zyyv&Zh}VZ2%N}#rX5;)^p4`BBmj+P&j@|$5SJn~a&#xoZ8EyJO=bv-Z`;kAK+kw`H z?Q$I<)aD%dIZ4nD*55zY^n+bruc7tPs!3~Lcj7k^^jY}dv-3wYY}3H5r!w!EEB<}A ztCWCZ!Vtbsc@Y)i3VYd+tHH7j^#}o4@S+WI@w?9=d;gH^mUlN2QQ427>;w{msfp!@&69A+&y+ zd~QBG;-8}WG-+r$q{~V3_gnGxqww`G1nlpM>eCg~k1)8^n|~53u1_7M_XGR>bwuZ< zyWjlAt$j3=dcTN`|DbQmuw=(FRKH~n`$F$|c>KpHx`Nrd^W;)jL0_|({%+OnIMBcJ z71fu}uq$BfH-!K8Q;0w7U$l$wa0|R4RKZ+*n zz^XC0{+_*N1)7Tvq5jTou0O;$MXA`ym}B6u09y-w@~Hn93)(;_1z= zH4u-#cHA?ro#Gg@{&VyD&ZWGWLUPN6`i_mi`~ww8UA+v|&ymZG;LzV>YJITvfmZK+ zFn-7m^!$Z!-!X7Qrhw`{vHNG&$4`VWZ?2M*VZ!=j_s_Ovt%X7JzLFiv!uMhG)7Lvk z;6yOKe#WoA3dJT;ebE#4k66Cuow&!HST}-bY!K%wa`h+fXfH3+AITk+gZ3NeqWZ$u z>%hfN@o0aO#9M>HyMt8!o6SG7M=XRPYPi1i;xj-l7Uw61tCqe`@6GS)CC-mm(Q|I@ zEk~-q&GrxK8h>z6xl>52+Q0nG%&*mjw1?1-OR4!3*8eS6HwKT*$yEQJ)z{k!=5Y4g zc9fqZ+nwNALq6FPDEK3Gf9-5X>3nc;1G>NZ>CsWB8_<>a>mZ(gf0tHsXFqz925lk! zZ2qWQD-VY~=A!yytaWWEeEOkn2m4qn@Mo=_Eoe#+_Y*7Z1-u$ z4}2u>&+c#NkZbVy(_sFzmB2TfKl7J;2H9jUevGPk{HMZwZbteDa$Q6CzA+rt{*c-8 zw2_ljoI>pL1^v)u;$J*S750VW@&EhG7;?Pn_{T8&Kflt=VbH?usJ~4~at8J7`PBX) z8-Lde;qd(O6O#Es+<#?#kB3X~4QT!`uE>EEhFy76KXE<|U%w9K7Y6fbe!}-<_2a_g z7o4evBRcikkAQwhU5CMWRESRCm%%pM_S8d$XJf^Q?xk~Jjb-- zQ~sUrW%o~W=hnbSeJ?)ug?Rs@qw)jpe&cW||FV2opZd%hNbk4ZcUI5`cK!J8`NjQE znnJxl&*q;HO*OdWw-ntUJM*SHZ0Va!cGUjkli>%lT%h9=Tpxb&5fCJKg7&vH^VUHC z*MR1i`^S#KkHRkeu3qANl)k9q)IT~<^9QVcUYGXoUDkx6`Y}p+Kcw3Hc+&4g+uujm zf7hP&hv-mTA3Z-!0bALtXnm(-u@yRfSK_t)itERZ)*CQwV~8G zP*zvNy?r$fjsLzfH5m432^!y{CwqX)m(5gs+5FJu`EY2QgX`ynJXdgPK8@;w&#y(m ze|(I_KiF+ONJu@Z54%t1LU~pfeoT;f{1@K&53bzu_f9E7&#|HC`QLRL)WLWO z&X1Gy{@F!uHj^J?1^>wU)1adxAhZ2J)W4hD9}B;4ohGJ>h407ammfnHgJQ^IvMWtI zzqs!|4&x)c@F&)Z^Rd6j7pTefME(1zxD-ia>0f^Pwl3VU=>N;S0D4pcep331>r^)y zt?#l<|K{$$nuO-({nGnGH{`EH=O0y84}^%)ZRmW{>3P%O=yIH&)&U9dAikcI_Y(Al z_2>Qim%>4v!Mw#;aem_dd&F%^9!|6t3E!X1FDp{NaQ!EaL;d$rS0$KmXAYWQqgvG= z_)rvD-!6zVfd%U}Q}qq&PwvIr!L|bj(DO^vE=0lOagR~|arpB#=)O&f%D=3C>z#7~ z)(!8%f6Ef*$7gCCtnl#UFAo&=Z`-w!B<7)w{NA}|{>P6Dbf)+jny^Wd_VX9Y*9zk| zT-mMBs6OdU{==QSK8f=GtUg^l(FNvZtVQ?Vn{Ez*l!|TW{?WaT?ohw?G&y@xh(Ejj z+TWNC3&&m|y4QvE&DMuX-x6S%Ydz`hBhKHM^xNPdGng;$)TYn$eC2})mE86twy3`` z*j>j3e)K@~D_p-F)Mm^fvYQ0`W9JjP4mJgaL3Dm&^@-<4!o=hQRDD30`zxMwTq?a^ zq7v;dx?J84$&pHY#MHL=eENJOi989(wVhFYYE7z#gXQDU`k;49l0-7Mk-xN6oUb_- zH%oekHKBanY+4(x4pOh|r`|Vs#qi^t5(rQCUPk?){_U}j0%0I}Re#-TD zYlG^WZr^WQ_i}eMKc3cCfto3^(fqinhdy*`j-%=ucK^IeUINM7e(L@bmM?j^nNVnW z8Le*$>~}%`4~l%+zw`5K|3m)OJy@VOn6Jwc))(8~*|p|7s40%)R|X5ev-fjX_#{gv zhWy|U7KroJ^fOiR?K#fZw8#(KR3Ce^e`Io0T5s9od^sv=L08+wRR5mMkBawtL+g5+ zuiWw>P%>#NIzPI9uovtKK85p^G)3-hi-K;zFy2r%* zZ?~}TTuYKW>i_Rb?_aEbF^keKw!e1#o<96N9f$U3d$&m7z_)!UUnUcSVT8|eptSi7X5%>7d-g$ON8H9zDB1!6x*NA&glc`ew&DqrSSK$`g3r#H>`I)Mao*m^<|>+ zDwrPo2=%AFbCO_-%@@?4-|v(UmuvLU{P#X&v&3ldS3YocfoOdb`y*NMx$HaYAJ#qn z$eH)C$Nj^^_Hbk|&X3M<1F%brqxy5KK2_EXg%~$npVQBbf# zhP)kx?!SJSr3wmJv&fLH!uMtU)rv`mknM`+KdS;uaBIm#=Pw47+e1+htzR(=Upeb$ z!D9Oow0`4-(Z!BM? z3w+^HRvsBsBgBXGPu-@+!1Bfl)SqVmEPy4^di=_J;(TRF{bi4PU-{iV#ra8moFb9! zg7X(J@iV6pgY#8$M-E0U_NVlpJ^wq##0WmB(R{J{ldW~bz(;v2X=)Juezv}u{cJQG zwA_d8PnYD*259Ed{5Yk7 zyDDzRQ7dY`jOE8>>@O~OsT;b#d;h2^_IVZP1=(u?9`}V;fl1W-D`EDh z#ta`1W@dS)f2wbafuUP*zN~+rfw=*CyqUT%AI{E?T{+PNejnZWx(DLx>+`S_N!Gf0 z-qu?@e-1vJDrxxm71h7yO*PyWZWLPoOh}Rke`9}YzAPK)`)%(3F@l_@YpDFm@;5^| zUo-S{CfXmYDwzW#58!X z63VTK|Koq_gQ>4CEo|bdy5W4;<*UK_bs^~aCE4!gz%NZAdsYbg$NH~LrjDT0cOSZc z(bvfj`c|Ao`I@>k7J6z`pz}v*C(puoSv@}Mxww8+9{UZ0=eVQuu~*)tNSc)D`Q5JK zd>JXEN)qkr`3A?eqVv}`Kcq?`PBx(Y1z!G-JJ>3r<{R1l)iogsFj&f8+xzD%f1X7; zkltT6AW9imzr+@#=lN3TMY}QKP1h4#QB-HV=t)LD^UF%);}~HJ`YC^ z;(XbUX@O@AZhYu3alS5dy~)c>YQ&v#vy-rv}Ee*w$q+hj!;(rp5DK858|wr?kB48i%_@WuwX z8C%f#t8*#-Fhg>Z@RdUTWBqaa+!V0;UPDg*JO9Y;|Jtm249eUJux&WQFGY<=!NbO3w}N<{0+Pmi5IuQRP*EPu+r^I^hP zeErERSp&g89-w>IA;n{ogxP>5@Z}aeg~#Wk^DD>-qitW{C2;+~+OVx4RYE|4or7!I&@7`-yag{V$fk zTzI;ByK0}&x)!tB@dIo@uM=%iuUJhzP#mfLWYq&vjjd^|1$2X z5?Firq573kt_Pv-!ikx;;BVOeQTWnP$j@2>%GOlFX*Na62e`MI*SC+u3W8ue$& z8Y4j6XbU?3^}U@ds2`WUKlJZ@9+t1K#bL1BfRLym;(Xn^5eGiAAE5oUXM+wvhkSYd zhpaeXeN$y5#;?bseCbcflsNam`8pfBRq~_hE3XzW&Q}Nd_gs55oG;Hmt=!R%E@*zy zp4}Nf*n~^Z{|euq#Y`nNXzOVk3+x3D&^{dmicAz!LkGlVg)#t{~8c;OpS$n&Q^h}Y-! zDbJwihym38H|rnHj+B+WIyRQy<1MaVFOxoU>uZLg{>oJPzF9+_3$?$*>U%|C7icgE zCrj50--qSn(x*Z2zH}osf5`TKPOq2(ef~R+?#~_#Ukj(2@1yH$)2t#WK8MGD*vV}Y z%iehZuzlTE&LxaP>ze`Q%8;HTz5fZx-T|AEN&$Yf^3%X10qy6h}(+t?~sv6ZF(-pgC%cHqRS)+XdqKt(EefyD^WW`a7)uI+CLdD~F7y?oVR%tHU5I`1~yp z)vw8Ry&(NpEXjM_rcbp0no~X!d=_L-{l{#e=clK9j{u+AV&bPEo*#cKI0UPH%Tf7{ z<&V4b0y^gR=TBG){K+uqTO*gsNm^=L`Ad_<`8%?{nzJ_=Ms7C!`}Z^b$E4Y^kfZEE z^|x95dcU+QeEt9K_Y>#qTJ&J>9D?)Z)4^RjpOH=eQs0lh-!HZ?0Jcltzn)^#rtj@3 z|LeUd9)|uXN9W5_`d)(PgLL_Qsp5Ri>b^r#7K-<$8+z`L6fgM7k9#f7SM+M>`$$bA zss1&~*U)GcSf(+ax}TlpE3~E;>@24FVfD}d7YE6H8N}+}{`o70pQXJcq5qCz)W08j znE~&XRuh#n@%;a-|6zD^N{;vbE}kFP->3r3#r^p@7lAKU-@;7gCC6^M@@Ef-^QF;V z4*V}UQ|D({eoh_Lf~&&+iDV}BJjcXU&4%!fNGi?A89T4b5@@YKYj^!di6*1DjprQP7ahYL_Xx)}}yu5bh8pIAOR)Of(E1=*yjQP4k@kMWh$!Rl!)`uz;F z*TeMua`NqtkiXgYLl%A^uxY0bsy`P`$xH0Vx$=`Xh_4_2t-rX17e|spCE?#E!}O1h z{*sc`C;{C-Eax4T#-)ApR)QAZxRJFZx^BddWlOWWbFDx zdOjD|mqyjsVEEOXKk;vWp4E?!qvb)d+6mQ%v?Oi#W)Vo8Z;N5$uV)EUc5fg{)7$uN zN9BiMW#d3ai_R}>d~1`|!^#om1vdErB%=ZVK}cB(!M315Kvx7Ws_;G!g*m|hk5VB@!^J`l<_ z<)ZnsAY=)&i!Va+hhAMKbhiJ5_AiuoAB9!}IbPRM_&)6VU(oRl*zLgM|1G46yFPFv zb$=Gi_nB0A(C_Vp*4J^7I$-*DI<^1A^0COn42pGPiKR{(AGAM%1D23rvVroyG0gt@ zvpi4uc3JxV(m#K~@^i{O0lMD5hw}49_A=;B)8RQ2;rx2A-t&sQqBgyD2o<9w> zQPZjUOg8>2pPE7YoiXTqKxu&&B&^Cp_22SP0`zgbN1B$4>$~@=9JpC0OX&m4zwy({ z@IzgPH|Q)L|E)6>B`O9kyulLj_+KbegQ`(J)cY;0zAt=c0N^yA>VLEG&7U?5QZ6M> z_hYeq2N&8yk5zR1S^elBI}?6=IY!?8JO9Y~hq#Po5ODJ%svjE{ZiC>gkECpvc>IT2 zzJm{j=KO+N;_+YZ*vzfyj`LqxtP8ziI#E3;=qDTh$B+8LsZBBH`fp72hEVk^B3~xx zC%e8&mTiC}vwI}zrFi_m4>$&?M`d}x>EimAbK?peeX7l`86h73eTGVsneUzXA7{nm zKT|;wVo#4j^W(!YhR`c{9yR~S#{bG3D;Rb>ft1b=^pEvFJ64Pa4YM?A{*PV%1Mkg* z<&%%0_5T!&?NFwUuWviY_t524Ki=)LczpNx{NX;8j6n6RJW~x4lDw$%TQSW1&*PPy zU`*jOH2z7``oRR-7^*&J{ZH^VANcfmH@g1SPA`YMJ{QsY{F-7eXhq8M87su&A9z|x z@@|7Ougi3fXSMhJYc>sw26BMjPgmrN=a=U?&Nc364l1F3cpU*99HT!l4zwfUN9;{2y9`2g*X z^yB9lwS6CYzIcqJh1)rH1XW+N`Ohp(9TfAusQn$5k08*4faTMu`6yugqoS=jguIBR z_+aa+=lQ-ct7JEM>(cgp=>Ej1A1lD#=ptF?Al|<@e>)cz^v3hULf>|hjf0$d&j)RP zKfV8&qp1W%4;<0{%hbO{u&iz_TK}9huz^~$1Zw|^)&D+jv!JfuF%o^e?eC-W`=lKk zVR+xWsK0rfvIC}geISay;_;XKz6Sf_wfPoaJpSzhTDeIdhokW|TGauz@m`caX5+iQ zSPwLx2B7PIwRV4~-xN*hKO5iU3mlKB`bqmW+Jl#Gm*g{LY@=7!j!ioq9N; z{y5{XF*q;5`Di|7167ySqxvD4Jsu3D?^|L1*Vk<}oIRF9BG!rX^P$U5NGyAg=KqjS z*FoP)n-BUR&WD1Q40P)<0a%MIf3wcGFs=C<@j4QE1W@|M`k%s6-N7hgF1o)IaKjd6o?lNqjtTK&{XxrQKPY;$3(b#-qvk-> zcs%|?FC@ZLvpcANo__xZ1ohG8Ydf{w-$0)ae7d0;hL-f@>zsw}!>$jxDKhZacR1Bw zWAj6Cum)^R^rZUxEFXy*2Y~I`Rg^xkeAKy*frndCNWXJ!{*tbb)JMg@n1O}lW|Fu* zynDYBG`-)W`LWjKB#eud;q^|7^RvxDMPg~~#5?O>6`jvHP|^-2?{+}*L$*a1n7{=P zvsU5X&*ne5-`!#5`cO1~^ot)3VL|Ju{tC+nESdll&hH}C|N7Ice|EMCg<~=}AHJiL zz`dXh-Jfh8dkb3nYx8A9oR8i$G7ws4i^jjQlO{|U>`CoEvhkl`G7x%xTS>nCZu9?i zf1tq52|D?vkc>OR_lsflVVLy&g1R*qP<{BjV;3y@{f=~>A)X&U%I85pcNyOAj(GeR zmw$#oQGNM&i^Ta?e5E3}bYl!3Vk+^K50<>g<5l4~oyaz{{&sQ9jNe>jA#X zI3LOFMnI>QbyRgttmXD&4Sn!Fz zKx*>D^`X#7dj2l`9pNIx`KZmy1D$p<{8=K-$B!#DP}BqGLm|GsL?wOy8rICXYxCP7|SBFFgLQedj^g(xXJa zM94pE{juueCb;5QMtawa`>XJ(Qkam`kxw`*9{+vj+qyAG{CT;@#zug0C^L4xr8*!%%4^I*t}BV_ipw%_Ucq`_e` zTz_{P*i4YitWFA%y$Jt z;}mLtj^(4;el=*VKTk6K#Q9jbCkrC3y(N(;;(XLuoQ71BzvSmLaeery{sl~P&3N^P z;(Y9LZ4W!O_d6^8eI~Y(hwflQ_2*c9(00^^N9QL~ z`GMu*sL5bxy|x_XV}GY9&~X?Z|BAKAFredYa!ICbf05pw8#?t4xF69%^?zSMd)T|( zp7K8|-=i$G!BfM7+J9&LVdDW)=p8Ru0bjm`M}DsAzl`)e(C<-y6uhVn;j zd~>@Rz}Vo)s6U)~WH8L`x}3_7Y=6Z>48w5?}u{3Mp`D zQz_bicYB%-qer!pr5y$S+5MMgx_4nQr^WyMcmF86|K`xFCV`K``#Qw|zH_3& zOP>^AMX)uhA5-lO;YSe751SwQxD18egO;KB;hgm}*t=i{xqPGT@1y;Jt$ivyzkLhM z4|ZN>V2eJ^$6@yl5`M1(pVaZ1cz6jFQ1t`r|2nHmKz09G>iz3M zOni4r?{_=6Wi#p@!ptII=MX%;21@%tcH?VuvsgTSmk-?ogSDD`)EII8)hB&}ra^u9 z8Yl7io?WR3kzK5*{wu2wu2$0f>HoNqnt$&b0JA^$yMrZky1W$C2bGu8;KEPo{p^VU zKdG}8Z1;828}}fHF<3aS=T3`{%L4pANZRZLb~r0 z_a9nQ?4kGUc(U%)KmBC*$~!p@J~`ujo#?U%?4BM%^~0rbA1Ev0e2tv@9g16f^Qx=F z`N{jB2-{<=(E4(kyDp?wkEPB(v-|{IwS+g?OHqA@ikl8cqPL^{rKnA7;fBLmG`}S7 zOoM`Mw@6QWaeihro&_J5KcvY?oS&X)8j^_S(fmv=aX!qCR7z$Z(JpZ+7x>u9@L{k{ z9Y!sep#JpJW+QkwYa*3@S^b=(ZU*f>1f%{!>FOwOGg(XBAHwQS)!Rj|Cgc#h|J!}_ ze%L}@k>Sna`ZDFveTeO$$>-#Y>x;>xbonN(FXzMT!Qft;^!&!Z|2?BG-={AI zW4A*@qq^<;(fyek#RFj3;}z;JMnpb<|0*<4euj*1godHLQU9UzO#1%lo?+Dcifn#L z%IXA37GtUXAC{lWAyzQ0B?{FS?I16BcVH8hpMmNB$KMQs#?ISOe^N~1;luVbX#Y2* z_&j_pY9_5t z0G<4o#OOb9{W%)&5GL=`;I*EJ>(8OopWvp^n=dUA&riJy+JPi@7^!m<_-6TWveyI2 zV^^xaWBDmlv4(XAqEP)&+vW{P$(u;j65;P>^(R(({vf!ifa?Fr0Db;?N#q4kS8FCs z1>$^2rf5mb?%MOO7mMphSt~EO7%x}y`NqlroxhI(`u>PJC!a{Bg>)=Ay++7StbZvq z(E!I0faWK|>)jzO%%6D97rq~>FHg<-LASJ-sDG(`C%yk`Kpf?d+5W)(q!}>a&^A)G zTljvgJ`X2LV8`==WZ+c6|HLrw!<9=i;OE{O#7|2+zqaazwQd>ZklBU6KTT*#3yhwO^oir5Eq|Nql|ebnhsMNwnvmToUJN#?~j2z6|Ktb@eVO5lsFuaji9fZOyN zq|jTOufIlzV8^v8)IT|?Jc5*l4t(8has84jZURYIFTUoh5FZ)leBYqp&T#df3!2~l zIM_h^jKyev>)YNJZakCT59TWT{j5H<8?hdScom@a*Y2BzU|QCM^5vP^QF5vW&X37` zW$1Os64hVWstL1>apZb#+x{)h$Bcp=5ZCO7`eR;c3=CC?qxz3*e^zr&F!a^ihUV`X zot8oUodYDHLij#x{D1A;0tIR}NbMr=_)jS~1b?_HG=E+C@d)yAI-vX4_nvizYBLwK zK589q4jp>UK<7gr*xO3)hgnR{JGTA%X@9&*eLNh=OCql~3BR-P|FALy3_orqr`xsh zPxoJXU0)BSzw=T3>3i!U$Q*4V-F^%D!}^;eHNQcBP%mD!Pn*8b{pp1xv?akgqxkb@ z+J2||b3eURAR`3l$GS!n?EZ{I`*&N1_5_!)e(3z5m$nlulin|AdPVp?*-Za>PN(G% z7A<{W1M$BL3^QTz+Uux3Jc&CD`xUB4u9dKV$DXg-^0g9{uk66T?k?Q_!S=5YwRC}{ z3tZ6pDBqz!oY0;@ZWf9A`(df$!CF5F%`d?-6QHs%pQt`+i$Cp8UTiCZ^^Q%XxrcE6 ziH)zE;UD-V+lvnkZ;KxtU&T6YiDc0zKJRba?{s`C>)XSvQNu`7AK|~x=GRYpCU9b) zA9epN>pwa@v4x2qkyL(V=esI5J3-^5HR%3LZu~4*k+zlO>I?sU)_=GduYi+!c>L2| zWWq|{>*VY~aeYuyIszYqUJ$?b;_>fX{1{{h;_-(Ck0f=x8kJv9GWqq^o9B|hO`0Vm z0>%B^{VFX8{x*_$)Cl^@=3mPWT|vvr8P%WP75yP`c@XOF&eZzBZ7E*`g~Iw_^~LOM z0u))~qxI2i*J6mc_zUIhwP6eRoHpfi)(QNu{pp%TI+9|!QG80H@H;#IQfOZ$xz(&# zq91VUfBr?2sjr>7sY2=|OQLc3-@l)kkN9cP5uOE)MDx?hY7^N0a6DRHt%w{B_PLAD z{JhfI8Qv+bq2{Yt{b`;!8>XA%`utzSR#3ZrjTmeZ=Wk8u6Bt;g&M$2d_aEi+Tfslm zl&@)M`+oHLeP7ZQy68Eh_0iIq|{iK^_ z+xnyX3ss>TVCuEgC_j1p5y*M}oJ4dHUteV^m*AuJFET|}T)$>$>q_38l<*qeu3!59 z@84tjxhMBfay?b0Bvt;-|M&rhpXPh2Q0ibw>_3U~6FS8d`gx5f!-om=1FK)@;Ul2Y zZxNNh+4^AI&^fT~Q6`$7>t(iqiSsqGcCC2)FYJB_e-EnjNmIr1%Nr|gkc${ef`WyA zAFB_WcXWdtPn@Xv3AVnOIddRPe-wzuzrBSEbiK8j@@K&0S4l5_(Cn9p?w?=qUIp_L z_M`rMs`f_kPCZTf|8C=l&R=6@9|hGwoR9gc1cpBTNs1PU^U*NzFNEux@+$Ym*GKa? zU5VXj3GdopoS&+{m6A;pR8jp7U91KXDwb&e>!aTb?pFCy`oh*nT`cUNllmgUE&azI z(Ee}a4i`|Kxtf~)XTSf};h}IgHWST%R(rRB(bubJemffZ3^KiNzUJ-F293vdS`1=%TzAVnq zA*CER`~DfKFP`@Z#LWCjS~iRGL;PeUmfuYHBNhT5Z2l^k(Mi%!FMVQkqVPMbKO3(1 z0>@>(X#b_h8#}1?iy+O^d=(x4g1N5nKogJu+ssgiYTAPK$G7RkK;WHy==!sgY=@!< zoR5_u&!MZnI?7FrQ-Cqcno)21j{}i!PYnxxC_2^= z2!&p!(EKxS#W9#R>>25{NId?dEJ{E!wvo~gwtx3&rmV!@(S$dfEY8Q{Xao4OeGFP3 z+Kul6x5|7-RF$B=tpBL$&cS}AaH_w}`VX_6^T1^07PNo%WX2BYxBCk5JS*-$f_hZJ zy>vA`>ymhUjS}=E{Z(-Nb6)&HGTL6PB!HCv&ws@*{_9MJF64e6LGnt3zmJXoEIUIu z6E=pV$q2u*>)%yoFg!?|hUS+vYd3hcA73Bac29<<+8a@S+bS0eTEF*_te$Q8h4!~0 z=1K75XCA5_T#sCsx$`NiA8YL{L!3e*38)j+7t7DUBeD|X8$J1(TH^d1FzGBwtl;=d z+lAlR{Nu8%4|H$wM)S|n|2W8Bw~+F$*^K{qd1pQZTW=xz9NYeWy1yi8*a6$jael%& zzl6<>YW(|3aelhEzmVA2tCpDe5cmjV_}IU*O7cgCuAgr(^|Rd=U3eQloa!I3{ABDj zgvTcw(e;%tosTpgAU*v2ul@n1{+VIr4ws^0N%J$opRxLSdg~N$s@Qel$Oek0imnm3gTCtpAV;2RxpVg?q&HCnD?$4C&lRVzY(wnQVV&wSk;uxoc0f zKAd>8vm^vK-hQ#b4|_gI#m!7Q-|0>KH?*xk`hH`><#XnZ z=kmUtz3z42_gZ`Hy*F4WHH3JG<14$(eXqygphswkHXDKZ3hc#^ZzKm(8JlV9x?al%F$G2S7;n1k~Ro zcoGO-Jx}0&S^YAEd5{~p5%n(x{R+Xt@fdx6Qe3}sv+hIaS|x7zZgKu;{eGY5eNt-Z z8*oWfpSqZ+gW(cu`m#(s{>7^1@M$0(e{R}1aHxqv@xO4WFJ#zC?l-!`^9zfQrAt?X z<=agtf7BgJ1+Nn|)U~&`fAurn2_@tP${#JA<;b;EN&J6_$3Of)Pm(@v1ScOT9)B}g zZAkp;fX09Q(t%(#X9B7}KUGFT{l`Af@z8a3j9`C) z)enmfeqi-Paz6+X|4E-$!}4T2{trf{!Q6lv>SH1v|0@kU;oj-%X#BrcoPfvipXiL! z;_I`$RF2#m*_Tr^kj7uwUyNAYi+J=N!FipM{w~}f(Ac95O^FWlw-&#CtbhA;d?dVZ z$K(I8Z6suF%|!D*bX*avTiif3o{PsndgDWIH&Wuh4(0E+VfSbJWuKEen@)oIrJ#Sg4Y*z|FiZ&8hrV<6UE22Wi>E#+I3o4FRmYo{Z7J!(vP%wkvKl? z{*@z#uj+6E6r}MN;v?{DFVeo!mebfP{auI;&!IX{qK@OEbB!Uy2jlB|rrsX9eh#C@ zs(Ain`6Egt3a-q^MEymcQZbAl+(1_vO6N<2=a;t5YK7L84k&)Y%6dTfhhb>{qF;YY zxK!sOh(9}j{*~%$)$UKCVFfKZf%U7tBCCGUsKEJ69B{qFoPN`DvTf9-(2kkDd}_V+qAj{=a~ zuO;n|vhn}aFdxQLW}x}qru%xB;+8^-m!H-OdV7`ylpJ^%U z;q2pTbp87V?*g}NSJC<xb! zeV)Lmr;1$J0&)EG{{4!y8>`Z=GF==$m%`qX1r0*~!tzVvA<2Az;xPJCdOnTem+4+c zaHDb@y1ywWI~2}*^+NG8-f$8)y;+X-M_x^chos_S6d!e(8(?@wHN99Zo}YtccEehm ztEfMD-gp|^<=&(DX=2`vs3&Q2F6()Gu>JYjvAQs`w>|1lZ;f^YPs#mU*#4Y?ZXi_I z;`|z6x)9DD+(3^=8tDA{aKiq^m&KdlToR>AR*3UY>bWP9{-z?zFDlVmq`$Ham!^B_ z-+!O2&&?ZO6N6{U4bv0F@iXPpTN0}+#7|pBpGGA2f~$M1(D@UCX@lWd`ZzlGzy2-T zpEkWP6x1@ksPAH)e^~uWGMNnBs+ZHr*3$eEp0CV)909iSrK~_?DDjQEqs4Q5-)GeKla=GAnd{xZvwxuvWnF(IH?MsJ)sd@W*U@bf#o7 zyxkU!^2@Z8Ao#jC5$(T@nwkKrPm8E^ycA!;{;REC1{Cewf$~pq*dEaFXrVoSiTj_t zc?#s~Fl{bzJRg4+AJ;;9lPGm-uFGGZe^`9{n$iz~-VxOQ{NMSEfR%1EV2cz#!v1TU z8&1$XHx#XZ3d|P6slgjie`Fa|3fFybe6(|Jf_|-UX}z1ce#w+QgYSRZbB0^Q@$=B@ z3%TzmoGGMy?F6t`Q$)EO z@%X#`+5=f9uh8GG#N#_k>nt>^d`n5Z`1dc>Xiw69_2ClB#pCa8-G}Jk9L~)Q;D2Z1 zU;m*WTnWbGuQkURie81F@wNCF4A++>Qu%QH`&fT=qu&z9y|EtMzmY$c0k`~ip!K6! z&obEi^(b}m5$BJ$2cN^RTkSbp1^)gLw!gA{(Jx}(scXa4lso_Y?{&ui{#MeGysv9T zU6%3u$M)AB^)>-@IX6^a!V-tWhK8xAKY8u-~8*Fje76u2kV_C)hoZ_eonuMcee&pT_AUQdQ`F4Oq<0|@Jz%y#sdbqoL>L*@F5fhS~ppa(pRF>WjzU_-h%cJvf5a&-*u=gR|q_&<7iM{ImU~{i!eE z)u{H|b9-_A7_#&ii5c5j&_B^;^kapN%t-aNkC|42nOc({*{${1w(uhYoCp zYsp7YeX6j31tv1>Ii>O9_{xe@B$wW4akEc|uaDj+nUVFhOM{I!k1tlg=AG99qaGHh z|Ah-SkRRhoJx)paSze$I%G+ndoNw`Hf2Fi02`0!EQitu*?-%;lj9nYyczzXqe@Pra zLl*6W<29F1|7!2p46f;~1^8j}^VLUf(oi;3(BEb8p*PR~9760+{&87m2ELESp!z+- zaSSY8GfRLEVDOQ%C>jU)|?+C++SE9v;LK{lo?sv+_|Cg{2ft$6Y#7zEFWM&hspehf2RLZG}0DUobsTG z8RGc3(R&&Mw^@SfS8-SfIIoSTAOHOK-)H=bs$3TM{@sT5->&uD53fgFqVB!K`6c;B zGo;JEraBtp^8@j1I*|7pv{3!hD$^kbc0;+(pZWY^{fqO(A7s!|6#>7q>$^3{0M-_c zKfuCr*TfztR3=VwcOmxGBij-MyH${}DCj*o}e_e042i>SX_Z1Dz8EK%V4 z)Qa=V$>0q<{Ed@NG`MLhSbG$b8p^RK@}iST^9{@DI-WX1@Te}>cyf$XNyDF4)M84FKF z&qVoW@W>TVb104G&XeLxs6PrSYryGLKFZHNE4P55`C-~EO}u{UJMt||a8=+swUeG7 z7T&K84?B>(XEf3Ls(#rU{u&HH&u6D3j{ujVDJZ{a2iqUF<6eIk=MR}sC6W}RiSozQbK2l%Y)(7I+_Vw~-%UmPD;wH{jv1@+VHL25OjWR%C!N|?W_&DKc=D#P<(5$03Y|6`B;b9b0J>? z=Leq&IiL_-Np%#Z^Etxv6|0^fgxQ`KsCt|@KU67Ph65*F(AGKP`mrRcANi?m#l7!) z`ky|q`cb~Z0^T^ep!4&yE8W05FNiwbmHH=P{wF^5fl!5o)NrDd|Aqa7n3x!tb|94| z@09*7)Q5-5CGRtp=Ar)7b>vpCzj=_}q2lq+E;ADd}tt@!$cSH6eQgK+-XytpF? z-=%@}m%Jpm2VY4vL-DaGRq{UDJR7vXq~iiG{MsZz{VYR-^-c4*FnA(4pO5Vy%kIsA zq|aMX|1fsvW$-Y<;~%Q2M+WV-jr3qtw7U+Hu> zG<5+Q|AQxD;MLGn)E}&Gvlc#0$V2(ha@SU{a6X9Y$3=z1pk&jG>Zk7X53uXJJlFJE zoF782btKn^Yj86)cz$60r{P*1FgH8A9h5lKE$(znIpAz=6<70{_Xz|K5~v z$S97b`JQ}!u>Rq+TP`GT-AadOi1S19^UJVT>p9)@NW6daI75%zGPdN5EyUx$VW%Zz z4{%2FzijY$II=1bjlXV$FC69OQ@K$7?`P+;%xqV|-Fxe3hG2h5nE!9atObYtxhVgi z7+VR`A00sR|N8C2Fyi}pTGlL{|K?gB;q*d0{MmgnMI#PPq>RG)lrvEZ8g#qsgM#R?3m6Y3AY+!_xn?gpUv_;}S9 zbPh(L{$SjSRdCaF9lHPaNP8XZtIeffy`=s}=#Pf}sDwwclJ_Y-i0i}Wup_X<>pV@Q z;`lgSuS`Oh_Tnl`#PgpU))%(NnV|EnZruif$JODefBck0VBDGsg8NI@{C7`wm)tKL zfY#^lm(7Fe+gGFbxEYWKzb;gu_~;(J4YEG%r=1>(uTQl_3tYYY6vfZ(6Q5x8rM8@D zXYu;$>mz+KEyIF)utyv}O}18$80U!IZ=!#|59Iu#Q2l8BvkDgfU5oa&6eh2O-G6iF zwI@>k5#l4b`%zeXKX2M8V zp*2A;|IWr=zT*V=kl~N+FI0Dn0B<+R`DSGPJ!ZmcxSY2Z_1CfI@?glw3RFK{4yl5a zqWv_gpLBm$INw`U-2$gRJwf*;Ow&KZmna+`V^v8Z2v@_;kvuKgDO{+*+YAmr9Cfqt<2li!BgL&{-y!Tv3ap9e1|fU%lC z${%4Skw7(9qvxwSJX;OA{%g_wg8>us;qRL*D8I};SOtH~_fsVcar`{HdKKO@KcQTI z@%p5*+ZTxL)E4dUeEOpc%bfA}pVA!$Lv$T!N_W0KVg0M|=NS-O7lFpVc~mNNa>}6( zl*RSstw}vJ?>>v_$E=8JkY|g3-|xYlNQ-?>bpB=k`u=33t~r_?CLfI8WZW=x{%*xG zd(gZ(Uf?fSe2gib2vbsKP`A3c=;j)^>1sQ=EIt^I48#~8Yr$W_uln`Qhj68f7#RygU)#lX#6AfMnMO!@hJax z&mh!vFv0l zye~;X>vyxo1>n_V3yohO9{;Li+hLE=K6=PTzr&xb>AV+8#>w*OzKod*4; zXQTD&!S4m&TU$;yCW^05=O7B6i<;2>#lw>8aB2G^w7zroQ6-O>dT>wQisR?ffdOQ! z=Mb)&>KW1gPv0YhVU0bGpV@B1;hDlHbpP6?Y!Z||^A+@m*!{`GZgJ3YAkH6NjyvGs zy1ghq{_Ok)8ge*33SLO?VKNxyhlBtJ_~JTFa6W{sznlUC!B%b_TEEVFH6Q5w7=iy{ zGuq$l7sN^Kw{4>F&iwrbZ2vno=myA`Jwo@N3%{!p z$0a?u3S*uh*#1S`w1K4Mo*5TqC?5aSHpb9gV1@QK%co9;%r(AfeP{h65RB)Aqw6f| zzO;^(JBaJclhqB7DS02mb)a~DmFWF|ST|Wzf0q1EBUR1nocvPp{3=_d4|{hGqTM=( z>r=scM^O9jiuw3iE%Pb@AJ5IGe(e8N4VOmLQQIlv-#_QfO&I_BA-aE9 zxz>;rXqj=z%f;~#U2XzbZd#)F$c?sv#_Ex1ek@h;fSknXv}J)bzC!=079R{bU2%N0 zoe~c*@@vrgB>F=-jBnV8@~>v}F=*C2Lswl8kN?8qKS4%GmeZXn&L6H>oyo#w>RjUi z@%VcM8$jp1gHZk1Y;Fpr^DWWyomY*Vpq~$pk1=N!!P4-RG+fX>Z7-OQO1x48?V8F^ ze)u}}7TlQf5Y>;Wi$7swT^sK2H1Y5EHycDIRhn}0rQ-Owx6KBYT_@=Lr2QTb=y%Tt zjepqEnb399TY5y;9pVo$Rh!V%wLt9(uF$%}evYxXbstt}0McV|J zIVPFL9+!Tn7Zt2mJ4B{N;NOfOVmRX!bR}Kf%^755P=v|Cj~J57x__VTs>Z!TAn0{%SRz@X5~` z?f-a=T>^)Dtf05@`SoGq9lur#j`vDY{gJ&=17EK0ro$@5@v-pu zZAejlfcg{Dq~B2eM~0iZQXC&=F7}6~8iwfptJViwNPPgPKRNN;83Oi=5%@E9ej|3@ zEZAT_{zCXtLx4%AJ$@bmdx!5uuUo8GAJ{gfYAtv0^c1@!7U0R75H10G<`6Yhw zR49Jwh4M#2@e*kFA{y-vosvm}X$eVa{yny+g=VMSR53{$AC>-pAY`iywQSz%*AJA3pMTVNUZsG=Hj6x)R0T-8i{^ z;`k^n9ZY1EO*m6WaeS1_8UmJn=Jc{B?_b&ev+}2@pswzP^2-SSLs(pNTKJlFSX=1p3Y9Psr7Qp#5VY)sddx zXXcNOfE{eRXD7f{4D)`Aipdz*vS17?c9pK55MSR`hCrEJDBU+e${#|1Gkw4^_#U^6 znvRs>Pw4MDkKP1Bvn2P|REgtf^~bxgW9B^?yHuP%Y%Pq*zmg&4N|hEq5QO5GZeI=Lg)iE@%7Ei%>YAt9Dj=zpM<_WB<~w66xaVh8}7lW#=GeH za^1U;=eN3Yk8}C@fW?=^Cu4FW$e3%>%&$K%=ab&1n#0Vg`1%yti~%p}(dc~Ygs#!> z;pI}4pTbR&z;S#c%FkbZZGzt8H&MlQ(*0rK{MpauUC`@jE!~tO&fiyEWQd>XU)o$I zj-UBu04ncB&_Xw!zyF{3x=7}0_f19l<=pmAuu7PX^7G+7nPB&116>|2jlXdJ*Fpaj z*kzueZ!^W?8{%{yqWj$y%wMzmOO|ybz9C&Xhcxl{s`#0Zoh^g8^4;R`otsriZY(U| zzLc5$)8`oICcyv4rb2R{s(`Brg(LsF|A2kp%<7;y99V6J>i3_alKJe8qv^OF()<$g zkNjgVDC>r=@7X)iz-b8a!}d2}YZ9D%k%0DR_V|@TyyX5ROy6EhkL=!>sR*PDMnoQvsL0-d1#d^C*D# zPg{Y1ywC7Y+R8a#EH@kF7xV3z&~5bwnw%w$zX_*KK~>umRB5v~{vNe^0LRzep+RNh z{C)SQ3HcE?nA5o~j;~u~7LYK*481?Wyn`!f?Qx+_v&8YS{F*mtpY){aX;S?W){mzS zFNZU0m!S2-x8BKMP>?{Q#2YEXVL>Dz`xUiwWv zu88x?yt&;;_l;dRy`AFtIPk5IwC$MBnXfnf&mRl(Z=pvKNt%_<(S+gu@FByTpBSM< zpxr22L4SkAhe@6*aGLn~+OC)jS(US>b%b<%g!&)%cR9GuS}gF_Z2oo8-U!Cp8>sR& z>Ax59+jjjj*pgX{)*tROPlK;tBZ|M5PaZ&o>>b)Fcz;qwz)vSqOiB1NBhL4QIQ~Yr zT0nV`DO$f44<(Q@&PH&*sWuUwFBp{M1NOr_>C~;__{*7<3{HJ<{&5+*2l5qaX!s&= zeNsWlIGqZ>i{`FbjOC-EP?+4J{?n~qxzqJIT_qe#nUBkr1%l?&$RO!Azp7i>JMu4>fpq!ozzNje~EDZX}R?o zkpF%R?GK%}+J-b6{i0nCi}RC9pgOsEtTR`BLmXdo>x#&&d%4_LU2%MA{4OGG^zt~9 zjTWN()cz-d3D>Lz_ZO%#`L)N%4L(kHLeJN>f3^}%Ml7NZ|GmG?_J{gU+YCw{ifGRs z;{MQod@I0{TLOHr{;9xHmefc8q!y>d*T;388EL&Zh_ibj&M((pt-$=G3GGrV)h}WF zu*`WROqR74yr0N^|H`uIuw%~@6klF*!(n4YFb$e2o`1cDtO2h89AEp#X2HU9>8SqO zIMqRl%ubY_y1h69_Y)-dcO&(O`AK!sFupS<-z<(F=Uzj|p&5g?!e8R+*X4Z?iL=e+ zVh)*z>fZ@cOx~=?}nke7ZQdG^ht)vpB+iQ;5KRs&FA>HsF8y~^xEjOurZ=Rpo{ClO_gS1>z zL-(&jjt?P<%7eHJhqM3bhw%Q4qb|iHcwY|JkS>m&ODV-9{7Vj(US=YSpLI9K!N@g^ zsQv{u#Xx`zj-SVx<*@f;A?hFfX6^-(-#bwM82(e1eAWFy3tx%zkFW1g&}cHI%g>AB zBRJC@?(`lm;8zwOB|3hvuXwTmAOFw%OYl7CzdI1cM|Zsx@GO_SKW-$AzYrfk`(}gc zr8Knv+$_0&>68bKkJH&b$bsQcm6{PiCAkZh)9|tT>fhXp1Xny5XmBRp^ zLi+Wi)E^1^8;?!)!Ht?7sQ&LVdJKcE-k^=L;`ya9Nsjmo{f_#}_>LvS;czwwZwHF% zxBs9LGVx|M*R_maU$%bTqdp8|ryA3VihTcs?awxDu?M5J!)TjS{(LHn&*9n;Fjzeh ztzWZBvf;+!G_=0BdH5`RJ7(2XY=m z#QA6TEfW}aSD)TF#^(pSe`ZLBfzQ{$)L@kO`gD+-Pnoabfc8h`xvqlcX7kbgb>!)$cBVhV(e{_HA&)aOc^eGkPm&=V?V17vf9pfhM|B9cVh434ccG48@Z?ynv#t|L8Vt2novm3IH@pUFTEL4ERJ ziwV@$>(N8!{?l)!zhAC49O4`YqxqHV?haOSN1^^_(g1((JT{T)eB%H6EdM{cy$Wn< zqELUd)MG6q&5NZ0BYAwY_vf}~?uQq7+fjdXwtriq_~a{taoy~;!WcjCXNhI_w@<;i{ zFFps-vQtt2<2k4ToMj8>fPv!pi^@6&_W~(epKbZ|1QO0(qk5mk{bQ1rC26)D$OW9| z@x}J%mw&1wi(I#H(K$T6?lbt(4>Ea`kdGhBPe(@#hvPv;Xn#(3$po11JBr%v zm--K3|2A~IKLqcafYvWPv{r-jsYro7vh|y1(OPKzv>Me%jotg9L1jCtf2N6TNtEeV zs;4E6uLW+si1oHkXnniqehK+-aU&Obfyb8&gRiw+Hjz$kvN)M@dZPH+IA|~Vv96NK z%kBAJehcr1mvh=n7H_HK_Qvt?DPiLCEyw{5gj>;WCwP5i`SY)76fBYPNB8Gmdanlc z`w;?tVAr?(l^p2MMRL9!>Hn4;tpMGvlKUO}#PQqO<~)?IuSe&P)Qg^iy8Ja7|5O~m zKT9pin8pFzru*XfeK6G&%op{ebN_q)g2ku)li~1I)(G{#ZjlqfeXu>se+F6saBJ`c zRDUl0Tnq2k;rQ#~egGV|R?)vk((@C-{!2#Vd62Yj=}J#=ec5rTEqQA61@-sW5A`DE z2Axp|lc>Q7VdBZ3dZsx2*^}S19 z$@zNSd{p22cs&EZ%^Q*WSn&SAdpJ4{|OLeJf`hW3Z{KuGfPB5>Ze}hM96I==={o? zVe=tuf*;x+)$J7vM`zDN`^Qr+=YsW=b+q`AbbW>Whke;w;c-bGijRf2pMhO{3#zZ* zisecA!%t{`re`lJqG;ToyQLzIpVCrm_`S^#?H@m15D3%SyVH9&`SoS}m&3_*pnq%? zT3=fa&4ZT5Ytiq27kChwwrrzA#)}+0AfMe;IEP2#{>!^^Khe0q zmAm$x*Duz;9*P|TzG=GDBY}?(%ikLUo#2z2rGQ^p{LFQp1ap=UlwYEHFMt=fd{O<2 z*bobko`j?RwR^itc&&%yEg0suVqx{p&Iu+#Rt)jjj{Q9%} z(>W{;(#Nbt_5aPKgAm(w8_gXdjvu#a7a(#fj-Q*ln&i$8Wx;$GyZ@~*(UQzqtH(VL zmEud-zdMv^2CwRL(EFq7COgBT`;zzB|9d}|)u+%wli{Z!q1lDv`cxFV06yHCj`C0N zYYBdO;`rH|QVH4hximCV+#gLIdk9vntwh&vM~4@X>v0A3N3TNLk$uZQ(u-5Y@wMZb z4U9T65cNNCSA(EW%QzGtkuw)U?^%-f%aHjl4Vnt}+NRO$(A^1q|AjL16Laz=!_kR=_Wy27jRT!kVf3{UpI;@+{z2HM zN;qMfi~8r-cZZ;lMkNiJC!SyZPrQKobC*&7(zvZ1F--q}>XV11Ehs4sMC-S?*Mnh6 zu;l%QNdE6<^+)DmDkR0lp!&1SHy=_~rO=)irT<>2zsb=TVYK04)c?Bv&?K?C%ACV6 z@%a0kv>@J=x?HFw?{C@q_T7yG^|;;?!T2t-rrh8<_i1^F!=a5c^iaR<)HpVcGY39tJq36t{2D0@f9!O zkI`jXZpiBsyMNNuS%KJGeNWdBasIe4-xjXg3_#}}KB~FEV}~Jv`jh2X?;jHUOm##1 zM+)AH;Cq%gdOqg%q%`Q+GY0J+kz4to(=i40H*fD=goROuP=3iC_6i=CUZRPU`1N7+ z+b>j$*w;wjueKM*U%H+JfodJ@NHV|w!s1Wk=|QsL|AW6@C5MP?T?O~eM&YQ~e4KB@ z5ExV42R(n)m^cN3pN>HNk9@Cq$^FuEs7GIE{t4%A<1TE29er?oP3d|BT-3Kxqf&8v zIj&M5TDI?Lw@7jPRCteo&Z+}Y{n^=LG+62l5#(11!>?+yXF}j|S9JemhwoxIr{|68 zlkDL%I5&SK>Tlde7eLD9HB|STbbW;UG`IW`w7frv)>jsi_kWg7@5q(KisNJVQgf1P ztj%@0!@rNh;^UF>ezGy84CSXN8FQ!~(noMVfDFhA`j-dvJ>Z1*2z383-8&vG$;_d# zpQZJKF#g5`RdDKaHa&M&+@A!_KLU3bSJ2-v;_(mL^$H&DyNK@38a`7X4?^Bis}6o&{fEp;`$>T-zCM~CM?mDd{%HNJ{%ABzqh^BnM_}-kH((az{1}V! z)0W4JA=S$Z?eFIGPnXQUtw8Jd@ZAM4!Vt&Tksp`f?cjqbKlO2b4MrXD^?ef9oBX_^ zgyPSsdF9g6hvLD8F1ZZBL%1zoj38#PQ?)r<9B^N#pJm^7x@lf3#zc z9rV)gPmk#H{*B#VypTQy9*;K@oPS{P(f0N%IO{nU^~b>nmw*yCO`@Mt{t(Vbj7&?1 z2QQY>iL0c)3;pp*heBBYAejzxlZ z`6&O!H`+mOYXfvXt6FU~jPxCY_J>vDmx8V7G;}_8e``8?{Tz+*$HvG)IBcGb`kNw? zD-fr40QJukm%V|yt<5Mt(uejT$G&tx@$tBu8L79|;I5fT`Co{S&lVPtF-J>qev!q; z=RRZMe1$2RUw-wTu-nZB^)IeD2{55!2;CUO=MRgY%P#Aot7SBrU+vCp2la7TDF1ws z+<%qdZVO%ii2uGA5ccOwTiTQKN3ZElS8@KCn%sxnjOxGzgo)>utIlR}I5w3FY2@+8 z_P=gaZzf8AQc?VQ`jnH)nQ5HNy&j_bM>$yl>%Zv>_$`LHpR@1Tv0!dxN;jHG`A;~X zTstKMp6idH0|fJd!v6G{G0Q-Hq2zt7WPbhG^Mlh~6+)Y!mtKw)F17=n*deqW>an` z|9vdJ#%k?=BZoKAWpUE~zi_@rXHmVRKV2@+FBU)Joh9$fSieU7PlqRc$oV&lobG@3 zm$3bf(8*Qg+>;FMM6XSv{>Z=m9x}=g=P$#N1db-?)Acj>_?IyFkkxaA&GSsq{PaE$ z0!Jo}rsewl`mpu?m561q%*zw?N2X=#;gQ)gl;7mm6hTgO60M&qu7B@$w19%ie!Bd= zRG)P3wi$MQT%l6V@j57?!hI`m;U#K__;jN61K)^3j7a?AFZ^h;N3JF-JfWg zlL)`dX3@)A`SoG(Gw{ZG_@T2D?T_rgvjb{FH`06W#PN0QXFXKbZ5H4Q7=AKXtVotx zzC!!UV`gfT857f$V`Dh0;d1dvqv>7I-ZH@7m?hrcA}5u{v4$LbMUhwnYHF6TAzn&Y$40* z*P-z(J6=WXQa5laPfJAkXKe|AlWp__{)mnLSVuS5KF=7{pT1S0u>P_$8vmkK(J;3k z9{<>t8z5uv66#VVjgQb@$96A3-=Wk{;9B|4+{dZ@34s36iQLpaO`-O!5=%h;rvZ>((iZ6wB zI;8u8_GtgMO23GV?wf$(uf9_yarQ{#y80CV!yjAU)pi>RMh^W1{c9N_JU^j1dk&l% z>x}AG|AggmIb;gTFQyxdA)zDAFIJNKsUj|9pzEhN`#M}6xR1)&@c3cx$7p)<9z5rt zMe#Mu!jzm*?9Ta?9jO0be~{&$5DP0fyQCNDf8O16g9nEOqxqNY?F9pV4n_IttX2{n zxe+AjAF}%PqE7~x$t_0re_pTT;G=OF{eGGE*Q|b>D(ygSzkZJ5Cuyw?8Plab>aXh- z77?$qcoaW};w#DB7pYuLAderm{_A5h66!*A1^0icGWcow=>~JJ8=?Ip#Yc0Xlcy8P zUw=L=hn9(xQGZmYTmrAF5>WqhYwk{XKP`hEIVXp5;DoY$+_MsnOb7K=# zNa25H`D@-m6XJEaD|gzN_lGRLmb4uT^UQh)_z9T)Sec%3*4(VT`fcC#mPAVdE4#eU3m|02QeqP5l=MJ5ARGVd{zD-;t*4;AXX9Ufd>p8S8KM4e zKqnuVZaS1cy~OvA*z;ADpOS$12BP(Sp9hlnsSOvR>oeujPSDx80rf|1t~5X^DWwL2 z`$vWPWud1;94(%q{`u~tzND8mj<3s_CL}PoGuLP(zJA#|ipW+s9Dgxd#U!RGj*I-2 z`%m9ke)`;4N@nj#}F-7pyK)>GiW+3&MkY!55j_7&`3viaN3c|4dk4MOpoV(SC$!>rK# zUDqMWFexAa*d&&Kjl_667685)7kN1JF21~TRsChmN z61^Qzf7n?)2C6(KqWxPxvrI@dTY&Z-72G$0@-Q6#wrg&{0m=Px&C25ZZN2Cd#GE)y z4VuOE`{{5KVpgZdeXi!;-(mUtN}@efwiB)|o8NY;e84*%U!S>;!{Eo=QE2`bPKtqV z+7r?9{i~9b;q*FxG(RRa)PV27^{Bs@`t%s+TI2a~<&_eN&U=E+KZQ@!CD(k~adPMR z{D@)hSJ@R_LJ~A_epcF0N{nyEbKgk*KmKL&r}bnhaciHzf!2(}ygwJdPugs-nQZN! z$R)oN&!2C)rZ74|jjo(6&fj|*hryKTc>XLhaEA-6hN!@e;X`5!|eX2sp2>B{CIuOm~_il<*YLIh}TbXqhM^Swm|>b{)O+EaA-4O6n$#P ze;?cboFKCXk_Y`)4m zisEQXh4gn}e=D_LEo?SekJg{LGmgW7vJzBZ4qJ63U#cIY{#t&wE}3{so(ni8oV zZXzlAaon`{Jkk8{ODrWvRB?Uj`LmSBhsSfUXo_h5RGca&h5Hh@`+Z)E`k!Z<2{Z(# z(hO(5K4$$-8~Nezvql}QU)El5hpAzPsD3;SoDS79El~a7X2ihfo9?Lpsg>YEcE}90 zem*R@pX}La9RKz$wNUmmo%R_fy+1&>|M2!iE!?(SPwjlfe|I%*grLhMRD($KN9cdm zt!_er$X`m=U# zHL1}~k-u+08zdY&>yk_(xxt8)=>uYiTGx=>yhQCwcvR8}a z|MqPMxYURA0(ZZ3Ow8NNU_wif^Gl#GELFzd5mVT&DDQp*{rG zG=icTp8xr;Zi2E-EqXu8?$aHKmf9n9et1PtKXUP1TS5K7`m5-##^js13U}iBE>V8S zQ#BzIvsJjCllb*3Vdl51XJwOd@(Z|`S$zIbrvA+`%^~}p7jl8z#(()0V<$Yn*1V{c z_|J|-`#uSd6UlJhGPep?{U zZz{^lWb*1(v_I0meKt|s7sYi^6^~EMq-=7*bUt_gd=hvUu zThO|(2GvjV5Bg{yS-3+{azh4g}s?7)c%>cJ`C}h2ph`>2+lXK_>EKWgC(&;Q2gpDrhxnR z=>mMR{x_ji3_p{kdS0;LUAENkt zb~u}~b&BE!JM!yO!r<$dW)88tAH^vi;@6kum&L1hk|{ZBQU35#vxbMKd(E?K#vs{@*JmveptUn1lF%fRP?vMKK zf;2y{yJCjoZ|(I}aB|EzwExg!bqXAtIvuUgjOOiz0|sfRf3~}F0xG5z(F1?P`*ZW_ zl*zJ>4^V$`>|-{O8y?ARc2oSPf9(A?y`6H1+0jUDY`Qr9OpoV~q_`;VdagKr@8(*A z{FrWn_nlaOcWj{}C|76+-rr>VKlaNaA#e|%_#@A=K&kgUsyjl8FQNYkd|w7_ELWrT z>1gxYa8zR_br>$qZ{hsK6^rlC_Ie}g-)0o(k+_R;+%aWw{xoVfCcAGbafeK6|E(`& z{KKH*rr`CgBb|Cu9Di}@li;Fmf3$xhd%+K`y*5St?;n-b(8=2k)fbC1DR6JD5Bjw#ioYd(n_($kh3a$11GnL3L^X=PK??fhQh*#Mrz?)H?@tDk7|#w|q{mJ^ ze~EB@3}2>nqJayW!-ub*TQ<1b+wT)5mF5BvLCYP@rZZLfLU1sNV+tbS@N z&LzoLBe;hJJib`{&4{;wbjPl!zkb-{1pRMn3eLwb0pb3hvchDbFZ5CV`r6eWUR^gq^|N}{YB=_2 zELwjAOj--qHhH1`PJ7`V=pwma;jOHA{c*SDI~;#`j5fK5g3m{AQyz%pE9ATl98Bnf`m^IM&Y)wCEOC5Uw=0L1x)`)R&viNl)3ORsd?|5v;ECoAl)tuB=#y4QS*$PC;`nKb{Q<2bj!~r`as1dmRw3bmcTs+_Ps||!^X5w4{}abghvRv~@98}5 z)v5?+9Mr<|^TfXS@bjcC zioYGsInZg{98@3gWt78&fEXI|P>N4sf2f1wDdK|LG^oZ@mr=0S6@|$~p1)WBF~{=qaFhNe``0I|au=ON8Y8 zD?}fETCIaTmub|lp4U&-f9+gT2ii$%se8CM{>*Rx0B`>Wnmkw>f1WcskzP0Np!<*g zCH&R5+Z=&^im_7{%xA3Ykw?Y^hjB%v;`(`eUI7^<8_B7x%KFEDtUsHPYzzB+g!qeL z=CdxUy1=3zy#)P}5=KA6#s|R5JY)2H-*k@!5Uy{F>Z{I;97w(sN|iTA@g=MeF3X$- z*(v!n@s3mR-yGNw^pCnR>%n6CuRF5<713Ta*P63_+p1Bz8bokgI{0= zL4TaZS7-kzVE(!vI{y(-8VlEpMx*>DXR{7oDosWGSNNN9_))eJt7acpsMKzvG1ga8>fYIre_k5~uSFMaADy+1@%ke?sSO~_`Vz!}dF z=PxT;bErP2DClpn_|i3Yfdb`Tg8Dm#$v-b252()QM-P?q{Kxj+4!wwlJ9k`A{LR0- z4jQUFQGVOvzXg_FTR~rbmad+1}cLNe|{7`K0xIKC=tMu0<+ zs-VBY;!EReAnZ74gw8)}9b5>n9t}tLC$_7l!sn6i z%j^@GKqYML>L(Uh0mKen33A9NP*qlTUdv0W$6bukpz z-_cd(uzq2CsyLJHkFfYO^dAk)W<3S|gyl!mS`TRa(ig2iR5Rk>!wP2QVe=-cTjJXK&KhgZ%oIfRG=% zcg-geBSHlH2q5%_29f#XY*PrAUM!B^i6e_hyLRE+i9I}i+5OK0YwaL9SQX_*g%^Pk zwQUf3{$r-`B1r8#9G(Artda){ht5LlU!zjV`!ZY()yo&>#|hW&Lob_3^!)mwVftkL zp&zs=kzYR+pCJQGNS8BhIsYo2AKCiiYlRV9Oq8V+KY0HiV<&*Gj9s_|1Q@m#=r@bc zi~B}HzqLJ3{g`Fz31esXMg61h!8jPb)CujcbcPC8x_cSgKUXZ>2NOOdqxu{a_8X2x z9i=m0h|j-ecTgjrx7-k%uVL{w^Kc%C_MOE!Z56MNb2sLbA7!%z_+;ysBPy_gIzmwp6Ez6%@8iSzNc@SEEJnXg@rf(jGo=?BMD-~91PC?J#&WXx{ zDzBNSeqZ`@298+fp#14J{{fg^-iq$;+78es$Nzq#q5r-A!{XCe$%KTo$ZIt55f61*1yDD@PvSiI;g&X91#z-YEG2MNd2F1J}35W z1)S=*4CTLFCi}r6CYhF<7U#cvn}5T~vLn=Ki#Yxqx~dU}-0On=%zcLcG?nv7(1e*N zzI>AN$)ygn(D{P!@s?2XRDpg@l=^33e>8h8fUQX<0soaS_3nhob$bQ6RzB zRR?tcYyYUN;6HFF>JNRE?1!~aCGRUE`Z~kw50w2njLyG5oS;UE3a`;6_xbf<@nt4g zK)$EV*ssdQj&ag9_ON!^N+vS{)%;7IWc&!K!8sfMxTxHEaBrg1wsFm)eq;F z0B3ipp!}C`W-6G^*P)F^`S`H)pMP>N{N6MWoj;YIodzq{Pofq7%}28RElxEbHY^H4 z@#%Y|33S?Jqx?7P#6#$Ptb*?TBaTl4JAI-v;R{v1!p{$|_?*4LlteC;_e_1h0Ab#{v`hGLdpX_|LF&7WxM>?SX zaA@FGxNv$gx_|iS^?vB;pF}hEiSwUJ%O7|+{4h=A#QAT`N;UE{|El2qU>2VpBMZok zW5Jy5L~(qEHEtp%nPJ?dJ-oiM`0O}*3+dJy$LA|*2^tCQ=sE={zJ&a^^z&3uD$z#g zFZ9OFgt|ckQGLEtn+72n6H$LX+%F&22M1EEiBkO$_6JSwH-TgCEP6~{oF9)Hwn9>y z3iSSu>*4z3Q2)==HB%gaTO zvS5GmKBFJa7so=9Rd4{urmzsFjk_4ScA@o;R~D73$mX;cY^ofgwX5ApisUiM!Y zTW|=iKMby^k<4ltFtBDnIf+5OEVHce%?H0zg=zq>=Y;X!=nNCy)MoUhXQ>-pZ0U-=uV)#u4BD7kp!{em zw+(Jf-fzVEhwcv^!Aj+F`dU*QKe3x-h%z~V>i4tRVPtrVA$N5v|9&F-ewppn!SH?a zPt?CG8#NTtrng1?UtX&h?CjAS-CqyTn+^3|255ckP?iA8>j`>)&i#++U~D%Y#pi+K zgV1wC0@_~~UV9E^Hf5mo^P6*>iDUQ6DF1m>8ITjl-qD@r;{0b%LDbpb3mc0n!SPurF<52wm?tchUPsh{8 zYSR0Sgy%CWXPt+W<10ui5E9y9^~`$S3hesq-*{_`CH^-4%JH~S@j<- ze|L2pK+>TPy8r%QoHsCu8YrKp!7*SJ2B^Oo6rKu?*Udun@1GXuVZ3}aT3@>vSqsil zY3P2pJAr+O%i7ztPlc$y7S5^PF1&0=MxXdhtIu}7&%>UdxUoEkY%yo|XSw{PpFdA- zE{JCO4*J2%-vk%o{+20ntob@Fe@2#pAnc)|^@)s^n?d8*7_@&dW7`3EG;AK~4^?Lr zg1h}HH2>B$eFH;Pj-dNH?!}9ftO=*-Fe{P&;oh$~y=DTL`>Q9jTBo}{!k#bxabYw} zHvf+1cmHiQhecJw{+7W%|IN|A55o7!of>))_*dJVxZ4H8+5)- z?r|!N&6|npkrQe>$?pK?EWj4&lJf@GIdcjv$KVt&(p8%pyIwP z>MvC#gW%1kA?SR`4D(Q^{$`BU*Zb8TfSbB=QGHBEe*;@*W})%9CSRP)g;QvMuy+HH zlKavO^St}_Ve|K(Wil8V;JB+z-{Lo*0664IjHBYG|-y=AH%` zH>RWYuMsN`LZ7MLsJ?m5tAlvyRP_Ga%^S^7+V?OWV#%Lh&r}^n?)m*knbZ7yuD@$X zj*O9Enj5?G8#bRhZ{0|bUVWL#jllxZ{q;Vq0g`=Pqe1$^XMswHh+i>a{aI}BOGmiz zQJJ;>ft$b8mdu6876Z`wcH50Du&>pKny~fNJ{-r-rBj4+4>GWs({CfTn^4lNhch;i< zvV3(AGpBCPUp^^EUmMp{l8q3_oVDZE*O2WN5F;hds&8=pcUIR#m@gs2y8pw~*E_XA zFi#ohx9VIPWT{U_^>yZ(gYa{w7wxR;j$iEhqDyogMBAmH`Ja@03uI2qMEk2@siVk( z=uh;;TYi39YA2HA;xbHXo``=jPJc_^%!3$rsxeIqR`K#{qhkck=l>I!8T0dd(#;9h z+2Q8x5!~9n9Od)*XCa^U5j5^HKcB&eCCE&Zlj!|2 zx2bAm$-$ef_z#@?WoJ+>X#!4vixdBMXcdrgUlucaTts|^bNGy3bd-!c9mtdyHUH)J zIVXQ^C6+L^N(`+}?Dw1mA2&#|_*CZ9CxyEepmlzK)Sp+VFN00>I&_?j$X{^xs~&Al zgTg`6Q2k{L4nf{NPjtTi$k9636_$+pgPrj$U|o0!&3}&n8b#8wKT<}a`~72fe(1Dt zGTAjrhS8qhtuJi-9c}4JY_F*?ZJSo}@>@L42(;}#3EFRn_OEjFS7C({42%%&N7^Cc zo2$Ql6T@KVu+gYLxUC)sEt!^R{%ta`7%KKHL-}1BeE}{6MbPU?-TfQ3zTUbiK?Zo8 zK=sw_t{S;A_$EtVx%^(Bxn#5}r+>!bcjNwivb8aQx%4^XFP~g~>y?fYllzMq2^A5) z-1+;|>_Va^7Q{qc*Zlkax%&%#ds)IOF)=j%6ib~1+Jc^_e`r^m2anR#(fP>_+RNbK zTWxgzy}s`bnCWXzRo;sFL)`h7iF*z~U|W17V`65 ztl$jO|0tpU_|>g2@O2m7Z$S1JmW9TFUq4G!pJR>`3(x;jla%gnTlgb0JfhE#ezE z`mBFBpL{v#&xH3qV=3})?ERb?%0*<;us{Yn`1xLX$P#pJ{tqxru}=?-wspGrd|M0|4jRckr~vm4z}ei?fK^iqtV)`|T3vP`-jMx`gA z{(0`p(d5Ig_tbYOKfhi%(@5@CS;j<0bU%vA@4anvN#9p}nYL3Kc==`MBnVRMNgdin z{Br$Q))8k&id16N54id~!7d!U%7pv(k^O+XFU7%XVuA9TbiEk-<_6K!E&TpBLsI|? zO}5fK5BUAX?6_7SGY_Km<-t=W$(U26==~^xX%hL92+V|Gi~oL~Oiq8}+L$addxICs zf6T>T#O-Uv)J zKcMmR$~{YPaP1VZ_NQ>_7h_;P99Z2C^(TiqmO*~VV6;A4->?I|Cr?4^*JDX0toi0f zKmQb+5AOcdMKkJQ&zD5>{#C()R=BbM0IJ`Y7xyK%rd_87cSQM%7{?#pG&3T@ZoH$~ zZv5v%?$k`8n<>ZGXLS2>wtwlZIvH#|q-erFf5M#~dwRkd?(bAY{fWI-I4r+30<8~5 zyo&=9S92QFB8q?9{UD|NNU-LB7lLf!>J}~{)X+}5)RZuEhM7;;ZLp+nJ4#-lI{Hb zcvd(N1tWRpb;HfS=aZ|i*|w8mLtYOmnJm&z%9%fWs_p_|KNL`YD!wd-T85q8+0}7N9Q*O{gxyn!;ho;XMQd@LT1gw z`LdA8B?lUOn2d4!e1&BkC5CSoFrVg$^pWdtyG+UnNUvgkCyn6MN0)MAP}O=T@c8#W z1~KMZ>z?m=eK_TPVhQ0iIu+r=Y25hL_yCl zoQ~YYAO97<*2BO<+tK=i+Q5F~WK|8zpK;IkOeJG7MDZ;RJIv4TMwuxPGpz@!e$C}G zdf*C}syzs;U$;LEhc70ExV}|pLRbA9l)w6`B`{rYF{*E8%G%(W*?zP?(y8Br9Lzn2 z)(?6+yO50q3XH#IJ@5G(9GF8s@AqOfZ;I~Uas4Nx=8~5>J}iCY_Lm;}6%gkq^O@RC zk-z2gIp2H?EO2>?>Yw^yD^Se&A?Ute$@Qn7PP)MT)e2~SVCe4)%OtDoTM#kh{anr{%63q8;JMys6~p(>WoJ7^&iX zjvjTCtcjn`ln068Gndb%HDloYh<3r1UZVO6S0Aq%&xVv{d9?n$tHl@MOH|SPX@Vdg z3~rA_`Ky;thep+jXnl6OB?FtYw@{x_e*Uyf?}FyR1a!aSfG7RPK7*_Dusgs1xlWDA zRN?z&m_FvOvWBS!KhXT~;MXZI$BxY>S3d_z1;fEpny7wW-ntcv8i%3z(cZ0xL0Nk? z>YsZB9D@j{0Cc_~<99o(m)VED&l7aB2a&NXp{SuYYMdV-24hzoGsl3#P*FT@tMN99JJ7Ck2CdUrn@r;rB_%pYJfb z=6-kn!R}8P(Zg_9&jr=TNs)J9L~A^{A84c1Tj*=F7uCm;GE(H1e=)TW=jX50+LbiC zk!N)M@AB&7UO5w}f7`}!Qq_!AqpM~z~NLM`mm$B{?2}XsB2LI z6b6~m52Ho-1vfuiC49du*T5f*57px@f?WA#S}Nb&pJeABpIp?5hs|Z$e<;5`ZCN^o zEO^|E>Qk0O9?5;@f%=nI*7+nt$BS7#ke|P%E5+obqaWkoME>M-o?>5R@lw8Y+p9)04` z`xS=I--2G=9#sGQD_lvlgFF)!&d=Ah!6rZ#Hw${j^Xpr~#yMcyPmWdp;__uKFWk=< zFckG4IvWyTuaha-pGci>9OUd5qVqFGnHOPM;U>yx^7D1WQ;Jv#il|`$|M^O+P$%n> zs%h0ie*SFF<&sHNZcOoQk^kVbfGXbPkzM}kzOVGFL&VrXSozVE} z-+mYJ*2kgzJsa~5Y}$nTGm!a)uIe#lbJH8DUBsWC1&?$ik1OSv$~1mH)p`o|!+DFd z^q=cLF4xTgfvYUbzj67TIwb=7M|UA#nPL;3mCADKtgd$=)+oA~+E&CVz4uiTl$<|bY~&$JZ~ z?QQJ(1UJ9iTw6kdug+)OWBL0FD~_2$dR?>Nh?PkHxc<2+a{{c>`66KL7v|I#2KQVD zrY617`MQ<|E5W#a0Lrge|6TB7JD~N~wz4c}neT}5`(yq+sC^QP))#Ihyn~fG8EE`= zQ#T>r&tIebCdIjtg<5jVfjEACqaExa_Lvx2fA})U6`Bvpp#Cv7J_1JE)<^jbP}&Y_ zkBvd|j|{O=Fmm^!1+4dZ+4EuPRaMZVbpxGL!q2bAb19;3UP!N>;@8(NzWvFp=T+1& zj-TJqihN>J;)cd=kBJ4OrC)rX z*MYXCu=2rcR(*o&pTeI_fRwiX1Vds(`60JHQQ@@^{8p-<^G`EY?}Ff58#KRL`Sc!? zJIA8?g>GBEhxE+dbi-oNd<^&fZH-V9@~rU{oyYL&=k=cMWY#uW=2td9f3phhp=|)0 zzi>`{VbTd#s2?oDitoVjj~265!5TIEe6D;M0Y``EqxISFo=4!?90&A#K7dkquj-5H zYoKONVzKTh%3s|5{$#yy|L(v>e*S)Z%_kQVU0M8bN?o?-7{L&Yw1{@8eSPa;StpmF>7^|SGJf1;vtk-`?_a*T{1(49g-gs!R39bZ+rYRH zpV0b{yu3e*(@;kHS6An(hJwfH=>4m0soTL;#u$xX@`}5m@S`<4KeIvje%=+|_0+Ji zTR++PXJ~T+{23I3=I=>rrsU^=CY0a(PukB*bB{2Sl6^RaWxK0xWHT{L}N_rIULpDFZIPh!`ckG@}W z(4&BKTFgfI3YcC@w(5H@;XU^J(?|CEWvN2{xK!4QDI4GX_wQW(dfqJ|mdaj?*o?8~ z_~u*osGKCb_xLhaVf^}eS<4LeWHhnrx7_$G?(GJj?)GH)f37}ESnm(xm-IsUtp2Q)QLhr-KoNeg)j_*7NkayM$ zJ#m)*{7+wHO03gfp#F1SB7nk@kAm*~_?aC4J)&Y7^g8{UrLSB*SMOR4$N%(0{r94s zks$M07v;Bq!x5<5I0LPpO<7$A+vm{U86&h4%rw|ChhP42}oBK>3!BcZ1G;J<<4Qt`Y!!pDCgF zRiZ{B%-lR0y+5+jc{kjDW665|hugoM^{g5+hODIn_jLb0Y`)!&-G`$;qUoUb-Subo z{&c(Z14wi@rPgiyd>^VYC1$&xQ|1)nZ{Go&ANm31yCY~iBg$X7^T#brBy3aFMenDl>1G47c{<8>@S!ru=kBl-DXe!2Tm4DS{be;GF>r0(@U{bs+{krKC6T55R4k3|JsJ`lWCBpUMQ7B)>KkbIm8-)9t|J6UaeATyCgK=sI zJH{DyIA2-629Vkk0m|15BQr9i>KV0p!Oz$I#u8HH=+69H&L7{-3E$UC z9Uwfv-vfB#*Oibm()YYKQxrG&pMI#ZKA@T%fpGcvD8IWKr-N+iPk}*n_xES}-xYxY zuth})%|EyMg~0t)ebM=2-KE(uBXJtauafKuxM=3hx;e)9G|fG@RC zsQ>8UJdmuqeStkcg%J<#|*+9(R91Zt!8zxh8BK}BsO z>R%7Uoq#OxqIRSB^M@h6mqFsmN|YbvT?5JMkCiANItR>z?;AZu`^VYC3dvv%C+2pC zs6Nfj4<7wjMEXy4VP2fvC5m4h|FwM2agurlKi|DI%E-AS4<>mhe|{TNSVl%zdotk# z8ocNC_17}8Z?`9N*PZ|TSGp58qutJ`&phYw-MDNKyt%DFZ$0Yv7wrD(?(J(}%qTT9 z|2?oh11=mlr%wO+uiX6N^`IPhT{4xv>s9gZe6#QGT~U1qL-nI*q*3?zXZx@C;7`!2 zDh<`|cMm_ytJ5zcjh&86WZFv`zWImcsU>7#s|({CoWaYtYeXqA zTIa?LHxltnIrYVm9w&)bm?x8+ul@JG=g!B6`i_O(ho7MJ#qwwZ8*^J({Y7QM-mkhY zY!Ns}DWLhW=f^c*8m)@*d#XAECY&74@^@T*+kwW)P~s7M@8k z)zuL7zedd`V8}gpG(Wgkdl_bpUqSn<=jZqM1R0{{o=r#g<>$9aS%XymIFHu9%Pmbw zTg?ONzk;9N5wnX)&|635y2Go#{BreK)v}DJ)w(hlJw<$S{Zs3LGSa8Zl~MV#pO ziDyWa{9NW*$WUH>>8-OQ;mtfWKW}+H780&MM&qmLS^~LhErP>uMDq)SIecIFun1}= z$)kK{&Rh%Mj`l(Q$9l;Jda19_nQ<}{s;Y6 zrBdxGet**MrWcv|OOi1byZ86|ap&*Lch7_d!w$ik7ySBM|H%WIhy>bS9QQE_#U!w&N+Fxh@NHQCS4@BK&_lAm-0)!+QB8pP7_JZ;tI*WZ+o z5@Pe8Bg)56En)uUIENWDlAq7rbtj2Uj5||s@z6j1R9X4ililaYtH61Tdxzn_zq9i< zhlp`7@xvpuKAv=TFlD!tHuearMVcU&Kv{kR0Keqp=-f=Vuq|1Z9a0eioO%dHc{;l&)rs#?UK z7$<%^IG-WC%)J=9<|F_9dp3U^FULWg!Xvc)@(w(qaEmyaA7p%83}xSC(fZ%%$4Own zZx|Y%R0@Re*XfT%^Q+3>D{%78Qq*4^ocIX51Gl33RyzJOKvy!AI?2yx$30Whk7+>T zQ^;Ujn0DngOW(QtU8M*r zBy3+b2c3_M=qF30`eo6Xp8WjP>uZwZv1jROH-7$>l$DXS(}neGLw>%_uRBTl`p#i~ z8NU0+7n@Job&{BhyE0UA>fii_TYnxTUru%_xiViS^ZU!p-sL2ypDQ!ZkzYSsK8=I4 zZ4c1;$J^tckkBE9#vh1Y0(;iTqWU?)A{h?V4n_0Zs){`j{MHoh4}LDV0t3>5=nEo> zPhy<<$f1%)@bpeN+8-PzA z5`37xJmw$DL1caFQj-j)zgcb!KW3qv$hed@oj}M0t@flXB&djYwbF{l&@E z3~}^d!2DM__8;Hu_&j1@6?ye#Arr1#`tR>-eQj_a55KeSqy3fB3%%g#QZd&4L2myr z$2u9d-ZVhxSC5U_3q#yYQT@Ds`wHw-2&9L9i25U3{>I5X2G{=KsD7RtIF7VzZb0|z zJgjseRsB9wA0JWumFo}d^X)(`U^nWff1pSAP%H`FV~ z!`}T3sDFLE#116(G_mxF%ZK~GK+x)tM*W4v!u2p&R=9tuUZii_{@RmSdttx`6ZHPd z;t6@6{gTj^=KTKdNB$SkkVvBIKJx2N*b`ZzReOkzjO73QuTSwLIh#AF+V;A?{DgD# z+40FNn7R4`s=wb%y&-^>9Y{ zuM)n0zHjX!*8MOpKg&OAl7?HSQ2(%W?Res7dXEa^yYFwa_ZulSpCDtL9U0kWEjItt zUvB;%m2{ry4q?x?bNlB3OBs^dGLJdfC-d)r&-K54O6Krq!#$M0vjRI95%7Y=AGbbL zIx7&S>PVyc`*!mUU?SX~6!Y(X2A99ooV_r3-59jKY8jRXVSfPS&-T}2`1CxKI`tCy z2jRR0OCR*RzCiu(L^S`p_(PWbsy;{+ZTR_I9^*;2SpTM{gZcTicXWUW)8C`|-1N%} znuC4|u>DcQe;e3r8Gzn@TDBqulr9aSgIMoRu=kq|>nsNuUni8$iuG5aU~&MeZy$V~ zz|iW=X#c5ViWX^UET?Bz@avnql{v|cy-O?0Mf{3!_UEp=+(O#xqZtjY^?%Pdw>~;i z%^bRV+(qk0+NE}&bLp8N<}!c%Xw1Gqc<$X3oxl9Has!;nQbP9^G-~aGWmU%XN37`l zbL&TT#d(nS#0HIzg$`dKa`SeyK2&WdM*?+(`(Kd!_SjEPqTBwHevRPgYg2~<_o`Tr^j%a@Ls%H%p&GKj6U*zgrLX;L+ zDTDKIxyGFAetL&?4yyh4`?K{e#LgUkw$!usQ*rxqAAZ?^Qh6i#`+sM=VPy0#fr~7^ z{@0oYf!9STw7(fRVjo=CWrXU_7Rh{QYMy}BH@<&)0xrikQ3pSM{i%KV6~yl+;PG*o zH>p1Nla?R2{rCHD<6rx)-Q;TJ2u6SK3en$f*#7zI4+j|0+>Yu`L)8X2e_IjFuVVz; zVC)5Tl%JD{r@&0hft7!7_t&2Ia23`bSU@``^84q5`{an;vIBJ4L4JMJt*LhDg}rMc6#uyXa&m_`95b#* z<6ppUZ?GBvQ_$Sreg4?~Q|Dq3G+Ifa{Y9r|De(QXF11e<=?k}ic4_lIczSX)nxDMY zcnX&^Hlq5xYe@%;7?wbfDe?R72h-<~`;otC%}DlOu*H`{~UTe*S`V29cxVPtZX-`T5&8ubRX~%w@)yAO6c1 zmmgPE3s`%`qW2pDWtFMf%N|z$BkdDlWIVHkso?K|InwfMRfyhUd69pH|4&8Lwr2dp3cu#g_i|M-XVOvO^#pR z1#}+SKj{}Wu;=GbC1E188b3k#5-W0qtDdc>zU@rh2(5k!sJ@+?90S^p{ZM}u>X#2W zbyjHorNQkq#7>@x&R>}>u7Sx0zO4P6-1wM2Se|^py^kI{%g>+Pyg_7(RT=G!;peX^ z^&;tN!2SK3kjrG(h`Eegf{0J9zkgP20X-$_SoLczpN4mQz$o(@%IBt>rLgUhBwGL5 zA(;yOzG$QQ^@*x|;C5mptNsU^{X?6+KZQ|O*U@q(e*Oa1e1lwgEoO@y`Tk6HeLo8QEb*aU+suG&H z1bw$e^=rxI)9|))I_lq3jpfOX_j}R$iSp?|j2|3Nrhx0fm zD4y1W&OiBg`apqVhaj}JTi@C7Z^znH_%TBp)u&LY{ZPP+VEz7FecD`E1I8ccq30*s zq7hcQtVQQ%k{(--M&DcXX&Zn3(XVkni8cE{zuo5l{SWW70NyNkiVA5yTaawSRpC6s=*(C9^8M8%NOym!MUEej+$swf~V_E)- z`@ZXKl0!D0AIp5qm|-pQXYBd<6TfefyVRelanAYY-`Mr#%wQ*Y`tuDsf2%cTE;L^L zg7SH?Fa{RvS3~PR*D_K;Y?g4ptAr| z4?AXBlKz3Us6L&U=1VTW{YK4R@$;EiZUGJIH_`c_mywg;TG|6NejXkp+@I+tf%4h+ z*(Nw_EQjXD(ti8l`ddSEzT!z-0rc%}K_4#QuMb|G^c^lPjYakQ!g+Zj>#+yT4~E~! zCb$1HWd?6{74bvZ{9HB4AyxCu7)RwDfBDJe^mjXi`_)`C%~*Us=j_KRJeEV2w3{)R zo{#?V$DY5x_QnZf&b>zUanXUfFv9Y)pie2kKA!j$17rVFrKdmg@3;AMTNpn#3_|&f z?0W`ktL<6wfqVXI+^<3UN*{Xm_l3Xblj}cn-Za9(U8~Xj!D;$nqLeS(UsuO}{=XGi z5+~1_)Y^>S-+hnrB|6JG=$=#j{JQP51m~<9EdRmH@7Ld22HwYn`y-I~jP)j);iQW! z>hBKS+YiaMhUopTb?F7*);u1q-`KwX4h`31XyGn?{nQ_3g0)|?QP0TR^;b5QMi9?YOE>BZ_LZDKLhZ3#br3yA`m zR=b-zToLidosX65=|^T-d`08OfUyzes-7YvJty@qpGJf|fAD_wcH%cuo!J!djF;c0 zfE+SI$%LV?{QP$8&ml=uO_(7)`1w6`Cx;|NnxOm+iku8DPd1?QO9t`IpziPz)nC8# z&2VC`45|;NOJm{av_7c*3M$S(+}9QP*$BLox{f%21JP|Hu!sfSs zyB>fPuVJWuX8-pL5^PqY=Xb!yAK)=+8yerW9sJ0Q*Pl`U{lGbbSUM{(VMZc8fx~C$ z^Bgj3?il8%6hB`Blyiw)>KK%-EFoVz;T|i$ zxEs(L^_L3nM`2T+ai~A)ZGRT_HcV#S|KP^=$z!fV-gys{zrgJZlcsK3`W&?cIX zi>UEe{`lUeV+FT**RbkW-1w|3e4pS<=m*qa7j-TNGQUgkvN!+yLBWAEQ2eQZ=7*~S z4?yR%p=kX*)8aV@+E<|UsmA6X&|_;fs-GE~t;l~(HR$=9xYLhx2(Nux99raedFZ@yb7G#cQ1#a)So#v&E8 zzMvd@6h412L+cCv0cXMcz$8}vip!UR>vhp^P946K6D*=kLq7vy%j*ObqcWiJ%{e4L76Vj zU;mQ_VBu;5G=4i?eGa2uET{J6{Qe~&>?g#vM$wua{`lQkZ$%WFuF?a;`SpLVz>g@s z625P=mY=_nuMy>P>6}^ ziPk69{fdS3SIQ`VmXD4?n2s5$Z{H7|g+5y+viu`(-jDkxrATOSI=$7&?{6O5&?ZmK z3Tc-$e|)_km`mCMj2I(ne!euf=Mt%SBb2Z5@h;$N`V2jv%5n2y)RVWUe+(G9L%82z zAllyv*FOlStM%!ELn438t$*nXu7l!SH`e=PTz_Ht`Z=tgzYNtshsK{EXNvPz++js} z7hR#DU-|1}HB%N4x%v-i{&wzs1d*(lWhOlq>0c&izPfr)B)MlH$2`jC=hIAJ1%aiP zS$uNiOK{#4Sa9Pus-GKItbo;ezXjD7y8FBA`+L1Tw!oj$QYgPU!uP*de>6e!zt;cG zg56d-R3EJ^70Iz|;r(ia&lj>fL}kWNluy@`T%zbRnu-6NX7j)L7q>p4cs-Zw*gG2K zvzEGmtX3mh|Eg-54}C-1Q9iwc;$VPKJU1U)^Cr;EFgVD-c##+{QCI&f)%W{ zsz&Q$O&wD}dq*9MFYf&#uhtciUh@-;A4NyDfSK@qIQBkX@|c5A9XAAxA2o)BVDexL z%AZ`&Imp;#%kqC*eSGezNNg_dpdaq?>*ER=9TMkRK%W}(>!VgfF412zirLx4&!6V6 zT#~nM6w06aFBh10<_X$=>$fxxLPqvN<3m^U4)9#tAN7AXSKNTIj@hWc-Jkmc8qNfw z`A2?~HSvtEX6YMu{=3hW1?08bJNiPnfLm05X1}jf8XZZlUy@KQyZS=YxHh!EW*iy}NwGgr|J+o+1ujbn_Y)xVn?JT3gn3zd zX#ZDoav?m*Hb(Ei&As>wWM~8xzr=q&Cmc{D%U`CU`Gvo19+B8MlIih_pD%CoJhH2B zB+6Ig#Mv-!$77T)&um{%5^qJnU)|0)keQ~0=3kzVcff@rbu>QLWt@YL6A0`6GS?qF z#NL3XTV1F}3cvn!jcbD7T}$YTYJPvXC0>UN_RL4)L;ekG;^=S*)xSTs3yJN;cIuPO z&+qbu)^J_FiZwsQ$t?w_rtwUZe%A?xT`1Rl1b^>v8uR`+=|LxW=Li!>aKhuBv!nDk0 z^!)XH77Vl2cA);uR`|YgbhQpEK63m2LrD>2j54CP68ZZ_LqnQCS#vQh&E`K}4`P19 zV5_aDevS27NRo8g=oDxE^Amj_k~q}&WaanV`jb^k9wAE&QGFA?lt(%;4N?9sIp-6n zF(a6U01s0tLXM@Yxv2hK3Y|by^)I6Jnf0Ho zVb3ed(l>7YuyKnYr0f^=hmraJH+@%vkMdW+`7HkY;nkF#FzR<-G(IH%JP1uW+N}E# zTz(o+T#O|4Kc$$}&7%A*m{Y%+p%_KxPwvU+Z4&t(%GvMopeB#BE)>oOe&g5Q zJehp5Fnc)4|2xkT(j{%o*jhgOtG~(|{<|#gf&9GA;-6bT`{pzUDjwcP^B+br9CE&i zqyF4}V?0PtQ=rV8?)-+`-`cVMJV+}{K>6QicM}Y*I#2^o{`f!MUzdC>&Y^`H`So}9 z-3i3Vf?wTT*Y?6Nlu!Gb60*+Gi0Sed@ku%Rc~?HR z20BR~s2+0a@A=~DkH4oqeBE%3<^Q?;g)`paaB+e-s?WFM;^Bw2JgUzFFQ13u1FX^f z@Im`cnBUt0&7YcMm587qnXZ)Q_g8L7x@5J!Lczuc5G2g>F) zp#EsE!~%G}@g?dXl27e~`&MeG{(i1H1dG%Mv-suK&o%Pu9xd{X0IKDhn=Y^Qv}qzpy<>&z|rWMbt| zl+X0G2{7-|1#~_=CCeVpIM$&2b@o~XkM#dT{r`bA;UI7nL-o_KqX;JU8cFZ0=Z|kK zDit6Q?kC0em#I@F68j+u_4lWa>5@Z7kD&F7G9McTy`#wUN0Kc6%8l>p?n&fgr6TjG7eAjfHsuq) zLk4Jk_d1qO-q#zTeEw0kfthuctoz&C{L`(>9*l%;OgU)Q>&m_`I7*Z8`RcraZgi`F+7;roR$v-_a&-zBvc zb_dTu`FwHtC0J|tqVtO~M{LOAdzEPZ__NfXTpa(BcJB}6@>#MoifGA5GEGvV{yvw_ zl$}YW{gDEb*pHvjcm*49@Ty?>e=c9j`&WU4_XpG;1*>d@t5g37!Ve*%l4qIEc0-!M1(1LqnyqUX0ww-@nOPDJ|$Q8oGG^d5b*KOiAhK!)AbN6+8# z>C@n_+7(uPo9mzV1h5KGWQkS>N}tI-^rifPc+mcQptzW{<5(Gkm7R{RC5l$KdF`q zAg+}!X!rg(E}ydQHn2hSJc}=`zl%*<2w(J{3vQk5=7&B1-ZXhNbc}qD)^B6ww?eeT zZvnR7`o@Ax5C=_k{$@Z~G0c=3j>g~Grxg%-Xgo{5xcPh6{y*Tlc>~&?KDe+Kne4C~ zjnCD`lE~is@=U>_r@a2=fJ_0=i5`O1N5%->4>A=DLHYe)G7Ua2sAkRAQ_lX*bbB{Q zs=kft=Th?o$bBk}#_x4Pe*0yrp!%qPzZN3j*wZOn`189<+g|~_G#Bl^-ruT6-c)9y z{<)7Kki`+_S@Yjq|KbDzHE){`!S-bT87jB>~mHx(j+l?ad*& z$d5n&c>6htNNdP5r^Wc=L*c9f@@T&v+TZGkC?IQY>7o2h**Fct%rCL{6P`y_e7HQx z4R%bZL-jLj`d080{6zgpTy6qrjF3kAuS&Bjq29jf3QjRgJ;McDiTMEdYQe8Cu zPAV)Qcc18@{H&|8fz`Lpp!M@=gXu6q_;`8ud>EInaXwqYP34CG>n}^!B)|*jp43{m zJN~lkSA!Hv!2gT^dVfe`UL{12AIqw5ar+Br4&DNp&?#tq?)ycLOlmra>RZfBAWK%C zMd!1_E(Vad`A=#0`)Azv`#aeUmW$s)&(}LCe=tmb%-a9M&EK}n3W2_Lt!VtcC%+4l zI(nh|GiInAhQ`?gQ2q>7zlOd;ywUlu9`a&jjmH|A+^c)P6MO%@M9*a6ZX(MN4}Sh8 zR}_%bB|0d7$+GRoiku3kj-avbVU zwu~4;rrtV$_P>&p2}w0ML!a94`$Nca1G3{LTE7}G+aKH~JVN;!@-`h>Zz`ep1A=u9 z!!_If=zMF_hS%_Lrzg5UqOZ0XsjFO###fJr0c6#e$Mm(cXumS|d>u)TCi|WLP-`vz z{L5=%GP&j~!)#d0&u7v50%Dw`&4hID*H=4@kCIn6wNXATivdhKPN95m9xww6)-ve( zj%5`gFg2nDtq|B(|cMmiH$(dv=> z`gqM{5wX4fh<3lv%H=orax{^6_?tTG@$r-FQ{LuG8 z31nW-L-`zLeE~-FGhy+`&HsFYmC3m=u_%9*g+s{Pu6?Ngz7<7C^!IYK{&PRx9rjPZ zj_xP&92NkLr|t_$s!!2a6?QWN<|=+CLa6SVUGFdPuSNGu3}Zle7N6X!rdVZvE>hvH2D+SI zqyGKu_z1Y^@>ww2z5DlL>+3YNWAN>vE?OV^z4-zxl^BEa*;%PfPH&E(w*&e0vE{}P zQuS*uT3@BdXMoSk3uydsc;XK9RSnAL*|_a6thXfUuXkS91sCTlpz}M%_v&C%qbpvmPVfMk%B$%60QbEj;6UOhw7wv9V>{T4 zlR)bW?^|}k0&jUVz8|!_4fdx9T3<-~^#VF;{KL*39wbA*tC5#wxsaS@_5BCSkL?b>Lov%H&QlE^q+Cx92 z@z=)!zZ@k$A8MlU!D&Dtx%FEUJ)bmlCj59=f%56-KTKSD8x~FmR9`pzd;{i}Tu}e{Ww|ZsV#-iH!>tyR6BhSa zd;(|x?DEKMq}P=WG=7^kC6l)Il8paZem=K01;EgScUbu&mp`rWwGcb=h2YyX{`-@a ze|AAjfE?<7Of0hC@g`L?zZ9p(K>g5QRR0cZh?6agmeN8k{`jM8s6wuvi9+-5M;?Xb z< zx?v;>m4zX=Q`%FBlxDPu@ypp!wPH8@6P{-couXj9>p+Pc0_r zU*2Km=Ul#~M|eO)Q#Cr@Hf!c0(CSl<>et8VyFvemEUNF`d08-n>4U~ckFsO%cHSU# zKf%?oX3#2dM*VTBf;f?n3q<=%&5wXj8N&O4 z$o-6Q9*H0u)+NC9YwXJufL^L_zUE*3UyQKd?8XCefabqcWkL+cEV!>|Y~w7yVUEr8<=BUt$x<>==Fk9trz zZ-x3tGSGm$nZ674FW_uPN|zs_*75xMxugFQlHK<YYyAzK2)8A*np zFN4>GWXHq)C||bnMI`!Hf0VCOVhcLMi&=bSa`f-M!8+Ko_X(=M){In zbOiiAE2H^^v}p^tq|HM61G@F%#5Om8zOdr=Z^Pw#ldZ{H(f+7z@DdVq<`x~MAv#}N ze-aT8L-tmFq=_5&^Rw}rQ;2DR7*pua&u^3P{mr6>>Wqcl4jaDv&)X*zk;`AyS^NSg zet%9WB7x)jGxFw-{{Hve`!j+zTe#~~#LE9Dhwp5&#n7|;Cd)r@>))Rzu7g2skI?uu zJ2VpN*SDbjOPx6mUU3>|{i{)(LR#A}7XRG(?8~DD#5`^%-FJ(h-`>=YydGJM)_>AV zX2F96r%?Z#lIsauvMA~=4?RePHus+btiNnKBm*Ax>WS9BjIPv!ub~Bce&5j+=(3-Q z-XF-9mLP5N{t?uI=?>#y$qN5HMR7i+$idw(PH>T&3B9*FLLNmxXopYVMy?0(mvIlYNoc{t1e zaP@W38v}BA{SK5*P2Gt^POgZC9^#MRk7XUe)xKQdafLs>GivvQ*!cpKPv?S2aC`O! zJ%879lVIDe?*i<8k4!)YoEaVQ%9oQ~!j^=;cKDB`9wdtt8{Q7ALk@|3h<)69w z`Kl&{+%0-XZzu5U=a-WyB;L4_CiLg$^Y9s={(bMuyzR%&r|M3*rq(?6*|6f2*cB!0&#-{s+Qe&%Iuty#4|@ zU#KbMkMw(u`s*>aNg%8K4bAVC=TTs?4Or)oTi@yvb_e!Vk3;z@$ZmzCbJJ+?H~#*C z<-&<11WEXpWc6B$d&0 zUxMuT=1co~A@L=%H!-B4s6SdDtpD_QlS~cnT>jS|=_S_vKeEOS#vRUQ^@lS#{v#vJ z0pzH#K8^6_eku}P2fRe*7d)Ml;Q7?A0_=T+s=E~CgzK~X1(z?y^g9r>Y%Cg|JOp?KdWw6)UY$z8 zFRkwWqD1%S6)W;z0*{=pviuu2ekPsDfPer=)StAQXM@iGMbuwk+E)r0zUrud`@U0x z%#EK<%>w!PS@p6v$+g~$#!qKgeNuWPi7qkY=jX0eFWdPsYnZVo>0f^foc+Z<*X=-R zR~~CWWH^Vf$@LEKKCu+#YuKappk#FqosT>DDG~~=zd+{?)sz`%S~LXZEB?wIkQ`-( z?yr*3Z-WssQ>j`rzkV@>lSuEo`SiT(t$+TG{XS4bMj&~9;3~a;TErLE|EbK6B@d)p zDLKl|SLj18P~UbQ?O$}JE&<=ym(lvbu0=^uH|aB)-)TL~fMfF{(E6*iYc>q|D!ku` zyf3xukOVo>I2VnNLk9IB#l;(`(_#MjSZCJD*5b=*R{ZDYPs-90;bKTGiyy8&4btBL zuWIk0eDqg{0@X3kQGL>DE`|7M{m}S7b_D|iChD>Jt6Y8B_UaC#9Wz1qt89rLLiRt{ zPET+DxBp0tt-l)6CXtMTdDQwDzdn^p1(9_@S5STWWatP+E03e~-`h^!uwwZ+v_Jdy z^AhmL7S`{P{R3~)l3;AkCzPLy27BPzZgJF~cFoELN8$VBPXG4PbLX$x-P@piQTaWT}${`A}o;0HVN=~y3)=cS(@-^xV1DD6@vg(suzTRith1pNWp!M?|wtdL> zQ|nRvK4LS34E9T)D=&!jUyQ@w`B?^J^?*cr>Dm!q{i>C5gxyRDTEA@x@P>!?&Y=4A z?qL#WjQNPh|1$GE@H$fr)t|DYZ1DR}mbHI{%MU4O1Igi&(D{@zvXbO_qZjI*h8hJC zw_DYyKF8F?lJ70A>6Kc3ecl+JN~D9o(3~gy{B3z|2YzKo1a3V<^>MC#r5p={mm4mj z_p_EB-2lUn)uH}#>WVTb_EMuYSrvbOKdyfyy)ME-Qyo@+hRfHh9eqfF{W@xLjbERi z{HI5<<>KkEkD~hvTz+=`)F+G1CeUbk5kK7fL4VE&>qBnasqy5k|M+6>FH1Sr%XUOX zFq3hM|9p-waD*1Q5>(&LMtg&8_GvW#-m*Lj?x;LP{ehf%GSsYkkJgWvoIS8Gw@ZNC zAJkfS7p_e)M)m*R>o&-)u|xGOa+oABbn`^(M}o{$LeKq2Z&&m4MZyEY_RB?7zrXa{ z2#ry0KWUIedigHir2*7hN$r`OQc zulf0td7($9ypE-xBl!7)VtsOYUOau{n)Q!=w*UIP)qosSN}%DF!~gz0lT&|N`KXs| z+n^OFe}1kL;qtC5R{xdjU&TC};I34$;PE1n|L69%blSWjdB!PJAIAyb|4#1l4&~3e zbPxRZp;LgpzxS%)F058ILj9|qX*&c>vqkx{yPrzjhkru#>qL(r7_^@e{MsV=_i^)= zlr5V+Hb^u|HZqjm+k!x!oOeV*FOd0Ns##LFl+vh%inx|Cn(%eD9AGq z{XSg&zE?y6k$r@o?+dZXFw(Oftv}Yd-h+YGqf!51;MWdXssx>{tBsZgB}XKQ9e_I|M+t*tLUBk{Cs_C974ikVrcbNe!c?N8<1!9u{5_`#FrT7 z{ozI9m2KCZ31YJ9`T3YQb`pF_%Vgz8z{#)MVw{Bii=*g#+{fUJpfUCaTE8FsB?<;c zJV5=ed0sLw(XD9xuDufGcF@2d7nlDgbEX#X_URh5*72BYy+ z+)1CjD%eKvH}Ufs9H?yjenB8J^(jAp(&1C!)wfK+)+M6)d${oRQm>c zPZq!b=EQgCFLadd2pk^WC7k-I<}ER`B0j=zsqO z*Vn+4ljqQUG-}Qk*md>_TK_IOhr+4Dw@`ihm~;}xG%2I`PPg3`;K&kv3I7@(*gtdo zatB^r8i?M%^z7E3$VrEC-W%xrPbiyAdR#rg=^v)+*Bj||q~DNI&MB78SK89;c;G&8TK9=faiROO%;j(3uFV)! zU%K~~CF6R|M*XEtiw1c(Zw<;1kym97yDsNdKG6Ab8MGFZLrT#8`erA8Xghfs-GA?v zD%O`3H_`hAQ{EneVXB=Z{HHMA>Qs9YTyJ(m`Kqh90FlG>B={2cN26-`6D7|O?$3h1 z{#20vh4h<3RureA`eZzH9ofW}p!~Si&VfS_hfqG^9T$P_ykn^TIL?ZJ&vlKce{?*u z4;Ehji1MMVmkoJyj+yU@1D^2%oCT*jFy)Z9DOz|MiE$`PqG=wNQ2YEIOb5 zJ8VP!-JeHTqGS%t)y_iw&*P>=FnY#OR9{|3g@W1o>*)TvjB^b5y=g$}TbywU z^tSte_J_^Vbug)-KiAEH{{7rOb6O$x!$@wj0=>SS^_3;frn5LZKRQ3n2i6hwCB+i; zU)aBF-5){1)$Vc6Ts!nxc>ngqjlE<@)pO2oHJ!io=C$Db^bG0`gZ%uVXVwKYzj+Xn z4X@@)qx%a3`kn&!b4qA`d}P2yxb#jN^-qpgnk1!lC8yr@SDysmC;eVKm_#{*a_M8L zI{YdcE2TTm zCnuP1r|p~r5iuF){;hmVC?t-nMfHDpYz*W%Jwf{$y_G32r}!P~C-?9CO6C_@&39qO z=zgfa4QgzKwWT9a|J52OOIqA!p#9^XO{&bm*{vNh)nuaIpjb>Ysq$?3qKzw4EVb`>76orHCZI zb@!%_Y18&`TiQDK70yqlO4&hQr*w2b;)B5sm|1lVz2AO4KL&CRK0@{H;QSP5NNq*) ziCvm?(En>6bpPg8ek(L7TA}sxM5!!M>^dFwXK_E*k)=texnDl?^Es$Ff;fM=EunwH z?{|6kc_qr5W6t(d)}!+E<@X{O!5l%~7h&hGgO;XK=zig$hHU8l@;8fp|LkGHDex~= zME#lbn~U)Aizc__1D&7a>6&Cf{4%ahpU#in#v$ZZL@-yE+rdwOK>sRLrjmjI$tXWX zWva|Jei3?p-<-KfIX3q5YAm{SN5euNvKN4gVYirL7N9e^+Bs2Nk)! z(f5HrfgUd^pou? zzGK?q4<+^MW#K8%^jARdue`XSNzS}mg6flB!w}M$4dR*=t2=%^0bjmzrxHW8B<`HT z_5c1|m`{7xsWNlBIP*pWfqDQJsrMff9A1JCZ`{p|HJ@q>3tI+?BT)hrPjy#F> z@7Z!&;oBt9#{ZnRI9SmCC3$3ru?cTzy@x##l z)(>&+B>l%piT+9G@AhR!l0n;VazmKUdWe=zNA4L1B)FKzqFBI?BWp?bR z1IS3!x5esv;OCF~sK1!sm;zUyG_#p+|M4a1FK&;>fq6T>v)KMu$k@(g^MEPbuUm9~ zJM+CJk^bn)*(uZYZI-JE8S^-hBf%Z~fq=glSv4lw(}^FniO!dnff`d2>xA-kYls^2 zJl~1e((d3(=-(8Ntb_FrkE48bIj|Mtwv?g%_-n`x*m?FU%9qiXQ*dXIJnE0Lye@(H zR(0-=ES*1D<$Dl2s3$sqTex>B39L$xIG;lQAp6LjsQI0c;7^!e*NLLYcb6O7hHfJ| z&c7hP9${$@H)IZ={EZd4Lg?vibpPCZ^d7iicMs*SttbV?rMyD*&m}Mi-dBBNvG=>G zqTWLG$)V_e=82J=iTChHX#cfjh!%0|;ezVpeUTcYSm?;#&8G9$b&48eS?Y-Lr@2~< zDS7M2U+L4qpHSZvN4mrP+CsEHE8n>lwltnY^=)(Z4(LDm3d-NM@kNlmRu1*Imv&x) z@+so?u@QeeqU$}VzGRI0zXuK`#4IU*GwDS?zpo!nCHcGKxpqT({aE$eooGBLl&H@_ zeJmVd4>6hh(fM}c09R13IE3n7*=8|+Z||b>?bP}dko)ig<*)fj4rs}IMfrQs{1$e2 zn4|r_M_^|%vv~sd{B2w6L5`&sp!)dM%N`~>q@ess zrSE~|6YrpWy;k235#yet^Al&8T!?b`%qq2a)L&u#+ege-*&kDMe`j`VXTrFR=W?>? ze5D3xksVK+xM3sce2ou}CWqG7a-7R3s{ZR8Qe%GF%;S$eqw}YGQjJ->Y#z#A$rUxm zJ7^xt-^)~2u=$>e_W$3exxe&y&&o)ce;C@%^NW==q#mu?M~f+(P*svwAsxgM|?NR=+Wz-ox z-MRb#pzB|tO0(#F_W|tVSbBcYmg@?ATr<%6(lg&3q(|kW{?V!_2lSdgqW)PYy9hKa zJE45;8Fm?-d{Rd9gNo&*r0;NlF7amve^LVfJoC~t;_SYc8x>CHkI(iXeIDj>!FKfi zSnBvTc)0lt>VG#Ygu#s|=h6M3RWJ5{OY{x2|9_Tv51z^xp#8tuf_LCKXb8Gr#@y;m z!U53vOt^|Vv(d(m?=k%VwLkr(s?PkJV~6q+GDw~2xyg<{MmqQr_75)&=fc=$NvJ77~eqk`(jz#lNz2?inU+Btd+tK^`OAhzJY@aTA zfBJ6AJLqRO5cPjQ-8@OP+7XHUG-3Y~a50L+e!I*)F^m0=4*+!u1CiMhORmY@;QIG| z@RuLS`%{@-bK&xo1a!Yh>GERWiw>aoU(fa43m%F!==nR|ydQjD)}#Jn#*$q4TKtCH z?M3&;y*1>>#NXDOM>w4iB^PaST4OF}nMLPgW4S4rp1G0B$)WS{#a*50cEyH2y^(%? zp9QEhq6QoE{4PyVXSQ{=Hr3t}2D@m)aX$ftVO2lwY&u_hH}=9kf4tFzP*gd)*(M z4<(0BC+8pULhHxQY)`W9Y%a>Tr*bs0O1{K#Yw3I!s>hK6*IMqvAUfZU8|T9BJ8`Ig zR+d=;4fd%h-z%r=1@lGKDBq&G{jm1h1GIiW-kJ-8&b3J7`@;UOdVm~}pE(Bg&-*>K ziBlgtZtfO3->=@766;8Bly8j~b>^(zEIz`G&i94G>df|WvrxYKUsY%BteVB^xzhQz z5xo?>Z8m0CHE2@#etyUU&c@K{as%F zIFb~2jVqF+^O>(T4+cGtWj}{?{CvXw&h2xTz-_(#X#GCxx)+v*RHF0Wlh5|URrVhH z?(h9v0LlEHlRgZ^{l)VEaR%A({*~nXDI@khOvvho&OaV_$PtU5qtN<&IaQlH^PSCo z4yW_`#Mq3a?O)GToTTe>(nWP9ea#HMR~(&Ro5$k*Z}$w8-()EbW_9@tzH%L%-+-IX zMH$l#+3*T=D!-?7JV9#SA#{GseBTZqeioqpQ~IgXaOLC=7W+PJ_cvEySD+$S_K?o! zf@k+ZFHaMlPkl0)K~mD9IKPi{J~vzw`-hWZ{qUFz6Ccg60!?v3ud<>#L}~@;a$tp;(9d&$J8g zA-;cKbUrYCogCRUcqFQ?DaW*lO}Gu(AJr>~`DvTRACW#t?JxDT#Q!cm9px`_xCWy* zcsl>ZkIvt-VPgJP>a%*~YJY#flK!Bu*AnROxevV`HQK=woStN&d`_1MfSXf}q5ajy zKe=Ed^$Oj8IDPXp42f!I?=StgpCtKyjnkhipfA4vcl;Ec-%H=`!_5U6=>5g$nPy~7 zum^hnuTPjkVw@wnQIF_+$4y;Neyq*n^aJU9A90E!%^xc``MUdmf4`Fc_rsI9Fyd_t zI^S1#5C$hso<;MID|hxn*t9EXzUHtc6`r}@LHBR`3_iex$Gy?{!oXBH@%KZmQ2!fs zOPf^On2GY+I!1$;K6Wav(Sy$K3`T=_GjS@)?=(*h#yn&yeYT#}nMPWuW|ye7haqBi_WER$FWm$U=12Wx-YSaD*Cg9{pk1&VtuL=#mO$^F ziRk`$*=bL>^EeI7HyZ2?11tXw)xSYvev(W-vrlHx_3zt~t6s!Wp5*L}yr7!H@OIY74q@IhO*yy0=v$uNy zaEtTM{c`P2;ZP4n==(ZuYOydn=K`AlYQ#MN|JSOhzaAR;0nT>niTcZ`>vAMDXc$_* zox(I2yPFgFyRNDKoj(9g2>~iQpusHpFp)R)pz~Q-sKGcZPD1%~xhDSaH=D#aCDZw= zD4qu%3A@nzL`rrkSOh1a`x67pQXxCy273R0X5eA)tZzX1{ITc^=(T)A>vOWD4$)pQ z4fWr@YRt$VZ#T65?&>j<*vN)+b=GwLF5g~H5(cHA^95V`m!d-!I;_Foj{H&zB>p^7 zzAo#*`qDx4eUy@Y0kGi5VKkq+BMOJPbtlpKY;ox-oVzN^k#}@`k4}F8c5dBKeZ2GW z1K1=Qb3Oy<^RI)s8cb2&34Db!oxkP_8q9&I6Zi=m>HOVzsKIEsO+fkkA+N~{&78mw z$fxsXaC#oNj)+F}(Mx727^uag{_$SFSh)0(N9)V2j|z(fL^E#+f9eY6q&H zi)5dR7EjV-Ydkvqi;z!G|Meg>`v7|X`@;SJ7`G@F?f>SC4~O>NCs6&|^WrKjO6i35 zfA60?fTNZwX#S>j{sZj#WQfksihr#qeCz><{!i#XdR&_akD4RV_jl?JEd_-xacKS! zIV2YDsdMQ2{hu`tz?V)ns6WX$c^DQxs7LvkI$EAoZZt>zM^latDS0=E)4oQpuLEbA z6Fc|i67zfE{Is%kCb2&e%8dx4>)VrB4d(qs20hG&C9igA97U z?aefqQRf--eD{6$T-0l}2J1Sqqdye#`6y{UT&UlV&KLLP2f(yj*=W9YCpsMZR~4fB zWmz}Rz>8;ZQU9z*Dxf`9hMTF?aeqp=SpgZl5gOa+XzlScJ(iNQnInc5YMH@4@up-8?UHzAA;gV$k8gh5DK{%K@IR+lkiaqkF?4_V+P#zJ0$W z7W~9_J3D*)tG|-`YEC!+OZ!)%`)BsDN1))*J(OSBaIwDnnV|dKeswye)MY$ce|u${ zlY*^_(fa#F%-_37B0l3Po!{dtG?~!(;(s?zqvmUq#C(o-6rucjCu%a+5=4B&6*|9z z*Di(i?_<#ZF!IcLxLlo#&L?&@i}SOqnJAxUMxKRL*)6EQc|5lQDio#A{_t|eLugG< z;$B;H=%*AYNgOZ@W)_+17tA@7((BXWU0&p-`#zMvmcB1VQy!~IoL><5@38F-aKStr z<#Sa{I1Ju<6s-@w^|5er(m9mR^i2mKa?Mp#Uz;O7g6ADwbbe@&E>GNR2c!G7-DGu1 zeJtVb9H-ZR|99rZVTTLX(}b?C!BLt_S>ae-|2dscrzB10EIXE;WlQJNrBIX6dps89 zQ}voAvqEMZ&)uc-xptLUKLd8NsgvpVJD7f6Fghv;&BsE&1;Dnk8EC$1KjjFds@0+W zqtBAFV7;pe<<~v90@hdlVzGSp+uVn+{DUGlVr@r%CFFN_@GPP*IfzTVLFZS7_aZO8 zBylU_)>H^s5{DU-t}+@e4K~sr~A!Vn6tPT?QcTd4}jgu%jkR|hyMs~H|n5# z?ktoi--ZoB_jCK2>JqtUB5or~=dwnq75ziTpTldSoLkLmpVc6ETWM|Ys#XVDzE49Y!sq4{k?e=qQUpMdJ;6PF_( z>V5~^51Qk07Cw%9iRKqqHdMfp5kFXLejB4)43z?O4BC;%nY_FC_wOV5zG>6#SEApwD(v^$9r=b(Umg1f!l%+Sw0;;E>;xUR zBWV7+R4oox7N0@q3pdyUV14`|s;|oOZLr!{8_job)W{R7ya6b`Ge_x?&RxfG@dp9MwnhMtMu_9DNG#NVf@r}MX`p-I%`y|Tpqg^<6Q0bVd;eY`~eE%e`Q zdV%or$pQ5HQjg4b!t}UYwEqA3@(@fz<7i}#bRe) zBjL}ybmoJhbqMO83aXZY+to<4Kk7Xq4#IC1q31ij=RvT1dmg>N`5^8Hs2{tI?iZQd zJqu9%6z$(L$x!lplp~st%rmwjZ?R!_IapfX!a^rj)7ukhgzgMd_i?U+6p?t1P z_JYKpv1t7;-xdg$ic`_~#Pwb~A*41N&DT2JtpHi8FX;JPJiQ(UnaiR1nysh}dVW(! z->39ZP#|X~_C@#8V`phG7ZpeFhpg#*`YhC9GW169_vF&4{g2OPEk;!|0_AgHiWYNa z#R&eF5}i-CY4hQ0a}dg>ze5}>>Uj#~uWSE<(B%h*?r*jiAA#1=8kE1H8)sp{)+cEH z-k7XQW-S_x`XkrnLy5+Rd8mGlce5c1KR0t{31O6FVg221GteaY5h8kbn2{CVHf zVrC^-^27D%{6)QP7VY-w%KpsNqUJ|MFXzLg*MaE%TZmsAl-r*``HVL{2u=6P(fs52 zpghp&bPc^famG%8Z28!m8}^aDUwkxAmvoI0?++pS#iss4N#0|7PNkY&-v=JGA*H-8 zm)MWa=l=7{An8UpdjDv|H7{uY8H2tLrXL*$kA3%{{ol=qoiOWCCR)GG>J~%AvPbBC z+VdWjptkx0i|w~BJX#Oo`#Yifd8wieGAvZle0OE5H*tEihwE%cKc8F9YcYmLhw&|; zbbjC8)ne9N8iw*|S+B*Ms2avEE2HzhL|&Vb{WFYTJ&4Y4kYS7Hh?Ww{Z>PueVSH2o zI{&rukAv=kg=qh2W_u8l^vY2GF5Np1j?|0yJO6&4N9a$NFI6DS*j{LUH?viji0ZA- z{e$}_hZ6tmb5MPKe$j@EAG8V8*B6791Ct(x`fJO%-s1P4cT4zBp?*%f6$q0|lhOLF zM~Xpz+C!AjyVEP-sL?x=PnB!+5M(EV&Ua^y{sb34si6B;$Hs3UK|5p6`SzwpasTpU zDE}~s&gax`TFjqsL-}5LbpEz<*JivlEl_^{jMHX%&#>V8j-m6pYG$j*%Up?-nXO0F z*S4IUP-u~Xp8u4TIOtn@4CT{5;2c5cBnB59w&cz<6zJ_Y* zk;wxrxw%c3|Nj41mhji>N`{g>dA8_&!s{j*GNsa+)BZ{Kr`-oRg6W=ZXn$zKEQb|? zccAq@JklGIX6{1y{gWFA_ogJG{Zpu6F&N#y$F{1__lIW9uLR4&H>}c-^8bE*;ry)s zqk1TimPY3n3Fe=m!b2I=*M848kjZYlCB9E9oKM_T)n@9zoS&LP=hxj*o0+`YoL?cA zLG`B(i8fQ_YmV~kw^o~(d&Hctnn>q&@w1&^pOc2(Ul~*t2jkU_qWeXI+zx`-z+yDN z3&>I+6U~h|?Pv7*KEIzHF?Sq>&X134T9DSJSzNIKJwJw`R#8TiqQw1T;e2+UgCk_9 z`lI}r%v%nbl_6;T|B~(vR`;UN{>a@X51tiWmN;3ck|oyIVsbJbx39`j?X1JE8Nl z1L%HFSwS2$8s?$z4-Yzh5OQ~(LF?V{U4=WjU)|03jb-BL&RynGXyUuYdz4jbPFqVwHH4-SIE)*|%$8|=%2_?Yvk zety1L49d%IqVtKiEw-fQ*jmm(mEPYqRc|C|3nRIernmprcggudng0gRG>Sm?%UGQt zh`q2E*T*ptAXS`#@;CHHB|P5x0`d+ z?LRVDZN|@SFuy|c;NPELa=sN?C-%P~gZW8!=zM)?)@BAK4@UWVBB#TgD;~_dd(-)n zSNX2Szc1wL>mEno%Dhp&hIWgGi5WTQ{kj;PG?-C!63xdnzvV&mBM!Zv zFi*Y&YUW=@`i`^MUS<7r)p@49j+M zt%`I$rR7&Z|Lg!%|NAZ60Qp|wsD3`z4uaV#dr*H&tRvvq>twV)Szl5Kcg{7k9+hQ( z`RO9j9|RnJ1pDH?vVMQ>9|`@*ppT!RJVgQBkKCcENRA)XLHRw@rp-jg4&)om>HG$( z>oA?p4CGz=WK#X{brT(C+Uh`K%y1zjg;(MM)PsvF_ozRDLJSaD+*3 zJ@NOczb^-kgl(uk%1?_2Xgh@ZYgNNEXev35>gR`ddGI}{9IgMnbP2Fc*Vt#H=>3lj zFRowxhH#%hU;gjs6Mp~WO{oQ`+cgQ@kBdyOCBbV~qWdvY{Wg)}rQzH_13KS}*KGhx z^)Ly4Eu4?V`UFA!m)&SS;j%0OK5kD!=eHAHR6_IA29)0?#g9Pc>L=DQrbB;0u>X_P z^a1xWD{MeqY7eRFPOJXrug|8m7Z2bsoTPF6hGjZ+;aZc>mUMx(=ghJb?H0 zrt^E(QHPN?8-Vir&{Kz5JY@jy5=-ZIXpDD-abC^r#Q{%Y> z8M>T7=eKK{#QIpg1l7mR2R4yqd7)g`2s)orWZsJUS4pAu=lSRru(7ir`u_Th+70l{ zG(4$ggbHXBe|q z7Tr&nw^xS=DRe$l_USO5m3?^ILOP!ZZ|g8`6#Alko_?jn_#5`+Wq3ND3fm)q zGmJ;`582pw5M53~^V^)AY4E@%AJtEpgZVI2z8HP~!6rhHywcL(!i?$tCu5>d#?|*j z{i)B0VPujQaN|eO^RulMv&s7fu4w;0QpJZv+J$i21L%An&~Fnht&(OoM*;H-FXt~!ABSM?=nFxK`6 z+Fvc%q)060tD*Va+6DSVeMn!v z-{cbNf7*SjVC9*+Z1ZV)e>FDgG0aV9LF@mdaXzH+T@ZRce|^?rCNJyBSKOoXsidRJ z7=`!b4gBc*#SYMALXvx;{Ce5xGU=Cl^1(0Yd``O<1oIMhqI`zsMu5rjJ?Q?h?umHN zmrs?b?*Slr|6=s+G+1tyi_Rb1^FG6s$+=t%Zd6rgz zUD$0Fdw={r{}|SFZ$kM}%$`lc{G8ByZQFPs@?%mUcWG)zeFzXq=4;>0beRo%jCo(F zwExbh@P4?Oy)M&s+L)hFL+3BoRhN;!XpHg~yHl5mcx%jyzR>xr>+(fpW+=sO%ctu@ z+tQ5?;kF(1NA2H(V6s6t+J6QoML_+X-K^;BzxxA{?_+t2`8}eO!VW9{rw@|+>V5kR zCa?amx^eXWa_&(@vZIUm{bXeRVYEb_)Q;+j&d+`a4kL+Dqb25N0fP5yt+hUg4%vPy zZ&+zS)z9WH3!tKPF}h!2J#Zzw>+g>0r)gRm$~ihg zv5yO?k2|W<;L)lqRNo(#<->!;h3voYj|urnG&%>@s>)G*MqaCe9-+0UKMaf?MrKrw zkm&D(`u?b9Hu>Z=j~h`>&mZ1i7we0D{Z-7%v3zoJxKhKw=b@7vJpgG#n zN9S+MR3|ukZXv2~8RGMKB`p!1Z|{Dc2CFt@pnNL*%7=ng$IyIXbDwh%x~3HMhjK55 zkslu|CH%2azf_A?0fjSWWU58Zo2!l7Z2Xn!q#w+fm*RI|5M(fx5Z zizo0zzd>UDAk@d^hA*%^`YU_%E1lo$=ZYj&vkSUEKIfV)6PuvNySmf)jDM}mw4Bo8 zH4^E3PI|A)94OX9`RqSXkIDR~$A_8H`Fzni0Z4s3>K}-9I(QVMq50PDK}TWs_Ixy- zt?7RbB27xrd}l_pKFN5kkDlMwcf&}ZQ^UAN8Xft9kk7PVvq{elvnBWxem_aZ*N5zn z7VkG6>)1~b^10rjMHJ=MRGz;>oyup7xPHV}I->cZ>t3@hCGHdZ^b(yv@6U?l`!)si{*C)5U8cB7htJ$f=kKJJ z9&@NwhtKEf{EfBLW1cGMqWn3|(ql^d=<@rA)A=({2!@93f#~~hb|#S!=d=^8FJTr5 zVD~E))lb)$bV&Sk0KH!mt6@N%p(-}$d_eD( z4_VUY&8>ey=Wok`x1#B8&E>sD)8CKIN_K)1VGd~h*t&lu==@xQ=CdP;H$md^^=Q7( zG$j~%kN~v4uU&W)2G0|JfAe6+`vgM&qqXoHY^yti_J_sl)xdnag8JvaJD$Mca}Q8` z9Vqn`Y!`n({Xw|49`i+4o4>!4&Tq9ykC{)j`3Z06{Q6GQW3EisM)~#GqQ{)tqRr1@ z=={!I90`%_VQBtk%bO=k};S|Mg-er0Te$`g&{UIcR)Yg!-GpCDriZ>m^iQtt+0ua^HJw@;&-| zHd^s3e9n4{_CJ1$^_U-XGoL7IXz~p%*;IeIIZ2P{8m@`*7k@^NQOVZi zjU4Ixy^h@ku`k!5{iD8pFhq9ViuRA0!y>`7B^1pU>O&JCe|HSpKfY4wLV67CjDEkh z#M^+}E79UcZKLb!p6$cQ_QNLJVP`sj{Wi@ZXRW89^DSOPq3#fkfdGQ3c@4kcPYi9fP7?a!T{A;Q7|NMTAWouh4t_Yj%4u_xJZBxqnefx{%$WolyUDd$j@Ck*tCGhh%;@ zY4ab<4ckTM+bw$zIg&h?`+Aw)UmYI25cZw3LFWtX&Q;*8=7i?ECYz4}vB*O63)Sj# zU=k>PpC8%Z(b!rIb7gsyzk>WH@b%tJw*LaUep-9`k_&y;aMz^h`B(N8J;vj$DnC_= z&S%d?J!YP~8o&2GozJUM`pkenYABx#gY}t$8EX8ba5|rjhu(_vCp4h-Y0p?6m>0bY z^-oS-!C?Dp6WV`HON|8feGtm8*^vbBP>V+A4}C4Zf=W>nYqNyTXOTk}609tP@_FEh z0qLrxj_PlH>u?g3F_81irt{gYa1IHdHWBr=obj>-BCW5YUneaws+?*F74n`_`h!13kx)1; z5al=P{#Tf9@{-kjMd$ORYZvlvo)qd&d*m39#X73!epbfI;pB>4f9{$aozLov2~agI z5N8NT%wP1$q58|2%k-JDyUHkkYf|)? ziHa(Gb5RF>!taw+iv7El)`Rj>rgZ-v?za${9H*i6$=zZVxYyXT_XqsT?_?zQd*hva zK-qo?>aQ}=g5hqUC#tW}8Df7>xec9vY}9K2i#^xS{h-3TUtzJrGqk_-4evsF`TSzB z_a6&N49Gll6}0{ zHy9?)r?LD`erFeQti7Gpb)w&oba-JvG@QGk`-ki9B|zTEFf<>2C7%II6%orPrIAyN`Z;R88$j-j%Uve^}t;M{eJCLH7r~?0YSm z%H2ToUxh;pVXoOkw0~^r;s!NsHYh)xM)|c7 zJL-$@{%~br0|X~tW!*C9{@d2-8?5wugz}-9(1k4j`Gx&8oz923fgwq+RpRbPUiq&- z67Em0OVDRrdMNQfj?>S#N|8Que2fy`)gYHzpKjLbGck5b==uI5Wx%Z4uEei-KtJD? z-b6ygK3_B+miw3h{!cgZiAA z==L|(knF!pE_NaH*V|Y-KRTbg9_cf4aus>_LFaE=lRi^=T#>h4Pv=j*O`owor-<@5 ziZNiMq`UA7ztj1<@S;VOr&&`zZj0J~=R@ev@5w{~w{j!Or_7H8c&QtL<`)B{GoUFl z8hxK%ck(fKrILjD*O8M9$&>Hm`+Yg|^Q*PXl8je1M)Ti(Zg!;apOF&tH6fqFy#2^_ zg#{AzU&!afQww42MG@+6qUX6mx%)I!KQ*5Cz?@U_(EjC-Un%q-orUISvD2=BoA~>h z*#6F!yat#x_5$h;mn3|HZzXl?*1H}34JY99_xUd5Qs{eBKSQJq7`40dd}x=9zxk5n z{Yd$t2F$!a@)G<7fVRZ>A8T#Es46P($9f*7>L*!Y!0a|r;J-;<6w&ryOb)b&94afz zvF|ro$%eoK$7QI0aZrka(5Ch1`)iHPiEtq}2%T?S9h3oUG9uCatj2kU!w7=S+`C6$}2n@4djON34Wuu_$Yb zXMpTeNNgxW`xCW@ZxHEqgZ+2EQOM`75Cdj@fGmG3jLv6TmI0%jB8&2OF4kNw$G*R=_|OePUr#{4@8oCZ3lopnqV;KGj}YMR zIHUQ+^vO}M-(n5w4^B=BT(9^PPN<$k_h+O}888=$WcZ1P>HOU~Z@_4umqGdB-x)A|uVhd@ zzeyP~Ri9<}>*MJBwUsxELTB>jizzx`npJ_3^WI&p!Gj6?HbsK-(SY+zxmG1WJc~Ru52&;eC1v@U}7Ii z@h$~)eiNh(nPZ)#`PbRT&gWi#XRyt;K=rdiX|?!$b8CtIQ^==6sV}%HPC@y+GcE+) zEVXA(?)ay_vJ&S@#qcSVi{Jn5Y(>vMhLnDT;EbzmusQdi{-+80%QL1*Wb~K@w7)FA zXGm6l{>5Vb{pmlJOjs(o&NW&xYjHR-*B!xq$j;T+3tvf4K9mO z{}L6R2q!YUQ2)YR%79@#gV6bfT+1;Sl^u!pSKUXIf#u@_RA03#H;eO&DO{?!NBUoX zCG^jW>wnn~?sgcR zPm^WN(C4!mTAvP0T@B8!M@j5=2>A?q;tMI_e0tB~fBZ@A$B%Rkfk^M!Xnr@Q>>5nE zk;$HH`**)jvj4OfJ%z^xCsBTFMeWe}?Inr&A0Xg&@en0)y1bsvGotI~I0YjzdiHnr zYc0M0FH*N6fim5>u-Wwd|L5Ws(Z!=@%SY$X`E2ozg1R5hXnojUnFzLC9_ak|ad`&V zm<6EqUte7RPb}HVs=oQB-;(!p4f~bBwzxR9?fbv}Qu6!i>lEzBk<WWL-awEi2E7&5;;eU;!ZO^_e0dt%50ntkI2rFHNZ0FvJ~@F{bK9cxTbeGEOc z8g#~tkodlVkiQ2Te8H!Lp!YKp&s~F-rRnV9YC2zL@Dw6^3fUK`bbZ|Z`5Rola-Mx{ z+@X)c`t0SPMDoh+qxxv{)sR5&7Z#ge*mkobr|Y|+@4p=U&?1^`eY*VP5Y-NS5J||p z)XL={;M{i>s{avbQE(@B0h*ufKa~jE0@k4VsCYF420Qqp`LFSfV{l}47`s)bgD+wK zq;6zK=Gyk*wzSdt($L>RT852B`HEky$0(b;<7&1a`0wWz?hlS@GGvbK`GoS9V`#(- zeg26{D5vvxEz%i0XANQw;2nSi0RC`>?ISrzG)d55!)Ld(fX`0 zyhWr^cLJ@iW>frNvAhU#ed!xVab&gmuI4}9Ok&3>Os zeM~_kTdM&{x2=vh@RFB!V<28qUe`w}!XV@S$0M*B=0R^DM zgrfalgnJqMdA%F;-?jZ~;MnT@==`i}=2N)&?Fd?bQ(W5N)~QlfpLFP>kk9jTTSP0G z3Q)fGURwUUzxOanAFF|EW=ib~Zn+}; z`(1ImuSI^BkCtn-ApUI88W_~gOd`J$`imR0{UD>?C_KNa2!ZM1e75$%KmRM)f4ymm zf?daLQT`67CBdzGuIPT1MU)cB$*x8F|F*$Kq^j#{Hqn#rU*B%ABAKh?QGN6a6#GBk z0QG;DJ+_eFJw~JX>I?l$P`d4j@>R5=06c92(f%nfs0=d0BH8vA9sU78(w}a#se$C< zi6~#dJ%z6q525}o^LRTv)jPu$&F;{r073m6CVv0=#)>DL@&070z7Ia3&HUh>a0iaF zqK^5Pq<>xPun5Yo_d@q`9-dtTpXLo=Z=LPnL&(?sV}7t>k`-ECn;wP$TS!p8?!AkG zRP&jrzq^>AL>_ooqyC@@j7aU~S13O+ZC2#%fzDjtXY~GOVYD4dw%6kxHqrgv<)kg7 zv)u^veSl`2BzUCmjMo2j+f4Ybv<~gh6K5AdY_DzT`x-&#%AmwIg+OugIJ7@Fq!JBNVH&DWLEVyI{9#9ld{Fp4(V6&mc+q;2 zovqSwzJ&VS`G^uJ(5*oEyCJThWl7Ii?EOJ`gAv5ZuM_9?gU+90i5=;8PaD-Qo0D6} z{prI|{mL_K7R_9fUA}Fm@_&Cn;e2?~q)fQ6%njAI-3|rt&So=OKQEswgHI#FP<@*c zR|5&%Vp0C|x->%7@ia6)UNEU0HvA}L`=)gC2U0|Gf9Z*x29s5M3-zCJ+ccO%pKoy= zNA05KOXK!wFgFcvb4$jS{l~AApno@Bun0uU3{ieX>T6(n-+mJLrm%l1J?#f2Bh1nI zI__2oTs0ko^4ld(iD)WcM*W$spAkt~(}4Eh+Id!F?_g>4`^{NZc4TLQCfYxYQS>MG zs)ll-&d~jt_;RCY>8s50_w!Y#d_{hZg0D*^q4O;rizL{0cP{Erk0)osnDFIjJ|Ey& z0MBl2MESI7ErW?qLr{G@zqbY)=Ekrl4fOnk>!;3`JgPzYsvW7$Z2MBf?KO*_^3}sd zof$EtmRrG;Qu&hGv^dw+4$@K@<(}zfNI)~0{DJ=J<8wsmu2Gb69%FB=$KyvbALsn{2iL$ zPfYVox%iv(^Jn`;mD#bNf}5d#j>^}lYm4BGo(}5YhUlz;x#IfVKlERIAvr(Po74!} zAijT#?3cQSx5L(-MklOP+I_SDT34?_{oj5&e=@piFz3M0`S`O` znK^06b450h|D8`M!Te=ln+j7i`vR(O%YLaaIW8Btr0?6Q`ldgvJL7%j0#|agn9AR; zszuQ5tBK}21?$$p!y-epekQ4uLpubZ`F_in8aU${iRO>~a~r|ME(z_QVz;z|eqj#l z=+>cc!v5)9ixMfieGZ+kTsvz-zE<2u>o3>t2RkkLqwf=%%Z0-0qeId9uQfdyI{R3o z{m+OkNx&;lNBfKWQJGM*%@NJF^*36PYtuflKUUMv*JyKl;?mF!Jzq7J{v_LD0O~)F zk5*=u&MM=KK1ERZ3ocV;I{z%=2K@G+^5t?#nemn@NBL}dq0D3rE$6DwoTc&?rO_hN zcT6cCd5eDjCsZy1$2v8%{wALUW{ZT&8zpnuwrJZPhFBi}Vf2!kA zeOu>4{l zcFf=YO!$6tH3@|$4@}Yiy-_t9Ekmq{8~LqnYrLq!qtkuarHm{Bh*jx+se$1 z>m?|kZsLD8xKYC8_wuFk{ky9Q)1-Hf3%g3^_rpjR(B0Y{-9J_JFM#e}m$A2UJL-#Y zKK0G79NrA^Meo<{Yp;Q@+#RU@c)g|(42@#h3$6e5rvNQzop9KJ8VuqD3QMi z`3m`|MCO~FK=m(2-vvClsYskpFEL*~ zQslUlTOIwA@P5&S<^Cl3mNCkg?iFQ5-ux7|eJh=>vtx~zrbAayz8sbtF_-GDa4?$A zSIL=72$Y`15~+XuNcvxw#sUcI?2OLeAN!U=w44Xp->*}u1)H)!wr4TDzn{r9!uprd zs6Xs)^BrV7_p`0l9rahp-&89XXn)xS<;z>FUvg<`68l9${n{VB83wJ_NBfTwt5Ddj z)EDJTcULqR^)^HGOWv?6v3_}sT`xtS@9k|fBD(!9qxratlNITr_>9%(>3rQBZ%;^C{i?f**W>&{vu=7{V?l&_gPj2PWM7rB=c z=zRH}N`kmFYqY;Ne~<~pa2o25`+qF}wM+9+{z|IL;nbPc=>Gh9rWS@}Y(wko&j*c= zA=YkeKWCM#3k)?;K>3o>S_|H+3d&c5m@i{H9kl-#pZ6Vh#wMfsI_rxP88j)6%}b#B z%VBcHWXinrC_h;NR>ZpeF}wIaou9)K>`Aq&G?%iC&X4yEe-huMi_TXfmWG1qhn{G@ zwdX)I*qj`Uo)5$4N#N66y#H6%;h#Y8eFE*rnINYz3Du{OqY7b4i9LG1Vzy5?3`|{) z)<HE7Ea*UYyo*a5U#_&eWfZZH7XDR)BaMN6%`c!AM z{|TM87Fs8EL;Hhqwwoc+LlfOkYug_RjgyVh{N&G_Mo?T7j`~a8M{Q*=I8^e`rCcbB8}vqaqg29A2b*5%UqlrgaOO4i2&-$Jl4nT@^=Y+hFmotnh= z`;hzd>pW_qY1BqkpHv<-!oWA7?8%26{!I8j^PI;<%!AvdD1VQC88PI0DK{aQ&Y$vB z7ud(kp!>PerEB4>TNgC{RtWwMqQY2-d|FtaW5xYP^OG#r+n3Hqtb#Fd=yZ<7-lwhI zZAD5}-eucQ(fR1M+MfIx(9Ztwrt>kb)}M^f(clgNJ)e7@vl)WssiFR|GCvg7)#;<> zC%G&d9Oe3=`j&ey2^QrIm6&e|^-W4O3yRl|L+hUzDTE1gW}x|YG+Pc=ZZ1UgkAdIC z{xGUof)C;TY};UC=E>z^PGesOAHw}v3s)C7W-f*D;l5-oBznoC^{;MKE$CKxp!%xU zB+g%c2eFwIbiOOu?@+QQ2K9gS23<+8V>-J#jLuiPg)u46IKzHjLf>B*oN7h<%Wk0h zb4$$EqWm^i-=5Cb-K@>fW2FlE{)s3x6xbXc^nOq0htW`dzb85$Uv)nTx*D0H`HY24 z7KFVTjrPCe?FxannS%18KEt2%i|EdciJ-sVyz0FQ)7c@58*nk|Z+|0szkl^)W5%qe z2<7YA0%K?~fwyZ)i6(g0E8m8+?e) z&*UTDp?7+;#C$}kPj5$eB|&h2tvE#IM}N98DGfb|`m4t6R>XPrHCEA;u21XE+LMA_ z?^w*Acb9hoSpU6Tab-t7C)^Ki=)Vq*zLjNF_WkQ`CFesA)@=cq;;!iZ@`Sul7`aLl zbYx1m6fA%PU3wbu98@KUn$M?kpK=S)WGXBO) z*zyx7KiTQV%#PhBIPZIOer!h;Lg9n)65kIK<|9Y0mO}(*C*l7B1p8lo;%ecp<_c7w z+_axT?vgF2KA9JN2fg?RHZp?lk8~}%l8meS(E3;5ZA>0rD?sOOCb3q;Td4x&%ixL& z_{x1L&*|U6hmaqsLUDi6ERFidQ!}=}-m{8mez)aHDEwHZhUUxBfzdE7PmgW4=-^kl ze|=NTPsY!FX#I;Gp9N08EztT`GRdB7@@ZxtHP`&rAIbNF#`^k`lDsaQejr`HhUXbG zoz5LY`O+)Dv71o7z~BcoG>P9|NBnn{s4EFiO+@*c5@}5I#^$5*hwfXg$kYoLS?At#{j$t* z`M1Ht6W6GP4FBpqMk{ko@l=3LkAhc!n$(|-T^ zQbhe-r-$a;&@qQm{tR1Ma3{hKYYJMQcl*7+Cz^k2#}{&7be!QrKh?i1Jr+y9!)Ng!@ga5q*H^; zueqK->Yps^51-c1J^k7I-RUd?)z>%t{rPNtJFi&`jf=nYe?MXKcjV0)czw7&S|49} z9|8NONYMQL@57s6KW9vLyVw5t`u(#;gO!kBZh`iHmzsML&-ll5*IKrIdAAH9MZFC4 z?xTVzK324~;Oxrwqx>lPSa72a4`>YS*!1VaZKnh6iuckv24C_rt4?eBU~{=VJY8zdZ;7vg+u?$57DUKmC{& z0l|kGq5Z9}?XKihXfEwLhy}qNAt7)CY3@zxr_$JvFl5zhYVc(@AGGe>-0mMAI+TR z2Nic-@Mj0=o{RORz^@t>eO`(B8~X-H$ZPXWG^072pH~;n$q&0-XnwaY)s@&RI6;d( zUH%<^#rt9P{XEIRg<6!KksE_a>Z)%vx(Qo#Ay>>-Tr(byYx{p-oW#t;$#l-O`NF`M<7v(%{~1 zb9DaxNx(5ExYwC3jAipRaMRW$;XP2i2d_n#J(8@(HRx z6W5f&{CU$*|KrS%YG`J-6s=E{vn0f(X%re?zn(TH@qS9w|BzmBB_=)@s6I`e?@7Wp zU7C|}ksEIB?#soAS!^Yt`52p+C@&rfVz z`~KhUG^cfZ7>!Rh=C zsD9<#I|fU-*rWd3fngL#OfNnELcG70&_xTUVF)_k;pQa+b%PtIKX77mDZCjp3FW7i zvKl^aU5x6}xk(c8_F_1yPyeQwlhLOVP=EhUjw{)3bC{~0v-N4*YELphuK?xeu3rdw zdhsnC|KN{4iN2p5V`9lI{*Zw3lQhwi>*}ygb23lIPl~Ai+Sb(%E~h>~>kHSSAQ=1d z6_0&?qCwqAsE+xL@-_PHX1Kq+K3ZQGu2Dksx6M%hZR3_S@cL?k=3mD*AA{LNR(kp+ z&hJ}P@zAKunRc4U&c8;q(1NeG8>(Nfk4xdS$9S}VnCVsxX~FX-6=u+N`;GehLopL1 zBtsEOSAIDA=Xo=|`taRBb5hVcmago=_U}I(bS3Vu_EG!OY<|u!^(4k+XK5!XTYs)^ z3L(CoUQq1&g{8ACxjUO@p9Zh}KvGXsZxz%7A zDnsWVm-|adzu+~fKCLe_CmK%$x*xbb+m-lj+>7${VZA4DF3d&w>Q`4zOy@kI&nEoo zKZ@$NF-bCbXkUQlkFzKFK|-q=sQyfS5(F*&d5H3{xhevdPkO^+^Ks9;72uUq$!{rV z^U-y_5>h=IQb(`a{HLMb`}xs74X#~oL0fLDeXidhFSP2w?XugbDLIw&=l$02ABCq` za=xVsz4xm`RKI3tSaM^_6&j2As^9awp`!bKJD*x|UD|KaEHo`}`=7pu^}ExVW6*zc zd(^*uD)8B<$c{FPW$Ryq23j!b>O!L?v-upeqZHPEA4V#X#Q21Yfb{@Y@*orzY8_4WV}@}H8{l9zuntB$)oH{l+WZLAtXQf9z8qv zPy7_|dGDwUo*&krd@ktj2g6OT@NZIU`O(*}_Fsd*d(mAzKE?Cv4Xq=gOM_=mq= zfW`wp@tFU1;DIGK!Z{k{C(g)#Ru!5{>Hh)G?@6RDLVi0r1%)D zHfyWrpNajAmLn+)aj>GTL)d)z8E9ce$L_T55H??-Ii>J+6QKHM5Ks-L$9hux5p2Gc z5fbv`=VDa>E{t_zLI@quFoD|E(eWMXra!;EP2))-;)VTNgs*wc<;2*qkUDnM z#rHZQ{j5LUiZeYIuKDZM@!#<)MHIh^Laex1FT*vRmazGm)HD(fwkhU!jn(CU0Q&Xm zfe8u-Fnh*h_pjWulwe`>jsKXY<3r5Xjt^`?!<=HF6qIO{^4N9*FJ*uRbXyBhpgkD%Y|*!mWlCn4*tWpv=wyg&Jc ze*N(MybKmCJ%-l5m6d{jHb+h~hwJJKF@GOMxstN{7&qd`wZ2#=VO(o=?c+dCb*?i6|OoNyKbZX>i=FlEg|i0PoP&i zvGwzQi8*oY8-Vh+r^bbRuZf~c;Res|`2|t@wEF5v65b`F`gpAET4EsFHt=YC`_F%` zKObgOX~o?&T#EAZ)4`g{9lKQ1=#GvbjmW?2yF~_lO48ByZ@#-9SQuvTv**?3XZrO^ za8;0?Z`pjv_1fq9{&BK>B(xuM9@W3wLVW&UcmvhH)MCNkOL&6D=R050AY{`=l&?V! zDhS$8SFgV+&i@MJ6b|2NispZ_dkFsVO%wX9BRl`wEh&SrHg;(JaXGsh4z}&Bw;wH@ zuM8COzkR*NP|JL_zO6lDPP(Y)QG%=%2e+>AgVqxc^4R?kd1x>U(40X1+4H(faxAJ|!rw z{>Q&?W5?epvvjzf^@=zB^ZjaZf4`2c3W9yBcx-;8PY#9sQbW}Lv+>Zv&Ei(5|JQSL z85Cw&p#A+L_o`v4aSycqZ4@gZ2Nn*c1}EA4NqKW(+gL^uwz2tp)WDUj`6j0m>$3TK zKS4_JdnZtDs*A7U`LRV*PPi%+T^q{I|3*x==ElvLjq>LnZ_Sw=pRIY@=7QV*^i`~H zh5cnPGAWUNKa9;+WP5+u_A(Xqm)k852Dhkx_3}HhKhwKoB$%3Jp?nSRtALl4d8ohK zr%(w&VK;f~`y&C4=}?vP1m!EEy9!p_|A_Jxwwi*|x_Z=l5ZhllGEfTh^l_cC(NzYKmGX;ejWweq-x&Tn9bM0)mq5E+X$^6o;sF+ZEPDfKl|LI22ASN zqW+0nyo99O>P-t1*!uNR@b8|4jibvZu=(n1>`Gn)`_Ud1y7^0S{CvVoNw40~beAK0 z{x!JKTGHcXIyF7Y)~~>eGAN6WLG!B>`F_yh#17Q|llKdTYJQJiekHCi7fy+UT}_Ul z{-4<>1<0ySq53oLi4uxepF{O$FSX_t4e-?T>UEkK-$&lJ=A2}ndhd^ssJ`yg!iF24 z>Zz&nVZT531%G9+$4&lKN-bad{gDzo6)Y9f6Rk)lhGhIn6g<*RSVOCFH`Z9`sEbo4>?xVZSqCBt21w&0ouIuEhHB zT)MIuJAQuHDkXnyjidt~>*A+a-?GZ(evgU?IxNDl&9sFHC)FJx)C9`sC z?)ye}P0k+n?_1QwhO^9YM}Oa}0XE#Ga(B(N5ccmo!^sD{Mn|Lm(wwILP~A8V?cX`< z35N2*ooM`BEQ^GquymCF(Fz6p=aqrhuM^cu=yg38)yI8RX^=nhGRo(y9xCuQ_z> z&Ls*V@vnKTzY#P`@K>UL@>u*03oCbUOxFcQ5VJpyew z$+%$}_g!qh`$R;7+uGe|e@6zq`x$pXDPiodQ>gxavrGqv&v`s{-|=}r z6{zAF=tBbU!UDGO0lM>j7oZtzkpd-y7DZ28@eZqx`MNmyo-UZP5C5 z<6NP>UEYs=Jj&*8*CJP9+(}9;N3r#B$Wti^Q>@mD&tiSt_t#pIav~m$&&4ZkxS#I_ zX-+rF`W@diqW(iel?~VXFE`E10`~7e;=K$ybP7e|`_#t%pqvqf@*A%f>euisD8Jvw zN5aDKJJ9@Zai{_Y`0PRJ*OZ4seevyIw0>1MrGqv&2j#2lP!*gly@2vHSVKWwei!9y z>_#ngj(E*u{>h<%W#HJQ4jO;Y-l~S(!hH1BvfA$#=+8&Jh?5Y>noiW)i>+@L+M1K% zsvfkZDVr}Np}+O3Xf*vbkj>YEM^X~J-=9u1*5!XfQD4?4a|ME+b@Pajxkv4Y=hsLTJw{>XJ-f7sAA46QHT9SMf0 zgB$hg3vvFKD&&tNyTqb=?Ov#Wi+m!QKQ64F2zOfTNA;_5!*m!}aGb~HUq*SWAhne8 z*nPNO|54~TqL9b-AEqtWLTPyk|E8k0{?Pw^S?P!}(AN3NWBs#P7B#Ttup!z%+m$0B z%ZUkEU&IM~^*Gm=1~z5$WgvGYi&6)p`t{?xl-xF%i|SX6WGy*1a|6oP{x3FMy&Pwh zFK;tjZqjpSO;MAJzx@$0UyH1KAgO^b8h-~{`a`(ODpbGhz666NC0x&c6Z2Ia90}oh z(P)15&_@B+&d2fC{$k;EC7hkHo1fjRwm#6GuL_=;4lmjs=CS)+2U1lqXGysyZ^QRM>X6CuS=aO*!q>F68irEMl@k1 zTff#dHzzMzSySf^=a~7~yBV&;Qr!=&AAH|PiBhViKlZIo!^bEUoM-~ z#JTrbIz_qR&);vXH{UjD`ZeM(_y!%i<;9=pt@WOt>}Jb7Zsnlq_b{6oUtiC+R;vp1$aOB z2j#Ql1tr|Szn!=IlKuPtUpzmM*()7dyxz-W_iBls()8l&|?tFLBc?8FWjWr6DJjvclfBv@$Pda?QaP$Gjz^(UeIjW|<( zc;Ge*<+qDA7(5;Zpz+&kO(cB3Do6Wke`PD+yI~Ys|3XSU?Kih59LQX|K8oz@De=x=54*$L$o8OhzHLzs( zTORXgn)4EJFta|YuK^E)@9zW|)2`th%?KcaO0Ab|e-Q_({y={RdR z>d!>_$w|)Z#kBT*jCj7~`f*#1oG?ZC>aVrsg0Guu{N-%E=D(3a`0PxC<=yO5N*DYn&w{Of7;amDfG(RL0(xEUg4y`{7 zW_qz z5^}SCC6Cn~$A$aWH)c!d=D*o|eHD~D`&bwxDOV{Prk_JEBU(;vQ~wm`gN*9Is|1#^Zf&B z^GALCdbM5!Um9#f`Knt$!T#PJl&|Z1wXo;E3{<}=e9K_cFb$d?7W`KYL$izcu0o2y z+W+}>RzkeJ-twy#u=B$km1cw+V?h0q*?fH(>Pq^hwnOIV_7r>{Zfj(P6*;{h@C9@poo(JML-MCMbUkN7!*jGn!~NT+{ILK&UD~A(=3nOW*!`aEPKj{4 z%Su$=411(QmqF{%`nTL&1@q5t=4X(CCho6E zsFZXub42yc>Yc5O>kO=oo=A-(zqIWvDD^{ZXO^#K;>HF(Z{rg!;;gZi5ls~6DE%;y9 ziTcL_29?1g(?k5@54H0J`uF*_Osj!)H_xE_sg6j9v*iuGaTm7!ojhema#P>%UEAvP zPrRQo&Dxa|H#Vf%0c`$mZIhA__Gak*PoRx3pCa5B!uI>exn`0D1EXl%=yiYeTc1B) z2OqfK(GrcH8@JnWJyulEM5U?Q|MXuRpD!J?ffdV z!QkrF3+1nkCK7DExuN}wxHSrxkTnX;@2;98LiUrXsK4B0Ksr>+T7>eKx=M(@3xm-5 zq2fD*w^yRj`e9X;7L1q0q49UAXBj*+*@M;(O$OIM60hPhe}+$ykm}dx`NC#w{(9Xs zBPIhL^Ud7Y{K%G?*nG{~>jQ`K+Mxa0`+5G5(BBO8pXOO_5jcY2}zOGkwYG!qx< z^*2Ctf2ZyZ3Zc0{e9vFC`J;aP9aN}=pSL%l`WHT?44fAwp!(+_se%4{8h`0HJOA@n zONfg)leg{9=5ISSBYkSFqxu)#+?6O>mGjPSZ2ikDlajq{nxglW97{vUxo0+1nxVTt zA?B~GZ6>)D=ttw6*!+!ZZqL1PDAwZ-MD<5;PkU~bS24};W%HL8-~&!vQ`DdSywo2o zTen8_Z$sA*X!y1R+F$FM6ba81wrKtrzgz*ws=J~54Ho(z?H>(5`P(!s9m?m9LiNuk zP6eS|y!7}J=YIirDAbHyg!0Gj)57d^a{kHn+Wb(zzO9&02Ax_(qx^y3pVXBpd7pfQ zzibH^SbYeMzm1NVk?)%{{OI!h-|U-tJuajAw^u7AkK32?*!{ucQF7AvmP9Z9 z))Dcyd~+soeLae1#k2X_5@XNFOR`Y@t{=4LM$}}{skvkt$+KZMnWA2395gelnO8)#%TY8AD##uEiKUc*Ulpy>Q8Y(_0K0s z1-B4MX+MOREJ%{A85B4gO`&H_8{~FUhC|HeFbU`Y+Fg{fuly4DWM8 z^C!R8-=F*|$&6&b*vtE#W9wguFdy%7Du=(&o*jQNVL!4B4d8^r)1oP-~awlH~s$HP-@SeuRMhEseWqD-R*Rk zJ}+hSd3U%lpRnaNs*eVH{b9i%3piLu8&X6tpSgnzG!_?KUbJP?HSIOcRb7Fvs}mze_W5_%d6OYPU_)G415pr z%OMxNeHAR z7OAoOda(y1q4SdxHMU=VVym#ufEFW@8^SRa4{UmUzy2{&r>rbr z%1YYO#{=2?T?oq}%dAc4vX^Xq^mlgPMy%bar;p=A^^4Io2kz0{jWnh=n@{U~J}_zC z5j8fy<)RS$!yl*A*nRMm^Fv^k!C5tSKW(i~B$)eORr~4P7uUakkiAy{w#SRr*nCX~ zE)fQPd!@$qcSn1r!`HwnH8#I>VxdsKI5*_a3X5$2dq2hbW8cmi0Na-6e4xuwEi7Er ziJx|cUBA>b6XpZ&JMq!m*nH+`tHE!@K)$C3o6iv8evpmZM1E)QO_*ODa|YGV-FAtv!v3-vyZ;j6n+}>i#cFJSWKXmT zsLM-r?f#OO&qhLic_g_?-S@SQU-5m8=PE6X?9>S5)4-<;NS-kozkA-U2HPTQluzv$ z3Gsd4iu#Lt515fVrS52c*-!Ad?>Ae_H|xpPPpjurQsK7=t#59vmlHlB4b{)N2eZht zA@BGSHJi_Qsw~pY;~g)x)&2b-;;v`wlB==r zcU&s;hsS**)!2RVDJ~)4-a&!pmrKJVp(=ly8uK4l`YPa-?{0PDIClS8Uaf?A#z)kT z@3H5<9{Ht1SW*_s=k#0^>}XS<#^zs(>S|!(soQF7zb@*W7LGN4smA;tciS@9GgQc* z5&fLps0PeVH|2kXvi0-nzY?O%@4zeHv-PuduNfJ=*cpxQDF&`2py5b9yq=B^asO}q z0V#QNz?a|E`TFnpA)c?kFj-CxnEu22)@9c}W>2z+WcU@{y^_smC#!7IOL2u)UDEyi z;`&Ec?!ei}`s(p16UF!M?Hsw1Eq&=Hp3UdG6+Tci+Y{AK8sra8$H~zAv#NavWS{cW z(@*jIY|>sqKi3DVvHj0qLVZ3~5rOJwNQXpN&@M)e`Q!Nk>0q)t5#`e_PzB0W>1r&# z%fC=a&p)ol{PC9sTA0x#59Kp;g)pDk>y{ep4{EPe!?^fYYULm{pRwB|&B4Z|LHyn9uizq@-#0p(vmGr^-pi@Ve<0S+HB)oQuzweI&YnWNqxoDF$^w`TaW5k$Vu( zfxdgf=J%tU5A?az8TFU?*!#owF}>8ghS&CQ^zVNh=obRN7P_JO+BzW;(j7;m@qf55 zpLnrlrfF<_ zwNEx95rf{UvHZ0EM;9U=Z^(Ce#OAl{bSZHPGUL59*O>YmH$YBYk_YhbAF%V&L-Vsq z;}IMA9noxlQ`csbQ(hbSJsvuK#rir%mP020+Q=VSqvKa2;#cPF$PJxP#n<+~#roTJ ziz64ivx>JczT)=3`ocm~{|}wv1MZnWaxs6tQ1D0p?$8jeuP&DbgW_#7H8!6yE-Dh{ zoNtTf2fl|DaQ~<|T3@{s{HOYDyP)|&;!d98R{8Y@ZhoP{) zkSRs;gR`%+VA^wm8rzSF?q3E2y+TlaV^XT&#F}Vzp@gl!#%m;`GHR!~D1y!J^zCM3 z&h!lR#+~f?>PdT7^2zj)8uLffq(XmaOt?v)?I--CsTeZ2EKTu{tbb=BB>__RhE zXdl}Y<+tjL7P7)j)R;f8N$9V8thH7Do5R-M9AUp}%m!C=!d5oFIf)XocEV^i<`4AP zU`AGanWG*V%H}t-zAL#sI9xsRD_ehkwn&Nb4W+tM9d>^E^JfT|lYLtKEso9a!Ln>J zY^4FOHeUamKQX@r+piME?N)o@ow=y=W&Gv&Y(87t z`@oeAwz=5%H!Yp~;qIMoxmbP>X&C}`8~f(g`m5sn_GG@`uX00kvHRQcmle=0cU&$u zfBCmCUw-+$4CV9eoOG~g7MP3qR~30GXgXtEE>?d%dqtsXaCC01KOp|T1i7jOiDG*$ zR(}Nv`>n3a({r)>;M2!y2$^>}7xP!0h5gns!>{DppJ40ji5+GnvFWp1OkaBo_vc&& z)mIOE&F1rBv6KulXs^cZx90x}A+g!6dVGrepJr}3Of%Y g=ap8SIcN1}wg18kOgWv(om7T36Tm}k?a&@oTH_wL8U#l zw@Ul#cl&sHJ)gJRIluQm??0ZmYajn3rz$Vh9oZ??@t;3P z{J;No{?~t@CZswH!EV+kxaTI_xQ8A8_xrAa+I0q!vp>o@p92i$J@@Zr0Ml)yuz^@* z*YobY=jeT4!NcJEH&IY3a>e#dXc-Qm)c+aJxJ=DU<*GeZ)YL_k5061cZ-UidXOE)@MK;-t)(glaXc226AsxQs;Vrk-X=TMoHkS zwgIcDo$UPm0mOOFrR0;5^#ULArq_ec^%6*m_q_V|L3lYm2-i7?*7xN-zhhB>(yzsn zVb8|`_xq3HJvVDEg{)t3Sl*zf>+}2Zo)7W(fgUewAcoBmo$Dn`rFqY@(HXcEo`K)U zE$k^55b4mIhq#@KopLi@`wN^YZikk?i1S*i!9m*YiQV=U3&FQOVMtq{kJy{xtt+ zpeY{*lH^_GUH?A5zHTp_41Tdv_)V6GPrklB1Q{cxCMl9xN!Qn?`DXBQ(P(_bo?9;= z(ANgvIcQr2^cHfUc|$B`pM`sVBF`2bIJVg!)4V~x9hf4;sVja|Ub zKp$JK;yxdMudmR3iRkXGb>zxEy1rzttc6f#bEdu$b(2y5@(o0@e_!MO@dq%1_x%r% z^oIibx!7<$ryl^m{u+HV(bCm{O#KCfhr{{krI<|S)(iEwM=J$YT5TfB2&X@P6TbfT zl_x@8$OdeNx%EQ*6|G7}vwChMEBA2v!@$?yz5IhPx{R$qi=9W&jJNT`Ihn4%80AvP z9utoXPgHmPefatdd*6;sx}E3gFAnkbw|B{DsLIN~pSIL>t>^1cQvVL@*DJ#x66yN# zQ~3tBOB=BJLb`q`H}*%5i=N>ggX#L|S+0cU-t9@;PSN$#Qm=t7rw=007wP)h^50}w zr#%Xn^6~>;Ki2n+(0HR!q-GmkKjulMP>V<71Tl_ZVSchcYlBX_8$g&39t>@>b zH+|N^j*sS8v8}4>_v7a$37s5d?HNKcMrT#i^y4vcC-l297e5{>;+L-beb-M$PCA>2GU4H65M`xRD?J&(oP>pTBG!u(RL-yeM|dXA$JT_0X^mC!AhUd;UR?x6-6 zo-9H16OVTN{rUN2jjldi+A<0su;lm>1HL}&{u!a}R?@^%dvDizzJHU~G=&OxCHzO0 zTQAHnT4!dVy)RD2 zCY9Xh3-xhnZ36NQTTh-;_2^p9*T+3aPq?+m0zbS%*N4=vOw`jWn1JsBsyLc$>2HdM)>*HMUIh3#!YV(35aRz#{2T<`Z(-y z3N){?^!ayyKjfF%imy4)^>MUyG;%)Q zi&y`Ep#FI=MH6XP3?^TTD!M+OuaDUZ`Vcu?nwLL>`dHb`7`<1QA?r`l^-((96egG} z<3kA?pThjn?lKFlo;;pZALjJoZ^GBd$2+$0_~b;Kq)qo<$)`Ng3WaIpN;-7@{z83( zJ3E2eugQ4UNbd86`sjBf0jb6K5QWh_JJ*W|>KpNA9x%w>l9@lAp36kGeL@JxE}`n< zZ`*cgo;#nJKgzr^P>2jWe+-QbgJojNnfasN?o6a{FPOBWeI_)0{0vKgv>v`peKd~A zMtNgHN%)&Lo$H1A*uOFZ>;{D3a&3D4Xg5BG=Dy4#twZSgSa7`<6pPvV=+;yZPf;cw zV@3B@GL|jyAonPCaiHsCOvM*CVS51|N}=mRVOu|xsPzJ?$kO%kVBTmn%CI-d3grBi zP#-sBG|{rXL&zC@u09vm|1AxA&{sl+SN{w3F=gjeB!yN- zmU4VP0)G8J*KHP3TA@zbu59gG55U*QObc5$vQC4kk7YkR(Sn2Kx z#+n6qxq~Qv^ZivzV+Jy@W9N@cvSCouvK%iQ&8-*ak3r+ok449G2U6|#`aL+SwPoE#efWWR}jMN4-C&gi)16RN#Fi-ecbgdhEI+OOn>Nt8-qZDQ!&DFQf@JW<#~fcmeYBWNMc38jN$4uNK0<>KEWfLQYgD=TFVx4? zpjl}5_6fxP-?pyrhp&%^r8bc9RfAc7XkvGi{AwB*;ce2nUYI{7PH}{}PE(lqV|0N# z#NV)D<_E==MD)OBGXaAko%J~u)aPk${lHUsA(Q{)!Zeg;%gztEb)g_0y#l}M$MFw> z{+PdPI`S_FBHq6_{{030v2G7{LvXh(%=-N6nM}0$Xeb%Gl+M3aQaXh64`t?u{fEw? zAzN}tnk$`u{q`bQe>H(wpTFBl;EP5UlYjjQEfCXm3>WO-_!jynGxyJseTL2dwA+1A zT%T9W`XVe!5zQFdhq$e!=ZAGCG?7#FFmm3C<5QR)4zJM#n_L-YeX+FJ1nrxzNRHo5 z>*9}}AI6&^s0~rY@k_X$pCQN(k=C=(`GFcl&UFWs|L!U_kiAY52mIvp2f*)Nxwx)D zGp|h}!?dS%t>@x+5H?vSz3 znyC+khY83)Y%@`?k)iglbe#R5?{&65&dp0h9#w38c&`Wr=SeGZ;8#(7!|xxTT$ztP ze2pgcis>f*`~9&%AAvh}L&C8w*t$TZFMj*M14Phh{{64O65WcEe(-o3)Zz3KU(cP~XWVq+g-Za~+^DqSsfL3{*RoF)4H`SrzD zU0q1 zUz!Oz`dUo?^wDxVy8mE4QO4yr6H#*wts5&2!%gctMH9H zj!&U~IvJdg9=whrCCfN{2=m9dmU#H7xD~ISz^xb7-(%L-qP?3lh+jBe9~*C^K~)<& ze_TCv0Uc>POdJOqQuQGd}(`D~mNPxnt@Znxmen&bFQHod->JogjW zPQ1+2$2sf1=wSV8raoGZDWKc!eTb3+T_0)@TIkStNg`h>`u_O(=&@G^3@*!Jw-p>; zLVY|??#LgxqsdL>bdFEp=a1ksCLm`xhF4#JKp(sB*`g7zHHdONrw?KM{Z)P@Tsfr0 z%pb0G_E2tX#N0n@ycdB^A9E-7^xt>#4}$u-bio>Ur8)zv@%%r(KfC#BF6tj2O+KEG ztm(`z0{;{-V;l6`7zrK{ikCOLZG16YG!?1Hz*%jEsQ0@TsZ!P`9Uiy z9-e7$!ww#zzaKw8R34~BCqoaC1-Iz@_lQV?6u&TL{SYa60X@g>HKRwx(VXFE1CQc2>b|!`Im9%JT89-`?Dv$ilbE#ZVW}K-4#yF4_D)6!1LMKO#U~gZ$ZV5^NF0=!mjoF{4mnP z9tIj2;}5$y{R-=A+wD>4<}WW2)%P1UKNJmK4W^4{V23{>2UJco?SV$K1b| z@Ua@{DIFx2rqT7``1SyFyBUV_`c1k8@=TF>`SlFz1tBi3f_UyMHPi?)22N0u4R?_BRM@K4Fl z7J}Mcwm!zVM51vXUgXlp&s2TW=b}q`u_UfSiJCuFoY(^W zh+{|nCtA<%Kh4uTiVPD|nfhoK4*@yPHN5&l=%1{U%FuY-y(DdIw#onU*CRoFQTa3u zzJK*&=8tisF?w(=o17TflUiRSc^`mkop7A~O!WKn^$~Wm0sW_Ngf!&S_0j9X5s;j< zhv}bGwqn#{Xby>yUe@{fnu7iDZ<=+muU9UPf5zn(p?@(g4~KAhbjPPJvp%m&)Ix1-Qbe&)q<_AC7O$TKGm7MS`y0aiGE~g9@#)NMf9J z=XxG@~w zw)aqx*NA({(eqDca~~A<>>Vz)q3b7ZvOGHVtuND`Js+-(>dd6cEp1NU!v5C4)04pH zz5-6Z#r3Cz`pIiCL3_uJA<;`SsrtFP!5D5Dso|A|9REUpX4PjF`fH&>PX6_$>gUT~ zYj|!x2@gNZ^`{;Q^s{dGR%Ef&fgFo=>{`$FXJ*#EUr%tqCLF=Wk|162K_j*Wvo`8$~Tr?#yct@)ls?ti8GGq3XfFm-$c zv%i(#QG>oN$|jZKlc@U1ds6@(?2?)Jr{Zu8%1z8Bmn@ccu2&G`AD4c$An}W>pEWOU zfak+1+%KE1pUl>GU@`wHQ$LHh_CY7o-!uEeO;_a5sdfFB`Z@4T8;$%XL-uKjKA)d| zu9j#+%5w$Y{-IDm;rf7rw~Zx98?rk2^%vxyg?h%&uirS{{<=^<|LHm+o1rFTO9I`$ ze6| z-}&bX*y3Qz%s)~ev(e)raZLU6cJ_rIdz`V$1(E*v`k9khhSJ}&^H0xF!Qj#E!P`F+ z>SvH|7LvahL;mJ+`VscOx>v`-+BE->}u7#xcF*smqo zy057I&GUALepbxFp57w<`1xl=HbFMO@=2786qmmQ{j)YpUnoEA!rXt%*ck-A$P?e) zC(;++pV|G*L{l|m$^8SIK7{?Td-GyJO3EL*nTmctzCLCe)S&Hhxuj1VT_5P~K2Yo* z$*garlB&_?m>e=wj-FqFt{#R$`4l|EmadQOCe=uKS`Ha;m9CEk!)m}L*Tg02rWStA&wFdiFkqWiOZTO82GlR&=xr0b(%z7_aB z(#5_Hxb;GRHere{@_p$@th60E^#OwX;;ud)evL=W`IIu9P}IxTiyZZ)>m%sqa*%JH z#q1BfEyHM+;bGFWLz1cw@0FWCZq*{DKTEt`iT2xMG3%QahagZ4Sj*d=7xo8w#$=)$ z$70FSbWT6Q`bO+Y41@*wGxt}*qiT`O!aO3gjq48x=eM>k-UpEZkyz>)_xA_j*Egk) zPomhrIi&kk6N_h!6CAFI9K0f0DpeIdq6dq9Li(vzkGOb4L13l zWagJ-gSYTJ^E$8p41)6~76HAHtnnvi|Jl`D7MYdwC(q63{pUCpT?9pnq$d1K7k~Wx zVzxvZ>b5FjtvD|J3H1}T+XThG7)QGA%hhe#8X+EIMlwib!`N9)@)Ncv{T^k1dE<-yo+DG-8YwNm>4anqQ8h z<#1{HY^HwF0yo0vhl}u}C*1cVJYVu`KqX3wWb0$ayFhp*<;AQ2h59(Qs~Cm;-bXf> zWSh|XXVN$Z%oGBc^IO4}YtZh4c|^>f(}%xcf4*97AKV)p#q2MyZOezVT6?jRD?NWC z9;rbdL3yN2kIsK!M{tyv&d1Bw(fw7p-!+&%zM5IzpWg8X{!X}obH>x_`-?+*Bcq$2 znDvRxPZ<=bG=RB3?{ZETIqNAAcfE66{PFqMb<=_!2};cRe&G~A;{w&mzb`qR>#?9d z3Gy|BzESGT{_?P24(QohGx8xNrt91F^Js0*q zMa=n?!Q(^FOjt+aBwkYaf3!H_Q5basjdsW-uWIS_{gAb( z5H}+Vhx6v^`T66UB1W3W3rOn|J!*ZD9hncwb$hY9H(fso?bYaNYaY?*LD$dxnI~aK zR6gE2m9C$h^H<^ek!oiC7<=|L)Lp)TmrKy~bLMa_G(PS#^ZcU9b{V9;a{xIrke)xD z4A4V8mM9Z7yM|7F{RQWPA3JD)j;}KIT+hWvVgBfO452TL6Uk-wyw3HH1o}~JodO@a zPhi$3hdrIpfhKcen-WLW&(wt$upjh!`9tWxqOSy^`>viuJA*sFC9Lla$IXR4Crz38 zV|Yq1dYZ6~%#)$#j~N4&!Q$I?%={sidlCf|*=gQ14A6u$W z&HqO~N}~dycJ(@5{o*f}kDQxcjK01&K#SnjgvUcheIK6xVv%gj0>WG^EnUhT;>HN1ZH-{=OeO`Z9 z*x#Dv7=$jCd65g#e7k;set+23dk)x5G{cAfaQ$WB{=NRIVASgGP1;X#^@ni&ag3}R z+?_awxqok|c@kaG$tMy<9RL1;`uwxI4}{-y#i3lb5@`f5H5U-9A7I zS~Q4*4Hy4~{O1gw0znoN@mz7Pza;GM?hJQAO@>zF>z(+n&*%FmyI$rnM0+w;`^)hw ztRK2f2}OnrHj%Zv{JYlk`B&O92R1C8#ynrx8WN1GOnpdH7RSGEzRP{~Qdn_(4sPDa z{riRYLwFX}qv!uhh=he&XZ#lv%s2ki@_{X4OPT)Zjq@&$e6${W1#>@N$oJy+W#~yw zCb4>uYx2MPL0Dg3{}lxvqjzDikz9Nd&M(Ht)}lk^g(Rk;SEs)b*4Hf)_QIW%XxuGO zw4U#eDmT<3`w4}lZ#A9&p`-IaS7{$J{yXPYfqS+i$w&)#!rgzq`E%>L7+ zdoRJHt{JO*rN{sF^qwg0NgLDuh>ev-wbcVjP79rXsZsh!Tw^S`JMdE1@5kqV^<7Oc zc%X{!pW?nBVf;_Hf{^EXE#kiZaOZlV{~3=Bz~%cyJZ2i5|2etNC~fg{q7j+U_4$1M zy>?B5*{AsY3*&!eyCIU*ijlRD=Pi-mK zpPI|u-v|h)M;>=e$?x28RQ?Za@rKc9OPTxYBV~7iRf9J+@5&EC{+;tHk@TZHa_dLF z35|dIv?zGm#^%4>?<5lQDIjJm>GgA;rWEKqG=^Cp{En$XY4Zz79}hbJS+$2iDQ_RM zz8-2<1r~V)_}>J2{7*P@1>&{pnDw)~(@SvOev|3{mmBp&zoNe~?_aomaum`TGl=wT zr1QV^l^)7%8%u2b==^IvM`%`$N#wXjK__3r`uM1%0d#lJV8-_inJ(z=>Y3!HOj751 zf5G{`Gr49k;Xec1EruT7hbwp@<-Lw1JDSdS-@CJ6gS0vGeA66{V5E0-BYF9Q+yBlG z%9RZo>fRa^f0MRrTcf+;1q~Wj=>2vT>KLDPhED_p!-ln=G4;p zwpTv{R^9hwwQ=IWWS#`mY)u0T$F9sbgv?(ZejUVvoJTTFjnc>O>0V!}6k z;4RnR6a)VKJR5CCA;ZIinDPBrrXHGcMvWYNMCZHdyD735txMvk6?XEOA*f#$FP;q2 z7d4pm>y=<ebzkyZ?p-IJLjNLj!WBw?&STDZ_&FX#Pu-KqqagZx;S`1SFi~0ipGR-@QSMMPbf&i9Qoxv(K)KhwW7%T&Va)Fb%78@hk-*>f2lF2l_F zHTQQbgj~AC^e@%s>gU{4_m&hso-pM&ohB?FyamYiiTbLQ{QW zvaXoQ_n&Y2FnOgWv%lH8&Kac=8!}jl9>2?;n!?qPDNKKU^ic--d@YH1U(N6Qd?DY_ zcV>ZUgavc{Z|M49^!UPNvZ40}D&HB3u5dhkK9ldLp$E~RZhMH>WfkiDQs|0xFt&Ud z7XQilZ()6!q<#$jjLv7)r~CT{K&;e8o_`VY-^214+MJtDjssKCwvU`kP{c``z|rBty&QSUljcNI!i4uGZ~1`ab6{QB9)nkG+-71*>QK z@%JyH`9c2tg;>OKknUHA-7nDjPk(g@yjn0GBtwtynbTY0lgn-Vw1w{9FOB^ViMM`d z`WF->g_08_$n*Df{+*ZVBITfQWbhh}e=$M-Qu4_(6#R8EDe6($$)C`_+_upNopYMZ z^Fh^` zS}mCV{GV(vs!H0@asLaQ|H81vU^{IAkAHu`{e{EsW}uPTdx(D@H7ft->%G9mZ8?*F zwTl&~P4zI7|792b!A)!v)8A}wt3bXshlyVb$NwV%|07f)!9FL5*`FLS@fcDHJWOx} zo&R5>lR@HoEHnP66y$)K%K;|e&oz%jOGzQqzuc+51m8~+=KOcifL0jb+`^py9(SP! z8kE|OAOA<6A37%{g$}-xAZM!Rd@I!GpqzK($ihh+-@^Hb;zD!ObY%+BsNwGS^cVP- zgZuTMpN1B5{^5h$BBb@hj=Zr?q4M457lJvr40--V$oGAl#mKK|4hgd1?jHaF-$yNN z;maaRys&}Ohp_*M{{*4cH@A{`3LmNQeP`ApC_K7=*?(EFH3J1|B$GJxah-e%`!7zO zUXZkY1#>z7b51 z-(?e?gZj-De5O0se-!rLrRViPE|Y)Yg-vvSem;35dc0vUv;OQQp@WJRjVA|w)BBGj z+s#o=Gb7^lfV&@1$oKT8x{#Bm#hkysIKv4oSu&fHx6u7d`eXztvy6EDML{s15TBHe z2F^?-)lca0yM3rFY+Pr>^e;=*Gtk^S$z)iTW|#lr-!BmM%?0**EM)Q>+&=@ES0@wr zKSI}ew-GX zj_M>+$Pf*VPk%vwL_N#}%na1gxH6mqqCBGq3Un7tOdsjR}UGDQBAKi?do zuoLb`Zf5Rp?z<5Vwhe4P-`Z55{`d$n>c`cGLVxUdB?*F6;_-Gb(dYC1@mR-f==Yh; zr;%j^M2Zz-FJF569RB(OJPJ95k8h&K&%KA9!oYuba851V|BkHdj*g7{#q3|}oRdWL zvxhL_r`4!Q=;RW0X8cUEwMKSvh|G`T^eyC5|AY=y?b7Dmk1E`sY1Vf^*J9=oUvZ94 zF+u+>6$3c`GUlD16!Ka9Jq?XtokGSgWnf`QiQ_{C#-elJm}fU|dt znf`UV;RWdV;}o+$v2^xRfY!Ur{_=jk?x@c17uIc{=XdL6lIYH7X=)g*cNlgFhW4Q>eJH3E3)TL76=Z36~{nC$9@c~Zx&Rx|r=4b|J>Lev&!{A`yChcWv@nEkakIY-eXi6Y{y zL+5j-LK0{w>}K{Cj;LlqZelvl*-Pisdgf8s*SmxnKg+M3hYLqeGvjAl*%P=HagWER zaR2-4&2Ff1!f!mZn$G9#UXsYxXehIPutriFDcesVi(k|ETyt|ADEu6U6^CO08Q^3%9gBDQ6Jh=3S&@eBKHN)YDrr&uX{xmoOghfySNcyH>ZX!P zG?R3x_1EPi?w}vCn(0q3-S-0`y%qQL;=W&D{|xfN;M{9=e06a;ip1-S$O>CJzdA<} zVfe1yOn)A|_JcfZfxl7Ub6Xpt3M8AZWxbUzH#wS$nVb3=}1-0f)qQ7{0%?; zW~`b7dagRW_YVmDfs=<5iiur7s-!u7h5n!hOyKZC6W;wJ{(|^hFQ0~fS)`KM?%e*O z(7z7UoB_ETXE5ul<^^fU+b@+kyE6Da;|P&^9C3oPh%bKpg@b9R@IHFIDzuRTp zLBVGYGycvQ<_DkO@c9+iS6-T7U@lgsA1}|M`&Z4;-H`Y7 zKTLjQ&ksj&%|l7>EIPjrerckg%O(=V+w}N*;o4YuAw8aVznYNWlYTSN5wIqP#UlUB z=QlP(8_pE#F#T=!$xdi%)|pcbbj}nOo#7y z26KM9s{H`^um3)x(=i0V%{TD-0|VL|KvL3)=^r*NOhaL-_7NO1g&Kd`cdmgf6L;qP z(IT~N@FQp&)-o0G$@jNzwV^P!I24B$i=OlO4UZ~ECUPYtU_G7R)V&EX-YfyHx8m}n zaR0gKQ#l$JP(n^r(a*nq>v(^S-0Xu`ycfNH@T;*5M%9)wQeD{=7gJ^ek z=J|x1Uu@9br!&YqH_`bxKHrZ)8Pqfu9c(BYfDMBIQ{(dkm(0u@}7gZqJZw7eT~bYpK%!$52MF#-_7S>^vH8e z|NM9NLufej00(ZR^L^7=47qCk!;M*VzR8H;=+)g}DEZ+d&HQr zaCfab{v}8EAKt09sPTvm`Stg7Cm$g2&n`(?aJ5dC8NcgxuS9+eSCD~C-2An0f9{E~ zF^rssc>OaW-%SPwkgN25vagEHx8Zgx*y1`9uO7?sogsMtk>{QRsAbcB@-2(wTi8Dv zTw)JxuFlN({pI2TR8_E_l(++x@4(}$V7HzJbG|4feGBw@?Z@j+2>BiqF~-!bRi*yU z#NQ_W%P*RU|9+MRu~2XfVe_y0vJA}(DJ74x==?X=?S`iciOl#uSGpYCsVpV759sl| zTYCoFQO{)hm+!AjLE%jqbN|`=>sjb^^c-{lV%L`kP`L6TlYh^b|3LZMKW2QN`+68k z+&!Eum%6~kPr>^qjCD28{BjL)(TC$-xc}_5Vhjv9rp~;d>BjfjsKLaJoO#2YzY+4E zt)m5*8}yj*eYlw?I^yC`C@;PRE5Azqd)P0-tW4%=<0uXKsP&kvo|Ei>I}!rsh(r^@b0AQTcrn z9Rh~W!kGSK%)T;YX;ns6)zkT1w{AC-mM1dzkH5^yfNy@8%>Kr6-BM_@EN8}NXP2|! zXw$&t)1~JF@MwI9$yj=Pemd|U{I(M#g~{~zTo5@7iT@eSJKrMoADNjGQTG9wM9YHC zXO^!j94l7G!~1gcX+nQ}^RpeobLSGbPaOY3KK*huq3Mnu@BKl-`tW0j2RiY{lQ^%T z^SRg02+kClGX1scr&2T^ri^$#xZKH~m|%bT<^)SncCo=yUpPKH{2K55ab`ysg7QNb z=Kk8+tt(;JK{lVTX)`#c>|pwbfCN?3v6ofrPpHu2tGICpteg?f^cN-;WoXdTGIFAc z&Zpa>c*uH_h~MeZ{qyNt>0t3N6DNhz{X_Sr68P5fejbB-x_|h1^9-0ZvH83md>^j+ zJ;FVv(fQ0@`WM#ZvHASxG7KFlA3*}MIDUkD9%`F_Jl1FuhhB6(Uzn@H-Jl70Ofa3# zfnVn!!@cv#P+1Wle1E)jlqTda*JtuMW8WI2&=Eh=6$`2Hv$EC@Qb(FG{jt)^QZz8B zoFp8&LgjORyaf#Y!RB*ozlD$zx`@f=;NTUIGHfkw*(IvK`1@xwF8IP$ubs^K%k1;P zkewIKjE@^$m7=A4%1QbgI)CGW1n} z_zXmvoM-M&Y&v}pA|)O(&R^ET325hSO>+M+ z_gt92_rF$wHqD95{9Sut4tiC-fV`{b`13d6^S8@L0~+`1^WKjujE^bHJ<)<2P=Prontp*?nCGE)0m+sY>p()UxL72t}9bV%{E$ONe!LPB<~JB8z=Ja z&lTqHoEvti=g@`Zy91ri(KQnx!fZ0GIm6XALOzqX2ceJ4(7erSlo$W)9zMX7Tux5ajP1hxw2gu^3;J5b?q9-x~g01{&+U za1VFUbAEi3uiOaTjr{SKzaqZ*{jF`igTX#Ag1LYD_In9xX+BE+igEl2@87r{6bGKu z_Av8vmQxzI*mvCD&&bb}9q*61KDC0$pN!urXq35t1FnkRkHNpc?EB2S(6ZnO4(NLS zo{+zSYri0=q8s_=NaxRH&k(d}nJ2cyF zAxZzs&CdwqW3}}}s5r{zuVB{(WR|pz6g=YozQX(c2mdjE?8DQrTQ27hg#3AHm!QV? z9sIe``D;2p4g4}^;q|xa{?R3C9^|}Sj4dCC_~G+sxojC2_gKf|Z{6DsfH(MK`Rk(f zeEu#iS2mr!X>9$)C-nNpV`~unD2>2-*Kz-T;rULFj1n|uaRu{!`C2p zdVJLUJOR!H88H2$`m8|o`*|pFlI8dk@@Z6R07FvEdHc6QK4Y?q(Y>7&Bw;1DURd9F zt4xEwPP3Wy&1|!IF!h5gwlfp)!RK?uW;ghgunx~R6g}t1M^CE_aPk8?K86ktg8t(o zaYEPmWFdbC=a-|-S91)aYg+sr`b=4@tsoRK*f7DO&#^4C|<4XSpp$HhE< z$LDYDb06^A7=ZWLb9@T>m)p(-!l#T#X8mF{ss#1{hqVsn^Ar_PuC1WSv`5ylK zUxCUn)AoF+`cL%{o#*2#5&!*FCw}aQ#icpS{Ox2>2q&VC;k!fWd@3&|@X_TWlh2st zEg+`-jG4cil7E0C?oRI8()m2_LjqZBVe?txI1V*G)FwXT>G3i8?r10-tchp6;ryR4 zKH80%g~UfWkmVof`MZ9XIylHo!EYkC^+NwB9+zv}9G}ATVJo`%Kzd~Wv;ST-Wu$4$8M*ph9v@Bq*MILgkHhOv^{@?uH?P_8 zRi(NZfj`y}Ib$Ng5%@WE&F`siM<4#%h2T>diEkCfZ+`#%qOm@N23g=qqd5N|%>VD^6d~C;$I1N`P9MVj-))X5 z?2w(q%>O<6&wTcDt4=RQ zFXvSfy#P9&jniUakYx&!&xjZMKs`DaZ*-&Qe+|PU;FEnE`zX`ntKpM6_@#FV*FB)~ z*ZlVu?A-92S)YHt_Z_CJV)IvYZV>X2lpK!Vt`gn1j#P(CZ_+a69RWIDgQ zi}fH`&5C#bvM_!g&nrY13Oo2+N9Wf_0>KlNxjg?W>@R)mxIbja12<-W>C4T!6qVNGH5r2Gs^N$pv zZ@7v~K1t`d_xxxm|CfSqwTjmB`MsthVfwa*RQ-^)uugs(1pEeGPK8OPhwvn6I=^ow z6+mQKB{Tkpl+}Vix{R|L>HNODc@y3@viTii`wjdC{YM7%qVrpuHV~;NN|BY)bbfu6 z$D+qXhur!@=hq1op(#|GIX^gM$V}w_pA&g!N$2-q%s41pXT*!YLVj~|{L%f};pER| zI=`PwbwS+5ig$mdklzI7LX^6xiaczg^BX%9L6!SFTwKWc7ooq+nm8M30+uoPRa(Co zYRLv>e`-vH7yK3vWb!*}M*!ThiN^U_BEI;1E?ZuNQsYh#*T-}|pD9Gc@zTA_{iF3+ zgG_UmO4Vn-r1N>lEfs!WJ;aQ!Bm54-p0-Ln=!s}PkU!tLVni)OHL>|DC~Ag=wpRRj zH{G9V#eIcuKK~J|A#^_1YYap_y+@JWs&qbQ?i_=@D(f=iYh0xQwD+3C;_6 zf5HB{qBX#jTl4VZ&2&DS{Aa;t<>gF1l`|K?Nr#P0fADaD7bK(yGW!GC#sTo)VKlQp z^|@COvb8!%=KZ4c`F=(em{;y)=6{`MdtrxF9+SVxKl9;PU==>}naqiopTAYtbf6Mj zGxyg&I0d1pJ7bBP0mmN}@HcP(K>FSJy!$gA3Fh-w=i7pF>T+KHURWQka_MDiFlBIk z>-qkje7_Xj-x&JB1>AdYV)EHIYb~_i3B)d<^Ff09k0$mUWZE-kRDFr}tIqu2AjtnG z&icdK$uZ3S{`|y3^yKwPlG2xce`9>NC}^9L%It5Qx7`cjd3ntIes*R)EP7Uj?_)Z@ zx9?TM)E`%v`Q0J73BLHgWb*s;%ok`J(vt)?bMu|T`@4)S2B3RQqnP=9tClMI(X2}@ zE~WEZ^hOT;jhTc^)^YJi=uh;H(?N6@cXH6#+z`RxBQ0{(tX zW#<20ni8go@v_YRsmq)c=%PLCz$ayIqf8beraU(PiGe2fQ1uYg9UG(~{1o+eS#Zj&NCKGc$f>jdX{+alyR&4+4L>ucnvju)f3VRm`7s=KqfZe>%~02b7$QW%|=m zlaC8S z(_U)E*LH>*lmqPvlc$iZ+rzm5&6kT)2Z=cD#EZ9^x+qDXN* zy+74ls0H?8W-{mZBGPxERV1EBpQG~&SB+qwzdiGQw@hRU~`By_U_N z%g$UFuTzbO$I|1c@4+hY^0>zIpNE!QgVIxM{)!|%!jb3f_z6$?qGK0ih-E9Czf3(P zB>P#PNIj+V*Lqn7oK*Fg{r!4r3uN?c5wV^~=P$9BDhyo@%=qbaY%3aYIf_)Rpz}9D zRtq$*&19a>Q?}ZLme1Txmi^%PQxMcoZO;wC=Z-zE|0K-sBO|9nqxNbZf5Q5|V2uN~ zUD|?oDvAF7{P~mtM^<;dUpJUp-=A34!?a3rXnkww!_N5mQV>5=eEneaMmC=-f(wx5 zTud};=zJc~4Tnt?`CO(pMK4-1c zkuRm^@8E8I(Wl+A%=jsrrHICuOeSBya`9ETzkj_!8rlcyGvjB`<7ue9mn(UpOXsuh zvobWTK+O2L`rc+V!6BL?Nz(azCZ`FKJ#3l&v-g<*^k#7a`M#ab=i1OIu)E%YH$Nqe zpBKkk!!PqS_*4PMPln)rVPDDL$i8x5eOOhuPCl`KPq&W?A+l{NGrw0f{X$1}53Cox z|7n=1ByT=ye2-PIF)D=TUxoF5>*=j9Z*)Af{*P-oj4mA}q|bXgzsibXFu?2puIPHd zo$!7Nn+ZuE{igsw#&mv9R%OGj@EUCGLXWSLe2>HFlIvKC_x>CHe3Y3*BiO{fW6uAn zOnnEJN_!KZ4Rn6@c#EU!A7#nvvmBp7|M~Wd0;-MD(hhdX>Zy52A%kcrrsG?e|QqdZ>50W_kR|E!Io|K*IkZ( zVSmc%+E1kZg3a&95i4QeqY&PFi?IHZySoKq!`b}q*?1Uj4y`93*}Jp87ta6rWro75 zGB&?>Z6Yi*I)YzV*GCp(dp%!uoZ zkHY>`UpE67{MHd4cM5W6`&s@20^1uH5ZGr!7QQiW3TiARr(>aWW zO*%zv_33n{X<_r1pxpMbqxHRiMb3ULl<_)}^)`z?@qw{Tes1K4kCCBs^SF9A!s8$1F?a29G z5WK%2^yDZQEN;NOKgE5GDS9Nig#7WM$LH07O0ZJSjCp=#){l+IMKy*Til_5E#&IH? zievNrR6PLgM@b|qlg_u+)yXh8(TP`|3FEWm5KCC~#T^Ii=Hjc+Uqt2qK<}>%s^4En z=lep&eE4wKj~SmGBbUSX&7rvBB=_@${y}A$m}wmzT5sh1fXeTF?ak0IaW`}R#jqhC z^?rJaOtPi(JM3Nv=tiV5`wKlA65y_DA+x`wEtLhwzSlDSMcBOx*b~^qtlxq@UjoZs zAFyH(H(wx(&v6m2K{B8ZG44(0x6!^2y6G&>+&?&cRUWx*nL^I&;P@5#<9}bJARQSn z=U+F=BlP);D@l(O^>_L61;`mYRt#_dK$U?a_TQT=?$9^v8FnTY&v$4{WkU#25ek)zjGT=*Y%F^@;PvI^)04UxaDS zhv7xrndh@6ZT*e>XAa@TX9a;jPJX@&%3gKc&&HTP+@UCDD(N?@e$!Eo??;08{M64E z&gJfA_Rq$x%|~nVPLl>NI^WYALO|k08aCve597yYW0eF*D=x&>isW{{0?;)jc=zQ;9rVph%otb=3`OgA+ZTIB$ zCxr2N_V{^V`F=Yy{`OW{1_j0)_wz9LT(7kWE}htoYwmO3pYVL)g%SDa%i=R+Rt%lL zdG~|C%{ZM|zb#JO4Fh@F*FtUU^f3!9nsTQ94Np#1a$uIspB;eY-| z$e&o&OZf4(4;i1!-QOpie@R`}8+|uWV9saXS|f*iBn`>Xf1Ljn^0zi?BzS!`z-}uz z|0$e**`Z;AJXbCukBc~dh4=T!+*X7;71NmaOWn8jK{M52iTFx7f4A+`Vb`D8%>J#P zvOlt`-$N9}#B<+|pg%S|N)KXRJM+%}3;jX=#%Tb_p7_^djt?P!hF+ghz1G0`c`fa= z|NH*)1ohhtrMaMLzk}HyOZRdE-SRMIfA@&*Z)7%TSpCgNy1$)RyAi&vNMOd#-i3K6 zMD;AWd4$gI+d07ymY$9^7Sa7}h0Jc4l2F8qpWikggv()=>2J@+l*5n0W*l8YkDu;- z7of`TBbG;Wey?180d;QT#HNhSZ*hAsv_DCKyf7E>#joGW+GLT|enYZ;6!%=nZ#tHQ z+OG!8^I1>BrlRYwmk_f<+Q1z1K{8prh0d??SUtF2;liumg#7NAJPqcUtmXLwA-@h!KcFA}1M2%Xw{`NHA>bE0 z=XCgEHos4tzM)69gL(cy*gq2wS_;}9*zvcmegn+NPhk4nIJ-PlcIPa)b)L@ekw+c( z6NqIn`E`tphfB}d@%P%vj{DUJ#yiK;>oaw+a)>gziSz5|{JuJK9_)I2!aFC?`Hi{U z3O9C(lYrH9el>M^A;~ZWVja)LS7H7i=qHQD4lp9IN*sSeev@M);ob2m%>M7CR%6t@ zXekj-;noZJl|HHf7em?nPTsv9c~`}f`FeDI6O_h7>3uf8ZV9>|rn890CkWrC?@-?T{`L3dKXvk%BH;5yvmG?<+lgl#;o`HfKW2St2`CzO+&{(0|9IR7 zl-V?({^hlso%NUSd~8LN4;*}+fXjP};v;{4rsCHjG&1NMnf;v3r^n6?K38Ti{Xw@8 z@vy+UnC%ZVGay!pF#BVpSCoP6;hW6(8a?qm98dYgjIZ|ctuXC{ILX>b=hHu?C%SN6 zfxNQd_!JY&$ILt{}cx~s!%>OMK zZ_uel{p)Ynaqqts@>wcv2d;(-WXm*>=62-e4fZ^ z()oWM7znEk|BtUT4+pA?+P--fLXw1{QYtEu=&YSWG!U9clu82{Borm7$UIjx&qdLk z&eotwkt7Y8lRSk)snqBFzD~}5uf4y&pKCuVzjd#B4SS#V_purCx!@(=(2lKIMH1iX z{O6U%K}*v~ewI1C|B$Ji4Xy)=nEs=tB^TmyDtW7obpPRYvly<`f8pn}moT*YZ}*tD z;1Q{Wb;r>4z1LP5bYY_rR_xQkx0wI^33_PmNITK|j`SaPj@t01{eF0en=n5h>%aRW zZBcHj4|X&c`VXZ4NZHW?9-nkz_Sa_hT88R8;&J&XI{%8}P2tLRcV_+Pk(-T9+hOcC zlFon4f+65}j?I76R0PX6_>1&EoR~j9dGsFTuT(C|-Bk0J|7e1LJbfaJ$qnashYI>l z`jfiIdK7#@UF4rh{#RSifh4=FO#b5&|3mH{Iu&`9()m9&ECBL4r!e<_w^SWKa?fw! zG#5Jm9?csdY|Cz@{=agLgQecNOuqdl?t<7gMZ8{Z$NgUM{m3IBxnMp0G1Ffw8W+Q) zJxzRekia+DKR&eZ4ZNvP!r!dvd{_UGMwcELVN-cJ-#*{EA%(+sSno{7e;4cfnG|g} z{?(S*Ki&~F0_k*{k5!H6d@r=?0cZRjnfl)8*b=nTEgoCMbj(l0{>3??FBrACGyO~c z;lW@yaIUC-LHg?+Apoe(pAQ-!@JH5voX=YnT&7e6g>U}y8&2>mlQsb+N=7jGeOL1d zok?c%o0&fwdR*JeeBYyQ?@ws9fqK!@{gr?H_aUM`+#mcQ!zYEQ-`!UpKwQ>s++#7F z-?eKuz_5BYzXcbz!;Blb{P-Speco|>C)oZe;!n5I`F&V)5?+`pRH{ji- zul&4QbbdoqUW3~JWhTGJ_DG`_qk1y+IbcIKG^NK#ratEdXhCU`Enoca{x+%4XXQp9 z?Q`?7{=fSdq&`1huMfX69hv%^lIDl5ENk~C{pkGKP3{Y~OFWqOdrSZ9MF06Gwle2;-LjX1{{0lDzYexKfT|bV!Ct9!K5L{mK$7hq-o%RTul3Eh!x6PSet_uy zh4}v24&$9*>2Q^=EvEB1*Wx7PpeiPx+MRB|EZt_&{Yg?^Et6is{t3!h{%yzim(@h` zjf&3FsB(KxyyaKN_r=BjVflGo6hCn!mi3|QtFo&WoQkt!_K%+^*`SyY^Ktz{x_^%U z(H%YyaAM9c=G<9~dOe88s&)dOyxbST?EiX6)uIAhvH$&!#QSF%yJo@@&26InNz(t?$-hR=o0W=!)gJuS&u~IN zU));;3#?O_`)OCc?nm}+ck$TUbUqg+MnK;2J7r$gBSrf^r2k!-r3q?}?U?&(BkHVCN!@%LJb=#c)~?;5YJwB5?JD?Z z^8RmC@M7c;k%0aFy$_y4+@IW9+#4L$dNTdN!1p^)pZP`j=Rf~U>g&Y-a~SM1k2l&Y zyst#|Kfdl63C~^!iu%Vu_}>B7o}&W;6pL~$RsGf1xrDxYuNVj2n%VrXs-6KaR&8VU zH%xadZU4ShDu4cqpzq{-&Sb@Y6jFZ|$5hez{Vf#%8b9{%*`ob=asR^CEEbx-&_XWt+D&y=cbbdGJOQ8^# zUbwE2&hO7sWwjgPyPLpkc}iQT_J6_|1Qc!cHm_ojdyIFTbt?zXeNNpj^HEeK5-o z{>1k)D!R;ooj2J0zG;1lOui}?_4KCe^W4Wvz~yEt)8Cd@?ML$;l;A*BMQVSpU~M>b zhP`~!uZ};Tm~Z2~F>rCxDW-p@^2vh!yV!hlJ&(iu9Z&c_K6HP($?hsd%Czuv>V@~0 z$@#N?*B21ypn~63()k{ASP~iD?1gV>2z-+B4<|ikNZfA8s~r;lexyF{H|~mJDmZ*4 zQ#eoR^EZpm@N~gQk^hwdDUrUPFtkRtg}$Qw2-5$)E9wTiI%9cGo378r{T8CVl?nKT zxxgpMx8E!i=s#&PbN?qpX9rq#^(y}Pn(lx9XFqw~BQH^XN9wb#g&lNJT`AIM(tm_Z zuR`^@3PpxS<$w7Gg71-8&Y&=#&3BsQOSA@5ME!}Igg*)HIUTxc$1wfLZO>|yXsKMZ zcuLt{f8tO0lQ(I85Y(E=-#RV)eo1|ozPJxv-g*zeFro9Gp%o5Z_x3XV^8)=C2!3#i zsqf#CGa={2HQv*QuJ40FkHOqwPkFtSbpA(K6agC7!neiI`S)^WzmAZ zll%3So!a+5t;X_yE(!jC^e4~y_@dH=1RPf(^gqb`x7=D|$b2|ir0-;Z`mlm z?Wjh-wAlQk-qS$6e++N+FF%m}TzA5AG~8af$gC%w|MU@la5f^1*`M3*x)0TLx{r4Z zq4OVOv>x()vh}}D)Hb;I;}rk%s^D({#Py>U%7n`+t~34luMbCIZ`xC){!15NF#6QO zx35qA?LU+CqlVdYFgU4#PcEkG|B*Tg)c=w(UKAkkOY;BCT@g}zE%|zfj{PFBKexWq z1*J>@tfnWNC;7LoQwO_WBSrmbQvc`99ftZ3U5I(Irp`B56vzufMz z54H9##Seq&{9bTh2g|nXW9s*8&28YGc$(>7toCGp!522a2jz~!*>_L*6}oi&b}Qu} zeEv6)ev|x$`96bg-Bqzp9Gzc&iUhK3GRB831pY{VjUOmL?|W>13w*ku#s;>2L%KRF zJjOBo%c~emR3Ekw@9sk9xAbXOs5NzF>UVde1;|k=37^fS^P4`j7dVfb!YdyU{155R z1;OzjUdxf$0-h@s?TwpCsQiSC^xq=jDnfuf6@3 zZ$m=AE90D?WyVJSj*oDjC-|<+szUFwl|=p}m+&uVK23qU-D8>ky`R$;!925cCf}O7 z_M+KmO0iNDo$n1O4BnLN8`^IU$E|0Fy4H6k(JoW~^X%pR_I4(K@ z%3jZyd@obxVd&#;{N;}v}c zeIot&&vV+yZZyI!1BCb>^||b|8cb^BnD3|ctQ(4Cx-Sy-Pe^}azMv~yFLmZCzR~?j zW1SC*woJk!#?txrDd-82Kd0~puLZtIfAV{T8FcFHBl`X*$?y1iH_`1i5=AC?2maIC1DG@W2=`}=+!?^BWbZ8@q6bpd52 z-@_6ogLOOK_dC9SOuWBRtoI7dvsW)V{NKaB{yd%V=f|TKLTFMt)1P<@-HVQ|F2h|9 z(D`>Z424{s{k&SO5TE4zR?|0I;Ic(NlmGu#q=U-c8@zrho&P+17>>SU^IxKP1!^?E zx9``|`MGT8_-JaQx4DSvPc9m(frBmZX9o-X zk^W@0)KGM0I5$Q$|jCE)=QbpFRS8^H^|sl4_L z;pdb3u6VzFpK0}Vra$+)*dN?}`S8KfLi~~OAvvlTJx!4)S~-y(AHT*7hbW)bOn>vs z_dd#eAX}7k@ESEfu$&_dRg4t*cT)eW|5T#wQ`zycPIWRI&WmN%ukXWrp+^l{|2sX~ zgAUGnfEyms`Cr^61pL>t`Cl-93shdr=anDP^*`x(8iaYae_x%^KbMm`3^m@*`6)_t zfAh+v5LR6J&j0L5=YOML6$~m-#lda(uYQsD177uL1CP@t_~>Rq|4Dx%_q6?9`|e@< z(gXkaA^MMXE45Ie)F_$Eyr&f z==}S1SqlyK_VZgRI?jvzPw(Prxbq{Quga$Lzr05ptlm`2Uv#JIe^ulm*e6rXAGf0O z|2*R|L_4%H`R`iz7$gUE!mo_z{zt0EFZeFm8~X)z@GG8g_6d=LYeTH~-S6rA%hqcm zv~m>A`_pk=+xbM9~^H?++5qM@j$FHvSIU zULaGXG_mk6|1Y77s6Si#b~GFq7|HAW`@SN{f2z|XBwfYU_helUII6Lo>3=TTm!R7} zWsADcx&4=ab%Osp`SW3PWCnBobbr7eWYbWNZyPI7`}2#UgCTI?0cL$GZyOCmCKd3v zV(I*U-;)XjDmVF0E9v~tDmVzgxN6?uzmEM`@%{0Bw=aRjkyc*sN5}gK;`@oIUn(Ia zjLrYyx*yQpyf;?v+rh7x|Gf9IkQrgcZ|?99g#HKEYN7>4N8$5lI?jvv*WauPqe2kV z|18V4KyMc<#_JKCf5SChpx=P;%>ImJ{akd;BpIhA()mvcGlbnv)0zA$gr%WrgNkwG zdAk0u)aeJll?#~jr^+E#Ft;s;>2EfyyoH)Z%M>lhxJc!HpVVlmpB>3BS}oL95=h*? zf#r`-Jr?UfS>LK;xI=9Gc0Op0pueR4-+uiJ{b^M%vh@=De>}nezE~d^crb%6*(IDO z^*?^kZggYiL%hU{&i@F04P-q#AiAFu4r2YUxVjlEiwc|8;#;VWasdrv9H%vOw)`XfplJ+zHx{SUZl{-x=F5 z2k9+L#v04${C|iufQJjGGwa`R<5H1s)eY>sOQ;{n`Rfc-Q;>hZfG=Ar_&3u3Kgk*f zV=k{@>VM0&VifsMx+uN!++Y5ALjTYE+k<{-B>(BM@b3!*|C-*D;O+kHythIJpW^q$ zqHcLZOV>=Mf7w4}H)@<$fgjJK^ZU>{2-N-@V9r+~G&jS7)&f3lilE;TM1Q>urNFm6 zH~A?Vbp0OheE_Bne8EdUr}KMQ`C|L`8-FnQby9o;35}g_`w9frzboGO4l37rW0wyC zzodV^@<9ed7g#g>%Tc4wC_IME@BXzau*Yu{v%kL4%pB#q`r+mO`txM{>SCo0w!g+R zzu&m^>uj`bS2CVuN9UJ+)dRANr;F-WvVW7Tk%CUmy@BV?7S5CW4vpyxe-eF}{@we! zCA`)QX6pCpRo9V|m2^?z#)7~6<`DeKT^|MGjW_XED+GSc34SZOP6C^;am@V}If{b2FLq(~Dnn(BN*5@cRfl-(Tmg2E*|Onf;kUJ__Dvo?-T9-rY-v zQmq&}lr8p!m%J$|*CuFqYol_ByKo9}OqgV4mIet288aGvDb zz(orJ^(Khw({SSZd0x9_p}zUac+=&M{=Inrd$xU#_V3%xVCwVr8ObQ&;tkA+-uD-O z-=QL_4ecphpl|KvxM(fL0z=ON78!RCL+%s<(myrA0$E^S=MtUq-gVYJdus>oLHz+b+}{(N8Op|Hz* zEmPl1eq(egN~-AN&D_8G9!}_cS7ijs`!gM911?<bGO#Pnly#0RA_$bl*)R6Ee0e#!QpH?5o?4LxPu0r0UHH(xL zD*oy-IX^mQJs0*Y&tm#-b;TSst>iK8++CU4Kk+wR0Xv2qV)C1-wF#v1&ocWbcY7p3 zan5b#ewXvby`UibioaDz*Jq!Wv*6+Ui*I$J^E>O{1BmFU&g6IGlCMzso6T=qffOuK zvJvUC1c>)rdL^l$6+cJg`I7|x{ujS4O3>^vnpr=ddS`|nTw8*B%@WR&{Ep4*442PO z6z%Vl{L1Z}j=UD9;Oq8uel;Ds!=v*vnf|+FzX|jST*Tyet#={vERZZZcwp~ee!~fV zXSd&PThuLtUwZSOe@E6fU z|KrNn*)SwCi?3Qq*Wa4BZ1g&{3Lmti^PAi)5O5ls-{nD(kgs))slPV%iSX?1ZT^Y` z-Cyg=?FGqgY<{l|JqrP!e(@RqzCS_g@A|kh_&7x!{|Tb&uj-5@Xf^MP>zwHN>(W;W zx=yrV_WvxD)R5fdF-(7PZoeYvY#uGDAA#7<{cUQ7%sMZ{s|L~e&DQD+TNPYI_a{hx zPv%TR$uTMT?2nHAq1a#l*sce!T4wT++lBl=){hBA#&A4x5pN+)_s=UbFCn|3l0|FK zp1=G8!S4~{!SMS=2-9EqxpI*DLae{!{L(pLJe*07XYLo89j-+44{H`Vl?ncV)Zf-# zv!U)io8L92*(l!b2{xKW=Xd(70O%%jn3pc<;9u;I8-H$upyh0S@8>0ehVdP~PeaH3 z3i174n>BktP5w30AKOhj1F7BH_(~bN{$4#;3i_MWagZaO-=c+IV8g+_On=;MuOt+g zv-S7TgiZ+W8G~ax3;dD#yX2h$)ZQ7*H);y}kn@|6;QnZ4-cmf?K{!w9?*V5GNN{&$ z)`uaI(@XpUv&cUHF`u-E90xBRvh{a;dER@Ah?>1)YcO;Gh3{ ze~s)v->~tASJMyk>rc@6JmbF+PJB4W^aph^3GMF(+~H$i(D~Fkup4H~f6XW4(EUL` zQ~|8XWAhnTa36M+t7Fd*bUs(QHA2JNzSw1?psy0d`#OE2%GV{N}ha9lYf6a3%=zNZUk`JRt{pN!^)Ae($ z_I+5*X)yEuLZb$_Z)l1KD0c8Ao_|Qql7K&+Bba=S`Kf|nr~{sIw&T2*&;3R6Fmu-! zk$#eVMm{q|C#EgK)7}W@N&T$sq7G9ByD|0i{=La)`r=e9eVfjw>{DHMaeX$k{yKlG zCwMCOG4uaFSQJU@Q5&G{q?!R7P_9^EZWZ|`Rr-v0#|k?@XB6- zzLEVg=cO}XQp*lze_)B+F7)8$GyM5Eolj_63PYYB<`>Ns{{Liupw@l^XhgI5^tu!W z<>)Sd^*CKW$4tn9Nar{FssuWp?mhG2&XeD~uA#su+5a6n`yNa3SHq z$P|yS72b~~=NmE_5}>DRE1J)d^;MjY3Ube3^EuB<9(pJ_F!|KdHAT0Im*I%JbUq6g zs6l#+n`l3S^r!bfd!oE6saUs^&S#E=E==X-F!_}FVFY2(Y(Di@7ogK$f8!a-JE?s7 z7!QJ8O<~OZ9xrbTUE0`uT2+n(sRIdo+|!QwOgw*E;xrxPd+%iSXFDz2i8f7mjuqe1 z`F!QM6#RpaF#YH6D-oddqy78mi|GB?#xZeF{Pr%>e+KN%h7~v1eAZi>hD75({I{pV zei2zerTdhC_B#!16iMgvo9bsUIc|zoAJX}hpYxlWQ8R+qccAC@9Z!@|{&xpF{Di<4 z=|62($w8N%4x;@zQa|12^+n}fm*ao~!g*3ZHB{BW*Lo7Oek%O!fh<0y;`!NhKJ&MB zh3^S-nEvzPDI+jgu|(uQ$^4#n;xr1XZo`s0v#5N=Y#RtRo7OS)vwzeG@b``uy|0i% zgO$`G3&z zvRyxu>3lk(Hg3l_TPB|`^_9`bfsPo>7x*IiJgP1Sm&@7uS(o1jeLb)oA1x5hlYAPi z>jW8i60<+0^2{AsYo=l3O6N1WPzThX%wgVNNjYQ)W82@)XVv$CdZ$p8T^k-Bn@Q!f z=fMHc_G}%W_e#(|(tpmmX#?}mM~mJkCHbtM;0O;>6Zrn;=zPM;sWA2YPQLcv{X(+- zF+Q{dHNC9H4MXXCjp^SjJ;*t)%hpHWE9?-!kR z!NlaZO#k^QFAucjB`}N6!0J0NHMTP|zc*j2gUdbp;iW6-eD3!6#eFEU74`qg{4Nuv zgcPG3v9!Cu7s;nXzAXG+=P0^=Lh9$amfom`tUn%}CY&evG)+|^iO{t z8xGZ1qDAi;kp5Gp(gB7VB=UBB1-^5L`y*{Lr@-acJNecY;lGo7j-RyyRor@k-}=${ zj2X2UswcDgR2>x#j)N{T>vzx5u`r>agrDa}=krh2PFVZnEpOyQ_n$S=dC-4?1fFt_ zuAkp+?m(aKotgV#tIIyZuOK#`Ar3#eP$N4gpRz9%(UqHy*w>_kFL8Y|Uq%)pPCGK| z_nSXWP>ZrZF4OKfFaCZ>S(*xLiJipPnbPa`$6;N-@#0*jKI*J70O$7i?<1@`&Wpbf zrF;Gan(X%zfBuz5ztzRxBfsd8@cSqA(V)Kx8j|FXhjbFollpk!vI z@(}Ik<`DZYS>T5DYp3J9WpsV4EYyZRFptUSL&qM_JANsjke>gSKXU&tN9i~kUHk(} zy-KC>89TQ>OtlFY@k!?InG)78-?RPw*?;+$)W_p!3^cw?jzlU)(@-pqx0G1+sYLW8Y!9|k@@>* zoC5l>#0kf}6V8)-o=KF3?tPq?_0N4DV`Nt1k0+K1=Se>GI;nuxDi4vrB>BA9$rX+3 zoQ|)4=;)7%=SPNe+VCi79{(+%!@tRh`lA6)^#PogwZA`4=QHEvQDkcU12;6M{N+=E zm>)fU)DKQ=4;STclFw_4tzg)REu#KA=`XWFM}wMa5|hsb86NQA@h)cm&NRwu@87+~ zlJDt!el+)mUY^I8`%|ZyL&4tQ62Ey2-Cxeg+6E)~-DmcX9w%hMtV!>ASx-8j>vB#& z`A-R4kw)j!_d_vspQMSs-wW?=k@wp+rPM&ATYn~>)6&0l0hdNH`$rWr3TWgbCw%g= zz!%A9&1h+mt#xANZ=K7%&_w3|T=!TwPx9G$wK60;XY(l+FcCe7PRBJ?bp4E6r3EH` z=85K;WdHq?w?1r^U(U?$GAc*VP>)vZe=eEIXV?={P}&jB_dhA+?aS^C4vB zF}~z?$9eJmQss0A-1oS|Pf?@usiD3N%y-^r)<3duGa>BEduDz=fA=^n?<0x7Eu-^^ ze%ye4QJT07)A>wT^B&|6_s2^O1U|_5(B8K#T-A+{qW(J&`y&CK@@Sj+SnO8babD~% zT?3`yg4$SSe*Y!i3oU&XfK5IK=Se;deksB5EKkwP0s#~gEEq+{H~m63WZt` zOnrs@maxUR{rzo5{{K)i3T*C+`6d17oq|cQWnDH?UpIPZqKi^*vBNkzznvuK!}rg} z_&5LFZz22hktu6o&aF#Ke_FJ5E5w?XGUuDK)H0z&wT4gWO4rvLvd2MVl_X9HrSofh z?K*7SqlxR=`$ z%zbJdDe6Cwe0!aiLvOc^#oAcllhj`|B`KJ8Wh_&FpA7GbMvM%^dAEe~B;UF6O3*9b zQ?%bl@_n5jhfLzr@e2dGKUln*zb5I99{l%k zIkP{-;{#}Y(KjqJC-L9EzqaTfc;SUz2<~*cVlt$S%FWI@7P6>a8$vW zIiH%o)(GjQ2V(B1aGvCQ=z2w1t2SBG|0nsjdFX`E%I-&vBhk5a_c7p!$ z1m8xxwxZnm_p!lUI^Qh@da%dIpUJm``+hXo@EgvV_wV~>gg>5?+XwcAiuoq}hhC4N zz+K!bny-@nc=HGZVWG*Q{sPJOuo72L)W~7-Z4;h>lD53VF)4JucQ<%J$@b&?tl=H} ziv34{?;4Pgy3Ew?Q)XMB+k;Z3KbF3b4tZbM`t82%DBP-N`wzn>SD{%|3+s2K^Zg>W zhKsHn##`wLe}0nhEn072sh1g!J3{AMss0P+?9cIK?*u+bzSHN+B1L^?tiML!ljJ*N zy#!4BHkQ|0+i_m}e&?6lhRDWf1rEL-oG1A{d{hC#hD;XCUrD}K9CJp=AJg&JQyu*a zaeddxTmwEfdGUu6grBdD#P!{~;BN5csXx){B;U(BzXrQ3GkkI@ zo$m*#U$~vmIlfL-I8X8&S|@{cY;(rJNdliF-zL@)(3t1U4`>$nBKvEP8V%4!+ZEVo zj&Ppjd!U&DBp;nD+J7PW{@v3VJ)M_Yw!=5PSpCc+vmCPrq2l`|L#_+ zVdB6-W__uz84dID%lM{yf`0%I@5iojPJ@)4ANXF+==^Ic9f3Yeq(t>4xj(bB3B!dY zT6n-!;r$=7|1tdY8}6ttoBtN&SJ2}Nn}79>4cwrSz~opi$$}9-StD-cPZA2?z0fWVU}gYP0@;uMej49nmreGGk6K{Y!A4RWKl{ zkm+Ccx8ILn6jR1~cct^)bUGDMY-;%+MSA_|Z+IA#lcew}Yr4J%eCA>M4lTSlk3Ya zrD$mnl%>5A9|t<$uGi(jdeRipe3{gDZ0>}V-?I6R8lVQRjeYp+RYHD|ApDEwqOS0M zc%VqX$^D#X4%ui{->-O%QY@8k{oTf}cA1!OQopZ!Fo$<{#QudR>Pz)Mc2IvKg>P*X z^f#Q~d;Pa@aL{5mQ=cmo(~&}tT5LRD;8y~4MgAt|{A@UQ=>)U?H|y&P@c6{mXZMv+ zFtnM?@8K6I@HV)XS1h6HbJKuB@aU8jcK<5yP418NuDt?Z?r33MFFL;;C%xhFU9Fk^ zJNjldsIMM?>z(QRCh6C6#j_BzKj?2FjgH-N!Dsgi{E_;+H}MzO=adUmpQAJMQS1Db zOnpv3a^U!R3e%rV(r`rUWuba^Im%H~II_D3- zCoKhj$^Q29b)Pt68^o+1R|QL&K0JcND&EB|dys`1z#2 zcoQ!RL-eLH^*2k#0iEoYi3>*4`Q7T<3C{5I`Fc;`@BfnMkHmlK0+(w8Me{*Ye~-@F zfu5ZFf;AeqQu$rkzZY145bG~lKL!R50*Qq&e8=}EN&ozS>qF!z6Kf|B8A|Bw9XY&zfbcOHO4U8V7gJ9K?E2`vPp zC~d5KmaflU%`dqvW!C(($HJeV^cVL^pTUKm1DXE9>*{~pf!|2f{|hJPH&yQ?5f?BH zkBFf2{pm?7_o@Fle##6%AIbVr>!ThT_`)N}q`epnDx5?7^c6aItn+-OK=8GiX6NV0i zFWxbH)~A2}{)E3+*gn55@%zH$`>@Ig(3_honm>|!H}=Xxh0DKS*H>r%#)kyaKiMPg z4C+#QnEda}O-1V?>+q--bpACa&j9`4lf1=F;m=R%`3%?qrSa+abpE$5ybOisv~fffo&WCg)tt`}D?S7Z{E_@OBs_&) zw(a~&2>g-rouAw5xKwVGXud=8e|DrKdU@Hs*ny-`mSB7ZA{z^9gwyQEw`nX2? z?M*aQ-{*%KLGy%-d~J%r2kEaJV+Md$VGQr6FXVqx-xaT9AZ5Oh$^X{Z!-4Zj<;yiX z{{Q0rI@PiaH2hg3wpmW+|HES^(CNB|H?Nk_W8h-;@aZQKbLT>ePOp zJ*5E$zuZiX549Xaa0}ST^zU}%W?-xw%k=NVax;)+pC)E}yq+~2N^05p!8bMoEpGUN zN1mg{$H>l3Ff4QrZ{X9xx48duOfnUno$(1rl#{u|1Ys- zBP?hx=YRI4$49GcB2>B8@pA&{{wQ(NKG@eLjV<*B|4+upu=N+gp>r1;XF<;o?|VMy zjJ$^PmKMU_pUe-r^Q)j!=|G(Kk{%yJjcU0eZ`kp%;>jP_K6X4aK1{f8oTlak(fbl) zeo%1v8oh3J{}xVhNI!WO#g2? zaszspdmj&P7V--jA7wW+L1*?#zAlU&A6@sPqWh8!czMU}`KrC`-}jKg<(KLHDJAv-T%XO3kI@NFIlCFd`LLt^^q<&|8NTi@C~$-D zAZ3A1GJkA-Qp1_`wHNi@$^4<2@Ecloj>m_U1U||BPS)XOPR(qBX#PaThsuktDA<2B z))_DSd@_IJI!VD}wdtbzK>~^22e7#dC|V;62YCxWpUfYh7b=5H_CnG3vB>=KJ1YWN zs+MBy|LF0NGeHyPS+8Q&7h`2pkd|ycEz6{ykY=T&_+-596Egs1$m9Y&UTLxqf?j-C%)lGCnH1rXWY- zdi)`e9v}Ujra-@nT&BOe@xc$4kHx%6mEa%A_XjT8Zh%Lx9`Xa6>G{LFF&<*3{Ku!o z)APsltUaJ&FN2fz(Bq@=(0Mp=fE^!Fr=M^=-wbE=?|JP?xa}|qyQR|e$J|x#x!E4} ze8F`=zsdNpcWi^FjpMQ3cY$v*KJ@&*a&58f_((DDint%E@h5NLJQ*KN8ztfFnCYVY zp-#j{NLN6EqqA_vDSCYLnyv(gS1%Opmy`8{O=vi(%f63qRSD>%{_jP@bH{gB!eg3|W2*mq{EvO$ntrGjM zaH2lHSDlOw&TL@%uiy2xZIT-$#9Y3yiPq@v;ZTR&a^&^pAe$9RayYIBePn{4yWdBwF(L2sr zWi+!s|04Gbc3V%tYR?7!$@tOk*Tfl>O%Tn$$o$eLQU^U>7KFF?3Fpc9F+S4%=dqv8 zN2mz#OUBPBB@P)L%))z@3;dJ$<^E|!sC~|kpN5F_DE;z%9I;tAPsY!}w;Ir@yPBC_ zJYo{jk?x=Ib0d2EXr0gpyQD~w|03f@~CEuNf(nR+^$ow3|H`_4t(-u?#C)x(# zGG2%;(!Ui%yyZ*>k7oL}%40uZ@Zt&B^MDW^WPJ6I`ob+Xo5+l>{H!kMM??@#Q4r3P z@%3F*0(|$fF$b9H*1lo|3&(@@}e-braeEcuMy6Z@#P?^ z0o`m?i}F)A@&1$dhXgb{{xg>CPmiw?rQPAr=}3NmXotRw=XZamB_XJ7z(cjXsPUC^ zv@ax2+0N__Xm}-|IW6q?s;nCd;p5Yp{o}0gB&5){5pVb=#248=PChdV%p>>m;|~h) zl|#f=Kw1jA6#Er_iO`_N*WOMZV7V)gH~IH{5VHO`x_Ke2wlCtfi|PJOZ(cZrw6NpH zwQM_l_W#7&d(-1beNGPa`pwQy)<4d`k~uoqRF&QzD4$x%WgfO+)<37mJcJj{=A!r^ z^V6-y*W8)jqxp@Sg#1AIyK5&~VM@&eTwmV7pZNaEgq;mst>;AkMS911@qTIfA8iC0 zYnc7BUWR|T(UvoKPenBV`8zUx-iCxCqu1^6 zQ!Jb(<7eF%b%>8y&Fl{t$Rwf|y9V6oK(Bwc_w3%jAH?=|vZa0Ccl35}8v;c$(naqFkoo7@>jcy)*MN7q(Bq>|8-o2!;{5ZHhz~8V6eP(vG>t{zeij~{0LrS#|zfd^Gl|#9{iTs#J@8C_wP@ry|O-??AVZ!$jGYFc31_=z}d zLC1M<{s>L{%ng|C%Iu$6$7-RgAJ$;SKEio2K6GaO;?5P%VAeO+YHU#Q$Q?L1x#PUp ze+71zhfgVsnf@!wJs4&GypM02gCXy8KV0+Wd2AymVkPee!;tXouStM=RR<7 zfA&6+zarzq;&d{yeE1FDpWB)0ufpx!0Prd1{*|=Ue7M--D*q;)ot`hmV< zr#bZaaDOuqUfe&$@AeXYK3RW6*LuT}O;`D*J@ojfz8?ZlR&G@&@#QoB$&wx) z1@=2(z(iiT-4$yeqsK>Qg>vpe%Lr!uA^oxxmg@}0_1Oa7WPIFtUd^f2 zjA7RAJ2!p>6S7}AoXx#c8 zc(<1D=O_JD=_y(0HO@~|e~|sQ#!b52we+=B=t=xMq#WUy<=~yLub?h5p06 zXN6PaV_#WU*qYDwSIZ-fVfp4bQT;*ok0YAn(Z}}t7p(oo)?4lSyA>JC`O7=sIAk#R z3-;PT_g5H?gz53^-|yZl@XZtThrz%k^fCH7mUX4a$4bqKkTv==bH8hBf)_m5bCo|m zogN?EL)Jq6*-Ga93H^!NAYp1fGd?ER?11I3WN~93dj2R{b_)JPb;UET(c@z_Jm7qi zZJGJwwV_{T!D-$m9R7gj&#Ow=5h^Ox>(o1h}d6<0+Fe3JRY`qW2GpL1izN6(3! z5!PMHjE`x%zjMuUvqbSh&L^dRSfS8&JFuUN@bk&|D1Ida&Kvzi?^BTR5qx1Knlq{t zhtzbuew^cIhk1@Nq!l(!J%>J+X`Yg!qFNZDc>G5H| zEDxm5c4hjjr6)_dlbdaMwXH(_B4QrYHYWI^CPD*wb(_iV}VQBq-J8;!=;m=RT z$3;6Cm@T)2>93Z0tUy7b?fK(8JwANZRp82$U}pX>^4x+7`qtrf-eJ`E7`0gkRF*}F z<}2iWy3e6VV%j`f1kV~4n2O{jLpu{mu+&<_FElr<}a3BXj@p zcWeV3D09V*|Mp)<{#R}Iz#Zv5iCKU9m#L%E&(~tyDExe~{;qFn=7NsT64l>iez0n_ zM6>O8;yF@6{E__EZ<2;X6PGaa!%veyG^Vr^TNKdwFEm$%y@A0z@}}1pZkf?&v0ojI zHly?3xTOp93XI}=IScwr@_**F5v2Bu7u6S}e|l?@fWp;&F!RHWCj(%;UnXN~InC!D17ulsBSv@AX#@=xJJewdo)0!}|q^LqdC2U$PFddz{=5;p(MLsx^W?_+*v z5}p6w1GhkVR0Chun_fR0`j`Pm8FDzmlFomhqbFhW2wkTBPkLLz^(wICYhMffBa;9A z1Ma{9t-;vhY{&0ktpA-+a) zGcXTm|Gp+;|GiIJEJ90K@Rf8r-)nZ;Kyv&6(S9$zdCZsO)A?R7J{l0;z=I{rlB}v3nYw?>Td-xbE*AMfaO>i2F_ZdVYqwG&j6SpUyXT z>>XF0Jc&7<^WxOd<+Ko-cc+6-@%zU{x0<+3k7kSZuSmY1^&5&tJll!ScN2a-sqY>= zq(I+rDO2C2%M~GU!&=e&nyh~Z=WarCGHP+)zBN?7af23I`oPxj5LH8%7$@eN^e;oV zY)47ozBBdvu8bL+ZDQ+prba9>^J~F-meBdmdNmxbwXyX(A$BaNX67^XJE?6Zq=Z~& z`j>Bb1$d(>Cg19Ln_&*u$Y&`C`~ryima|BQE??Pv@5((6W!bve(VOmHDvIxL=UwfX z`rZ8dCd>^Rj066CACc_;sI7g>-B{$rFFhdmf0FNjd;h_;+itk7Uf`3|??GN~IkN|o zME6rk{YL9Mp{m*t{4`%UPx=?ngI~C1E^|cpH%PvZnh!zuA$nT zM!}V+My5Vrj!OeKM|qL|Ap4gOjva&Mi@JDcZ#uuK4Y#-`Ej!+`8{K~#DlP`I3xjde z6hWU!eivI+a_6qI`8~d*4r;nj!pHyBea{h-g%Eav{*+4lW#^_2&i^`T)uN4P0bz{^T@ z_#5&4xZ=sv;q&Y3e8Mn#|8S9Q01Q!i!uwvQ`-iigqd>Q?k#7`zze}vI+t;N+riVNp z^hnTO(mxnh9EH#x-LT0NI-gs{+~U6Mx8t+d(fQQkZ@|Y7gYjuAflsnNGr~LT$WYuA)WMgS&za*JxO>CrithiD z_kVbO3zX`<3*SlZI4|aNy1WGZ9Js9geH9@;ko`mL2zj`=G=!!$Ih(C-kN&&o%`!0^C9roVNSbpg}O=lLt$g!^GR zAm(%Yl4%e=_6F16!eoCKn)-yfADxlC3Cx#%VdnqdI0d94F=-Crj8Y?3lZ(>LtG0~U9j7xQTs_nW($ z$>#HGxg3;ghBEidb}R@-);r$guh0Fde7<_40jO52pXB~?Wkq**c057!J~+wexh{R- z{kbe=eYUd2683dF#OyDq7LSH0?gjj!Y$5(6keJV7`cok?(>LLLLz2&|?d9C2ZDX1B*D=KpaLvt~S$|nxd%?MFWb^59KpDl~2*bTTcJL+U zGw{kMZg=N-qW3pRJ{{Btp{1vH;c~Z*^I|?%tZ3uj3|P+WFZUZL2gedanfZNS+-aV9>#_e2pNd5wyJZNjSSs*I>Swh@ z8P}<^vuHj?`p+Dr_fY8V!MvZ5=>42a>F>$R?>BOk&_}2BST&c_62w`N7!VPnrI6_Qeg5{h)~-^Hk7hvj4O>JP~@1R={eBbUqEO4nk=UJ!XEl!dJPQ z12|EAMCSLvA|6!t48f~<(fOQZS;|dFcNV?xNAg)v{T2)^vH6rb@{AiR-Tr>CzYyPK zeY7(`5gFI5!?jO3_!8&$>_4^KI$JNM{~V!fhLmiwv0sDWpUM8Ji(M<%)zY8YUtO?y z0cyVW5Z8JMKcC!ReI+de+SkHF`Jd#sFn0~AU;Yl8EnGt7ckSg)@a9Z3bAQ!jnl6m< zPZZ4;NPazU7{m2iHowzaEMSAgVNv}=@;g@o!L?gw_-$H3eNXax|GGO={4VCp*U|lH zp!*`Y#y{nUyV2`=CyfoDbKL_=juP~dte^Jy zJmm^zu=!oRLjmQPuV?m8i?@B?ti!#S{?yB$KRUQF8*^{z{JQ=3jq^F>FY>2k{(m0t zgEB)O;_P_gJjt)En=~NDb@O5YyLa$Hm_6nh zFTIh@?<}VX__^aNQ-8nQjt89_1w3dGo!@iT`@u9+5Br{{^BW(7xpOzz`uoSW5We3S zg0&+Be#1dLzx9_Z;q(KXnfK4W-FyX(r5^as`wsmQ-yc}t<`SoIS3To4vYH#r2d|$7ztJr&Wif0Wc?Lx<_2r0-Q**T>HJ0- z`-1DWXUzH4z4q@bFZ}eCH@!>O-*S_9&~8+~dH>$0B>StsocDpk5w`w%2lAZTU|{wK zS~V}j0@a}+{U!O`#^2#q++_26&;2E=R`bLYiv<2i{dIf%nA1~kf8UqkAF3MV(1r7C ze*Y_c$DKFuX7*QC*Y-upN3*f7kH8Z_iVbu;KMOQU8kc2hlTE zp!;6$@VXU?seFDMrviR+wut-z*}pQq)CJ0nlSKZ2C;0sR(Fn44?qu%g-#t4JG&9+J zUeq25uiDP?$F~UnK!VWM&@Qf!R&|rvUv*EO51FlOeVwp%JxGsj=2b7#`PA+n2UjE& zas7C@zN!u03&o{+IK!W=udTlexoMWb>T6@bTx4%ifmO|f^Q68mR*{6Tb?Zg`faF)tBM|jadygNs()oS2 zR2g!%Y+?4ddf(HAs!2(_&H;fh(%;VfX$W(kv-usMIuM%7kBItPJh9)U{J<6-^*ATm z58#RUz|(URKuhu#Q(tTSec*TKbEdxL-wuOY^PBng0d#)Hd2NRU6BL>LcBR1{u=`IB z*AJodyG*B$TbKyE#Vmn8(%%mEz6kf;4#l3I>HMC)bBl94;lk{16-sp_`*)rF{pb1TeVyJtdYyaU>t1W`{ix7R*zx`zvAQTd&+$+EN1t~r2GLppSU;N6dlGCh-;|(>*({>Tj(#uP1%pd5y#~HZLj35s9y6) zyca3YZ`_eU{N~z}>u-xJV=$_pCQ(CqexEC4!-WTYejl7VhyJc3$cTmV`NGw}tKeEW zmAikV&Gbi@5n@T)sQp2-ztva02Yqf>ar0T7!^(m&xRZPpd43O_tOEOzMb!P_tiLUA z(GiA(Mw6^d5`Qeet5V*>e`D5i=UY}P*a|C7-Xk@Qq~}?FuPgk4eJ|ap`COJ?3xm}{ z8;u&094YT_&F?nF>396ah>nuJvh%s&6WZhN>$HDh_4i4i?&vfkl3Sm3dfOkpmnMh< zwWXiW`dg#3V=%@)Q*7Nw`rMt--_>^0u$6OxIK5W-oIU^TWw1T2OMWai9xTuAg~3~J zi0)@G!d;%n%h z{Dx%w0`r;fT>o&=ah2fL_66w{C7&+@J!pcaAN)m)XOh2W`AxQLhYHPtDgVpz+u~kV zyr~^2l9-0)>GP#^F80Iq!3m=NkA~0b^KlOy*2mhXnPSLTiBFc_^uANk|3(2fUvPC^ zfSD7@MW?m${O-KH314J>=FY#|s0zT>SDTWgp%TArefDO46wcVGNqk$&>+fBMbMR%d zK+R{d{Hhye;B{q8avx0h#%E_n_7((?s-vnFHU=K^uiHHlwVU$s8l;(-0-Vv)T(pO=Sk#0_d+ zxc=amasWn}4md z?JWd%i{a)6?}ax|XXqm4KaYf9-SyZ#?9yN~w1v&q{Wi7!?^l{Vi3t;{*x{l^xribC6u z?nHyC|LOji?yE;|?)_qF{b&8_Z=GJkp)N7x&Sy#gS^YfL<29^*vtZ+Vgb@{7{k-L{9*r`;h*^8&{b|7_e{@{J z*H7Jb;b_*bE6K`}=d+ls;4%k7Rugca}V~SO<=|jGL=00qV zf!BjY;otpJET2mjcgB}v>hGt2+OR&;{?oa=E}CBB^JzY11m->B>*oMvV|=^(ns|Py zJfFV3=HZdq72NvCzr#9Q+2SjgPc6|8mmlEsIsDLJ+$wbC>ZfZ?I<)OHUTl80A%CId zRl)DhX$(71ub)Td`HWvepyydrZvFp!$X)DJIh&NMmgm!2w-6#%T65R;J-`0ok4Za7 zAAp~OBR9W_`rcg_J0yk#{Hy<1KD8ZRKvsDD{UZ9(-=AIIqaRxeqd(p! zgGR{n`FibVSUY0})!$x9QDDVN?0_y?5dvjNHcOv&qnO(Ec`_ntx&SQ#jjI-)y6VgrM>;GHdFJA}4SZnV3K4QghblR|kOd!(pET1haN@3VtzJ97M z>MqPJTny-#xU(-&Wd;&!uhqTAbs=V?A$PMUy8r>=?C z71HNyeROyE9L)YuA+G2y??3Z;ufhEVeEod(%LkWMHzNaoO8m0*`)rRe%y#QaJgw!| z_ml5WgJs_d-1WV$R~iQX97*o2l;?Bhql++dv>CO&v-NwqX%TK6U_}-xNqn(7FO?#p-AKgU?{a>h)Cq z#OkNQ77O7CDIv|5OV6|Z^PAmAn0bn?p9>c&VVw`3&;HX};^Dm^RKCRO=Vtegm{!H- zv+>Dr7=eQ@c(WuoEvH9bM`2hO-OVz4X zxOu@hZvVe-bp8G-o#x#7=w$Xmba>vCm{a#>(Dl*01E=5=OyK5A-&UmJcO1p#GtWO8 zl9riq=T|m-y@d`dt%z=2!{3*#-!Ba)05WARS3i9h{6LF`{PkV;?LAO2UBd0J-n8gi zfB(=CQdhsl=zsS+uzZ#`c?yTq)^peQTN*QkimxT4=``timQSPebzpyQ2R9$hEvpuS zCphKgt>_~D@B0S}>Xd={&xrw+TaV&zs8L6r>wp*X7LyFgP`%}A9-$T%7kNWyb%BNWWX<}C;bX?+;6KNvP=iCBCeE*uSuf6@6qxL(R zPgY-zE~}&F+GueZmCw`b|G}?4QTNwL>i$QO>HoiX8-!b`&r$Q)Z2lCR3|QpJ=krUC zS(xhmM1(|neSI6X9FL{)`TV@u3$HsiC#HAg*MGzN2k`UwZshegc|K=`Rjit zqh#E5bQH0iD9@+!^7HUPZ#u;%n?LopEyTG+R>U-|L7!-SeRwwyUi_rj|7hlZ)3S|U zv2cV3w|=@e`wr;U^7Ym8S{EVh(GhNb4^>Z~=ZE#w{p;-d-?wtQ@F=I0G~d)S@78~9=L98z$v;qOcH>FJRRp#oqpwFLi#yq}$&ekdh z*EvhM`UxJL1&_2N#Bz`H{p|Yx=tTvbNZY_&|CKkG3FGgVl1(Pk^X&Sc_T(+}iS`h8 zjF$fYk-2{)ZL|Vjn6`^sKMkwDUnq3o0Wru{s;^o7>^87H#&oK`ADwePZ%Sr&eB2{R zG`S%0%lgynO9x`!qVrt+%=;Kew&?guTN(xcR+R@@*(iuw4)8*;h`P4}zSJ7Ez4w+oo@I1|D!1T-DGHX6H|Ig~@-rSGq zc7fJUM7qBeH0>57t2lA>bI#>X!hjV=$;+P-Uo4;Ne?0=t=2kG^3we8vTM<>3sbxdD$4P6Ay6r2gW>8!(roMxcO7+qpsNH1--tr z`Z>6Ne~kRi=X30;v8XeuP<*>XUO!vbpWm$4s7gHgR^ETw6g%Q-ogdu!(;|Z%m@={j zdHY13&&!|pW7{9yNLT9oLAt(gQ=15h9gMj7)0DV){BPN4lJQj9|H`iKCzQ`ZlLvhL z9Je_iBMs(|*J;w<7m?<(?ks_0^?VNeBpvIXZ-d|F#&GAG3QuZckDp20{Hc{qKP)-U|SV^C>P zp;%}m&*#?jrucg%pU>Jhi?QwKAL1u%i9dFI-#E=3Z%l1LRwPKDv-+9yavxsq(47P+ z%j;+P>jY@I)`+{lTWycSmtLbuXo@_a_8-r{eEk{R`Mhqe@=$Tg9P)9g^!H`?RPQXp z^bzx^`km!7;Nv?qkK^-s&GQC0?sDShPcIjB5c*mlC8Vc3pAjWx(6PdmTfYzUFcDIF zmJ*kmhWQ)1J{r2Arv3y&PjQHn^nS7R{d${k@T6jwc<;L8583|GEqzs7-!qh3ANjv) zjTL+Od{&+Af`%iLxqP-&=!;qI7r6CN>gUlI8OP^y|MY3N)ul=-J1?)Ft-=?g_qHEm zNe78PmQTN4ZaCP#1xd=4K4Y(p)6yyZbs3MIZ+{X9P6I+T|2`P93h zE}Xn~lq?I8o@dwh@9Roo@{o;OKBJ0^gre#aQaN6pPtRx1;E$~*w?FUrbgH22T274H z&-&Njr}NSLL0`emD3Dt}>1|QL$*V%Ce4o|VVZB=8k}CfCpLn-34%?N?^{3nZ=;F%4 z3)FlbtFKMYj>6Hm3%T{Z%dn|<@g-khf0#L7`P(1d`o8_rZTK~&1t|=d=Qq3k-uis4 zJ28FJ&_AWu|CUj4@bdwG{WtVDfuGy!6W3ev`l^s|3KSpD;QG@*%_~T3tVz$756}RmL22fPx{~PL+hm* z`Ro6niGu2x5)wk)k4)>Uf7DZOIqu2LPtPBjBKTY=C;eK<^P79-Gi2`wr1B|b?thD2 zrHn_NLb>(-YLix&tbK$#f1*w_aAiDSf5&C(V0!Td(Qadd{?q-_%J{K?S# z$vCoUHCKQ4KVMM4|L!N3-&WOIFrb9*4|de=4?MQFJE_T+=Xd-bS_oabn{rw-j`#t?Ca`0P*HL>e1@yGI8XK?`n+u3maf%b&g7}&~_EI!!q zJY8SekGTq3eVnQDRoVHy-M`ui4l9n4g{9K-tp0|$-GeC?`TRCHG+vk=UqaTHNb8q7 z()@1vTm?S4e1G7uezI_TXa$*NF3<1c^Z!ARe;{{0rSkzL?07PiTYuGhwnWtfN4WES z=~ZX0zwP#> zt?(=07|BhN=XdbPyHGoM6L-EZeYYUQk1QqU!{qr58(s;KC7#^;->k?)=&w^ju3fZ{ z^$!_VA0e)q)?e2Dt~}5P-LHg-*~U_R#O7PwhPS|iWk4Mh9*e10eNJq~A%^7S`B=_r2i;q&{hbqYL9HRt*V^_C)zeQ!5*gzreFOo+NFyJioVZ=ED5;%eefu>eW{0`TQ6;{z{(T=YGYYTF-BG zfmC0y{j1m_6kHmW5mQ5X|66^e0&M>C6ZkeRalx;&_Zj@@@t=LfL- zPPng#1Jn*u`pfcb651SR{da_$&${opEzFFrpHJAXBHdppbfWq)-XCkr>$BF6BzWI)Cf8pS zExU-rE?JXb-6efSCLdGF$^_3|wp_k<2h^a=A5TKI%JaQt`xRJf$LG6!XdB_#l4E35 zp7i~!ztC$@1Ut8F5>F?|^S!+egd1^Xq<^|R-+S+rgZ_3ev1o<#Jlp>=XlEoCtgIkc zr^xH`sQ&NaxZ!TfAG3VBt1IGRn}bw-#`1k|RWnqoI>PPWsy(?W%nNkNxj09j@1u$8 zxXdesy1$au?`uB2Fz#D6H^2DWVkkCVb&K0S^U#}!uZye2L=%Z`cckaLG%Dtzu@#^1 zIkVQI;VwSkkL&`lZgvl@|M;DM1dLjkaQnM%kS z-zw842+kubNc;8j`h9tGE%>bD^F3mW0zQm9$jvW|BAQ~S2}il}GcJiYg@U2Wa^6Y=5p=+;T_yoaKAML~FF$ z^GjUvKwiIxySd=g<1NW+7skKdAze1kx5N!f; z=Pwg2O(Z_q`fzz+E8&XjaT261?@!kLDuf$NH*@(mnPn(gSUn_%+eq&R%lB&2hcF@9 zi^`8#zPmOZFC+(5knkXRzAqNMf%cJnzWvAlhN`fG+AqzCFkuGkJcaE=9xg2PWM9@#xq{jC2@7tc@D@qxW}D>6rkUaWlF7j}`OJ zVcnFuB>&(2tSrAL?w^70Kl%LLxl@J0S}!u)R-Rv-p(6BCTh2ZI*y>zMVOGoI#QTQC zAL~CdLvPd{{z&u7`s+Ds#|bqGk4V#9((^38b@lh3MHJBdvi*B z<258**v-wC@7(_h>p#-|gUy#eCO5{lkw>}t+^)d3c%xS;SASP@>5ex;FLLX{UG4So zle^V>8g4&Gjv$(9-2-7y@)P2`O5Q*JT>KLBfAaPBng4e<^!^|>-*7&x ziUtKox$_a17pvhN^HgrWVXxQ?%RbZofvx}SUk|{j$+x-r@{4dothoPFtW=l$@e@XW zkCx2BS8;s(eYbNZ`U$PbKx%(3eLvkIJbi&atVhqW6 zChs3kFNlSMiWXdc%Rgt}puzJSPl%3=Jij+QYe2E}9`5`^nZh>+m=;F$r`?(J5qBo5U`~r;T>ZUh-3E;V z`1}?XYhtR-C2BsB<@ZW*f7~9(=eKn2IJ`9PnP@aeo?o}I7P!CsH`o78BFj2R7yP~pdj@(_`7*1&b27&X?x~gJ#!&hG$fLW@;Cq)n z-1*5O(=VX!97g4HEWf*6DdS74W8Cv&$`-Un>y%W{V!zbCWAlmF@-A3^bQo2?vHWh_ z-Vc8!-sa}ZW556hM$r5sqrVBy%+W;m50~GEBbT9rM=P#>IPc+&ZH;=8sUzk2y?^8| zHu1{na{>2Wz)&5u?^O)PHn7q35nI z==l9KrYEaVKBL@AupM%Zc+68?A&v?H6 zwo6ySM5ANe{)pLvR%rE^ufOJ@oiT6QC2sw;u1#Njc;+^De{W2|7>p=*CaR5+^q1vV zG?;J!^8>u2ecx6d&&FXt~`_u{C>HY1jX5QV)H+e{}!3~ps?>{xFyJo z1pGUHiQRuzXqg4IK74+QXEqf&2b|#g-#+HK(CsPTKYV^&1Y_L!`uf3mtdO*#iVX0O z=d;ka3U00A>ub%2j}Y}NjGGT%sceK(gN||i?YsRg@%W-NZhymKlLnrOyCjw^lJwV| z*&k_Jf4`XLz#^``rmWM)qCd~XO*-;?UVUhWW8?mC>$6|ym*9l#R^<91c|Nb6^u$A{ zJ-Pn&e*ZAIl0Avr-w1OL#eJG%$+sC2pKSg+tM&+-44B3B2aD5B;acVSr1ukffAF8@ zNtoGtfq3iR{zI0}-EGRya=16~e%hdq^!x-#$biAoE2#UI*?eqI^Cp7!mJ=ktOT+W@ z{a?RcTn3d@TPc4aBCW4KdyNt_S67fB>GJw|uId(etoP=g-?^^BM9@wCNFu9O$@cFG z1D-&kA75YHl|DcVjYAZ_Y`#!gs)&=X@%i23)B;2HrBU;jY=7?5(oWd9y~y>qr*d`B z$%W7FU7h;*%#F_}f6MAC>0*i-ivEZXcXRah{bKy|hR^T&Js$YvYESY^O_ z^%<+LXHx3(;h8JB{pT;M8w;)4#*(I@Jipcla^ULSt=##wLtAb_LV`E<{J5}Q#zK($ zM>1PSp3h!&<&9Q5a-Wh3Be~sm{#gvXX z!ce60FV?@Jvo_w|P{dvT2YniecgmiN>o>{k>(AV&sM}S6@Yet5s}^CUc5Bjns=U4y zpWA^It$K0&tM=Oi5I$@&S6}Ztgy36``t{#fp3gjoXz;l+i|b$Q8l|G^nEB+bmpq^5 zs}kVZ0DEr!bp!9?%W!W}s3GYa%jeEc>2S+IsxN=5zsOVanV^_P!VA=GI3aQkb4eiMZ^TRxJ}C*|)CbLjIJT9G|sYxjor zS(WPV4OmzU#vL!3OGgoI5$5C-+x{(+_og=f`O9ke1ztdW|(#}jmpPZzV-We z!0II;U<@ZZ^fa*grF}Kq~&sXzO$5Xz_qC~-)w)PmG=a}Z}5L)l8wAR&p-DN zuBh(i)@K*?zkxgJ4^jO!);}C>`x|1W9p~zEPi%@MAJe$`!kWkJQQJxsFL#jMFP7f{ z{d%KPt77i?U|lqZqk5AXD&KWy@`bA>C*jTU3dEN>zm}fwncB%7KRLAK)@LWO-EgLD zFK&I-#XlI-QuzA3`1yWZc62P+R3yzGvi|qr`v^F;+LAlpV=^WQD|XE%>i_z4Y<;$P zc`Srawddvw**}UgzrveX|7hTk_P?&yr(no`E4lfCLxi$$JwKM5f8X#t?SB*SBDmh; z>$A4PP+^kS6Yl*Bd6@<9PThy=e>ED77drUB19ANgMsQSZup@@1^NKIhIl z0SAdacRoJ-WD)9V`4AW_=_9MpkxFSWY4j>C-@UArgbjhQ#Kc&h?~#hxP&TXn{;+@N zGqU<@v*jvOF7~1FF*e_ArXvWZt3Q!utL5)^9@)GUjE3(O3mqkX*nBLo-%D`(&9C3` z-M+(?SI4>e?goX%SU#N3=WV~Xn3OGwrluFIvr$-fwpPY}K<{ z7_aF=Y92{^vHgkR_4#nzN4|e(eYuekuNTMNAHVO{IVgO%jhpXA8|1^WbRX{gP5Ler zKBRsos!D5R^M$%Y_o45my`n{!^!I1^OjoagMRkX${x9nfYNmVzwI_UkVBAR+yLp`w zt+q)&pVd#LU1}((5pi-q>2p>;{r$V6N@+27er&DMV06r{q2_;Cf1rP70zTfPK#sp? zsPAZhaP!$bRL$k{xqH}Vj8y5(^|uT9?}K|GQ@HbE>b`rhM}GtIIvx!s*>Lr<-7u_dL8ES+j`??SO_P${@`k770jzSMa|!^_1TNbZ7=``c;CV6hPv`rCd9Ky4 zY58F)e_-{uBKSYJw*3UxA9QJvCWLl$%sJDfk!=28{89(7UbELR}k)FpmJhVL)+=kHF^YD1=elRjtp?tXJU z25I*u`uF7hL%U16!Mtb+H(v|#48-+m22}mV`iGnQL*bgmY_5NJ9(4lkSJ{x563HL4 z^;>Y$7J7N5 z=Fj5EF6cgs|9&i}=#Qo@FR1xT*1v==092?`Amodr|Iy6*vGw?D4AX2w{9~o}gZ0<@ z2d%?Q+uq#z?{jJ(wC+8X>#v{q?83w!24r5Hr2lOF7c}YsyqztAA59>*r&0{+fM1zEvsW=wW>R z4JNe2t$lK+{F&vuD7Z5wB;MiHk9&Rl;kTnNxcfWisv2VV-iloPU+`fT{v6(hOx`8W z_jseVIBhFm|NG6}1%bv>x%xlKB>-E@8%MV2NPMz|zwea3f_+I9*|MbJ{z2NG4^z7YkIne{ui1KpaBIT{g3aam_E5bEjs|?by~IRe zVvEH&8`S0bZlqNX-nD%HGbySTs>)Ar=QC#4D&X^@r>XvmJG1}v)}*6C@lER-tv0j% z>ica*-_!qVj@HIGqJ_Ei{;>SF9HD`W9^c{i7j@M7;+R@B2Q#aMRDR9+AAf~BoL}riEY~*pb2`6{tULi$ zg{!&#-pTG8dK$)a&%YRJaSB8=cW!@C+g?YA>sCoz8%y8M_7}4zWkZ~kFIAti`kr7k zT=;t7BQc1SzdyLV>kVi*cON(Z%X3T++N@rjqh&15|ANa8LGAuwQU6Z^e~qbs|G2|% z;6(RWZvXLg$Pr=M=eapuSAK{8oga_P{_K0Xe?afcX{x`@z8|9Q5#gi5+?+gf`S+vo zg=YB4o&SC`zSI$$*WKaXU(jrmF78r(DV~mz_Mfo%_q&=g_|R98m`;%RN5=n5+-{EB z655c0oQBWo{^U`$mFRH0H~DlyzCQ4H)t3^wXuOQyTXzaN>O4#Sq83%ULGAKq7R#|t0gHc#S{T^~{-kAqdyHQe`Of3GiS z(NKhfdhRH#&U=hnYtdT9#;DoN8flK*1g55LFf!7+e-KiK@{*zplU!R{}_%UnJm zS3YaXpTsxo?`JO4$Mk))|6%#|$e506 zWBB^7F?~74*7YWLQswzpN%w<(_xOD4p1dojpXkYnEMMon(c$iAy(qEEAslE zeK`s>^=!#$BYD1OyBvZ)DvP-NopxVx@Qu1JIqxjbcj5A5Fg0oox4)z0{s{~H;<@ur zjW?t~pe3#U?o9n_si!4$RH@>gAKz*AIaqRu_CGA&YsL;2Ol!Vy`#-jg3t;i(ecXH< z)|A3nqj2$=p2P>6?+p17BXp^?$vG6J@mIeW2puW?Z?W?QOgD_>*1x?Ien7R!8E$^L z#j6QIS&mpZPI`aXe8;7H^Y1h>ec_J>%aT$S^d7Ka1_=aUBmVF!Eqn)&WU*L`A9R3 zli~JW+TXK$Px{bX@Z4EVay8`r{pR19kWow5uPon9-G&S0lfM(aG8g%LXM8?vys%FU zFqQaV`$w2n-(Ru`=jJyKQO{x4lvr+kYWy}*xW02(6I=QGi$5=6`9fdv@!$RMEdPhL#lWI#eE;Gu)?wO< zc<%Z32KDpdOLn?b^Q|JI@5O_A3%kOfl40ud`Av&98F1sFFEyXS^8e_Zz7X+VF~{C~ zhb;fLzPS+el+XX+4|ieL0lvP6-gpX@A$exw+a=F`nU*&U*v#kujiDFj zUKvLs8q4$lbVVRMSD(Z6@7dyE?0LqPd}}4o|BDR=AoL=i|A&efv8S~!`PD)4H*CIt zzk4*yGFi**zqU$#hp3&vy}v1>C;@iG@csMFF1-XVn`hko@{dP44D0Sk)weAF5aptWtkJ*k!8!>dy41ETh!W`ZwRds2B9WI)hhK{mJ_CsDZ=qvqB@{Unb@6tbV_L zHwkq?jml?O{f>27gdW@Z`u#!M3yiC$ar5`*8lLEJe;n!ZSlZvf`j=<6yCBJ94tGA* zXZa!Qb<>t?d)2@{eZG>TW(cf)yokytS^x6w^Laeh#h0Ybk?KE|Ume#-*wkSycRsd< zQY~KHoWRZBXRnWkVYm7Eoqei@5ajfXj94$P-+O*x5 z{eIOt2d)p>&-E`FV~QZ?HDA9?zCQt*mT}zq*g^H@M_y~3PWf+^-xtct7#m0X6P91? z?uP{($N4!bKP3I`!RWX4qBa<RVyeHy@?FyZ92#`>C4<__^F2+70G))jTz~#E@ioS;OyK74p?R^8 ze&3y%k750Zo!uz_N19(&fAxls7LM#w&Z#Yy=hwZX2%3ZUbM?2A%`MoY9>J|IPZyWN z#IAAN`f;9S9R&4F=j!hZWhHFc=?ZuMO`dvdygvP&_+_m;pGgYca8lSSafiF)A6Py| zOc;!hEgEtCbIVaiSYxb4mVB1`JPNv-Y@nyL?uIXz? z9{)REn$=%54}Z9{Y!25yLux2?P_`q!G4gy~ys{tqlEvKnbybzK(8S%Bg#0_7j@4hg zZ--%SBNwiJ5Qo32Kffe_d@+*mfA-Ee0fh$j_v3QrU!A{c3Mn(6601n*c{cy+S(XYW zetdp6myZ;#6e{PO{3Xxt>e7qw>+pVV|MTSGLJ$r3{LUzN1l{_@aqGt!_4og|=%;h* z!}1bET+#muHQ&P4htW@4qLMeC-_7SWv7qXesIgDtH=3E>x?ZY>FSazI=40KN{QBqh z38=77jrfj{{4cAox6*9UxR$T4%a^-Dl_{U!q4V8v-9$t3BUau&JYMYwF`xMU*VyI& z#u@VY1$HQbufyIXgO7`!_;H|=U$Xi-t!AX)uBn<+aov#&!7 zM?Rm!RUg8a9dX?A4OAoFKLT7pXUGicN-tpW7eo*QGOVoXzLc zpsYW(Pon)R%jcefh%1BD$g@lGe5Mr6MJEkyGOD{gpJ(rGflN13afpkgAME|62WvOu zrf`~1wtq4|)*Ci_o+GAtH9SxE&j%z1;Z1iwpN9tQhO&^wqS2Fv=NnP^ONakXqho?E zx!y(cuPmPiv7vA|+J)<1%ep+pyOxRE`pkRi5x5aW`-5mEUo)!fBxrniN?Puc_-6gV zwX#Go&+`+*CN=#2D%9`ab>SZ2(ILy6ez)cM{V_NTRO9xGa7&u+W%>Qkq_ z>T{p#f3z@52u&%_19pbA?9AL_YZ~ge3Q3xFk-njw?4b-y9u7( z*3xBvaqE&-xc{HgO1 zSp9vQ94L78v&?xqP2%@9qra&q>+k3M%GY02r95bSDnhick@#ctvF&T`g8lY5v2kew z|Fr%-8TK69^Z5LFkN*zN`B$j@H7vjBx0>KQ;l6m!O!|H{Kj_o8Bc46*T1+>S{4L98 zMR*?!c}3@Atp0wFFhILXzWz=wosI9@w8@rH^7=b5-xW^#nQ_k_7y50$X}4%T+4`*8 zQBOEEZZ3cSZQfq|8e&(^R|DU4KK3du0BYwua_5(7&ZXj_ti;9~v+ zyHqEV#0~O%mVb?eJ-Iu$^Ggol>cX8(PsyP5QohXU@58V-xZB*H(qEQejS0I1JuSw|&#lkyb$bc}l+JSfZ+ht$nEL7p zmG83ruFY+Xql)f}`sd~O9du9~`0G z&)Sh+mD2O<{OP^@J0Vbc33t9oaa0PXY59?dg1mpoatQ*{ee1aM7a?ioxWn!w@%${$ zuieTBX!4xqm-P?T&11pZz@OWH%hWpqE5-+L{cG`r9I#i6r1Xmoaa+`BwA>ZLHE#A}g-R^S9nzA7`v; z%gqNuD`w)p>)OP+zr22?Myv&!?PlD3OZDO!Y|{)#*I^C((C34XdEgHEnsd49`!s{y zxbmGH>GHbad0Ia|RQSQ#4USy@y3;QS`?c{SHRbZ_d$PuU_>i!Un{Q32euTrl`TYG> z3x_q0Jh=LK@9=S$KbPjuo#`Jm|KTSz*O`@*(^%neef5M{-}8^2f+G%mKDRFv!Qm@i zU$K0C=ynV0rt|q+W&8vlc%9{*ud!*(M@TZx_$FaLC3?B<2nE164jKoc3LXcXfa~?ke%e>gVPqZg9_OF1Np{{&p8OX|aG@x+Oi& z>Zi+fU$FkoU;pR7OT->M{D_Mv&+pavy%3$hj$417#D{2JbCTRKm*#U=e|locAsG6Z zpKmE7s|l(fpOQ@`^6UQ??PDLrbDG3Se3vqOr;SL1%9J2({xx*- zMJW9fAr4tBt-tQf`Ch9{3*mxyJa;~GvOzgCPoeo1nfZLpadlw4j?Z_Op2{fBDdFY^ zgEG``yXzauzq0H9y+yrn!B8b~d6m5W4jDKSPw#I_8Y|25d#%TG^!cJqZheo zt*@5#OF;ioek9`G`E_i4)v?tcxbTYaU!UJBMd!ySN$5}c_20DQAY9h=;MP|Kt&hOk zMgC&U*VBLVSC&tONhz=`KZx6()!lmmT91kpoBB!ovHr7%#&tMzgs-nhu04dU;#tvV zsq{Qs|A!^l!mxw6)cF~#|J<3^2nX%u^XH`72Kyd(!}Xtm7ki-gESf)7KbKn$$Ca6U z{sO9};a(*jVsuTOzt0nvfzcN;Zob;@zBBqQ0%G$~@((P3zejF{{df5M6?fc;4~H%w z@!RD2J3q)9Y>zLY=6~7#tIobSd}QoL`Uc4B=f}-~u!lP+x1DL zcapq*4onDz3tK#>{ub*$GY&?>y?y@TC6an$>BptvzoOwVZGi_TYzhZR7#0zRMH4wb>g8)v!sRC?MQI8~R+oo^iPrih=8 zlyK(*e%)<_+1F`4k?CKJAJ-kHI4hCZ1(H6peC7ua#S1xYiS9$`b2k4s8#EOwOmw*V z*k{jD_4p*?@zDqi=vjIl6$>BEtluBMU5-G>OPMny@pE;}U;eowLq~ee~pV4Xu;M`W) zpR#=FwT^<6R6d`bUL?Y)A3@^e;SyhLJ{sea1-I`-Qu!#Wj~f@{!_!~<^|{TF5@@HK zLDlE%`ut|_E3mD~6*JyR?oc1#S)S^OJ2xtkRpTYT zSpIr-9D?H-wd2<3>YXQJ3(z5or{wi9b@CFJ^+?l<{#MRh50ggB zd{|EzEq%u3C3D*yZbS0BGJ`gmYw0x0$m=C0pe zEiynaHImzZDzMB2ebod}V^Ra(bpE;dz&*$uK=aA2-#S(=pow)JxBqm@@Hb3tTgt6} z_G-4k!5!a<7A>Uuhvl=WsV06s#@9!^*@N&+^L8YkI)8}XpSIoH1n0T%*YB<^7C~R9 z>D>O4YOh83Aiuu;xhl`+r1fi|Y{)!n|4ua0{ipd_K3EyPfV?x7=d=Cj9iTX2DR=$O zk35QoPJZN9CwV?I=lX-vzV+OEUU_m6dWd{J7d+e#nSmbM{{G|Jhe4~7&*$)C+l8Ti z<~a-d%kz1Ec^sq-4(8@dmsY2PVZDAf^ha6!{A_p`Ms-i%_DAiE?!ayR3~@zYiC>n_ z=T6VyOzS*RH(g#o2m1ejV>+eW{?X_&&2XO?%_m#mOxWES!y=SOmw)#ovHDpTKM+I5 zwd2+|UCoTpZ@&)deNkRNKi;>8=C`JE^QEjJdtCX3ub=bnR>PB`dEEZ}@C#m;m9~Jm z^pfW@`IZ~l1~28#_f_Y_pw?_Z()g@2zs=S+3p)8hN!JbB`dlsi79JgwOjKUU>!;y> zeGst6gF2s0Wcs6PW*maJt~;su6Slsws@Wo3@-)x+RQgR;Kc5~v0UIX*tkURj@-ZPmGC?_!OD>>f@T0@ut0e}b0^qAelA}>Kcw5? zwywz4PlqKdAS;O0Pj^N?3paaWhblgwuRd;tKf9Mw^>;LLKHD&dXiVJiN8Wyr=hHXV z2d<3Vz+K<_Y$(KjBa%t$Sb09vzwd!XPd%vpF|5D*a^xVSciYLWzn8Z=4s&+|bN%J= z7w*D?;5j+xEJyz3_bPLK&)`>S;G|FU8O`KF=Y221iqHgZK6JhLt@{2hUqAhNR6@IB zdEENEqtj>jv9y%i-~7|G2|mC7mRp}63GIl-YiK^*nSArRX+Ko*<@?Y2`l-- zc`3KQ>AfKm3nKgo7=hMVd*M^TxK(vsKDnf?3V zGw*iX`H>HQPkNrsFPAQIh20&Txc;-t^>8#h>__JL$@6*Tm?u=l@%7X3T>;wbq>$KXX@3cu zzn7Nm0^>oR-2PExixB9rVkea!A=5uvljS1RZZOX&sQLPrPX&h0*y%CQH=e(~Pg6;T zk)E`EvV3Z(oQH_;1hGt6TL0Pe4?;`V3LnqT$jPv)h5yY5#xduA_@rF}x8MBr-|zQB z=zN9tr|!)9Up}Y~93Pd6&lX7E&(4qR?4*KkM$r7S{dagRI$2A(`BKs1!+0y(kA(a?KZ^CI%5y!SZ5f~6&^A}`GNzDC!Sej>G!B3< z-8{MVla^vIR2|z%&4;l5)LUtd@N}SgPR2-ie!q%QFg%aXujizbkP#Hc%|AoOX2FMS zKEF3kT?PMkncV#IXkHmSyOAe$-7Wc3md}f&wQ%$cUtc%mD`6w!S~2T~#4pR|4c&J5 zWRWtd*eL-@ZPAZm=H?Uq`TS@sLJ72nD)ojd+=j-e6 z3qm~Eg!lcV$bsHrvdKHLXRJ&ISc>$@K;~kF#5V) zDH8HkLb(3*oK*ri=F|Gh)=&Ma&w_SVf_RuT@I~iO=YHhE>8Ba>37PacTi?5FE&T({>1LpYY6yRDjx47@yF`tR_jJ69;Wq^UH^B_Rl|4nd^Y5xtbXQq?TxLU z^4I@QFZA(#o-Q??&-zpCVHWV}#0+l!w9#Z1u1!Hw;Ue+H_K%i3*h8R>4K;uFgyA#F zc@ugpwI`R4NYAtSi59D%?F!@b&FZ?)*}teM0;dIxa%)%yO?A8G!XUEgo3ZiPo7eEl5yi(rcfDP&%eJfAgTKH%rV zU*Fx{?FONW_NVOn-XdXG~=A4x2d=eNm;ji5EgRqXgq@-J-vv(Qk)VS`hNTaPP$ z`C#j-hdsUFVj#^gtFJ?b20}{lPSN7B{CtR2w7uYUe_Bpg=l6eqKFe>Dg9o9pMu_<9 zU%t-j>zN(SLRHDEoS|WQf1kh2@VhhO7|eJVMa?&{{JslJ1FNt^ZhjST`x1;_mnm+0 zCC~3;pWD#fo90(!>Z?JQp2D0&al^3hIX=HHKTn05Zsy$iW)m$_gq8xan=J9i>hFtSYv}yeMoiC@{(V?}9lEbU zsJ17IeWmAFe-Qo25w`Sl=IXCa{C=Et*^dNx%kw)cem#s1bmh*Mj9zsSlhad4*eQ8_ zd+hXt;aPnDT7Dz|@-zdu`GCzqTfs4GTF!*rcYpco#OSZa*8{L@T?n^7wRiIonDdFR zuQS`HfbRN4Za&~AW<$#|y1o*b`MbV%3Za=-zNofD`uni@Iw++QQjeC2A*vF8tbgq| z{u^}BeJA=pkUnSi)vmZ1n)xad%S4IKXeM8cQPIRS{q|ga^$Qt-J!*7Gc9@i3DKPc_ zo~p?(nV56)tB96U@l_9jbRRD9#qz20Vm7?bq4iZkp!=tLi&x@6O$Tx`OnRQ>)A-^d z(DZhu`crKFKSg^V9;x>STkPcd%rtX>FCSdF`=bx^yMTLLQi)S%c|IRE^?=kf|A&9= zwi86%04o1y^Q(8R^M&&{({gOC%kz12R0#aHFoe55&*yD4G#MOC=_l)7?{7?k`rCK7 z{r%Q<_4`-%Wr~4`5`XRtpLZW!hm^d0s{UvB+~`*U4_}sv>HqE*V)+c3_8Bs3YDMdR z_j9p)hB-FHJE6)%KV0II^{-tv*55xri_d3L^dQtL(IszZ$n)8Fu?fH%KA)9olkmZ4 zfmC#p_+t5-_|^h~B5WxC%JTW{{W9F##i9QGROxw^&$w;&Fwe-DTK`!-ZtE6$P;ENxm4mS>l&n z-=m@*!HR2T;=>r2?1Px8hviIuyg#hoD8p8+4bGz+CFG@kzZfMw00G83!HQOrcD3)JbV9x zU={(pBBHtZs@jNnuz$c`|3?^PKtGKvs=i|R{cf5MD~zsk^Q(f+58#~21JR{Qp5J3n z-h-vjJ8nMEWwa{x%2Os?1LgG)mP8n^I@=uv)KHP zR3EYVK&KA@7;&h6|I;#gejnX-hC7}cx$A#LKA&Cx zFZYcF-Rwkh2(`Y``IY5>bSUbQC3@bIettBw{;&UZ1tt!-O6e=R{wsedfzwkSaQ*3% zUvJ^)taoBxBYAxt{8Skg-qQY*UH_M~Rmayh?MZJ%c|Mb__QlGceW?B_%cs#f0EG@S zx&5hQqJT+T`1%^6Hx2$DU*{c<)&Kv0mC;a=(9qCCDlICm*YjLPAzDUziFVPDc0^Gb z6(xxf(J)KHsB=!KBxx^6no3$|m*4fhy&av`=XRdIzt8QuF0Si-9}u{5721E+wq+G0`tMCZrY!&>d=h&@m868wM<$+Z?xB9zAE@Ud`-Ac=c~`|^kp=b7>MRm zXg-rB$zamdiD;~ooIB`T$NB8LElcry(M)dnU}-+@pI!yaYy!~!>9^&#`V`Kq6srwO9k}@JqBws&!@HL^dqGC9v;z~2_0*|b!#s0 zN%KA7{YVHHJrV719eZuTn9AgwpONr-nr~O9(V!eMQ?&nt_O~(dGnu~!-MGDfh1b*m zz}mc==(ONHam#>++3RP@x%>e1J|PcE%T!p%($;O-wW<8hXalQqW%`` zZ&hdb!k81dKlu33K|X$(18;L)n(xWgJ3yoRKD578aCa{#zZ2JAv_B|X6%U6Nok06r zPN&jf@;0$Qp#AHNH~BDj*HtvX+B^Fu?0@hW?Y|bqy@HufaX$C;Rbs~XP~ny104gc z;p;h^Psgj%82%d0XRl!sfb+un{5ozcGqoa!^XMzhXVc>|;qAvYXn){^N*XicWF}`A zAzgp1iCG32tHt_D_XkwXHiGX}F`smPb$NlEd`0LO{*2Z82L0?#`B%rMK`^V`J~sED zpntS~O}$|!KU6!0XLGwYyuOms-^he;(0LlirW*+BH=Q3eF+T*pn@*tlE6h3pH;;?? zrS*47Y%Xl6yNd1)xb9aBBVIjb{cDB4pY{*84?c&IHlI*`YyR~&43XjdTBNsTO4hgM ztQHG=)Ba&Yv_4bpZNQy-A@E1*YgltrIFg0?+YZcd=GJOCCvSZIE6wl3J97AXbS9b~ z+%TKMXji#$K6TRi+M;MIoVdMMG(Sk|Yv>z)#WcY~_FS`kX+9mfZp_+f1FrO=G@rh1LqPut&gYXZrp&4;Ik$PU zz!$y#7iAL&Q25(_=ljwAcGo~x#=Fvu%NOmR5%*sU&yIngFY)>-yVj4X{2s)0{vy;r?_;`VeN=WjR;TO`6ZWH_YMTh?%UNvXDP@r|K`YwN8xlGdHeTknnoipQ<_7 zLA}iqw14F=(U+;H4dU)JK3|XK^Nz18Y*Af@=C5&AlbJO2EbdRB^!h*0#{(jY14Q$I z^!nd*#Y(7eAB^U&SD!QT@~!s#nWpa~^|RkKe~8+J`_t4p4sy3mu6$ZQVLpJKZy8+| z0=9kQ*+*^v@gd&dKi)D5%ByhyI=&zYENae)`djq+|7OW4C>>Ua=386S3qWgNDeH7z zdj0?6`WTclaeZBQqz1Zd!`J^mp3Rx{`R%zT;|0Fy_5Z=D&dm0m2AuzDX?-my7y!S( z3C$0x0tPWQZ*YE_C5(VRCug#e?gGEGzUowrXXM}9xB^lCLaeXrLPmk%#3ktZ|Eb?b z=FVNk{+5Z-`szQxNpXJ2TGYRG3QJ=4RAq8|`$+TK(cKO1-ow}bsY|?IwRtf6t4vy7 z@AwdT+$MWIniuqyUjM`E{orZvK6Jiiua3RE{Jbk~?JCW0*u-FP_KZj83w>-N!Tl%h zU%j>+hLl(5*h5PM{%C%u^v?p5$zp!#{+Ho`i?DnPuD`2~JOItdIKMlsK0)+66;9Uv zAD`m+tO@s2nN_cG{XMs*BQqui=eMehF(@s-`MvRX0OMXO=j!VP{%Luf6^NpkF(4c~!0*zj#JvgZ|R~ z;J$$`=$*y=!N`F-V2~H?4^l2gfEjm!ov}&akKX^X+#w!1_RV3#_X*eOd|+mVjeLTR z3%@_jt|6bQq@Mqrv@RWvj4xzW7~%DFf1%}e7N&=kqW#;JtM0wu)r_vAI52^FwgY0(fq*HLzmfo)_{YV0)KSgX^D`v7Atp$E){oQMOuF&6~h;s_uBD?>fT85 zYjJ%e)HRPp_ZKX`6a;ps;?en+qf^3RO7B$G^Mk+_&2PbZD|z)a7v6O9NBD35Rvfi| zYtPI>@VRFWs=qIHrGoLsLN>%ncz>GTX)foXE(Z4x(D62S{l@vd#}F?h_1&$XE(0DkB;X;^{G-;enR+u==`hW{1SNV{29#`mQHyC zS%oTGYNNlU^;b2o2{U6b&hNW?EhhW}uD^l%dcpb4PH2An$-sa~?rO=!XAAt({9f}I z2-;g`iJmV+`-i&{nj67BhD)^gSLdnm?rbXZI|I$nSQv<2|oQ^LzTGH*~7Q z{co$30GPnx{(+p6$y;1>7Cm42JN0~J`?^qQXPS!6Cz$^{07cIyX}P(h`Qd z&zVQ-A;(6Wi=QD}r|Y{Rk(!L3iXqpfasGz(7qaLcuvfzw^%rS>dNV09obR+^V|W=n zOO&6{e9zfn#mredmn&}EpHA!Zx#hzl@fhxpFIq2Qww(^*qK8ZKz5ALqbctAp=DSDy z4=|>uGSTy2{J&3xcB65=o3@$_9*JUorumM(Zz6Bn#*QByD9!iyLo48W=SVc)o$+W3 z^ex5t_Wm$fetF>-5#QY{#m^7l{5=@5EmPSm5rTfw{$ps~e&`V(_7^nYExeAv?pi!w ztFu21Uv8DMnyZEPr}Y_BhR9d?kKsQSrZw>2mU_Ny;FvAdj`%or|8cmb};0AHO@!UdxmDca= zkw);S*=)3bVSj>Q{yNU(qHYPVr}<_Fnu3yiDVks8>n~*but8jbzBJ!yMRM@ig8PqS zx%-)4t+KdDHq!oCIcprGnQRsL586LBRhj`Nh2s2z_8&Pz2FS1F+Vb*8uNwS^3FSXB zCVN7dWhB}kUg>TsFV&vNud3_a@OpawVdo$}aMw>j{dMZM;qq`*7ZLxozMuZJ1AdH6 zMe9e+xBFmnHSS*qt0uzk*M+Q~vA`#-?};x?!tZ8JSp6X3I?cZke;Gou-= z`Lf1?GBB;f`8NCW9rV0$zWed5nPvS9xkn@Z@g+W=cza0~i1u_w_eUIX(r4P*SaR~k z!s}^&;&!AjXx+p0yZuvr#`~2ew|7=}!|$i0B+fUyw1>bXt)(J=P3Ic}h5=Z0U60N` z8sFZ>4D`rC&+k~_>Hs;0TSfC_G{2W0Pl2pI;{F@0&r1UP$!oXS^1oc9`LzgL48LWO zX#V!R{SdkPs0qC5)?SkQ-uK)DO#cK?{zmub-qsJ3A5Iqg6D3N&e`+b7Ke;~@?cc5O zjDYE^Sij?_`N`io@vy1SHMBkqnUe{6qo1JuI`O{Z`OnFp*;!iB{LYAe48hG*Mfn`9 z&$797@NKI$nlC3EZ^c|3Xvi(s7Wkv}+1s!)tdlvT^OM~yx-q-gS#tV2h1b*khJ5V> zTQ1BJ0({TOu8Se`GLp;A&Hp)<*8E?y1jFaZqR&hR$TBk_1X1t(J^!&r{m~~)fkRa;M z(epX4?E+!@GrazLesYlf(YA^Fgfs8qzx*PD$}jAv?14W|#C+2JqJGC9`2*L9{Jtln zB=b3b%^_HCgY!#nrGb_`uD^?Wa?rFG=QsP{1L)8J=l8~o&oEoTuYO;_f6)GU@r@Qt z_yj{PTwmai=67CV2iP?W=Xb+xJ*KaM-}uJ!muY_AM)ZIQX0y@yaMXfM%&sWlZj1|) z(Tn}?x;P?hK^Yr_duH8)9Xip%I2-2{xYq8W2<52 zkOWcxj^=yV*8%dsGbf7tLvu=h`*hz5&QDX(=W~^g+y%2c=A!xYiMa#h^D`#!pR5GF zKT-Kdy{6*)T@Re^D}7Etipldf!56-Q|y3 zkLI%{J#YB@;gr7Xo|plCg^}p_Bs1H1g1tBHUw;1eg|F??Q2kDi+zBqaxhUU1t0KXE z-4N%Fb5j|_qyi}_@! z{>gBQGt9FEmE7|A(tJ88+d)%Ctj~15QR&x3UNmVG-?4o~!{=L2d~VX53MJ2QKHm*q z3>KkcKI!_e;!7WSp`KWu)hYiGcX1;`bx%X)E}h%^`MfyFeUpM+TUK@ z&Pcwsi7QVWLmKoqj?&*+NQ86QPuTjog1*xFdwX6s%+&qD&S^X!jpn=Co@)>&!}(qu z_X0vnaevX{U=t=Y*pMq|Jl}-o8$PswroZs~&M97tDM_~Enu+%BiJyNLyHgihJ)On= zI4tys>Hgsev$l-UB*Ga?mF9avuO8rJxs)B^@lPMb&u`wI*dM-K!|TJ{j_sLsepcMn zml~3Mr^rXb^Rlhz{*502*^Il_TQ1T|I3JDH-{Ll-;ORu1@3elMD>wj>7eK(}>=3jXM+hWj@mNqu#J!}-nK@C?E};{1L)Ru3+R zaenBqLrtWlQS&4;Ze`5pJi6vn*}`(s+47eW?O@S&13%$C;YkP1t1 z-Wnq6AJY1)@1iS@aI)sr(#je>-LJh8bK+-5O7okm*ne%lCYL=tN#Kv>ca-^V7+-!3&6m|?9D=>g%Fz1nP>T$hwfGDB zqw#zRT7M60y#y)KRJpas1ph$$isQSd%`emW+^P>Pnb2J_&fYY*kuPz+{Pm$8nEhOe?jKFK&=)KR zZ$R^n-(y=d4#ya-k9n)c_ZR!$!dF9Ji^?{U{?h)pXc@r#op^pR>|1;JWOr*mJ6f90 zl6m7Guny0c-CxWCz0(P7lOO;15zikV+r1pxkTkTv@uP`9u;Dm=)t5sdxB43UtAp_V zbbsST$U!i8jr-g8da2;C8Q0J1*&LYq;QBey<`E24*FpVlng2J)FEHf%SZV%dtEquy zPZxB5XZ!(mri+FZC)bhIPp3Z`psO|q%@-zFH)ozX%D9JDcQ*1N=FhWpCwR4TnJ8bQ z{cXmAUSQd616qIS%xuXl)MYsPfh`-~U(DZ>X(sUUw>TfB^^;FK!CajEmRtTtT0b3Q z%%N&kh-iM3*3S`dHRZ0kR{YwfPZ~a-UjK_D#sIIrAMJn42$}|e;uF}7nF2qwza=J1 zA!{FpkI9|M|5$VSC0kw)C*zzi56{-$lU;(=yb* z7WUPWw{)}N*Xtb>{4XQkzwD@Y3|gMT^>u8k^AHuT%B5eG*4GU??}17`9W-C?)2IP; z){y%aCe8Qw9A)sC=7RP=Zp~}S5Pd7|a4TuPGuO6;{=LO~)AOAcuBy!6BQmZ;Q(9l! z4c3KaWErZjVUhaqmBIP$)T}x4t`fM@TnkCQtw#3;qO^?-kqP|xQuSM0_Hg)lQmn5u zzd5Zn9#(ay;*IwV=4h281v5TKd z^F4NXBz$zj`Tjkxy?k0vd)`0sL<8SSR6ZO$H5n=|;rjjIaSq6~sd5l3&G$-^+t2}U zzH5y?Lgi&c?xc@2-ys8=LI=hLou7L-xH3KKV`~J@HN||>{vm(D5$1w= zC1=-F*k4W8Z-H^cVCp^G|K6CXF2CSv$>%qD+`uoLpRIpt4Zp4Sqw__oCGF&2`i$Wj zxitS;p3X3!N?hO3`o1{X1LmK?`F~*DK|U)^(H|_Yg8%x1w7y@fTm!P_Vt+#OuaOZ5 ziIzpEKZ&h~0PTroY&i(`C!J3iCniGKOPp`_M`z$mB+mET=o{dz(C-UZ1pev#t>vyN z`1l+5$3B(#!vV{iL(2nmM9=r5{qgew%FOmp40n0I zbpMY#qzPTzma%@^Km8Er6IDT-VcCEU?1O#6b$b7ZO1oyv=efY0INH2{FC`_hKZ%{( z7c|D>{Se-W=V++P@D<@ZcoQ-;pg|5Zo>g%@4*a`@<>QBGezar-s4j{$=dOJHq`< z>m$?s5Oh+mVFw)&_@?uNPWLh)GzaHz%Ec=%ZzRs2$H^C<{lk#+Y}`Lh^B4BMjyPB1 z`nYyv6Xu((!rz{j=5G{f2Dk3w`l#LEC!Dg9afSV*`KyRj2l*IJ(flQye-#e=3*Uz^ z+}FiUjr!M4#LuN&+KT*c1KVu6@ck;un~APpG}nj2e%nOz@$~v%qZ-Sc>s85x-xT)u z(d&O&Xg`?zNu1yMQqP}KzM(9y-YVxujDOhh_tAV#=ra;>mgD;PS>Fyinjc20E_<>uU!e0ZZniJ%7*)j1IwO34bp1B;S1=eX zDPv>43D;?UJ=6}ud7Tr1{+*(*h2E z#r^ANgWquOtDL*P$5oQwv|(CsqUlC-er;Z#u5iF#yuQ=*+1{}Rpjm_KXU@K+^1a*T zeC8l&K27~hp=i>6cGx08f9UzNp5vR#b*k+6MFlzyfBz@ye4Zg2Y+&#>oZnHcUBE}- zPrI1^dw=oylLzwW!(F#L(fMdJpZu5&@MoELeW&@f_t^n2eahI7SJHfXdqlx|ry8~} zUHE)jUo#Zv4~Jh?<*H^1>o?7(gD(s2_Bvd>w{V^IpV#)5f_hgY&e2KGN1D%9PF2L? zI$mGhO8o{A(=EB)!~ea%xIbo|^qVX?>xMqxXT#%9P+%?N+J4*7@cS^-`W}5y75eIW zqV-jv(RWBVXUXljJxP+!UO5^No{9U@CObNT&LX_NYMb8+=BS3E^9Ref)H8cq%K22g z2MwQ3&#zyo91Kj9SU=;a^ZV{TSCM}=vFFFC=t}Z=vX>kzhaVQ@V|0EnHh(-UDNSRy zPZ0Q^_h;n1cLRf^d1!yvRK*8wEiOXyuavYvP}_&|+16|y^c+>g)^8L(pXT#yQ8GAj zs@&c|0v|M=9na;#gPAy=Q>`C>yuT6GZ?rU@`Muwegy%S)b9Gp<_d10z>oz~B;d3OMGjkwJ% zrTMfgs2~^q;(Xp=D&ee)jJstg&F6&?U&w-NoKKZ^>WstTx!fV2e}A92K8mz%0zTt# z{XFGa37^)=xXVF~4Sdl1ljl3Mgc7TbX#e3vYJ2!~WSeMymtNoBFWbYM8UBWQWO+{D zpApwjMloH%z&RA{&pKYOV}8tGcuiG-UwVJCQ8Qz(PQ&Y`ka11q)9mf}hc9#*KA&Fy zU)GO+dm9d;^9LK1l;j7jZAJ6FL#g?iqgsmdk9wq|{j=Lgl;m+XcKn#pFX6xZ>KWCa z=rL$2km-4-zirj8iTtysJwLt&G~}=J{^#k{OCcv3*YDCxTj1g&-2a;2+6C>yaQ~ZB z5D#rDaQ&Y3AR7+4>2Mq2AAjQWD}B97;DAEEvHPQL&l7U>q6_O&E#$BC^DWcQzkuK& zGH!W&S|dMVfAL4TnhZKA_P?}#&klJ7YY!1||CjO?rEC6>)`^~I|84Qb7hq#1KwfGG;dZzUK5oy{P^oNV} zo$g;`aG#iM&w)4Wb+6&?qt8!aqYU8k1^oU_SYcpv_*B%cYEz2R*+ z?mu|lZ%pVqTYkVRt%ldr`fV0F7^?OhM*C}l9p&I|oR0eAnyLwqmy{=(-=+OW+G}_4 zd4%T+yLPUJgx|P7UcPWAbiR-0V`*{G&`H6sT=aZy@%dC!4AS9junyP7QQ({QABH!t zfQy3>H=}XBm#*Jh-M&ql*t??rvHKezgQtOvYnLs}Z<9wAWPpO-SC<4n=>EaLTc1hX zVX?oU`RuypF>pO)T)=#3K4VulfoBJCK1=_!gsaipSRa*t`XJ_W+WH;Lj`Irr6rGPH z_7^F~+k@#gvA>}COsjm&*sTV>r-d}1--qaf)@3|j@b?=4BpK)Lp1us$#H6G1Ye6{cm~E2*^Wm{zc~tcV1U8>4qTkzx4SK8&Zb@w+i>a zdI`T6{RC$|eY9`dx+^S)Vrwe@3 z`EJJF2-u|HyLX*%o#tEhNHVnAjq|hvYZ{+lN#|!xjGrtJJbk$svJ9TGiyQmzv_J02 zZh@xn#C+5Gy=T-Oi0rL~`s4S3iBOxY!^wIH{L=nn@r_*Qv&@LAdn8<^^_zWkk?8Ek z`QD^j4E+Ww^mmc8ewSRlMXnxkL+2-7#1unHmW=C=Ch%=S@g1mDLAun4{RhqWCcR=9 zZHe=pKJYV9`i%Pz$Foh~!Ygq;O!Ix9+ZLwVzBk;-AHw_`-G4g~(Gp4{L(%=4vThHV zPwNT)(d~AFe$&q%P>a%mGip&N-&fl8gupVf|DgE}N-=>Z$I{XBdoG>NJpDFDwEu^m9~&B12xfor`mXwPDcRl13+->5D7gwNZDgFWy0rh;e5s0* zTW><=)BD^0A$MQm`W$4X1{Z=tMf1J1KVG1Ghk0{D##b@78u+B2?^g4(9eBLkkM1v? zGPxUcDHr!IXg=q8-DQ?&;{M`Tt}#^R;{0|!We&&d@%;GWD+jn_ejV*^d|EdLcCLAf z_TSz=TnqUcwd@cFfiGHLAEfPsbDeQM9c*Htccuo9KK?n$MVN1rTFTMDqU&(3(pICjjr+f`FyO+X0SW4?__aVygry>-6K1SKv z8_fI1GCq5#G{5=L8sKjlh0fntrk66uZ`$!Yx@tG@Pv;K<&UA*a#)+c&Fq-c}CrcQW zZv^$v)k_Vac?Rx3eEOJyvvNL~54-;w4b}4NtjjJzzga3@o7HwYRD0q6VSnpY5Nn9@ zeR6FOs2kyY$83!PFNOZf&PemUX=6I1Z#3fUVx;wV)5>gec-ACz|IfKS7eH&UjC1NP z&9~($jtt%4hVK74cASO2ri2@yB=ql|QG9!b-Xu0YUTFRspuxg{Br0E{`gc7u%Zb@K zTz`Lj{Y37Y2a5Lp(E0CyWlC^M;SZ**{Fi^Lh}PFL>4nVc<1)UkMn?`54V-OrIj=k}9shgY*^WlO9e-=O3mXE@p;1%lUx3GWgFQKcxJzW6ofh z&^I6L?;Rg@kJ;yH%fGgeN&1Ul`c}|ol9+G0{>wY!3fC4qWyiz_{L}t;|J-FT%?H6>0&%IEep~ID460Xzwy<^L9a5`kfg=9J)E}ewe z)BTN?%X4ASbQw38k>-2n`8-nc8qYWS6y`xu9O3-k1-^YjoNw%2Ttp6D!RtTYTE+R! zsSJ0c^~46gX#M7%KO(-~o6z~5qoMCewqBrU{{`)jGlG{gi!)wxKX(4h*TwnV++ROQ z(X&v|`8{;~cP8@^~QRsYn)%ikZ=nXml`y{35~b3$LvUk{SLKkR%5fcpsi{@5M$ zkm>Vy9B*-7IRBVF|EI%l0*4pj_eY54L^xZD_gCyrmoOnKM)MU@h5bu(KDepdLU@=` zi_Uj88L$Ng3{&H>&;H|EoL_H_*aNH1;OoPY_+&VyxPP$q!NTD%nuQ+ObD7sZZhW_?KpKlYrCm&uv zu;MONOlo+&5+m*p_B(iooN(TR_6J84z94P?iu*70{R4G1#7>cq{5yZ1zCYZwStkCM z1wTJb`u=d$Q33hxDAD5 zaQG=ZEnRwjXks!Kvf^ve`K4aZHp0n~YFyM&X}+27q2O~~kq?80^uMZt>7LzAqH=*-ON1v7v?T&#We^2`# z|B`Cb{5P)u&%JY*g~=BD#jiIc_1}1U6R>lRLgzm%9rBpK^)h~dNz;bcv()_O{!!}S zpr6PlM+v_#&G$}?JZ2S$`EF0~-F9RL#rej#{wwKm%s67n&$fIDQvT@8ncmQLEbi|! zhYo{o@p%2389W+JUcvpn&h{Bl7KHnI<9j~PdNj`WpWQpb_L2_wD_Zz|Xug{#9s*GC zePM~fC!G)0%i_t|=9AF#tv>xa1;2Y+b9285uc!GQ!>5wYr{;?GhtPaae2@wnRTf;Y z;nIAYx#bY=^i@6x}d%{%L&LX-2D$1z*!i;J-cPe-^L!O_Wl_`cBX9>EAfR%(s*A zSBsiR^1tsvbJ)2g5uM*Jj6K7w?}+oCJheUS(#k;RpKP>qnX3mF-sP8cem-ZMKJX^_ z?8QfdKGXT*&x)(ezCB}k(^K+>`hcE)GDNl>9sRqLpm0_#d#iE& zgzgUo6)uM!PWb(?XGoBuzl7f(BQHgRzrx?FcNX}j?+=sv(WJNwet%s2kPdnst+^N1 zh1b*fhsK#?GQ}JBHxHH^1!GsSzoF{`yA`L%rF1;sNj;YWDhDmNXAkWp?+ ze;)+?&r}rSPBr zU#05fiV!^*YlZXwctbx}dj;pa|91;m`5D*$Bj+c;`oLOtVPpMC=a;vCErR*8alR+d z34n-)I^49z{V}xuM{SRU5iG9%EqX+f_70QK`4jKe$01A8no~)Y=39AU0@*cWE_(iQ zbgN?!6=uoVtqN=4gXTM8bUMlUgXcTRD-+>Wv<0^;N1E@~YxBsu=9|%c-O03wjGHE| ze`&sJVjdAol`z!5JNHOs-o=~qG2I2e+fw?z-lUqSdq$z>FL!&d1TG5w{&&6rUB6a8 zO=Y4MiTQ0y`IlyYTS4&|mge`;rVfzkhx?b@{5~-H*mZRN&wJEx zh?!W9_J>?oIl!hO+`r7c4H~vliVE!wd-{KA7a3$1;OKm0aN9(ii z#69H844hvZy=162wC0k|2(PF0d0lV}*&Qv`XWGAHUpq=_YQ_GW?q3G=iGwlW791Na z&8M=@X)@z7uD=Dd3dlGAK+$|Q?N8Qry+f>;hN1nRuIEyifK}$aTEX>(`-|oif?t!{ zQMmrv*QPVou2%e)kd_Uvr=QPo==M+IlPu29Y5#p{;Zdf|Fr42%_tb!>WU$%2{{8;q z{aIU2A7|R0A-v6EX?}Uj_AqNV&hMz|GmJxX2RX%5>ld zd2eg*FVCp{{@X8u!CI{xtxxlBj)L78xPF&b%!EEZxPG4o0x5J06wP1L{A=I4PEPBI^_lK}wl+&-h8URh$>sw8>Xbg$ z6_%6H+2Z`2&R5)49cQ!{E54VrH2)Wv8nSwyIA5Xl+xcN4v+0Ss$bZo1dz!aZ1`j#z zKjxdJFeBoCZ{9}m-?aZ=+P8(?8F>C!7k!3_xIdo1J;_6I zKfD~BPh99PhlCnj-|a&tgWps&uGLI|Pg>uz)~oni1(t^mQdw9Nh^g|5v>S4`o-6G9*%B4M|d@=4%mb%B1nU}pp=V#D-Z>l;*_84tO z^Y!pfQDCr-a1ncy8}yStKV!uDvt;2cvA?GIK6S5vd}$em_LnU79Ae)59?5rkQPlAM zG~baM9}+`e%r{+MR&=i-`K!hG3C*vOYaH{t4Ci-Fay@y%WT5lelP(=*N^SuEsFyUq zx{F)E1%-ZN^D9&DcYuz+aX#&j8-R*2uD@Rs&0)d!S~j|I|1a&I51CJdEN?Z=W`n>N z&8P3LCD8JY4)f!<%*r|2$cm&%SlRL~HI` zQU9NwAGA8VpNt&49PNJ|T)PKuueIRvnn~-g#rQ4Wp6 z^)Ot2eM=88Uz?lr&B~>hm|qL6`NZ;84Sdt*b1k3#f|T6E{l`_4 zXy(~coZrm9UrE|B+&`Oqi)B{70)C;PG{5sJRbli;Jl`hiT5zRxv8caK_dk1S^aN|b z`TaOz7@Rp@%O0xym#>JQ9~Eml29D2BGJ;ikI#Oy>P{?~@$r*R_m*jWwolLTQK^WS9KWMX?dG>Jx|4sc`gMK!r z{IB{(o}@j%>%X4;?vg8SaeWOl*~94R;QS7H|C+Q;$w2oX9$dMPS+|7Y{ntqI%jNtc zbJFpAt+r!4bCq}GPiHWa`Lf)$B`mNgM&}3T|4d+f^v3g5gQcI(+P0tr=+43Q`B8m1 zGj^(scN-bs@cH!liU(gAg4$g%|Fr+u^MSzIy}17vnm7sWw9!TNd%^3~5E^g9MIDpo zKX1SS^5!?L-}e1?!f-R3f2Gaq$lQ{-=>D9nvOsbxKAL;BCa`B(lFONJ)n z{J)I|f|X?qx9iddN&bJlKSrjwhl%F1>HfMRcwzdKj^H&P6-x5o#5A5k8qvV=fU4+lH(sHq5H?KzuyKMwG{bWYiWOcyX$hY@aJ4~|G{Mqf0FrbIXeGw z#3_WN?ZE4|HvOVVuXx;FT)CS_;%4IhcjcNOCfRKSAKy;kPnpu+!n{*NMd5$3{Vz5< zgPEdhiuuz%%^LWn``T;sv46pR0{(dY7L*#oXgDzZ zJO^n$2dP()HsA65&An|C7;A_7haLHCz{9H?o&W3Cp&K~&t`qh5Xg&v@7z~xW6!WcP z1-@wid&=A%@`mVgomUFiX+Ha$pAVLWMqD{BT&MZ`zRrbcbexRVZ_1HdV84kq_o{LK zI-MUYt(Zp!D*E4ZdI|oA_7BcZ>&O#F+&?(23?zV7|y5J{#f#5EA9_^ zs01)SnvUS_cwKGai{`UDJ(YBOg!eDrGzns2eFz^LDLtQ|nVnB=+`#!f>br+IeaAt> zr!mE++4CEuHWcSmb?P4GVXOnce$^}Z&)?JMbIe%toD8nZ7oFcp>*u-~fsA|*;Xk|{ z+OU3KrJm0hQudup8C}elY!H4wx_b{9FyfvI3*iPVIiPGnXHA%$cCC>j2*KFcfB+k$1 z`tA=~K(dx*uw&W?-ygj{u}_FUll_PA1|Z$vFg*5<1l`SN3mfb3`__r_2b#~^?A~xQ zT#Y+t^6&o>&yObUGKZUOby0t?%XAW4OEKa;Htt`i^;fkokhxbB`wQ9#e;+-6oib=S zbk?)xdcP1ppXPJLs`12bv%9E&LF;da$~k0|lbFvqrm1Lte`>lnXLXyCIu#peU1U1Y-sv45cb>(KY!Ox>Ch{IH(_pR_((&WE~1Lo0U)0?&JBy zq^uI6JoY>~|5-EqC0XY#)>oF=|1w485BU&_`vXtI*3i_jPLwaue71Sq6~-&-tC+@o zi1r7|zbl?k-Wlg}dhl3CNHpS(x(IyHe74CnC8bulKj1YM!ifK?uMquAh#5_MI(eYy zE2@8)M2>6}`vaO!w{MGxXBEz82D6!LRMc14`7oz7caT-#Vtu6f>(zG|Gs7R}Z~3K2 z68R0+M<_I4&>lnbwNt*T-Dr_YzK zn16-b>U17m|FgH3l7+L2Me_}`KJL6(L!MqMNB3_(RBa9yO~w2@qt2i89MciFQ@B5M z4d@T0t#r9Z?*x6L{prT_qrvh#u8&=N8HiWf$m*& zxwYS=`5HMJfW3Cm%Ts?s6 zTRXRjt&u~a3A>{G0t*!dNw9{Mm%KaJy~^4>J) z8=dd>9Gy)@_c)LCPlM{Nko^mB|M%ANDQT08=l2U^zLUJ6b?lwf!uK0T>6@)w9bA*t zIKOtn?@zCp!Ladw+3$-#oW3NiA_l=g$W$F(cDEtq?u`kk+@1W1~so6ET1E`R;>{P9^-0K+*FD z=>C&x))Ga&FZOqI{qfDliOHQkoPVS%@b_J=E#d<*w~#8$1L*vq>_Zp{vQ0wwFTd*J z#4H+x^Y`;$4B1$Y^Y>KKlNs=S9AA?u&0pv7spL^VF@OJ4UvIuZ^uxvej$U6~F5D%r z_ms1(8tW6f{wV79fgIJWV_R&M=5NS$RWMCd-Wy+Em6S|i#ziA8 z&`#io=5PPaHsstY+}};vW)0Pf{(aw2;q|osjsL4hE_`w zb7B_0S#*96&7XU$Bk}%%=jRy{XOX+SIRByflQpqtc6>GC?=8ICu)fm#ZFsR-@%VFm zeT}f1$h>8M*Bc|9PsUXQl21Lw>o4v9l>6B;i#y|d9=6>}!oK7E`EQ@ynMLQv@zVpP z`OLRXBx6i*K6gfCli{0jeVje%8X0#3U!O1Be@={-iTxj4e?+J%0Uxc#^=mvIp5}An zeobi7RhNq@5%{L{acOB^IC}}#N8=P_B0GrZH*dfkCMfpjT-h(pXUh%k$hfI^{W11> zchYp{3ifd0`2e&&CXj)oW2rcwr1|u6VTgUPxc;E^ao5fXWOc5%{-F6BmCZ1r>&U4oGs9$LnThI;Pt^MC@FkeYG&9lu`>Zz6 zPb%U5}Bd)%Kzz3~=sT#GiD--eh;%~tqC{wlOl10x47q7pSuT{yd9Cy+A zlPuFjw7%`gYEQ~lSBUm6(tPzY>q(-U`l9{wq1T5HAEh94|9V8S6}g{?&v$&-XvU0c zZpQb2dr6Y74>?nar!AhZ{I>BTIlYt6{>#l)!x^>RIA3iK1dwfpnP`99f3jjeaRFXm zL}(`vj|iNvix&be4dH8FYc9}V;FDfoIn|%CTt$8|thaET zUSEHl>;ammWL)dlK@GpJl9Kp*1=oTW`Ac?(w(fuR0WAx#XV*km8^-7KJ zFMd8+jzeEE<}t2+Up|-;yBx7Ur1O{dv5NB@Q*F4}HaQmm^*5B1#Qv~Pe+P1KDXxF2 zhI7c)`b75ELgD+N>)&JR1~Sg(Vm>P={rmfJ4e3~m=P$M?+eve)^P>HK|KtDm?&}HjD85 zFXmDhfzx>YcmF{gnUYh^{;>SVmsmf$Pt7J@XNdWv>*HCiZjgd(e0}aYvWooeq^OTY z{EGE6#;`eBjcYd=6jC)yT3&8uH<=F2f~#U^~nfnKJN^=DdXmQ zu=72H>$HA4OxFaxY8jWJwY^c_#QN!<_gZFBjpsMP#!4hY3tztC#3ar z^7J;Ox>lSY(tO5t(<6VP!q}6O|NZ~s^OvfYwTF6FImcYrlu7BQy8A$K-4U;EW)}2f zY7GeQHec9(O3z8AY%w)8`w`oml*!SIvd(%_klh)U$2j^sGJA0t{&ck9gP;!!SvKi9)+NG{U z)~EdnbpAL-wNm!B1J3W{sZGfBDtvwap5BH$$;bU?y-OkUoc}d*{aZ2jL+XT zGl}|QyuLo&cMbWuznDEYK;Vz&^T^Jf_?cgcp>;(Q)Hs0_Qxt+@F=gxAx2cFswX+0O6~ z%@5Q1YIw7rSg8~4Rc~p1o#B@wQyGcZNA;g?%35mpqWd>GM!l28*W>zWdZ7s+r|^8d z&Et0Dp*_BSo1W@L$|vD`-MpgC*qh;ety*bDvcKT_KetVFBnSO){rhmmgB(!kAI4W~ zk{|JVh3AWU1H(yXv^d|U{bgi}6tdy88dq~!_SXhQAZ|ywBpp1rS&iASg365Je;r0!gu6gi3Qj8T%hFoUD_u>7Gj0-RX6C2 zOsl<^FFN0etWoGE6NK(hZWi@g_UfFNFWNu;QS5J++=k(lhV_utzZKEVh}otC==q+u zC0ZoWB#FJ{CwxD&zV%zwjCu2Yn8-iU`Zka4P1IXtqWX64mL}8duPtvr<~jW5A3jm% zKjd{DNe-;V^{=R0l^L^RB>ygdP{Vvq1~s3fGh_l8e->ZAjlM4-ms>wW^P!0!wh`3= zTp!t>1LX7_HEwjRG{1drXA&R9d?d#2o%JQ8RM8*A{O5`v<7Boc{y+Sxz9grraeZ8o zwNl0p#nHM;Kdl@O74IFd8NZ^|h*Y7W?-^reh zI)L^U51OfvFlRhp(rEJ)N)m9shbrq3=$eV{&s0}3BvZWb`hDIULTbE<*~8EN`RkUV z0>i0^Ix}vyBY%jI-XGsJeKPr=&|j>6N}1_HbQJmd@>Rn3OY84w{ZQhbBChXg{k>zH zNEUY2<;=W<*VFlVp*~C86!Q~Y0f_4kXJgKXzD4>l%A z&>wnz|9$l;X>#0xbKN4XzdP!e%3gS`K=*I%T(Dhct|!)CdcI;|i{$OERC3svn z-X$+XUPY}`J9-3Ti%h&dUwb5ds)7_%u&-NKeife zlU-^WB${ud^*PWyN;djv7~6{c(=Ty85W(boUz{K>!kmG&o=<#%ChC!Ft+viGvV!!yzOkSVP{0;gxs`?h=0 z;7=+kf6~%KjleOye=ze!N7CU$F*~HQz!zPgz20I%Zrv$oA9WS3)BSlWc2@(6i2PR1n+l=dI<+G@${Z!TxQ`3vt)`;W`_ zhRDXL`l9{&pLtVc_vAt7{K$ap4Knf=&ks^Z9wn+NhL6Tpe>U5d@T(SS4^Q~7KFT&QZLq-0Y*5?OB*JRonxIS;*a1~}aj^KZW z-f!SHj^fvF&0CqC8{S{tH>wn-#M$u?pDY^mRf&4O$MhWBqv>Gx!-p(HF^JfA}IAD}srjLXCI+bhF46vH+JEmlv6q~d z0oQ$0f64n}#~e@Dx7B#Qwk_r)bTu*K-)|7~ozB-rJA}%o8?vkXg$E?=YT!#W6!{3o zx9`lyBip6n`d;uSh)j5B#U-En_x@si|Fq?|`R))rA9=cb3z0XMaZB$?`}4NiZWbT6 zKPNpY2&z3dT zcl3Nsw5 z{{Fk22Z;*A?~i~fKP+732iX3N&!?sDk9qDrWlcSC{}b9T3`TXw`9ILYL1xkq&lhus ztdluz#`QZVc_qwU*O`x9*-79N#LsWj7#As95s%MT=thOZ4A}^Nc#e0&>ochO)xZ52 zS<|05-$UG=$hK^)V;{^Fem`3OZ|_#DA8BH~8Aj~ytxda;9g6*b7~jkK$jL&*`B`%V zh4-iVZf~ZUyc;_?H`&*|z9wckxkMrMBXO3*jUEIH`tO}OJe8B5dGqo+CI(h_ewk<}|zrS!x zmA$sFW4#;oiRQaH`kt&v;cx!cue5$Y-_w+AQ0yPX{LSE`?j-)85!c02_BUY)&(~iQ(1$$Dvf|!0@IPupC@&XS%h(EZut)8^+* zsou;so8I{MQ~K@esz*HSaew30RwHkMDz4wNf6vW5pr~)L=VzVO*C+m0fXfJ$&L5RF zFE)SYj^{H<{f1arxZ?h$r{N6f9FFsy*FM@Jm%;P%ultulsN(#Vv=h>N2dliac)Jzn zd(r34vL{z?f6_JU|MB(Z@lbwW{G@2HWsMZcTH3W4%b>JT(Y{d8zDSEwDpJ`ZDkT&W zEo7^-G56d%X{WSPM5Vn{qP_g)_xpNy?(g;7&)@TUW`;TM^M0TAIrm&QyD`tJ@l|E+ z|4-}lX=AqAWsGOX?@E>9b}uuP$hhU)^K|^iOucJYEYlzUJb#DpzZjUdwV#s9&d;Yb z^dt*q=W`~t%$L&Vvp0^Cw?CQTOis+_KA(=?e=!{-yDqZp&(n{-+BNyw5i*RSKfW~< z9q+grOVYUar}Ojujt`1#zp&$X!m&?w12RSAgGEbzmgDP>*dDn>`()>PSo-`$TBF_b z{`REp+vS{ok>l?lFj9^zx?9Tj*FSaoX}A5b1L^PI;@?pIdY)mwqPepA^y@@n{eIrx z$idgJn>4&Eh5LN54o_dD9*HX45z6-0z24Y3boOV*e`-ii(Q;>Y{6|k4>wq?krTBqx z{P$mDYI|u3!uJxn--q_!KkP}e{d0pI|I0gkvHkp@8lU^c@gE)kX{UPIsjp`Hk2)$# z>>5t8<3IcR0Xub>K4HcGp>=Kc&%@p(Jz8H?SygqE zNX^4}_y5rTi(2DJJJVlwMDFb}F8-+ammB@PC`UFw%IYtjE6B4OQRP4;UN__X87ltQ z8kH6~F5&0*RO;#Vx3|JMZ!mW;c@j(?4}E_Q0S+4|(fJKMfPKBb)*}`(arc1 zQ~AH#M^m!VjUE5{zsX6ayl49}rl0@XM|z5-UKfSqf34c1B2Qm_{L}u-j}FI*7Va*^ zhNWD5(eXdpaYj+Oto~&6m;4gb3QZQX{S~>iR8fGR5?S(@Vw%DBAB$G+vW=GAUo~ul zaD1os4U)Xy!Jf~`oU~42Ig~vg&`=U#`?E$w+7}Azn}X%bC3j@=|E>Cl&hJrmdu(g7 z?8xZArGoigalE(0_A}d`^qY0aw&I)vDa*GI%94V(0G_&X?_tx;aY?i-qqeRBdZ687lK%TF>v%`edL)Q?enA@1N80Ybv{6MA@LL z)ZnYIe>id9k0MLu8s_<{gALN6gZhoQb2S&AbpDpR6I?VoLWxL>TH}lFulRMjUU;EF zhkSp{Jx}|GM&8Au@^!t4yBYU9oxk^Z9F*w(WBV%s>3&5Aw>y)Fe%$kP{tj4{Aer=s ztzYKb#unAw`;YmT^!<{krELFjm;YYL$SG|7QucLkQNeY}Kcw{g=if1s2?p%>fTGPi zi}K9vNll7y{x;bZC9(X%k8gT@@yx^>MgN}thkkh+Cb>7B?JrIYw6J%G)s+Shj}gq@ z-cLd#ft%U!FE=VsGFIjKD;_l;(MB{Pd4rAYd_(azEoTy9N&KP z+$9OJ`9#+FLf7j<><8{PlsdUaHtUyIO22dqv6pnPYQ$NexcH^x|GK@oq-UZMX|(6! zkJc|Gl1`E{f7$w_IPFeR$M9ZcU(54!{9pQzCy{Gn$N#5G6D3wFWcpo=`+Pe7%_inb z+U{igFTHn8lVsj!$N#tVY{}+uc7CsXl_g0~4#q25{2zM$#o2wjml2^`Bx7Ickb;ud&*$qGhb2oT#{$^-ebJO+N#-v0d_b&Cj-+6- z%wIHV{d|6Z$nEYWNt@$r{gOK>S8}7+mgxBj>z4?ROA>|U{QOSq^CQ=#l865h-}4ve zN>aayNYQ&?{j#%{RI*KWzM)mW(DB`6ZI0xgiW51nvZXn`=>7kuu|#5dmhG?4e3&B% zNuc^iRDF8=B9_$rM|@Xpo-IKZy3&CPy9DFA%X5%e4P?i+<#!~xQpeWks7@kTXM*s@ z0o?CL$M?{4MUw0@?ELAst-zYX7%Oa5MA_x~rX`5{@lKsMjfj{E!R{9JLkLK0rg_7`uw{U)j0W=o9C zh2yt)>SM{bW&HT1{gui3Pb6hj{L=Mhm*Q^{!zUt=mnIy)L)unK&fA1D@2@Z${6o@f zf)jBa7$g|K!Bv$K_51Ala@K+GlCirT`19vf{O(bDDmf@l#P8p8|3A9E^lIM=HOCMk4u-_`O_Wi~7uSWbXgB(Rwb~B|HDa(&rUdUdXIpc6PgFjJ(}|~-QRzBIgp*dw*=Nng0AS0!TW{d zAHArT{0Z(w*0jvm(E7yebe&}Bf5iW(9X-*n({RnI3bwGD=t8rK{_d2aVo-T+$H%dB4 z4x^tt>&$M5}*|5){GxNs($?b!4MUS8nLq+7k_m9IQFM0 z>KUR$4tM5Wr|ZWJ1Nxv?+5NICeeFDZ2)eqG9p6VXI->EDWcxu{^f}%CT)Wk=A3wfLE0xiRaCUqbr_Dzfr`wXSpP|6*FW~QANNZ9>=g0B=Z(5(|Ozw;d^w{&a zBRb7Tx$8tEV9TH8_@U3gb$zFatncviGwlzeLpn%9HlN7q-!ELh5Y=hQ>cdI>1@rS) z9eosH&(SyE?qVNC04TgKM{-Dz_hsr z(!lp&&G8>j#s9Be!;n!gwm#Y1#}V1AV(WAFfN^L|i4J*iq%}VI^=04v(~-YdFY;EN z!w;R`A1~5E1Eg$y9@Qljm5-M7e_pn}KR^Drbkjv1q3rlSJ!l)+yWW;4bQjhq4%K=n zY#ZA@sl97}UJYjZ<6|F%pqfJ>GVF(N{694`LL2|^>q|QRmj(4ick1~5AU&V8uHSZa z@|w(FlnxS%|9REsXpkK{{#Wm|Lh}F7zbOeCfbP9x=WmxWLs4ZE+yDE0+z#E2<@aZ3 z{V{*}NOa~gJ3h;A8iAIBq4c%7u)mi&Wjrb^Z@}3Hx!<48&(@n~pvD*_Qqkfs)A`v} zQwK!J8q%X`=bPi-$gvx5z9DkiLS%K59ltIO>rmB*USw+(_xW`E7SA$7Kfbg5zopp; z$hogG8FQI?o~|#S78s*5MeO?WiRpec*`FQ1zkisb3QKnXe)d^Q$|Z1?+?`j&>+m#*YfY<(W3k8^PgoCha$sniFm;UE zQ+0&>J-?xLXzWb>d={O*UrcvK!Afj@Z}r5nXsauKKAi5~cntJFrLz5FNFehb8+2QVJwMn#%K>%$#Xo;f z_h$lwPM|+G?MeT6!ufZ47ZFW=r3(&_vwthINzX}Bxu>Ff+Gq#{Fvi-@d{-UU9 z3dDZYl`fyn-Cr2&V8F|-r*y&)a#bQf&$h-7zyG)^Y7z`;(3bYSU)Y?V`&0QjJ2e)K z$<-lWH?}^{*B3!o528Jzdyyk=x!39ZtmQHYt&*KjCho2OKi=1q>wHv#&RMYYv-h*1 z$m%RRKgVXDM?cMM$%mVqz7BSv^z|59^v#%^pYvQDk*+b{|DgT9!T#q_#3Oe9{oi93 z^!FQEU+f8YmGKihzJuy6BGF_AGPhQ^|Dsbq3F*l8OR&y2oD1^@oi<&iuCWP%@%=Mn z7MkM1t{Q8{KW+P9jY-)a4_N--I=-N(-FS6^qLa?@UPt#@n3gu6bcuy>q|7r4UyOE`Ko$@8%QTf zMB>yr|0LLfKVSPMYZChWkbVB)a@U#2{}H>slyoXZzGB&Y$+4F6os_?wv&tJ;TeJ1` zpatPDKSNI{7qw3?{@a=@LsJzqa7st6|48eT=OZ$}CDM);|LRoyZ@;=0jcv+f&KH_2 z3PP6F2)~%c;e*yMZ51|wQlYZc#ZRp{zG?qZS+WDA4=Kf4mvO&8jgKv%;c)eq3?C7~ z{;VXv0Y~SIXAs z544NW!(P3JU5mb^<3FK?3!3zftt48rZok;Ik?(^yRPs<#KO#kD2+wg%E$VE2) zmve!Oe>pKf|1WoNN6E7LA+{3k_o4fjA>q@|cq_I(7vC;Nrm6h-aytG??7UFzWxl^c z`-iV)EG;oT?~d$Vvg1GIK|Ojb%l~hA z`iigbEhbDu)w2FQYrpHe&L0p_uq82h!ttND)DwM??Z;%r|E}5dQI9r8g#OT?XPrx{0YsibReJG3D1ukt8GE%GJl1o zeefIeu6|H@cf1sn(!<#$bN%w!eVzSV_GIo9XdEj~U%89M-iPKdyK2C?6p2Ni_ zU7t2Be2iXo>O~%;a<9|zdv^OQv_fANzl{CF`9=z`@SGF5K9YN$&flJe-stucwmhjDD+*AKR-h2lLWoJ zDCH|VKD#HpgS1pvsp`Ah=KM_GpDQ;!5gBx0&rfN~`jTTh>Px>Z)Z_9ibv}9I+B7t8 zG+)1Cs=s;6=_K->%hn$?X1Nf0O4q& zr@vFF^T~#b6VW)ru0MA;rlF$)+4^I`-D?ma-$SZ(sJo#4-l>v>BAnUr?Wu>L?ygLK z%oWxjXQc(mM5aGj^M!i2m`~7P_s%&i`G# zF<9xwEDj#7qV=|i`%KS=U{!?A4 z*OBeb&(re(Fa2+!k`gvQgawwtxDonNly;Y<-=t@8>RU2P6JjGWC(K+y?Zzl&$Yy4C)3eQrP(U9TkkcuCecLy>Yq=qs#vnn~guWqrX+FnCGXj+joHjV`ci?Y-G#)fd;RBOfQH)j@4{@>Be;de2tplrS!i; z#~73^n=fdcpP~6jYe*bgzdiUbbYXXjWYOFSdwuq{v^#GjiFnSXf=C(K->&7$P92I zS?aCt&#!Ou-9nL;?0ns}9o+9j^M~519v@X)JAECV0^=oOeC+w)>rd~oJMZ4`$1XtZT+mbAUCIrbbEKy%pYQL7hZnwI$wlF zw_)?g9()z85SL=jqulRH*9VU6AAt7cj?!Nqj)L*s{>6PXav^(u>}XRX%+l{6^^M)x z{5(BBv&p^|jZS9!I{`Ppp*ll${4eSI4irh$U>$=a_c(1`{%KkRt^1*(Fyq_xSRg7`_FcM2VU zp3dwK)Wj5`^y_T>)w`z}9_}(g8hE^{89#oM{+cPdj3RzZnCF*tBtO9_UQg;`EL?v} zR^LH8EcyIFZ@MH8gF7jaFrL53*I&1HssM6llfc%!(h)?S%2Xbr$6ZWCH8bII$_M-Ul6-`FnnmVCyV+1}4?N25Xsrt9$e ziSEC3bJl_-u55gms+mCCF-vmEf#YAAf6{Ye(foC6{_*p1g!@ixeE93`M{TJK)Gc?EVC~PmrH6dw%X{$xYOFl06^l-Nq2t=JuDyI&u6nm*O9%0gq5&m4tb| zuqR#qkd_21U8(ijel;-&f>%04JzoKc~tMSN9Tzt~_ zdH7Ne8{borK3^itKbuVyV24iw4h-a;r|TQ*&mD2cHG0ww--Y?7r@1P0|Ds4H%;uh_ z{j-vZU151&S%0Lyl^^)^zno0JWCmLj8#V5E8eiI%_n{u{?D|KtWvooUI+4u6*7xVv zKV=t_(8>ku{@xC!5m4zQB3rdNeMjSKxc6c7q?FA+qY7LgzTS@1&KujpU;O(2jr16* zD&gxt+FwJ9M?lGPetkrrFIe;<2Q59%uK%qR&Y}YmeEy;9|4COygWgav2{tzr)OYTy z0L49L>pN2u6+E~?Q+oEfF#q6~>q!1@I4u9^R7KLwaSHVKcty`H#a@AJO-_C3t;Hf0@>Id*}Z{n;W0vo-OqS zjh}0#`WSULmTp}T)%^Z+eKh=CdssMz?GKDtg=Z(gB!8Jc3tTD4UoVyyp`>kWeEGOvL6((l z{ItKUiF?cN^P@o+KV@}g$nYB*KURZ>;gW{oJpCp|%}=c#P>G%uvHgd8xo=QeDVv{q z8-GU`Z%df-QJX;t$Ga#=ZQI#5$3N{q*E+X_nO)iSPsivB@Hz7g`4-rx1)u!;eRhpj z1yF0iy2H8nruoNozdn?{Wb?~VdrMjWfUV!+b40Ks#FA_==iZ;j$M9n*$SRk8e|1I1 zESOW_NInD#<73h73^e}FeCGYCKkZH;&4=v!e;r56fJFfgq{}QW{(~L({Gp(E8tvJ{ zo*&$8J_T;fX7k5kg+g@qB%41PI?RMuc4E?yvc5U~>HQC5&P$R19JYT@qEU(*&n4hz zp{@Al&rhBEtA|tkG^KCKwl%*$UB8&wm!q8Obl(0Fx<6xG@dD+oXY)sxuO5zjrXii# zQY%+Qgn8U%8i{%a_>w$%*6U!HZ?~q&7u3|NqRmj%Kc7 z=l|d>_tDoT@`5#mDd-a$PC}0b_ ze*e132v^m~K7XJvKJ46nA*Uy7e56=(!BKxZN@q@1ZOPyK{)6p@ObCz|6s*ny9qu`>VX zR@Qu8e_zf~o`-+`nTz02KfeFm-ihyzS${f*BDV4Il}hd3uS#A7n!X~U^P$Bb6Z7#^ zg8==z5X8Gbj;>GsO}U0nX0!EE)2t=XN#XzQKU^ZHpBCIKL)kL^Xzl;g{@B9dmFVbY zHhvE2n&X}WG^FEQgz<{Kov#pe%t{w1Y$Bu*W|o`0!RY(&GRvgdQT&+nUc!J+wl zIaQx*dLa*?gkPV~`z@{>vc&&3X-U_v)fU9hhwdFgy{H8LoyNr<%|EIk_n|gd#y_Jt z{LuRAnW+{O{CdiqPuEho2LY4L5ZCb>{{&O`DZ5|@nVlN&xS8DN)A$)7?E~FzuysDhlOWd7lH7a8y-w?|53>3e4QJzL)wz{$z)VDD-WJAB-R}Z4 zBbARI+CMXQ@`HydBHsLNjUyjFSDYni&rJ6H6>l?FLPl2+(eM$*kI4Tr>YL5RPo48E zG$n%Fzd4`33c5YBB~dEE_)#-{gks0A^;hrAHPAj$HebfrAE4#=0y+OmVD6XO;?V~$ zf7My4{F~eVMeDPqbDvP~6+XUbeb&YOFA6)6$Go2_ct#%_^`WygYO^qY)>tY+@KrYd zG?0GSOG!(rWGsxIq>HMsNT%Od=R0<3RYA7$S>hVZ;fL05e{}WWe)UtPf95#t39Jp{ z*Dthw^LH=>6+^y$qw(|b>L8eXiH{%Jf5s{!VP2&+*`34TgXW)+#KENn2 zl#QQPJ+^|%X%Xr5l=GL*Q}{8dyoMSB*#7d9W5HltXG7)>7RJx!33t%?u6%!t)^9Ywe`6hXIF9`;$)>Ob($&(84^VI>s}sY;qKK9t(2 zf#F&S{@$|Rl*UKs>MmfL$>x`ZKYHQvOKqif-lFFCruEsRw4U(h>{C3rWqyqIm)C5n zgUg-I65mrCK4^ZKc)mX<-T%t0Z`6XsFf3h>{OK!<59y#uu)2_qk8vHA!L>#U(k_j| z56v$}=Sonz4qKlk%-s&=aw2lESQsC(-7X{BKt4WbeWp{o9m-Dd@j>&8Ph2U|kom`~ z^HsZNYzK=*8&W<=7$0d~4^dYuzJEsh$Jt6dz^|Px>GEFq{>ctUYtX?Iwtuic@EtOl z$mW;tZ*~A)U`P79*)`*XzCYVf;|H4hIRWPn<>vF~{UF`$dtn8UrSzZsq+4bh&aFE@f(OK6BGd~m% zqeC2i{Hh$KfkfQNr)9`E6*8IdP@8$A(Mu57qh$Pkua*<2s_@#Gt(-QRqs@)xQL&JeRlojCnP z`PZ|8`#|I7r&!a4!w1bzD>nU=`D+E_)^B0|;P`40R0Vv+Zc5zqbp7)w&=u}QDUupP z?sdBU30gZB#_!Q4eoKY%H9>hJOuK7AAcA|H=BK=h~U668E#M}Qs`v<1373h6`zW+w|H{Sb^av&&1li1axtx0x0ih z`)|j-bOi7H{Q8CV*GAe+#5Z=b@$v4y2E=w`>oY6EUr;;#Bw5(01s{~ZrlM~E2ZP!C zVLI$R6eu>z>7kXIO5%Fqad~E2b1hxCv z_5aOVs$jc`t-q=tO~tpI*!Wnaq6__1+5WTc137GSCyU&wiQ@Q!!iU#3BhZ<`=8qXm zXJLZ?ZK<4>jv#;dI`)PYi`oA3heSo(`~7LMcQuC(+CN*|b{Op3C>c`zJO`eKvgdC*-m*h&kUmbK5WEH-TN>$7(Bp#&Gt2{42c=K!M1P z1i!ZxVhTSO^7$oI+=0iB^HntPmO~QKQ1iGMfAoCWl&<~3 zYbF~%+Q|yosBI>h|F)f={wiK!2VeZy{=l>ZW&C^aS+e>ESKrY68<(rDFm5!PU!KIz zflf;miIjIfjE|of@P~l4Z2UZ~4~K+UHh#p)h4oiaQ#Jao zIUnCl=i-OP&%x|O_~Fd=pC?lMqFeA5EvWUw-?wqk)A$*?HxWcVL`16R(yagFsQzc9 zX9LP@+`>Hn?AJ#Q*3M`5Kkxr*2jex^{E|88Aaq_bRhP1~k3bV+GkWxYXbe(1mZS48=3+)da{h);N8#9T)dPPC} zWY;^wpFwQ?v0kc<<9hM&L;Gu2kGO-?yL#+#hT{jie)-pa0n|Dwl1cZu*J*#?cVi&* z^wB0|vs+*1_dlmCjskgK3v%0MD*qhS?g-muxf4%f6H)ijck6vQy4$HRrMixCYyf_CoRL` z!)*R3`)Uk!MY%Yp<$g>0eDhHqRqT+IO{xyG)HhW9FAC`c<#zn}Od3Bc6IAhDryL?$ zb-P9X@%^>qy2GJCjqR^J@l?hxi?YZMNeh0c{Q-3&M!^ahepvPY;rwo>apc{}z9^t0ge&ti&yGL#!p z^$|9HR9w>`MYccBLVYyHKh%6%RX;hncxnq)n9b#Hy8i#LR1ti&+4aB2jtmIdXGe;r z3ZK8xdZr9j`fPo-Pgff%T@!H6RPOU>|5?0i4K^91DIMr9Jik0wzB?@UY{IjcfCp_a$I;mC*ZmIve^YrZt*EslXZ9zu0 z*MozBA{ly_`~7HsDsTyh;riMnw@d5me0`_e{s5dZvLL2ExcH~>Q-AUu z`jN%<7d-v);N(m(aa+wjPvd8+UL(5o!G}2?ntCG(ENX2?LkNc-djHwI+9uTg5W7B_ zS(FPJVGd;Dwef=dH0f$PDD~Ka`}E-QGd*8Ww)77k4LXJ!&RKVf|353qrySBkLG^;UfF z{fBGwx?(k>Tyn^o!&eP;KbnK`C|DrF7i&JJ&`=dGk4z!z=5m~VqxwJHCQOBgcdPL8 zmh+dizpeRR6|dQlN&X57wEulZngm+P7DWC7haa(6jmK}t_RIF4o|Db@#I?o;?`64O z!TFFHZ%g(?ootR@S|2X){)Lpa*!>~L&$)2A)P_9Vz~N6!?MI%T)&_zj+4y_>_!K0X z*c0_Jt}XcC&u6!J+8&C_wlL?j;d>q|{VnUio)pHPS+W`o?#cGYx4p;*?+$j%`@KD! zb-)64G51UDm|zIgyRzqdax%AJD}7CAc(ky7TvKTQpF8sRv(f#f!A%39%TYFeDSH~= zBj>V6%6DOW9b9J*6Rs9vg{Q*!`gz08>Ts00<(r@A?&$;-c`RlLj zf;oTp6!Kn$!x!B@dge6?IzOvo_K)<^HSm#rsbubVVSIUQS^=X{`1KWyuhjEBaG%Hd zB>jpThi?jBC+fDs5kt0re*VoaNcgQq)H-p0AC0ec{}kx)$(%^;armP7tMWEXS)ZR6mc zP-MWazh-yn1DiYX=i_L6M4s4=i#n+@>#K#chJtAryS}P-=!VZeI!2-*cRDop$Ep6( zl#R}itibojX@6qD)`{R1auZLz&BYHre=t^03tOHzL=49NYkq$@%6~AcoeM`LRk*$f zhfkV+UJug6W4awCa*KuaUsLEBc)x+K|7d(v|24%$yYtEH-NN{=b=UzF3T%IG#-UJL zK2$>*cUbs-t(66P!113JnP|rS{WN~$Bac9z^X8;;yfA*$Lw};f_H6%8oPGh)_lrmu zA7T6~Uf2e*1ATD*c8=d@|Ke+XDb%LAlTWKtIeww|i6pcKyDxtDb~mnnMV}w~@KzOO zW$^ij#?Pqn7huY85t+S8cz$mAFKyWPHx!TBz56B`~^Mw6xC7&sva{DH8Kf&r3T6kneBC+}Ys|BC@^QXIBEr5}QY<@`<>Ephu zQ_0vb!u+Bxw*l(?`TRor4>pm#aHGj7l4!~4H#v%5_S%I*!;f}Me|))5B>s0^LpsRu zLNhi>|*Mt=oZfD!cyL*8#y}+5Mn;e!};E^)~4QLH*eN;IJ#5 zA$lm=pNQzI2iw1}@#7V41a&h1q4j(nT^}v}LqI-VcK^$5J+6OC-T%^Fw%;zl_5ibf zDly-QpO&aeKZw=|o^L?$){ye)2y?&NRI63^wfhf}n4s5^|M~l;3cVem<4m@HzR}YJ zuh%+8`nq!X3#RZFb8#FDSX_iPQ@G!k?%)2)=!T1brjS?viaGpH``7P$ngNqn^7S3f zUuRwz;1O0S#9E!xcfk~Yov&UBOJ`K!{EF86--%aX?2qb>vp%MhYtx1KYub@5@JC#a zFC5{Xr}^u87c2bNF_(A*j}z2)|5opWriOMrf1RGM+vAV`i=(xOZ)__*`2NN7#ZfrW zsIzpf%f06J7mNA+pr=k2oLy#4oX595&#$i@%rwS58q&$id9lsU%ZUwnf4|xXdH6Mm z?H?W^QZUOFk@eZa_*;jRVDk_k96z7q51QYcJ*AK^QbZ1o6UN`EPO9KNgkOKr{C2)U z3y!Vl^Be7N7{4R%_?8WGzSUr|0qlGj%G-}c^IP(*o?sizuAdsdU4e;h#l$E;OAw!J zU-p5rh67B0z94WIoUh^IkJg6<(JOJ&#?MUrE%SAT@ZPz&P?!7v(*3KsZ5;8r4Vdh? z8`q2k@UkHOs-Ag4Z6Mzt{QvMLHN+eHCX+mkChmC( ze?Q#(z_YE6=8Bx2j{5=h6;3i@I^F#;X>v}D6E2I@)e0*wUWkb~mQ=)5>3;)ySG{5Og zYzys5*!*^K!Bx08+sR$b^Lz8=lt6B&nE3VTD2N~b z#RFj1H8#JEc8S4(Kb56#J}waCx8aVqV0rooZ@z-Y*QYsa@%P|QOnm)4GYX1_v-wTU z(+pqvn@U9L5nOyz{oxB2C&T;6MOfvGFuxf@n&JSMJHVdVUIdbHbLx7j?g;*R9>SJHuis;hp&>Vvw_lq+ z-@WaDRelPR9#c!+pwUTS_m zmBP>MH;ce+^i4dkWxpEDPv3ov@rlz3y`-@*5S>Q1}4w8p1QbByWHY|sdp8Wc)hPppX z?wC0q_$QI zO}t_zG{-mH{|Y@C4@1_rBa>Z)@rkkqV5dXryL z_O1_p8gq!0E#UZ()|bPuQMBeKehW{?`sE% z#%hD+_@(ieG9((-?f!zN%;WGw^J74@GjFX1rm$)6dF2_BeO5J~F zRcDP|EYr!icurrYiuwGwT_qEm-e{8dA2|I-<8PKyG9G`pvs60ve)IRI{T06@64=49Hve6FQweGd97whXhku&?l(e*Apds78tke1j=C3`8-5(Brbbsw% zaaZ`Uf?eM^r}hNDXMFt8{>eAo8^$jU#fBYPH8r3Cnbf5(uMIixaUGy|C2xeLG$0s`hIw6T@u+lRG9w~C#-|t zzi;sR)3iRVz10_2Jxe6IIl}y>_GUY5e_x5odoKRz`c5Tm05rMY zPaz}Imbt(G-m{_bVYsdC4AFLjTlddO{`g9I|sg%ERGbRkwYb%-liu>guSUWqJ z-xa{KaC#L#$z3-*U&WE=nFV(o`Y5sHEZ;wY7 zWRMR*-W+}@{tK|r2lIMOqB4NvADaI<46?xz>0uJ0(xN{d`SoE_Y$5Cxbt9t#(wgIk z_BSUk)dZ*QZ2fun?@P#$-EYU@zv%V)FzS;xZ+?=l|GF$_i-T%BNx7vk{;KcyfJv`c zGW{3#qn1#e#pXZn{R3g|8Mgk^xLOP9y=C*u1O1!pGkX8>T6Gaj>dofIA^LuJ&XrQq zW|x5={+66`fjcYM^`Z6DbvWJm9!b4@sOW$Cl-~dMNqZ7}c4zya`<`vY|D4(QJaKCd zY~GQBH{a*{OIn|<&=BF5S}7!F6NgW_zwY}6dOcK8cp*w@i|XkgkQ8{ z`=3*v9f54cb|gmTQ~vMwq47B=-U%N+ok4o-;qWO(;d2Bz19P6U@i}I-Jq}e#Bd5ZI z@ma16AotaPOz$a-Ps=e*xZXE|L>cXF;a7hD4=>gRZMmt;{c67|-hz8a2h#Tq$KSMm zH8^JgpHun#N#nQdoFeXjlaF6ozYZ}o0q>0~dFMlE{&X5|1>5$r@mt(xFceG(#g?Y6 z`i`$(3-`VO&(C&bdf-|?{2u5is~fwq@w@-mT5Qt)78yIPTl4Q5Ox2ekFOLDSBU|70 z9=`_HN=k^_FzE#${BHG{3d$x&@W?Fg`_uL1n7aA+pgZRAE4_d4X_yau-z_m}ln_CD_O=ay12X;kr9YP+X#b|o&!PC`x&#t3hQlY# zp9x!{!1WxPKcB?f;Tf*UeEwc^0My2_{hJOAc33?vnf#f-`KvU4c9&$pHLJGd z^b9V3X?!N0%fic#be5VN6`mj4hR(sH`)DbEd2RY8p0trALjn4v0fc;!bMN=eV{OZ z?o~C1m7Cc9&85}-V0`{&rhXk0F$`29L-DM9E`DkMCVcuwsMfS6vjc_sQ*Nmvyi#G~ z&nk8!R?NLctow9t{{P8Q`1=&^2E#oMFz+{bzJ3B8Vx38b4Y}3ae+(A${T=stGofdH zHh-2rn2FckJI%zOUfCj0i(%{Ajin--uq%Q5@DFXl7r*}z5w;#`D+_t^&vbn`BVs!o zJq4|tmpJAJ^!NKEe38Sv+*|oJK{a@$wW?t>%Y_f%@@NYh;8`H)UUhB zXX0xQPLuHUt@p$8&kr15cod$sYeQ_No^1a8X#ACbosGvP7m$u+Yg_n<@8A6BSqRo~ znq*uxhhG|ho4@7Yq|K$xghLodh{rc@!C+wfV=RdlB47+3r+7>IB=ey+`2f}GPe*c2@PvzH&z*fxe zA9}{sLruIru^kv7$bZ=%M!=G;?Ec1!aY1y8@%>5!N>65UF zT_&mAS=x+0OyTd{cTX7eEDa|Fa`}VizYw$oE61|^9pkKJ;A5YIJ0p&tX#M(dix|J2 zl}OUA3*&G6yFhR{&*w)Pe|_6I;p~(ol4`^GJ2h1QagA(mED65BoUcB*(HZ+cI7k+V zx%q0EA3LV(2Aye@IQ1%5-_icgoam7_D>|9zXbR)=@$W-0qJoXjvnS?Y%^_#Vo0r1) z+>&)1&=`4A)}eL&guj2ps4*YUYfzVp+Y0mJj&uZ@wz2Vf_m3NX9F;+44;S`#{+xaQ zebddzzrn)zY_Hf2yw6Qx>eDwnzQgi`hdNjM0QZj$L@t%v?@rg3H-?Xf z{(qvG=MxU~pN{wL%_OeRZnxl@zdvq1o(xNSv+K)@8Po8M+7slU6eU$;mq$K4|_l6pzQJwxkjDOGNhJv*r9NtzSQN7>D~mPa%B_qFeZzUteCZHUu-*DR@%L{z`hjyWjQS zU{lP-@8Dry~s6}jkP3qAP$ayw?OB9BI@9Ryx{SGvKhZH!%y8e8B zmYxr|WYYw7+Z>6N9=E@Q#_u8VICy$1nt47p&|)_JmzqibIF&WyS4`>KG_UC}W7Gk> z-~xv~+Mk^}d=@r-eu9Xvar&0#*B;3WVAta`W_|hn_f&i#=qL}rsnq`N^Y7L`%m{Y> zJHsVCH{tc%3m%}HVmgR3{sczrXg803<@-k?7v-ve!e+rIlN+)g&!7cdX z`?n{yRKfWDW@O<^VSWwLHipxZDa`X1*_v{AezZNQyUXPdnqTw&T0*WNAD=Y84v5#p zsRnF*ZE8OdvSj#N>CzhC{Q1;PIwJV>auaiYrwfdLt_pnrhps=Xx4Ge6Z^1s znqNEI7>DCy63OL#oIgbC-!VG7z&qdu?|eJWulau`;K#E0oL}j}^WkdU5}>K*2_Cwmafw&z61 zzwJ1EHdYNiMxGikXvSAC<=;Lky9VjQG|AGl96o4%J(98j55AE@GIxYEKTrEZZNr|y zpgnAUUG&xmtFOr>*Z0J?;G55{LF-Il^ivtX_HV@xFTCaId$hq z@I(Iua&BZ&OaA2VuUM5j3P#BAKgf~$`)T}_tRIj6s3(#i$DLcA=i?uRxWko{Xy$$x z)2Ck0@P>_V&(A*iVnQZ49(`Repa|N z2_G;?Cc7tc{TVq5-%7rrkTvx(e0VSH=l427LCerE0O zT=!l9w~4kR2DQTborXRX!{#WqzJAiz9b0!xAj6&}w&0VG@3PM0V6Yrtf7AHhbaMi( zQ9nSoyE(Kx&&T&z(aNilsFNN#IkC-|7DB zjmmIHnZfp#_qz|lzW2A2*-rV*_?4sZexU!BJ3S2;(1{ru&gJ+^V& zNkZ53YQYb`ex4$`*W=yZKiIfDqd7j*9r^y&57}ESIs7~+X?rFJVx3;SdcH%pH6$; z4{PlUB&N>}bNHj~$HsBa5a7OvcRxH`U(2|o} zAGDvmdn4jLpVIez&8NfK716kBG8cdJ`Rl`{mSLrSeE*Eb|5D9`P$p&bKU%O9e;ay& zig??YvD)|8~?_u7U0E^eEbJH@XudA_`DVBpJg-qyN=c~@F4$#q^(34{||5^ z6n(qM^v|T??)c*3d8EBonjrr7m&ZZ-`s+-8ds2uQ*3Mi(v{UajKTq$U@06MfCcbQa zPrOa=&}~b}i*c>~I3NEGr!yhn`yF1Y%k__F{C}=?#CuJ45`)DY{)4Idd$zW$e_Q+q z=l10I--yD0$W9;pt4BIH9w9uxSo7^JBx|z$Gl$F%P-13ADlLWa9o^0f*OvPeow2R+ zAAJ4p)zlkAtEMo|ulb#CkB`dPlYV=J@$I|N8W!fyjH23v+vZUWzpa@^#`Waz9Zd1N@uYYt{dS!>e-(4s5?lR|;k!l{-zE!= z!26gdIJSVxuQb0Obuq_g(M!qXrNa1z+b1Dt>|0!=!u6kMe7Bu$hHd{3UvC{&#rM5` zqu7aEsMuJDjS1MGG$PVS2m*p2DdM3U=`ax+F|li}C3bfQ26nye_Bp@nb2iR;uG!ze zy~cAmGq1Vtm3yE!hBW_o{-spkyR_QRj;t2*-D9^WJcwJ3%ii+&02;p!7<--dyd~Cm z$3cT&NO%NVdR6Zy(wFAfdYpLA+71-w*R1C2Fy9g4{Mxt%4I%gM7@>auY%!d%95LSu zEw$j%0tdt!^8UU4aed}jPn`dDX)+!HIwj(j>-_nle24EdVqr$&_^saU_a&Itm4+=yX?XH|Twk^1!4$Vg_R5a;K{6}do%$x^&Szsdf|7pK;;MLq7oSbKTChfMAR+YZmcq3h-O&Th7qMFc#D9g}$d zipK9BhfM*)izyf|lIyn`)$gf?Si4KVV6?xyervi-1LJe)cz4VcmH$@gOZ!KTuDi+N z)S6?J-amgU-QTbv?GsD>*+Zz`KYr@6SDIpe9i}#h{!hjH)*msF*>{=+CKLJoE~?LW zKX(NyPjP;YT^q-mjTP&2ujdoN=xhSkcjV890XaWo+UjZSWdm{iT{zYhHkYQMaR{Gp zH!zUuv(?-g%w$Epq`#8J-xi}SVEwTST=$@lir-?wZ>Q8*Yp z8c(`G_AW=vKYCi_4`}^5#dZVR@$EL~7|HYNW7ri;z3g#Kr;n=Z75Y;DovGX_)HVMZ zBrW3gE6T6OVI6q<%NGNF^Yg1{e!WhklWgl*bv*x``&U}OE={!qeXBe?`SM?Xij?0? zAMUcMnC5tD6u+Lv-)AGgv6)q3es!h}X6-wR{k83srr>o!%SnC zY$eX0nOaX|iY`)qX@7HO!%49DK^zXg!rxB{!tcO%GuCr_q;S9N^x0-`$RQOS@)A`1 zQGQps+cDow()d|nAnlKyc-9hz>`BLxm3%%(LHMT z1=m*^A6wd-VYNEcLalW?ex>#4vh$8Gb!Hy+tYg9TmE^}?kFI1#3Y+80Me=;QX^e!S zUBj`Yg70Ud`LPREezI-*df@!p{PSsktpCnXIApROnMF=@eoq=d-`+TsjZ(&lqWt&+ z<^JEnyTp9=`Z$)Y36k5~1_z!l5Pn{Y>NA7skEdjd-juL?>=^7=B>&#j4;@V$2` z&abHElhm)Sx}IlkzpLX@$@v}9{B`{^`f&P0BnCbh#`z@v_jvAO_Q1C})}JBI=c!wN z*_s_aaDPX6{_++^Lce3{@$+GM{_aiCV;U!|h5aMr54C{JDP!=$a{l==KmBZ{A!`xf zD(ugkV$>TR`rBb)oz1HE8||O&e9@R$t@9K1kLW(13OnY;Vb(Z)|ERv+GMLU5uUjDO z|LS_n8W#Aa;5YYp)#odSKlbu)VLztEL#yijrPLp9^qUD=7p0@d0l^ zeAE2&@lgv{xv`kvBL(s7-LF-`{>(3E1V?^L`K0=IylDorvK8l-zh9mPT8-k-wPzIP zi|C{6s{)psxnELWt|WYRX*d9!wP#^SG1tdp!l&!C5*9RA>TfBZv0wW^kh3%PeQ`$h z`IV$U)4*dh3v|2zyTf_@qu4;Y-}6ezZgvtM!=iKl>Oa!@(TVqcq2pgi)T^hV;)nXz zhoP6){`=~9I*ju{^%1U*1H+w>nE70uKaKX!*g%)&SnAH7f9hYY55&OyI-78FVtn=I zOY=*EpVR=?rD8s#?cyOxd4AH(8bz}D*zNO3*7BjXus@_m{nik@NUV=e(0HA$KZ<@Kd}QvEdQl*#h-#e8=E;|lC{CicsU<$RL( zGpqj+rX4TV&-a4|LDhy?m~fBtN%O;t^wzQit;Kw0QZx$2%d}FznZ8m-cjxK9d?_cU~&z1FuwObu9KeTBz zKhpg0$HJ@Z`57_4{f|zBiD8lW=(aq+LH;k<*1_WVGxMhd>_|(;gUI_w)JXrw$O?66 z@7@D--~8iWI)8NPu(G!yZ8JW#;Qb$TzePujG3;iFSYL~#w1rykVt$LeO=jb#x(fTd zJcG>HCs(n4Ub=1q3Bl2Lx{}BLYKGGDPkN28XWC9;J{Pz&ZLh(EsC zF`7lxC=l+yXcMo1z1vIhZlg~sf2`1#=9g9`Br}uOtAza>OBI9`b!Kl-jsrj5p_->Tj3z>)ES%;{J{% z)`MZZ!UfHDoUQ(RX@6H#2nm_v4@GWaOOsv12mRWEqdN2BK$*8_w zs=xQn)P}2WJ+QDD*MAzH=Ily>K&#DIGJ^A4N%kWi%F}1bZLOhyGSAP_{;ivd?VE~DP)dagsbA# zsraINm)3P+C4VD?=ZkH=Y6n$&6S4j3Xw~&pe@{1=!&(dw$F~bgouF^O6udjHi|Tsn zkN1uXVV{1a3Fn{Yw{wEn3(073!C5x{6!|=cjd+zWs+?vK^d%H|L^`w=ksG%7(o0-KWx1zNW~ZJ-`wN0f`!zS z)_1ADo^fUvlz6z})dli=@3^&*Rc$^A`>Xq_slP65JrHy{*kKK=Q>xDgqTlOscCm9C zZ-9@1Jl~EE2iXtnN?5y?^Go%)MVCQPe>YL_Me|R|=Wes~eV$Sr$4;w@`zyB&cY#HQ$p{&fWce)pl*R_et^#!9{+sq! z?zgdlr*&f``6&g-51TyAV<%7kAAAOnhnxv>aq~5KK5ZR~S=aCTB>h#C&+pwwLG9CS z*fe0ZiZAM~7k}KuX6H!xR5NTK$q$Zk9t>`OW=i-}GnDG@=4*S{^mH+w7t{s;n_!DQ z9RB0)7qVZ!c-LX(I9$pv%}@2t9R@#@`_Eoa;qfu$H+bni_BTiDuYWA`gl$99an88v z`Yg#Gcbxu-{a4itleIV>G(NspI|+Wcug8ZoV^#c8e?59(eONVAtj|}USV7dnXpC_6 ztG-^EKb}8s0(<)1N;qGWhGx1q({xj=H2J7N0=DYQ}88G-$w2<%A*9C0a`7&Ys)_w2ae{{F8d@pH-SVUV@l4qJ}l{#uRj-N^yj=ZTfd9v809)L*x~rU#L$9I>>g zJm0++RWgrou|8{MOaP66zG!-*f3?0!{rA^}%K3b3hEr;Dekk9!ax&m$r_H$3Kz=?d zetJV_&`Hd5c=3ExeGUD$Cs?XN#CbQHg;`n*rF)jGHd9?6+03&M)mbBPKSpRKN zJQ_alb;7=91$>9vv(S&elKdCtJAa}DXnqdG@84Id_@w@OM!6>o-V!0~pMH1K31&}< z!v+!IvV0$C7Q`kzjg$0OQhmPh+6l5O<1lJvOV#z%f8Y08#NGy_!TebM_fh>G85{yS zJG1fIZu$6HzjqQleLP<{A31e!D#VXihihE!^7xw6pT0iKWaa*1|82X$9-OVD{+sH% z{>LJAC$0?iv;O%bssFxSHW^$-DxcrJ^7{TMcMbE4-3NoK&p)L68>bn-%s8pOQ~rA% z*~VNwPJ(_k|NVgMKleX63Zly#v9^mm|7QmtV(Eo9B=sjXLur2dwQ~QKS%aC_um`UX z)A%~>**W&U)@uk2;qMR1e{AcK&|sxKnvUc7Gpg@;<&T-QwK|4QmG|eDKh1%2WvSSH z`y>_rw7-%y{>fezHN$!@`R7yq2bg$4NaGY7x71m6J&^p_a{I<$^|3oze*gFWkmk?Y z9`S1&qm04zG!W8oT)SqxtVFbcL1gWAW&JEvi3XnqRZu6wSsLi2eJiWZt zT4{J%cXBm@Lio8z|>@hQCV2k^3U5 zKVQm!(edc5`&cIc&VOWa{ksGa~t+wbE&_l^{=Q-%Ky{+dP-3)vl=Vr|JfUNh*!S<{+(Y*^}pxq<*bdlSpSD; z%z?AoiFm(*LdBng`2V2W8`w5uss2;`N3VR$niT@BNn_VHOW>fW;WDPgMVNmyChP#F^M*59c39{jBcDYi#+CH;{2x zp8tD4M#4*P8|+!tNX3sD>A&8q-2YlJO6>oC90~#0nt{J&7+3Qr<^T03HFzG^3|}?3bTk5ebRiGVy+SoQi+ie|B3hof%Ec2dj7d_o4N15HbHA?@SGp)nQ}wV-6VA5*(f1Sk?3vC}XJLKqSny;>+2n*B zocQxg_5EgmC;MzD=KJypXV~2`0edSYJDkw}>@dCD!kL39evr zAQCU{uUq~1Oa1#%-vnkqS*+i`O%?EYY9@{gjaTtY>*JkG7c-Z5v43ye(iOH0k5u+2 zd#d=Q{{6UfA=CU>Eadn59zXc#5iikiHIkoS_<0rURlf|bMDX9A?)Ov-+RS|Z?iKp; zulvS9<)2*HY+%%fjiXm&f@vAo`qq@11f!yQYv| zrwB(V(FjA&HuClHc_y`B*05&ibyq$<_p1tq;T=0$pziqk>OXy# z#^kU-bQ++=8B$3@7B<6e4 z?^GCib}5d&yMgmf;`3!EGTAK)X?~8z=lWmW;G$h5&QWl_X@1^9a|v7cp;*{|x>I>R z+N?*?_}qZ-?X+t(`(C*TysPKSDc|d+Oo8Al4(Olfr{d4WP}(2f{LL12VEtY&*~{-Q z_2LC0C%og;m^+U{J)7m!>UHy63$oEeKj7E zZqLB9L%jY*{kfXqJ+{wB%zt=$V^DwUgk?RN$@=qS=^t2!8#S>@C;tBU|LONcSEyqY zjvAHn{69Wg8)BL@Lv57j|7tfgNG@^5ZzByXOWRlaaWpiL<64+Wy%)|Xw_$pd2k6OR}{x`#c^dcprb1?i88 zdf~$+>H13c8`1oHK!B3JB@6JQE$=_9B>kxqszRAUc?Mzs>hqJRKi?AS0sgTOXs+;( z<-gI+81~Ui>dz_v;dMRXRrdw>X?z`7{xg;)v$wsa{+#CL^Pi-`>zE>3rc=WCC;e}= zW3$(qWo$}wK_A(ZJL(G3%RUmXZD~-=7|GjUoWjc>GN%Hf> z2Gabz`q8N{e4Qg6{wU9Xeb;TQc;_A{%;wKO<-c@^5uDVsN1uGozlNbSKKIT$%zQSS zkmToSe(qA?c-R+ijT5uw`QO^^yfQu!^S`>^B-rOP1M?y{|1>|J_T>S4*ZmFjUBbUV z_3vpLKC>Pu=KI4rYq)iGHtId?D;s~$kE;tm)SBVR^Zfaz@waWTJzSmWkJF;Kzo&dx z7PSS1Zg<>pP+s4|_RofZ#tU)E3GeFnlQjR9y3&>vW?I3(AbGy`1KXk{LMmF!%SA@5X4`S+*w^$WGUVBW)U+;YlYmT$dDam?FN%=e|YJ}_i>6kh*PUzYC> z%T!jTCGLM~(0(pxm?`jAMIRO4H2>zR$YsV;^PyWY|Nd0p54V{EVf`a9dpy^71*yMv zQtp@kb-EZt{p;J8DB!^36p4SQ`%OkZSNd4V6 z_9AmXaua?v=g+4B@%P%Nrod058Ca3P`KJ25>-{74p^r2^r~dxqTWc6_*d52WY034K z`1@-|zOl!pV*V|Eg@WP9cnm1w`fNb@Ybtc=L+MQoOe&Y>-#^F-?zD5mFi-tzex?1d zxTHOd>n`^9C*AB|#Hl&B`;0yR{`yk>?bq0`J&!Df`S;d+hQNX=WAJ5B+vNI7{kpH2=Q#fD!n(O~<;H8&&)i6McW{J&$#(@R8KtDgQllz2Hi#P_&$0th%1+ zdvWI|mZ#MBfBaK@@2cekE$)Y7Mjd&5-*PCP?d}u@jW7NC`=s;N8lwW>!aSwF&u=Kp zf0JKnY+*ey|J!r@;6Pd=w!P7b>pSuHu3Gu5du_45k5|e>2 z#1sqr>*^USf;MjwCH&L)y<3}7W_op#r2mHMyX#dW2#A`Ftv}CE@vlqx|FUyCv+ubR zj{M~QkMgf=WC80|E9>XQoPQeMKOA4d&|2*8-Rc>G;hyO@Igs;D^KB7;A<7YOGiB z1BCwthl1FN$>R7vtK1uA_70ZR-)aBNL45^tZx9X@>Rdl5|8L&;!kKkpSm-4m-!IWj zWSXyI;d`Mx|7YAXSoyJ3VgKAZ{XnpHjY8cI-BoWM$y>d zue~ha=BBIIo_@vPU5o#Hw13uj+#2|A_ht#-RNv1Y+{EhoN#l3Q_n$A*;6NW6)Scj? z;#-68ePl#ATcIe24`b!|uK3Ry)Q>x%Zbx2UHz4`DM#GP>if6~6b0hxz=#u`~YnD@C zv4=G-KFa+&)%S0TYixSBSl<(s=UXglZH+O;?^NHP`uB_wQ8Szo<qK8+F#TD#2K|KFX^LJ15o!Q)IOJV=)+4sX?N9!^8dI7&bl<$^$ zKJ1NwSl{QC8N;{+7T99NzxZ3)KU+LLgt^u7fo_uX52gL@qi#jBXO?39PF*+;_Pa*l zG&4`t`-9G}oZFVfK7EK4>i4a!L9ldhBpO_=SAD%S|K6}hCi`|URaigYTreMEw=TqA zmfd9ep0K)zE&H1%^zWYUgTVfGB!*3JSMg2b^Ty*=v;48e@M@|&-=l4(!WguW@U5mM z-9P&G$YwTouGqg@{+S9|ftG0f)LX?zC8?i({i7C?F7Wc{Z2VZd zR&_n)JMHfwX1nho{L)^l`hB$s-$&n=z}aYP?DB&1P4&B=-c9ygxxYcA-+zrvz~zb+ z_8uh9ci+mFY;^oI|D2cf+i;|MXv~-~V;@fV5G{ z`J+Zo)&4{3-@QJ%vgmBFe&-Au39EmN#&7rS*c21b@%(xv z(eH2L!dYx{AL031L1r^y<0eO};l$^^Y5ja)-&nT$Vwf;LS1@TFoVyc(HvL>x&lkuLOc z({w4Daw1Q%f1JkeUzEAaW3lt_etfWse>FAf{Mz#NYuWGS#n5U9=f9Gi-=22Z1j=Ix z|0F-Jy>%?fr4x3~zHc45( z-Sfx|FMexL&4+Zpy!Ygquz65T-0@JJ?`F#U@qthud>x`w?T@AXF%54ug)_loz7KbF zg{KcZ@ah&rS-#U>c81gWhM}{&J^zqEK%KG%J+YbBH8h0bA)_WqO zV3k`S);nB7mfwn2%UPo`F~1#m`9b!7{ur?_RK+jV@AggCvwgLs`c3)uK4cDmo)CVC zes|ilofR|}^Bbu=A7w_e86JP?rQ(C?xBkq%tn;Vs;JB36UxDm*`TNEQBCi@_oz+WJ z*Q*hKj_r_5sdoUvtU2ErM8CgpwSog5t?`x(=ewBX-~M>qV}EAdl$;+z`ED`B0(`wK z@vn_M-*5&D`#cKYMDqBA^82MKkiFULB&?r%95MqBD^u+9Q(m8g%c59wCg#_&j~#f|oQb>o z#i{r$CiSyd7vot`oiK>q#N%TcU*~G2GqdPeco)h4o$|Z!^#VAitj{HB%lq#smvh-^ zH?jU2m#eaP%bEw%{siEo^ITskpItX^V6g{R3ghRLrxq|e#a!yIiN5wK zE@vM;l}hU0Kx9Y0{P!;={K9%a z@cgN~ezd&5{(RqybttzG_P^|Js1HLgj1-f?1nYag9rN0AwNwLMe%2-)`&novDMS6<$cVu&CI6l-KJwt}8u2)l&_NTj_&0uNq zvBLS3ShpysQ5Avh(|Laz)#sJr`RtsLnD15B6p%M83ZHlDC9BW(=M=LCw$l6=<$rl{ z1f>5BLA{y2viiJuYbkS7@-On&GZtAx-&isK6Mc6vqoPv42K@a-`TyF$8s;`O$I7Ad z{(4rQ1FYC<8(cZJLG}AmeZCWI3VVW#@qQ8KpT^g9Iv!&k!uP}758R(o{!MB-KzV0d zyl2Dt2cpm42R~vK&u&QiUnu{F180NJRyVwT^QY?lLH+lDd!JeKnODO6S?|b1IB_i= zw>bBz)<3ELZgQ&*eEC>IxL;V!V;00^J7IGpem$*^jl9wlnzj|^$4_)l0kh~Nv>wL$ zR~2MF?QU>4D16!pXT0G2s~Jl5dzagM7;+*2Z7lftA_hdi!wh^_zW}j*d$O_cTw4!Y z?&0~-Vp1PJZxqHlgoyq3ju>l5cxr;{uFLE9eGO&*iLsdf^ubPWJ9h?dYR~zvB>J8G zI*Fb56DrJ)``AUn^zu;DOm|Z~pESQ_-ZhgM433366ZrE_^}T_H0usZ*aaL#f{+CY8 z3)xStRN?tP%ba5%q;(X6wLJe(4$9}=D^EC|W_Ef3Jn0sUb}#43^1m&&j15^K<)7xy zmwmH=v-VQ{Y5z;lLwguhluG(rDgQs_*nru2Gd$c+p8t0(53%m;x548K&VMoS=l!*u zVNA3ww$0xOcs3II^ASD602TAFbqzk>Li6W3i+jMhznyUMSnl5`|9&>1&~JMH zrnqtb6{J2s@TDIMUS=W8pV!@O02AI1$DswBf9l`!=S8rZKOH6eC%~YFq<+4`W(M?| zY>MUc`1_seKXZ;{=d{H9pT1@X_x4-hqah1a{L=o{ddmD*pUYzY_52kOKRFcl_Lb-V z_t7l2XOg%+w)wyUh#ne3^g7 zHRnUCSzN6=$^J&F|3OWnV3%S(J}LH><-dmh7WULl?Ekxuo(cXv#rz+8xQ`vIES1#9 zDgVbB%z&Z4OfV#g`+qf3KdbTM5L@wT3yf>^ul^~WPubYV725usfx)kM|2x%x-K|&I zahqfCdbkf&sb>E4N3l->ihT*clb2Q9*-4#R`IPy_`YxalNHVv>w9p3a(=0+ z^8B&-JpQKj?_>At!|5|pzNx>zRT>I!2hPQ}iMre$kp0KMYqf=k6;1Jk>%aWB^!yJy zrFJ>T%|*Mm)%$5kf9u=aUeLNrXS7=>&v&Q8iE#aP4EDS`kAFVV_sQD>SlnZ!z6;Lh zZE(gA>fIfNH%xeb)PU&wweAbq$NEx#Px=0I*%nNvo8aO&d3~>`+^?j4+gn&48~oB9 zyl0x@%PV0jzJcibj*?WiJt-7sKIQsM z&L5bN90~q90a$OzR~6sX-y8H_%GSP35$gN8H7g-;Lm}Sox>|KToj

      UCY?*T*>?y z<@-$8B1jk;gy)Ut$@1-Nxs6@OTq&GiIT&IOhn|~B;(My^&dUz4$GN4F{?jS7V~C*}E$ zYw8DS)0O>|1Q^Xn^o zfW7Lv8P0y>{S7pJ-}2=adyB`Q&tU%h(Ejv!0m}ILr7ddr=I0kwlK8wWtX2;2-DawUUm*GS2UU#4_?1e|2crB2={i70z*JmyP@dn|1IWDll|h^Ht5v@* z<=1G32V^PdN3APXsQ9A&>B|G}GQUD8-_(CAw7ucsi5VEMR6hSUZv9&p^y<2#KfRdr zr=#+G>ru-7$axp#`&(w*s{vcSzZCYjgnGt7-zUL%-m)X-o9OdY-zK0PP(xV%w)9fK z4dc1E^BMQ&lN&zI)khneX@=dE3ER6qWH zp!#h8ECw1h3_|mhZmR3mh(C{r2xUGMV*WRVj0cCu1Mx^F-hV{-k1L5`#)lk*`_=oq z+JbY|L_Ax+NcDWU5dO73C$XNZy@mTBDkI(CXDxGVpvC#8`M318%Koxu;`rM%wSd)2 zje$e&xqfIEO8KtoQ_O;&i203*D`g!$#QIwPC<3saC;oBdeA4<@#e-cex#db>|5@|h z4zPEPk%UhTqOZdbAqyH?D%qc0O#Jh;Y)9~)Z;T7)$n$wMw1PdozX^IRmgm#m&l75$ zvcxTYIG>fIe(ksZKI;@D<&)~~9)BN5T{HuGCd>0#(D*<0;E0&dQ#ZWeZjq0 zQ2h<9r4D-(FF|KAkI$+8cKfV=PiuX#?)$dY`YFwikEp8wW1__Ro7_AWSaASua2&+> zBK>D`uXTi!1x?WK$!68_OZlwonF~g0kZ*rT*D+S_Ipv)MwH8UXA=FK)o%x_@tEIUm8DWUW;WNXF3Y&+g;n(LdKVI z*hM#A_4jEJK0gJguw|RPCG(+lek9Jp1FTKVP^}4%pDCXSiY%615h9GASH37@B@>k% zb(uV$spq2L%_mPZ|NL0xe+>+!{iW?HRU{R=2f3ZTPzY5}?AJ~+! z!s%lD)vQQ_&x#Pdtmz}`pBt3#VX;*!B=s-qpC6xdg2EwEzKelI%y*B0i zll)hUvcX{7Ud->+^NGOnL-5;m&+6-?{1&H1GOuKF;ePb6#SLV-)(i{ zS;8j=Nq(Eoe;stPgKfvhVa;Bg-%P^ql2fT{m$SEU{%g)UcX+Bd4foCtR6ResWWU48 zIytP%<`8jxYe)cmy>5ebaFFVHHR7+|tX{%kx>$d;7e|Apo);c9f2QJ_`s?|jtJ&Xq zDU$gR%J-$(i=q1h1@846qPm{uzg*gFVO@ud`L5q488n-QpiUI$TaEZ@``q13z2-8w zdw}~Z+J6?Z+Zn>QPL}95<=ZX)81p>4QPST+^}E>sXV4ft8N-Y`tNE1fcQ`rc1UnZY z<~!+}FYMcGg}2ws>-Q9!$1JI(MOF%EB=@%~T+ z(eE`swO~TSCiozZ>$k!{%K!LvL*Y=pE?Aq%>+{=VDe$MKa(~2MFIm3rZbmVeD05-` z>iD3^P-Hs*>kOCY8wMn>hG)fm-}y8Xe$O^Q-Siw4Uj~HlRgcqHuisw6{FmlYcYx8x z%Ka&GIiG~@_JeX+$m9@V{>yWnKV0r=jq}gz@XsfFpL@8JnRk)K&(vS9>6{3qU;NR! zOg?@-aC!|pHY!E3Uzze9WxEE{7iZ(yfNWX5;}W*AD}Qnzef7WiTblpsaxNKCuFc1{ z9eDnW_J_O9+s)jJmVmn!e?BPRYo576UWt_NN}}KOx1L~eUpGqXSCsEp>dLdv4^BqU zG|o5G@1mqrY}mR@lK8oj)UW@%^o9NFEHL{e*KZ*HTsyRiEov;*?{d>1a0;1$`_6H` z6(m1)fBrYt+3LFF{9Rh#8hU;%40f`@5-<7un4(Et@Te`;?_Cd-_kYGbyc@y!ru}PO zEnC9p=HmVp3zK*VSm%pRoOt|9`%6c^>k8hEO|WD<=a=$5A}a+(j0{1=aCv>#+%yb+ znQ5WTS$_YiKcAtDFU~4AxLfPaRPj&aXBS@u`(0%QPrCExkM3_esWkCupg#QkAm$UocF_QjNH4&VLTH-OeoE<_PoOW)oAPZs~kH(o~** zgC2WXLBl1m_dV|~p#J?*oEtPaGfATFl>fugr3i4`~#_PKQ*fdIt4Gly%qQ0G(LCyodiuX12A2)A46o)-+P``wts6ut{r&RA{QjvKO7-1tf*vG3?~GlX<@vs| zpa^s|6EW?0IM;WQAJfRHa!sR$}RBjEcyKQyQ}qKMac_Ed`f17tNwgxe*4qw5n!F! z83#7t{8p0s^BSvkFiH+ahhq8oyU~{zR*)j*cSHvh*cPpW&&oKzH2$vZpTd@wItcUI znstp~@wvWuvpLUy8IbwSihfz_K(v=Izy0a@EVx!+h#P7-tN79)e2@8F$UKKg^_lXW z?^6O+S5r}2FHLnl?LXKDP4{XG9d{qW=D(Uh4uarJbL_V6t%`4|pLcpUgoV0N{iJ*rsuw|FRxECI=~=CR()?G@ z*R~L~M@>?HqWP~mGYVnWj~FzF<@-%&{ppW>U*&!Y4II>)-#_Y~%f=T%!xu4VI*t3^ zVv^tPv2PS)kLiqV$luSD&zAFw;P8L3n9@I3R$uRojAJc!nhEn`eRi9`bo2h$V1&GX zo-sR>ee5sR*W!cIU`A*^?D~e+k0_s}*4fN{ggAcQ+QS2kwi{w#6z9{N@OkG_5gTq0 zEUZ84m4v_xW&g>eJAG7q()?Jbs#R?7+Gt_^d;Qcb=+ikAN4Mtv-v*?Agz0Qz!}p2# z9Pl;`AkiO>&gb)))IWRP+Qqj0%?9O`3f1?c{7$%*0zV)6AnXiR=`*cwEwVnyT$CD6 zGG3nV_1EXXur*@;{M7COi|Q}d=Y8&e@b&H#ygi!pP4#)$!+Y$^`CTyn5&!;_Z{68G z@TALRT-%QGtswF9lhU`WYW7h{{+se`rLL@x1&%|zpNCZZD)goPd2W{)P&7}>|4q#> z=sCa=N7a@0&+RiB!B?{v;OfQSAC&*c7DaGBIR<0GdQ|J9l>hGi+e3ea8XB(U@dM@m zkzNsK&5ywhbRl%^fxPOsjgQL{&%h~W1bnw(9M)T z|5Tq(-PpxkL$cuDlz-2MG(WcHT?#}j@kWF9k+OX6d3uPYdKAK!7V><@vRhCxWA#7iZ2(^|2gXT1LmK)OS0dX^4<4_AH3`}8Nc+E z=i7DPdp5O;RKIEc`lfG9cpP|5nE&eiCjv%=TVmQQ&M(bx-#OJ7Y-+p^)~7o)Tne!p zW3XtuJipCmcYxi))v(Z*-yb0Jo4OxUL3^eT?(fI*UuuNkQSmy^casK|J9GUuApW{m z#{!659EH1=T373@)L-8$8x3Z+H1VDrpWmYTZPGOvVicZA{pbAB{MVi>2~0P{Oql=f z=w=3g8u!Jy3IERbk?uGA_8^^2*l91RZ_)f$%tcGs`>j8^cZpIx|8#z1D$8Y0JZD2u z8UOofefsokFQ|9g00%ibasG&Yf8Du^nSNC6AQH@9_t_i<4+ff|)1Y3e>uLXIvtG`-O7U6hJ%+CO&Z+F|AzUjWVS^ZT!6SXVMXbLK%H>@k$` zP4i!2I#-zSbur)be1pJepAjm`xqefBo~fLlJiKC;Ld{%762w z)1g4g|B^^~{`H#Vv+-?a!?pB(pD*2i7V>!x4E8d>;t!6h|DXEzr6X3bc{k?^>tEj+ zhr@@7)6gNZyXt!C-+d>pX9w%YNX{1p!v9srd}w?k6vyWC`E6a&zj9Z3E@U$cv3@VQ zp9ux=b8*6OwZs3*kJ0(9aYOeo!}*J0*9e{;0dl@zpyy(k-^dr^;=*M0z2{V52JH*r zfhXr*m+(LOKoH<*X?$Kx^xZl58Vi24LDD};^J{DTLtsraW7K=b`KSKbZ(M~l z)#roJ_`RN63`BRc!7d5%{OhJ`Kw!~xiT+dn-q@@o)NT0(TFmC}XD!0_^*ZSg)YuCn z7s&5Nx^!?LMw?E z{yx|*iubS4`OMi5lUUekQ=vb{=N2$LuQxV(zEs5r<-2!MCVQ4*FRX9bsLg=LD^k9J zU_xM3xm0P}_YXX;(EpmVA(erhm7bv@;~ zQNjimSRvN;Hs1Mg!6q2b{^0&xgYbP=e>*!?FB$s&;rc-RdBoCOSU5cpckXVa;+w|j zDP?=vcD==*TbJ{#VJP+QJp(dew(|Lj@|M^4Mn93&{*f=?o9cV_!eH2JA?ADU-|MV= z;Rg6?!k<6N_aeV=m>X-1&AM~{PWPLBd{V{6JlhFQ;oRR)eUG&DhwYl6yp_eW-f zp<8PWv{d82Kh4kS*T@F#zkcYo-Kg4MNd5iSr~2?Br#+?z@%arJpD$sVp!v)P*QvXx zuBZBreN$Mg-KN6%kic>)_^RID5Px6uM=|SfF822)w<#d^xhZD$=*{^j^|3{RN?D5| z(USd#)ZZ_8m<4MMe6aiD57qoi`%|Ah*umUhBuV&JGpsE!NP}|rLw3Icd^>rKtiCUB z-p{JqNcpcM`W{lS7=}g6#)O}of100LpKydNzL*DR_VM?>2GMu(fKZscTb!SJJn0r| zl)XWie|InmgBah**jSzGJLTW1!E<)ukeL6BL*JR*^a?2Y#@~-LK5txqKBzw*k9wAj z^G)=-ze!y%NxCY@zf=F7do30c+gPLNaNeIr`8HK=0ZVT@gQCYg{-*kErB?uLnke^M zZs+qKlKvR>_MeJBnqNC%x|7X2 zC+2r`j7ejqkL*)#ejMP z>HY*7e=luthpq7!^Eu>cBt)7UDfhQ=KB@nXH+spm9`6+9&&M|Z#Z0{`g!%DX4`V@7 z*Ag?2o>1{g<7>r?dT?&+RXA{(^G*3|RS^TbmHT1p`}6vBreO!k`>~00OL+0*nIyiZ z`dh5j->b^}*o35Z)qF|w=}u~+_hGiY!%U()`Pg+GSERrjX& zzIy(&nB>=9-O7RyHN5e4viyFudST;WOkq2;Hs|wG)PL{yS_QU4qY;`1sy@G%^q&O# zq_MYMO@;kszgt6HwEv9p{tiYwC?McETVUs$4k# zl+T0ZxnNS;2k)AHl;!gl+r>NrlOQdJKVMW|CyvR3pvOK~*zdC{e@5fyA5{lgpk4;d z_>bqeDZkoNv%#gyY}9?s^|g}phi`d#lS~Mqar_2bIMF~G%U5vyr2e>Na2{(L zAlA={{~W=5LO;};94X7^#P`eCY!6RK{fhEwZ0ZH$(uUw9hbh(9OV8hJ8MBsYw4E=k zUlsdC!;2$E*yL*$)%CQ$q(j~owtAX4J}%bJhrW&epFigO()@S3hr3zdx5^o-oB#Zm z)E~FFpAYlu`{K!vud@6;P@Z3Rv$d38>W?i@c|OLa9I&dMU#0r$dT9|{{y+N1mW_D8 zs``ofjQ_L{cHNqY%a`*0PAyWudYJK+HJB^rb7`P*|HizD*y$(FZ`1x0$4P3?>B14A zKlW=94_&j&@J7gS6@OHJ%ilJD0XMHm^q2DcRXH0wBx5R?{d%Rkp8DgnjoZK!J*hvY z{64!D4Z1$YSZi5*6@Rq9b8Y*caDLKXaM;Q3Zvf%kPK)d%x_vOfAyjoe z)!(hHSFo@j9+LVN!0r}?cKkGC?r7SWRaZK}U_ zM-{*`%m3$(d3;+*>Q_S+>|t$NC&JvQfAtF~zcamxVaClc)Cl9}_fY)}uwd++Q96t~ z!uLy2evckhz-eWCYU)xrR<1wv;ML=-+vprv>AXhu_i2&%*2^gx*6$YU@1{qUtmU2c zlKxPtzm^s;(0jNM#{J^{nZ~!vvfs1ViDJIw%;q7md3T~Y3@;QCGd_0_Ogc++4i+V10g)B1I}XRo~oYzq+WKqca%(oNn9~yILC7ajWQ<9&id{()8!1o*-%%3)fe?K*;{vPeTfq4!N64swT z6)b@l4gJvk7U$Q1#J8>1ZD-4xi1oKyts+>JGY9Wpf2luSwCw|X^}QTyGkAW5=ATVmqT%u4iIV;is=p&v z)`Tp@5n=v$=avMxbl(Ig>^P?XzxNa6(`G?q$cnxqtS_x<5f3`{Q}MbM_s^ANzM}S# zb}(VTn9tfR`+$0PHPqDMf1f$g*9%)WLsnQkj(*F}$5D{}k;4!4z;0hd9JBmi{z6(` z3ewDht=6t+eM_FdIG2f_6Wa<)j>_{lV@3)1_7BIgNj}y7T-yIN-am_-+-4%||2*qi z#L64mN#-Yj?Dy=LI2&>^b+Bwsw2CjfU&L^8F;lnpfM)(YzNCDP-oBBIH475vm)@*c z26f-~Ve#VX{4(M1c&&2w=8-~jz8%%i0Tyc@?ru2xc5bBleg;H8n;7nAx{DGZ>OS{3 zx`aQ!&a1(;rgHwJ`g|-p-+VO}Sy}%yu$?T=U%zq5(Cn!h!i!9me$xD~iN|R+Q(ej@ ztq+B~h=KV{#C+zzf5PS#t{2Wf*|^0*uyTHCt1j11%IEVPpV<0~Vm`W)-?7!u-?5NltL%To3%}!uNa8__qDFCCptp!(4UrUw%lsA8f6sKYaT% z2w$H`kmXnH^D6eblayaDkmiR|j26LSZGF6-!uz}Ed}IFgQs!0>DAd zN1pGP#GS0)6@{?BtM1hU%y@1B^!m>EO(OiBpS&8Po(AJVuZ}!_Mb4*fu2#Xq-lxKq zmYiSee-}JUhLBgL_%Sg{mfr)9&#NcnCL#vf$BswmA0E~ECf!ev`1T7kyHXBQ&T;*r`uf!%4noFE!ipU3f9d|Ov^}+8 zZ2cq9vWoLZ`3>)t0H?H#FsZvdzjw|xh5pUN@$I#`iQpG)jQ))COZD}0e@)oa;wdc8 zl;^i;{ZyE;!5oJ)Y%I&~zD@n1R=64tuC9;M{PKhM+u`ic1T1YmQI_AIg(G2yX9L{5 zgU3HwgkM~-4LS^p$KBEV{0t!dTbErXLG7RxnE#shSM4SKx8|~J*lp~9A%Cj-Kgs^> z#-%wdx2@R!{+I0lQMbF|y|~@vURb}~85aY0Rv4n1 zxjf(NwtizT9m-*rJLkKY>?gQzIu=f4j7Q%huFupzzkgO6UOYo#{;E%YBK)#a?l-dM zd{h5?`Mm~IZoMqj=T3piaJtttJT>TzzA8UJ^3UaN9bx8*Dj50y(RJQ&Ie+gTzg38g z>=m;2$6nFil%|=TEkyQ=ib}{zWJE)ek{PA*IzlNb**i0`A~WlEKOW!r$@}^}?)Tq4 z&VAq2`+2`!*Xz2@IYTt_ebZq*Qhp5Kr<{d87ZQE`)U+$U*{k@k|AanMzJE6g!RhYK z++kM>iEmopZXRrmd$r{HY)1G_{+W#Im;T(!R`5;F57SPw#oG#XxQUP8`zYaixzSd* z>w55J9R=TXek0-2Hg>3~vcDc+xQDShBNhF1pO#+uSiK7m?d2=+L(duq$`wDc(=l>fTzM7;eK;Mm8(wTh8b9m8aR2ZOZ!l>rXnHHefCC>WKQ4>hG5A z7g*J~!D#+k^k*o4>(*|@0Iy;E>&W#Q^)>3=E!Lw~IJ}a?{0^;O*XacSdo5-BnGt=b1-kWT-2|0KKkqA zX1M+5IrQ#{{}1)YMeRf3JI0;g(61@+qcWHGZ*#A9#iPD|@uH^q{-OT3-k1%j)y|nW zPS(udpcBSeTDK}+xI^eGo4?Zv7M({_@zu)SR#3otIQ=Fgt6}cC$&rIdT z1Kp(cG@nu#oMA5Wl=n^w%*l z7ulO^_5R3;f`2+cXVu|Bq4r<7UZ^#%bn1zP>Jw zkL1uz7yMHGJ$41-_{r4`2#6k{p8pf) zZ&UrPxy~4u*XZ)uRpO-Q)0yaR(l%SzRM6*otptBmUx$y_37fm)_}if)#P<`)k39o+ zurtLDisy4Cb(sQfyEc5$dhz;&q(8KA(>_)yXN2PX)Ql`ITx#EuhmBe)_#}J}4?oCk z<0mQhf0v{$g0p!K?(SdCH}TIp+m15#_j48dN6prsWs}^L`AzdWh@Lyt{C*Vt(*Dqb zgPc9x8i0Nyg@5)Y{&~O2MSODE#E*G~YUH;~>Lpg7-XCQ=Tg=ZGlKHBI^#hUXV8urb z*r}0U-}uKY`&@+L{gl_{1mVjdWqz-^yk~tk$6|Y5!9SgU&ifOfp8qrFea8uYX}*pc%X&26YgzJt=jS>8!yzE}P?1D7M( z%H}&%M8DJSL^8dt%6zZ+JqJGbJM!?EV!k7s@NH2kp6w1&*6(3|79hm5E4O%OCjEXY zqTi++jxn2}xr+I=*2Vp}|7|M&evR+)d#btUYTn*ZzN`{OD9JNE}7vb!a>Fw)$A zN{dlp$jxJl{{6C_dVlS5D?ZUm@K62w!!=c5WyxjzVXEJ~?ybk$B3thH^Sr4h{;M9Z zhd%qS!PY_WNA>&kk6^6bXTvKjdM&L7=|8nQXZlQ)>?4QP;}(C-Wbzf=n@GMrHnLz3^}2iGJ5SdI3Y$ zZs6W!Gs@pzKL0U8XE283*W`0;h5pif?CJbn=wLmDH{37wPtp4MSnf_%qP|0T&mr;r z_?pSS{#1{gX5dTrHhf{Bczr{{KSms2A1;rO^^fWNM^1td2LJ5De=QUKJ)iJ@*WnOb z@1o5Ai3{^k+pQBfS=nFWkMiFl{y4LHHdnF!*0P#gx3;qW zCk(sD?(zUE{7?A1LZa`6jrYQ1!+4%w=bXm<%YinR*_hpd=oqb;@2YOk*o_qtvioT$ zzn#adhp(qR-}WW-_mBaf*oVQfiu;$6x&&cvKMUUBjnHq9`n$&F3TO~=OmY8GD|J3^ zZ*9rL9%%O8^A_u2RS{(QHr>Azc0L6ArrYv_tD5;8exp8~k5$(1vG+pID8!bVj}ZDD zN%&njx&<7g`w*U zJb-GwCiA+_-bnfyN&3(8FJ`jVMr)DiCi2lZ!mnRsG-_u~<#&3$mH4Ik_TF>Z?4d^> zV&`h+cS*+`F!FKdtMo&JKPU6k?HjyczBbDKe8QO!bYGy%cMZeOEUK2WKX2SR7-yL| z&&(5i`x3s#9@4^vna338Lk`srMsln-uqFeF`8N9;f?3(tJnt))^i@Ut zxoPc&xY|yc?}|$|V$=^?-sp~Iz6(uSA~@qQ%$&vidLZF@%l7r?Q((!9CkejIh(G6l zd&9`^7nTnY|9?8al{!8S=R3^e7q*K15wyOp(bEFM3o7x-UqyZ9P4wAfbQaD8Z{SBK zY36(J?7^t&Q=M1;D*8+A#GmWW%S8Co5bm*G^Ziw8wRf`**~)ycFPn)$BU z;|bp>i=$bE8^f`}>RUDS0W`e!Qh-MZ#i7WXwqQNNo#4aSi=YCiV~zRd{V(Z{us@2Kp*M@IzVgoPmC^E9)`NM>Mn-RWmG;M^^OZlj%Bm6J*-)(+u!c!MJ ze#BbjXVia3y0^j=r^k3$T{GWHtTv#}Vk^EpPw-9a@8I5jP_auH90ElC5=!)YpY3`y zk2dGlSz`Ybt-tM7S>jG`CH^v5@J;>q%U9tTS!F0U%rTPmKa%Kofu}1Lw5r8D>O@G- zcR11S><`&EZ?KVjr}&qzm(PdU_S?hOEgYk+{Z>ry+h++B5hRg1! zQ<=;89yV?f_M~^V%+FU@zbieQhgF-~^4KQbrSf177t#NygPd`kO18ufi}@+)ThVwWsGr~T_O zk2hlUC3*jv=I3iCerI(`W0doAxAoA;H09g6Yv%t&rVh4NQ`Yx+gM;DbX2QR>7W~ut z`*=wWsE>b@={xoBH8wOxpOk#Xe9isXCT#g&%|~w%^)>b9m0q?+dk1Cx_IS4e)8<<8 zlxc$RNTT05WBOr4N*QjA5cL=J=TWmm(0`aY-*Hwm-}zT};zeh79_pc)-&$|n(C(r> zpP8k2tj;`yijuZ+qES*Ml5 zW%)Sex2w@2Of+fFhxJ`7@ki%BP1WZrnLM1R*q?sYc`2eDJMyes{mR$N=Sz})r?7cp z-irR*xcN2Y-QUE&+lcys?yo2rlELn%l=x z=I6)G?LepXPTcTM7mfTbdRf3eObSM|%cB3$jpXOGU#DQ+vlaYA%20`4Iv+aRxtKXX z&M(a5=Y!oky9tRSmHAEn@`Ei(j8UB54j;Y&G1}&Q3k1J3Klk5X5w|ZS%jQq$eA$zt zn$R&+*5|09TQK6c`h38BqQ6D;`JR6h6pd8Y=NpeUW5jSbK}GQ~$lU#wOI5t`6{)34Wi%`*776{!^;MpawLRvB8#8P2H&;Y{Mf=;n2Q$#!XDweE zwW7Sfm+SM_Q~TJTF@qKJv7QFAF=w11XU-yj_a^@PY~47P{%IKOb%g(>eD58-7!Mb< zBp95t3A1UAG zn(xHqKqp=j-%aA1=HnT;4_L~#O-TJD`lBG{gPe7WK)~38iP(PL_SLM@eXT3;SyoVeea8WJd*hHUuP=e?SW*)e66V4 z4$QdkzTQ_r?-`)Sv5hGRJhQ3Ow%hZt3|7C;T&Y?R6;7m7ia&ng4U6hQh$O zCcg~9Kh4)#`R&B-TF$(Op`+lR^uKc^N3u!5gP>b}{xZ$S9fGBCV(X+{^V6tGa!qV*a+O=}BB~J)ci$UPY`Y{D<*8 zwl5<9j_U8R|2^NdKG&%o0ne$o?^) zZt)gu+oi1EMir)X;{F<1A20mrhT1i%^L5LF z|MeyHab&e!IIeQyX5Qudn+boFZtiEMY>;BU9bC%`J^LH*_Fp$hpO5PAl8uMh(LKWy z>*L1nybzLWzz^t;mDWd+`naLqaW=k#vcKN)V+EY2w&zP5_mS5768&A*=o~wKdyb;N zz8eybivJDf-`94K)>Hj8PS0eEU6uK(oe~E7qjtQi$zdtqiX{B?nSPC>rv+elsd&Dq z{vOEPjqvYk{#@;ZzgEfbZ+F{K$PD#EW%tif{jKtD5Bjfk<)g!d{?dFbIPn8}@20H3 zEu6Pw_a){2bcdk7EY3hVAM4V68wQ$L^YMoSpCJ0%8oH=DG+8nKo)UKuL8;?--?K5M z|NDNT`B;rMb=3PGl=Zhx>^4|Ew&oL4h5km8d@Qt}8FWVHA!>*C`%}JChirrQG;7}W zl4ic+GrAx%=^4WMhGtzF^5Dk+11k$j{$Bb~_AC z_wD$nW6dP}1DQ`T&9Q{m4HYliA@uhs(ckqiccXbD7vB16zw-5R{~g=O4Lj}ic)P+a z((@fk_aRup zMfEp#!c+G4%O=_Va&&)I2fvT(NPA^|Etv`v-bX9u*B_m?p?ajH?0#oj|7M-80;5XG z^>4I61Z*xl@ILnC{#YgV$5HD06}4TJ_4VA}FuX9f<%vf`eOyTRJe<=Uj+b*`-bwHY zGd-FA9$#}C4%=Gtb!M+j|M&es^DQrvu2{eOne2WG%4e4AHUu89uwU~^HDxqytjhAmx|jo6?~QuJ~yA*jVB+6@LN7YpM6Pw zop^FMQtDRc6)K2)xrFe!N4>AzZTBF>`OgINnW*`&A)j+LNP2$tiT^$GFo7MoF%)$! zi07a3SKUv2zwhxzyuG*JkM^GyojJ+sADW<;Z=H@>hIzTIcx+r3>HTT_J0^>)$y6+fj3|C127)=r85lJFhB^Jw2*e|MnRjiF==1c&MDP3(rdOP*m%kY@e8*?2o*Ut4esXx86`W+n*T^#z7Z@O_ljzr}n9Zp^pg zUjqc+g+zZh>RUkTco~jo|Kn4Be!;YFyJ0lLk=GCIQ(nKy^|!3waExE3$7d&Qm7Z@p zA9j1gZuENSz+ak)^TFtR$u^G|ru)NQu|IXHu{RDMZ_M9>gh;PnLh`TcFOINTwnK5z zQ#?PE|FcKtVC~Gte9BgF{>OKszd!q(X1V(&DE6OS?=QgOHO+YA*{!7ak0biqel2G` zEaxchpWL{6H>Nip%$F|hD6Rj0`fGWG6)jz%SpSZlcotd#^LXN1U1>elU)_4Q*hFLH z{Og)^BrHqS{V78$jrmT9TtDH$_rwYQeaZZZQ@t(qW!7rd$sVwCt8+&`I7VdwzDvp4_D`B9X0b`<(eLn_8(Quw+DpO z$C+E{iuqQ-tT^moqxiCjJX7J%<@Zw=-Z#X=VPAmX#%_a97NK(fYZ|(Qur2WzBQk zH1j>w%p7;eeM5&zVm^e{*FO7p!=%|@ZdAXwM!t_}4TnX8s{G2)&C>Hn{dMgb=&+o05UZ48wzs5=Icc&nVwkH*T|^Jpy1|L+AsouNyn=$A)=MT$OC5k?+E( zFIlUMjqskYneV@6_G5MhXMVn5gVetQ;TvgRS=FV=`d+m|1PVNr`M$PV8yW4QG5oW5 zf68~2_J>fVmIq&)3Ei45Z{^L`w-;ay; z;7bLy{&W(2)BJ4n`{6KLRE5XA50##O%6I2yQLwu0%ERW0`BcjHkX;Aaq*?Zg=bPNf z@WzKF4f%)X!oO3#>yA3gc%HkWe)lYxfgcfd)$?x-(&wZ5Gly`^p#C#~HH~_ittD?#0VR_I&%P+odDrZ*;!w>E9yOWVbTkqaGeW zF`W3FJA&^*!guF=-`Qp_W&N&QYqxs;kUT%5^Wl@cbnv7sO2#+!?>E~gpypi<{;K|5 zQ&Hc_`5tyxJs)PGtlufS8{&>>I{t)-zYq22?Q?d*vDA`J93b*BGg5zN=e5MpfE?_z z5qujG{m%a{92f4H^9NUiKd1T~Zqf@jy`G}yXU%-yE!hPh_4%V~hKv1|RKIO{n82>x z2P`h%KiiG){XlCse&4j=TiS?xOhx>;QCB;RZu<+3ABp}_FAF)}(|_$j?o@kzrF$=p z`W@{Zg-~Dh_j}sE`>W*r=e4uLQRJ^CW+rJjL#mnGKI z{OfqiUffBtQ_R1fC*-rx^UD?IL#NEw=5Ip}@+4xX)y(JJuQf2W|53&LSCbCzf}yu1-~C7IzltRLFMDJ(!iM(g zvi;Lkp9`#a;_*RqKK>`9?+427{!gvY&rzA*H2a-+n_$jA7YKf-KF25ZM#b(=74z-0 zMG;t8-I^aZ6Z}S!`LMSW&2Z)K2W)ID_D}XB{07#t#;U4c5x9P<^n6q!d^%0oi`u4k z{K`5p|4sF`YL$bqo#DnytX<0amGjxF!y(qu-d=J3OTX4U_@AlIOJA;&-k;8AhkQN8 zR<3u)k0`+ht&da6W}^z~^3Xs>X+1rkWUomY%bPJ?F&}ffx(rK74fw7TEu{6dKh^Kj zC3g4eEJZ$5iTkiaov+C5ha~$aYc(ifj-!{$>SH<|vU0*%G#iB(fSBK@9be;lYjTS9N3`uoRN+z(0fYm0t^aARp1`rH@u zg;YQ5Mn=M9tUd3zT<9m|bNb|im{!@9yN(q8*O&BdjzghfMIlnZ&Dm@U1QE7613kknDPL)wLL|I=u6zQY!=_JK``rC+I$mOQ| zZnD@PMfEfLPZJ!vd`^~MQT?=Q5ssZ72lCp}(>3zj)T=Ez>Es}Px$wUh)X+71?We5AbueRjk)6f$BSB)=wSZ={lAItSK1$rb>4%W z0hYYgdciNPZ#TEH$AX&QFzcttuN;WJ9yk|;kc7cp*IIKv{ZMx_diz)A%dt^6u9!Vm)2>L>W-p{&Y!5FOQT$v~2PLf_K(pe5@cw(y*fbKC3jmAmUm>r+U5+amlj^LJO) z-|j1-(0-LYuiZ#0xUS{VkHvh6uW4P`=iAx0kj;JSFXOw= zOn$z7YRmJ8tLV*3LJUNGOYUbjt6sv~Z*9bOT`}KE`M#MDk9XECyx_6mo9god|G(`1 z#&Fb(`S<-GpTBl$ugTN=9k70B#Cy4(lir`|cYbU;yg!i* z%nB zPeslr8W?wqtx0xM%&%|sUVuIMb@`+(L!|YzKmElfjqNx#3aZQE|3~%xsO=1ts%mhP zBpqoz)%PW;9JaoiGXFvMqR^n-+W@iImKeZJ-i*m;fS-X?|R{L1-X zzxN3nv)5l%AL|o+pSSEId*i!NHXi~qe|_oeAsnjb!Vg{-eAD`P)m{~5xrU=}`Tf;Y zzZ=IKfX`_;-_(B(w5)>84WktM&%-|KNAV47J}PUPsqh!_{OarH+Gy7$Np`*%&8IV8 z?m?AYGuizW^!#3Dk7jV3cusMCGq&zde8@54D<)~?d#6VSm^946{O&@ZyODgWb6_L} z)wAMR%ZsJYA4&FK6wK<6yylN_^rKi$^?hx0B=+^Q;`JRweN6K$tL9c%>GKvJ;sxI& zr2pJ_YAhyA87w>B)0gnw>w^o1ANmdL?P7mpA(=0+TNQ&P)`R$nNX_~6FWWH~R8)~~ zKNKQ8|N3PAv)zh#^e}bekw-P>Ul)2OvTL!n=(11fE1kcdo_LxSk8xAXr@vHKh?d>z z^0n6-rT3@&&Pz{YTKh-hVL^iQbIR|#=~viGtyzluCmR2V#-&DfvizCOPsg6V&3gY? zD!YG%*2k^Z#-dPX5Ko+VLZkm4Gvq1Trspr)KSAfWwzVx~ehW7$&PV?qlZ1L--1)Ed zfhPasgYx+(qyn!;b3n_r9db@@MM5&+G2O_svH9%{aj) z&9ClTc1A#ltFrye&Vv zIc?PEn^hO}HTB;^Kcuis17&^_2Y8`wNi}X4Gf?{dD8F4Fo?{;EN5XBpW_}0TjYZXo zI{Z%7Gl{Q4;=i94U1dLRcq#Ue7fev!z*w|Yrmux$|5Nv``%&qX1-EjJl3t(ok3M{P z#?F=aDb8Ovn05#YYB_SVUPe;=>`VOhD12rS12>}9E#Z%;{{D->cs4!kD^7{8Asyd{1%t z4_8aB;y-)w{Y2~Qh>iy^4O>Jx5r>fwa*4M!wozU{XZ|KoZ%zx4SPXPxGqL2Fi%&Y*x zH}%)C*5fecw+_E>Sj=zG{ZGxdAHnvo&OCOJsINi%^(XbcS^i6G73*tHowLk6))iY? ziRY8%*LgW!IN6{YPpL3K`u*+5{-%4m>Fnl`5wK{incuyBho2~YD)B}8!%@}p zSaTyU#r)cM{49K#TaA~s*&_HS`Stim_gLyqIp0*DTaGz^KAX(>q(=Lt^}eLPls)GK zdvV53rq7|oKl=?ijG=QJxS2_BiSJ0lxADlY%u7qzU$<|SjNr9yJi;zWBj3fA+Hk+S zL$Q87F)9`z)0O#7`K*UGGY%-`+cn1RhtViA+5Sd)|6{_ZdN{Z_QPE#7{j?uzs+;q! z34(9xujl!+K+Z;Gz8kQ;sNTVtXZI2LcO=Qb3txAIdz)M&m(Rzkh<+EAM&bSnORl#` z_-o4d!EXcb>FNV)?k?)La55hfuqhIE#+dR0T{ZJPa-BJxHa|ni6fu9TOZrbUJz_C) zh7Dh;67wO3=JNX=ciwVB_wSz(GFjwjDw3c5F^WTEvK=o|Y3942!9>JuugJ}dgukZw znf}Nm_>6SnEq`m~+w*lYGuF061jP3v_1B*&&BvtPHMzx?6%xPtBtL6pp2{lPxMH!k zX8tp}c_P1NMc#g>$gk-9*OyerMkNf#OkXh{Oa1q~va#s7R*MJjd?@i3PV{@JM?Twk zawZyW6z@;_%c*QOYE`brJ9}=H)`RfxJL&=J(P^n-euj!MaIR*_?VMxE*URhYJEx1- zr}uuc`+`Tx}KJ2QQvKI2_M-&Or|@Ge%F???NN!cx~oaeh1d zM>SOFt<3iTb-otqX~L^@68@at|G2!gJ}M7L#Jo1*`JnZ4sk(par#FB<9uY3-KlSJS zi7gR3Hchd=6%ex@F=ZzF%0fu%_08q;of90pL-pq>3V#24fBAgpgya}>y>H2%)p#SV zr}cAW?SUBg;~wVC70;K-LVmvIv$Xxlt8dD0bkfXs*8*#}o_UGZANNVmKh4KFzd49+ zK{ovS0Kqra@6jFYa3~4Z@>d)^!90yfRZSJWr{5jR{ z_6w5L=M%Z|5f?T0r_I!J89RX`%FdWTWi@!hRyP4BCoH$m24}5q};*0K|T6Fgs^NX3O zsPFT7%*Fjl)%fy8Tc!1e=JNABo5w$7vo9`DtiQ*sNPw=-AnuiaT3R1T^xgl)D>gq= zeaC2f@%z*Hk=AuVy*1b38r)mrSX?;HH zdjt5@ll%8VvnsOuz3-C!SZ-s?Erw~X&zCv0#`)`M7#t_wU*BAQ|N2Vx-s}74&3Qxn z^Af*>MBn$P^}w?Rx#&GZe81EE8)akSp|8#l8*hB4k$(&~#;r^DptnXmeokN7-&b&eo9RK5Sw&^~`rlelYG7T-ep!C*OZIPAua3f_ z-X?sujb{G4eQby!PmU=lW$iswA|lClKq*6*N&jayg|G)qeLVBt;U()>Y#f#XsVh2Y6Vd^wOu`5(^|9s z_kj(n4SbGiANEMk?<>N;hu&f6w72CepKIp-^0yJ#fA7%1hYf+Fq3ADC{ja-tI`kqc^1asu|8#zox6NQ-VZ#*lzhA?NFj1fH z;_WH)Ka%+SicN2@RUtEQzqfdPsJ|cFa1Is}>+-j60wsQ_{$CC(WRp9}^`GW6Z%E_<7-Qkuzb*9ozkjPH{M8;;Y5!)~kQmrsFyULm z1^+5@dH<~Ak49J!ugw3;B~h^5J&->))2#pBKDEWF_i0!?Q~duZ|9{lkVxubqc%M&V zK8Du!F->~o>yE36`afWVTK}fl^X<(w^MBFJ6x;UR#gZJMKX-`!Pplq~=AA8hpK#6j zeCvnS$aH#wk^MyfOP|#D+NxtXcHEKI(Q94apO)A69YaRpaqJI_xi0t*B>F#0eKy72 zVh8^GwC3{@!n;hyiMrbS@FSuB-Xx!oo0EhgNrQNevEuv$%D;ESDRy>(jbc9U*Ks-) zF4W=2+D(x7r}=!ut~6%k>4-2>(chr_w`(y4m7SI(+>}_g#V}f&)l1g?-vGh@09~3{tJo!cdGfD4H*%F zH|FB|gWk^<;dByx>N)d=Rm=6C@Nc`JGQysQ$^1Xn|ML~nkYA+CzvB*lXwBO%%lD}M zuaAtun)Ajo{Wl~0o0c_(=e8rV`Bv)xe<#PIm!AcHo*H2)&DW6pzI{$ROxcizkKHu$ zZ`(EohkF|H*mpwzLHz%q`h8$)b`^DO#Cq!ge;i(g(ui8TzP32uf%fOzgH5q<@Ex=W zjhCL!EW*F8dNyE0u^o?!6!&9N|6f$m4ja|`OaA41{)GQp2alm$nF9|w*GeP*KCj%- z$>Jm0xNec&{}tgscKJ!%vUlc@g9enZm+#;9IyqULU1-Vbf69Lw>z8;J<cFYDY* zT2IeUx?ppGW&65g_b~DIr~L0x>;FfeKlnBFy2LM?k5l>FVwE;bNB8o4Qe`f`|F-w! zX}IxNi@#0xlGZyD{#&nn#%9MYR`mbp&5y!!j{5unXTiT2ssESm{lGqs^h2jVn)&aq zKKpA}fjuud*H&Zwzw*sb7Q7@F&w2>|MDO=W75 zznKINNR@?>A5IuOj*1l@@(bJNXLu8?m19 zAKG{|mKW6GE+Yj0W~6_YXkmsp%i9>6BIeVn{&yIA0`@%|`Gik3Bz`FW%RTHcDY_7b zjfMWx{Uz7pk7L>d2R?DV;Gg#A-5ZX=o~~ao&qDO?==_ZFEpOOoROY?6{i{FZ{J*?A z83)zpuZ@Wo`$uTL|D)+Kd<+}J{~Qzg?@RoDSkp7??iXuC|KD@vWTdoFasRBL62Ebz z{vX;RoyDdM#==Jl($6XXrcqN+Jy*r=*tV2@ZbkIJk<~?JuRdehsZ9L+DgWASJ@J0$ zZ+v$skocwkKR)^m4naj^lYcNQK&6Pv& zpNCja^*{3EX?)w^#E<`u}?K35-ztx0a&>|0=S-C9uU{Ox1b{mweIRYfbcD@7)Ph?c%^!Zxj6clKHu5 zSBIf=#s{c+ZI<|GP5OI@cjw{twaWZNx@P_tESZGo&Hp0oxxciY^1sFM4qjiJ&rfZi zBYl6-^U0eII?KAAQ0719nV48O$w&QZ_zq-o|~>)<5hS}XIvWyB43aIz;_$N&5Ok?a4J^|R3Rgf`dp z5dNR)|D6#pS<}~x6!ZT&JAyICzA6(c`fnI`z9{{QKo6DaI5h@)E% ziGMTV|0B{Wpy7rPS^h`o<11ODpqcv+zU8XWe>%UjX+l*LPf?#?R(^gHo!{9}^ANn+ znke$$CcX}8l|?Gf@AS!AjhnXm{DGmn>Hqkr`M<}zrf7U50gLtj{r>X&f6v&%=oM|s z>lcdtKJEX7_wIzZd8vy2|Fn94WzY#D?r~o;|38lO#p8{W9{ePUjdW3e^=3wqBM``hUGiB)pW;8z{>`Cn%>`~TF1({Nv{ukHE@{ipfgkMJ`n zx#z?eFVx)sYvOj6MVncn(@Ei9X@9?Ym$A4|YG!t<{l={k?_TR^!_H8oc8{q3?7)FSeu^zWOWcd;c|uv2c_L|8Jh)+l=V@ z#`&F5H8&NNSBcM0_5Ee_I5^KUQr|zJneSrW4=+w%#=r9yDc|$#6LCj9AGqbXX1?7$ z%n>v9I?mXM`+HuI`aVIu{~@W89Y1_rGvD#B$I6li*xy$4=ji!t&Tq%!?~~7Pza#v6 z7OCI0St^d7cIJ=94%Aq`-+eh9Zn1KHkCOcE$e%NaNgKi!Ld@r=h=0$jnaaE)EaB5t zGr#HEJYY2V13I2Gk@zhk{2nvm%rs;WYK#^9QvY6WhzDN(e2ie zT(EiYLFwnzzkeGy1EXI4h5pw&5+7M4zdzTqfPGp$1|P17?_bKd<4bSE?AGSdg$tzh zw14-^;5CbIkn1<~?E)({Ym|vUD_NzqZ4HPJL=yXB`?PZ zqpG~Sd4RN@^4(>A7xeK@Rm|_}tUZLxYXf+{0#U!y{Jv~Lf7E@IB|CqS?r(F9OhSba z_5QjN&3vDqXn`);*YUo-X1-4>J%Js6Z1^h&&3yZWx#De)7ieB#zx4c4{a(Ip32rUZ z<-0C_7JonD-$&@Vq2;L;h^Zj*_c+48$?G%(E|Bx@YbvkbH$Rz%rv3jQr9}95I=^$v zCKZqO4dGWF3I5Fp|GB$US;Bb>6izuReSWIn=Y2;bJMcX^>k0m;ez$$YS^vxSSbt9R zKPmrJEGFRFjZz$VR$F>~Gs6GM$yqE{bL?azJ6FvP2}!&v!Kd_Kzex=JfiTvCOX_0r6D z+Rp!QcTy@gY!QE7s^4anmZ8K-m$&qYl=z^0TTC@VhxJ)l=KAmZQ9hs7qS{*6X4c}R zHN^R>Dw5AFtD)Y1-n9T;k1~qrT#m=!D%GVwBu_pi2dniWPeQmeN&QeoakfkN>D^kh!9NM*00PZww9`dxy7!jiuM8{GK~_p4HZ}N0p|U z`PE)D4*KstAZ~FDX?=Ub@6DfCEJx*x=05~~l;1k(UNG482dxi^{+q6a{C+UoW;fV8 zr_t~>5d72rI}2Nd1*fZUiyEO4KXktK>Vr3|{YGVe&&7Xd2BYNuo6gs4oq86}R}JEk z>6SvDNqs%_n+_JdSTFP6bbn04r$GI97yfjh=&#d!JvOX5I?a;%Z^~~6EI^R0JYS>w z%-c0UA62BRzee-5I_uZKhF9ZPez}_dPoL@h{D8C;_>_EDeFm{+eqRq-g^&$Z`0nPK z`E`r$iZ%6>{db3cD{wG%$j2z(5!xeRQKtwiJNA-3pCLIP{otbv_VAt^S{e(! zX?>mCc^o#~e24ay!k^Rgk?U+%-!I?X32V(X^Q|}02T*Bo-&tb+8=bEmIQ9WcP4z_I z^8Y{8=R-r^vF0NeD&}V`3ohei@krh|;dwd#^7;6;PGzjtU}gP%vhg&`pIGywzEw5m zXGXCV5xRRl?1P0qQND}JIaUWabFWg(e6Jo?19|^#$4P6kp8D@v_ZMQ`D`kCt)21QZ zU+q(zpSe824*>_N$@H1>J%4yhOlWWzac+WdmAO1W8`azw6>C=EmH+rl-w)J(r*G(n z7D;Di`8nPHcBFVMT>bR9b99Wfp7zf^ejI?P|1#lkDfp)K^~5I0aK387Cpo+>e}DP; z=gmJ@V)dsyR9kgGdVVS2al?>HfE*mnrIe!j^}R)6DnScaz}Q<}SxOL%#>j;JNy)vtpAfURybwvITc=DYBv#NT*Qf0qP2VbKew zVs=CE{8PS@3g_Z|6BQ5i@|4!=lYDJd*?Tsp(L!0iM*a87@tHU^e<(LwAm;b<&E@=O z-2KTys;`mt&uD($xZxRC7h7}Z<25AyeTlxCZmopR3)jo?bISjZ*XOZmr!#kp7W}JJ z^7;A9X*H2pXFDb=`1kwE^EIZf|MDD^^}VERBLp0g^A9pVJ95}MgkP%3*?5tkQ~skm zv_i?|L&zu=^_wB#KRVtQ6a94gq`R8=KbO!Q7NgH9=I8Bi9ml2aX8ddOfBG!nKa=Y< z5NB&#!lqtApD6#!@{ZwK9aGu;f04wWm%OvWUZ*@PYNDC{YKh0uvXYtXd`8+o_YZQx zlFARUGhNKTQU1Fl8Ch?Q`PY|C%Jo$~Ki9(617{+OP~*dTiLWryKWi9y1|}k75Ys1PjMZN z+Zj)wJGzVX`r#yhGc&o!GM#ME^q0uDDgSLUCSs`Jd+1KBF0H5i^UkT+?2EA@HXIe_ z15o})UYZW`6JK!FBU9p+_Rl9Zd&U-oPnFHjQU3L7EX1+p6?od}S>^gI-#_D6yM!g| zSRkvvX}*4IRW2GG_28oy6qkR0$ocQv=Qo@1Vznaw&Dx*EmJ`-oRj;PRKb@beH>5J2 z3|8j9Z~iiL->JjD$6hk|pTDO5{(gOZe7L+#QU8A=EP>x#W&Lk)xe=VL_9^D;%_ptH zhdVWROfA7b?Vr{D+zR!~58)~V|IUQ}<_W7&d`Opc8CtS4{GHfD%u^|9GPREmxg`pR+w5-$?Y&3W>k} zWH%hPXP%(xp|#TQPyK!4X{i`l!&Y|x3FUv#nW30gr4U1w3I4MP|8D75@%zyz^%c6K zHS*sv=N#*rWsF~&#ov$ezrkTBTHJjI=N9dy&v%sYKdJR4b~Dum`4O7=U#~p@dDDt< zsYexQy#cA;@9-SfhC4vpM>GG%*|l8t+rg z-|d$LV%+N*ymA-8zb`reBIs*tRIe!KzZ>CyNBtA9JZvoMpQ}iJ4aa-pMZp<(H5H$q z@?R@`4gPXnzPZnSiC@b9*NMg$*jt%@qg5&JnQXyhp1qaU)BbsnDYi)XsJn^QE7t6 z-)Vkl)-4@ul^ws8CC-i=-{{OzEL-_UsA6^UP(-?h2$f;GQ4Me+W@*9R6O{*j7%<;;}UA0_^O zz|&8xMc#bH`MC;R)w5Yy?)>vp;r}WBpSr71b%!$lSJmgwMqaVxg@ek{{--}6{=a3e zE*ubyi{<;rsQ-8QxE!rJX!C}FnI`{RPv>X4H>r*Em~D#lGr^ad!0*Fe#r!TYBM9BP z)Z{0|2)-i;-#vG?!H_BODD5Kj-J9_3{i+wb9yuec-zmSPlh5GAeRKYOpUB6}h<^7~ zd(SneGH~8V=nvKJ`LzR3uWMC4p8xBw%j@@jS+i61V!{8fxAMUwrq}Pul`u#vJi`B}p#*`+S`K`Ch6E5+uVOK-wH|2NekX&|ksxrS3 zp|jxI^)rszUy}ISM)bR8yCRkwJ4NQ-Y5qQU%yJaIs=!}m`AF->6Ml8gKC|fMa(=0Q zf0ua$-XGNZ{pG&2p4RVgzNzqX@oKahBK#+<--FJjs?VOY;IJ%~_>Cm|R(M(kfzN_v z=hGFE^CPDYTZPL@wRxPOW_|;o*2aU$+hp_aG@swEzFKFqx1DT0hVFm=m0^JFn|o#X z9j)It{{%`G+wlv(XPS!d5BdJLJA>PzUQrxsTonDSP{Q}Z$?Dm_8S44XWZ~a^iGBx- z?Tu#FQ*d^c`1=`>`S-Nlr=i+v!oRTdi4s`!*TuE11w^@r1i9Zchk?n z>BEEgS0BMY_3!u9`khi-h%pz1f2aL(ueft~_{EA>jS%&_FX_MSA2S@Y(jK6yui#%r z`fo*BuV7hr9{V4x0dyT-`oAjE55&!;qMIPJpcQ7(HYxeKg`^|<~(I>2(ctPTi?tf`M z$6FR<7Tx*Exq7=Pmenmv<8XW`zHizExp4BN&zE{(JvQG6Q9N&lhoV+I-VB;op79 z{7lBFIyg{kn=HSh`Mq66QyA`4<~wZnVzkTtjd?d5CB9Tdzk?6A!``wuyt5Gc9ZvYJ zkkcDQmri5WXp!GL6Mhe;groCe1ODmN5$W}*e%n1ZL&n4mS^aHB_|5B0k}wHk=&mqmU~`E4;~6uj0vK>pWu5`Xzbzke8AW`ogz>CQ; z|4s8ZTSs45w$b9znS$RqqTkC+zcKHZKC=9+&`d}6{w0mGaq#UB?!7KodVlJ_A3JEl z{DrUV{0geymzG?>#9H<|@{ps({@dPWdZ<)87-nrW^P3vzi>97h{8Eb0Z_4k+9d(iV zcB|t2TZ0O7FyrS(?AqB#@MA7Nza})i8GgI(mEB)P^?UT_rFfC^8^>P?zRd{Vo!+;@ zhpKVtQNI6<>bKG66udt&kav5jdA{||hCWztej3-x#P>rW;lIhiGdMoZnCB1Etlv2u z%<+5BdDNIMo?oip&Wq1r=w4&)TA-Q#n(DiEyDrEr`=hu*&UsWkA5Plg|dDuy{VBX=SCBs6B%%UR`ZW7>! zA?tN`{t~hOq>#+NR<5Xx+bPQYSNU=Q$6DI)$Y@J!Sp=ShxmhPqg`? z;X=O)iGDje*Mt4ut%~#Q!|u+;qedk%{+$W`AICMvX)W~`bLHntQ~sNVw8MFySoI#p zBhvqm>i5DaXVHFuF;5sE_NUSQ`n$xw*x2ke9<~trew6V2dX_qSGaASnUgoBvK9KwK zA0g&A@5IqBC|-JhZ=&x_)}_L6vI$>)MC9uGeb5`E9zmCagjvw-=MSn2aqzORK$!0PxyI6oHm8!aY$_gH+L?LIUZdpn8# z2JNpsQs4j3_L_QsjE~6I^@+acyT4^l?Iy$8P3R-7&r80ngew0J#{U-idL+^Jw9+5! zLsK8cd~Nk#KSWm1;gQ`sOZwc6WO>Dv5Pr5+}d{~`W-$+v0< zDh-nL*J*t|dHxz~ov+1Lj}iJ#`MzXaADb3zmHBg8pHF@{7o)x8`aYiUo$q7_@2owF zeE&>ei!1jk@wY?8d^_#04`A)ld3G$KmI(d>iGN?z?gA2Xt@+oYz2*EilKH3C7y3cx z{wW#%zJ&kKdV%=UUzcwQ6Ztyz_j`=ZVHM1g>G`cj`2Y4W6$MV}^ReCv{wV)0{f8pD(hWpr3VjbH{BP)W4waHj_}oK6 z-&N%N*|v|yV)N^V_}(l)dVg=C?_=%PqW{E7e16=&_m|JNZ|XG?{!Q-SQ=YT5p8EUF z%?jYq+?}Ub3Vo;iA4<+(#+{8|-cNjgQhmSTGYaANZezsqmeT9fe7&$o4tt(w4t6I- z`Z?wQZOkP24S0$JmxaEMApAeweouYAwF?eT5cvS*zcB9|V|tSn^SA94R^xn4m8^f> zjqp8x&rg=nP_Ez9zXvW2gz9i*-mUv$iEj}7Zs@B6uhGi-ZI)CWsV9RJ=i}U-`Qhvz zEk5a@W_^Cwv;mTxEG_l+^kp(`U-BMfVo4+N{iPlarf(N;SDrj=QO-zvTJa zw5$%e?G%gfD9!x3HOqv}Y+F7*d7reN=4<(p{qfEF6da0#Kd1cOUTcAys~FN>3qG9* zpQY+-!Zo@I?`JOf^d<8zZ?8KdQ(-6*Q8p)rJ9g&VPZ-%q`j+*&= z9-gQ^vqSif(|P`j^4WFbc>HMa0x#TJi~k=zKmJE2MSZ%d4Muxt=5uA#G}z9|gr2I3 zXm3II{2HI3Hq;)4ZaB|DILQnZgG{H_hEie8gcvibAP-2%~C zDa^le7$EAiKA9iUepMapo4Zanf7W&O8eukP6=qRIvp(<2Z-_s|TP6NC<@>qCLbU5G z<=dR-^NYVNaj40DysFG!Q~x_nm4r<;gW2+KvqU~={Qah0N0<#cip&+ffAast--CnE z!BdCz`5YwLQ@-DM_s7ON7lj$pobNEA&j-wc;qD;JFPp^Q4|IO?tFE?q5PbuUdvX40 z{%!hbhKj06rh7$m{ae>bn0@v-2{9jef4Vv0zjTipod#L4*m%wS?`q+JJt^s!+HG4U zAGIa^$Lge;P%jnEw2mmw0lxjrjR0;(yPcmZI*`Mv2Hp+<&I} zo8jRj)PFNkW}q$FQ~ixPn57;vXSDqN;+}JG{ctY!4CeEh6iVs&l)lXi)TMu>Ncvl; z{~gzB8FsDy4ToLMBA>LsbwGm(b;qK)vV4y&yonSi;r^oCr$l?I&+qD0!-5(r+4JKp zEC_nn6wJ-2pGLmd+tx+8Ql9Sw|FxL9PhP*rMH^%3@vXA`EzY5f5d28$f7AF{|C2DE z{l`Aot>N`4%J-a;ozYqy4J%z<|B593_3}O;@b}hXJIXn~3R3?{Z8ZS3lowI6oZHj< zS)Kj|aC=b`W>I>|`hWfb?O!>2#tvEOH?aRU=a=TsioAvT-!)5?qWe{}r~Y-vMXp$O zCZdwa25p?=yJy7%JM+{xye$bo@1O zXEy^!X{>)W`fyvlw_RT}j^W=Q)$e8|Q!w}7Yq&1xAbvj0pZ%ErK>g&1HGKPM=G(W| zbcCFFkG@y={oXXb&MN+>juLW!A;KK`|NXvHzgNHhp}vzlMUo$<{2tl3OvoSqMCfh@ zkv}EzuSY%nr%p_sE1MtB{FR7L_k{aPcApXLRYad-GpZq1m?0=P-)*Kt5T0cU@q4_5 z$gc^}=SyAm(W0Te|Lxo&1XFCa*{eF-|EBYuSDk7Ewq9PJ?`AE8bk3sPfL9CE0U*jwJc8X@p=M}k27qf`a9MyOt@c1k8L|xUio}d ze!~JMVNJCcIL1`s{-yQn_d`Q)Wu7*RH{|?AlKS=5nG?|C$5X@(;r!C`-w#{WU>UE2 znPDNXew-&_fZhe zPpd%eKhC#5;d@!KKK$N=%KG10g8p^bQiUxHC{myUP0U|zK}>+{IQ;}9}V$T98VeAD?3jn&}@E!JZeJ{98g zsYw1i{rGt7%}GZ|$E70QO46V9vCBHFR_QR)V$FP;#Z825&Qn}H$@!-FuY1>p*%g+q zY+(2ZQJ?92w!NWu)lIGXz^kQZeeU&f0+uaIN5;tJ;`7n`m+jn#>aPkZ-}LS@+zgB2^#d~qRm6yFo=X@5$GZokyug*#;ao6k=9 zP93@mtp@%=`)b_(ruD5cu3DJiN1pHbQS0#Gi#F50r4;jHRKK%)bg{nuD%t$^rAtA` z=wF6AzpSl9|B~>%D8>MLqviRIYquVI{B)S(okY=IN$OjVCp5v*u3KgE-(QQDp?8_I zzU5Ei>vqwm@N(LV)B+ygn%L+{;=|@$Q&6klAl5nESKPlKe7_vk4IVdQuq}qaA1L2@ zY~JEQ$w=09YINoPm+JR%6HBOvo`=zt)8hW3`t7(s5xyyw?D3ylqJ0M8JA9HYnEw?x zec}D3G{07EpNND-mTYt2*UIOY_NVSh8xEsw_wd`8=hrCzzb1@F@ZU!;-@y5fCHmdB z!9ytPIk2r!y#I{yt(`p%FI10kvj0Ny|D*F)vyO%0$6w+7{g2=Ol0o!a_l_rmg#Opw zpLza_o*z9sAs6{?CbKGYr)u=Sm$pk%f7sC*C-(CC6!pJrjP}IEsZTJmgNgWjMI^p% z6PTuMf6Ypw-<0oMuNjEz{TA&%l!|;({k}ZmvwC{zNL2jf{vq|hYd%?piw%CF_dl-R zDx%**!hWl3zwnaiH}%g?*{z1xmEVYLI!s)j^4;jM7F@#oW#el>J#VjowjeLI`Uk}#PLuLENZ@k@%{>^mRz4eUS6TYvR zG)3Uoa7q4*_Mh!Tv9W^J%ky$9|yIp5}l@5HjTXr5Pr-)XKQA2ffqW^Z>C zq{m3+ud0ZCJ1$L!L8%jS%8e53Y5YAR(h}O?=iq&w=hrFUK^3=Q_}r2;?T{$iQ~&&P zxjpuuy#}ieJbz31?(cdVgF6ZJ<>j33NRmH)Gjb%lp1ggRJzP)PH9i(@*V&5n8 z{!^MiZ)YsfJeTvYNA!J|Lw$ChK-69bL>du1o7JLdGl&jyq_T zApHI{8iju^lW^-V_s?nm%*FZ+j3X`B!mFD7^NMAY@I3#KB>$a6^m|5!Py}vQu;&}| z#s5Ep_~(Vu;|2f!Axvt_6Tg2Q!Y?*%fYTdo_T(q`&lNV({MnsN<1xJPLp(_vB-+#a z&ApUD{b5NtPUdlbY5d)B^*y!Px)%n7@%JCqZ}(YK(XID0j7n=Qem*@v5>otFJ>0_z zYe)0=oATSQpEm~7eTs~{&mv#ziGL3Fuj*k}N5Wu^X8+u2rV7^U3h>T6NwlZ;qwWkZ zQn#D$g`gAMp6d5BzqR<+sRVuZPZ8}+2;b)xXd~6aU$+134K`wWa~)=W%T1$xcU)W( zKhLj_<=f5wGMU~qO$AYDNQ++m!S&igeX?#uV z*CSKf;98^I=(d9UzixzY{b3x~_zx&A7Nf6bB{(dGCxWWMG5&!6x+`}tjrd~d-#u5f-q_-*oT6nYFu zlJt*Kej}dTLHwryEPRD#erwP6#Nru`@cS3nUs}I@o3;+koVD1+xB`)1>VKDwACHxR z5Ab4=zeawm|J{HM!u@7buW){;{&w6u9({!~+6mfr8u_jMJs3aq%CYB@W`3J2y|4cI zt|wCc`1eQoZLxDQ!n6hdVrNtF^J)M1u()(}bd04$e`)?~hubV{v3!k!`NbkXw0^y5 zP@ejN@krVD+H%|q9AEJjvFH?+g1W4k5#O!?JO zhafkp43_&jzX}pRzh%8(-$%+Xjh`ni+kq3p{qf!Zgoyi_=Ev&TS!2FK9Ndmn_74$# zc7NxH^WIl+Z5Mz4Q~&wfiF-)1v1Idx@ccIQpWhV?N5|@kxL3^2U(F)*tNTChqUSz& zej7BK0^dcCanXFZKq zoXho<)}MzfLa{)Y@9)u}p6DM_eLWkTtTwsaQ&wM_O__{ws~)0lVq=j{+F$Z7_L=&F z@Eg?b$Nd|sufH43f@8E$zwYu!fvG&!1H1gT&unrdXm*+FQEEqvIilKV2LFAL3&vew&!-hdC zWb{uVGBL;-<)_g7EpyzX7_f3&CnD&KK3!oSqM{*~NyK1 zL`&uyQ+_{Gd4Q_@tXbH?{TlhbZ>2<6<2XFM#QCN9ZDq+e%UC&+D8(7-t8jX zjkEQtBtEA8b=&#(aU{ipJu}hF_blaTJotDU^;YxxH0>{0TI(LN7Y<B-{}0XS3_c_1Td0pJ*qA!n{p6_Sta$RiwUk?|O=QsDhDq{Uv_2KtdKJ1f{vzSmVxaVV zR+E5^Sn0h7p;vi)OZ9iq$h~muT9XAfhX}KCt_U#%*Jl;+uaDJA z!N+Qr%y+Y9epfdY>dQm#;Hd}i-=_S=T)K~}I|JC|H=6m~*31hY_foORg!4=LOI~Sh zL?TnLCs#PXw10b~?qv8TK7h%-0CE4N5q@tbhT`kYQfw^L7WoY$@o{{AFC>0UMeN$a zmG*Td^@oz~8(>oL52~p8qCMr;ZBMG&uv#xPy3X~N`q!sAO+%^RUuP(I{fg$d7JkT5 z*Z$;y6SiD`B9&T__2*~I!B@jqSYDm`*K|Ho?+5wnZMq|5^IN{70?{Y%8-~5%=d%=K zzCzfja`o&}p0fJ=-X|DGoBf6&YP6`|O2T*TI@NGsiJ!#3runa94?@u8@?R+3r)t!1 z=asdEyAPMk=C_v)Oo#dCfy|_$i$?v{(rbwPCi40nQoa}6FV$i8`Bz2#R+0Snp9U>4 zXSuw7&ox|wfLqe~71eLYkWN@`xd#(+H1qH7vj#0ae_+ErXN~-?wCjuL*3q){=`klB z;#ip#Qy$>_Q~$fW{XooJen#Sd)BJX%NhV8gqeiezYhjkqb?MJs!vmNK3=C`{vNx|XR0c`wV&ObfBvA6CNOmCWskGI1_ z{wV)r3^roNnSV%q%JX9i;-C9_d*jyFhsYbr^V_t(mGL?R36KBc`Yo>C{)GR#3U8b& zPetlr2XTFx9~-h`1J2*8K$tV&v`KIr-D z7N;I#mP*O=wHk5071H|$KKwSqB9mZ5-s1N3{y^o=!^m#afVmC7DDqA7-{Z7e;oT&u zzSH=5Ow<~9c9HU3MEvu!LjR|M{T|F2&A%V&pEq5-2AhB6<9a{NH?3dYx!)H9*Bq71 zKc?q1N7a9css8pXB|EZ`FKK;x&qP}s9dQQZlDWP|lK8q;hjloyy$ESZ|DErYp3i)l zHw0;RmoTZo0cIaH^L_uHAKV?EVV2$xkxv?*w;EHZW=n?4`sX)h zt6+Hj6FzHS7VSL=-%axVsauy$lIT0FZ}rd(g-ZPkdA~hGd)goFy{cI9#%EbFoiJx+6eDgVzd|H75k69xO);`%CUDgT8(8=#MJ4My(e z@r}8Sbbd-Z!=u94_y+87E6x0St6Sl24XM6U{$nSt#>1u3_?-IpZW&!L-D!{Hd?w|; z_oaR~)%_?=S@Hjmp6@W$e~J0k2C-{?n)%LgvV-}L(-Qrre4pEw1}{rXiT_UX)6Rp{kqns}#(eELB$75JoqU3xBov#vg?gT~-Xu?W#3&r(fuhY{Hn0 z703;%TA4qS*0)Z#mn)P`#gyM~I;)Z0?UN)vr~PG*{&Yp#9(yG7&uIUNX@Stc8}b1Q zM>+ESP3{kK{nrnLPDdp3ktp9gW^O^Kor0Yj86?`%_NzJ`F3L z4`63DX|8{*d+m&b4Hu!cS~K6Lo2BDMcPo~$jqA69@U5RP9-j;nVbqo9*XaG9DKRRn z4#~!}_ILU7TNA$ZHep|nGQ66^KcDjZ)NmRS52PUDTY$(9<#)#6`AEuti5qOZ_;)4g zAF2Co6LcSz?*>~8u3ofm56^W%wMYPUnT6{G-2bF}CLddei(bE=>fBW16Xbly_rCf# zyke!P9t%xje^{Q+ed$7f%ZzUl zKHZ3aomOCmD+YV8y$^qXnvnc==hOXR{^T&U^ZE19^BIPbVfeR3!GeQ1e+rTxTj*G_R00p7ThbPsO2exg0)^X2$02)R*#(1J>RCGqi$%=tKf`32@%juY+u z3BS(oU#nXd^hd(6%K8Q2)9cD~IL}PRmui~zv()B`Iw5Z`9CbAF8TfiG%)_3*w0pkD zhYslv`St6!de!n_vi|Yl_geV;eWJwwrTqOc4TVvS0u&|j{%p$M&A=Mid1aPt{`%{n z4FaD+eoXDDk-s;(2Cy8uRQ7yT|4v^~IK!P~m?nw-GxdM<2Q^0FinTb_p7T%RU-RcN zNQ*LLdPNsRK56`$-lh%mhi;LrAD>PL1O`dL$_^mFo)0m!*`SfZb_KO`ga72K8$WXG@b^UE~9bzsXNtcae_MB&2Q&3kM8u5}?Z=b))boMi2((tPI$4IIeFo9r zib?O(wjTz-eLUZPRDYwl_~5qsK4yh96h9xtKRz(>t9st5!Lsph?v?=ji%&;N?l+Nd zn%^?~|NWUi+|mCjU!V4GUvyfD!v612_BmFxr}M{_gjT`ZFnRuKj0i>KS>gVXP5k^7 zjelF$s)?4mvt<3_zWE#R`sW`gj%^kBR}%egxYq!EcP^2Qe^(xCgpH*^=z5mx8})yS z7RMsHgCV=zUUPiwval_huH1raPq==%*+}pAiC(@M3ub3Z^q2O3`9A4};?uh^!<*Yv z|M;_>FyHXid;IIk{bM?RXi$I!mi9O-J0Cd2WItL|)L_ z@D^4y+0~r0{`KAw{qeg9ZtpAp|CI0k{lhUjT8N)}@$(r}+|yueS)qneq?9 zd|J+T2I&v$w!{)=N)JKz6@Nd`_;+xYJ)9<-Kz>lHxPNJUJNLpEnzX!fjigtUiD0>4}3m3ti+Z>*Bo`p-=zf;m$nq`6<8adrU>)m^)Bd%@Eh8{b6ZQTkx)C30_5UeWv$g zo9>^9Rh^RI6v_L?E)#x@gx`KlP7zXzD*HQ0etP_)47E$Z0CYLX_ZQV?*9*e^w)>Oe z^NRCJ>(9G)d{f6J*vs;(Gv6P(zokNFVwSl7Y5&Ocv&HJm{_^~4ztYB#^a-;5_q68g z5g+y)^Pdh8Ki`w|Ul$Coh2UE9e9l#dA=9TA%7)K0>aS6c`ndjQv21?oM~ev5XsKYC z24+@VAEfyyttQPd)p9Ma74q+w`rkQQx1!pba{M=ci2C0}@7m(f`%Q38;`w2J!f!;$ zT3oftk>xi?t0$H&-;JCvT%W1`?V274rxPFW1Dg5u?_q`fRfo_#nDa~HXRqr*{CH>( zTe&)_a(_$fPt(ua?38Fv`R=)P7+x*BfcgJ;{z^&u zOJ+4&hhg{gWb4b;efQ`lnFE9~{}$M^=^bw=_SUuw@qR zE>A|_EuNpI{h^<4Zo!xJMaZb&e47xyT~~e(ZXW251&#RrqkK;;7Ut*oOhL456Y>9} z^{3Rb@9Own_OkKyL8|~vsQ(b2(H}MP?ci0aHeBY8rr~@`np8vnKHlX{a@9^yCBHGjblEba_koa<@tpD9=RXEOP6vNZ=vqt`R-Kviz zmWyTU&mEs{gJ(rKUi9JfK~iJmzUtu7 zV_}BGTmJmi|DO0x55vySl6?Wp8WPxAX*y_tvf^danqgJym!{Cwe;aTm{nIluILMwC%L z-o18V&UZSA{L=ck$?U$w|EB%h zRs6Q$PC_YeU*YkCKGEktIa%sj{{3-d1>gTvpC9NQ*fDLUY<~RJg9x0RT879aMjHA4XVd_5Jr*H*G53#Y ze@LsM2$Y^KLv;NfBEKqfKC-F5aQ@=R8dTKc{89gWN1Jv?7`6c|{r=-injf1S9)h3q zvL$@e`qYnuy`gn|m&E_3^M@kLl<=z-g((a8=hOJu?6V^#%#-p-&p%d-IEdt7)tOHB zBO+h){`wEmuIL3org zKQG{C-Nx)?x1W4{5+DD}n~i=alF%-3vuIEK=OF`s;PnVs)^w<5ef?-c(XX-yY53GZV>=_dMrTMLkIomOKYZ=mR zHr2@IrN<3$_v=DgK5woK()#kXi0zoAU53(pK0l1c z&$?&Z^n&oq8k4;J!6&7}MmkouMT;y&0pYZq2j=EsFr7KuJhDc%Mv>tZx& zJyhKPp`?EGGG2*<$&m=nJSFZA%J+__jrhJN593a+673^N{W*G#0~R-m!R@KMzna#c z^U{u>c8gkU(E~o8i2BbanZr@`Ar9e>xjxhQ*=qeR+}osJ!){&^*H>9f=L^l%@x+he z*DzgAvp&bXy$HLMMzZ`Tbe)g*GbyOEahv%6)BN_78iml><-+XhYUUqhGcoCQB9vpe ze@*9if2dxS4YT)RB@>2meYcjz&+Yp8qu1bj=xfdMV>EvDw%7_2n?I-*&;4tV`qf&e zPim+4{bciFYpmv@hg~v`eB<$R2I1dj@K5!nB0Cfx=K4bWN7nCMj3*VTC^F#l3#dMK zIrmRJcl%J;{*j}1_MpdlEvB4ZA@WbpS6=y24I7S+ll8CtvNvGe(Of8DBie(U&#PB=_4=eJ^-(Uby?qh!tMr^MO>> z()ihJ{A`$c-NqeTuJ4iL{MG*I*D*4!Ios^c=X)!tzFP+%Zp%IRdvSd)Ao_mHKSzD^ zSU=hLI8N}7yWYN!kEb}lv4r3Ap1;&Bqow?+$oZ<~RhOdZeJVa5=KLm+^N|y0D=@=K zp5GNas^j$ZakA$p_C{>PA@^Jq6lmr%$EPk9#QDh9pR95-QLV_5MKsdPXIICDNYaDr;%~S4jO1 zNNc?wJ9hr3k5d0S%P|5!eEvxIrT+EJhQe=qeJ8BLIlnZ&y<+NTERGz=OjWZh_rI}3 zzwNzjP%ns}dtC`<|5>Fi7cLfU(q5fa}f#$!A z<1V95v&QUkvtQ!#{~vyf7a-X`Su&sGGO0i7-};3J6BpV1m!ZL293FHRMp1Lb^=bWi z-cen4ckEO)!fm8ReJ)xWfWpN|I9-S9GmW43P56dOFYMVG*AbQPAL;pu4@*9)-N(uE zz53(=Z2WjnlK-OdbMx=N)r&9MN%}h}-)6HHq2;7xWK7Bs^^Kmd$j(xr$3<5xjOY8G z=C=o#>LTyQSc(49__#-NeI!ozk?qg4AMg<^GAvof3C;Y*w>3upKMQ2_^|PaJekn9a zQa`5pT5kUx24n5n`J51uPnv(Wzu6H>Pp?P&avq=VBKq1QEdr~r{+94b`$MW9>W6Uy zcA`^D&L`E^W?Em+Ks}J9#cAd<j-U4E{B~gfEUmS!R=l;{K-j>7EZ4;n~?_iN3}XK7C(Y#nNAm z*{hgZmG)A7P3RJU@E><1e1;Nz9Z|J5n>pB*rI?J>$YTkar+SGoAUe6 zeJ|R6s6d^J5Yhhs%n!P!4~O^DW%ap+Z65wv+p@Ubd_FMspN~B-hJ%an4wE_m*w6L{ zR`?HQ?RV|hsLx5ATjSrTAW43k^8eoHD~$aIvVBGCHS&MBPG|hMyB^h!@c22D@V~=% zJFZv!lJK9QY$(y!D^vT!FL?*@D)akPpI`U-f@+~QZ1phB{P)zcMZWd{RR4NH+<%ve zKF3&xVd028s9JOWmBhd9{oE0&uN}tQZc(Cr0num6HzVQx;1q_9-7Ef`@_i!iEQWTi z$F9HD%=bILDd^w%3SL*y%(uncQgj{W#!^0L=6k~CMJTL(A0g&j#q}xQ*Vk8L{nQg# z&HjBW`I7SebcsKfHcCYBwV9&5its(fQICz72$b}9Q~!H_cUO%5y#dkf`1_02rxce@<4|@T_TT-{l;43P`eV9~QdZ!A|G{ME1_rFN}Yeh#}T(R8`%SN2vNWw1@W|Iw_m500mn)x-pxT;z`mty@5=8KON1-)D^Lvg|}(wzToMNw5R7U znz#C@4*l9k(jTHwO1@r&hyOfWYmkV54fREPeR4m>+K)x*aW1x!{1)Z6uFi7d>{v4P z#bk>7P=4J?tH7g~D~7mn|B(96_DyP{O3oMwpHzR@mtE*^{x43RULt-z&0kOKQ4igQ zOqcEd2!D4RZf#m_HC!e=zn^?tbe`s$_Xs@sl}T2=jRha__XM4iYFTa zF}*J5kMemo{SbQU=`i_q2QFg_V^*qM?Zw09@ce_6psb|k%)Cr#7qWtQ%ISc!b zby=a~eewCJ|J`fjbgZ|&ir)=5zx4jeKIOHUubmI8JGPC;4~>r(3iEvoUS7nG&P&AS z|4jVvua~N^3XAbn9-YU^nsav_93& zK2QDgd>>@>=lh59**Ve=G1)gzQBO~_&rnL|gY;=sqV8f~E9*b&cUy%AK`Dr+mm~6{ zOU_5FUZst3CtPIbgLL;YVlDU0XW@Ekaeb< zm*%&&3-jlH1qZ@^KL7ry|LpYe1f2HNWF9B^d>{~h2V0n9z`hOWFo)aI`jcVCA(#x* zmguj_TIxS%Iawfht(0FS;Wsbo3z8>VvF4LzS^tk;1>v`(m2iJ!o4t5@I9B|9Xns0> zNEn_M<>2kdm7+ZezoQbI@Y6dAH%d8wFNpu_92<)-RdiYB*OmH9__Y`~4hAKsk=~fw zo0I(3+v}1lk%Z3=3k;ai znpw=Q+CZ+4q(8Gu@8vkHe;+-!E*96P^Fit+H(=3+=P}RJ$(8R1slIl3H66+kS8!ll z7tx;j&(^Wu)OqXrNcuY{zvnvpVUpQ(-27KVv{w@U_{^|U_3E<&W%+HjP6h3KDJU4r z^UqXY%LeM;=^_`|`PUbx*20fwQhlX-j=Q%DS>1o3Y$Nx7%}M`8ldbh}dx1Qkn|d9E zt)&k0w>((MmsDRv4>ZBl-ScGQTV`?;PMwAO+wV6N^-)Rmb;7weSW+zzrhmA;QGNZ| z`xNTjsmaQnIG;4XwXUKo2Jc^o<90m0rF>pIb_hK>RFUN~x27c?8cO|RbHeAPCSNdm zsRhFYUu%(1h15T8v2!5w_U*=mlRQ5~`853&j?90bad{oDA1Q34`K_c2&UpDY3SlO^ zKbq>RmGTm7{?=o$y-$hj)BLkuZ4b;fIe}nL&HW+cCmzMNi8^drEGq4#^`kipTv6Bg zFiPev68A6V_p71~>(FZ|D{9H_m!SIkw$U)O9Tbfeg@vc&7Q}Uc;^*33e zhod(pkw*Y^7%ybRM~FS>0L^--Vj+qIn`rvIHPn}0U;I0{9uHcKbtSa znj&xMJlXiQkwG*Jn(8p)zMA=s?JV>+?_P~2;hOn%iTaAZ>nzyin9Y^^OY29U&v(bl zTN_aKD32dJNq*|<$FDGeg)F~%1(sNr5rLm+e0{2~s}B}oaQ(q7ezCu`rug=pjV(&e zcVqT!&HP6BY{k#vpJDE+ncwvjh9EWZAcijB{TXRQUk}!}jQeNmF{AF9`K`EAg;_0j zXKwxZd^#1G-{J7Z6$M8R;lPH4;{K%lTW-|=kB*I4l*w=L|D*cqFlYp-RYar2YOH8K zi}XjoKD-}uHjYji?*RSpJRs z$Fx6VV5h3M;OQ)zUk<1ljlOo;Y@;tu4PE(`KQ;do}X=>3&mSVE`g*`TnQ*r;dM)3iFY*+3`J%ME+?0DK)z- z;yk7NQvW!2n1UI(Iq+uc$J=a0`hrgwb%*=MRDUzC55brE z2hsW^uMbgvZ5>N-yi|xU0(g8&_18Ia2n@;&z$0m$xIdGKf9!iI0pURnSU@vwuONK4 zsyP&k6QbZ$K3}w_{TqFs)nLv?#xX4y-akR>OCwUo;E>O8cm{e^+Dqqy?0;F4sq7~( zpSxUtX?)wq#~WXNpF?w%vuMAI@crCq23jS=V`~uCU&^;m{U7SgcfFyT$>SrcujY0A zV7&bb)_<=mem>>5_2>%qnpHNE`B^mow96w9C*qUgout`6w%<|})(Jxpx0A0=^G`ox zsB90`1V_faK6wq0G1Q^{-^v7XcdEp!?jt*3C1FS8N`2Hk=hmu zRVpMn@cAqLWPVRXN;f=pU5829|NULspOG^93_NoLA8mIdYaV|}@fb=E{VSS6FxW9k3dE9&yxO0ec~V2GO9~L}>G|UA_v^6WK3?oktJb2vQ9e64O~cu7=kcN=_pd`qe5+K|Vg*0O zv(PloC(R%0R+);&BhKN#n<3)*v_GTw)>h2omx{gW=2z+eO5@wA!u@EUx5dLVh4ULp z{O1+dTeI@4)$ICCuFne6KiMU$P`xd$H`sLUpHaT!Kl-71qbs<7S~K5UeE+G-+RO93 zx@{2D*OHNVH&^6?#=qOFtHE^Z5ZV6eq%KuiQlLBYjoHJ0AJRYVmsT5{4vd!g*EIh; zqy9hmggCHY?*>=eOZnd0-3TlHddtqgEz~Z8&*y<`SK34I`9b{aD3cBimu8i3-2Vczhd1_#RLg4b_Ay%=(Gu{PT+%y|A=~)W4?l z15#^gvpLONCH&L;ReqKgd_QazX0-72-AH_FU+)yMEUUA#c_XYf`PU&U2Vqj{T?o

      yPEU=Ytg)Bdas(-G+M;4nr;9ua?^%f!D9^!7kQvlz5E%;i(FRlNceK!@~a?he^H0PV%Ke0V_CUUP_#JQIp#Lo{S{5BYU z8y&+Mvm-yvIR6T%e|>G-PxW$#-dLoqncpcw|JT6KD+vBpP5gYS&$TxzfOa;L^GQ^n zTY3eddfa{4{^#9=)evYqMApA=_0>WpN(^xV}|KmS^qlfdO1EA+B04A z-Lco2_59K#`Xe=z&S7F%!oL?o$KSvbzLeazZ$WGwDALY0AY-nO?>VOvd6rvof7|&4$MjPPrneHdxR709ee z5bf#thO2u7d%=H?i|`liY5pqp(-;H@_gj7On;`!E1<_x>@y2ZG6hD^m$4=yj>Tfff z>Cm|&oR6%}{bQ=XuS`0yar4%&0?+xJKhod4Lztaj*!&VUmUI@^r}O1|UH_$S*rYdx z+wZ^PDTs(h%8M=O&`RrY)K=E>=Z2i`;U=6xnO@_|buj2lu{Z+Z!s|)8Von-mE z&?y8<20TQoRl7uc>OZqFbuqs7XxaObdnV;z)Z!j&UlmjF|EGL*In)rkb>;Qd$F&?s zCfYHN8&AdcY5q#oMb?OIDm8Y5q!QKp*%$TaT|pE{Ol13CUlT%#T6mzY2-IDoOm?!bl1K`{8)? zjQ3|!em#3cAmD74a0YRR_5aqV^KB45#47@#YPB>rCM*Ms_pT}qNK^(LG z4gWviU~QbqiHI-loilom!VR?6ycka-}| zMhSP&PJSoy;X&%Z+1b^F`}Le8@v%x-MbaSBH@q$^EJn%3zvI?^hDC!O?DM16;`32{ zA1I7rK4Xe({QJwL6w_eC5_WU{SV{b28*3BHaP*he*OiG1rZ`~F3jUna$ZuJBdzAfH zfkTbB{!xCzkDrE7PF0p!@4Cn@tsl)9(FY!#)=Tb3HYfagm{n!{*0@OcrTMGtK1wVQ zW+;w#DG*Yxzk^1i5L>HKx-3wi-kjnj6OR_(DTOSeLAEoFx zP&2>RIuFIT`}>3**IA-H<#%i@!^ZE1%+`wMmuY^w=G#$Nn0yFt(ng5(w7;tDx=0L3 z_zm-?1>*C&*+~88$h?^-U2qQ55?n=lf0DmiY2}ODi|4S?x^3m>OXtH6-W&;+#NUXR zz~>Xt__yA%zv`iVr2ML^C0~ysAZ#vT=EWm5PFwtZ+W$P%vc_mK>D92uhK=|_l~msR=p64+U*}AFmJcW|79{C{(cXAq^6IQ<@?WA1>17Qjs>2v z6`!B-y-?_1Ht9S?wtquCxD5NOZJ4ta=bQS^)@@rNv4y{E{QGXbf@K%mG4p@NH1eIl zzXQhGu0Ycq&Q~bW=OJH=Sc|jMnc-7sjeOq->xEaJLh$Aqe?PbpzQ=~>ut^<;$ntHq z$OcPVg=6nFzCH-wD_-lcZzqPZjJ@-$|EJFiQXlp;b3nZ@JCO2|`^Pl?{W2^TbDAnx zd8}r>xAk(z^fCJ-`RS&l|7yg&Xta4&4hK8U`W)=!iU$q$;^?Db@%N?r+;~fE7T9?V zQ$FJJuV{RH?EFxaciAV*5A)^wgWSK`pvg^iY-Y%+M*radKhfu=Ze#H6&|zGdFUc8a2Ysc3#-z&GYMYet>0-GHgk;X0NWk2w>m>6tseeAzUyGeF93idP>ZaBSVFSHNy{0Qw2x!S{!#b|l4 z?kXN%Q+-cNaDi^jZdlr_6@OpKf2>N44Q&kAq;C%@*O%tMPmXg#*OPlON{jQKLHfIn z?(l$}j?e?Ukn49CiLWnB*JqvDjc4{>`)Q1??LPRTMphh5zG;rH&v*61*{hxS z{Ivfg%A!P_n$rtQo^$`2@)?#hAHA={!^y0wXixK7divTzZp>P?{`4du1a%JIhtHQh zaewb3e8%po0k>+7$Xm?$p#HUeSRiuR-aZe*Qfq>?zC12(48Y&e{!z<5C004%s6DL z$fuI<={U6$tkRZa##GKH)#o&aD>%2R7JK2Zna?XJ{m^#qI`pZWFG%@(^j3=*th1Bl zb6SWkhGvJsxG`UU7vXbq{f2Cb?o`&eJMZ71@pIV=M{G;jj>qq~K2ttVk4eD47qwaa ziVY$kG=9#qcZFli-Do;zr}+EqBJuOBHHOT;*<_a6MKhnn%Uy)K&355f)Edz~mgK+8 zE*Y@=N8?$^XYzDnoc{<}OHFDFD|xwm`e z`qKLGxL&v6cF2&8>ca1LqxIwN>9cX!`7EMma{rt5hct9d!lQB{R^?;UO8%wwsf#!L zv1sFYWQOtlHtnCDvLy<$j}~I$b{=0x5`AtKR;qT}(+fF8n)#2fwGh4R<59CQ=RcC@ zbCVC+D9Nyr)o1IKAy{N}4;RLK5&1DD@%6)inlO9sAgNDL{_EEWLeRpSI5&XvpF#X{ z7u$Lmc5{TRJ~y^0Ll-|w=9b)7{Cz0@0m+T=EMc;2e*0FOaJPqpHS@3jKzx4cpLcHA z8nH9|B>GI}Z{>Syv8B@nGPlhC`ah-p)lFA+#{1aiviWVJtyS1gb33*!agCMeACvsH zb3}hQ*OJ%gq5=Of^PIJWe_Ef~Gr<r~wa6v!!oha|i>rY99fA4HVR<7^K zK0nA5?WsPO-xvzDsn9>_!}Zyp@PDA8A^ZD$BD?UF-=C@^{MQL|$CG7y&^=;?`2Sxf z`h2UJ0n_U`mVFL2spL<}|72GWtcf{@!Z0_{p617ASGkSBGwL(Pt$ckI>AyAzo&{6g zGuXA=NwlZ_`HPe!cn&dQhjw%Rl_Wo|tTPV^#RYV2&`GqX{5$Keg_-I$UguR<|L^+; z;oqirncB9ZC-z5Z=Kq<{8#Qs^IkdO_C+>f$|7XVNz-Eq>q(56p=7V&1TZcDy?xX3l ze9^uq;oq@JEo@iG^Ph1k2z}jeV&z57KaJ0uCD+4wp+`?{ekKlc-TxnYhFY;!zq$TX{{4@)hJVs*464KXJ81qqx1WN&oo~(hdT!FF z|Js+k;BcvMKYIl4FQNMXL3;q2ZV1JgPuxGE`o5&>BHDGRF5z3DkoKSCH?qUd8C!5D znDb5by-m(#L{6x|obHYi_lJUK;6 z!GfhbVC@wle*gZ2?`_77m}%XqEPwVVaed178zDcIn6wi*--1N@%Y^UGn`3cHrvx#_ zcz%uchwZC99QK#?z%*l~Xixp`M$>NLhqD1&cqd<6pY~_7v@y_nauDAmHS7D{bp|Xj zY78qd)a;+TIQimljZ@gzWw5wD&7V(jx`)oJ0Sofh%=htm!u<~gap>QU=ig}m$%O4| z(W$kRZ+idgL7NJ7gVnvTj9ujGll)u3@Oe1W=p14VIp0d6?_T$GkX6M>QXivyU#cC7 zr`PUcesA7i=0Nz~6j}=*?d17R3kt>|U*UdS|4{M$5JvQU>5Te#@Nc-RzUNq$!|L|{ zrZ)Yo}x}wKMA^*2M zP~5*6g#TBWYcGt}i5Kl@d_Vcc zT(r1%2Id7t;{K=kH;?XBkuuT}Cv16ro$`OQ_9l#b@c`bL#iBi(|K-s^54{rx%lh|@ zlWMTX2~O<$Vjlm|`uL=thPZ!YxNQH*LgNw~8QGT|3hO5Re^lQe2RDUwXW@>MeViZ4 ze@k~${CXhV(UZ&LU&?p4)mqG>+=^Xx*rJhd6H7CcHC>L|r}+DU_K)sODn`}Dec7Vz z{QL&Zubuj0fh4<7Nq$X9^6UQ^)nrk^{OAArOR4`}9fQ#F?PiI-t4RFbpt~+JD0N`N z=FhYK-}^;nEj@oVY>Eqt!Xjkj_dzEc3wOhLv$EOeMSCUD_sKCsp*L^`K7HZ(9!B)N z`He($Q|YtgMyEx41*xBHKQI(a2gvh1wB-pLW+hlSOEce_-wN~pviG3QV_rX_{`qzJEXTga6u7Fk0&< z?myb!!Vb1$+PRBZ!P1!;`F<$e4->6EjezN`MSGf`>-_Zy`Yiha*DpMNSJ+7V)3RnN z@UT-a^cbv}?^WyPVQcL;oV-;c@=5*omS?LXS|QJOm7^PQbf++Xq*kG5pF#3>+u!TK z^Y~!N`79d08;2X>ywPx3|J;0M8DiS>V_o<45dVM5?^L~JIDC2%cBnM->yfF&QkPgU zos+yj+}uWbzH;_nQ{2j#iMvxY^L?a^HhVTk$zH7F=R;_I?r@wrHoaJm%s1S>_aybR zpQjWo=Zpn=WX9(QQT?vJ$`WSZL-4i>e}B^YnK!#ByxXMn3ut}(Pc?h2wB3wrxhKW% zhw68&PBoay$&q=1^G)k#RySRctB63MC)aN}KPYy99ZOsp#)jQXwf^7xK|%OF;o^pn zk3xKZi}OwA;}`ffXWQQTu#>NIMSCUTds<639J{q08(g@4)AvqoFUw^=W_0mgi$IxmcLrVCo`%f3!Yc%eV{cbZ8|@ zDgAGLu2jD}yqSYC_fv?t#`#Vo`aRpUBO9Px%Ich+rIGJjZ{}is>S>HHFcsIQ`aP`M zTJ+OqFzixR`Ta@x?&zz98?$<$SGP-|J=O1KivLH~Sw~gTbz%J4SO{3CfJg|6frXS3 ziee!KqN0c`CMqTd(j_5^AgG81hzNG#v+eHJ4(#skZ`OL}+;{f3?p^%JI(KI7J->N& zpBZ@cZVQ^F|J2BLsbNLb>*tK24+TG5zfFo_;D6@`er*uvQ}tx_yJzp}F#FO)t9}=s zd5QWFHnhZC_*W`cf9l$_Hg3oF)tWzlIz1Nk{~X1MxZ|?Ea{h0vGDef~!w}{v?w{-T zjSDIoy3&b8RXQO*zl!nyala)VNHdgos{1#*nf)IAyc|iU6V0~MJU{H}pjL1+o(KPY z!M``-fBu}Zw6aD=vP#!%zfZr=0sUQ~74r``|AY5dqhe`3=70Lm`M>h33;vc(gr!Q@ z?_A%}vK|dc97e0&&R6drrM@?-)ElSYrQ-TY!9S1B-|T!8YwFjaN4*xy>pA~X+1^-Z zvJ6dY3I2I}{?Dw2WOivBjcW2jeSM|<-Yd-;4eBm~;rT`K{`F?|`-07NX>0$Xw6m3n zkMsJ}VS{~ebVWKg#Ep~J^Zt>dltEa(GgF%1)kFS2kH6h((TXa~SwyqD4$!FI8$Sf$ z!N&px-=&Q2V-2Umy7p!aUeQSYe9rHI8D(&@e_I^2)U3Y+PiDYBMB=lPWNm!hO5-tEoqy*14INsJ>RNXs)d-Ql=K4Es zVQaj%orjlhf`6{R7pj(}X%5bG?n!LNfAuSy#mD!3>?obz5Uq%xasD=xbb-U01cYa7 zl7C;$mrb?$G{ps9u{T0Og+nZzR)8YmG zuXXOLpI;fj`XtS^*;`zIFE(cK@0ZK?RY~#RXKfB*cBbH$=ch8) z%)+gu62BS3f93U|J%3k1nI%p*I#T#ooZpK}A`!iPKiVcOUtd2fOXHe4Dg0L+pL&?t5d*y= z@v!@U@hxTl^O7m$sOM`ZrTxnCPk}={ae0_hUwQtixKRU&bnw?|zaBl%8`F2DU|edB zynnd;+GC3+1=LEW0kZ_Zp-f*VWc5d$^D?Bb5d8A|Q;Qr68vJ7ddAPn-?_VXqO>Xzc z>G8{u6Ds&kXZl*$1*mmZhu*(Ap(6bWuYcAvW@v0W|d-7b`eM0cd z>${svvCB;>R$^zEh)5{a1WGf#aS@a0}ds zEs>Yx`&X%y{D$iVql!wYzsZc>4OgPz7gd71zJgy~Uy?m?HnQs!qNtwWm+Nmzst(rn zbW+rhaei++jzy(&gl`d=>$?x$sDaOiJrwgZIlrTC$D{t5BWQaqLFOxz`KKm3>taOB zK3elj2YQ>L-t?hb^|fLf6;-pcqenIe#OJ#x^>u2FHBL+nL}5R{54V4RcP~%(syI_= zBXPb2uiq@X(H1>aA&T=QTp7QwN-NOYz8z_vO3bh4@u&7uZQl0t5!iZJ=z9>;*Om8m z>0=k|@#Po!p14Kv$oeJpH<#&e-3u)!#C{Gvu!)rS53diY?a~LQr5RqWN3T67$Ddh$ zmH&j6^tkR^qKPGfAI5KgCqEoD%E0|MVm>w3-vQ^WDARljS?+o(_AiS+)#&Yu9^KQ> zz*N+SaQj&AL_>PKd?Z=?Q(di}N`8-(8Hn4b(%}6|=r4~ik8N*EwVw{7ULVB#OwO<2 zfZ@*XQCpIlUb z|4M$(1O($%n@uR#XexjIJie^=BMFTbpTeX;<s8 z{-cwk{)_YLES=wyJ^lz(C&m0ATNXdg@zTR98}0fVm7j=+F~<>SxK!rLl;ww8wlT!1 zU~jGQCDXzWh-_^`{%$7n^Sd(pd9O|**wq=T)qgF0{tB&YT2c8*%QW)6;*~WT_>V)$ zw*UB2p0B#JQ+c{@!I4f>jL?`rG9T3r&0EdY>fbhsyN`nRCN$k}ZAY0Oc79CBTNlj8 ziBQujln&*)?0yy$5q?Oof9k|K7hV<2%E4C@LgmV0%q5|BLh8?7kVrr;VWo z?KQ`jeg*g-@k^>AzU<2M`H!j*m3=mnf^CI;oz47Tlej_n^)^kR&!J482QM_HRge5B zAV)Lb)wczpr*0N7qPP6~-V3^=r#p=ICj1IxG%7tj={!8B9 zT%SK4tc)=$9To8@&Ue=)i&4F-l5cOu_q#)S$WHC7HGaHf{bF3*dIVQ)C(73c zL%`TutA89+@e{_?w4o1$n)#kz)Ch~RhiK({SCWc6hqqOn-{#8tFH{4YU~cGGm~_+3 zckR*A`7O>C6nbEav)JFt`p%JU?6CdF9EJVO<5#+C9^l$86Eac>zPbI~a=0s|8b>J3 zZ_H+VpWUlRrGvEV_m~l$usj=!zcIP;{^EQe>{pFe8hTI*GtGSWN$iWK6;sgnsb>4T z$+ffS{jmnsnv*E=tx_rHb4Dy4f=8z5a2zA_JBHbA5q2z15kKbfEzftxRNq9Z4-FQ4^ZGC6t;6AZ zA`?GC1>f9%t}>_?;S;`M|HCix^Yi%!Gt7fg`#~;FEcKAT{}|>!`})j;)6{&7NfP{W z|2Wfj2`X5fhF3Y!pT+At3WDZg@WIU}m?-!)W%}ISqKY)%*HNo~oc=ZzLwb~;ZG#&! ze?^SnRUP&5%&@cKd?#*SUpt$O)qjp-gV%EP`@=xd;CU>%9(JGUt<}E1J^MR)Ja0}z z=860m&;RIonW1wl?fh1K)dc-Mj={_pn)$4^;W>;4NyVC%$8h5mB?IBRA@8u;0tE`1m0BXj*NDw&DHd-9N6 z$y2^QuiyA^aVCZw&qIFLKQ90N{7Kh5Ala=@YyI@rk5#1k zQjS{f=c>(PVN!WNE_@gBb&?sMV=wE&aZ4wyd^%T7!aDaO_)?rC^O?=`HMm@TRBhf{ ztNrX#{1v;F*iglL;{C+!=M*wS$7z0A^RxS+D%0Jg9m)Cgb@}>W`s$I{6nADS`Q`Cv z{XQ?SucaBe_RW_0RjHKx#@A_&pr5l8^K*IqRiojLU{t|`JgaHe*Iu_>;d3JlD;pQe zzdw&ZpM6)2vXeV0>}SsJTxmZ1yyLM*TBw=dV=>j~<><~dxP{=C`^P?md{D(P1;6b? zewNo)b}l@R>;*N*H%9Qw?PuRlL*SR3CcOhQq~1teCoAKkv}@Y?B}>;4XMSxp>zqF`Q5p0 z6!Jf3D(WkF{`Tu~BPxy=MD~f!8vWy{_h+Jja*=>8^7C{1x$KHyL|Jb{^DUR<=jZ*+ zCo9YWx#uhLOWZ$R<`;`8-S^{GWf9-v`Wqgw07s?x+JE}X{o~F-RWYZ?K`Y+_jp8t= z*M4Me5%YO?erfUm17!8l&i5Vtco?rcfW5sI$$atth;Bvo5%b+ktN!LSmTGURG$%7F zp}(AO_ZV}8^zqYbKj%l3qgbDIr2ARKuX+7+zYrU|4;+Kq8A6{q-@hlm#5O%M3jLv3 zpZmJC$HD6}(W6wv&p6*Fnms|*7!#^JS+hR>I_`>224NUwD(WZr`HdA#Pa@Y;yFQ=J z?*ZdYv0DA(Gk(=6N52!DJTOhom$Lq%XUqU}c1_Wmf7;aTB7R(|L5b%y^ZjwwV1)cl zh0oM9d4K0J`&sXl88!SFK#ti@)z??XuXooPgr$|F{MW`X^?K!e5+8jly7_So?U<-1 z^TqjIGsO=+1=5VsNu%ZU|5tzImx+vkD;QArxO{!C&(qG0!g#w(MD+KT*YofZY1)& z1YbccfBb&r7bK-yQ>Yd8$@VkT?*K1*^eC8#{vO5h_s8SgNgZ`)bde+NvK94J{QTta z>29z(zDO(IRoqTt>|gEkdB4r*3De%O7+E0no7aDoU#v?{CU>HGMnb=N{YS(wU!1*{ zj0dZQeslZ#_%CZ(Q)e7?PuwN%PZhJji!Tqso{dX!`0H}{`JXYqz0>?qd^#0f+C|9! z=l1oGfmXEh{AkKG7yR=0){PHC(D%Sn#LW`%YtFB!UKXrAUdD&Yf?w|c-f|v`(f2a( ztf;SieQsZ`^_hpI3-cB8b*nKxZM%eE)Zsi>KNS1#1j`>atRISirV?MTMST?K>r0L5 zh*;%-zmGKYm5~#VI@0-3uUxOm`;+Tu)PkC@nCGt5KHf4u0T0X%V0?MO7oSgG^+f~p ztE*iyP)JYfRPl zjHE{+YiQIzuj4}z5~SpZ`=@(mNwfPpUB;t_$JEcStiM>(C=k(|vhd5dzkGdOAC(m# z&5ob-9&1B|{+Y7*Tuz zM|1qQcKbzmE7e!!9{eNk&tw)qYQ3{M940!To#lW1gGzmyKOi1e68EB~$rX+Kh1=A^ zWe<0)`gVEgV$@u706JA7)O;x8N0Yl5q3dXAMxy%sVXki$*K1P^%O3RLw3tuI>o0PO zEYSG*K(rkv^o8@8I#`zm-FKx&^+f$Mw_no?n&ZmoQLy?h{6o&?%)ixX{wP=4{Rnb? zN5$rQqy{*`cFjyheuvwyy;oPKy`?VHc~6)|J}3Wn!^7xMT;97${(be_mGu{cqpMKJ zT4ntO&+n`Y?TJhKqEYzIMtMEgw^n}owDM19`e3V>-`sh=h;~m>#D95yr{h{1@-7=l zhT}E!+tYOjY@?Pa>Myu|`g=!;p+8G(Zhmn+VP;PKx>k&UVJ z?{GSBPWY!hzBD5^2?JUKyA1#94_5MdDq|9c1g^p%)4}rhQ=ZM&npE?OQ58ANN0-+APGSY55p8%|c!u#Pl)p?jp`@${Ss#PzC1Pit1B&y(`FyOU$7>uyQSBpkb_;w__>HL z@cQ8f`o<_|&`WE6Wjh)a)Psv{>tDhKpyBe)u+JOd7(L7(nzE&s9pA?Gb^$Xlo1URodt4j7#YSyOd~!e)9gEdp!*3(~r)SKT0!y0}BSi%QOicoYu%! zalfV9_UExwrMa3vW?v>R48T9rmtvWb`2EVW`FEj%Eotm4seUq6_>a84xZT*1C_6a~ zkGsXn*XQ}wnq_Qg^U5(4(NbTdeqLN7&5x{B#FIJUxR|*a zdd6kd*Vj|nhrZH$_9p}F@%V^le(%*t#Dcf`6#gTR|6Xvd4etSNTJx)e3=GI1x)YsR zE8+*7-{otKacE0Vt^CFpK0~MO4ajtrW`3_GS>pIOUwl6(_~iQf^2QfDDYc*~(IP*@ z^|gz8ODu{Rg$fR0J+F_lp70KFQKnRyvrNQ)nZB+W?}S6Yf))KaTwm>^{AOi1QJo`^ z8uhhi+0H2O3Ptg7!FMjRf6sc>qz*R9`F1@1+f=emp65m(_VWh$_vL(lJZV6Q3p-Ps zpWvIvf2{^c=lhONQpA6=8Q)3&G^bDX0;TzKn)#mGVmOvmTZ;J4>GJh2F#Gt_ji%(G zH<~(`zH<4OFV6SK!cn+0J`J8b1>d|sXP&z`wL3MKYQC(h-rvglsLuz-q1Yw^g)TGX z>+|!$t8Pd_+u9`Kz3mc|#u4&sT~Xh^vOmw=dl8}v z^O4(GyGDtA4H>lZ-mQ55TjI=)d9q<+#_i z5oF?~wSIVVk^z;e)`>nPsQFVV?OQJk6TGqMsWt!7?&2%dvN0yd9aZG}=keKchK*6~ z-T=H^EBN93dEfbsnrp4;>ZcspzIJ8#m)23XIP-KAURw+O<@W8gp`TFB#f((etu*o% z_1Ouj-GgyMef}8dum1h&wC12QMTThB*R;kS@aZ3l-R}f{ygqT}Km)3J$X$_t;r(%$ zL%gsnDhem;HQTrGrZvg^d?zw+6#Vh{&G=)3v8pr?b=y#IrB_p*$I7p$Mkh98q+5`f7<%YO3klQUstu90nhc>&^ng4lgtRCLP*`q?^o$}}N_$nqRW5=!ih^Q;-gI!sEbXiUv#NKn&S|9v=WesZk ztOM<-mLh*X*T*3h8p63wPp$JO)~3C|{o%$`hpLM8D&_epmm?d)%VYp9^%i{UvG~x) zO7Adfpa~u85UuuqmGRZ`daW?jZWOXUiuGI{Q|v$D>|9fFO$?LybnA2sHFh zMTG}KA9?(!)9+?v(Q-6heI)cz#p;J=)*g+%50|3hR1rVoeEMxQr^<&0lI=LbC(obU z4w{T77Mb{FGEct$05<5$oA}xo*2dasK*77@p}aua98yqxb6;!J~E_-sK4Y^8)ifv-d?{nRJG<{yD*~ zN~PpC$~_Xho)tj%xZs!jr!^buBWHH4H1*lLu>!eHkVhZ_M$!wI8;eq&+{XDO{|c!$ww={ z`TKuhQM?7|MvM9JTwi}}Z3WByBNhCbvi!)z5ucI&%al|H`fB9YZ;#ZwKWduR`EV^) z=~BzNPE_@|W__)2!~-h>mHdM7TXDQMZhJ;4;zPW?|IvFLn)tR2wd*iR-d}va#FpBF zv1n%ksKpxj`wL?B>x@MXl(!(5D!tQO-|sMQBwBx2f**SYpJ4W@d)94SkIVF>&F{e0PU#fChbAR~@Dfe`4*J`BCjgZ$HGCmhvS&T)! zcBB7hVSl@_`RppsMaWqtosaZmy1ZV+`1I4Yp*x<#>D@ie{^`K(3vqGkdYqcvMP9GR z_?)$WA6$Gszwq-_sQIaWuRpp7`(Megn`IQ9O8xIW zqsqzGPiOj@Kg<9LrS=$fe3$%xuD_X<%iw$j_%!d8&@aaCtQ~c+@Rf_!{`4vvR$zh7 z2|RES_Nj{5$D1pdBIs#%t^VoqxpispXAkOIMc602e(-0I6)JD`UJ z&#O<#N9N1-&-o4i-3pI$MkxAsRE*!Q4RmSOQU}_-K3ijbf1kt-h<-j*F&`?K#h>cl z?1DYE3sA1Luzz{}C3|iy8uQmpVgGXfv-b>dOb&`f!+XO2gQA1 zx6A*|!-AVRNM0T&ujl6rJ}s95hu-^e>fQzQdZmA9z9aI=gXo2l~}q=p(mp`{tTrTXJ`;^+Ec(eEdK)ybY z-#*Z>MzO1QzV;9P3*RJ5Iv2c3ydRkV*?DCf1kMi1hP&(D&lm^6wwY`ezn=8j85+#V}td{7)X=?J~`TR9|~h zvk{xs`$uWtHcuLbm3LC$SykvKkNC)9L*}Adi)=Vn9VPEC zUSIICwbWnIeh18MoKZi&l285Skti$0e?GPCC$H!Emw?J)$VuFQ6T`2n*DL$uwmXI+ zwP7wwUJ8C~S$ydJr6}y)y-8u;^7F+GA2Y<8uN@WfAI{&^A&s!crn^@Ab4>fcQg5UM z#Vr?nar<-FHfsb)^AG>iFCO0sF>QsS{r(tOPvq};{O0$QA2_@? z*AezjgB0iE^883ZYduP>>`05Ni})$;FZ~+W6+JG5z~ooH{QYzL^1%y3YCT>VKjrz! zv0MA1f9FWt%+<`#hM9F}shvAj4b|))F0>qqLA4XGQi?MD`+VNa{(SS;g!0<=qII1# z^OLc4G<@??aKl6J!|QL(k9&a375bE@o`1;mlbc_U#a-i6DLxV{U!U8bCq6W#uJ4A> zc~6m_)3^^wF$!7NFuYyqcZCi^K{*%<}mFEx4 z``wC~n2w?DW4ej>5AzQTQzEeCcrM15^Oo0Vv;0UPBCw%+p5puvd&Y<7j!2kv&WHEh zH!lBv|Jkg5F6%-JmIiEwPQ8lq=kxxu)*oUq@Oq(CeV0usS(B&bknMD`OV*>ximw>JD{>y&*C?hZcQ+!kCH!bKc=kvfWScw zXy&GHS>H_A{4xEMR#;cxA3BeOeaHFCkNtt7*;4%GWCK~>c>O?16&DnyO~JN@!hYrR zgWr_u(askRwEcqc|2Us-|4OqN?Ly%BNbvcM`G3E*)*;*3N`2#ec6RB9Ax|R|@f%)0 zP*kZd)qCPb&0;n48DlpTnf~!OTVC+V?MsI{4Qc(5UUV)>GoNF1$6`LEDB?F<-&6}9 zfou%ukIr^^|8YL6G!8@=iO)BVLZA5j@az>fG%ofPRsQOQ=gA*$o#`|X32;s-3i_FbMpPGR7!p8X&a5i;YA zlU+B}!@fTq6!}H2ZwJ>`ro@PrwDMD!yq^1SvCYho`_)rx{f@mw1sbxw33)$nEY`FB z?4#S7ph96^ERGlZpY!K%_Z#A8n@~ZpsISXr_GR1Awn*~!!`g0Q|8xH4CDtGti}rM4 z&^d)S_pDF3Hy@g7w^8WL){8o75*Kc z-#_G9KjcS7pjB_7kDR~CQ|i)@UT#!6UGT^Ai^J*-#q0%fs8%^!{(d=sKbDx%62o59 zJWDfwH4Vq1VOol!e&9Ou|1P_Cq+X+^(>jCiF8{v&Ie*oDO~h`g{xr0@@c#_mmG$R) zGp$KyrZ3%XB<7Rx{KlT8A!uMNoo~HALcV`n7N5x)0ZcUb1S?m~{Po|t2m{-%#oTK` zA4^$(_V#koh}6x;T#x?p=kxi0>C$}r#iKW2a3{eJudge79EDR)^Wb(~=%0$|-@2uV zc(-vYW;^J~pMQbHSB%~+!Bpqniu^wBzby8tk6WucX!Y;@I8>r@U2Ul8JrQ5#{@tJV zX6TvgsWpCLR;ww>o$Z4$4Fq4@zRcYI9VdPoQ;dz^i_h1rx33j`W%?n`LF{kN*Vj8W zX?2JbC9f#a$X8z*R~$5+tT>;J>sz-j2BbgLfr4ge<}0IBH&om*2X7(--{o0-&YKnM zQ10P5Xq&G&ZF+yq){Rj3Z=A2C%?+u2S*5;lzNU@$$H=L1coil1;`xbr^G)eMUJtUj z5q$CaL~p$Uv1nonHjU4a_Xp>z`wUlFwKkai1Ae$@;_GHG7HuqVdHrD`T>lu z`_k;=^=A3_sOEC(Rlhc z4>O$Ks@E&yD@Iip<5uPtbi7ysc)M*EW@zsdvPVVRJPx|S^P5Laea8UQ1Yi@ z@s(FCt5B1&EvSx_X8nu1WR6~oJ++?iuKUk>Oe|was$0T7=Kfz#slQ@|w{|`Youu<^ z{utAh4q|>nDbv3`?d*{CeHeO`6v@wT%i@;>4*C@L-Hv7#i}R_t{rRn~8}?nBq&T07 z`-gF!`V>;FJyrIO>iF;efcuxzg%$AAMgH&Rp=Y%ukEWw)ZC>f1#QyI-$L6!IL}PR!-<;xza{mb;C_rA zZBN@KU!TV}QzK_1*l`7R)?TWvQ`ut?wdq-khz7Z`v~cDr82%Y1~Gv3_2pO4`ub`S3iUy>0k~# z?YqeL&+E$+ z#h9J>Nbo2xujld4T4fqwi<2`(JE{9C7=P(^f1}YM6IyXQKwi)FZ&n8jq`&E^HU84Q z*KgF9`UmYd)Ksrm=I;aTY!G+Y8-9O9{WsUg(Z|}ua&rK#7^?4&@wMh@E$Wx%NTv3g z^>0&0H$2-kQE~oyI?E5Ft<FEdTc)W)9~5%D^=T!Cw%IU$$P^ zn(EmH(Csp!K9$E`I&2ApbI2O>T^lEVe?hE%W^d=Eu%=!3(_8Sz^>6H_D7<{Q0j@rR zFFnTBw%3bLJ1QIdo4L!M&*yh7+>!*{kHttkE$UCX{$)LgMavcWSWrReUlGgCclaj; zKRf4PZ-2oT&(H5I6NlHk@{rg?bAI8KQ5s4<@5aOrqJD;-&v<8B13drgq&T0I>!03C z6RJ4RgRWYvmY*-wMOokW=8y%FhIQ2%e;HBtx753AOlBSi@_L@X`?$phsOybx$2Ifk z68{;q7aP*v1EI2hbNh5#u00k^48WOjf=_-vV?fv1l>EwpJQwZPXrH!N>V|!G>->i*3zyxp0N zI1|AqpU*X^nY8|dA5AQ7qRvk!^M50x*zypp#m+O+N(hHgW_2iM2FZ_Cn+YmF#$M3#L2JU;WZz5}+b z8m7=s&gZ~{I^;dVk#-L|tdY;_gWM5mI|0kLi|h0J`q0q^WMkWo^d4yDGp|`sj1HNl z;4_)UM>o2ygJJARt$g}6_QmSVFx<}+`pNU}Wp)_S{n{NUHhjAL`*S{fj~;<1>teBM zpoow1{;DoZ&8e`cJDFyv`E*g{{|r`5M8hh{XzVNau6P1%naP-PX^?GIf_xb+eIOU_{lgCHz>xZLq*=&V>80weJ-FHgwib^xt#;Zuz&Ku#;jC)6NKes!N8BLterqlAcP>hO%bFYos{w1# zKkbnG`K2tsS8GlLUO&!87k>}=^V3=UrG>c_ozU^3Cw2O(KVO+YSnad~4i&fJ^3!kf z=X3wKRR3H%a!p}GSLx9 zJNz-PjkrIqPgSM&LzuHG1#J5w^Tp@OH9O~qpI4>%ksU<-kL%L{a|5zE-TtGcBQEuU;pdRwQ;zptyCGQP5Z z>$gxvl(C61rg}oEE^H4JInXS`8rp*2~9QcO>KjG)X%5nYhmjI zT$r1OXZKpj>r0t_O$tbX>BB8(Bu< zhk7ge19|@L>&)`xf6J8YF9`dP^Vegb6KtdyyEc7$?P5q4%^k?pT%1qD_R5e%rf3~aA{;R(u3M<#Ik$Ox>zJIP?%il#{^qkcw`%Bn= z+&}YgmVnfuxv)-XE`L7H&ux`v&!+@w=jZl~1T1sTMYRS(zqtQ3bZ%8j54Wa7Rj&N` zuB<+#p=m>yRT-M|xB;2e zQpYD*eTuV3OQetT!t#xRU(VO~(>hef*^-(?=L`Fh&7Wy=(Frblhr--Tv%a}ZHKbR5 z_LN+kg#F0+Z_oAXgzC@6AZLouHy*#7y`=%I>g!C;uFdNx;(v7%?~mYdUidpL82Wef zaN0xsxqyc3d6!v2%JKtK52IKvaMGC&S{dl^#F1?xBo*u6ke3i2L%TG2Vaq4*# zhMrp`U!V8i&e&=~FIBG8W3b?h&tH7v7=+wMiEv&o{4Z`l?y26E{?s2#vD03-2tJkb zX$*UWV$s8NxE&Yz7Rut6bELCX*6tli`E6^d?K7qS)#7mk{K8jZNPet*|2#gj;aLV6 zwU+u9O!v#z|K_H&AN364kbQL>2AT*yT^XOz*3k&+s^pW$Hw~rwFr5KXeqKxb^WL zUVpK|df(1k?Z?~O%2MnjBRW=GTmJrd{IO1{Ew0)0);gb}uuT(sxVZ^5u2Z9j#xE!h%~uf4F`%b#6erw>wfr(}f!OYJRaN z3QectwSlM~IlsLx`Lt0pBN9$4rUn-_w zGm1yz#LOs6N)misVEXmj&xCe_cBBf|g#E_z1JGH08SV#Q(e--2FL12u;{~9dG751fyP>}D;4%oDP8{~;y*k-`PH~JOcwT5%s1rm6`!ZhxDh=>5r5?U z2j!*wbKBMSl)LGqMm~QG^}q)j1BZ#5<@@LLD<=DmXz>guh5qsQNq{t;>2bgm=-gQ^ zuYbn)yh8P8%5BL$%&6z`@BZO@w)s97S0{%e>6us`#QeJ>O^m794<|D2AmS%n|E6CV zg#ja@(C3@rvzB{hg+50;nTqe8i8!=dv%d9dX-8e{29uks=J-e#hehb=nU3Kvg}(9l zV&GM&cdhXWWJ5E57KX9-b7~DDjgsW=hwIzpgGng)Cl6y@iu`;4<1c0GDwxLa!<(1l z{<*#tJ%~f?&ubO=aWMaG)jtvFus#c48oSEZ=l18_j945Tn`^n zT&Kv7bNySJ=}Jq_jiJ1{5gPe()LD$V3G3kE4_FALnH+K}*(9B;S{mK-y!;CHjnTg-W zMVUYEe!n$-H0iDN{5!+dE$L0UK6I+Mj=WyQ;xGNjb-?Fyeu#MZU;IXSzRshN`jnR4 zo^<9M)yQX^u3g|O%@n%Adp zcG~%@x!(_;jg@?I`}AX@hV-dj2hyoAL+l@>pGQWG#>*Fx7`{g{pHn^?QA~y-rHt4p zujl$1<3Alyy%X`ezlgtZ{VZc|M>F0HB%@uL^>btTBDB7+Tw$N`{CY}Z6rR6ai8lcv zKgZ9&BSTV>36}f3mBrkDSk%!{YJJVkMtE{xWAqByLTY_)Hai zhO+o(Mq(^J4O;`9GgsyBhv(N5rTK*!;cM}to|U}+l9_#4*sTq@PVk|1MYA;W8QFC) zI^0-?OFDv2?mx!#%YcQ`HdKod^MCpLru6HLP;r?94&-R&bB|j^dOpmA>UEztg;%9@8!RZljCek-j|+FT!L1iw$lv`R-^%%=R)N*%$Zkur zk1mq^M;@QK`LhF#HuF>T@A3HP$+-=v%g**%_4CFi>FmD2qmWTW_>Wvab-x&qL5Ks{ zK3t%Y&prlTC>TB&+p7utl=sh`tYkv>$Wg0)4rw_AHckuiBvJ6q`813*r9}rj(2;n- zCz${EzU3IyNmKG!jp^r1cO%MOXHUMl8#MAc)h-wTpBHQ8bNHoPRNi+KPv0*U>)H9T zx;mlgqO%M?)cu{D&ytln7~i)92d3r8>v{g+#H?u4l?bDzc8TdSGD~epi`8Fyxe|uz@8NT#! zfJdoj{<<00py)qVWVkg{zCN!n`+l?u!r!~0%Ll<9pHDiqMP&;4Xi8^dO~rZ^zX_b$ z7S*!6aNwQbkK3pIWvkI0FAHiLy;&oFC#QBqc*tNRr2cn(r9MtLToS zW&Gueq|GBO)+45+;D^UQN4|?e>fu$2{&QYGR{K*tHu*~ZgT9UB`{#VDU(=Ez)4gck zkEt56356Qqi(_(!4dR5+k7L1<;_ssA$#U5Y7HS^Qxf*yIiv8JCR z!{qzp@tF%=O%dzshTB*E+rLWvatW!bDk zjOpT@_B7iyRHJ^??%x~R%T7}Ge>}fuziKEB-IwShge)x_XyRc}Uy{xA z>BPx#7#|s_sQ&_szhs1&(1bb;#qeuO)%&Z8!ha~=JOb6t)6qda zzn<%lZqgc*p5BW(wj#d6^(WPQ1$tE73j0+eKE>y2uMA4Y^c7P4;j3nTR(@ZNHLrKW z=7*@?=Jj1F<5-mcvJzF|y2$s>`H8V?N54<@Bb~cL)O;xQXNYbB@+YrBozX&nbXfoE z({E8&I3*LqhdptT^^N7{4%(!{VqYOFOfSm&?-}#Yo{TWZ%SPJy=}=Ffe)YDdISn=Q z^T@R+p0#vE>~j(S)MNJF^DR2mOPV1N*3MXdes2HiN3_E_X@;dX`|tRy*0gx%cd7+~%_~KRiFaX;4?}^&Wxb^+JC*KR0tssMOY; z3Q9EV&mgHbyRP3P1fCZ5ACGUg+G9==tUD_72P}UuEyN#-rp=dPP=YUBzqPW9DLEKR z_1jwd>rfPkUp*pW@JZz7IA716n9$Zxd-~<7nXi)6AUyYp#jzQh`P!UnL~+O3(aA}d zW#R7etyuS3%tvr_Rpz&g{>jAs@>?;a-ffNgwD__)5;EIsjei)D zK3y?Y>Jzu`^maAHz;!M#J|pElC!3bsAdgme#E+9`S<1e zw4n8PxL=D<)R*x5cG%5^6tTpf3>RtU=W?wXFtLqS%s=7wTba{Fv{NPV(_Aw@i%TNm z;+Bpv<d@^()FE1NHA0qSlcd`Tq6Xl=-*1lb52>h&(i~*&+X*`$zX5Rj1C`=2Yvx zrN;P1Ezk9sRrvr`owzQq=l$Pn#>8RimX!+r0+|2QT{{0{f5X-2mY_MlarWvm$-di! zo?jgf%KGG@X8P;B_|5Oy( z6tBEH;?w&7^3zKD?!nuZG^u5GvV9&b-yi2k|DhfBZSJX+AEWU#XxA(YGA!9D-yhc} ztaHVvKfa3jww$j@*Sg}<0PXzDlg|D;kSX=wXyM29SRV|!Jppx;s4cVaenR_&P3}! zaa!k_Jg8$#Tl=*o1C`(-l=at~njD6(#8gZwSR(&Ee15`|MH$%SU5E?Cf)8FF5^SnV zW4@cwkHwnz|Kh6g2##Ng3ud13=V!Yr=WEUVy%gQ_bK!oaiu`}>p9D#<0sV%%aOU}I z`S;Ie^%>!nEa89GPHTM4bge#psoI#VuM7X4_pemfw}JkZ4vPKD-~T%8Yml*%zovV-p*Tpnf4P0NyB4^E z^%wn)Y{9a($6z$%IC+@$S=r*BpRh9EW`2JmI;tv$gM)m7C z^8IuBsr*1Q8t&ylH}+_L|34Tz0k{83{b$34{dArAC!s4hV|nlqyjeZhMclu#zUhcm z8@Zr!918M;|6a=G6TD5$L*26n@#JEvyuOs}?{%h;czb*qDrBe0_s{+Js`aJwZ8l}0 zr-874Y}xyFUXw($mik9FG!^e}J$8OT$H9d0?QX%~$zu8QU77upRXrOmE^Wt#3{n5c z>-%h{EW_;ZjX<8}{hw!RMtwfFr&%~Ee}1Toaz0$k+Lripw4I`Ug6DtQjZ)FM4*GP- zytllb$Ct}rut8Kv2b?Mu?{6O8+CR#c7C3rpwSUg(+GAE&4@G>7`{%VDxWHvjf7lNy zl&{a<&(Y@HvEM!bwXbX5-!oG!$>pjOnLL}Waev?b)Cb+02V&zJ5noDY`PGZ}t?BS; z?fsE{ABST3i?jr{v!!o7FE+wIhgsejDF5ycg?L%KnX{Gx2yn zCre?!cr$(;xUa*)g}V`U@U^@?)J5rk8+|5x4!?;rX9YhhmC}AOllm9KeK$f?tEzl| zynd+F*XcB}avZHNv6k&G&c}o=mZ(kbwE73C&dpHktuq4D^F#UmFAS|lDfTARw@@9Q zV)f^3j@#o{%O1FBtvNomxtA_&_AsSpl|+3Ww_i?5{r6*X`zy{j=kNa>C->mdkMqbM z(@oz0y#94udN&;K^+&6r!av~kLr-7!MYpfxP{!*&|5tgw)S&ZCsb`6DJ`I2WJ69ft z4~J(;IWF=3=k-C)?wXP9w)V7rtl$GIK9wx_9=^}QFm|2DZ}AF@xfyaPU>#QIlB$=dT!s3es>;w?4INL7vUds zJ|Zd|M%%EP2swUC-hZKtkCad6rSmPGBg5mT{P`-DANeJnPqpCiYBYT&-oM@yHcXQDw~FaYeCkxHv^j?KJ7>x3dH-RZGHK}Ry8(y( zR+jId+gFA`jq%e*J0BC$tC8ITV+xx*MPASKBkNZ)WRWwn8x+a^=loncQjMaDjLC42 z;D_7)6|EhR9p7E6eyn}2O93XPgiV4U6^rj4IqQZWzWo*FD{_4qVX_y$-OuA#sb+rM z-MVAs%b}P)Q}Dy>E5`v%sY@#tYO!E~nm?s|m3Gkwg%u{itBj~0=JBa@0XAegOgmq1 z>iA2w9l^LcH(UPxxP4W_w-IIhZA(R6rn?CHNZG%!WA6myyjp~vfh*m3n>pwp z&0x?rAAf-xmu-c z9Nt=t>j6UF`T3+_PnW{Oa6LYq*(R^&{TaP%593Ab4Ggyx{PFsMrrkPGtC@aO zKT3W2*)18NcUGhDo45S^WHWtw`!pGIle5t|_J;cYmHIU7w?4gJVNNgW{gT&n{?0F) zMw{lw(AW{0`K#L}9R^o7!g*eGd3`90Z++ielTznckXwq_f2GX72}^5?Iz8Je>d(1- zSMx#z3OrwnzTF%w?vK^i#dmCmCsO^oS(X3nFQtF}-awa*G%%sG24?bl&gbZ-4%l0{ zyH@|)y;m?5FN>kAP7B5JvHDm)6L%DO_QQg^;`*j6{&g#1FI4{L;61&&nlEMl;_%+4#XQCsP+ z^#s8m_s>^IvpsgEEyC6Xg1>a8Z|4^jz(eX^8ls*Lta4NOH(UCL;PTa2t^K`^>f}iC zZ?+<6XOhdm{B!^PSAIB#r6=Q~`h1fMEI!;bY=ty`As;ChH1qko$tAph{|t4K?uyT6 z{fExMhY>mQI&9*E{{g0d=Zk~M^IQyhSp}>0N6Ft%{S=JYyc)JyedPVY>sw!cPez&4 z)fiPvGk+#kYf!y54JoqaCwcw<`B!x_F#VFmS7TlI|JjT$pT>IhI-?==II~v%KNw#+ z-K^l%s4brAY?uGf`O;g`9Os)lVMj0FAMyA=nv*Wg4VH2sv5nOCr>u{&?dk~q(cQ59 zipc+S|HyfLO)3pHr|lzlm5AS086T)J#2uri_Qk#Ff*)7LPh_us_}cIsT7TE9Z~2n8 z7EANnYPZM}&&TFlOzdP!fr*{SBdzvmV)IC6a{hBXlW8?SE-56MEaRhzJP zlkmUz{HNg?HejS`7y6|hls})J{}OkqFWs;kPj>GH$oz!5DEY~8PDQiMYZUWAx&7F& z#ZfeCc>}v^SCrRhv;53~SY7&g+L%_>`yl`RoS&wpixJZ)6Gw`k%lF6gGbvSS(9`k8 zWI6bxyq@!Q&%6fdM;p^Wy~O*I>sP-BE1dUkBh~l`|A_Ndd5tawOEr$p?Wd|gU)ev^ zY*0%W>quv$SQN|u=lmUgQ=N2M8jw9biUDq&1Q7fW~WB} z3Tt%2`fq&@l_>ZNV*D+fw+~kJ&q_1&H0xLUv)!Re8!Yut3;U4gKYwnrrIXj)X?FAB z8u<%a=8LQ6$Klf&p>Mo@>Ywx`r1xD}|E6N`=W3fq;EUx9^k^X7e?0y?CuB2hBM#u# zOHY@7`Q!b;4RQlf|Mfgv`z7{2w=ZYjk!BaI*o&>Uv*h)>J~b#{9)?N${bzsj_=mZ- zHFb!0pzi}je2w#Wc76il&!l74dBH#LUtE62iE4TECfBiIzAxvm-tc}DJ|~dI-4J}a zGXLyV&!w0%e+@b>@s;-v&wrl2a}+B!UWZNt!58<>%0rKi_Gw55b-t+gpE7=N>ue2j z>t{@l-w1xV{TD5rZM9#jA)Hr1*#DfLx67>%?9*Cnf4z%QH8Si_k8VCx*N?g?`N@uK ziSPBD&@DyyXPlqP4|QpFZzF2`QnP>7XSNfb_4U-MU*9fQq)MY}lK+TUnIG<-g&4cz zOF?gpn>QYX;C8;KRX{;Y8H@ydzs+9cj_{M9U0ob^6H0Da+hk8bUdDVxw-^2q*C(f~ z^I$8@$kR4|@P0pQx*lv#TOM5#{4xDG`zId5e3#=-OJQH~_}|5!F0?XGs_j7adZqqkj$4Kav<6jd2Fd%ol=)8vcl0THqX`|X zdRFXz)<5KAUxPXyY(RfYMf{)d?-hfrCAL~C&kth#3pf9^#F_|4+?lR<|N2Vj^L&o1 zPvx7Ki0iZX-1lM5IBn{QTb+geaQkb7T}2vwO`irlh?Ms)kI$7XamUT~UZ~eu^ZvD; zVo1yGThfIJejGOhTq(4GH^;#}~4v7hsRsUfk^`_ID|Z-+f&>1%F&a z75)v6Zx33M3%|QN;OjL*-oK@6{@>J$d1yO4T2X&_g5__#qD#?l+(%Tulq;|2@Bi{W z!(mdIfOE?i%fBzrPv)HLOa-|ENL64U?_XYj)^)=|r0B-N-*3FUp3ncgIy(mSQkF<( zqz;w;pUviLmbn~Eqe~*mbDgNK#cPDWcyZKwbqxJ)u>48Z|Tva ziV-qjp)7vaW3xL_p7cV~bs|0#!0fB&-+K`Kxqz}f$*3w>? zdw#Mx&Gd4n{%)G%ceeTiVANnFYQ>88KkqM?RG}HI9;ThI`@Kh@@s?={|AzDR#A7q8 z{_H{1K*1O9pS@guB90k_;7nstpYo2y5AIEwkIY)piu@;^AN};34ZZH;NFJ4My2$n$ z(~o8CmZ6R0e?RmW-!IpX3mq1qePlGee~poUU(QEH##^lJRE93)zmq?o$H%u#kH&^I z$>{q?tq&|dFm==b`mtji*>3XHs4woblF@Gd3K$OSE?@sT)0bKYccby-qqzI3i~N5* zrY{@&??U-UhtWM#U;aNoA2#BgHMXv_MU%n8|K|OvmGpMvci17Q9QVol)6`9AKNT3a z!j}yWTJ0ytUpo*y=@4F7wUF0y|KoPHGs-mUf+>3H>$CG=r*zzb8mkGe3(l#}zf$`D z7shqM_4roiJn8J(9a9zgA)Y_IeZK&0qIaWf6S4pK{F97`K(zQh6Iq}B>mOD2 zr^X#`PyeIqy5n+uzyD*eRI;*?9g4JzdK#o*gwP&jZ$g=Asf17@D_J2a871<*%vVZsM<+}Rb=l6R0H^#>yr6Hkt_7s-xrqbS2NZ47-%zyxyJjktCp(gpWJO4hX1ZEMg7Ynz78Psh1N$8 zWRa(RS?)07O8=JkSI&%$Ld@~yuo^4)p^V^T(W0U3K=;us;K{H`dwKkonzIzWv=b25 z&zL`-g7nY4xU-n8w~b?6wyvn;Ke>Kw^DPC=4R+v|mxXvggnwQb=V2O7Lua4BmxAES z&ny=nnWylprQjdB{(I`muDBCuSmk`m)Xc-UQ~M->Jp{gN3BFu98e`#ct19Q~-D!Fl z2Ll;QH1#>YK=|j_25U4@cf^*B0$((~Yk%(`wrc>2ZO=KrK=|iOoCAzQ2FUg|p!_qW z*FiiRegZBtM1CG)C+D9dQwHHr9}jr+7y25-pHgikhOY=jepl7}(k5^WBGlygq4{}p ze*^X<%aVOgn9Kb?OewGbSY=54#dZtv%VQ(|e<^<~*wvZ+onplP%-dCIFV~;l-50_o zBnmbiM1KtJui3t_JF9lVoW@XIoh+}>Qs_`-FQXB@XT@9U4jrsXgNqx0}!y*>GDu#U?w}syyt*4jSWXJzxf%oZ_$*WpW?@ESy#*+(i6=eRO(w~{`s^fx!4(S5)~;Te$yoQxpmtZ z?}MzWoG&zF^I_4H{E3=$r=Jb(+Pfln-4_JuHhJ6UF1grM4!&~^?-L;Af}cJ{80V5 z$%a-6P z$2%WKFP?^3i!&mABlvogBGrcUtYq`?Xn(^g_oFy*;1o`uwB+_>1Yg}cD$!?BzbgBK zHV&0)@5>odU+w1jG9>uQ`O^>j1p}(wUruA>VZ5Ds0`0r_+x(0FX@Ah+DTDFy`UtH0 zDe|M~1YhRmIT(5K82sAZ;P$q5^7ybzyJ7G<=LKyOp+8alwVsrXNd2QS{84>P>wtv6 z%~Nr*xxgQd5C3#BVA?~?*_?XNw#O)O%e=_?}frNoISeKgr^M5(M9(UXX z-SF-B+g9jX3KAdsj2_G?%DvejC)M%c?go+gzCRXvB?5mn$^LPZ!)LSmL&I5O<7t)n zmdA(tTq5E2DHiSb3jBfKZ%OPqEWCORd#;J~J5;~^HYg4Q0~2s*h9-YMx+Feq*)xoF z(2Zdias)mp|J7Y}6#3^*LZ^n{KUyF1`YUOterM3RTXTMXko5(thjhbN-5$6Qt{R_F zSM#CK`ZVqyKh5z)^RsuaOfWXcvP%A2J^dIuO6z;wC)sj)8b8)rsKk#=eXHa@+rh_h zV%upbmbc^hr29YiU)c{08o44oR^(@t|K2`ugKo2t(5n#fAzi;SvECtkcySDUuZ#Rl zm*DT|m!a?+=!ql!M0`ip!&oN*BMwB9g0yG z1ioneXq+_Xq`}GXlM8#T=l-|AUXHK8(F?J^X9T)65&THw$CN#WYx}up-1+QD|G$=C+ix_b(p{(U4M`~X*nhoua@m^1rlE}4L3Gqs5fgp zK;VzA-!UqRz_l$gxU2O){XsszveDEigh+cRj-S_+-yhY#FCW~FHwk-@vEw;^J_V`2 zYFNbK#*~#v9HhbR-3Y$CpEYM|Z|Jbu8?N)?3Znm=?sEx_Gm3Fb*^?g+Ao%Hhpc~$A zGC<8B)%Z~hFF@CKXW*E1f%|_L(f`hund0$OOGNC=;peCP_G{pAY}tJp@88>Tdj;XQ zpG|Dh-@I>?{d+Hij^j3y@N=t%h#yJ*)!|!Tcn3IRXcN`(WB+At*u8N$20aq|MfE+i z;|DQwqqM)fQt(%pQqEr?^@c%R>4EIS8~F33lm75E<|#-`+EOKd)$<*TK~j&;^dQyv z*<#s~Z45PM3#WZOW+PJy`0+5MeEn$V%cg9eRDT** zUDO8^r2nU&X?JA3)5n6&0zXtAJePSH$5V@;ZSax%zZ;1U2M#nt+ang(H(fP;`p&k6 zcc4R+`ozlj4Ou<^#%yi(#7cb0^}m(V`eE?~C)9i(_=D;b;~u-gI?Y|Ce^dP-tN9T; zeSQq%2MB&qDCGDUTRI#sOFR+Uelvf6RR6A6){AvJWg%N%P5TSJdyj=_k4ZR~BH|y) zFS`wUuuFYR*|=3AzOyCqT|lQ<*t{VGj>ZBXSw#Pi_UOjEjC--HW&$5n|GTWe1XG>K%X!$i zsQ_9%1%H9y=S5_9EcVsMkvgjJGx5lMXdWx zj3^ZKS;{}5_3Uu*hJBUz>bIx~dp4p4EBm~QU!T^WR(d&NV}O%v|6q!*9-H%VCLDOb z%ERX0_b-g-7cL*&Fml>3%)TV_3z}bTdNvXlvb~UZMBszQZyH($ad&HOmHgBA`&g`* zG7&D3!k(_bX!oWEJN(v!6=tZ$S2wd+=xQSE-?2=@cZCFBcZ|EU4Gns+`F#bxDF0+X zSqKkGz$~>q5W}%M}8pHuo~Mq?7EV_KZ2ixHcK)5U@U@9 z3w8ux4& zG;>yf`HSDbE!8IucV51%CKmAo>%iKG5rwF+27_ z&L6aX^uuKwS_V%*S~ua}ls`5-?a3BO{+;n!wSPYxJPYmK&c?b5Q9q^gq3n+4pr7&x zwnT^U|4%{cM;|ta;eD@g+58)-4=`PKb|B7+sjv9T?dkq7_3lSvLP|6`uNMBFPWrD+ zUpTalCtQsH6 zi_KWA=PlUj+2Z|CeC$1E4!<8}xMQk1K5K4x1e$yEP?FN7k{{&#+rKsJuz$I&Y=0R# ze?R+rV>b6zGZz0St&-p5@!JV$en-b=jH`(JLl7eUnn&*B?}zFG9rpR6hL#*( zG=F&)Xv8-7$oGe#_;TJb4nc0?vGS;h?FTQ1b@Br3)CU%tMz#w2O}^{{Ao6spG0e=+%Z z)44#>Z}(T)%kg9UEduVvkyv|c0>6Gb;g6>$OX28yA9;IJ^T#8frI<5324{zg_>1N* zE&LuJyUk;K*(~rw<1dR{5hz{~i8yo7KS}k0u4^8#;AiD5)UTZ9Uu8reaCjDr;h*AA z+`K-&e~Pb<628>O?}X;upZxi${`UJsbGD*(OBU5Yb$(;GOdmU@c7x7f(LYD|C98=B z``)e*i%bjT*QfY7?q>my1hXpj@5DDpupuZ9J}Y#%|JxFMVD@@DsMVF@ht5A-87Aq^ zr3aDqwXgL*|0pB+fPeq~Sa?U8VW`~A?=Ob%Q|HG_+MoUuyb1>K_>Ah`0T+kh$96Y( zY!diNC;GQ%NC8q>0?Bb#xqT|p--5sTVvepaw)hKvqxjo*a~xjTj>AG1)%eQ#X2_mA zF|Lxoj%Nm=Y-%tzJ{J5%@s+!!Hyd%ohMly?;{QL*f5xXQLW_-yaHFNbAFVGHB)hYK z86K?s$ro-<`K$iBNVIGk1r7h0%J(a;FC~S4#GwUW@axzmVNceVFP8fAPL7Mf+q|*d zp5kwU#bb8Lp`4|>*~9%mjLZkV`!W(mno(G=)3MTCuD?ClQHr6}?_tE?AN=}se$Mdk z;h3ovfw0|exIL{u4So`f4&5dF&bl5yPVv>z>lRjp{D)?*X7b|-g8b4uSxk#;^2fP#bq5CV@*Rn^y*-A955ct(4 z{X+{h4q01V^REG)R!nf9eNrJ zoq$<5GEd;6gyb)qKlEk=U2ND0U4f4<65kzCEJ5#pFhnd{!~b8Z4-D%$oNazFlFfUe z8XvVB(5|Q_?S-OyRQ>N(ct%7-2E|xpWl|uU%PO4BpbTOi;Z1uD*T_UubbIE z3LDl%;<~Hw|3Z?#n2);y?bN%tHcPetCvB1VM=b(<$LsLx)B4X%N!xbl5`zW#wfONE zqMvCSv}K1cv}FyW{^!5)`6BPH=p+7w9!#zNcU(SSzGQwLE|=uOWto`IMD?-x2A0_D zVp?T=W`b!0)_GY2*7Bp^KkEP2UF~r$)&|d(s`mfiLyNIevl#CU-MIf!|DW5(8ROUV zljZl+|Gj^;WRK%oG2P+KRQmrQ_o4W4QJR5!L+~pIf5csuW`8%!0Xuz@`#(tkcJ){f z)M`E)YhR1{4c$NU&BL)s+BO=lZ-o9u>!a;+pRki{pEIvOkw1hH{cPF7**HIICYYOQ zd>ncF6p>|5QC=%n`Hx>If2ce7A@ivhvUJ4vo5pXSB>xOO6#=W@rQCn0|36&%1wW5{ zL8s)){QMyNuy)v7Om_=LaLzz(Pv?JH{&|G;?;j!U@k4G;*MH}(2}j-TOK`uh4Y#NL z*>lE6BcWjwZguI%j~5dC_f0X7si6!jm4yg#(#q-ewsjl_c0f4G0WC;ag6ZV%Qk)qu50{=)B%)+e>B zTC>@oTCzGrMSMZ?_qsEC;Kmp|co>TBH_bnC3i7e+Z7$xY9jf$idH;1&TPv7ZnN-Oi z4r?7SF3DQ9|0Io%s{e7uT7^_&JT2~z`uDlvt(m1pE9REeM&%ZMi^%UIv3-HS2i1QqM~=a~@&4%bDVe`t8vmR(P%!JP z-*DTtlK=lypN&rU#jZmmQE+M$w+|rxZE@l|JT$){dP*j@r}Ymn^K8TiW}?+Gq5snF z_aOUuDD(>ko)6~dPbK-a+VxwQEb;I7_a*%NbbY|y_;932`!Brg*oWJfk@#j>$$#)^ zeiJwA3VlsM)@RQ6xD*R&OY^P2b>j9l?dAGZVsIv0Htj{HcCY#MX@ARt^C2*JIuqk- zUg!RmOZ@xnhUUz7K~vfKWm}>@?fKjjwZG|MD8%=b)(4YnHD?E&HDQI?|Kkt2|Jtv! zLc0XxD*KxYC*`5R+C$LZ*n;05NdEjl%|V*)*c+k41iu)P?|aLe>MZKG8cY8i$L%#q z|Jb}`&Zs`u9t$JW`TL{(pS>d!3Ad#gWF`x_|JsuEYZ1Of(8%5eM^_2|r~2>G4V!W3 zUJA@|9&-Cs@_j$k#vhtrMehr2P{0J=(wd zv+XnZwtocomc#k~PwVfSN<6Um@DPmuEcC$ul0THa@P+lM5lHBw8b7;tDp|~EX@8I> z|NDN+`Jsk}H(tLSCdJ5=@rkWGe=hoT5E|{XF=gf+et%&kKDy)>h1FY@$kyK!5`5XN z3d791q3HYAl>dL_1V5>NOYyG3f5_9U5YMlW>$@MWhr!=}9#X$I=Jr&d%AK$eS(|s` zdFB2tMc&rjng?VQ`VxS$xN_bmBw$`A7o z7(zEk4_jIv;KwPxZY;OL2XQ2n?2`Y|}y z(iaxbRO2T@SpZkpJZuPaQT~g6sQ$a?q!-%x4aJ2C^Z4^q{A|2lfYQ5pNY-6YX)o^& zD>(57p@!eF@0QSS6{Nqi-^wHSyypPs#O>wwWdt9ko234$UQ3{R=YRQ$eEop_s)zW| z|1RRq9&mfgKhe7u;Pi)CaCzN>-@g-yuNGBbj3&~IQLVQc{5V~IwoBUEc*)FEG)Wcs zr~ALHe>xAECNps`<_7m45PtD_bPZ2ZE@JA@(fs_WB)?b{SqlBu#Zb4j;>W`X|9o53 z3n!#Co^uYX#>a>u)0u16Nvu(}s6SHu_VsovXs_%ABmYYNBKrpfOZ?-yBnO{+H&uzB z?rZE&KFR{lZ};;1b0hdkDEtq}6R#m`_;4OSf#^>gx;nw4%mzh4B7dg*Gub-}*VpX9 z&VBQ3ROJ`z-?-s?cz;~Z7WxsbkHi;gv)*5uu*P9Y!k+ZETrTlPGt&`RkSOp|PWZ>@ z%NQ6~`QS&Izz40b_q=ipt^YfW3%{L}|L(7h=Sl#NW?!!Y}C;-{5$Q z=TKV3aeJD7Ke14-<00Q++gs>Y6d(0Y`@%ub9Y;Ia@$;7velalqflos|VWgqRPZR_{ zjixQZor59J4f7QCgkMHXc!*ukO40Gq{mT23_ouuIoDY-XGY~vXpW9RZi8%Eiwv4%k zld)CgC%K_eKQIkem+EqRiZ8vj^DrlVIxfu=`)APnT<89ExG%Yg*DF->OS8$-S-pA_ znbDf25dI_Aua-17LK|DXD%VGsCO2SRde>pcUWoXX&WA2+)m!S{tr|Z*yYo5mhg|Jo-LNtHN*G`BLATIxzn8H?BE?O*4Itc52=22yNQ%rpH$*&SE0Ys{*;Dw zv+>Yl58{kfeN(_H;HtlAw$;#+|qIzMArxU{#`oxupcAmTF+{MaW-^Q|%u zf|ZAI|5PaC{9;<)2Wz~C;PeS^?q5{j?bNXvGp_iK)(2GME3`o%^c+Uua8y5TuS@jZ zj!*6*-T6PvT6=*kd>& z)kn%&s#}ZrMqZ!)RBHfU%(TVqV%7Q4<*a!uan(##bEn{Uy1&iF^pQwB=Zfbh0-vcw zA8rxn51Zg&82eoGw^038Yx7yu7%0^sEBF6(BkR`^=1SVYs9{KFEBX7Q`06p}IF|K3 z1gF~qUv$2}z->Nwn(BsvH6nha>u1jAdt=6l!En*?;^)^U{av>msR@k{7`*=x>-yf}?d}t^6_Az5TC=>ok@nQVx80zHZ zKoO*=5+9h@9~$Saa6!f&^8BY|=uP~Ze-THI_Y(0J(GL!e^@N|{09k)>5y3}v$R1q3 zzZEh0cZEHvzkhBMfHqk}vGS_GPYj9Q>c$+wsPIe~e(3tMHWj|8v(XK%tCsWkGo8%$ z)LGBa*ESc2uBy&|em?V+dMDiwoHw7_)A>#T_S?|^Nea3gn9Tow%1=d0ywTWd5biGX z;P&Z6pNmt}V7F)f!1ow|FB<=;M@#yifg93KT66mVg0HPv51{3L6JrLd#@Ce-V=%FU z2MX_W=k|1eC};Z_IPEwZ?p<2*;}k!?Q$m1I6Vc?>Is7=)2aZ+0kHT%& zp}(xUI6tYc49)6|yOBL$@@GFkPVw`5kUFyuuEQpNtS9Wr{?;3N+F|`wV|3Ud_<`bQ z*$+qPjkd&UE0JH&{Kn)~YqoBBQx>-WDX*VU{&+IN6TdWEW&OjHKkOxKIXyTPW9&rz zgzC#*5dZ_@p)!7<`wLFKeFXiV?~~z!>I1Q%zR+$k7(*fjzf*j4&OC(UMSC%PQ-9^Z z?|&-Ef4=-A zV~p8tJ6EYMEYi7$#&Ja`OjHPag0EJAy%B9_fCeR*{5Zu|-oAXPexHS!&l{_Z-(Fbu zMaeExnZ7{rRgriMTH~@Y{i`nLC%Qhm->3fQZefYi6RPnyIMP-I!#kDrOC5Vp z3@UV%%^!GA_^F~S74A>gB476r=O>CkpX2^$_iJ#K>t~h+oxuL)2W9wEDCF}Aq6+zn=(G26Ic(ZK*0@i%u{z>(RqF$SD#&->Tr@i6Vr}$Esbz~ziwPf|2 zOZoLFzTj{RF|P}y8R|Xwab2>0^Miv4G$T6Ub%^Tx=|@f({O(@I>Lud-!wCLr-|UUX zNAzX*(r1C$sgC(4U)|t z(6pE94+CDG#P{&Sa(t2ck^f#_^m#J?Czmhd@1N#RTc;j^_1@j+JxJh-@>`c4J{TVE ziYCKnb9;)fpFwFjv1}cj*H2RZ^G}K|Z$DqW+BN_mZ;SXZmEfyJLJd|t?Hl3@RO2hp z%o`Whx}a>lYJ6qR8iVV@-QiZI$M28UkG5Uiip1a29w2=Lei8_Nb}yZb6I$MIiWT*t z3X(tVZWM~B>f@o4-0OY;DA;qWUW(;AD@$baB!7A+D#JiUjV_! zqqkb@>C$?vph+Wse%fDCsAGp-QjKbS!vE?&HD&Wb0K z7i`gCJ$E-|=F3F=L_z99=UbWLgiA+^>8;xT+pR6ZyWNG*yZ^q@Kjr${dhRb>`N(CQBI6N+mw(Zt_O|Fee!22!5gcXT@IIpu1r$Hpd8l(Ioiz zeLDcoQwHMfXwiR6*RQEvEKoT% zp>_UZ^_xonR?79e0atwBvBeod-vz%U6MZ2u;vw2xV5NZMPc9aV5tZ58TU`x9~5?G1L8whV%D~o z!k+Ng&cAV3^kX5?VnzQNo&Oeoy(RN>(qI-EB7UOyy`y0UW#5if>gNVUU0I`nZCLyC zO8-*I@mutv56W}8p`x$IzibJ=OHxzthWKG3_=U!YQ=HV; z(f!p}?ubeJ{e+SIeTE-&Lc1JOcsEteZ)3)IqtKu~?q3z(2by2GKlQ=YL}`sed@}$4 zX?^zEa8FFJ?T4e2qxf-(uZRAJ(P8;69PKLNHwD30g|;tRoN>aUY@tuk_-*%v9T?mo z8Si(f#@FOHFVqNh#KBi?{Q3zbe#>rFk2N0q8y!~*d{O;w;7o~s>$>3W9-&{*{R^D> z2ViZ1E4rQ1;peYO^a=f_ZCLgy2^OIuek-$;*JpdSnu0mUN8-mR!B2Xmzu{>32{>qH zVd62>_!;Rq7blc~FiaBt(RBSl>6BR1Z7?5UmxR7Y^P{wD?WMf~nz9=!iuwK1`cdoM zt(kr=O?J4i$j_<&4@xnES!oBH(#qlXRNwnt)RYz9sK>%u1XiA3?*GgW1Gd)Q>2CdH&~sLtPE=L0kAg?GHMvQ-JVm`w;e3U+@pfkD7S7Vs9sN zoZSDv`l?(XKT^*}+JDOtZC|MNf5#)asDCjXiEaP05%G(BKF4V_FKj82a=4d?{P~lK z{@vMTBmzwA;c_XQAE)?8=}?U+jNjmjYbE~>{jMfFVH?{Q?(-*C+RNwfKJB~<*Jmd~ zU3ZG|-~E*l{+YK`icg&!QE_t!x2O29@;(L4tOI!2Yc02@`oV8!KNK=2l*d|dd#WEi zU-1w{XRe@n8`b>tCUi8mCl17=C=uUL{^>t!J2F2e$@iBd_?ewD0loVVL$hE}KcV_T zFKuAuuKh^ABJe}|Q(No^MIED22q+Tz7}fVaxW_>;bUxl|eOJjZAL?vEh}ueAXf5(1 zTf#4|b|&Fhz*3CYyv^-F`iEK_Z_T!j*I>``#rK!$=grrd!Q+1WD(7DtJ@3X=gtcaM zo~q`Tyh+wL)uSsy6IJ6Y{FE9~Zdb4nmumd~qxIR~2nQq-^}tGnh|j`E|4{Yw4VZuE zUj&_29Ulg-afZbt6EvvYKZ3@G+K&17)MXC_44cmJ15$qqO!dLoI&%Ec`ct#Vx#;+5 z7rMI${L%SQ69@aDB&k0R-w^yn`|pAWT*A30^7*4wUthm`B(9B+*1*Q9#^(Wb1!EUp zz-qN8$A>M!XJ{8McosNdd>4VwRFZ#1rtCtS@9Sjvr19Zi<^%oCjJdsWU%|vh0)MoAdoDK!ts(|OZ)yi_PxGtnm}xk^MB2k>fY29O6MoXT z47_#NFZ~Cq@wLru9;$~1%J8Ki`P0hOkp-VgY|@k9A* zX^Ac?b=P7)XI3e|o*oj%mDObN``xZ>*w&BgRpPJhLUWiMZC_=4 zmpS@19Q)tGlMHo!e!9PE$L2OLxTuGLS5@P0l-FI9$DKn=ttkF{wErk8wJ#Kxd!YEV zz#on8mKSQUmbDy9;B>XkM{khD*y2t?a%AK%o{iFIKVGwFt?}q)zxd~ z(K6yNb|{m%J>9>1=E^{{810O^g}p27<^AEI()`q6%~P>Ydq?H<RFra*L|*wXf|6tSqpGyOprdBKo@ZwS2g3OGl2|ErBo6AA9M5ANEV@W4rxc z$FEQ0%hOh#C{DCRtVRSsPUFkmW**RpQ=;5f;EUFO|9swqU47PLg|EPug2azQGQ443 zWRK482l4Y$ep+aE5%Z28#*(!HUm*SCN22`U;qHj`+2)n^FUQyYC)v2ZdP|k~GTl2C z3+@cS!MPo|J&hkP_uqv#Wl4y||MEL|{*@m(3)U+rT~m#@-D|CqzZM@KA@yEbW9=~2__B)d!~>~6H|O0d{{HCtzIXRG zlHrltv!M66@Xg?CGTZ$4_A-J~Ybl#EiE}jJFui zuTSH{b{##jXtEMnaOTI$h<@R#c#0@#|H|C9Y5e@Q1Ye^sN%i4f4tU*F)L*E6u{tRm zPGdL2@yPZ{dpUni&Im%cXU=fErOU6cP4tb0rQb2UfwV?-Z#lQ8>o;zHn2v1?hNIw+ z&K0j_tMVCxRyJyyOYS@Xn)4|Nh9$5NpFnQ zS;5brO7xR!@mtW_QjX6uQa^s%(i;J~w&-_T@E^tJ$*Fm0m$DsCO@;nQ@p)3J-wj!5 ziwpZE^6OLmv10gM%)h@5VY-4JY5aLp*9)OGN<51Y|6d`&uYdJI966m0&7VSFq4=GA z&=(6r?NQsnm|vgvPbDtTMymyzFm|45{Epc)7U!Z|s;r;&JM$fSNA5#msT#l4%BG>- zESr0^5H^;~{)%-cLMI(0R zl7g-JEBXs4KI3&Q(SK6a_?!~2&RlE##;vnX{QcOH{*E<+Y*FW4XT*2OMz|3@=(8In>3>#g5#6sf3BH>v39o!oa=Ar*QfZj zYtV?*gMy{bSIwVENnZFk(?+)bF@eOViay5>+hivaZi)ERmgIl^9(W+;MIU_7O5oQ| zC-^DOX?;%K8L39yK{YNgmw-5@nm3iZcpReMn-9vdPthDY9jbGOev3V z+r`H~FJKznzm#))DoB3WZsH~Qq#VRyCpA95g65ZFVxpn$JrM&!H*kBZk2XEs0~Qv| zs^r(+OoJWY^BV;XrtMUio zz;PqA>zBsuDSmg&FF?H(yI^>Gn$17|ru|#v?s%Z*+1_|~O?CX+`b|gHBCio!m8e?3 zG5F>Q|5JVNZL7d9)lUz<@xq8L)-rvR@@vHWqv*eM8{S(8{8D|?tB%y)zgUSq-35NB zzSBtm8T`X9Nb8HEl>eSDmE@ms#@^U|&$>$dPHHacI|*4be$}*-*Ux87^2Nv!B`RJT z^7l*Y=S@ClqMMZe7G?i0zLv+w7sDr@QJM=f+jQdgxdgwfM(jhi%j?i*w!kl)f817W zGA2G9fUL^-k#v3L?3eTLQtA=VAM}g+7wzAAP#S~#i>IRSw7_3$g1=fvE+Ow?4g$KV z#$VilXiSeJqmi_mus`C`O~v4yHib#tsa@mpP%yQ(J7Wlf1*?6{EgBN zcVTPCurc-xe?A)D9?i1H@78ksX%hThEPD@!k5YeScQGHF)(4%|^~Lo|dRX{Q;E(2? zjfx&2e9l>D&ht9{&%eruewroq2Df@?gnFj`vzONgyAAKa9>r-eC@MsMGU@+{k@7pc z*xq<$Ci2&s_O)gFW?$NonLp8F26b0){L=cxx>64uF0{g<&m#VHLjq$v&9T(gxErBKZG9@p(nB4jbS24Yt4YRtkQU_qTjJv(Ud?S$R3;3TX6fjB!BIpm4P#oK2$XEaOL&o`p{m9 z+Z@jhf=gOMZl6o~D-Yb?1!d>eNLwxVHH^f+%}y`I%^|*cR921K)A{}#ikINWnE+__ zy2$;%Bf)Qd>ogqeyc{m-LZ4NT`r_M}OL1cA1Pln-$nDEW{Uh*%AzF@X2K9&o{Q3%8 zdHo~zXCrp=_8+W2EaG3vpEJ%|B4CJ4mHV%qN^(GpZ=I2onZ?hqOYphF(GglByUOBM ziob#rkMUFgECSU0IsQ@!{)#&fMbGQTSlm;@zjXcdgW1yF7-8G+XU}YoAIg8dmyAHp zZgbSr68)1@Uk&l=$nNaaV1r%={L%Wws{`IJSN1_hz$*THw0<$yXb0w2tdQYPLGsT} z()yRQ7rkZm4T`@W4iC}e=P8Wb=%(cSP5NI3*!V(kqc!Run82@3`^$O;=i}GLH1u&2 z_)`%4?Urf-=GwjSXK;URPxH^GP5m%U+Cy@Vm*BrJ(mz&yZ9kTHB;(l;fiD`rni-5n zMu|N-7PRE&r~2!?5mRug$Q8Qo_4#qCuXY=jj<)%$APqQE{(F8mf}eAn=ODG3J3=-I zexUl#pWHMAosUPdlX zjnLrFuORp|j2nvewT;p9hwA)tjmZ%>-ra=9E5bNFZApEfse545J##$jvXT48bdp~l zE9=C(8%Z+|@2QSYJ*55`r;V1#Ra?pJX?*(C&4Gf9ShDGW-P){>utDih0|mHE4^1xjoG5_p#tVTf%>yj+)F46{u4^hCe@DpU_?Eyl8IGrb_<%Ra1+7x$qN%9uBCq zm)9rf{B^*o{+)24Y(GCv`?E9NcVw?et23j!UHNfZKS?fh#FRr_aPg|Z7v)d&?~U0F zqrXt3E)wsL;L{F+uwYjYS^rIfojiW^xzmY-8)~qC5)ID33KGA@-}jJmV{`1DCGbi0 zpD81|u;Tfe?BjncZ8(1s{pa@vPh{&@U`cHeztZ~3f;H)I?v^0qPg-9o3Gsxw!UC@~ z7m4>v`U4Dge350)8>wT*RlZ+&|67eE$FXO88WOGuex&%k@<3Yu>S+OsReiZVtzX_c z=Z6!ieQm z-}|Hep|yTb!<$rBOl=|XS(oTLQJ-F+^|K2|4E(|E>3sDIt7f5%*pE{ zkH#$N8*<4)^rxi~{IysS2gk&T5B=XQO)m|SWPwm zUHD>!CUaWDwqG`X|Fr&5(yb9Yd$j^(CC>af%@22v?Tf(e9T9L!HNILbDuMBhTzK>h z65j{1K73TK{y3!31t)V<UpeXSczx6e>Q+1X{n7gWkZyWx z&2UXNeWQU&d^I}biM@K}I8Y++Mb|%Q)zf3AEi_rpq)L2|`v3bBFZ_9Ej_if1@%87y zPK+?Er!~fxH{tdrgdY!H-Gfx?Rj^%lkY7K5@Z-)~(_rr8f<0XtaC@q+ z+68jiS)M)-4EHU1K|bYXSWHQ4l{I^3SlZ+K_oiMZ{iNZu{- zL%P1Twzm$;ZB&ODg{&9+M(}rlN$cCB{fVloPyQOP6F$-!$^Xp*26GnPq_fr$p zz8A{}klFUMJ+yqd@lY5ilj(;)=STo32v0-v-$E?e3=OmCtUoIV@y>r?$S@NhPg{nnz% zY1Q~lO$~(NSs(P6(v;g*5PaUdwi_E(t;CYd9De_)r2o6E<_r`YxxnnFz-J-RXKK9- zL7N|LSYRmfC(3{MO=Gb$Z>+RFRK%ZQ1fTu(Zb9VrX!M_5&aZDs@Ht;U7JJgi;6j>e zeA@0ZlJ*B^j1%ouCJ7-F6Fv1b5!aL%3cpCqIX#Dx*>S;E_#Qcr58}T?nI@1Gnszc zMA8>ed^W}4mCLz3?GH%pu@i%{m&x!)I)hDd^XJrt%-Zf#@?DD@LK|fj)>E?8dL}M)E_m z4kz%t$yOB975O0uKfZktfM3qNk-W%|+tc{8ASVYU{nz1p{5F1l%8z%HqY>g_jmV#( z|Bd#4Yc-jUQO-`X`ov@se_Fr0gQQb=Xw~lxKR=B>ZCA~QQ~RNae<1o(>H4H^f1;pk z767-F#hf2$fA=Q)RJ`33jZfJEe<1p2wP&%|8aW1qUq$^qmE?bu_Z!0@tuaDs^S=};`eJ3Z z_EpyZd*t82sCl_4|8F9Hep)~5qU(VB=XDYILg2%VtiNdQejnvoM-kBcEw4Y&`1Hul zVX&;-6N)IouQWbwyT2)0KI|8YTGz4W`5VdqIvV-lawjvm+!WWR>(}>O(qnICs7+h!IYXaC zlxeb=^~8Jv8lT#Yka{N-x^PGm{;x~$7xusn5p%m^@@x@b)BRUFj`BtuKNF1i68RnN ze^Y#@&QcoPL8tzQY&iaiesZFoCw2!KLH~3dzkj;EHbm14oo$VgVJ7&C#*gpT`lI?= zX^&Yg!A}$)?jA>B*J1+>w-@-J`bhFmU+i9GCW{X#J|>U8iqWq!V76W0BaGDV0&fOl zez7G+m<7&kB-OBMn`Dy)}AZ$?YgTt+x^XI4a^`XBe!^+VCm(B_Q zHzfXlcfc-;uaIUy?mr{WuawVscoQ;TT7NSbVNc$2|4kIN!ho-@0qzj=hKvDL*av(U#pCQi~n> zBJvYjUqAoW3biYmV_>ID{(dMvTqE?^_xl=bh)ElsGT@J<)6hl`fPa}O;%BFxxf$MpP9@XX6udNtPt@bt>3k8SA(f( zmCE8nTEAQT$rD~pj8OI~r1Jg9>j$?&YO{<351_B(rR4lT^bvzdAGEhN!O+YAZXZVK z2dOssD0-cOJ)WxZH^J8*ztYSwAkc~1Q~bppyoz6)GGzRuP{{jRo^|rWsg0&sQK>J} z{A}*7ENrU28d?)n<1eQ;NLt&_8*Zhl26C;z#SOFFtfM zf#WPaetn9cSkv09{N_E>x_MbC_*>o|_VB_um`C@4zP8Z+X?~^OZW{XSw#T0@wfOm| ze(^d)stq1p3ZtW^#Q7C+{;KzGF6PvhX3Q&}aQsmHaa6x>n6Gw6MKAE{;Yq-OBMp^C#tG7tH9?0XeQ~`SmG&2I|yeIj>5AiC204MC;p^Zup>3+W)4r zoxooi!B2^01_JiQ%l3~6Bk^BWEg#ri?1edH-_$s?nq_`%>}%ch?F2QV{;q*YZMGcSGFY{P}2nxKF1yVrMnQuq4&|rBkgnI}`91dal0W{ge4b{W{y@q(dt-|0MW}#)lKH zv|vpNej?gR^v6;CBHz~qjvDQ&?7w`!+6Dc4w?~tQN&Nbnq&{80`g4p4I)+?8@+Z3fpy{mNnDpt23_p~g9=!6zq}M%g zw)!0LeuzGQ+5Ib~YMw`HV|OL@Z_>Y&vD6C=Q+lF&mcS2PKcxNL506_IW2`|xetwFd zhyJIq`t@eGEf@Sm=dXA+420Ts6L{Sc_@Vo|UiQkB=3ght@MBB#2b=gHv^s2#srI5i zM*FuiY;R)Tp?y+)?o#FR$@?Rx{GNoJQvdbP(+Yn7l)rBK?}WyOXsoy?@I~h<*Q~h& zUz)q2wOR%De;?96lAN(qnoqnGj;1A**O#w9n6Nk+ZMu5GV&WBUUqInY+DF03Mu#@7W7U(xp)VC=9?4}s7xh@S^#ayFGdwKj=@!ko4 zzO_YWnpmGl_4|{a+HBjaZzzji!k<5k#E-`Yy5L;1cDU6*;M0xZ^HsycC~C9@<&#DH zNbxycD*zpS8^L#r$lqxE_~Wh@b{*`2kXiztg`~gv%$#kQQWzn_C(X|ir1|HQOAXQS zg6jHp+3qXoIcOKMqg^WfN3P#5o$Ldn-#y{<%5Ssl0L%MrfXv9)TV~BL1ZK8~I}gQg26L zsq26I{B*wg-a@HANjpEcO%G=aZVq96V@qBnfsH^!IaLjR-rTg0?hY{QD52sakr zXIekg`C*F*@!E(Uw1dBYioe~ho*?w`5hTA{Q2G6k45ZivviLO)3+_|y#kgt603%kWA0^TPvQ{Lwdr+a`fe zs_*+vxr#GCcH(2QYJB>v_C>-QX$^|HAAkQ8pItozkY{8h>#wBw-R{TNG3n}VEWRc1 zNA*cPk5Py!HpVe~fj`Qh#utvE@c26Xu;0o3H<|1oy((f7E)VOCc>`MW`)fkh7d&V; z9ic6i@LDGHN!q{VXkCInJu|U%vB&yW3G;4=nMQi!_DZZQoYqD_(#c+CXpXYb9 zf26wcDA=bOA>@kCXDGj&Z&;lzk=Ea*S>_6SDdqKR8(%++4etr;38WAHj9HpMo@;UQ`K{1l(D^_sDYBk!=NR}Frg_Lr1* zbH&m}I;gWn*wgs5O~Mnb{(cB(P>1s))o1Sb4nSaOTTD5tnjepKtH6)TXAlyn$?-?y z(_Xbl!F6OWjIAl~OZAyK*85T8RUF=^KdiKu<2NxW06Po}VPLj`KOg1CQ%80|qa;#> zUt6+1Xm*YdUe!0i#0jePnHR79aQs#e+>aOhN9zYuO&Ag;ug8HyB0dF)PlvwrmHH!l z{2yKC9aqyI|MA zQor;2eLtU^_wRA@k3a6?bI!S^&-1?C`-9(hzU=v^KF;&Hi_i-@@Zk&R+n40;JYNQ3 z$BR~y{5H+swb^hQ1Lm*7^;TRT>3r##?}E{Iz8A{Ncz!#F)OTqX7a&&5ujdw3#ZP5Y z`?ce*D0K4j#;Z}BZ<=4&m9+yOS0urAAm>|7;x|oGr=pET2e{67!1$)~2aV2cgQ@X6 zq?B>}l#%{~#2M+>FlG{RKk@uIh<`bJ>?63R?L&@5ZRTIn{shh7=D2W1r&_*?)1L`b zk`D_9{dTF0uZ|LHXQOA7+FV~j_+6=V6kKZS2u;89_&W73-7TQdzkg!i zhKjX$1&3_0CT%UdK8>%+_Kd~tH?ETYS!%xyHON89orQ49FH*^8YX6Zqxv?pB%;Nqf z&HtsVYYNZfZdJ=?|K_9M+ou^)2J!bt^AojG#QNk_&Csqc*Vjmr-z!rSU>Ti(&`{1N z&9BGR9F1ue&CsP)2loA`|M+Qwx=^e5Ix<`B^!d-er}3XBGefZXuczdE5s>`)*pW4a ztQq1N0@pcTH2!09AOvF_ys%`L1-pL+;q$iZA+#R481CbaR^4C9XT^dkcr?`;0lT%? zdK&*3|86J#yh_3%^>chZ;WMVwRJ1Pefy23bY=791_)mqHJ8Iu!E=pE$KB@lR?U#x% zJBGo*`Vm`iNchYUd%G}d78dU+X7{K0!!3m_xHC%|HJ)?(mg=u%6FVX6teVhkMIQTp zRDUnc_r%u;23Yi*=NGAc+`D^QSWhy<`awI{ddg>A3o}9J_8ET1d$Z4}zMB8`!D~BX zY(Ar!&*ZIU!X$?;aCyz&Kh1w^xZDjJf7gf6bFOcc&zi>_g->D*>%8+m_Wr28u5R8} zoX^t`S-zZ4T0geJ`iIyXs>H4>#+*M=KUU|*Xw=!)3S9zp=6qB8+GtJ;>KS>Xg`EytPx}L7MZP^vld$4A*WV(-_b6oy)^+v9mM~sF zL+h`nqP~M1?c*B z00Lc?R_$+Te5pgM7p`?PsMdZ~jB*yfAJP`~Kib+jFIFbig=ZG$TTbfJ5*M2bX!r%XU-|o|_VX^s?#Sw2A3En%^Ih53 zNjP4pB^aLJeAD<+TK51r2o7I?(b5vepUJ^84Y%NSqMQxB2*d8e32MldhEL3T2`V z>3_6}Uy^@0{a`eDCO3uUGS&R%iTAE$yc(Cgs^)jthd?YF*9<#W`my^{eSTbb5*~IE z<4+@1_XqAit|x@MK7xGWO&_k`QvcUJGz8<1wM6~`&L_>kX!}ONa&Q}LT%gYGPx<@% zWe?u%n=j4)IM1#xBmCvhn+o?6?Xl${=P#esx7A79hH=XipnL5eTTl5L+$9Bvn)b*0 zmsc4-8HB%z;w&t+fUsioTX?#~F)eR*YI+!UOVb4$XRr7rcPL=n=_>@KL`f`$g z*>TUcxx;bZaw zW`75e{-(vl{P3%bF%BQx%$`4m@Ok%?snGw$dz3y>?cXM}?T#jMEKoF1HJ`KAiDxse z74X??m&*9>Q&|AE=`}#=qt)#Gl+U2J(Rkz}+SbApgwmW2&!D z&yGN)r6XELaz1JNY30H#IF>f2T0U*F1L5h^6n9N{e3!;^mm)xunL_P4px9%<3`T$}-A9)oj=9gRI;yv@K>+4GbG$$TT!;b^v{Hwh+sy;W6 zd|vS~7Uz2Vz)Oes|IzxK)7FnsVY3@DSKePw?OWaGg|HewP|_bk^DD;-vT(O=90b!U z{z!bc@5C0+yrqq-prh>hD1XOtywF9Vhbcw7 z^pEn@ri+6RwMAW6za^U8pW3$zk90z*Q$0jla($)x_w%u%(BXxK&?coZU+*i;uWZWf zfhMah;1{mi|2%HiOfU@97WR$(SAQ!#zpUxkKA8R63hUZ(zG(b+Z2hmW);oogc@3EU z1(5o<_N~WY50=J{ zXnw`a~!}v+^n(Qhx047Z_jKCLvO#9691LPmqyhJNAmKP zC|%F}QyL$3TQwD{IeDRedI83$v>FcCo z-G>2?8F2s9hUnka$6*K(>z~GNJjuQvtuGikxCMGwYE`R$oo*!IN_r3cHs<*Ydj42^ zht{}0R!=%#pUkhA+`X|d&$bdfHpb;<9OovEf$$M2f( zwjzb;pD)orWqxM}E$SgpM|J(r{Xx1yn$10Y8+M!PH|ejReV_+i1#?(dsMfzx_1?g$ z$srW!nW~KMZaUKk(QhoFnXroOPpW^~ol9|}&j}1Lvt@i1k^aJ%B=PL;=gn|1k>8*C zpAVaf_qG#jK>Bfgyh!+TYc~qxJRC6jwQ7Czn!5*2N~^C=NbEWq$21*bc9h$%)c>4y zYYaM6I-z9jDE9qme}=tST6p5>a>VqSQpJzCO?z zke9cr`dpfyc_!-HoNRY&3*z=Cjn5j`<>PzlR=C!?!tNhH`r~y9qmkwBC9zNGe6+4s zV((P&JS=;4j;#+Q`Ip=g@rcm!L*RVX^J6~jUx11YebMs@ukQ&U{OPSLKnv6D@V(3D z8`Ahrlgha;$mj}vuV}VEeaZZ$&D~q$=6YR8eYl+PHE@!n5Td0n?M0<*3N?!+X0o zY<(K>4>v^Y!tE6a*mmy$`~LC{()znVhbWAD)l#exJXQ66r2b$2@VR)>w=<02gs|%u z5&zC_v)CK>%+*qnu3ePoWC5x-;uN9FmtjKHjiG+o?oAwFC7)~7Y)S_`oH-VMI?V| z)NTS=r8>jwRyvnlU5WlpQ$GhY_mzll#rZ5E`Ae^(5s37k)=k2TVIqojj5lvU?b(ELYeSP5Py z?nhB+IpdS|Cw|^I6ye7kR?DY6Url&7HV?fAXnOz0C)LNRH^$-1d`HQAL&|5k-C@j* zOU9O9ZhuA+K3_f@jfwI0Fg0Dk-cJe1fB4n8fdaGj5oZCH zx}JIk-qa9NWSs~2{P+B{|3g<8hpjUmanNHlTTl7@>Y#*aE3pQqziNJawFpL7unS`1 zdseNN@|#$khumH(aHe&dft1U5BoAFpf?Qt`+i0KoZ z5A!)^7VL(##rT;A+5VT2{NSceQ&7LT2kc9^{h2}dI9|s=Xm(qpT~>FQ9`ozt?%)5hQ<@kJS2H zzg&ratsD{x$C74}^FOJ7*Ll?rtZ|I1R=;X}n1H4Rj#w2uhdn>dFD!PD3EjdK7?i4- zkJIhPLebG4=f4bN>#2U({Zb;f<}yiqh1#Df4@CR=j3ee}cdmMWQvF)C|2(?nFNgMU z&JT$FdHZk}Qa-uhRSkExp62i0YK3CU&SrR6$oZlAb*9&KG+Va@``(`Q`A@&-e8P#g z(Rk?JLacB7%lM)F9gg$m=%3ae`7V6^C(ZwT)0~5MokhNGa=v^CU#kihBPh2oav$*c zsjqKsiT!=-X$*XadmwZA>8j_G>eI!eO@toDeqr$d)%7!1wLEb`(8S=`Jbps?n`Kcb zcnsbqd<*CCNg3fUe2_OfchJSemt0>ce}`W=3q#dp!V0aa?EO>w5)C@xz}i~X=HHVG zG=%Qg&cfdJ5dVE5`G;dh;%rr86IAT{$CuRq)9>~YgFfwq{MvHv{}Db<%^rs3!3`wy zW2paE`0fLY!*WpCit|bJDZkGI99q;wVqfMEK9`R=jL%MDePki$)0gnMqjCZY3?0y9 zJNN%mh<#b>*hCy!>j2{~oImQ{wVWdp<_KpHx{UKzMD%HC*D<&<&kjMehOqZf>(4tE zE77}Nnq)qcjMT3V{xccfYCB8LKcxD#IHnv2hMq((%`I&I(fnT9mJxVa?gE!+4|acQ zKU#&W33g6E&nDb|qxGx3GsCd(YBN;ysK?gtAoVk?j$TB|sVh(r2zGxOAKkB*idnDS z@y&(j?{|>=#K&O?Sh}^nB>qY3W32R2@v~)5#F%jZrik#@_{~&o)Am5m!<;`k(Lb%O z?$EYVL$Tc<_WW`m3BEG(k|x5(X+P0iS2drf1uqn~)xy(Jd--}2AMNN=AyjlcE!)Eb126n9{$-mS7|Ll9OvFGwGV4lGE^d)@mnKKNz5n}(==Z)<9Q$Dw)O~m&p zO;GlQ=U=FO*kt`-T$?{nl79~*{GIg*M*HSYxbMG=U7yBZx_8zT`n5hQ(MMW8zOc_E zEKzsBE30_6p6cWEw5J%mVGG9P^z>2X-$fOR{U4rGEiD(Q3FE{WhdJe3-za}~?}Z~F zs~LuQm{dKVH2>Z<@*;K*S`Pm*1^a$QB>vK`?hIV$+7i~Ywb*)^pQuy!IMN>{V}Hn1 zww~6Hw|*{1*}1m3JK#CnUsOMxGv(+a)?g>@Kg8A>lKAK`?^N9N?SZjJc>RnkiNENa zo{9~Z#8c!(tLFFWe0Q|pB*XNo`Gu6(}S|a{H9VS67ZN6l}A$2quq*SMe{Me^c?P3u@@q zmh^80kouX>b>DHv^f2Trczqt__ub+?co|hslHaHN{?aZ+*BaX)>)Tl+zsJpnqoI~H zVjBO`XQ}<0-sc^bMD0O(aVzit`0yqEU!$87AwO=9D1~aiJ6RrqNwawpeWmtqi{TL% zQl}Y;^H;L{N9T7qXHLNG2aP53w<*6drQ;BiVTWxIJbp^~tljGg)M{qK<;NVh|ET?{ z>pU4DGaMxI+bF+Np9Y~*2M6THoY?balKL0V;&6OB-W2Kkx&G1k=hLSbVemK|#eY@v zSH373Z=#wbW(q(5llDJ;nR^l)Kc!&vvuo`6Y5nM>fr+SB(hen&y#I*mV^&}SZq95A zrTJmDK9KO&Ysx~X|L}+PiHmH1`x5>dc}|Dvn-(~f&-u$F`gxDpslIu=hjx zTjc&!=+SbEurw}PC4a{g#rm}b4dAb8`*!8pb{LYZjfeVM*!8LX`a4Qf>GD@83>iM3 zUEh$zS4?koK_|mncshMETTkOFZ$~^8?)Tp!?5pR%*3{RoY=4UVTS@H#g*C^Qgq4Av&qW*oe z(?G3Js^dG)uBXB7bRTiXcJr#=2WfxgVzfhmpoPUboG;2};sF;S?!#ZmYQ?hq)A)`@ zGk+|!tp%NpoNsEs_GqFn{OE86W|z5rPx&12x)0`Et1GGRruz4LjIQu?$3^6wHDu2( z_mT3s-e2th+hB!1@v8ZJXZH)kCmu$2TVCHr^)GhLD0n7V!@zhs`+go^MAMN$0H`J6(-p8_zg(>=8HHRWXt9*=&r^4C#e6}_4o|*jB9}v ziJZTigui?BJzx{@S5aMmMcnf=3_jW$0XNrhen|eIPqr7fX{w{9m1_N4vSk_KZ}ovk zYKyAh1V*avYL;SwT`=_XVdSj!y&_g@}{J{GGKC1MymsJ>A z_Hw|8u|ZXTKPjINzDHnZpcC48_hFyY`q9t_p|?-OO1cReg8pBDCPDY^)C;0pNbxxTwttg$<}uw^E>v0&O)D9cl_4UVV_g~alKt4 zLOohb;;VFi@M`A-SY7f&$Ije8r1jnT9?4j-+E<)!d7SNks*ksO$gw%G6}008_WgGd zJ{=yrV|e@@#j^ljKO^&%{QSwxhAhK%)84q*hoA2&Cwvas;RXFRYRFvA>qDu3Xt4ON zP}=60aHq%mD*sN(r$dG}?j&nLXts|+E)wq9`LiilK@(u25Y=`g8gH?P<_3={c;TYe| z0^2%oV9!V6JM%p?g*IbOBmWi8@6-6J_Tu3GGF zUca<84qB_B{Yb9AAn~7GYtk|DKyUn9;K9Bhtsjs4;SCMV>iO=myRoo*)_aV-7RcT& z&9Bso=_b~<>m%wUw|}XB+V`xn(yZW~U@h8d|Lw2*4$}S(hueL``Ya>NY0veO+P{qh z-{8!1aYos-%_{ls)o=vX)Ud#Z%bf23GQTdrU;^suHpJ*2YpV92G{3pT^$0S$$kFOh zmA;bstgT8WBe<-QWc~+@?_7MbAB*2q&u?>`aqv@XfKdaZ+5KsK&W4T}LjRX1@c1X^ zm*)T9&Ypp@Zq2c9!c4Y4m&9-F48!5_-Cj~Z7fIr`bt2Co|MPrQ3|s8O^;>HH_Bl8K zD?Zp@j=62s`;q4Vhm{l~bXPY1ZaU1?Q+@sYD;fvmoh1G%&7UOa&4FEI3*28)gIyma zKXPP)SpS}w0`*$|`X{CS>8c|M;(P*eK6<04Z2uOK`Z$@|Lh<}xKXf@N@Xty9#Io%y zSUS7m?H_LcQhgm1>w(0uUy3QsxxV@meU+_WhUD5kaWjD1zm&fM*R}{xR>N*<9)Fc} zkev&8 zK}XQoFCL4osOBfyT|B#djx8FP@%$szKc$cZ-vib26Y+d3F8r{gH&es+-hHj_G< zg2}fNfY(5u|Mqt#(Z3coXQRhqSJ=tAqxpUF{x=c(cNv2B++*u$e{Wc75PE&JfzfYnU()#LE64FLy=Mi@{ak-2 zKi^-@!jTA3Uk1dp`%`_n_G}WC$JyZdeINEYwf}0@i9}*=dr5yh?eA+cEE2a9>?QpV zX2gD*91;(cwr==VkLv^NZ}8ZC8_Rbr$LMd5e7Jr|^&#rdTzu){DdB_KZ^%u6rz#VdTp{EY@O zPOA3LmUXok?rFcl#aI|lCjiK9C3OXUV|Lj^V9tMG{ta)mYSf!yLD`T$%*|oYG4I=>^lJee)ZY@r{`Dy zm@!eDPiKu@30$9O{o2#SqiAq)HlD8K`XrM{=es?Mn~aS+ZQvKRh~1youkA~@kIhLd zCH@($zux|MA|h{COZxwEh(1k8)fA?7KaNe!xjxbOX4ao6_+jdRIm!rje`6Bg4EU-p ze5`Q{{WYtXnqxSp{e>G!kPdKzCz{}c(s&y7*%V{>+Y zIv=&+ynE5>i8)as~Z)t>o zAIoJpdEH-9|CUMYN1aoNu$b4##f`9b#mseTTOUJ7N`&InB6 z`ESa9Oh7v22I_2FIyrMb(7m0m&Y4QM!eQ7AMFKK+{>7P2n zv4pE)jb}^t_mPqO;;H;m_}bR2+W4vM3SHsLKGD2$e#z^%WzzY_dO_o%(b!V7p?LoN zCb3V88hjG#r?=vp!A17_LG^R<$WU0HX$X&VJbp^&$2s+VfC;YE^S?)T0w$~$`nDIzIuO4!KFr*QWa3>2x8k1+B%J{V!DVZT&k52fusb=OWHGjlWvN zC1GO+PmGQ|!q(IJ)@-B2Ncz+P+uri}0NUT*TrUZ0wu%f#%7(2`c$cQbwU>gdHrycz%=mpKs^o<97`y-?aX2 zZ}fQB+t$Y`A(HV)^CS0PX$wXjPhg>1RsNFjZGA8b%g5QFaA+`FPwUeY2bQ9Co$X?c z9_O3Z_oy|GK&Nb5iGND#dmaoehHbA6*uH5E+rRXDt0}!AF+R8vH1{-P_wVT^^Xb~dc`oQq{IkukG|7`j& zA6|xDkiS01)`QH?`D*HksbSw0eMhL)?^<@|Lh9_>NI1m#krDfSx?_8>f8wvAI{#Nc zty~B%*e6`FTBB0G2lVQQ-fkM$e11Fo`%wL!vrd7Y4#12<_V95xA|`D{>FaN{L1IZ zk;ooW4~l_&y^QevyhS;5KJGzDWkbd%&95kGPC&0s781Uxes`Qw32WE==xD|HmXr8w z;fx5FJr(=EZl$sJN9QveH!i@@l`ACnJLP-nj|rIGslG(N<-~q}zdZ`O#x{a+%4BwZ z8b6w;{uTaJo7oO8LdO&{R|%#AMlaJXE&Y- z$Ijsm5mUhH_h@}>>CY?3i%7)`EzWNsIlsVad>jruYPI9z{m|8Swbb z{bQL-I{)=_heS-A>54^}dTf0TiQk5dn1{?s?#N%q`%iunemCzG&$iR>!pN(t`JLT! z5nRH(ak%^}u1#;YbyH` z9~JDzs^<5@?VcD_UIU*)`0opiU&Z{i7e);%#;lQb*!5|Cbn^1PaO}PI0m;zv7&$VjPXzT9pD#^c}6yv*pBB{ssF9Fs{r1$rTkL=TPr^V+r{%&vIAzZ z`_uYA#rh~T9&0Pkj|^g;Q~P?@sIM@&z7@XhIlpxNRqxf2*e2T7*=xG7^_1T$D2C24 zk>6=m`b+BnjHZXdEvbRze90Xo{~0>sD(V+4l<*rs_`R%%!GcA0lKdyt-w&FFcyG8G znl6`oczjIC?|$)YrRarj&|OiBJwNSF>5+H`6K*WU409e|lau*9l{FI4+om}Vm+}5E znt$27e+djTd~sOG`+I5qQ8T9$d|Ks+z-63YYF~dE?1^`0OBK#XRP+0zkC}k;*I^gJ z^B*#qbiON6M1Hf%6|)-bW8aU)pLcdH7XlLZ2>R_*^Sijb6P}+|N1xxEU#h?RQZ$tj z-Hr%lhZ7n9nM8k$jeBG1?;6-2!}XW)yZy1fPdv$O0Z z`O!>LKlrTiQ?z)#3cu1+^LwXaE*^^ctGiPco3+X&wj@}p|Smogikrij~-e+STMe3B*@NcFg~chcHZs{ zx!E6y|7%0?L!D=p3(7gW1zio*d}g)mj3*lEICqNkN%KR4vNe?pJPr%{;#Kpx;&N|v zPOX7YS2>^5KK_|yto){SS-3uI0(<^kVju6Q2tcNuE~feai%(1I1B)6Cz(*H-ta--m z&osi{6S2Q=;1VlI{}|2hbQ@8LO!4g9=LOuprSa)$`$I6fttHw%=lLBvAN@(shtOV@ zF0pUv`LG^_F}U%$AyzJ$SH+L?d|2b!bp^jR=iygg#UJrs=LCMkk%3zz`bhZ-{~ZO3 zBpcjp*_~aV^3^Zv*m|alFJj;3t(XV*zOJx$uFcld`ai+891S+@ z6z8Lt@%zi9`KP~u$?$FHf!MP=K1K7hIwhrW9k^M{4`?y|sQ;I&D<~f!NB|f`^uhUmEK4|^W28+&ccT$t|fBKU8-40JRl_#PP2}Lti^Qjx$8ws&G zlK2$W&$v`$<%zu)g<(14Rr0B=-XH2Kbz#|f1N(k7{+yuOK)LqieWCbgbGF`)_^)L( z2jF~HJ@g&H`K9L{)EpZo_7+=8&UgMy;!odS|3Zk_c8r*t$Muoqm$udqLxP_r*56#j zo{#c7WXdC)oKE;9^S2ZMG4QZ!2<2$i{GR_l6{9+c=j&F*k9~!Wlwqi5RD(d)`&v+YisIaH zbMGts{$!)%CFhUo-zD+vlb?;+qUlxcf657eb<&eDzmGeFZk#_k;jgT%7i>m+QUpYE z`<3!n(%4)$`TGhw_u%#`YDFl?~m%Euv1fcO6#ETs5F7?e>t&V->&F|S9;pw`7hi*ruyi(*jBicoe!@{9d>=% zzw);8P&9sPfap8?`_cNM7CH@-JreH;>*sU+^a+2xvWCM`UK@`LdHkF5Hz;Ew`aCni zudgfE{fh{HE4Imm!)m)RBD6|BNqp#Nix_b>hYbV+9{(*N^A9%kFN9g_@@n<-*WVZ% zSY{*9PinuusT~K`KVp6Q$SLgkWQ0H8&EL`1VKdVEaQ;B-(`K`R5g%`kc8lAy^)!F; zd_*MdVyv*_u_OCDpYSzr+es95jD_a8O+HLti9Sxria}U^8%h0zoYWhpMg7Cct2CAC3vz_@D^>ILT)#KAE!M&YIe$K? zZ^Jd;VAIJpurut>-VfzVsXNhRMWeK}~5sA+%8WV$qZVjM+joY6zK6C!=30&VZ6(&BMFPi_n zH8>J(b1VTH19ty>!dE+G0?zeyl=PR-_-Wm)3o-SW2h8St=YN0VzcmY42;sE{ERP;z z&o3kO=SMr)3--Mqqvg#f?EZ2eY5mgpHVZLpn+N>bUSR8K{p;{oUf4V8L$&(#InGo# z+~)$E@;0&SQ@&Q4wnyQYQpKB-oDa&^b?tH?Nq4)@Z{jMZKh%CaHlQm`bd^cwM^gPV z*rur*|75?=U+e?_@Arr5mqYVj&}*uRmg-!82yZ^^mVg!mSETDe9Bm4VPeOi%q1!FoTVO0a}-+}P8G+LZbzR4UnH`}rG zw7#h0?^E#BpN=}UGTHu=6a6yZ5RP^eEwFFWKYfzsFS=fnBTKsp-uBjH*DoRYi92sn zP~)Z>NSlA1O%7?h}{V`il`AHg^0t-tw6c6O~Um($^$Mahwe9wDH{U5de zWUuQA7kUX8xQq86faDK{w(v&zgHpwbQ>yjp&(S}E)!D5=+ea%^@-uc|S4?|bp{UOO zYkxyinN_+^xX@8GKf}Fy{p zvI^w&+lEn=y#Go@?7!1pqcFg^K63SWeu37nSiP7>`|mShdtj# zV&Cl;P=*~FGsXE_+`cO!_MP+32yE^p<%h;cypM;YG|n7%^BS}3)B2m9m!omW$r8Kj z@c0CcZ$#BUhgaruOiw)S!~H91{D1psIU0>?j9TZ_+4X6Ea&Dt!Z13-aqE-C-@qD5` zGY(!sP|Q5MKK7PfpX!gl=Llh6sG%^{umS&lCi=5b?2qd8#T8~}Rr7P~Y->0yepju1 zH@c**u%{7F&zJK<^Y2O9ebBAjSH-{ij?{meZqiW5jlP9@#}=^fPyMI8MP2c-UWMY{ z`HfV69&~Ofe9XCpE;oAc^~8UAZ_)?e7c?aP6V)I2)7NO$WEJxJbm#g*=F2(8421r7 z9rQfF;}-#>ztQEbwQ{}lO`&(5I3prnCjO)RjQZXm2Y+c}QPU;t`2q<)_W~!QyKX() zuF3U*=GXOx%Y=#3wqejhr8nO{()fOKs5rl3n3<%$oaX0-&5A+jKuhQ^NM!e?`8U6c z8bbH$2XHWNpwEBTr}eKMVr_2PBwO4Kn8w!MBz!GCUWTKuH{q_GYQBowMPunB3!Gon zg{_y9`nUKP0ka>@K=8ChRri<1AMc->3XdjM)!Ki4tt0U##T+#P^w{+&e{J`kL*9gV zyv(e+HR=P?hD%=p9z153`Yuq^$mr2(^d2Jv|=Ha z4{RZ^?;?plwX$u4p`mZ9_#(!&$XHH8Sys-KO$t^{H%4L*d^3n-ac!315So24M3_4OqEx`;6*SXVW*h`%b*~ zubwLTTID_v7Ei?UU#s%tl&{L?*2;QEuM18+IA5AXpMpjV#PJ{6sPD=3Ba-kX-w}l2 zi|gXpL)Gz#Tk=O3S9>vvI^R*rSHRjZl6EM zZdYIUm3>w`v{KEV-wSKu%F8Rz{*qL+UfLfrKgAyrJO3#D#V@G7nIvl}8~N`R-dM=F zeiQzNo(w?!#v0Yur_2~#PiT>*fZYOq{vFM4-+DO!Bl5K*`EBZ7^>l2YynX$eu&Rq{ z{sKCT#?K}CI3B?DpZZr9^PH8(?F)s1uP@m5_wbX}hi^F-B+dq_gU?GipEUm#{qhku z#4M8VN$tl5??Z7ZxE{Wp=Jo^S)3N&$^iMU%;Dfxs(2&%R`TeOOl*aEzL9%K-d6%MYq3S5maYAG@tYM0gYe8 z`oy5WlLa2TbNiCce~Z<-g!FcDl+-)v!}*Z%*Xr?H1YNSnQJtFX`7? zK3{3odTIWwVE=r~n&Kpxe?#@}qs>$C{GcU>sQHVnr}4#opGOD*&b0*H)#8k@|Fe&% z|7O@~F}9Ypz#_#(wmz5e>0sCv2Iop7_1)Beix_MnBwxwHD>bfgoa zzeV$BvlFZZ1INqa`Es1kOw#{2G{7J0AN*3ZkLUSq8eiPLUsIVGxl5?4shZCQx&e6o zQcW^{k;d-}>b-@*=@qz|+DoNA9(pzaF=GG!`dpshrhF=YS}T)#Uln?8Y0BO&)yJcA z$KYNQ1Gx71w_X}w^zEuC^cuAThht2b{?Yy|kNrXDa^47A3{~@)`|1hyy;y`nOK(@L zm)fTmgF>;$#u&?Qq_F)LNa7#A4@9Bg3R9RB&t{)z`bzWPJ8RYy8p!uyaWv;s?jx-~ zNqQ8A!85Ip9v;Eg)BM_o2S0Fq%?6~^0ZM22j$PIVuWyLpn>4zubQtfX^T;#OAFk5pqelF`!+~%dR=XNvE>2_ z;mZB9(0R`FkMb41u7h|!%cpAjGS+Dzv|oJ*CZjoDG`{%oS~nzl{Z{-t-=fG@of`+@ z|AUWdD*Ht26dcmy`R@nOziBN4pw~)GJb#SGM<`z*>)s;VQ9OU-gKEAs+YCaGp%yA{ zu4jKA%2(toYvrA?%YwZ#=SxQHPv7uBe9X|pkds{hT#5Y|GFwCV(tjH+8e4Eae5Lv~ z@IVmkUKnECZl3>2A^Ed0dE(ix53-@7SrtDa`RkO%q3CE{7mIv3U%rH|F-N12y3+&~ zT{&NJ!dK{TT_N}Fet5R1ivN@PlIiwxY?0X@W!iN1eu{jh@qdfo(YP6FiXqyZ9~wWY z{1J_5(@imPwS!7NdJLb2v)Sfoq2&2x8lRt@a}L@1GcfKBw@+#Pb6K-=d@%8ZhnWt$ zzMS}Hv+t$h*2tEa){pBWJwNUFige_z^@Lr`>x?fM$$vS=FUEbbzgT@K=ZDURsXWmZ zJ@&tn=##InWc$i~*Q_sWcRvelPp(fizIZv@4<@ZXDe7+8%buV5Z-;t@DclbB&kJIDSgf{8f z$QWbG_@L)sWZVuykhUT2j^=zs5%?_rELI|G8p)|I0D;5U^n;-ydZE zkA|L5fc?_>hGhSnjuZF4UxRA*|Dxq3825Uaq(4AL;_E-QMZsfBJ$SkC`b4S^8;|7S zShH!^GdA0Y>xo&!qP~!w!Py2hWJY5LGwM}8x!jygg zAU~=9b)thz@Nbxfj_Kd|dQv}CdujyStI@X@U%rH|b0!P0ZGaOz#_|3>8o$@~Ylj;TURK-x6FkdY2rX0K-B6zY$|U~T z+3b#Z?(|7fq1eZszlh9Vy8h5Y=yX7UeQh2;rt!x!lR^}FD>W6L&GxF~Z`%Y-<-|MN zguB9QmHK2;vmeU#$t3X+Lz4em`r{pTnJ$NXbDyf;A8Gz8p~*nZ+^&vJr#L@`gufdf zt(CHo7X|we)%?9VH5O&<^d$CQk+0PLTiilJ(73W0h6R?4KWhIOd=0`a$J&zlqk)7! z+sUC&4mHBO1Ig_DQvPm_iGunZW6AmS)V@n7(ig61=V0`;D*Yk(=bvli@jcE8tscZw zU0d}80VNv%ZAv`yj}iQjzK@29WS z|N1q1DcbjOL*W`3TTlD%=GG`gYPW?*f5+<|0|!^D`OAM2fI6)z6#wQkQU1(2 zeGq3irvv-?@#iP`Gv{CZF`$+jw*BGtPes1c`i{0%*2*}o^FqZJM|S_uOVzU#v#4Z49c`#RriF(?wFh;TV4v z`e$aL({FCy8Itn_Yvd%M@%=^^7R}?AnS{TG4=eF){YGq-SMf*mZ^n@{?B3&siSyLi z_s=2r>@yoHhSxa~YtF|vI;ufQ9V>8GKIDb_CDwEnFcJK>H z{+jZ4+;9n=4;I&ZOk?|(+Ly_eozUavd&QM_&L5pWIDYMKVf~wR!lFUx+#miOz56*3KO31^Jc%_#6KJUHWYWC)`nUz*GC%vD6AKS z`f+t|)Nuy8KIM0QxxO%|VlOUcbA6=oj}6bKLUTqv%=tc!tq&ma$!y(71l%z~u%kEo zJfG-eg_{61=P=xl;{4M3VLRm%xHdM1Z@(sNJ+)tz?UnGE5sshtRo90!v6zLC!^|c9 zan!$iQ9Kt*w%VZLyB51X&41rEkO@Z$HlWLdDn5xmmf5AD)92>Me8=^X){o4xUWPMG z+;H?Xw@>9He-Q7!6a`8b2u*qa0rl_tt!W3lf@jt0pKIO{ER%`+J&sk$-{!}i(8lz= z!dQ6c={gIfrF+O=ikCysP*ziDL!#7r8*mU0iW=QmNy7n@0wrz7s z{eKbhAFcG4B6nyr?7PC_GnvGGeR{kdy00mc%ny~5_{^!^3oypLG1~1K$ez!pgS3D3 z)y7UJ?)O$=zf%2tQeh&@t&xj;rIGCY$cTO}I2)qSj8;=zd~%TKX8`HH`94EaS#U60 zczA!NO8ZssLI5&){!&c)#rbt5`Z?OyL1@$c8V;s$`-bxSx9<>a?4gFY89cs8`Ca4C zNNB2g0ik)p?EBOH^HYu^kg`()lLXcLZp&5|?tR^e0cJdYL;c6*;{3K3kM$({QvIxP z(p=D-bP`1|s`-7hGz`B3YhgeeuAkKYUD+@SCzl(d&e?zQNooGT6Y+Sr!W>1O(d_R- z?b{c-qmeP+NbJAzWuFHUJ{#!+x3hvU=|1O^#{YXI#~^rj9ay_?eWdxlTa8ZRgT6S! zx5q}G|M;f!A12L+MVh%7AF9TGYhhWw4k*?Q_<=Ec_)o*zF1qqrmN z{n7k;lFL%uj%bSDL!8eH!lzo3_L!6PwA%hSccTT!xX}o{d%1rmBmQNFI~`GQ<+Wnu znLX_OG`_R%i-quW%SkNR9LGMF6F#T^4OSRf$rKscxs1<1!spLj=0dZ2ClFNT&eqfV zmrY9pkTB+l;)g%yliIhfI#>(F2NmKOrM!NK_7A-5Jp}IIGD-fO#&@o5ttVV_JObB2 zwp^ddd^XobqcGb?6G``ZevaC=d!Z&o-V)CaP~-DW>3o;drop(?M-RtbIp37ey?etj zCBZ=Af2I-reE%d0bBqkJq#M`IBBGyX{^|<`>ASF|*B~EmA4~Ihfq&$T-)C9!I~w7=j)w@A2J)RyQg<+s&n0eMG)kmI1*zHKuw23T%{VFT^i z{V$UGnD@`li{~RmKpCXkKV3Lz299nvhAhjFt*80DVV)^s?~g4?%X$9+^*;~FD=~M} zT3oMN#V4_E)x4J>>1H$7E>){~KeZ(B`=KqDVp4x+#O>nw5gLDW8o2~dx;tUs`dq$$ zh<G}$m`#P{WK%Cp3Y~nD<6XSzbX~aW^sL_{N+xmCydQKgvgQxRqszaUrDFtc+@?t zjbDvsHHOyM%D)7#YB+AJ@MW!e2LyDG0k> zTkLP;{v+jY+&z6^j`vQKHK^i`#DB)^n}-YIti%~N@$CK3^MOy>{>EbCRd{-c^GD|! zx~s*(zm~D2zueeQ8XxNR;S-t`EyXqewLYrs+nB-_czrTN+ziei)z9E(N)%ND;dFv( z|FTHTeH;%r#-d&P?@QxDqdP2s<5ydFD{HgwNBP@$X(=AOa6;4G+&-oG!xzhz!aUOn zCls8o9Aclg{k{T%`G&+kZQa#WcyjzO z2FiH+gVuk}T-q58ZoZPtSE2f+@4o_n#rlG)%DPqiS6Y8Iyd+eyy;0?vfA%TmZ+-W^ zaQ*#FqHi){f4YV@5*kfBi~GyD|4r>rt(ak`r6rTpPgA}UPn!z+{Ey&foKw~FN%=aO zG9I<-Ya`2-^JPf#hc3qIf=R=5xH^;bMfEM_W-#`?tcj_ns`YJ*O$2P^`p8eXCX}u%POyl+;t&hGpwLLCxexxXxs9JwCCYTDwCk~-FZgc*gsd4!*vkxgBzq0z`!Go_7 zJ~Dl!`Stnrhl}}#N=2~NMs|I=|3`MT6yla0hh?5G-~YtE+tOr_`=xsSTe!_ajhMRVTrihC zKi&Va8MTEKqjn+IvMRqo@^@q1t-y`G`!Mii=UT zu`%3_txqHVnb~du9?9e3_ksIoa*}_K*dB|c1B_57jPpa|mu)@rP%C{BE??&Q0@B~s z+bj;U7ImQghwBH;@5yzJA@J;AlofM+RWGYJ|v( zZ`j|T=JzHhEkl~p2^oc)A6LRp^t^=_G~5;?b9S)x8RUFj?^h`p6>Njvy_7yoe~EoJ z>T!DM`D@8S5_1|{J#R0{V`9RdZ+keGWIA(MRCRP2x)W1q>6Q+3Fr@UHza+~*s z&ABg%Eh978`|&0G)Yxn-oN0X$Uh6(`K1hE~!tfE;V^XR3cm5cSZ+tVe5=zD$hh1Jr zzMk;4Vft8{Y_5S$gI2TqQ@$3|u@rQjbCJ`39pj(Yr_AjhinqEo(fK0hi~3JVA0uIT zLl3PZd3}nU*l(`a%vEf$j

        a{o7ghW_C^x2lAZZ8-}}7H5Go-%<41O~lJGs>=eb|c^&M}H zqr)HfaX;%l&-*&BabI_t1M>ap{(>aqXgqt<00Z0BkmnbX{9ZAOLEX;{75VeBU6uaR zdD9r|snt+npJ;tp$AR%^tZIrp(?9Ee4LMPry8yds{D=(`_QPAIqfZmIUm z|HVw6IK-Hz4Kx+;KhmE%N!=4`T0B$mkJg8M$ezhM)G5~djbBjvjW3qDKM}KnrTUgq_?Pn~lh0e}%|oXSl7C;S@5X0H^~Ey`5%NUvkJeBA z2%n4mj>dSgSvUXIL@dVQXmbo^E9L8}3I8&Bn)8q^sW{(4H~(HeSc(nrEfoD{&B^%? zjlzDxGdo_|zZH@Ec}|PtC>lNjRxJd-sQuDx3B%;*+GtWJ<_8mgrMM*G z)Tfr%8zkl*C;cgp9SK2b?^7%OkdDoQyxpza9JMVcr)boa-s}=g|1!&sR$@(!*S_Kh=fs z&)~2bUr~1_{BDnsf8RV}|C;R%fXdbyR^3JX!;k38=Zk;i_qcczObU?a)B69EYpYPO zu`23pahIRpgv2k(=&e9l>q_XkHmHiQ#-#L!6JBEY13I3?4erynmW2b5=`rlFiYpNy@F3v4sv{lScApEnx7m3YX z?O}f9ll=Qq|17(8ERtF~py;OHU)ioT74g40pVvsWvrQEB(e!-Wd)-5@l@{$9&jl+`Df(l)CysqYA3YyV39wMBnH8vnRFb{qzG_@S_mlz+<#t$CAU2e35XUdvx){G)x%$#AWw4_oc| zew2TYv*+N!6hm}075#q_h<|7La30n*HG;LZ;2(`2jx1g#HI9|ehxwq}znj*{oSPm_ z!MAU^`B!CEAZ!On@sAUtzB+;MZ;FSCZ)h5i%WHJ=@AjcU_>HoLdDd9@`_uh5<-V5S zW?>9Mk8PCsW!^=ZAHT3-88%Il;xpR*l+^x>m~_k8yB)(6Mt(;vwt?L>^So|j!EN0evQWW%Y7J&s-kMSr_w!mri8=EGWwFaF(sO8Ip;e+jIYRm7=VLSLp4 z`&R2@AXbmILVQQT9~yt}QD+rqW?P}ttZ`cWDdX$gy;a<>YaD9b-z0v2;-58qw+!j2 zW(t0&i2aJ}cLL+xh9ccf=u66v>687ic8CSsBdf^wk0$!j_}nQ>=r{u2o6_X_)BQR1 z=Bz<&O+$>(_GeZR{TT6T1L}5bfu&|*zB%C!q}uIS)f?dHd_C>^EB&|6|Ep8Sm;D$JuQBG{7u z2-<}%4PxczQ&ekGIr2i1G8k?JEIl=e%djL+}uFq^d-`bEJX>fc5A zRN_1AcVhd{TJrt<7@Jhc}JjL7%x8`tshzI?giIk z14aJ^%D>TzYVZ?x4rAHMeNH03q}+enV&MXO8&&~VZt1pv%|H90m$ii={&Jk~^JbL* z+zhV_qZJ}QolNZ8XvueXc(DmjYXr;qq56_94?@WjYdEG0eVIn$mmwAXFr=b6Y|Vte zr1|H8`@f*s(=d$fepJ3b)t9OF{E+kA9ImZ}zH}k{oO3W5)zx)Ty@FU@Qwjfe7jM9( z9@6={TKg4E_}9%h9ve0^Kz_Wie>6TBSaAay{L>s2%RqjZYtES)Vf{U&>~R5!nB8Cr7R6FYJ4XEYP}31xlOw~RT=VDuM_Dr~llA3wscqH{(3 zk$xnf?G>TZKWmvYi`}>SRH{B)KE#6m*t8vO`ibvH>zj9t@@5lrOG>p*hjxs^o3O76 z`=ciQS4m+#?&5qJb}c<+{?PuA&u>qb&VKyO7BA5q|98=w3yZM^3jIg^zN7iCNb^d3pYIOztS$5v-5>Y+#yY%h*9eA> z1b=9KV|cDJ?pC;|h;Nv8QQD`R2A2HOr4)3#shdBqD$HVoHx+0ShOE}fAD=Zj|t#J2mh#6B1pnMg{o=^W z>#)hXAqwlA5%(wdDROirseW-g!rSZS-$C01v|P|oVZUg9R?lzFn14J=QNKa?_jIr& z@0GO!lMd_VU%4i;*{RM2n%;u~bn@?U`zqY~P6|#Q^pJm_WKzG_dDJZCG4O+?$oZ^1 zpZZs)`&sa@Q?{a6`)cxhYQH)yUdSe_DAM?Tx+VBa;v41bRpBpL3Ton_);=lsr=C^2 zLGRNiHsRGq`TFjJpL##*ar?_Bkh6J;JfHG&-`*(*^ZCjC=C{2_e6h@WsXo`Y90uMI z@eOL_@^fEMZF*E zrSmr$;ogB}@_c);KfLM9`xu$M0A2P8|A?ON{Csf&ejjzfuWy2XE`)#UUMHYa>xTGv zL-3F8kBgnT4$A`@;90e6^7nBk`tZD-8ecnPvi_TdKBW9w+Pn&{9Jd2?Hpa-$PyH{w zYF_MgN`WRi##<-9x(}VjoP*zK)J@Lox9X*(@{l>Sldm?@awRdkR%ZD?6@JG*g8}iKuLnQn4#6L{_epDY?oL`A1zf5s-k;qT`5qAT-;#nUL(uIA3T3LT_V0r@Lr#8USVFJHuwNk&0 z^_2SaWJ>#A=Nxwa^ZjUip~ACiy!9D9?y#`7Hh-k-KX>4H0_GJo!0r0i<@prf>Sb!E zr`=G*7gR*Q{j6-oFD~7I+DRh5KQBpd@2Ix(Nz9^G(KK$ z-fXtD!#hpdQ0T<}gAs^`e_Y5miwiFNtq!AB5& zM)Xgo@wtQ;H=KH3!2X_JO!;$CbB{;7n#XUAzM_48C4U@_PQedVv4TH-#D3&-H{@Gw z)*`uw?*2PF9?e6X)E`!Vw6HJHB)-?B=^~8nS03?Q!sYwZ_}(`2Kx|DmL*HUye<(lF z9RkpHQ$^%Vm?zH%(Raxk197plx%4+m9;fved1F;PyLSX?{1EYP>K~oIV32qQ&(lOxe@-5afg=WBb+UfMvuzB%!a_FCS= zr-M_mZcVoHAAW%NNAnZo;bT@u5x?_uR`P4dmQb`Uv_fE-uusWEpXIsS;!7UPeru6S&!st4dCw~_!Uj;$NODsj2L>Ion*p((E9bvuGak0r5*TX7B9aat*>30 zx`4e&Db(b74b;i6v8HzXc;EpP9$qHq6Mfcp>}>XX@0(Kf+0M~c-0#A6jE&OGulQ3w z>~h7gn&3H^I{D>YV8tV5?!fhhqCSQ4t3$dQEYm))=HqnRr`I;Mc;UkRm^8v!*e6mS z^}5bf)cjb)T7K1SpT1qbQ1Hiv)IY6#x)O7TnP6K5-S#E$ zs6VWoOcnKmG{5BG9*6=fGt4eGQvUw5eszv9SLK;cl=72b;r~HT zYoCS^CkxqoBWYj3u3#HUjIkDt4(_>C9aP-kblj88SGKbll=JRIA; zXZ5-WeESjqW1x|WA1)V$%Y>!AKrXCCZ)e+78L})s6Okw)0Uew*$H#g`eHue z*NcTyF)8~Ciwo1uuOYMM;NvQ(zrUXF-wG&yT$UoDzX4VnM9SZX>aQ8mzVK9+#p&w4 z@;L2pKdMa-OsbmU^_xZ7apnFDj}}4LTG~b=!aPIq_C}U8zbt&sJ@!}&YLy)_(5YgwX05k z7%VB`i@OBzE=|L<{8ieYOH%$O)$&ED{J7A(0Ur}^Sn}a|YTr-Ek74Z=vVPX@OXWvW zs*3N?gupjc^!K3kJ&n}kan$M!`*I{nyg#u&mf2PL^Kv_Ida<3>ektvbgJ!Cfd;ZMc zcAdMvM3~jgOrj9gK;i&0(`x@0udnWkfPVA4WV*xfU@q_*JgWCDZ{)lszgkZL`e|Ki@`ttMB{LYjo z@woQB1|BpK^*59sWk0UNP<3rAC=vFf38{Z;Yih$k+HOPbdPn8!Q~Pmz$aW;{ZHAOL zB0il)^x4RO`Kd!7EgKjp{PpX0dwhfhIW6N-rqDxswLRQdO%{>i@Dp;G@n3)mL+(BfC=zXvt{fXTI& zqcBUvf7N7vl1o7-zBH+X=iP+=LF?Bp&Rh%su$s`g)|IcHN8(>GLF@4CWG%eEUsfJh z5&QAFoGp*B-;TK2$K`R_zdgfuKJ)&Pufg%BI`JLYdORQV=`C(7{;8d>^gsF;d9$TQ z-e?>b43U37HSs?lG}hyqslmVjp&x1dYWcF+EO*PZQrG{g9cuE5i+1ABF=2mceP^;% z*U{GQjmA9tseFH`k8Gm!_`R%PRR6X_#wV?h`Q$ks8;tVVIR}Ans*mD++wi+jwqRO* zRWYCFqr>H=!KTYc*55!kz9*Hb%UiD73mfNPo%nuIG9O)xezAt#bmLn;YYEo0E(4no z5x=7A|NFZukw2q6M)nC5zYkgerxmZnmdNrrq&Gu5uGCKzY*wStz!c}1@IPq$>IF8y zv}Rqr-R~mLSCRN^ZcqZQ?yiM)ZX&)!@p<}eGE#gUkpGXBxIe+?q|k6YxLXMx^$t7# zSzisw`rT{2Eq}9a8=4;$_@(Q2kzW#KzNw4g8#m zt?71HnmUO2Bz|<_#8kZZ{J_ReSt~yu&2Q9wT!%k(-2WpDJK@te6`{+r)Z=HIK22|%mHhKl?JUB4Zx1mabJAzJ5q$%;o#j{KW9kcr2b}i+i7sJInfl#Fu*3tHxdHZNt^>C*=85-&Y&9 z3GZ&&V`lR#c|PsWGj-!~*5=Shjmo`3dtLfv%laC8`nK)(WVk{5e9HB`!$Utd^~Yz8 zdyDfje`tIuzKI_9+!lnyvyH^_k@)GB0kc_~C3%|dm#@kApz)>H@LIg&UUC z^L69j(rg+68@w+S|MMo>@keWSVwCYlo%nY;H6QgB6|=wn&#At@p1c&(-|OLhvRL1f ziN3eB2*A=psXxhqRr2?t`H6SCSE1R#3aHt5p*&9O8zUzL!D^uq@(+!Y$I}V^SEjGW z%QrPKvAD1J{vS z8x3mmZnw7KP;cG%&YQZ5wc1*uQJL20DCX-a)`$1TMZC%4m0WWuM5jLAzH>G^Z~wSd zd~4R!;{AMf;GU%x-$b8(S?Lx|<_lYL;4HgdJu$B4~*iShm<13xu^L=m* zzkhZd4|#W7GbN(uvQk3bpvii`(EhPv}n? zU$HvAgsIy}`r4(w{QLMhEAjdA@;6@S?Z-W(K8SztOZ9a?^lVl)b{x%f98|zMk`OVjC*2OjQ?@#r|u{Cvhm6fR|crEk?#c%VO z5`Lq;vcLVgX?#+>VHrNgsgRVZd;QIJ^FyD1^zm+kpL~C+KgPra!XnN9edC4xNGJNE zvn_zmrHimf%{Q#n$$4w1`{{d6Q z`kFxSJJ)RrfBF3#fHOEt*>%=FUQj5R*x)s~?9?STo@r`!>jz{HLdF=1`3>2SFyVl?}c{1EL zHx%>9`Z}uDG`#EnidB!%jn8QVYx7m_w?q9x^q-*hKMuAFaB1-uR`x)w{C-p)cwAft z1K;25uRfsrZ|w)IKvs|n=)7E>PuJH^7ei1|Y=r6AE41TE|8Itqlz$o~osSzmLLN^h z_$*gF6t{;MqyAx$Uy3I2y;}`J{;&R^O`SUOd^OPzSGUC@v!xYok6Z67?5nbVbnegu zjL@@1L9o!@G{1DDbv&$41tp=W^89qdk9|EYc%XYc;u>C*?@##wDYs(#%LErM3jIO( z(X(JO?{?!2QhMm-$B{;BP*-Dx`Wpm4@(4eE<;Jj|Qw&-3gEKNeXnlfJy9xYdm;XwQ zpE&IO#vj=%<3>DK=lXrK?Hp#McfZv2d(dh#p0hFrpEJe!K;t6^2l=v;q0dY89~;;; z=GQa!A^)7d{Qcgdd3?reVHwKC^tH zn;&bp)Zw1iJ7ANd-9JS7>$MxZ0N1~KVt@M|QT>rsAnkum|H-<}73(*xe>>l7rPP~K zPoX~?iTWA=NDm+*+QGP$#|GBM=KWuFD@nEdb$230Dx>GQYdl*XnFFMQfj}v~l ze+z*{BO{E867f6A556@XF1A%L$yxA&?jJulJsdsvnc&KPBl-HYzWTCNJhDP9(QTOE zM?T@l!{rvdN>H4FAJqRGWE+kvt|r*=LhysuH~iXf&cCI_LKU$?zQ3C2bJgaxaIY(! z|Cb{4Pg#;*x^f|&-SIPGsD583KZfL)bGMH%7#19)y}r`_%&26+)9qv7yFlm@8eh3| zXf|76epj;~@}|80Q~U8_VA->k#s%@bxY;tlsQq|8(TC~1ep0IasF&G@Ul_X=@ejoQ zMH*k3)X5#so;_q8k_A742|r8{YVd>qZIa?E!hTSF6F1KjUwXV`f6o`8`sRA<0<_vt z$d)hFZ69vsE`z6O343WF@K5bSZxeqk{6`O4=lRRu*M;D}l9@jSw9`XsClTMK`xmwx zT>^u=@61hKg~wDCoyK0oGZ&QDH_ zMzPaC`TdhgeB{HOxh!PoJw<-UkLdGp(PsQhSQJc*#rp0?{6~XAU-shGlTz3BXFY8A zNY@0|+&!;TpGS;whuY%-t3OTPm+GJMUQPK{z7H8A{_1;W{M!;&UVcAX zzq!SEAwK(mWPkf>QGH{TwhVs8#q8fi;Xl&&$E%h8sB}_=qfZ5X)das2a{b|Np{F?i zrZ@2)#~b@%--yrb;<$G5^SKj!(=|=1Ez&o_g3bcJc_jY#@bM~at6dhGDpr-}=MjBV zw>S=sCRIZHSK4uc?<&9I&|q36G}RaDvtd`|`A`KHCUV0A&+x03qwp_DeWl-^DEzb6 z6i>g4_&D8vR<5-L@7G%D?{!AtA7p(Vxgn0l4lK_yCtuNt?^Bi*d`g*U3~wdy?MLw4 zzV|A2eAm*lGkU7?+G=U@y!kPVN&EE zfge);^3rB83mo=Dv%u%RJfHfX;f76kmiZohH7O&{r~3Y8*m&&vbeElKwO$^l_|~kp zJ$veKA~y)LmA`*5IsfUN6#rh>@F^Q~P{cpz`kb=2Chw5C5r#M{KOf!y{G-`Ixb69% z@INX3J#RShjX689wRNhK?7x%qXR6FthQ1%ZvC`rzT{{IJ)nA4CX9MK-qx`6RJ_1WD zjqyVx@lOg#9V$eRYc7wQ6Mgfl(khsZ(TCj$D|wvm zANwKgKjt?qke!p@{OA3O$oUk%1|`6AcNNUsQAeKNiR@po)Js6?G1C6i$-CwGUPRw? z8@d};Gz~DyP52MAzN}q97?xxiVs&|;Z>aqkX;hb67;VM2h3Dk^)A;($t+C9gcR7W= zr}p8Wa~1jBxNubW5$hAR55>NLY>w-Djq2t|VIN3-wAB-Ho^T)%Z3YYbkVp7arQck( zGvl^q)WfSXzPyNiSUkESk8BhUlLQm-{KP(lZCS*6*gh`RK13!pMYER%V!ldQ zKX&Zrcq~fGW#th~vUI@#3@7Uk|zmz|t+cxCy-lU+7m6kthW&eQ1*Owt_!q-yyGh5pK za!l$!nY2Rihw7u;Q>)PEm!2ZNL*wiJzVJuoQNP%W0O23d{-##x0a$FJ!qaw@yvbd_CgKpXa0gv2?m0w+fZcm@p9gYw7tdA3FuGS58v>jrDe!KgonY zxlPRYWmPx~!urVXNBx7OHuKq}mUk5U!zh0S*D&L=K87JE-BkO1l=-I$YnHI`iyoI+ zKl6B24c@nEBHE?j)TysrO~#{&(``2Jx2O-G_07IjZO_*GwT`cyQ&rf1Vt*Fdc_QMU zJoaLS;1AVTU!N@m&v{#_eHl=HIX3d*>K|+y8jN2%%Ak# zX9kyO!H)vMkN3->QTc>1o;DHnm()M5H!l*^4_AQ7PB%YVAFskg7saAi(+v6fsr{(3 zDh%VU8^Ga=$S+WSG|Q9LugN>HE$4>757A#AZYE&jx5~JbaK-r#{%L(#aZWVrnxe;4 zPf}!lsEGfOo4AVoaDJ!p+hncNe$1#gpP8%@P3=S6S391uGzrP(;`~smuRd(|#;N=_3jYG6zF=h6#$0cGigdG)ytIMrAAxvTL>E!7`PY%lIl{EwS+63{WM5-#5fbr$QVvVJlnXccOH`pr&z z3;m@c{Bb-IkK1__5wcnEhuW9(o-x?8L)xEkw32-PeB!^1-xURycNNg=yx>nBu`m5c zS@AftSnT>P_@g5EiI|yTusUB3hQYe|Gk^X~9&vXd?;&aEKkrB5OJ7UnErk0w6QWF+5}^$qo3F4@-SW4a`x z$Wrv*r~Zqt#tjR3Hv6hC_(kor^$Ry6L*VdCA5oXW zWqi^4{&p9q^6(CMD09?T;M-YwzEG5E85VXdV4dto%kv!xzxv+~!ip}Ee^NA59;f_@ z)?bf*3oJ0GMDRyN&eyZr6oiM;`4+h$Hrn~h{b6@J*P@Z98RkzG@mUc2Q%x0x`HqH| z)=;dkE`&czr^n!as1dwQ?vUS)@+Y!j8gDx82}~xo7WSX`{~@iy;o)5ly$S_?Xnc0& zxSPDa-2mR-MK^zL)Qy#5%f`std|tjkt^ao#AIAcF>nr>lKf<35MwNKW+hM3uQyU*3 z^>H4%`{IS{|qTs(gAOTU7IwqJIfQ~EFQYuqrsUlz-ZT`S+8+NXv7GRO>i;oE$kD? zUtDcC9S$oWDELF|lSShi+$m`-%xj4L+mt_>`uiZW-7AHCqWR}v1D8XkU%*QG3;R<< z__OC;DE=KL^|#*?DL=m*iGOW-zZ_9X1#Hv$G4eRgUpTxB!V~@9Z0T;n589vFrDH6b zERyPj-iiD)jo&6^tw&6j1$sJ%IsaKdy$FA1Ru9I#y(;*pRFm&-PVCQ$qY>yL>BBT@ zk-wn*H{rboofA!wT0d33egUyB9_zN?!^ojahwjg8@Koxr6quvvA4vJJ#=x9!O%KM*auwz4 ztGg)um$}x<*&(m{rSj)@Un{=+S|qwUozUsOT)6Ir3%72t3*Nf#geUP*61PezfMxxDfr;YKu9qJ0uv<_XK}H{G(OVm$R`|?v=`)!;7r=yyp?fuP69J^;^kHH{2P0 zogH!#{BbAw!4^qU{fuWKY|eMm@=xg>eUi?1TvX<6sr-2cUrZ=@!Ky40{G$2sMi2c^ zG4z9?euUy5d;M|dXCdS1egYrFz8H5|hUGoqu;5=K<#Fo&U;P-2E+2ofzx^+${u-OQ z5+0@>*;b9%A3*z)b=#1Las$nA-9zw$?oUp$T@9x>KUm5%q0eaiOf!Bx`qwr?*v3Q| ze_lkNd0mUbJ3XmBYpc*_w7#T_lv~?)wj7*V3jYSg{)}?k29FRMxM}-KQ~vCUjzGD* zGB8*z_(S8%W82*1KSO)-Cku7+C#_8=`s`QXY`__v{FzrXiM@y@&+N}t(Bk8NSt$NJ zYubjNySf|B?1cFJh(6n=*B8U}PcVnk!v0YH4EVZ;y>FePDX`fm>nqBS6Q?Tkk!?fK z`hlfo{i=Cj>Nt+3Qk0oI%XKxL-2?CH(xuhhS|CAY(X#G z{7E)WM8CZi;dM{&Cz$YO@%(7CSziuD@nU_X`y0w^h{dC=<uCr(l*2L&MEwYjAA7c1gh4-_DfCql(N_*-{ZX;ud-iw#emddD3s*nP zGJ3=EN_^$_ODFtj++!+#lX?e5cYWmFhw@`s&|*Y%{Ey|l`s;rv_19_ZV9bjB&T^jq z<&RQ-RUEYnZ>N1`BicC1_XpvJ*Uk;_YG8)*DO!Gz{g>A7L%_@ZWR5jz%JZrIa=*J4 zp4*Kutg7(;qX|Fu?ph=9y8?!t-6_9cCb1t!GG}q8>kl!?S2zCq#71J>BYnL1p&S2i zR5!WrgdW`J#s;1GtGTqd@$ma%mT0US|I4?&z;oY3caYJFjRr2l72{mrIL3x(H9vA)py!!JktSR0$%Qtd;#R_-V%f0fWPn7vZHi;-IU z8GCqM=qKu*zs{<|clB9|pC$*K{(L{`Uv%l~5BBjbYuZNm=ae7AyaUj(_6L^JPV9f6 z{mGl1ox)=_-9mbxZhkyHwHQX{pRor_@WYG5zk=GWLa^k&ELhQB#xJ!W({KC3^xHeu z#7pci_9FZksFw)mcoTei7AoV{&siB?9_Am0?ApJW$(Y*m^<9X6-_tSyDd|#u<5t0s zq8+=;lw^eIdv_R?OOL6#Pjh_QSsJEI#SmT@*AZEBHh7Rj(HP z5mn(|w#HU>{HtKtS6-{F2cPvUP@YfYUysyFSYB49Cbh{P8K0D2=k3d$&CHq4U;N{# z<-gLuf4z7mOZ{|5QxJVlp6^Hczn1G{$*UY%4U>ikWd1mIQO3uHA9P0z{VVLv3*G!% zywVe&8fKSjKgu+$$8V2Whu{k91;0rBZp&_qv1`v0wqcKMesyT>k5}d1u)q8FO^AO! zi{>1OhU_=d>KX!ya+pcWDh<{A6 zf8GZ9`DuK4h|_Mq?pk#|5xV*Fv)g*Se`JKJe3v}mo$%*Q_wCqWS_O8FLci1c-&!6K z$l|}5!NW9pKCO@MrJBY!wYdfTcOt$+`v;s_{f@8m8O<|)uM_+r_T}>Fe%RLQD0|#~ zr~Lj@UwwO5h5L1tdXUT=E{{`wd}_Xo`B-FWqL*xw@s&*MPu$Y7XGiUu$DLwy^CRi@ zN)}oEj;8lXu9F`(5+|UZ+hs-mlIp9xRTcT+1uNmzdGnb+>%SezuQY2v9Y1v zz6vJ&Eta%ff`4A*Dfai%{Ny;#y1e3!cr3}^uhYH^mi+TMtzNUT1BHE|{)uW*7?Ro+ zGw(?e^7nHm`YUI~6uzxhHfGn=ZC~PFEW_fl&)AE=5#skD{LswvN6O__%;ZZqd7Rpp zN>YEB3zyz8|7uOO(7{Oh^LVsKCybQ~}I4-*pq3JTti_|}$~*iYb}`tR*8Naw4yQK9~6p}%s;{;8*P zvU#m|HNTvis9k@R^)LFrBXM+w3Qtap{A3=nAAzyfyxtaRZ^t#^U()@3(<%(WgRe)} z^Ton`Q2$(A>ns1gd^{gMO1J&6Ik=Q{d3If6Gi;|8-%5RUS=E|9S-lneTWk5HQreG0 zdj2dU@>Z$*Nc*QeFPS?Z{xt)%`b%j)5|2(m+l))ha-_&lQvZE^lZw2ag&$IHte5%Y zNcaXELPd=Fi*}i?L|JBZYrL`P21vJ>Kq+q#;cA>EzGVr~sHfeZ^h{M9KK1 z`fOjzK-`i1mu0a+pE(l#ba$D;myOFr#uwf8WywiDEI4w3L^kjGpA)}3R5$(~e2c_}-M`qVaDji? zU;lyLdp>U92)^Z>Zu_w0=T27n9}@;cYZ+e@|1K6^`TDiv_);6)_LXj04TSI6d{*^`;71zq@0ULdfcxrv zMSPgnzl?4&h0k4i9W^iL=EvaVB`6>9kQv$xk-tCHUrQbb;_$%NZ0mZVzg!4E<_!wK z<0UUy>SG6aKGk0@dPib_%MWH`P+uOW=euWJOO$&18!F<%$%H@I5`PBtugXt!)6Jg? z0WoMH?GKJyE8@d+e^uefWc&`Oh~U#ET6`(vTQ%~e`kEI~e)Pa$=Rf?T^<&ASvw7O! z&b+C$ZhrkRkZSY2e=*mtTsyy(!vC)SgHF%g;dt$w=rvNY%B0f@+URl zeBoWnjOAl*2k7)q=C&P-ddA0?cj9L4`zh_qm1$+q)+?ULM-88*wU0{sQuJgLcE3H% zs(usuOZ=S6D4yRT!;tqqJP(Qgi2gNn|KXf16TmN?SHuS>zXsox@~4dgVV8MF<`>;x zm2rJKmY2E4d}{0F*OMnc;4GJAxCsA(=1+EAtjC9rjVtwhvYtZ%@%73}wy~?255k`Z zM^` zZvX%6aerjKdCq=S5cwB+{!&`MIBD;qRG-$Qg?#;J;-9E867ipfA&vxz_%N-%v{|s5 z7xc8@X2!btbNp#6Oo~*fK0@d-x_{U6?K$Uh(>ND$zC>;LugO#Sw9G}kOep9m1EUt_^pYC6e{=JJWEH-BS z&1z|%Pgy_K>Bbknqp>Uh9HW~*W=#j9ee@CL;G~;B_LHh`qr?E%RIMU^e>KUkbh;u{YhAU^uheI)=TF4vkLMKjiRv@Y)h2xR45>zCLZHka z5c_oOzv+ncxyl^giuhUru}_|R>hc#Z(J;)>U7uOA??OZz&tVxU!aqqP@#VX9>+_0% zv8d#s)o;W;HT$qw>YQ+w1vm%F-={i>56qD2*K61N#QxTo`Kb*R>q}FgDct|+)l&IY zJjV|!Dm-Sri$}@Vr}>$cF9T4c&3`P#x~Fzr8Gr6jDG;sv|6^$?q2F9cd~IFP26V1q zh)0{d%kydf@#vmXUSpsknluyo&Yjq&Hq*9Ycxpw2XSI~)`#CGmzpx65m(IV?L!Ayn z-_iX4q!F?3c>Rl=JumDJ%}=@-W%FBuJMeDPb@Qj*)p%6ip@#$c=biuXuYmYBhs(d` z6`}_7t{rvTpRm@unZI%A{29OV3peXGiXWBsVf?v1_5WK3xF9~{5K}kYB)>n^cP9>4 z;b}Mh@oTu?k00UBs_!FVQTqhzF=o9ypYmtq#g@E@e-gY`l^5e=|4Zbji5PzKEUPhJ z=sUXq>=z2_5aINn8KT0xs3heblZ=J?3LJj?ke$$V{haLZk zL-LGY>{owbKZ=O|(zVYzRL#_f`8e(Qr=-4R?Y}Yby8MHcaTNHc`9;0VEMBms9k*8L z#((mM7|d@{!r~^Mbr$+fslQI{ea9VR2Jy;#tyq6a{Hv+K9(H|)wEx{g^hc%fFR$s} z@ZRS28D}*q$ruk1785|E|a%UiX3ebAoI?=>Ewtiy0W^ zp3Z_-3j0C%kzBJLKhY-&)9Q=(9NxrLi6-&0t4#w?rf(j*-9p6AXngs|sQ?`B`h?XVq}#vwelrA(KE7dY?X~_Z(Pt;N zCF1VkvOry-&(etfXopR(lk7{e_WF5*Up6^0SpW4qJ2^u5H+28lHRH9IzE6dvM%w=L zgkL`-eK#`e2iy8w@T-XEvzPa>c%Wlj9(hCLA8GyAr>Sdjr-lmcs$P)!MdN3#@80oS zWd`!AhjsJIquPEJW^W?pZyj~&Gs7`ok*pqynLg(7?~_dO_hIc_&~(%RRTS4dCRX0;P^RK=9fE(pS3zN1NYiqQsh5r{JH*m2R_Ow2EIiRodrLX`zzmk zT!5y|H`qZRVW0AdKAY|8!0$bd##%ew{ED;;L}9^W=C)7pi^dP`?g&D~sn1!Dy8+to zqts_LhWX?4e-Buv%7Q=i{Pe+V12H2zk6jEG`it79ZlCf! z7|p*p>2HFMbbe=P_#gK%4qh^dXy;98by|nuWiT#*!I}X*SerHby z3j9<1aqn^#KiI4_ujis0{~O1|VOU%dTU+g%^PlyN;=kGYFSxs85MC6jwePR2|2h+O zkj0cYWiuO!^RsCDx%$obh&UkCAV(R<^QrwPt3Mb=XYOOuqXhnw3I3ZN{D`M@`=hYA zh#w~t`%!EDNc1i^#0IkI`!G$^odB=c3NRSC_mcfSLBZQb4#@! zt_xF1o{3U_wXVf%>0uGyp!v&Fou}|#N6%qc$wK+}rTP7WEB?4W>z>qqPuLGfqQ3^- z3WUwuhwSuZVL!Y`d^zayGF0FS9(9^GaU-XnvlvXml7-$o|%cQGN`M z%i^t$wB*$ah5t?U)rpF6c+=x63p{yNetzn|J1_i#)aU`o?=AR2<6mAa4zVpGO_+J( zF52~3X&-Eke#D0fec^qmg8crJAM3xl;Of&o3Vj8_535b@aq4U@6!zI8U;qE{V zD`9ASo3%+3_JP*tuaWS7>-%r^sJOcLzC{0Ac)bq8Czi0k{kv%VDJJ9t!a{qa^1E~_e!r;+u&U{Vy;Ilg6!OYG%wnm=s! zB>}w$l(4`16Ya_Row2L{kDm6zzcqyaL-BneGYU0cyk+$(9d!PKZ<_y$dt8X1=Y6o< zLpQ#69tg+UEYQZ$_eW;eK|xkI*L+zxtkKdEh)(xc{6g<6o^-#*bVrJ#eW6+{@^>`!-Hx*dEmB266C#LDm_`t+yz+tq&FR4H5km!S|Q!Xpk zXX@X!xzdPR_lQ7H$!_iXu8bdf_m}$PzPra9s*3x25&X_emF&CoSC)5MtPga3-uZe7 zdZ?~3^WOu+??doA*L68+Rk*=SF8(8r)A-Q2X$#Re<`RqaHIv6_{;q#_e>88I!<;S} z$m8ZDKIFP42_BVH=-^XZ9#19v2MyAbaHx}1|1@^D^B;U#5`24|OhlUTPnO#GhxYeX z`mZ0SM`5_bYnH!L)DP15YQqWmTbGZn#i%Tu3uf6KnSYloGxK2{O`)Y4%nIwkL7_n(OTfgRbOajZuX`b#zN&1#>K z-;d@Gs+f(!>jV3kTNB;*&-B#imuC)#ovo|(`zZ0hrGp3V6dWsc{f>Sx14-5zHh8Si z#}wbr^L*f)c8RTY5bH0Ef9|Tj8dak1v9@i6en=(w4F5MAOLL#G=`Th78P(U1%go2| zvgg_2NTL5|emS6*bp6}+Sj}Gjt&yMm)Ijn>{NM z@ktv0uh?%hZV%GKi&UYX-3dO`jYAOg?I9aDc$17z8lPOUF%jO6idWQ#QxX61-}R&6>bZ}N zi4gI}Jfbi9T{q@lpCt{Et&Ojc^*L~w2VQv}WfR?Wug|s9O!$DQlTh%|Q`Q$WzQ66( z3{;wUnvFKmjo(YNP56%=9>`cy-$~ZbWPLUa@`dxYiwb=~*XOTht8pYGmp!;6)?XT5 z^lrBrZ8CCMt?#1$9*y7selj1Iex7AL-Mh%YFV)8veS#62dyhRWH&7mTB>v&^`wQ^p z$~o54tfD+l|OF!c|OH|7b*U)cc6$RhkTduLF@PCIK-mG+1D&^jKDvQFWN>% zz_HacR@(m4xjpoF4;vSRUvrV)pW@pk+LHGOor4^;SRW|9eM5%gLDQYg>YP}A9m)FJ zeq0_lb#9H5DPaQNDrNo9PkUEPir&jM{3r13*hN`Cbo_x4cRVSbF)=`Q{m{&|9m&ym z-}L;6x%oc$mUX_={MCopF z?GuN9yRVt6a})XgsYHK-olJ(y1Qk-O-Sr~3L_&F`4-Z%^cJFxSpko^N|9eJCn?-J!rg)gM!OJwe#~R!I30t`q;p z?_JUM^d6SxyI#J&Il+Hq0oL54<{8p}+kI z{%ae~L_x#}HsQ3uKdt|{bk+wQ4bQQEcI%FhPkPdb$6pRcWTY0~BtDpOX(fuHGgx~s z;UCidKeeRs8q)af{Q2_x+Yx-HH<^bMff`o5>RvIO(3`X9kJ1i+n zyZ)2Zdhn@94iAtfrl_t5~f>7%uO&dT~X zW2l17(hr?*i4tDPA zX8HZi$@*Sxrz`rI>{hJbb_Bm8c2?kOl`D>n@fY|f`Xs?(5*DvJSSo&7EU@OP8eZsK zHCJB0lL>yOoST6}{x7T6R^XSe-%Y<6^Oz&!Fe0R(y#Bg$QRYYMRcXw7r>|Dxm#oi^ zX9VJq=?z7H4Z6P|`mG=A=3iznxR<~W!S4mzW$2u8ft9V%QXZ%N--A{Q;49%fvAu45 zo_w$ou36vM+o8fgqV;92!#81TY>`5L)BOV#Z-gSf&s{e5tFspv9-7EO2S0{C?EG`~Je1XT2SR{;eCy z_)`=7*?NqJeb8Phemhg1PvdW4y#g_|>oulnDAr%95323+N7~UV?DMUK@_a9XKa^R8 z9kZ^p#KHdk)3TZ^K_ILWVU`mzR_$G>95=L9~?N&n*;A)#+x@XA+v68q#s-^KR=Bxuk9O!x)&a?fzt(k(@6a7R#`pX z_Iz&)nJoMVst{K&f#>Fr!2i&7-Eld-QU7U5gNz@^ipUDtAu2P3?3Gm7dr;X= zX{UrF2}#J#-ko!q*~wl>_RijU@Aq|GxzGD~`uqM|&vTFO_nhw;*STuU5cZYk=U&>l z;nOoas?^6NN9(gLseUqjK=Ivcq%VFPzZbd;7Wk(2^|XgROWZRVb6W}fO6TL%n;(EL zZtaI@>7qY`<~MA|Mq{n8^HA$Y5`TZxz8dJnq0zz1P-ku=zfSe6N{v8*Thzsgnhd;WN_$Kous_jfh z=Pq|-^Cgr-AJ=HT2A{V21TK3;euU0niA!CAryWWmD@cdme>};L97s>Z@1w87z)XSv zg9QKAE4HH6Pfh&xSn$(^=!^H5jF}_vz{|}$tc87UBI}>ty6P&ktZT*;DXQy>kA0F+ zqwqGYW=HvYdVbvDh6)zGav+ZP8piLR)?XUxX|eMohU1RCru;hP$A6{(#e?+VA6)%x0NV9AQ+Zt;KVIHD1-qtil=nXp{b4ky8T;We3uBW7zvz6TwQJn4&!X)x zP*-(+r1lIw_H@()RIah+`h(VA#_#mS3x<2(u8ZIYwf}Qp_@G_bZW!5I$)De{pSJA% zr@dZ?b84QI&F_9r@_Qu@6Y=Dms}R&bj<3%q^^-12YQNAgbpJ=rTzwYWZvtAJaNzh=5dFNZzb{5l*#)ne$UoEip|!%Cbux&? z{4WW81U}^Yxu;n;j$LvX7ClPj@5hMX`_w^ce_y9FkT+Lcr}@1W-I6i=$#uxuF0Rw~ zFX*8X)6X53&3B;tZ^LhfqN&p!SE$katYPhjhNs&6|sH_|Mz$a)c&-KeRrh zVU>ulhFpR7-30#Wd{nzV$ei}qW%g(O%{P(b|37JVRq&A_NIkHXKc5lNKmLhVnVy3w zJ8z;I|5=@ruxVj2+&UoeZ$t1uuI^j5ux)pyb8VT(Kal!N&O>#kj2wj7=Nj|pv$2)u zM>_Om&?s6L?rk2)@taNbz2RF;c5LGiOtZWz@J;l6tt?0Mo{Q|6GItB;x(a^K{@b0}HJH_!37D$y%lTnL_D5~p=!>fr`H*%`@Ppd- zxJYxB)@>o$)QDHf5Bmg1RP)G%E!pn;{wP1%B`w6qhNocNn*@HH*3b8Un~Nvyk3qpS z;a{nKA8#Croe%AUz4w~)^)$Y`w0RjzQa(iEORDYry;^bjZuU8-?ccU?y6i zFTMgEeggmbWIpiHWyzQtaSd#)i2e}^V*dv&NWgmCE`V!P3WxxNlMsoE~4v4;%UZkhZOVW2AjwEO|3ftXIhW!)^<8=5(Py z-Z?Mw|CAr$A5TE7AU%lgGKJ$G2|q48)L_@A4Z_^88!Gv+{)Qudvt2La2hG2j8|bl! zp`*~@p_uPL`4PO=4VznUmhpr7k4uefuuh-H$?8K2g?v7v<5^#vvVMome^7o*9Nz8t z@k0r0QjKf;{j}&O_a6ZzQ}Lp1F5Ft_$*((;{;KXX7vhznCtz@j;0LXLjww@O$~1u5 zZ%6UVFuM|->zvFzbRS$teh;^XJ8S@_2K1sF9D>yg9< z0~aj9u{Ey1TUWskdj8zbmP_zO^IKrII-lR43BiAy(IPAhE&_{ANBDIcg72CW6zqVb zHRfs6=kHfZ?E9AACt3-@E(> z!rAqA!NJKQe?alsx=R`xl~RJ+YOBU)RQovWGw@86`%{x8e9dWf0q!1Ajn8IhlWY`#(OhuUArKMh3+Jc-CSaXt-ta-;XEweW0f+osVLVN2f0k z_L<-}DcKDpn{0%lL(BMjsy}=;)nm$+PFNIsg6j|3A2sQ+Cn{3%pxQivFPeYZdS0KI znmb^>2O_^n^DpoEhhW6Cd|13VhX21N(dTPo7Gm8O0B<^o->3Rx)1w5u7jPDqFN)^t zZAgAGRy!D*gzSVIebxBwGd7KF%ejZ2HC5yH!^(I(6?sNBUy7d3d2UD&M#P?n7n(wU z(D~7wycglnt{0)GV*`GFbbo5tkOb@(UntF2UTpmrU$j2I-f|u0k9iH67NS4JhSVor z`=;aV=Xar{!3Msb;@eW1kKS4L5?q+68o#^O{gL{gt*~sBsNX6{f9r=I+RXFJKy)1_ z{-4&@ixtxBvIIQ{atl<6&%trk*!&fP&~W42Bh~U>M+2DBC z@KNl;$X-I&)9_am+Rr%#C5EEDNbT={8u2(x zaY~jybRhT*PLIH_#e3jrWPgsIAkx40c3UW#yxIwgHbP(9ko<|0R~lR^~tU@`y zl|&zZ9j(n8Htmm(Ki%ioX@6^vys0?0*BTlAl?4A^M^{njV;+v}_z`(ri?)r(d0i3Exf&eL(fgt;{rbap-L<`l&kpbk&#g zi&GISI|=(o`Ej*VqI7oaX?PqV^b0*-V|ZCCZe78^%~GG=Unz+{&+8_lt<`DJRfzc0 zhUn{|vzMd3{!RGim21uQhmHLFW<*~+i0ip->3XJ^rCY=3<=vCm;G>#`PW#$eR@)#CYyJ~2AzhS|~CkoZ~nH;T`D*Z*S)HO6D< z<$c^f)A%sXpAQ$7lD*L=1F2AiTx}a z7K63!AAuQdZu9R$>zBGa6R^DVaR_R^n*TrDKRkS|gm24xVAw-7z7>5Iq1~fXP-Bt6 zw}RN$*H%Ap>D11cJE$@~B=`>c5rvJS4?=VYfp4l$?&MeC!}DFxDPSOf{%oR8?zOuL zAFdcczuTgJkK$LuT8*t;*d6_9tL{&EAoU*kzga2kkD~YvUaZElzjQ~7Ujz92qxre1 z-`udc$yyn{Y5W+wwE;U8I0@soivB2y??WZNxXvIK{_8CC2gSGPLVxVsYXdClt>n+I zB>3$*EgBo`J}Ap?Q2TqQVGZ`+nH^@XY{0*-!lu5geyC7eg5~TS1O4;5iHL9NrH0k*)c4YM-w+Pr!;u0F#|UUsL>-#KogeZUJ0buNwb* z*Cyc_!xM0_=)cPUm*d~CPa-D##~|aOu+MaVL&>O2d{gHZRAknxygzw=;D31uxX=cn zc5Q)w2cpj#Ps&24A9uj$)n{SfhdbjGsJwfXf7lK(T+llo`Z zbj7(RPV@UOCH0$G|J!@FG(*t4H5c+>g(?DLF|9=NgTT8Q_b!SA2iXZIV@`P7FG$j%3*`dDk88$Nel z4bgWi<1b>L&-IVMM7OPQZkx~-rDXq%jYmB8J#$nx|CjDB*c20oZ{m-DnT5co1+mYz zwvkw8({9NA_=~?^2cmDAO7ppTU%Um*)kOaXwZFTD&B8@Zx53=r%lY@G_SeZ=js3jX z6^~97`2ku#nL0;0-|^=OFz7Dw8?--g_enKYvY{KAOLKbvzJIE3J-UWt&)h9wSxc;^ z{Z-deKVzfnZSl*`9(+Buzu(%cGYy}vxc8#SPdXF)xy_L5uX`7azApMhEXe-cqSj8h z!fA!f{!;v@6;)#{qpa}xO&|V#ZEWQGyV@;sM`dyrEUzW-N%ciym>1oV(M{x6C_V!t-Edm*D#(lz z__QGSbY2~dXC-~pHCE(5ElB<%t!FGwzjXj=zZUEBiGKKO9E<+j4?xKhCC85g!RNMU zB_`h32}LzUe>1Irr<6tFEVc_~tW4tT3yFRRDosb|b{Ssl3w=!Y$JC0K_CB}U3<23` zd_5BTIVRvY?n~~7+ct~%jP{2dwMfH@LFeK0X<`3vk^btk>lOGV!2*jWMDX`d_Xngt z4#vaXH^9pqTPpuwUjGZx{emU8TH_}NOTOOFR$l+R`$~hw_w0taQPf9i|5LjLv-s7W(Jp16SWobM zqrL~`#;>X}zEev5*M8F-Fs~1A{rsHtk1T%fhcGZ345C!yKPA(EdFA)R@tWow|Fr-5 zY>Yb^nXZEUwFUmEecrJ@8Y>#?g;h=o{QXe<5%|R$J$tSJpH@P@(fF_NW>?(WawSYo z6ZJpJj}g^_QQ2ZWJe?uF59NnzToZW0c6ebCNm=J!f2#i6K zhWntnO*MZ1LBxL7GndXkj5z>Cty8T3+E3cQ9blS?b)Q^;f9HeJ^L00D2uF)!o4{d( z;0K-me)88s46DBfGCVi(->2v2%o-YuMWfck_egx35;oaOkW`eDuJY4|>QxvakJ zO!PyAhdOJT*$E%l5&eU7zBG39z-dD=W%`2Z=M!rFX!?7NEI&u>cip_&?68I%I)yjl z_(hVRYnU8}T?(?Hb>;a_Nc6K#jY!;)upMSJTgac^ne_MBw(~(-oz+$1w}rVYK9go^ z{fiH&K0aw3j3qDDRf*r18A`Nxz734G{?n)O{tl<@aX4=4ez;Iy=nq<7DLkgcY7Mu8 z%ge+{{K)q=P8+-i7hJy%vEzh)NhS5cDE}}lo3jD#wGsHtC-(bT-(TplryaI37ygyz z*8-YE;?V5v;5asy|396tFxKoE8@s<2TRd2`{;g032df}(wmmHt8Kl@}?XB?E1CaVw9{ke?~tFh`2I$(LZEniRLySbx0u;!%< zSku1p`AL1dc1wR;AGTViFPzDI=9jTL?5&w4T0OJk_*4-6`*u$-zFL|Mi=T-6ZxO*~ zpjIS$AKD77d#TM9DX$USKpKGzp8yW05y}=K*@Qb&kTvaSdkEg?ayzQ z&0nJPXMREgc3gh|vhE1{m6HDISF;zR{Y;Sc7nKwHS?$^aT+w|Cqz4InBGDHEqq4E) zo*VFQJ_5C$tJ;R6+wfeNI6~l))=!GNGWOG6gALsHZ+@)2|4wh%T-3U_2};}LaD3AF z2;T<>qxFz%2pXl@zFJ>bXK7nIVC`S_9DfRuf9PUWot+-t1Kq}p_?PO3rfCy#NA(mb z|GQQtezhL|!GM!(aqfMn#Gkx>`m3Ka+Dup`!>TB_)Tsv?T^aOhGQks{Q1fW zexEC&@O#Z|P@`T9zn)6)n=mQ@FU?&KZ`)25?}y|cs*RqGHSL$n^nnA>&jZ4PaA1cu z5O7AsS0)7C+jJsvW}PiCzkYrG`?P*B&N&_{{_FvtegfalL?5)86pur{?12u)^!fU9 zk{@1VwE#D?$%Em&1-@ziZQ#u$JhkH>Sgv@-zc01F<3nfRMw?vlcp>mj`-7TxW2{Ft zb@pqPYJ3m56pHnNvSC0A(ch6u^m7Ia#z=#;u-9AQo9;i{y2F%RFqniTcZ7YT`vZ>p z|H8YaW_b9im@h%`U3z*7`aVd3(z!X}`;q){^oKvFuxf*5QI+^6`^(24D+PlW2GHS7 zGJiixg71bS)!AxCbKIsQ@^3W$V_iM4@!jPRuukNcseV{z=8s8{nX>u^#dl;=9d@N< zS4>n0dn$ML3`bLiYI?bQi+fT>b=gT0-M(A5Z zg5P$DAyUA!2AWt3|4jAmt3gVfyI>Qfey_`apXSfTX2juO`(4oBnb5a1KN0>XQTn#~ zAl53R=&c636yE{!UI_n8I6T|4|$pgO+$IotzB#izma7=d4BqA%v?`(qa1DAtvwQ?1_TNufokLnM{ zCBE29I|D|`{4#o>a{*CT``BM~tSK3SZ zUq|Q@YQG!C&q4FmIdE=m4e|a-{=+mo9&@#J$?Ug+=o1~Mg}6s=3q085u$$noakrvVlJMFTMvF01wUy1!)mt%yOn8#uz=A^DHCY5rLI%?g?Qr~Fvft|8lZYY49Spuzb;^B>RJ&%{%&vLL3d&@WWq z9J^bOJ!n4wOJ^1E^|b$KzON6iyS*GNhEC=0FN5%B(ST?v|GF9W{uKEY%AY#-+|Z)) zQqX+doUhL({^J+=W1MaVbeJOIM+c&RW*g1N>t}MnF{Bn>Z$kKEGAseDt@EMlETMns z{@}08qOkb-Mz|Fq^4s}D-_MLvV*Z|7xV%8{hvr8PrmaJ-c17^ROWZ&0j}BFzjb29C zFt}9cpCA%{J|B}U%`dzJmP7tj;zO?Q8=RYozN1$|iciQ@zjy|?;D3=RP~JRG zC4XiXo3M`^M&hp>B7UR$&+49j2yIezA?j2Le}2lJCq2|zuwyH1-9f~!|BpZIJ@Cwm zCD7&j67m1Uzf6$wp9ag?$oNC+lgFm`7W#|E4~nUAIP&{e zu-qc_7tPOXoEC+hr2NXi`VgJZGi-_!-?z?%)^`PesQ#LkzaGC_D*~$#!hbpt|6{70 zhh0x*L(&c5e`x)3-^91r@wX8k3KI5<=5JP;hGLL*CbX>FzfAR6hL##Dz1R|i#?2P^ zA@fbLQ)b}W51DYM-B#%Rm;JSi!XrR2H{^6gdanj z%*F>_v*6`P;a}){iZ$Pm9ZdL&`Jw;jr^x+F&9))ve`^Ii?YM^H+kxn_Zx0mg=zCMt znIqyuT3;PGbv}OIvli06i2g&`-!iL}I(zZl6es^Tq!Rz~`qZ{}b=kbTy|JuWKYpFY z->WlS@sGOV@f0&vylWmWQ{hO;39-R^kYOz?x|N9+EaiBpbd zKw*EukAoz?r1!Kw^Utxyj*3eCMdn*&w~WIHR(bF+O7N4`XHTq>_SbDrhKV0~^7l*U zSLB+xqM^|u=w&MEOWA}UmcT#t50L|}Fw19}EO5^fZl96#cWqpt#KFhc z!hjb$`TeDm_+;vLHFihQ9PilJ@#mxQ`}Ml-+2^eKEaIVbj@yF&Yg{7ws(D*iyt^e4 z_S&k(|D*gzuzE$cD&zA2Ume!ov@L$xEA|&r|8TjwCpIofhJl?_da(BJGA+* z_o%o(xqt9l>W}m9FM$X80)JFL4c%qPZZ7MJmT9W>Q`_VInEi7J>^>~|lWG1bedRoi z{jmzP2Z`(EtNzZVgD(xq4 z27`)L^Yt`7KU4n-EArQ1D?L@?zqy3}4NcZSMUlWi)kk^@O_}zDp=jGm;EUE53T&&h zh`2WB^Q$F)zchbUD4qZQMJE9oBy8f>X?z}9sKXw=YmGYRO1S-}@kOiM58=JG7TkF& z`X{M>*x#=jyP?wxXB?Qy*HeC&pZCCK-4{VqraHbza`3@P-YJk!Ec(L_lKR5tqUpGO zQX&|B6Z)RcUzy+Eh|RLI!nbdZ_2v4K*mq4UcRXm71nT-@`18jT{c~E+1LF&l;8Kig z{5uA^;;Xp{FyOn$zbXm-CvW#h%Y~_c*M$D3@j<_F5m?Y}1r#=^&i|k4pRFI`v6|T? zS^bvc|Bz`E=H#q_Pd7w=4(&fEY8!{fuW~_imcYLQ!GHLG9ISTsG#no)^pBG4KkE7> zMwt_^~1Rshkmp(*8LMJUP5Of4@}!JU{1xW(9FD z&PO%=Q-)P%onE%Wd*ez4{z?5|`lvF3q5-JAARfH2cDSy6A6rB=LjQ9wRp3M=z|mOYp~r@aK}bwEwk70;K(M;O{q^@F!i` zUugL!0TlMV_;p&}u>J0emb2oaMYzxxL4-fE+xz2;vneqDWgWhr@@HYQS$LvDI`~}` z{GtBizmx>rY`YPZc9GVC{|#mR%k@V_VfUe{!LfmuKTiF}e)V|to|p@c*93p){?g#c zmh854e#kqYZ~Xq~{?ZdKECb7z>Q(Zm{W@J% z{-_lejtu7OssHGE%mWt$B)~TZ!GFr1Of603alR=k^yl^d`~3|Gf5tX($5GPk+GDGu z`1{Kv{E1y(oweR>hPo&EaQ@Kx-m`Qme;BtE-n5VA>z|YOBD2^H-`K`O=h~{{gWd(x zacxE%ytNbhgZhuRDSlZ0&myq6U7PRirh zH?74`Pc?prF7v}K{z*{rQT#vEKQq^W~l+nHFyXbE&0Eb#e_;M0AjH||=S0HZri;{Q+cqmko1vATrc!lhP~_>$*;Ca#)} zGb&=h@Vv0!v_3a8$q#3GC4q60YW$A3n~ybGrOVDoq4+(l7KN~OCEPplmA^l#Zz{4^ z#@rE@B5?m0o^O6>_E%_bn&^$pO5A@w>AyI<&yu= zJ|gg2MDjON3X9mXuRqadnaEGl__fC9P&8k-ScYG!-G`Q z&6065a8!B<=xU1s1wN@hIC?u6jT{vakD~pT?UNtEkv_i);&T%D`=$6yka|CS?zh1F<#YIT zLvsGwaV@F;JvAC46#~E1zV?y&lLtE)A$obK#IN~HchsI4EwisQKR-NChwc2;6emvT z$MLHm_#IFdfc{q!z#{%%enmbX^x)M7EOt&;oZUz0YX#BQCV{~iGByeN*}L=iXGrvQ z@NPd`91{;g#sgI1KdrzWLp-8o{X-Q0gGTsEu}M5wDe6?N*Olqx*%dP}OeX~lt7-A; z)IJ~4iovn3Rzi&*qCbMpFCVpI4$k*n0_sP1@$W* z2NQyS?RIZi;!a(*WQS_}4;fOg@i``l$4>3vQGlc&>?O#~C%ZQZ^?}Q(^tInU-+USEnUd4cR z`6Rxc_WwjQcEikiQQ&i4#OHK=OXN0BY$0juqJ5%&hU#P8ul{IU5(i#c0>8BX$FydM zbpBH!EUl;D|L;KT_t6nCIBRt(jn_#^g?`lk=%@!jDXZ^i--wMl)B$s@)$aS3-wK6%KH>fTfmq8jPG+BJ{5D{jH`=~j2{Of|mu`7&m`=K&^k}34GK1pV9rxtoy8T%pNB2 zP4%G)ezfKNJtW)djw3e`UFwAL_J;h8E_cf7pTO1E(ZsJi2E#Sl+bY_@nxGk-`rr zzFP<$c5V3ee3E~ABlU+>lt;_*4^$twi=K%uJQCnJ)2RG?`TnD9%NVruUk=+22>eog zaNurJJPwu=c4icjFOmKd64LE!9_6Nb#?3>JpBRe3GB=I?Gt= zbN8h^c&hQat^N!QTOJSEhN3=6>oXS?6tNw<-{O|d0-sbr49Xsb8&kYt&}@NEy1%Z8 z`WvR`q0PL_RpWDCms;$;g(>RR7yeJ7kk7|D5<49y44nfHHmS}}`_xxE{-1Siw&m5B zN_{TxZ)rKJ4C)qtDClY=;ya38gKkI4p8fY&>yn>;f1!QQ({E3$5eEtW3WHp6;xt(mn^7h2YdrF_89P0mm23U$kG* zfDMxR=b|nP{cK|^KmYa3{%}0mI05!r1ytg*n#?|Ghr8mE|7Js8co%-%g3OO=b>ADS zTSr1KHPJss=abjoHxti&j|1(Ojre++pKH)A1U0_KKqGz8e@OMmjU_QSvQ-*{SPA_> z`7vniBCOUf3l_Qm+n*+%KjEVrh&3&u!S#&b57p0?(-{k{cNgb&QH}qT-NMoNT0Cgh zTxc__&w&Ls*^w(vu`J$)zaN@k zE}E~;_Oxw;cdoVN*J*vG;Gio$JrE9GmTs(EFOMJhM$}*nrZ+)HxAIE-%JKinw+#F` zmRD)NpQZoAY3ubc{;|M6-CufZfCs+XI|l|$6!@p{;~jN1*2cCbnw-h!_*atrT>d6c zeAIs)Y)BUPr~603m@ymC#T+BjD)CR^$J7KrT;UuEtuN2y&p(&cXJ(}|U@h*nmDM*D z1pjRVW}}ux0;G=<`knfRp*yDIkMj{=q9^<#t?xe>B%N>3Pzh$^RO7#Ik~AN*lN4VL z6#Ju;B!BW`kspS;MnZg#_x$@%{3nORqU(}n@a>iGAEiXU{M?*^&X=-aYpTFE?XN%U zm4dZnvf!SY_TL4Ta(mK z#^~iK_)$vwSKj}0Lrd#$NV=<9zkfG;2p!J8DtPP@$KOA-|1H(jm`{uW1~u%+uhaR6 z1I|syZLem+6xn7aq8P&k-SL-il?eE-}b8U{a=V7>txs%$Hxl)OYOhjL=PuCVpS`GK?G?rzoiji29; zwdvjl_ZsM`#BcUG7qm7AhC2gY`Tx`W$;ZjYEah`6^im4_f+YVp`;-?}dlms9M&tN; zBhsH$zQ+R#v%_TdMXFz%a(!_5=h-s+()!Fi$v!s9SOB9(2>iwq`~6Yj!nUuUi5ozoZjf3b;#UiT?-eifSiD0$+}mcFcs^2pJQpz?-E4zES)^LOw7#LoynENf z$9Eoc{3=O({G&mcG~4T0LFsu>Kcx2i`zS3IVOA64SK9IQNa~C4ES+)kAwSS8i|6-8 z^~>^)>MU%TzAXQpP4;)c@9c#sZZoUYFAF+pvGy7@(ZPEp$G_5Ao?mHw*#)nL1jz7D z^DByD4OpEC(*A(j!hUBH{QvLyE}`Rtq3-qJ{QhZw`iJ2jIBQ%e=y$dh@1N-RI#H57 z9zPFeKQianY5%R!FMqV!F$dnh75Gdg`2UgY!hEKOqF#0t_`eZ|D|XF;pnak~X-M*m zc{#~=BqSZ|uZ#K;tq(n~xfr+qSpjw#0{@02Ka&@{oz=`fg7>BfeAE0)L;FDVYB*13 z|0zGtr!b~5_X?`76YFVxez0~F`dv$alD6xu|N7rlqW=%(6*12z53#l6hyGrt{BXTD z6(_d#froFi`Fg7V`yOh-%2;c(>phmg{~$8ot9Xtxw(9Kz)??T6>oh-ppl2CO>h+{b z{Lf0&W*siqK;`<89RD;w-q~#$7T55GZBIo1pdqpU!}lxLf3Z5KG(0c#JK3LM=i-G! z_J_#uPxVW(RU>9l&rCM|i{=*#nG5z^=?lfBF8uju{^tH@V`i+=0^1!B_P>>GQvdDbj*IpRT~#nrTve&6pUSO%musmKl%Ho_0dLVarpf}GJIIF!1^zKY{>rF{E}Gg z@0%>s|FpiJSu-AScM6z~73bs7{7?GfKrG9g4K4Nw{!slha1~><|GSKB6IA2>e!WO6 z=@tjpVLAN%XnyirQJ6HpFjBU^FN4_sMeq~<`>lapJu2-FvHx}3RG{WSEzB9OE4~lW z?uKrTXmM6q=Skx8Jr(hm;@Q69e$qgfP%N-nR1p<@x#22?6LMUH|7FXnyCEoeR6W z#2;4=Q0*VAXNF+={j@LPQYzkiDV(Nh1^ zaJ~PqbmIs9{z{2H3NI{!E7MD>)cazTf1?dlXbVxdz<(4aqc@fM1--O`* z%z1UTcXl;2nH0nEuORy9L8hnV|NP*;g{txYW9<*za99mPb_x93koflGSXW$@?IF`g z`2_#NiW;+w%ceNg@(9Pj(prxH8Z+JT>@#mTw`>Hze_Ef~ch4K`Vgn!xME@3z4-#ty z;GB0MU|}rqPyNG^tNyrPhmTua$%!!~KJBmDfy2bdBNoEG6}Wm-UiyPDUzB?D2x* zC!5r_HtmznXWBax3d&UTE4_Yo_N;CVv~*p^-!JXIS-f>2-Z>BpS#@*y|I_+yhWi!v z=-3_HJxb^&%CDN?VVHPqj%+@Og7B-ntpPikZ-_yjLO;;?IVyKzLp}Sd@*gMXN%^66ZZiJF6aKjLYRX=C zo8nQ+!+bsEPiSj*Z2Qhb7GKc*^?-F=ct*-y=WS5!KT6XBu>1ZXsF5M~L-)VdnkmgU zRt7+$>NPojXnyGFW*4?|h!=JoqS}ANwGKu#=TJD<>HF9x>^SkA$k=$87gej?XTlQx#YJF~k5-N&nruV2;CU~Td> zQD`1Iq1qHD2<{`|3k%{uJ`Yu}xa(>%{8RljOq#E^q+S379T)nG_Ae~g z`-#cFe}nc);Xi16@#U>E?)W$j>N<%01I2&W4vpAZZ>c`ALA8GJ%kjtKU;W^CpDFzN zQ2jLOhbKZiPq^bN;tN_Ia2gVTw{rZUSGlMk)A;)MF+cP-@PpPC0{=9={$TFH!lfSk zjxR3q?@#kf)7pe!$f{t7HWKj#oiFG(Js4w)f?(;@LjHY}q<&!8HV_9T1W5Z+qWSNe zkofxIVN*8T%nTcZmh<$t2^?bj%{ zzd*#-@g%-}7w3(=PI$o;vkmRM`1)6lbr!qbm(ku{-7yAPH zD)3F~zYoT^;L-G{&}5&$Zz{3hwmXekwGYO4{Go`CX@8_vy$~sW4S1B-`Tft? zQh%7P4_w=5%db=X-uvy3&AohN{SOqs@B4;G`=bM7`&X&`er71y?+&h59aZCZ@Gxor zf)szGP8Rw7PH>3sOo|*T?QI zQ?RYt74WHXE0y;D*C|ij8|VUEO&0V2r}?Gh()k~&EB=7<8C1y+olgPSe~lNM-6Z%y z?SJ8lpExn>8yp{5Y5z(5u-sXSe|4w9Q6CTf|FpjFdAC$wZqWcWKdI)=uJ7}))`kdZ zz9x*X|3>ml-Hr!iuAeXHtQuVTeDeOb$v^xsI9JMF^v{1AaY- z#1C5eE-cv08CPqn)<1{;1ftFsZ!l>m&d;FnbGM*iTy5+NLp3V-L-I?T-%9cKN;G`t*uV`h0lS5v_+y1&GS zRb!r=v@v;-YJRP|?~iBVJmFR6Rn~v`XF>dfMv@6T{i_M8n{DCmkMb+c#v46ex`NqD z!7rMh`f=fihk{|9tVcH{34iGEsm$P?GPI6>3rDg6H_e-uU4+0y`Rw8@-sROmnX ze1vt5(tPe$?qGCZ@aO;KXK(((M3*m+lJC)%+c#352pH{-%hVlVua@8s&ChDJX~>=@ z*O%>orT*t;U?eKq&w}I2=JNZe@k81#Ukprlg`?a0^6Rv|9N`{}z2A6(LsENw{TAuJ zyWtg#DdnE9CAKcVo=5nzVCYQjbIKRo{hX}D^U3RT<0l5RnEQtTv{>>ksB)LJ^OEF)` zkjxKBSP+1}4c*~jg{XfkN&JyoP@UyZ)y4@M*YW44@y9-CfBiFCH_)r2nm^rao3m*t zP4H*dHol(DKkSg~jqN)+%lwm)_@`d$8nf#yjBvS~h;M29J*LiEc6919{MFGXBY_r>SM)8ORFBbDD@-oM>p zav-LdO^4UcIC8QpWPTR>qV-(Af`DuTk<+v-XZ2WmlUM%Y8G{1Fpxi>zHom!=TQuw`M_IVHSsf%j= z^tAPKv=}oMc5YOy@6xAevqw&UV8n6Z-?K@6IJ%+?)~a8sl0Q8kE11#UPmni4wZ2=j z-xEjeoe1h_s`>M%hNrauVlcy! zK9B51EZF!z+*q9hens$u#y=rCfw;0@ znsk1Jm|sTc`yA~NfcHN;L6a+jAGCfx{)8@T_*w(|R-SJ{`SGpL4;wF^3K#MOKZ1yU zi+8%h@>Uk2UASs~Y?t;|WhYMtjgnmcep8A6`OxAOGyYbB9gJ1;qprtvoHcMXgq~8( zkIPH6*cy|caNPf2enhU{GM<#dSCKVMsSJXU=ybaoW@r2VfMtA1j}q}Sl(=-rpEC;S*OC<2Ez_mG`$ zVMO?$FZD0mH*uHE_oVaL1{k|w=Xwq>G+*eec!K|5?ZU7@b4fqUv#7+kk?i>`HoM`| zh%xZ3V?&N#+W*~omm9_?$3R(zz&FirHSZ9NgIuS9vGG*?`xdrx|1o30Tr7U;Et`Ku z{m1m9L1^&BN#;K&KVI(*!jEsApn2z0{QJ@PW=?Vd4k~km>@2~LAfnHvJqg5FZJeMj ziuk6K)JOa$2jK2qjxv5w|IxLN9<%wZj!tKU|Dg59it~P$*?kI_uTjm9sCHLafbD5q z)~lWPI|+B+m)a~!&jv~GdevTx7-<7 zW&N?y6)kqg?i(ny#rZ|lzv$>cg6uYDtK?5B3r%*m=VwTb>BYYf&9A+AB+WNJDB&wy zHNP?)|Dg7X*Whfe$N5!C>W?jdx?{IDqX0b?aC}mJXZ8vkT<_>LPtKLx7^*ZF!R{VA#a!f}q7D;VGK;_Gh_|KoSl1-t5wfS}Y4 zmG>vlA2`hpL4(ax;b@ae{@KX+*Db;W*SU@cw>hfkYqgQ`!xtT=!lzS%tpC~%LtD9j zYIxfX%kDYI_?bccQ?BHHUOPHMQ8mF&CE@4m?Q^kFA5R#NqQmbWZRGo#HVh8JT^Ung zj*V*n)jA^>H(hgtFcjx!Qhxeb2H@7slc4>4!B6VHnk|#!+jo<}>ym2!^>{!4PTMyL zN(+SlqWtVNhB5z>d(pi-t&$(|{>WG9ez>LCM6jQ)nx7*#S7Qs{CoDQ1#h+iHkk@aL zhxuT;ALGDBUGOuA_^&@DFWLQDw{XR7)%<+*MVlELe}(v7#{Bn{q<#}})fJC-wTDrc zg?*vce}D-&U+mp84dxX19$NRY1aH7vGeB%8}vtw!<_C*eLj?N&15~)R}=59UY;n^LyA6b# zE03?v+6Lf>^Wz~kOz@BT$3JBO*w|$PjBT}quc!L)tA7CQ`ZQj~KdK+&{TZt_V>d2; zp_+eP9{AzFh2!9LylVcKdfPn&sLkHyXZ1&To}`E{CKAGh8OcfTJB*RoXi=U5%9#?Jiu1V%eA^Y^15@mIO# zV|WyQQkEa2{4<^CinDLq!H-iSe@F8ZwM#s(?1w$%St|McQUCT}UMMz-nh2L7ZuR}k z4>~`_)OaQ?|1k*`%@+QV`nQcEL-E;!i7;G8qY^*z{+j!1mDs(uJ9Hfu!T+D;_kJl| z@l1ssysg)<^8V!h?d#4EX}-k-*ws+@HwRm}e_IvmgC}epz&N!zUr+n<%PWG>uf+rz zzv2nM4(xP8#qXi8|Cc&nPtPar{5A-uv>Ok7ABp@0<=54QbMSQ7G#S5a2)`Q555!(~ z$HLQM)%+TEVKwXFv>31Yi}U%E)^dLNEDFHriZNCCx2$J@xU}~;nSWCf{W;@^Kkl|3 z13C+Yf6E~G!R{}R6$I?Wh7(lt%e=iGR$Ltgi~6eO*FG#_t)CvlJ<0#}r^x+V^fBrD z#%Kqb{-pUqji~A@Q2R4zuN}+ZKkZM@Fqw|yzYVI=fBkTN3^4Y%tUhZ<{L|Wp3idPN z30%uGYBRMu-crWg)}+Fu1fX#OFxdk8jPIu_>W ztLDeX86NoV+Ym^(+KB%?^*=+O1mhdKu`qg_@IRCvr>?qT%SbyJKNLj&<);PVf(Bz? zYk}Yg)qf8*&&I(Pj<9rvn14h4PgaXS+=t%)5^B;h{(N2~Ae;zitI|bg{6!~v+qR%p&LU8t}QE0m`{L5`qH*D2(Ao#pe za35>dsq;Bn6FnT^HW1U?ir2d-Qe7%zJ%OZOoY8g%f zuML7&u_tndBcXz7NLPmqy6=6;JrJV~iW- z-|h#c7J^?vB>qWm7J{DNM!;kZ;h!=HzYKRcVaVe?;I`x6{uz0Fsh33v4%Hed^G}pt zY0~_qlJtHscC~7LOZP@-9K>T@Mm~ic(&l2uBdNQ{#0*1 z6MtPE0olo0IR0sVT&pY)xAz|k7H{JC{Zszv?h8hnTf?B(S?~u5e~zA>hu7`L%lJe6 zQ=ikp*y`CZ(6Um^pVHe2IANGK6uTvg_ec2SpB{`yjt!IXCxh^3K`&Q~59|vj_eFl4 z^2c&xF#4Py1}#2y9kShHXOA5zE&m7?Sf^3d28xsF?NeRGVjfcRXC4zrc|GnGs8%uxRf~&^K z;`=G&`MpL`e&Ob(!C*c__$OMwJyq}k+`rGW?>YCJ_g(8< zYp=C7(ua+=E`qc?Hxa*b5Wl?oP6gXs8+ucp^)F+7eQ(C+7n%;CHs7WB)$fxxOy>rO z{1fKa*(rfA(tQZE+9b^{lgBe4ZKs1Me~$SzV)!EXHPek=EoS}+>%UIAD;J_3GUn@(Mmf9EV?NUQZ-I9(gdH1B zbzg24_yvex8GQeSacfsme1-kn+D*T}E9(~Zcpj_fx0qjwRr8^f$soEni17>SzjnF5 zVB7v%e0`=gzv7PigVzOTO3pBT<)i$0Mr8wT($O+{{^@8nzs36R(D3Hm`PHzaoA%ZRiVuovr9$(_X@Q%+I^YflzteRil24l=(sAHfvf(eZG7Es{fm= z6$mSxTU(}{D)_N5)8Typ|Rs92D1O8IjP1nFUwk`=+Jr0-)(0Sd4$b>O zU-(nf&U&rzelS1B>M0;bdl1#0BhAnHMtuJBnw@CAD(2_WdV%n6(m>i^KI7+A^-Z4l!p_K)lSO8}2wv#HD26g9uZ`NhEKKnOcKP{hwF z#LwEjy+QA}1W9i&gMbPfco zz=70s5%Zro{ww44k6q_MbixEyzkvJ8KaL83ZttDwyz2bVv15=|_|>+TWFaJ@HZC zXC~VJ3Ur(cwkPaG^;1}%I_n2RCXWx_8!sgJ+5K=ZxVyN}{AEi8er6*7xx9+sf4$~R zPd+jb_!W)#88rF@-FPcsl)uOPY%@y%>!vzWql-%=`KcK6k^X61L}s^*mE`Bd^dOjW z%!!7dX8iO;{&N{!03&((KWPffpZKEsT-V%1{P|&W`gF52Kg+dL5cFsmZBRd2;0N}f zVGsHGypeKh=EnG$i2SEvS}fd~UupHl;%&y9w)Y zezRv$AQaYhqN8Li|AOPk1=IbYX}Bf*E^jTYH$?pW-?yk`Oo}gN|?V-P76yT1%4JHe*UmfLT@KIeVEDknS=N_-|7Wz zY`0Ie|BU&$d5!{_Zgr%0e@gRHYt~2lTzO2yPdU=J*M9~<@L)&!dMo2+BI4&m!+DVN zVF2Cyh}Bog5kIfb4+PtK4x;={KJuS0NhlcV52T92OdppZeS6Fx5aQ3;YxJKZ<+0$B z=S4>)u>62Nst@^L8U(Rf4kCV*BLCUFlMlp)nb394Jp_KpQGRp;4TM{R9jMDM7Jud- z|M|H2B53>0PShXli}*RoBna%cIf(ox*0;+>@aLNt*o)>9VSa883xa{A4s@>rtKV`* z{Pdrsgx9`u(fkR#zkO(T5Uj1^NUL5ke&YJd>HQR-rF0ba7h`@tC!^EfPmr%UW<{@_GMR=?0ewEy$vnF6Sc=f`_bNq)9y764WHb~LvG z>wm%hnSE+2VShW`e&xOs_^IP0-rxSYeJ&Uz3=r)Z}y_U4r<1pFiK~ z-gh&N^_k;7DL{XyJ&hmV(c$m=!~AzR_k#8^-m6hRZ<(ur+Yjw%Y@aY;J=V_$wtk?p z?nlVQ2`oR1`G5F#5X_6Rqm~C5|2H81H}#nZw-)yoozJL)`2YAlAK&e_rDk@_KV$y? zsTTs%-Z{`womIm7!~D-v@%szoZK;kU^Uo^epGQpMmQY&{)52-6wtQ7j+!K~`gyFMzx?6PcktlxtAXFE8}jxe!Hz0ckCx=`DPA8I z-?O7t2CoEu8X|t?PMZe>Vf{t(0en$@s35@?rug@ww)fcnCgx{Zi2}m=+tAGIAn9KZ zZ<+y{CY#WKr=z2LD*cz!d)PluL#{b1<;5kEIz|J*Sc7CPI~kKxON^@Yek8=Ve> z+gSrd`!ATEw&NDV`P25I{slb0;Q6N@$W5}=$j^uUrh#EWZ@Mg)<%iu7Kj-dLKw^6v zdd-OO6UVn_zAIrtS6iCy$@nQp{CvvKx8MBUhI;A^cKmB!eGxy$cq$;^fi*qUXrF znLmmI{u(-o^S|9%@#jA^=}mXmlICyg?n-d>v!Z4Jt0nnsnC=ICDtgj6$FhX)hwH0H zJyyV^-c}mRrK|b% z75!;e9P_W4$iL<+T>z&CTF_Hj()^9x5Comg`_uT=(*8BRdoVcm7(fGtG5+HEw`(y$ zaII^9jr9jEv7u1<+nRbu&l29>|EoVZu7GKB^8HPR2GBmPjK6ZZxIf~9tpaxJ>rV^v zr1|UTp@65fKedeiD)7S{<)3!(_VxUs{&aQ|<{uLgKi6GQz&Cv>db@gqupZ}+juiw! zv1@-iZ{{dT{#C5a2iYnXObt)PEu>X7sa(tBr>7-d(VFR7TwmwjIutJ4?N5JioGH9NJilsC zIG-OcwG{CW*Z)jz>IdE4brbQg5cyAQ?GVsv-k-)ykmes3qlC$?Ea}4ujDPOPf3{t! zfQ=n2DcqFi*JnQe-s)Ok(fnx4uchTd&?~PmyGfmQ+_J&99XI`1R3! z>AY_v1%4T#{En4NK6H8)NsZ&A`L*an5PUt{msVVPF6rO88hC?ttRZc#kmk=?GbKDZ zVy=-tGi|5C?>1fOHcpy9d2^I7{h7JQf0d&6@ai2uD7|c?(SKbB1st7jPT!qo{K4^I zUPL+lRxe9bUkd2_#l^u2nBK=+qyI8K_<_E@ldF+G+-?QLk1?nJ^e4^_?SHlqhMws| zJ@Q!o))48>jXZuV&CTiZ`*$7w>MtB0_Tcro-Dz_Xe{g(gW1@s^hs}BZN%JRcvI0i7 zHK+LsUx7cke|-7VU}*E*Lc|{x$`7?1<_Dc-8qwet%zx!0{v=)xfk+;|bQa@}9QF6z z&Q(HIOAC$su{az61=CDuNi%hPi2Bd#b>{c4-kH(V0n+@sW2Jzzzs)rAD|c-WY+q(Z zhks-JV_08~Tcm)bp5`?B)Otz(^(Zt5vIETM?1LkO>j8*gx$A=9MwA(KFMcY?pFetW z@Y8+-U;o4Osmf8T4|PZSz(d`Rbn?kUwSN%%rw${P5N2hnkzdOSroz%YhSY@Ssn?7B zlj~|F%${m0;up@pguD4c$)8Rd=Tnd4^6Ngt?P>)ph7L$vUIu|6DFtbnweCK~y*k)I#cX-sbszi@n~w^0E{4w`7> z*K3nt@Oo%UpB)Mp-XHc)$s>Z{PK~LkKhGECU*=p3hUhV7w7OlarU1ta zCL;fY^Q*4BekkO>PyR1sm`-p$G`Tk3hfX2@&3u&+Jt5fE0g3`lyxk8|K&!@&;2K?m!tUW zcjZ(#Gs1w{p88k6Cg#^pZ6###wO5(Bg_7}CcOyUWH0wxb%J&QJU*#y~*P_`<*zILZ zbyAuB!~8n2VmdtOW2kXHkhc$C-!RTtWBe7D{({b$m?4^Pg8B8JKmpwz^w#LVrWSml zJ6G=17=Jb7^-V8@F%5HJ`Y#&AUnZ6dVQ^V@+Tt$Lf9}YCx$yNvcK*iHCW-m4Or-xV z%nybxZTrya<?0;qk__rVsN^Do1gD-U9ym9R7M$9cg`M)jA07=l7zi!Hi#cK1#Hc0)DRU zO{1Gj`=_4cdHc1#H#M8j_=WQywJL+4t6OiHZ_E0}RVcnPw@|>Fu-^Rs+B!-9wE8w5 zzuNQ`@yi$SYqf1W3|Q?(J+gNT?-%bM^wm|suvxt|@+)^v97InTOh;ui|5b|k)nKbH zJUiHq?$VLYPfq9e*L$_=Nn!FKNq&tffM)#mS>PqXs#0POOYP}2X@RspMj`I7v0{HW5nzW`7%cb>SwYd^5n02F2`>-T` zih56jNgvwK!B3?56W=Qsu084|%J1i+_=*ERux{E;<9x_jeEbn_+fAhZHX!~q7+Owm zd#xAkzhnN48xRb$Uv{J88nXR&IpR;+)fyV4n@N)Iu=zw-|B=1HFmFJ28g`oXS782V z>COfBZXId2GPZw?_21F5P^fdN2d(nCBkpR7gAb9uNNX#F(m_K_R`1k+1n@0Y$^XK>HKN!)r)r>zleww3H0{C>J`coKx zu>L#xTLE30cGJio7fas1S#+bJx4#Pb#{7wjRzTUYuA=+{=8r4CKVGBiN@WunfAD;S zK79V?zPu})J&46e?#TbRS;WJ_P$#Nb$@qi)&(>B7*gUtZ#`r1oS}Y{TInsg_j6XVv zKfh1 z{3!Yw49{|msL58w53J8#+4JwOrxE?Vi}?=~@*i6hL*R~1SE}%k)@LJ{218MOBaQlO zcc>C%SzYMu&TRh}$2a@=`k{7#T}1h9T)*|avy#_8T}1h9jDOFMLC|kQXS#2Dn!q27 z{}w!cN9^w`$`4@tFW}?fzVADW^cCL!HOyEKyL#~bcY}!I-}ndXtCAf)@Y zJ7!7ZdwW$6A_DR0Q^JH~fLY6#RH*_qZEvskdth6vwf4L;CO zRp}b>T`_|1-|u2Xx!XCydO-cF4Tmj)do2v8^N7{L^J9E};p@{pT6UuS-!2udCn9{` z_!11Oo_C_l7E0qA)(69*?VV_j))4l75Wc7J{&(P{P9pqb`#t4`5(+wYqHhAE@mmtd z>!&J1(f%pM?*m6A1e`F`h~GiigJ90tj`VUbY5Z35@kL;Le!V)sWrpnccs@Qpx5rJo`9mllLOM#}_qB;HwA0qnxc|Aidk8dh>PS^q@1tUWV{nURgu+tu~O^vl#xdzWH4q2%iGM*a#%Hr@N(lBg z&{&_NtWZMrd;@B?{~P)H{V_hDr}Oz=8v{{&jW5#YhF5|hvQY=>^^VQA#rD;Rub-{I zrGv)(4ZZSMnA5vIRjkSp@Mnnh`7^%%qW>TRTH;kH;1}1&9X;X;Nfk{s*1xGvg}{RJ;e^a6JF?+oT zgo#JnQo}e_KaTO4_Du;lj~4 z>1)KV!X+4%y=qT?-j~+L25*&c^gw%!_`N(e7?OXrr?O~PKW2#bzpZa8;Z9b2QGF=J zug?$#Jj-mSQ6GHop#)ot_B255F1&voWM8-Q{`ZltKFz6oE8tUx_P6h~*$+mcKGd?w zRRQ0)K5QVLU+zDr9hIN@B-l?}U){yg4^|g6p%<1*ENk5aSocf32H^!00h;X&B#Q`PV*T`+H|u5=b7*!7dAh{4D~-8 znG+A!{LJZQyq_xKQ zam_4VpS!l9iaf>-8RAFfr$l(1Wyzoa$@T|u|IpEAA#naaZ=aTblH^bEfHWx6v7ue; zPO$fb@|SPImcZR3ZD?ZGCc=8$-}kA+55iV7qJ3r3`Tq`uGhoQk#j8o}S$AqS_E0Z6y4@OeW@sMaT#Gb#$Ue zeXRG!iF=b%MTbvg{E#Dk9A*#%3GH=7_T3ld_s{C_^}V0<=)q%5f8-;5JbPCNysB;` z;s@3r|7}Z!${+p2{6O}-CMyIwzHddZK9%OjqNYhOF~XcKb7B0z`H^ZqKhu3fD|&h_ z%im*uG)xbH*veLPra^1r{bBsu?oEIx#irD=%Nzk8nF#+*uR|f`L~C05{EuK?WC;H| zauVR_NmH6}KSEe9NA<<-exa~*R%_AueP)OsjkJ`ol&^jMm!HJ?=e|A9ul=n={X37(=)^Yi^$(*Td30=@zD?;QA<3@zXGrN&E-ssF!te>ybz zH$=@$r$2XF(!cnYq5A)zaev_D<8*4*ude#Kc>Y&l*i87fy&;`8G+Vfi`LT3@9#^yc zKU&!9Cwsq$ALLIt9b7L;BR{Nb>2k{-9HQlQR;$;G`7z~0HBH(QOU8{`Aza7$$2QuD z`&0ay$}*R!uZ#VMDc|3vYS>&fzXj``KQY13SJhIKAIU`gxMsu8UtXh2T0aN?6lWtxIznv|-;5`G>J<6Tow}F@0H|@dMZQ&TPFD>J4v2Gbhwy>rsDs&BjDHUC@W# zHjQ-riyzDn!wrjJldm3szQ9%W`xnp8+deKBcKNmx)fdXp`7%GohC)%gE=_DaNm!5j z!#BC4!jpa$G*6x<+#mBpX}J_ir?jHeZR)V~j^h5A%qA(Y`LLOYAGm&FaZ_z>f2Tb( z*xy_D|9C!1%hSK$&%SlEz^yjBj^-Z^ZZr$_x2~^ozJG9=hTIZfdo@^lN&SAr{$uTw zO6rrnlH7myufJ40-#_P6{gchFWWkAdU4{A3SYPcrSwoA4uF)7D7|wFycITJ#{0LXy zU(Am^V}l?dteMDvV19Hh3kKhuU$R4TW*{no}3$ zFyZ}SekcQzq5n{0Ixa$*9}QOU_IG1*I?3H!SdaaKDYqCdPiR3~CA3w4AMyO+TW@u^ zg?@YKDe_FXE<^JV0@tpCQY&++Sf1?2?4!P@z~DIg*W+4pnV)j0T=%2!{qg+Y-R3W8!5x*zKFd)2$#I_C)UMy? z@LFBf?@w%>t7p{Ehe4}JcK?-Xe2M3a%!_yC&gYiVWA+j1`-|~s?!fnVj&4Ga42}_g zALH*G1cUv>rXu^i0omu{7em2GOPi+Z&k)wjQGLM+)nZsXm%rX)xNsf!FME5YfTwmZ zT9(7`hxPlrD~rK6U7J>Yun^Ykp!(6myhLu*sh*(9NKwCk@%(xJ&+*_;VMM2{lGYc$ zoEvjF^RsCCt+$2W$MbpZa@WD{KYjT6A%;&mIzRjN#1>rb3wvmBY>9fkxWD-B9m>6! zGZps#Ocb6^j`T;+sXQok975gOvHZ0P)o(xf?#=B@uLU<9YDwa^Y_bCvGv_`{DP{YY z7@z*%E4ghiqrhOfG(In6HQ{J!CVd`pUyTp3eViZplKM3d7xf=ue1-=#w5hD-sz4FX=tEy{^UyE5V-B$m|m@9 z_Awga^Qre@_?Fa!x;=UoEQ)*4eeu%xy}4!zm$>XVooQ{X#-|v+X03cV z!$KJ>JKjcpUEKfvc(w;L)qX>~q7xne{(s#6)1lIbYqCWK+0Ph$RY*VUo$>*v$RFfa zJhR_8Khvq|4>TU1K#x`Q6aJqZ>1WTAu3XFQPw19bZ2pPLQEY$P|EkM1?!AuAGv?Iz z6XW}#(MwAAgoySJF}`0|jOXsU)zEhfda&<@v`1TJ ze{p_Lc{LEU^y<-=>ui4o$B(o8`TXC32Gm2J)qi1p@8suyt?$@KRNs&By)k+ToKZHS z)2EFPo?i#yd(YY=@Cfciw~Ua+cl(W7AkxK*e(k$J{r<)H9em!4Q)YgpQL7k!Bl+UA!^%B*;FV?R^zNSHwrTqTAku-j<)+*7-%TsZr|cj=C%ht>aI+`pDRb{MCh z^Msb0Y*7Ec7~dg*4LPlhb@XPP%aZtB?NdRUE({Xow^fc}eY>aEcy8#~H`K;K8sD{S zYH0T4Wg6qZ4|4`{6GlCtQMv#6OU3#k_KX6oy40cd!=?4br>jFbExjjHep}1#@Atvy zw|lk^h2=l%(uy{${|xUh9-Ocg97^ho&iBCjWBcNzpt@h5T4an=zhCiuqd#U-IBUfR ze*QAUugXzue^)8j!8_+JG;uJSFQP*EiIrRiH}It~SmZMNsgV7xwIK~Aj_6FUze^In ze$`N8Kq< zx7IsS5h9Jhx+TA1w0$(S)056mctuolKN^HV&eo}Feu(jR*0?^Gk()?!tj-Ad%S8F> zw>K)Ojo(61e1-An>Fmjk@9~_*AMK)kezAT?Yg0oD#)oRu57Q^PaW(_*Q2E9<;r=R= zpS$o%3AYNg==*tVgx@zq`MD|chI2Ic0hJA!W-Eoi>v^GYxNmLx`x(O@j=y$(Q$c;} z1~lV&pz!-RKQX3f3M_ctp6+S4P`K`k^lO??A+-KBknY~LQn)Td_H*+73~tV?9&m4! zG`>bVCPCrdw)FeG1V?7y#PO5Qfytb*-y7P_tQY%!D1M4)FrJI(`I6o&)KOm-+rQw0 zW4Nf;G8%rWMtDB#zk6Nuf>O&0q8h{Sh3kuU*bm``%Wu--FOReJj$-?k?p4XnkcYrk zA8CAP(R!SJd>pM>z|J?s@zeahmDK8nKQUX(;&+U%WsBUojEV>J^OFwh_bbL%+{_vp z+)kmUpcN( z@MltET6Ub(-(mbr8=MSRJG7yr$E^~6ALL^DW!Z8cw9D;B>zif>*D=1JWge{DWJz_} zvgeOR`6=I+4DMNSSEwAt@Rf<|S5~1HH{^2#AD{GA<3ntp+L(KBW-}{j=T>^cbsXPp zH}HaP1Ioz3MhqWj$p7`7JCS?+?g_nPcTISH71DPO_s4Mq2R)*0-&p=L6Xk!x_Iq;K zbstc>Jqlqx-apHWsibQg&LB~>rSVa}hZoo8>@yng%ktlNe?V_yH8nJvPm;Sb{f6_O zu~Ua}-Mp{S;ceOeJC0x4^8Hh;+MkK4GmBraz8h#Tgwv~gg~~s83;qwE4{SOr9QL)5 ziO!$H`mgb7=CbmC^%;iwBh}wbG?~Co*m7Hq2 z%4Ie=mL`qg`q>k?=FSi3nzjYZf1>(@QQk`U992Um9Ax$b&Egwu|N6XI4K?}oXkK^b|5PYGf4d?DUI(`j?|-5F;W1NVAg@mY>TesM z{(fTnn6@?!uFYyfbG&_o>ncZad_H+<26ym92e7Wo@QL-?P4`={&tWVzE)7xtzS#bq zFJA%9TWV30<7tlU`-<^r`HpY{Kg*$vCP>=HQR6Rhqt=arNYiNHdM3i3Rn8Px9DJV` zCo=qHqW#yXv0mJsBm8{xvYYDX6Z==~{7GD^R(I$;qus)FnM|zTawbmX?wq_uU3;_m z67R3x3az9T+b5BSaZKN1{~Gn7-pPbft04M^H2zF1YiQLFKhhvrIzFBT9-NW&6`D9L zTM~ceua#ip{+4{vXZj82Cs+JB&F!A*47X=DW&aPIk9*rA0$#oTrV)Q>PtS3tHiJRt z;38>12OU`j_1v}S&CP7S6rSG*EmL9h8f}gE{B|}D4h?Te*F0qSlgY&R8*8-*CTwm+ zwW)_1KjQiWzh*n(DqsJoRgc|26Z!9-@(gZp-FC3>28$0cehcqJ!PWV-Xp#4N;rC@S zF+Sa8l-n3+rxBkUzhB~_hYW)w8PfQ)c{rSFQGA+y8Ue!l$NM*FOD1u4pRdtz*K>sH za^%0qB~0Qx8(pUpMlpSa{dd>cN?QBBu^RE`lvD3y{?Vo7gC|!(-3vd-Kl~*k`#9k2D!6;?C;9C&L%6>?%J0-`djPa1 z^`I?2ZdJd3G5+4zWWmr+ZK?B+VBxw7;mfpjD#!*kp=TZDIx_z%o=?<$>^?ZWw=1o6 zdy%l-7wzx+O-zDyn;X*Fc5MGr<=9@Nj}0Q~at1S&(-+Ef>gN;Ze?}(ca--b4Lcn!q zKV>L>Q644S&qr2JqhQyu{+wR+3uYY%q>9?C{z!)G>%mb|U~{vpWV;WuuldNo&)zVO zyKtt2`n0;l-Vcgj=H^v!R>_l~j=r>iSH1A$?)EOG@nKA#svO1n$Jk{R)T7lX(fmDZ zU-!k=JNfh#e+IULG`>fA*U)-1CTO&;-Lpn>3)-Bf`m47|+gESCKgXzy^l@IR{(f~u z-zV@tH}2NHswZ6#e?ac zS~Oz{^FJy_vHvb>@C(A0&!unDYpeB<7{3EP?*!K=?Py7D_WOYF8#yrzhMj6im%U;5 z#ryBqgLC1;Ccghsd#)OP;{1EHWRsJKhDxk;a4T`X@9VSOaDC< z#x;}1r+KsATwuW*c-&T6f3~-;q~&vmiRR~Ee7=~~l=I`?eMR|H0be+N`qs3Xj?D5P z1NJNzuH*RWRYeo7f4qvy8jLyd*S^S5{^nC|2n6hSOqPW(d%($(O%cAIOeV(Pjie-KI<+=G zUz*v^Qj~xE)HQ=^Gg%v6#4`M0|6lLIOBht+L1zt(Q~$nLzrIQ$+(iRZ*k&b-&(Z7F zK#M2e$XBnOj!fT*=erHCG~kL>B+|4ind;vc=O3H$`Nvl6&k{RZhF^R>)xO&0T<`rO z;Jfci_4^a+*KS)YxQ_MQ;Y6vAa2>}_wkOAOU8WLRc%QvrtY7z@sidcexN6i7!?PW^ zh0%Lx%>!0ng7JH7N;P$AH-b11`d9xa-d|T_H{lM%ET&*=C*T*y|L13iz!8_bB&xeK ze!p~f<>q9$sBRv6zZkzCIwx{Nx5_|n$M}Ks=M!C0pzUBS z8d}cqD?|9b-MkLhpu0a^)cvf0A34fDUDmIJSpNLN^w4-UzQp*AT1dDqy?epL#tgqQ zw7;H`6a#+Us>!6B9RhxF|763*7rAK$R&YFiwVK~z{1&eEg_kEzkq41%e-ihXox1UY zOU@q**ZWH2*Ky2PZhLwmou9+%zhy}Oo>2bcl81T0G@rrh`-}C#i|LirahzPE{nfuG z=l;;0)FrvD`u&LG|CLcyv`)M$ac}sq{z!~p?_rI(oB9D%)_4DLDf?@)ECkNNXx#F!g{O^2A5pn{)AY< zzw4oteG{(oZo92m6`4mPh%TiC90WcE?4Z@Yil#OV#K584jW_WAhoT+a2DF6>$J z55Ho3&krTsJ)f=+Q|I4xaem%-L<~H;TS;t!7{1L=|4wX*1NZiHHq|=D@@I0Se}8O$ z!ClUC29Ji)_#JOm!5x3>0tQaf_Sa|3FRt;;aZuhz8ow~*6-^Ge)0m%EzH;J5ZQ4$s z@ilw`{?Pt4%ui!JJ`8 z4wZXkO4{GO$&rwJ4&tcXgC#HMve_)_804i&{yB!%(Kz7&LAx{zs36C z=Y$>5wYnj7RWSXF@n;#61mBHo$dbKt7`{+_^^@2?a4&BheL3hhdw(eZ+CFFrwA*rp zsLr$fVLZ*QzvHjir?j^PE*-zZRi1yEI zo$8&m@R$OhLpuxWaee3me*a)cjh#mQd(UqeSABgaeOQz%iQk#mgF)-mS@LiH661Gl z$Y3rkbvrHHy@TNw+21B#A|XP4gB-fV@SBhDJFoG2xE}P8ke@#s82?&{;=hs}F)(l0 zBjOOp@STbB4}pU(aZQ`_)M%e4eU5;Z8?KRzkcqiiqx$Jnf;5L$Ge z$PBLu?>`gqgXmU5mnIIhmz`RFp!~xIbHYtc(FdRX()f?&^V0(#J`&mIM1=p7N9?$Q z1L-uO=(6zqIR5Ko=L`E<6%Y>(rax3D|GRtr3$DR#D+sDwA-q3aAGKqCDzxZXNmM#L zg#HDrKdkD{gA&g|qP2zP=Wu_4_4gDwwXlN7F0Hj^_z?4B*qN7f*I83he;SSte_EzO z`^yz1)4i`6Ut)dY|FoLgJ+~tB{*%_%JHn)8~vxozf9~O<~1SQu~)63^$KbHr@x7Tr^D_N>k?`Ee`luy=XP>E-IT`k3C6#J zZxVcTcuWej8VJva_lNV_y`tZ~7;B90S`148ONXbVSMUA;{^W8o{!Thp)3`Vb^5)#X z{uQx4_V1Dk(-NPNAufsP^0|>xzt6cy;kMF_{)8tjG0Jm;7@%lS#bqaAoUp{;gf&8i?O; zgBUq8{esV5Grd>D)jru0)(@A)@AkTD`1zC9$^GjLzqtP;yPg3zXO)7cv}O4ZT>rPn zD;efT-6aK^o07lw6HtA_en{c_pYIc$Y3&62Y>4`Y>&{Ps37zkgs`x~~{_3Fl3U5xm zrWqMMNaUG#;rFrqogQ0F`}{Q4s6Spl3xad&4-uQqY=0Kx_gq*c)L99l{28{76Ix#2 z`h95ws;xZ*`-M*B|h$YupiU9gX<>FMSo$BFK+{7*Senp?2`-eZV{d{$EE&SSXnOOgc6`l`J{of*aE;puJ2Irdp zTQ9b+g?rY(_h%Q0%P@xD0Cc|R>*Gb-w9;l^&|Mn86Xa{4jq^ovw1(l=9qEs;x07L^ z!#!dc@-IIt&VMMfM?qiH4P?UC4Z`!wk^ZRX5C_2t=Lr=5n}03N-|de{fvFd7kj(3P z0>0%4-&W&N;J)exQAH*R_{QgZmh<_$UWT1D=08R|rht>r4U!nk>^q)+v!iP@HI3;` zGAgC>ALn-P{b`?WkVh5FzT@))cTWj|S`YI`b!)~CtS=h0O@(7yZjyc5n0+rr`r9%% z5>6H!6XicJf6l!~fz@Mf5+mzhlJ-4+3$Gt4iiqxX*582b`}#k}Ipu_g8u?THWep6p zE+!ME1u=Xh{?zhij*(apGe|(RFgN;3uZt$G0pfm^O#CIy zpJNHhuwlw|0!a*Cr6|90E^ss~{+3Ftv)KKyelK1y7s}$Zh}+SV0{(G+yNz!Ol;&I% z@dM9iKRo0Wt!3FkqyEXClLE^RUli#d6`HRzobO*4GPtuw{gb~x1s=A&B;p62ALx8i z2_4IJ6YV}MzQq1Rc`XGl4&n9nW5y3(G(Yf)ZzOb$E+Au9G5wD9&taPt5M1;hdH9;u z-(dW!_8jL1ZmXja|4Ra6Kr4xmlA8+z{AVKk|LR^1gZTNEef2&I*JTL*I{lJBmUfP) z&W#lCDMROjY`mPn_s4>|HL^0vwF`tEsR9J55YKc3Gr z(kKBwCQy>u@T=e-64Cs%(?gnZnA3Ps0=6NN3 z;?Y{8|F{s80%5^tMEuA^{20=xnp#=uYs{awJ)Z(w-<%<-x0(L{G@rHsKcDQu#g+`;Xnsm~>{_^!eT*nPCJ65z`-gEKQy{S0SpqFa3)gXd z=%#)NkhP1FjDCzCIw<};`8F7)WM-4ush=hJ(eF|m3_n&xW*lbz0rO+^)wS?l>o}2B zG5jYY{NH(*%+IGeO$MxgFZ_Nf%HKrKSOdDvkCHXI()e%CGZ_vaI3>b=DZ+o>2QhGT zOd&b8nc*MD2i7f<;bF=tqThqzAJ2b#rI-X;yCf0%CqsDu?kK-GtosURIAb@tIy+F{ zhpw|&Uu|3y1rAU1$oT0Gg!hm6k#gQ2#+j@qrAB83e)uB&^~XE~u52TO_Y;!*2|ZFt z58JlTSbw^hw=c8nP!WHye`zwNnwGh=)~LUHKBU0aZIoyoWc$sI4Y ze~SG})9op+)QXZ+ZN?vbe$L1(DtORvCm9~h_<{FNe~(N7^AbW@hB5tx&(GN&91Yp? z^2sf2mS4v8`5(Kdz=~8t{_Rg0qVowZ1jX|6qy8iQbD00a@pakV^)T!FY4Ur$I)91$ zkKe6Cm>O}MoZO=JKj?h9=1sqVo_{A=mj0aaPbQ9EdNoaenO%<(lXi@Ma>T#$w-&+2 zJDW)6(N_XLGLb$D9}@?;4-b=rs~G>>k$+kc5dmxa?;^0{3F9xC&tmp%E%a~kpD6xO zA%0F>l+4%H6_J8NZ-w=Ee#@=!HSnkXA(4JlA^n!$JQ)m)iiq6==AZC3;e|O3)*kP;ZEij5-`85z|R2W zzoyoX;`1ZB$mlN8{;Sa)f5@1TEaE4gA9gz<0QR(5M`q~csrfCQkGsl01s>fgB zK>XcWKNMEnOD9j7F#f90{+s!m6wq0ARHP3}kpHtTP(ka5nIs{B@fX*Ro6Smr^*0L1 zFD2t|1v>x0>|Qj?8JGJyi4Ye4AKA4*n&10-r9h*oLei~j zq_AF&;;;T6+2an8hC9a;ykMn=C?w8ZI*7b-(UpD^(=l`y^ zOato;hloeIxxjB3;&-_PU*EK$iAH_ zmsl82W#13^?n8+YI?{qeE#h#jAk4G8-$b&qVyr>W~0#PJ2cEI}!1_ zcatFKv^R-V4P^Yn{NB?l9-@EkAvqXl$0{uPvN&jWi{C#~r1_FzAkR{QKzd4A%FgzJ9 z8RrwbS4=(^}0q)A(-G-EEp+-|+sFJ-FicZ>Mhz*)S1 zsui*pns47m!kpFh^C*68T9pL5+;^dxE{&1_7VahkUNe4T{rt{m4Hy|`iuP}@f9*Ur0<5>B5k+@h;s4?DWw(}% zhnven$;FSGgy$yltX z!8TH@FU_y?8FA38CWE+DdI{?dQU9=ab|S3amMQXog~`?aG;#gQ`tzHt8kW=k(f+7n0ytYZG@F2eugi1~2$co>m2 z-Y?9b!1WD%d(8!H<0T^f2nhe(-2%bsyNY;c?vup-?qkK=)V25M)h@c~`YLh#&eXjx zY3Zc*MRuudJ~YOEO+`~~JwLzrqNgk*WX{s-7)7Xvktv!)?Kl^unvbcW2 z$#^l`B`ZmXXUsogetb?p#XWCui=HfLDEvR%U)RAV5j5eOtYGsX(r5A(ssq zfAINu?y=F3b|Xo|AG|+Za3UFWzGjH{Q-$>7WUm-#b0nE$eVnhxzgR!!#3n&P?k4hY zei-&o8|~v@@TYZT_FTpve15Yqx5czWzId+Npr)b0O}!zDWfgu11nN z(^>s!CgRWex_p1fuO&ou{vO)DZn@7F*6;TtO>NlvtH^&1K0FWR$Ic`w|8J81Yi*l@ zFs9{xa{6E&;rVd z_@Q{008XW`<2D%tU`eU{0@@z4E^5wNm-7&+K6SNQ$`h(FPs3if#~B`%8@zU7D?T89=xa%>Qh z*Hj7qB@^-Ea`;T}@bD!AW;6d(g81>-U>=0-noQ(_T1)zuKVJ)A$&cN{Ey_lXPw{*X z+9&{AX8923cGCW(Mp43zt{~K*km)--KVg30Yx=zGrbd2@I1vIXPR=C3k>L)1-=7NA z#|{tS>$7*<*QoDu_m*(!9Vne|&E{`n|8nkjC~UbpOBDa${Da4rbKI$kKnHYgDajA$ z!}pKf3>5JL*H8KFImkq?=qQS>^Ir%qV2K$$Bu4~|0_XyGcIPOm< z>6;9mC!)#Vek}gM`M*QA)muOs!9^nfP>T8!nj39|V($c^r^D*UWvIUJogxDE1}-AyBlZgT!uh*4Lr!qD z1|6dA;jwCcBK9Bs!a_l7$t?2k{3ne6q}qO9U*kbSbTftjSAp>VsAMi|IW>yN`gNDY z|FPu-5WFsv#5xQRo==7J)uHAKp>L4~nN&Adzz5b>KHA^7!4FI6G8<|CP|x5MZJ;bE zdTjjfd?xYy%gR2BA^62)Lj0Es_|HW6{}WM7^SWKpi2qsZ&vWr-4%5e;X=?n6RNwJv#tClOtKD=$yfnV`x`)E-FO$fGRxc&(d+XS#@F?6>)c-3- z_&)7E7v|^=A~L0&B)$)19)w%<*OTZ2rjq!MU$hWxv)st8snYn4eNfC@_Q|Ew+c5i% z=Z8EmuAsJlMMcm3rQ?TAc1vK>o6*GJ#bQZ(*IQdnXTLkG5#MdSE^^J~`)RMi>xJ)w z?R%u<5@=FBniOQj3fD2dySHBfQ|!D%{gXJqH7s zWfjvu?kIm;?`bqN>NAs!vz#Z~AKUL)C)YsboH@k8huLQwU%$v*3pGFd$-X38VZ9E* z=c6T25Zibf+4Gb6Cp_P-?X(DZ=Q5GZYyDXGzH(%rowQDH%X@F5J{HpW+fuRu8qb=- z?=LX@fahnA-4y_D_YNT&(vAxFR3ZIgpgR?;UF<~tVP*)QmR|F~x`8df|Iu6$pL=#4 zgzbmoMfk+|)q$p8ITOoswDUM8wSN%jj}lB@(W+(z8ttoH*Ci0@;7V@lEfMgC^~KU% zRkUdI(IVaG#p?Gb&Yv!?Eau#+x6uUWWJ&xL<}3z_dxOY=*3$T^yKx0%K5!>ivNghb zjK7YffbT!rL`!>FsN;Kae45iO8VUwZAc{`X__ONE>*KEz$ueD*|H1VEw{2tL&P#7% zF><1Ce~iC!`&j7v+MDQ9Gy4c=|8Lgw2$-cek~Esd;%|(<>m@4CcNW#OrkEeIc0d&&_gV`dK_5OsCxfxF2XoWSdRYzc1DYM@<&O zqcQg6>e75ke0rYng(oTIA@c8c=SD!&kxm-z=b#(A zx%=}YsEdg-e$DQ0fT?CPNO(PFKXHHh^Ia*RZ99bo+{txh_!7^riK&_clkH4M{-N_y$+)}qo2(ZYI+-*DqlnEca(=yYQ78zB8UvZjiLblg$o zJDcsFro8eOM?r2VikC(=8&HYPUi#e(EJAVeGU_Vg*%h+)% zpyg6)@+N}e8|MezZ?1;?AC6>xGQ+PN`S)8Ni#dIxM2+|@m9K_D-5iPGh*`q@vHj&d zW8v{~SJESt;TOke7njFDk(nEL_sdaOkL_=}11q8aB3p75wAued_&t0%o!j-+o5tGy z>%S7)-yGilo=H&9O|7Nz`*_ZL$g}89zBV&v_(Jtf-F~G&a@uH;&}6S8d%t4*uKzF- zrmpHtd>@8M;&)TZ7LZl?5>=g(Y`si;zEQe%0Squ*NZdMYQR7RD@BSfP@PX+=Yy^=KTNRBRnywMw7muIf^scU;AHx}bv3~6mxfC*rx{`sr*mZ259S>gS zO03sX-*;`<_ec14?Xv>3TK3VXZ@ZgC!oCx|Np=wHzsf}Tei&WMX-|vNh;OfFk&vHf zOj1`)67G-Vx2;`P!-WMFg!l{-t{bBK-19+kFzc8NIXRW#yA=l8y^)BXBA?*6_W*FB%F*Y#T0>jD$6naW{*!&&9(q7A8PGiq5a`r;{-Ebby8L@>(BFJiTLmMN?o7QXtHw7 z0m?s)UuU0N1&1=)D{tOeD{6nhZ1wpE^I9tVJ=)7ZzeFbF|IUL_Zv5I!D)xq4^ZY{o z?+2Q};2jO?U^^flImVl_Oll`A=D1sY+TOt#~k3eE;rk z*;;s*rZ3v)Sh@-b8(AGrV1fSgcxv%o;v@h{cyxW2w(j=F!(jc!W4iG+VXoZrbz ziUc!RZ>3)TV169ShiPdHCr=ut+V@hk{|cQC()#i)n6ZdaS~Q8!@FkQFS!-=>QqzOV zGe-*e>tp}$R@f1a?Y2<0=Z?614AOT5SwRcslW#q#ens+8&u=^Qe>YnBL2{hGKaO8B zdu_l?uc=aAwm?)qnlH10B?lWTJuRqxj`#QOo16*5eP=3fn(X55kMpBLzM8>u^B;;t zA94F<=y-qVF}=CcvM7+34++|T@~6TFOqc4`xjsbqsZ`}$4p9t#w29sy_22nE>;f0R zZI$X%^ke?}V)=LzSfe`iDqK-leNK9}BJS|Qm8$PuV)^-aeF&Ks2t5N@C_9bb%#TN* z`t_N9`P|d?Rw{$NjWqLx=RZvEDTh`gS}KpV3FpVLeLwK~HLl9tStY58;`3)X{$bH^ z9azrlpo}sL;pb!f=$d5&7|m?2+>vRe85h&9>is+CTJqz#zh7tf-JE6IFje>!asBV4wtprppQH-Xq2ste!~Gyf zIB(EESweb?^4)Br4OA?aC=-{@73KFxCkt@N{HgfXgXZ@Wk$&%^n*{-fjg?pD?4kUi z{tKH-%;4XYSBm;)#O<438v|ghX?N=m~cwzngWkaJ?`8T>~{BvP`a>?y#)zgI@b;d`GZe8PMU0kMml^xIjAIz^? zegI7KsIR)8@)qV`==v0NFp;_1D4RG+pISr&SvMg#5;vM?mh|Cd!|lQ#9kk z`19+i5Eyc+q0;>$wO?c?eph%a8X7)nr6ffS`T1D?28}$zS)3WJ3XzNJ-$wIyL7(9U z%25pUFD2-F(YuozVV?A};)!i9o-Y%mp9l4~g-wSm6^TEV^88}|@^1UnaO2HjB}_@? z=SvWuanZ}b#^Hv-^3(zP{n>hg{#;?F0zrPcMp4q)p63(qA9o)2mCOI+q6#-*HGB!< zcW!gbR5ue$6>l0xQu#powZOW5zLB0>wPmz8pPTMitBgKd)X8UQU?I0-woLWSoa#@^ z=i>x_xTUC4)Y{*cNWV%V)ceaM-xLRyQu{)V_%pnJo|~RQR7Sc@H1a95FCfR zg8D8!#9zmD>tJh*M0s@=Du0~YjU|_!xmb9i|qq>x()PQ@<35*A7DPKeHKEX?%-*FMpr}rDhlaG{NBjg_*jt+-gi(e^X z9Q*O#7q9=H`i8^J!!H$4i<|S~mMH$Qsz?s4)1NA8^K%kZpOI6u2gclPsO+DW#Pfss zeN*iU`VDR(IWzrPXEpJOY%A$L}>qWpJ|rhF!%^*_ME1(tR^r>HAGUHtJ2 z*Zl58m94h8{$=M?sJ_8aMP27pJsem+pRF=c&3N8fqrZjrL1T6OZG7ygI{AJ5xkdi- zWh+&W*NMmX)Ol|(Ja=C4#f|cd_3vC+7*bkMD^#(Z%2S{#!W@$?y3AZj&BT44~Oih z*A*#e#re%x9}X*$uPf#l(fC~y;&+W_DA>-uqLBV7<@wV?{5EVK4F(gD%2Ol`FW~hj-ruytZYk`J zNmV>sMEe66p!}Y6moK#Hazp{kvqbrB^359bw00{RcM<2?`m7%`*p;Rz$qV8CpB(Xh z@T?1bEKgF@m7mU!`@-!i>#rh*h=xz0eNo!6Le*|;Cq-T72YsDaKfh`5C{>fz;`-Uc zS#4j`bX9m>@DbI|qeBY0#!DNk?kp6yFNPoWhiBuD)@fga9}9z^)me%!Z`SjC;rPYC zx#zi^Hyf#9U+IbR-ErzVC~?bCjEWA?@YzUUpS3NHhVjEdu}w<%|6~2U@Kpr3hMrcW z6i~kPkba&5;jp7TTai&B&i4VQaJb-=te*#0rZu4Z`z;aQ^CpEu z0F$k-7(@FX;rbx$IlExvzFP|Y5!C*bv%>t~)Ze}^&iaVL_xgPP|6u#$(B>q_-1tn9 zxapKA|6SbG`xkB&+}h`^4nKVTSB%=ydtHocznY2mk%t-i&K=eP7&qbqXSb|LtIZh{9mE{(d@J*u;(``9FJ!3{}W_MS={K0hEE~? zqmGoTF5PROh)NQ#KU(KnKmSgLuBuctKZ;=Ju>E4yfy6ls!)&a2G zcAH}ORBFFq`=r%Z_5KR)3gyC##{BzX|4*tD2K|h8E9yEwqv5eaZpOOzN`n{gMD3TC zW7om@8T%D0JjLZB{Okp8cD-t0{VM98de%(6zo*j?g~QGujeH6H!xnLoa6f3D!f4BM z&A8A%^wEoeJLw6EvgH2!IF9d`E5admMuH+Efvyj(NPhCd!l7}41cmMfDnD{0Kd(-O zL-hCrh5K{5e*xE*o-6T#o&H-Du|t>geBk}-7u=G-x;rRV_)_`6@$GZ+wLlJUQONte z=j8+2=N}$h!DE|nMeX?nIR4S?jUV*emq3vJ1-M_f7cs!}8&GH3U2|<%%?=xP9Nb%Q{Hv5UI$VMES@5r*6&#ZrbR} zb@ES6#lYWNn-sIs0{Hu5|MbPZAUG5gpy+5kiXX@8M?JOw>bNpo(LaX9_i%nQ_E|W@ z-3n7wzoPsbA^u@yIDlzbo$H58M{R$73svl%a*F@Iv8cX!>jqCa*v?&1qTI~>XMbb+ z$v1f|^qcIXkXJ1fm5)t&dmz_pw_@7f49$FD{xi8E6js~|QB>x2;^zZeKdu_sz)x#S z#jxLW{lM}e3lD>BT8kAWZQOYIk|F;f2LFK+ualRW@$f4@+d_`^iF9XG2{z=zC1J+!i-!b3ay<*k< zvz!zIpUe60gYBQOlfB@!!8FCHX|?u^P=5z|>Tq+vl`71t==lk_KkG^o0q$>?Do!i( z`0L~Sp%){=;bPVjf&Rw(Yo3Rw?dSV56bH}mrQ0RUdJF`>v`{{XViIudevYiL5}_`KO1%!HMc$%;$u#5V#s_s8}JR z`W5%T>*c==E|?EioV_EiUrW{f0Y`jb6sf;y{sr%Uc{$n#QqOc%oO?_4V+raH;2apn zl};L{9HrjJ!p9F#f8f&tBH=*tK*hnwbbr1C_0N*d^M?tJ-4)evjsL$mK9UjX1-*B7 zQMBto&ws%CyC!S-K~Ri=qSe$m4L?HryRyt5jBj*TBWlLik+urTueVlwo=fe2tUqsPhk?oVFL@HLRT}$5m_HA0yc&$o zKFo`LQL7(?e3}J>!}C?&^I|X7XXyGMw7=uxY+#;mao*)s`$YMCxmTCl5gnnJ)c7v{ z{)uRRe_{J~s;a~Vd3DuCzbx0v&n-~bMmdY~yVtHprN4K1o%~kM2!g%6KICQAP=0ZK z@Sc4*n2-OS*RtJ4{`qnIWW%EZE`PC9361}X+Rye}1lZmGnfE|eYyS%U%kJa1f$P$y zikUW4KIABVGN3pTOy2&^YdCHOe}CM+QPO`i#CkPUXkDMkk4q%N{&5d2ykSPvn>+`r z^ZfUfqxkjbpkN4}Rh2j4_dyMR!upPRjn_hX`*(S@{-G<1@0l;#3wrI_C<;4K{fO;f z<+D&2H0w*=ljU@M$Nkw1udV{yE%)=wMEOJYNguUixG@%KicXsIg>e3PczrL} z_F;2guXVt`zXb6aTj38AJ8a9V)sL9JCV6`y$oX7e_;Sjh1nvLR?-~l@yX?yQe!U%k zeca#Veu5crqeAj(`#a$H+%6|S_%)*-SHAH9?|&Jf{$bwt*TCBW=W?s2i1YVzS{NAW zUC-5X?;y&bSvMPqjy{>2Q?ZwRUskw&+dF>d4u6}d_#H<1!}$~42NkNF4#RWn>VMMj zidKGQ(LBX>Mx4LTgVg;WPL0m3%m4C734$>vFXX0;7w7Nm`$Degmad8(TXi-6Usyk} zrXU>lxZlj(cbxKh6WO0NOG3clP~-Ty52#XVX-hxMa*{wB_@=tbT_KU)8Z`7Ar?23ur`+|)>#-%CV%`sIYd zy7Sj_TfGe7`I4jlvd7i=qfv5mK|LSzfPRbO?{_{51{@BTl|-UiQUm$ zZGBq*hS%?J+XBJ;N|ABw+GdLX)?XvU=a37bU_A1gv0hvcoi*A8K4z|AU}Zt^9l8^O!MB#QDon*EgpGj5e;* zKavE){;CVcNpX}vY+o`z3%QZox-y=J#QA%;HUj!Z-!eY;gzhiF`Dd-ZYhjA?ym8(Z zD^dQIHui#6l`7-ZJLCCrtRH1P-GSMuF!pQEn;(}W{rG)(7f{*|;E?`q$XL)GhD?(`=RT_eD2(zT}9{&cjV%K)1uj)*WenPmc1-+q74!miAs` z9G~-<@+T97*CkIs27ur4KxypVhNAo?sn0*lo*5=}?cI%^kNY2okG6*1FRi58z9i7^ zkMyVM{ZI(+A11X`Qhw#gzU-W+m2Y;t0nz>2Nt6E&=I0iu`E+$JuanPXeu2>VZJ@Na zz6`I=i5-i$Ot{RaRngFzdogDLm-K^XZEG^VJq>Rg1n}F#h1vL^EHwzW4VEg=VfVr9}hi zIPMR+v$2m#tF+MguYW&&zDy>puU}di3TFRaN|jNo`Ed!_KVnf+t@`?GrnD~o+NdZ1 zg8My@4%kWa3s}G2Ulsv7_m)XVrcpj|er-x-1Uwx3PCBq<5YHd3|6OnG4j)TyOC5eN zluvYi;QCgc@Y}jrdi|iL{s!^;PA`n}y;;V@t`z6@q4Op#W$`a2sFOIqfAT%ysN}BH zLW|m$GNd2-6uZKwfLqcv2PnU||3vf1!<@_SHstxO4I2F*^p6^bJ3@rws`SY%T0fSE z_}-=N|MEWWwKQZj^>6U{|8Im7q%FTD)hS5e`Nr|1IfV|YeS;fFJDXSXe3c-6tJMCT z))jq55*^0#TY}=Bn_D=mUQcNxO(~`NPa+fgM|bar!o#Q@jKP}j{Pj~2zp()xs+qY> zq1X6mYMA5;?oX@Q2!)f8I)fc57;b$p~(&z?+=ecn8OHx6M0_j{9T%f72|9;s1thnt6&sw));sbY!@>TWQ z9FitAW-^=5`deIoV=~=Ywe`jjX|I&WJRfqz-<>31$dOKCYU>vO@t1$kMb%kl81Q^vy`=Pi7!Lj`in0_5PmHnt4of){!5_`;+?gt5Jm%8rhqt4Q%DFGq;;XRm0+EjaO(ssA*O z>Th&@WXgDFAgL@PF&eC-_NlOb=KW1axR=Zb_>-gjPS|D-)!TZO(u}RO=O+n1k3{c> z7Z{H5W@LSRc>RX+I}Hc8shpzCr5_&C^&PLzZ{0${p(vCwnbeo(ONR7YR;;^9`?rNu z>ywx}&;l{=aa24r{KSZyCz?CQ`oiQ2*{T zRyC@{mF3d9;_G2mp%6MXjB%Ny;Y%j$Pm)w`Elf0B%M6-8{p(m%e;ad0eSX&)7e-5W z0ssFjk^Xy;?g6KsdN5IMsDF(0-?nk?&{|zP?>vP1Hxg9evMkyc&OP;IvX8gnuP;OK zpLb&-L6#cH6#S#{b*%rszKQ1?<|mN*?Zx>kelQ!Ve$HaXmU*-P@rBpt;-k&D#$Q^H zOG*u&sQz{&_`$gD{>;@t@%Z~^zZ@>TD37f96Q$9wLViEK_JjJ<{F!Nn)c?lock^^d zXnfF-an0Su>sJZld(H)aNE{Nt1WY-?Kfjz6?qBORWv!}RRixC?;V{*&tdRfh{oG*V z{!NU;aHOWchA=+AL+PuUzc*5}fVKQ2f7ukX5vbDDL8WE9f< zGnoJ9-{U!_U1!M7f#UqTE9XMz_wLM&t3E8xKk5(lytEl78Q+g=?yKPMkN4-q*9(A= z{kJh%55@UU^~~WE+n*BcpW^&~|Kkg%muz9)Mbi33K=IWxsYP5~&IfX@THU8A`2UfM z_`kc{8+7txnH=e1{`s+gR&vl4V%a1{G6&Al`9i*i@({U6Z7+n$yCeJb$c?h+SO_2S{ya`dQ8=WM*r)(k0 z_n85qFzM9^f&GBbPdcWqe;jhO3sYD9<5%_h>PCA`FuA6b?-Im!jnoNd58E%`8|SAk ztNl;QO&N@7+hWc03FEIrT*H7nbdssvzmNSllVB^j$n9iaWm5YB`)^%;c|x4*5K|lf z!ueM%KQ}PClf+~U*Tf&t`fx788;-lAFnYEc{g32B>bQxsxSCJu8;JXFJN5*@mWrdy z2A1l7eE#qq_4=_n`!@O8NnC#HWoO~>(BI6oIJ&;!{TXit<#1U#e@Q10=if4;kbAU3 zhrK+S@|}qI?$X~A8hkvQeS-H-)Yv#d{L?JPvJbUyaQ#&i`8pL>u9C(l<%sfW z{~`=NOu5AL&7$_R48^Yun`~5RdlpK4Ki$>L7up~78i&GK>mq^uVTtUIE9(05Yq`Ui zTKhvT6Z&5zpF`l!gdzc-Cg^;i)G903k#Ur%4qU_Q9~}Q0qVNJTD3>|CiuzwAD84mr zT?hp3EM(es*P{AOBCJ1OU%DJ-e@K44S}!c3Yq&w)2M!8I|vrw7M@8T!n|3t)ZRuehQnslCt_F6%o zU)E7DKekTx9FP

        u|n09O(axN}n^=n*q z5yoe%X8CIBasiW4_P{Gz;zx{+CGDR(`g?3UoU08MLmd^8o6Wi4EnJ3i6M;=(eB(x8DC=kH2hE+<_?_7`ujzzv#}_37VE#>s`gvmj9mo% z=Zt=>%=XTHo$Q_Y(1bQk`~Sw@)mvZY|6{A}#iFPAtUvR;b^-CvceDC-;K4KOzI7H? zf+YS#eH-w)0=4=66zcnnMSZ(Az7a*mSEdPO>irAy{a6F)wWJ-RRCg@>>;Dt=jUroM zjFk~PzqS8CUrJa@wEu=Oe~qJB!=ubn=Kn>1R%PKln&UEww)a=&ulnlta3Ag@>rWQ> z>zL7+w9lAP>qmbS^UK_h-Lbu&C)*!bGHeJwIR#=?xiWt?^(Wwi>V8|U|NYngL>yW? z5`7y;e2Dx-Y0pDI+!VHcG1M>zjU8vP^@}})>rtUp)kCpd`uSr0qS1=I=r}c>%`fxD zUPO-}yRjfo;z!iCrJbMSTm7?m|L=TAosvcMTSnI)lt&@wBq?=?=$VOHKm2De?sK%s&5gV$MfBkw%FfJP*<1b#w zKVOWPhbJ52SpHTF&q2?PGg|P`W;q@8vMK87Q*?`t`^ofIj$k1o=N@VB40td zt?1MHCS>fd%-54&EwJZ<0oxy@vA;jL{qUk&=F0VtLvP#QQae?DER&yFC3iq$b4OW! z;Xxrk_X(DYK5Txn zlGU$}dY3V}pb)1HNctq|*V$$-;o^E)=Fb3mevq0~i8il&%=Sk|Iya`5Q<3 z)7AzsPf_N}U*Cn6_T~A~edUBFdkt9qdKxr{@HV@^y5ms(100 z4ILaE{V)E?^V45B9Wmvd1InW$ebOd*|9$*uFIuPSKML(H@h9q=&%_YqT=8Jz=MB}} zt7hXnvig?3C>93_Ls|b8csmIRb%x36Ya)Mz3G>lQPj$a9bN)0Tbty91q_Fjmz3Vn2 zx+>3Kjd}aCZV`EywE5^FoF?r>(}XYj{LlzQP2%ir?ljVU9h zA{C}7$IpoO)-dsC0I#*m{59O|LX+R=(~arM`nGvcOSH7*`I}s8APp$;q?BM~{%p2; zV(blb_I&+xoIft-I>7Lu#Mga6-^R28Y3Q1g_Bn|!QQtZY3dOex9<09g>OCCo4t8Mq zy6-*-^*)BMd@Tz}MvCfw&RNeT{~_`f{$@Tl1;n!P^O}7w#(YV}tWx#+^7DaP8k^u4 znZf$AKfm_jRnZDo-#q(Wfl1mGZ2OULsSOjfJ*pZ?1aM19ljQJL~}AA!4{ZknY& zJvLC?-+Eq|uTmo$w4b7bx4z1J{q%CB=F$4(lB>*@M-^vuJlcfq-{_h@kUZ*nl4);c zzFydQVSx|NSLFfebirvn`7Bk=4;J(dfUD{Zqg_|&?-%)7Sdr-X2^0Fyr@~)-6!k6s za45{zxwHL2g(f3#z@Y=`SWEFs%nu@KO-6%|5H>%sD^7;q{vopdYLUOlnG5jc{6wts zRsVc>{mp7+E~Y0Zt7d?e`8zvv6KsB^v+?!K{Qb~ty@EYo&-!x(BmWd2T2FocB(Lvo zs{bEcO;57@iRnu!Q>4v9cE11aG<`~3SAj~8DDzj|!UkrA^^tO1(ht$U*%i7{w~vjf z`x<5b*1u~BqYL_&+(rF<1zCREXX_v;z1@a>eOKo1UcMJhcbT#J);TVnD*YZuS(eKD zO=%T~CV%V^aaiI{%pdHth?ev)q5LR`KT-dR{d!_pHJ-l(qeftU$M$S}u3p(>lpgDW z8#C1W$n(>bS}9mr9xmfAUdT`ToLYeHmnUFz6ZQLY{+is)#lX)=Z2mCy#wN5Lna=88 zrAi0TbVnY`U*qjpVVPEdN8OeAOJ4aOK1?{l@^|ZJWjZ|b0jqx*FZ3zQy8<=1q0C>{ z4jZ&-Umq);s`-)EM=DsmkyUhKir%WsU({S@ypGUE#d+%Y<@|-73!`U+ZD{NEQ~&&# ze7>@%%nKvmnX>b70Xx&FRe3b+ex+QWYq&EI8-~jHix=W=b`Ng~*D|4A_ay#A{fj8< z33PX3^VhF>zNBMePVcH3{;luDd&%!lA4Vfl`MMvgkKT3T;9Sz3jnBJ-Q_!?&I2)g@ zHb_Uni}5I^s?6uhh-LV;J_#8=mGyC#)n?e-Siqit9W6M3kY0H>BD-I)rc6H?X_P|q z%nnu`UE93IjI!gh{z)-D8~IhCQTy(*^K)~3n^3;$em#y){fEs_XHt^@%oRZYvMHN?+#8-j6H20~=SpRL zth_D|-}>3Xsj;Mw5csTD(T8qtG^TvVii+_$%cK`BuW)7akDs$fBJ#a2tB*qt#bJ?N zcXanq^CQ>CS1~DAs5O|Kulvy<9iy+uu=$7Qp=Ahdp2WuINryM%{fq@{e6H}~09$jzrYmBL8)0K++t#c$) zax`VnFJ6~r(6lOKR4BU)1*JP=n^UY{UU!__u5irUlTg(Uit6upD)y3;`jH0 zzK$!ak2z0#slppmx|-VbuRh*~Tp!=+jzUmdp3fe6Q_v*48ymk*)t-rld&1cIOu^=K zSTu}b^Owo4%i(i25&E+Fwmg5C(rODj)Lwu#HKp?bu|D&CP6?vjm%}PodM@sVa;Q;; z_RF_po~3g9o*nuI3JvnV$MSj0z<^TTsd|LJD#z~@t!?q+O;x z&6ka+&K+ewV^_Aqg#~)7K4R8jD*5cr_CJN4QSJU+X~OEGUuIhxtzk?}Qp5i7Ew9f! zuF)AsRr^1C&Q|8rOBH`}Jxu76PnEy#9~91arw{9m^-(Tt{<1#PkJgPbrIW5w{MIHp zpYzX;Lc@ja*!+6OpsDz9D;Qg|mGv{qZYB!H4`S;#RV!t{rtUaaKi@A}j>TSyZ2X>* zz6Enfs&;rX=fCG_97JyJGM3M3)63v?dmBQkEAyHE@(sFgKg#;ctEj5VUGK8-`%=CE zHJYtK4eXTlvuTbk`UTX*H4EwU74`F4Z4Yv5--s@qR_3#9OBWodp(o34MEyLyFN|E9 zy3vu>|K@9i`%4#Vd85Z^V>Z8Ov1%bjctw%hJ!So@5#Jd;>zcFr8ULRjUEW|qGcBwA z(Y}GQ z{wgv5zEIPjE<2c0>ww8#|I_22t? zviFyp=i$qZ1em+1-;-{yq@eYvHnfH+^L;_8x82)oH7ce`v=AS+RGxnaW{bHyNO*UO?^3reuQ5B z%cpq0{Gmb+Ubbw`>Tj*2_Oz_K32li|=G)P$50+MI#ro6TN88iEnI<%@ozY)^AnI@3 z=Ml(qY0K*GVa;h+_^}JypL*=VO!zz-!0PW2osP6-ktsdTpY)f{Jb~{{4>J(CZ7iGr z@88#v<{6mL_>3)zd>PLcet$oHvNRjKi_+brLSqnlF94AuRJp~`$$m}G|@gSAjVEi_lDt4BUZoNLxS*dl#Q(ZDf-*3 zdL5|4MPtGuWqw^x^?`dIXO`ctLpsp-S|;@Knliupk3^#XE+2I9QR|z$e=PC&G&~OP z!q!I{x0!`P*8wtp7VA@I-gO|2I1{=Vs?6`$jtlYQP86%p%WvhuqkIOdzt*Oz{gqbp zFmH%5pD_W4@Z|PVe48vi7xmXb|2j(RZe{&%&28^6YWrc9PfxdMbg#y3wtiLXbW{47 z_#2-CmHC|V%nrwI)?xWvxuiAie$kN3?UnV{*vJ*zlSVGBe=|)?f=;Y->2SJ|HHxHEMNtG~a~-eafJVRpXrTY5EW)Akmt zzps1@Nx$e9VkRo{ZF~~?XBih?w>XHb3Xt9x`!kcb8`9Z#KM}lGneSm8?XhQkZA7e*^h?YSgD141br&13`aRv-4VV2I zvh@q&(qWW!$%V?FO8PC{zg#P>Exzd(vh}q>)$Dq8)qDh3pIG;xBPDh>q9KM_C4ciL zA^&STryuSoII;YGvGXV6bR!D&HBr>(tUseM#fj(lN?ts+tL}f}=I85K&qnQSeP#PS zM1J>w^rPuoP08%Q#J~EgP4fING%ORZJB((}XV0tn|2(ZJm95zH_x(J9-@fNo;O2no zY<;*+>+M)PNp**+gT$w(&ryYkVQZJe=6~LoZy+s@=l9W`4|sm%plp6sJfG+ns71@J z+(2C@^Luc=A$=V916+MrE6M@)$JA!~Q~LdEL#NPy!bn-4-(7NpUr7Tt|La>kj4q|N zlKJC2L7yXcwMCvsQ?|d;W?dJ$pJ7Ia&By=cQ_TOoS9Zm(`c?>AqwGJb%<`uS7YwOw z4`sfa{?`xt*R){$bBiPX6#UbW7SB`W+xg)bl;wl91VB+kMVNR%8V0uQx^b z5iaY~`fVGf_aXP!cP^~Nv(53a@2CEL$o5#{CWxlig-Qf|g!{(1SBK+yxV*{EQu==0=%KIPgsP+piY-AwQ?>u3@ zO0h`*H6GKHepiz2KNt18-r-=FXrXPQ#mMH2sFefr(R0oZ%S5nDGa z^FRAU09Ah5ly+(<^MB}Q6mnGe$8hs=T^9ONM1`i*a!I(SR9_bOuQ3BN-2&nCP|cV8 zeEMgOKXtFxl(LuT{pC{wy0Y(2p=v+b&ECCPf4-)-FV+5~M~=Ou@5ehq|37*xLcOk| zQ1n6SpU{9@|L?!{r412{X^ETi_v2OPRp{yw5051E-!K1u1kKxlkZ*I?{L^XLQKX+* zg7?Pi`AvEM#Y*2>7}QPGL(cREt)Kb{Ee;-#?N1Qvf2E<-srlS%s`w^-zr^pyu|7sL ztI}7f=T}7iKikL=p3`cw{Xsd?y;S#8)u-L7mA@Yo&bs62fAwMeS-HMaxs5-Cmo*`e zwEVx{4^jV%0)6qLxQWc49~8bH{m1yzu3t^4(SxDV_e;1R>s|G3_=RSyzZrVYpFXrT zAkVU@f8Q6sA6azzGjS&-M=OBy=|l~)wj^2{F590 ze!mV1`d?}JDzuB4#@1JMKHY&W5p&r3_OiW4Rs91?Sp9dsc?&a7Zh-zciBD1gwZDIY zP2~f!{YE0+T}rBx#;Y=zu8`gr`A%^+rfsVG1xp)A`KQQtXgfzN-CYC0$R{cL+aDkH_CkbFZaOktoky41EIgj@0LF`?%0IEkAZ9@YN7FZ!SRwFhEhT?e+m<3myay*|@~?e7?s z7LEI+p3t4A)<1dud+2yo{5sf#W^b4DU-UnfN6bJ!KY!N$@i{jIP(CbLGnXYd!G5m;3c(^%s%< zRz3Z2Y_7hnKSbm^@M|FXzivX`ul(~jf_^VN*$sbonzR1?yLTr#WNtv)-b?-_-b=ne zJketiUf;84{r%6?(a5ddhRr{9cB{@#;ySW?_O3Y>R~Lt}{@h@Gd%9fKh!!1?^f}R6 z?$00FW#MDwaJE0BTgMKR9i}Jq=l2DDK7J}6&YDy4pqAQS%lV8tTY!B%XS4pJ?ek-p zQGGFHwNU0W;o5C<7`UFT4^}t%f@bmiSba8#s6l&Lm!jQfWj=M2Oz7e6FL0_Q@d?QH z13Z1~h`UMEVc@H*&uJGyKF0NA{zKd!u(L&L%xzl_@9RtNi+s*HJ&IiHok-V7s(*{; z>y^s=u(ydmUd@)?7x|r{+CBfl%AD;Fd2?|P#`xQ_=QI6d#=$nNH8T3B^+m3qL4Rf- zZeItMzjvzLgF$yg*!rGXXh-_gQID?nm+Bu7{O^Z8S*YG?7`wmeiNk7Sn5yoOF;?bF zKXNA;Rhg~YPcJ55)oDHPsV*Ga~ zszDFOUS;`ebk~FiJo$_(y2^a%<+i~3PSs`e7oz@^)+L&kT$cmL^D6KUW4DQUAF z-F`3ew@2Wwe^M5nbsfs?r#t`LpZ?_OQQu^#{x-~8UZ42Ye>KKy#o^jh_4h}ve=gg1 zqSnM&Z2ir<$_Z8fauy60DeGVQvpe|Z%kw#VO*!f(7b7!H;!~_IL!&177G7cb3~p^o ziz|Lcw23mG?=Q80)jBQKpZchFpXeLZrO&%1J`W0fo~z#md;EAlr#_6Jr9U01Sx;p? z8=yVnGxcQk36al^(b;5sbO_ygcSZ82UiD@9&(rEXkXLHTo^Ky0-AlQu9sJi0Oa4ql z=}i;MNh zyGQKb{OF{>Z;94o)%_?#*!^ThVS!YmOpj((-2C_b*#f_@$5-RB^<>sxcBx;8F`s6# z{5H}%fry@qSbdFaeizrKt!3*6*?Y<{J#H^sKNvo@Cavgr1-TZ|erqwmy1m>6gQ6;; z?A@ytzBN>LL;9QQvGs+$H?nEZ^>8w*cvX?_DhGNX*w2)W|9({l<6Z+> zw!U_?&UiQvb!X#$_rnR;r@8~4o8Nd6l!}={yUXIg$nT}Gi}CeZIJ@6$!^ciE^M@WC zN>Ju=Vc#{V9zF?C?WOo4-p}A4vHr!6~yFD03*zuZ%D7dNl0Vg2Q< zw6Cc5um}zQ^}mVnf5Wqy#Ki0OI{eVeUe>sRYK ze#0fFB9uo;{y^l{#H1D#hh2hm1!aDt#+p$kePH!7?Uobj+^fpwM>=18=(~Y7oiUU8 znhs8M?*1z5zF#&6vxuNGeDgKD_=^J7b@$`K=mQStksaSbFnC-v( zbEga4^=?d=r4pYf1wLJ930`^+mYpAn^`&(Eu5@a2V;VMp%is8)C*<#A8?43m(GyvH z{WNG7_6_9uY*mo#-S=W!Z*BJ~fA{~j754wtzIqZ{OBZ7I8fAWOti6ZjajRK>a5()N z)(zf+7*}O}w@$7_g$FOP{y@vDIdUR3(fgmj6ZJRxxf%T#@gDVODEosQJzK(IP*u1M zk@9abKRaXBmevfcLsxD|`YY!D>rQ#1)yLYbKls{V3>o&eXXihyef$ypTUW-n=zp76 zT}s-6!l-AcGT&LDp@^Mi%$`3)Muy|n7i-qv`W>GDb01ff#whbWZ&D&^?`g~SM|AC& zhSK+4S-zLl45rnVjp?YhH2)#;y+3OSzH|#?`L2->OigAtrioRh`Hy&k@9(PJ;IaRW z$C(o8@7I7lKg;^L3k$y`qi(sR&!T_0&^Xz<&R%ctGs7w?^8KjoDWtgbe7_03kC~tI z+4{neQQvXz_HH=OR_43grCK!W-38WPeA{3LjIDr;kEQRI$oJ(|=Jcf3J6sv1%=gCy zEpcu~6;!rR=6hmJTWWWvwv2C4zf+p3cIO7vX8pzXhhu2cc01~RMp?hFC;MY_YhC;@ zP}XmkrAx`?{2;1)R+;ZldqZ)q#E9*W+pY4R`l=me-2G=m-6o>d7#G(6=6^|4?Wb(Z zo{#xWPeazbE^PhvcJplb92&&-Uq(0RMp^ImXko2?{Cdgj3uzPAV%m!smfww|cf&O% z8OB=D=P&Y`d@;#ewF1>U^L`~oeh02Qg>#u1Z2jR&>3t-%=lMNu^8+(zH+COX=6A1C zZQ9b}0?b2{{YArd=47(rEk3SL<}<0WGgkJfBGX?8=VM3g+fjp2wON1BTp+?&-Qmi(esNT zTYq>va0qIwwqo_ybmv42IM#~g^R7)2a)klsH=R(}=sbLFYs_*1Uh!O8IF`TG=%D`p@mN#axNzquat02lYHLe#(WQ?dTq zdx?s#)LqamQ08m%+}dfN{|Mu#6UD6j(AE#+qkagi3EZC&XUr4+& z>Yl93@;5E59i^P9MXB|a{q1oLz{a~48~^ivMydKcY$@!$vOemK55QBSh8XJc@9!7* z+t?+S5}OUA)OX7Kok;1450Qp!eIW7S5LA3`$?{jjA{GzdJG1rKZYusN+k3P3Lv}Nr zhff27Wc2~DK09n(HaeXg!1jl2X|@hA8sk{~yY*u?I<`x~gM-TPJMKoJ_k(e5yeYoo zU;TsNPY(|`jaPls@p_yxpYP5-fOZX@&-D#|V$$J4#H?24v+P`LDqnsMeqqXd?s{a4 z$p(MCR$EB^MC8*p%7Px9e2puIl=%$TX$9L}m1X_wqCVzm_|j3=TC`bTna^7z0soCP zSw6e07)$@1X-?6)%KE6kCjiC$8X!YMna?e&a;a;J0TlC6na|%2y>RboQ`VmrF4|8Y z3zF%YiBumI>$5u@hvKK6C3g3f{EOH>S?PN$-i0~K>IY(ew&U(KY8`Sr*M{vxPFh7jFi@C{qXB*QxoD*SCV6=F-L1{Yn3_GQZEGdO_E$DXXvVEf3I- zPRTTUs4~B+)(=(X-_2NlA8wiizY8sqb4bz$k>BgDlF;!X*!krBTj$}zvQDf&jS0*_ z+2?*NpVw}#gMO8SLSp0@-r}+umA<$q~~J%_sV>Tmboj~ z`qjLwUud^42m-nC8|7nhtBj3GVos~XckV7{U@S+8cr?3kNXL%e(pSb2Cf7Qm(9@`d8}E zW8X9QxLldft9xzH+3CC2s(<@4MLz4KHlxUoFR}fBa{QlN%LVQk6@4Y@82`0`heL0Q1v)p9{D&C-wR=y-+X_6N8wMxiyQ+Vjn_sIO zFdvKV1+aWBxt)X3w|&_9)Z&fn@!ntz8{eN)+l#1C2}p{O^ihoOaSsx_ugAD}cU`Xe z*T1$F{OgErXJKJHA1_Ww?~D36XY?aD+vc(LRiBH$anzvz-`cDBlBGi%t+(spZ8jQR zuBg9X^7#J9cQ0~p%|Lh;i7$~)55ENOYuV1;2XATo=hySI_*OIz{?+&WjZY$< z;Z~1v=j3vvZjOmN{YLG;9jv|4V6p zb2m%!GG9EkoMV-IVGqpQGW8>8rJ5^9Q27`W}g) z?c1#AP^mJXts*+ZZEHQ$-~R9K7vg{Kv&*S!NFSEZQ~mp(;sSlPK6>EsaJXDEWBUWX zwvR)t7)Lh$FKUcgLxJ@IUiwErs~66LAhbozvL*z5o5k80@%=?QdD*tU>F_w_!;SHJ@^RjcV7W zGjC47Wsmx~oZo5f?9sH*7gk?$8d*_8_h+cvT$$f12CmqtrHR60(tMW4@8OUR)M=a+ zm7i4Rccr!uw8vFr_4U!+@ie%jB{_Xk*4NvYI%An`U0Ho!%KV>bVfv>b`kIi_s?^`^m>Xnfx^+Tb}*k>62~Q{ej3p3Sd@^h!a}Ru9B3l=3(6 zewniF3t;Zt0W}6m&qaUmIyBt-Q;xoO#H3n(`4absWJIx+vhxT-=;#hwX%Q69Qy>9({tJSR=u$r zw^|vmQ>(ZOnC-CT#GT;3z?XhqCC$@etV6YXPYW);Z#>#xJzwQdBLmIOF7?JOb zMIEToqiQVQ-)8xs?x(8k`Km+E1gf*J8D;*b%y(b6AcRcSX8DdfpGRp+db0ZbHKi}k zN9(cuTR)6OqEC(qd%im1@D(ZUb~xOe`$UF4b&gu^BeNO z5cbvol~D0H@5e-JWu!#MyYI`PAMR zRIr|fdmi%R^SZBdA-zbOF%wYq5Y$iu)&+p@4cSwac*WVtn9_- zH^*`)q_qA_`ioIL`(wuX*HCZC=hwX1Xox-XN8-1Y?=Kp6TcCBJBF=ct_ZRL4;~@8{ z0_iW#_VmCFooRk`6|Lcog(?|;kCenN-Jdc_Jj<=36`&r$Jru{=Hy7yg~i<+sRZGb|4rMEd7tJpv$j_Gr?7RGRID znUBVk{LXQWf^Eunuv4_(T0DOcJ1H6Nxi2O8^-8@2X5+lc_?-8`NBDJmfH2~~&!+f1 zkcrPrz3xH}y|+#CmS<_cv0 z_v={?Y`3x({&>xg&%2IU!;%|qMe~Vld|o{-7ITyA@NDmgO?s-N^aepbvL2&U^EaDF3wcV0dW7RA=!V^jM@vW6~>eKku-G&-aWC!(iBk zddVo=|NI$qKSxnv09Kr;ApM7q^%&67Y?S=Ff6MZ{M7p0P>aqeZA1Ql(mYq*@(=r1g zswL^4?F=?x=1D!0@0mBO;oYY;r2ptP;wTy|u*2@^kGOm_YS1^;ZDA)-ojhM~}CA!Jvm3 z$?p%1XmIX2gN)yU8k1qC;}SA{KMKr(v@Tw7Hi@4f{_5=`3=HWj^l<*(6ujKbypqoS z_xBfFkCFTCFaSRvdP(vfeQpfgDf=bjo6QfWzqiCwiV9fQj?edsWoB^fT?^8m7#!Mw zZSM8N?Rot8eX83us2JV``iSp8%SnVMw%?$qLH+@yX0 zKcu~D`u(u}dWX|WX#cwl*o(*5uMy-&&3N8GHV!QlIJvi^~-p8`?s7mNDOY<;>gKMS(Xc#`qi=7zVhO|6fR z?Ea0*cfRy)L!Z%sq(ABSr3zNsA0+G3@uQpL`?@4BD(3Soap{2V7F-3L1$@5MoQFYk zw_3>!Rhj=}`zHZc2Vg)|Ik*(?{fW&3Dc`Bm`HPnS>4Whn=TA>UwUUJiA3?{knMAWtjVBBg7pf;`$Mc+#HR&CXxO_Kf427%*m0y(aGmG-f0*(y?Rg1r;W@T zfRERgk@@4~PDY@-{D-9YjVym;{fAe!8R+ei2i=XbuODIfj8*r<4QiCr_`rI zzrHk|S1XR;$DK2ZZ*9P4)T{l(n}t3X?s=5tuy zZ7lHg$BuKSbNNi!EZseKxgQySlM;8pw1uR9KIV5BBqukJ`D3W+W}$auPa$0IYtzryWBf0&a@hdU5o$XE90-f zq)6W;fAw5+zk=PrRJhRy?vDFT^4%$Y54C3K@cDn0KOKghQU>Go|D7*Pe|ss$;i028=(U~TznLQ#^iwD6dxizKac!(0j+!Cc zPr=R)?V0QX$ES8C;Kd?4*jUvmHC0Jwujd;Iap+Ul(T_3zmI zV^ueHz~$}3$^PSjp8Fv87LxZj!j>F?fj-vYcU?BW!QTH&S$Y!2t#$%07k>WuvC$4?oFv_ElB$Bio4 zkQ>F1@0R`aA)(?O>A&Nu2jIElXQKO^EdRUZ$3pUoZ<2ra-`M!xYu_X+)tAR1-(>eY z+57e9+$O;5Kg~t+ooxIcYPAW+?(L45Ieh+i4zz)`nl%3b4sqDhYdYE)^7-$4*b$tM zb|B-whVyOQxX%|y%=q`dnRq|X#2^<)_31>`PX;|Mz`)VISnfEL%fD}}54`J3^Z#LR zAat)YAmjh6KKo#6G?4wt$j3*ZMgCN9mH)@DxIQSCe-fVhE+FsMzZr7{>ejfE@x5W+ zCZYGQZbF*e=O(_pG4VaYyab*++D`iKuJ7K0ZABOv-`|XpzWuI}2%hix@jWm}9XFU< zfvOXHzAu&!gNv2b63-l&zmNlQetCYzKpcPnDH-4IEFKF<1`Q4aY-e@tv&?c6b|yrKhH0Vkn>Q zogEfHY;}8*?^6p3@SWloj9x99FJ$9;uO6%6)Gb}I{(Wgl0qQ7k!I3YgaQPnCYYQlj z>qGi){bhk*@JpYZ&r3bK4>bQs$oSo{LkwJuvI6hN{P=zK{YK$laTj4hXWu41r!xC{ zmMNveYrzq|&Hkqk@%-NX-B+M}-}PjCzn$$Vl-P9@X5Fjj^1rI61nP{pL+T{HfA6yS z9e589Bj@)NLgmq7YJ&9r)PH=7`H@;)U-E;^99XB{QEHe=H*5& zOzzPQ<-hUc`!YKlI54dhdB5bIBpw^HtnooKpZ|=h3&26UJ?U>!h7_Q&st+nB%l6B% z{QE9i4bF8P$@#wC4YyEI>Wx=dOy=^xYvC5i-PoJtzvan5c-WKXf6nWDVAEhi`up1> z=L$kMWuZlcViSLI%zmpIjxq4|*c4hHdsAWldI!?qchk&bl zBbR^mPWPm-XB!#+KV5hSPv`C@`}Zww%cF_camZBU^Dj3=1JgXRNd7Zi^}#=(QqtxK zKmOnPG6=O)pF+C{++Y~nO!|t!#a>NFr_fEw~3qJq-Y8HU7 zryUvp4W8UW#V(ui&DDRuU$MXWJ#7tW?dk|W^kx5k_I|)6ms>dapcht@S#tTmlDq}f z3wx3NK0PlG7W5rP_CNhb?1xr^Ovw3^x+il4zt*h<`|*7K-I8Kp?S;uC{{sPj3&N!V@HvJc(*YdmJV14H?sKkn+Yp63JPAG1hpr1O`q??_@h2g z?m^ywZIBYpKOgqk*T7Qg{ugS#+wQYGemWKpPhar;k-}XK^!jiK9EbjkZ{qpGPtWxs zDeDdCj{@ul*HSgiE!wsoalUD{n7bF zoAKy{E*SlXe?AF=-fzJz&1(*MQ&3qwma4&K{@!Ri#pgVae#BAc%AN@l2!yH#*vc6vWB?i0- zCy{)=)k=dIGv<;0-lWwAK|i6R&~3qaF5k^cvSD@ySCa4O;^&Qs# zG+r2tnwF2@?lL~#ZU>CPFrc2~J2u-2TmF?3)!*6pe^PHEOt|(}^6&i|mhYKuy)j0w z3vM;y$Nv^iGvM6{MKb=sE{MnafGL>Sh9CbkRyl!(x*EAZ!(#AFTvP3VWwEmOwCcVL#}R{^ru&Ajqj7LiR^uPXZ=sa<#;?ecrxyA zZsKzs!++`b zG*}up2clo|`M-E32afez1FaNf{Id7gyvBJ5iKg1ZqI>VT{O{=Y0Q#@@2lryx=UM(o zy?qZ(3ZXDUS>|8Z`)iMnwZQ$0kCFbyCSMbW9KHzFTlxGy{9*u~4pm6rR`C6Q??prK z`k05{;>PDcdZY<_)~F--w~C*N^(X#9_!GXrIpSymPhK`kG+Oid-#f<#d#QCsO>q@K~lm_Fr=c9>;6KBs7ZW^RIDZA#87yzR!78_Vd~K$0McrXrk|i=SR!< zFK6Qa@vyZp)JcoXf4gk;g@Mxf^=nE0{EK+MsOzO57*I5b^fv=d!r(*L7&88=54IPy zDq9HSSGH{8i;e&5vtnWT&55uhm0$n)W||J#uCvMb9$A(HgW_C7{>De5Eb{jY54#Jo z1)4%mX$_a}<)U@f%1c>$iD z<@0^UVmO3sc}eo!wsr`5t}X?aTYSE|UNr&b-nHa>!K5EkajpFyn4Qn(yClZ~<{kS@ z@@=!k2Op_*!VOWf_|Ecuw!IxVUTrDjoAvL*R~*On`j+JUj7G;ru-K?AIsd3&auY38 z)}hM;KHoWYYhg*4COIE=F*^!MJqf}wZsLF9aab8;BW zd_J1=_g*(<37vE01r-fG|9SUg;a0FYxgYP#s&wcp-4V1Sj33|UtzR#^(9#f!x1VX^ zJAlb=pGaq0W}a9D-#*KJe{B4J*4$kk{H^XiQMd9POr&Byt{(++%nyl?mb z@8b8s4nuzYZ!@7K+SkOwuO58=|J_pyr@YO8#vHyrR^<(c{yF86++KYDbJ%n!Htu}@ zsbze9TrD?&oQn5k{8#X{#PRsWad#((egvHoYMR3B&cbkTC4 zOdss~X_pl3Ah^B-S^qo{ejHaASfH5`KmLdBT?D6++mP|USHexa(9soLmdO6TZ2ZsN z?h3!#Xp;UvV0ZzZYFLL;y!iS!-_;N9TXZM=PiAN^oIf^@%n$6Jhk^EAL$dz=q~9!I zY;<#B?}--N^I?ttQD}8%0y&?vx4WD0U}*>8n8v22&yQvNkyUOwe3?9ptPjP7Uxk-G zE8*c?+3%0lhqYwA;H050^sjl#)rY@hDb&RH!tqahfAo87E#!RJ4b~m``p9=_iM73A z$@=J&XIi+#ECUk%@bz)^>~JW-GO|93cZOo?vio2qk@f%C`e^QC3FN$~A@gJNuhtm1 z@;9UmR>e&kqAvKRBG&jhv7F znHUTm5(bd|KS=tv$qIc#@_fKkGlc~IWeSc z-p#LtAzgQq`SEM%?Bmbqz!CiGe|7mRjKI+zx_eVB3Ps0QKe!&M5KL4#HmS8dWyTsF)&;N&hKKS>BHg-sm z%^$P;yN#F$=Fj9s{)y$kxlsZxl$ewG@g?WQaL7!BJRhvC-opNU*5H~dKL7idt%HO; z>g4$l87zH&D7GtE|1Yi$2KVg#B>&6Shr{d9qe%X%-`fcuJ>`T=x8c^}3=E521427Bau^y;lnt=Y){@=<>ZKPK-Q4`lmPtZPZ(K4z_>d z>tmkt2*|E{CORJgMCp-S)Ush18&U#o`t$W+{8$2q2EUaYj+5z&?Vk<5KMmJC`vJ=4 ze0_L+u!Kua-$?&7Bi;uO3fibMOm;rVN$YL@{%d$Q6C!5Fi{|54ef0lw99Mab$7?PR zoBTaHA9_LhHc-90GMQg|SyX^s2Cv4+CbILJtsnJ2xelBXJCNr?#1%i7da(;xKke0f zC%nz?N9GSDf#I;SxpW8QE?NG~&fmBCa}>rMA4kUj?_FJm@=>Znss4s0eup#hzwpT^ z@aSPn=Fb(8*I>rOrK0?q^*{S2trJdEs|v{-s+zt(8~+`1AHskeKA=2;AOCX=>!4uI zE=auc@9S;;{dwhf7%HG#PBh7PU8FX?c03FCgwOZx4kKazoM)o^faSX(cNo^6FNV5_ ze7*x`0!*D(P5Pf))9E;}{5x!4!RNd0+DXvh*FgH8UX!<=ODAnne!%vJzckE*^`Xtl z_;0l^0fURouD!jur8}fQ|Kam}TXGB<@=Qs-bB?VQyw%$ZyWKpvd@p)`3Odx; zko_^A#GNE z9R(^s{`jm8mTK)H>qlpO6;P#TG(5GG`5*Ru8rxsm7@K(pK4{A3y8y)fUyG3=VP(sw zqWTfb|FX9F*g3k0^#37g0KJD+k^I-Ko{qbmzLEZa$K6S=#Plo4fB*Yi&@W93bMDFV zW0rrTKC{5|b~Ca+p!Yffuc(;esE&O9e>Zvw3^iy?`k#!L+vu@#6=we6^Iux!2JgMv zlk?9zhWbPPsLo`3@1498ZjR|o@*k^n01|D7i|V7myl*$=)G^TeCXn|BTYOw2OgW<> zWN&hB;%_Ju-*so6hJ!z*lliT_-dZ7|L`AqM?IZth{+i{#WuNPSo0pLMAFEp{Trh7V z+#JE@fBor4P-O27F7E&0ySRSp((WTfnd~I}&5e5s2rHr>YaO5exBaDWPiCAJ`5Tsh zKkt#SO6dv7fByygIO+0T*lEL${|7V?60nl2pFa6D9h0{;K%5&t{!h-5@_**Ds6Wi+ zzhzT>@wBZLM!L%S1FXMETsRBT`!pl-UrBKSn%^+R&H?=RAF+Q4*vxE2&Og{l3h~Ch zm1s3j_V;1^&8>;+;q3i(B>xuP{@{G16B+*x)$fFi?S07kW>cpFaCyIhX#R)g|J$2m zuuMT9>pNSMPlKcMj!- zem`t~Yje;?Sez6Ljqm?`UF=_c^b~Q@gTr8)B;%LOUmxt&!L~Z5rTc&R@q0wfNa&va zi1g?8BlXdH-yKLD&gWNo2151M*JS+m^s_;$wO?U=GN0d`;geys{AaTMujJ;7ZQV7o z-b}_Xo4#^+j&+=;> zCFQqeJF>sK=!if3Iju{^?}t5iL1|=fGJa1wegOI=>Wlbg{dt*P9CRIlWPUnskhM@} z@)7SGwQu4tAI0z6)YP7aE49{S{La+37WBU41 z;PQ_+``ZoK=TTSWzhg8XgX6YMBL5->;`puJ@DVgV1(E#kFjmB^&!zjDmdN;L{map} zI@sOp6lBhq@$bX(;yy?YCj`Q|~Gp zygU30c%S9-Kjiad_>f&s^6#|D7gd&M;D<{x|8j)MPYu@D!{Elhl7H_vvH9tS>4{i& z5;18hpZ}W8(zm~VE0X*3mOa0No0hLY#b8a`3j@q|xlQJ; z4i6A2Ei1_SOxNBsaQo>`@M=4se?6Nips@TS$$zqiFDCa<$3=Cr`V7mz^K5(QDE~)N z^WXayEdQVOCSp}E;B;#~|FcIgh0)H6q<>#_?JicGU5-~q%i_xsX1+o5jyw3rsgm=} z#RgkpaNmxke|cK93xd1$BHuTAtalJjr4JSPcQ*cOWW>SODid-)!l(^Xg`=wPan4d1 z|Jh9Z*WY^v8q%!D_@9_GRfso#kJUT){7+k*3w?4HkoUWE6|999C*R}LOLW9qzmb<-uF+iz< zs6NT^zo+?Z@Y8CPQ2RqZzE4EWbO}CoEH90Z3X#7Iwb!yjYD9;3O(|D*5HE&!Lsd8GXCf2NoUu4nvnB5w{xrn z+l;rk(0?X3{(sLt1B-&Dknul#&{V;5*gI5~=kq@{Fc%grbR_o&w}_f5987(OjUD;? z>kfYcZ^Au9{)hGd3*i&!-rfN^zh(ZDoo_2?t%PYo5pejh?C-<+f3wn#C?B6n^1q>j zA^3RQC-c`i3d6Dfz%5AG!RP<4o+%g>mrJH^``3SJCh~XnnoR82wg3tddZ7Znl zRV#Vim(Tw^!55u|wa4OL{QlLV^|N6^{Vxgi{*~OVMBFve1SjW~%Jd}>@4wC*v<%)2 zQXu#Hr6m;O{j1CHaFMM3%f^3&Ngj~ZrY-6JH^yuQ-xzI@{~04fz;mi}Ke6(^`7`nU z5bga3;cdlWQGK4xUr+eO!!;}E{&(X3V&qgSVa(|&-1N+j%l|=xv+yi^GMV3A4Ym?& z8miD^@qwn#moxsSOG7RcIXRH~-#64*39A=Yqm@Z+)92F||MPb96Ns{OC;L-=mp_60 zz#U}#uN|X=)t3)KV+f!Bh90_j@4-n(I>V3u_i_xu^1(exjI)ei*8dbZ4aex@o3JyH z&%d6VDO9GFk^DEGZi^cx)WPA)eE#dBtsrvX2QvOEefGuof7_w4g3SN3^~s>30IZKQu;zUHtgJ$#ofcy0#?e7e=2e!Lv@w(C)JA_s8--Io$(7?Ann0ug=;E z>$0`T{MUOz2ppf*gX~Y`X-0s_(!2G6r)^<6f8Z)o@g?-mA-`Rmy^O1P@x0GYo| zbkxPjuPG$I-=w<_SL`ey`%m*ihGW|u`Jn2}=l8*0Q}{Xag=qg7o4;mVx5biSwV?Bg z&+qyKD@cy7A^m&YSwEap-VV=?l+|xoe#bS;hEe)IB-Hy_UyDy*V(nOTKf>qtOvW;( z%xFRS_lnwkIC0oAtf`Rg$C6|Gd(2A@(Dzp%=aaYg-3E_GYLW9dqpycR(yi{~`&zGD zBH;CoL2zS$EWWe;{oL<(xMOcb)^A?to`vEVOENxBPS1lr!aR}x{y+RKehM{h+#t^E zpMMb7SCU*m!?5ey$^Ou!R3-dubb$01OH*`lyIu;^{rA2gTVD}=N@tIT7mNIb4~Xo6 z+?UHzK4;t@>*H;!OyNbZ=OmvFzihE4=RH|p2{|kE7j52={r|9j{y1`0JM5al=QGh} z4k$eNM)G;VD+!J5#$t^HzdvL&YB}Vqwjkr{%*7kPy-1myf5{vueIILpCK*3%9*2Or z^!@GP&;R_p*gteW76Ge*21@V$@cFy3UHU$I>=;-&=wE$Xyx&8i!#UU$U_tVifBy#L z)z5{Xuz&GS96whcdEKtDB-&rHL)kn+7ja&M;0KeP1@_s}E^ zRy4xMI)40ATe%$C4U;G9-(_9Oadqo;=(f4|zxj3X{ccU=jnKWTGMWF~-MtO8H)@dc z?T3c%hLd$&$@$%T4H2MtXaE^Mr=LF#N^3`x=l__6=fG;-M3P^P_W4j5JO`GqKZ|U>!19UPNPoIts}-*D41>A8d_KMBb;75MlHiJl?0jPRJh^x@ z#AVze>k~mUMqrQrxn%t8x@#Pay8MKUpNZG(u+mJrLxJG)k@r+6I9w(9w||E1FHYa= zk0FVw_|TUhKfAt|3l<6ul7H`Kv3z!{PC`SyF{s>@A3vjSEr(YA%}G9|PASLthu31i zNisfJe|li_MliN)O~%(UDW7{i)yexu!yR^m(6%d?pPj0R0F?#($@*L;#RM1_YzQve z{P^m<`y8l@GAHK)1KZ@oT(#Mv`*ZC1o}l~;4j)=g`cIz&UtsW#tz`V%?cNGQEB2G| z^K@({Tpe@*UjFyK3d^VUyfLuG;f`oO44Xf>ZX1EVZLX93L)~ZN;6dbL5ue%2ewd>J zXJUD;w=nuWKYqTinF=vmE6MoTzuX_McT&ZIH+()nM$Cm5I$uQf1D4P4Zprw?YczR( zsA~2K$o$ldJl`GGmgCc2Yp|aRpHGLHjnMjXD{}s+>#uDPSl5A!pVbF;LnkBY{z#&J zaA`&){JGGN%%4UXB|u=nC^CL-Ie89#$W0*Ux3@0Mhh@KKfsXdS_$WUAck4cb#qC|l z`}XVKqZ<7q3*o3szS^7#CY=-(L^ zJV=0EWBB}j+A{_oW)+b9j?^59@gH-@_-k;|44!&C6xFZfP+Y%tu$YA}bgQ7xWjz{lQz@in9aT;GR-Gzs7R&U}f)m3HAQF&EynpRx%2UJ3QvrZ#Q&Y z3C7a-59=wt5A*KXmtPOX1ythj`6Uc7OQ@6Q5Tne}zUzKcME5`ddsAws(Gn z8X3x5{yVg6jdzxYlJiSG-kmY@=W*CMkI%o|Y9qKazJSc%f=7+S$a_N~rgVCVYO0b8oH0gU9*&f8XN?Z%h@*`Hj=PYO!eF zM(n1r;lJ}sLlnRICT@p*(d|fmT${fK9^BC-<9mwkAqZ5X_2Dx*5uOwehxvAV{$2N- zhs-illK<{&Z-VwATNo{RzfjEofUeJBfyr{xpFEmuDU6SPfEkXm`^gCm|Fe2Gz_rW1 zq(5=bu@tsxm*Uc)GX9S+@qhD%)~NVqFO>C?^_STGonl#Mv>AIGMo04be-L5>m!I4e z`ERzq_NHtEUi)|%hA7MU_W|+y$_Gb{hb{H@N&e4i*kgY5Yd9Lq=YMOTX^=PfC7B=o zirI<-tCTVG3ZH)y!}$==P)qXPEinZxLq=fAb-sVOzjGz{O7~;T3jC*^79u`hheqS< zs@}Nm)5ibK4{`nCnDZtGNKzo{7q3&cL*aHcvi^2GX%Afc(2<{-wqu z5q|j^kp5fu!Fh;1CXoIcqi#amJ~PPtFevCbynnS6Hf;VE|Hb}gK#7GA;B^mw_{;7W zr!jmF32A`#4O>XQTMV-l#+Kj1jZv+e;(G$a_oW@JvERczqWqGbPfC2!8K>08iSkR< zpLg*vf?1RDNq>{%I1>A6Ncnc)^X+thJgBz1FWNuK`kNWM?XhwFD=;qN^If)S8u+P~ zlYHCX+lsBVl*#(s&Aj7mPLS@$p!Tn5--^Ps zFZEE}&ZCKMVEP;JcQ(O|%9bSGoBwWyMMbJ)e|k;j9&lEs`5v8g2o4SCMb_uCtpuU_ zfScGSx~|FJ9AW%T`k_Sl8mLeD_j_G3KnOsR|IfW|!TNqSU^(R<-{SagA@>5TlAOu? zh$T}j1dUb2XdN%RKgsfcq`m?44Qc)rk5~x5bBeJ+RmOiB!~dG+t#M1&JrLcRAK%T4 zyWriPaiqUl7jFdmoo|r+lakX?f8Qxfw10?=?_L=bpv?Q8q}O&?d}Q;}ODeO`(YXS? zDct(+d>7}ZjXKj|@t`u&-%M+^4Np#MExlvIkMI7?9H7VY_oDi=53^sf$NDHNm%blk zw}{Wb&4N`RH}IFlDPH#PXXlez>PO*ky`GpiZhh0gpRNC0H}`_ZF)hjZ$|wi`c`a44 zzLKxH7rOM-A^ppiW{2VH0zHVF$?vcH%0(gA_y&&tSlh&Z0>l5s>_o6}m+mjEm3^Ll zKcK`Z14e8DlK*`RZ^78F(@1|)+xG<=HC{sc8->z|!aBdZSnx=8zcPb~|5hH~piQI? zxnIS5DQY1I_}Gg$t+Dr3(@yGei3+oKC=O7GxN{=TFCSm+#+Cw^Z5M8~__ z+8(2%FF;;`A!qsVzwh!1V3$=aivMhV@y+ttxYFn)jL_lpKfKd)a6bN=jQ?^&wqe&@ zt;qU}zoG+V7QZ9wi#C4_5Lm|Lu2r zL5yn)GXCGS2mtHeZApK#*KsdQT%`^2%m48y?k|3Be;Dpg?@8vjgZxpLdMFq5HuL%4 z(C-8cI5Cv$Ke{Ajz&#fU$$wVNEx46!4gLD_{*EK-c>fu zcVsjC4~YB*A^W|_`gzRpiGo{IA?j(!_|Inee>+VX??i@>{Ey75C9?R*@}GQbHWsxh2iF07{=-L2hiao| zWPPW^Z5zr<-%qFNI~zkBpzP9Hk-ul-e~Yt+F?VS#c@Z3A2OW;A^sK)io$Qs7=#AE-t8`$3ZrgU6~K zBL3O=yhDgW|KHcJjS8Rtw!=<<;zsFyQ(}J4NACjoM4FKEODUQKP;-4MS>Ksi_yQ(m zEF|Oq-aqET=b{1}Hb=&PKEwak7T-bLcr)q$@474F$!ohvf79tp7yRZK3#rRwe9JNQ zcfDI<;jqSa(SA`je=VG4h_QtiNxpaZn?vsNyCS}iF!gu2hqKXh-3!v+8>`qrbJwS& zztP{l4WIo|#ECI{e^XfK0D-2}^`GO#_y!S!{EQMJIQZpe-xb8T}7A750d}YC({`Ja>ech zMA;4|=dUw`3!ppQn5@riHY$Jy2P-mukApHW@{;b@ChG6)jm(7)!8b9>M0P*8h~XD5 zeuvH)UQqU*zhvw4o?+&~)#{sQFP)?Q-~V4e6Te68QO3>zvph4t?l$IKyX?j6a)-m>`3^8G@24nC`SM%HIOo}3Qn z<~=6&1Lf3i!`BlPQT{8RZ}Vpk&|*s^IsY`G&tbge(it}#mDT6i`0e@81;PWqlJWcR zjYC)}-Cx?*VKtY3g?pP}#*pTue=qwU0BPrx$@^vJ+Ju7UH4T#gFO`SEB(xh06J-8| zozFYo1BG9e+4#|w&;OJgC!olA5b58ePh5aR$yl<#ztyJzjwnna`==ee%V6~vM>2jl zubvoy0w zxjluXS^WBq`~e#{mi>sFPu(+UJL-lhpnHeAP5iO*sVl-AK`!cz$iJ}tRjo&d@R?#K zG`cF|2S9wk;8^%-c(?wGgt}idV9g=?6Qhg!ey!s2UpmAaRY^FYM zqB9Zn6mCm075MRgzQ-JFZvO<{F6Z;V>Zgr#Kg2`Q-*jHL9q&nZeC3$)`LDd`2wx|? zCjHH@^@s5Bk&YOX|Ia^*`Tr=t1}>O=mh9L6_jPf7ez4{tTq|_MKVd7m{Hw`%OLHSR zvOnb%vI7P$X-&=-yj&Lw(1YgxctjM8)$R&rr)2tN-TTojTfH(yoRHHSIF+? zF#Ox3{Q%eF9wh(H{u6||d#+1o3>2E;Kg<7lP{Gj~gGm0{TPVdgbUWEubEO#GL3Qo&-MK+^v& z``s10L>~tE!F>PodA|u%-MUQ9Cu}hojja{12{>2)4!-QFD7ulmB7kzs0E}xWA|$S-<(5cM&=_GbHObf6H%!$Bv0){bu;t za?rRuhn&wjtu|h`GCCWhy@`CZw^+&M-&p=vhphnrOLE@Z&L;k$u@;|IP3Cd0SlK0oF9$kdq2S<|i z`|pxM7-DWt#((MKOpv}zddHiXU%0TvOnB4#G76F9P5ggk_{W-`FsI)-lK+oC&4f9T zm+|#9KK~{!Rq*he0Mh@|Z0Uweaw0|Z#jO8%U26hqHkZiyy{*z1jA?(GykB(9!2+t_ zhN%AI!_+tTKbnit@BkL==JRjU)fTMQmyr2y!@K~z@wPdZ?c?(wsOtnTp1dIa|5I}* zzYXg6clN*iNn-!sICU+Yp7(*wf1lltK#c%(JUPyp%fFV14=jKEQ_?E*pT5NYXO4Ry zs1H|!2W~R|!q)GX4&Mihyw%A5t%^r9cuI6h|6_bgA{fj#k3VW<{AV-%e|fiLP_XGk z@*grR6NaB1LCzmn`W8ae&E=o5#`EL5O}}|q`Ticsw|kZ?*sLig@6T`87=X4dnxnxIKHu&$oSZ2mJYaQ)tM$f+4vrtyB6Ly){y=t-7Ny!sdT_Qg^Rg-pFZjXV={k8jyLl8 z-m@hT%10=W_5B);eP9-^O7^ENXGeqGjE-b}>lr8!vTmNmG5h&^zY0%=Lz{ck`K@y% z%-S}b%x|NQ7Q)k8X5@Urp!%1vspTx7-nSciaGdZh^dcs7k@5YViSH{*e!;|mHDDFX z=Ua7n8+<3(4p&~v>NhOkJ9~CV*X|Lb`ARl^+vk~p`r-@Z{kxr-Mrgb|9V|`wd{^wW zgwe}#C2Ri6505bM`@^|;SpBX9JS+I|+kLDZ=r5MuPbJ>J!@K~Do!tzzj`8`nKjs9^ zYR^P`v;9~9!x7lEM|+&U^E8+5OFFLLa_}9=_Ylnpd=c9Y)g2ab`PMIz*1Lr7B;VP$ z1L1{#O9-9AkKdU$_5oJ4CHDi#OZhGur9;l&7~V^U&VIc}ezo_R3Z2Ji;I3a2{`1e` z{fOtzWx{vqd}cF0S$_jS{JwkUTT|g^SOyyJ3~u^-0<+&aN^%FhK8}OP1X+KZyJN7K^3sv&6YerMm#kY?&+V$nBwPL{S0*c4Shmak@~3)ZiC~FY$g3srE7N_H~auO z-!P^b!13Jkq<(h#8evMmR9M-Cub+NameAMasz^WO%=t0QVLtX*Py`pg@b&ZVq8%*0 zQb^W6?Yr;5I={c*d5Eu{imy(vuES&Ue%9rNgBUPN74O|j=jtam*At)B-t8b7 zRkX$Y!UbIY9Nn}9CKrB{gdgVX=kMDLv-4E`)+mPpnt@;tj9;-#>zo#`M zLjIg|?6Xg%pM1vuH-1Y7l|enp{iDt|1mSZ288m!7o_oHmF~0}eWKoLd~UY$;x=y`NPituf94T_qV)D&Ogs>GZUWAx=rdwX~_)uJZL$HfbS@jd)1v=Xmr%OnBM`ou8+1^>h5aEA0I8hU^~{N)BSAUmM(*>B!ZO z`J63a6#SX=Ukww2K<`y^GQTKWzaQQkOZOv1$j%q`{Q0or2*g=wlKv~*DFx;j_8{w{ zM$-ggQTZv{W-immM`k~%f5;{1(|0JTkA%H~uuu0i7LMlYV_NAQF#ZJO{eU%!ro!`W zr%~tJ=_bC}^JV_`3aDH?ot(eu_C*l7xSht))-ru4G5Yw`w-G*hFDLWw#ogLsDA>`+kGVU%ozK-!6o?p{1lh8#UmdboZbNx)r2y^|9#0 zI>`F?T9UYo-(SA>`2aQ;s9==816Lo(+qb}HwNIozI!WK3UpTZmnV)Pa*$;j@l)<2a zuMeqx7QQB>V#Glm$^ZP9x}YWM-)&Ai0=8>4prwoK^Q?c{P%aU)XQZObZQ1$5`nSs$ zQeg9p?xcU)l!HQsaysrhY}Uj#tFJcMm*An&5YoSm`-(!{m~_0I9@zBx4Cef4uX`7+ z=1NF?MK2SC&vEJ4C@0g`P{zMWB3{Av_0!1ry%()&grD-uNPpJHye;M$_<^xDKfkG+ z)&m!B+z-)L`1%=s5a3;xGotzxJD<^P*H}#JoJ^iCqY@^8daEm<{xs{)bX^@#J@Pg= zU+rZz6K3tdN#-{z>vv$P^!-2YUPVp({-60I-9_Nv{{h*bwy!*ZL0yzFPD!R8A7(zO zo!dHaRDC6(?$6(dK7c1)w8r&D^SSyN7`FvhZ~92~C$dfjL7ZJPaz3LvR_f1eTa)$K z2dXjfK1H3ZUp+k`9WTf}iCazh^(&LlDPT9V8>x?t0t%%QQ}J0dzCH%`%YuqdgUS6- zofe?ru{aguhw}B&Y13UOK4n7IcUPC7pm#eJ*G`qa|HtaXC+QV5|2~zh|GxUw2y<>a z!}e^x|MK737Q49mlKKDewLP%Tb01m%I(Y@4d(A2Ge6cMUi^tm}k@^@@G6^!TWs&pQ zOQRf6$GCv>U%IzvO8dL{WPLYEIS}W0{vgj69p6O|S$~f_UqS*8V8XRlXx06sOka#X z{*O|5fFD0GG$LlImj~S0BH=Z-M%Wb&?fpBtq3VHtIj*J28a~;V3$AdE`|yWHp=cswwa?617L3$SfhI(h$dfuS*Gb~pjc^ZEYH)_F3xV0*Z<6QJ#r&CI^gd72KLln!{h#@PxJBzbgjn*=r(Hc3!?uzV(fv=h z{?-N#VCqsOw3(K|)!&+tZcrkWllpV$cmQ?Hm2lm!Ib8jX>+K5~XFrhoOO_9YM;3o2 zs{LjDi|ro{)(nG~XeF}0Qm2N3t4lJeufo6>aDUJqQu1ZrpY?YehoZ1MC>b?P`T9EL zd=e}tcOmr^VTeNE-ej!a&DYmnmn`^`K7j1cd^eT)yF-{hdyC+hU7zKIHwQ z1;2Y>LHb^}R>1dvZVm{_$I?ju*Vo4w2YgQe<$HX6Epwa!q2*<5{na`1)wquxuRC;$8T;{JRIO7)f6D6uw` z@z3h3F#?5@9Z6WZzkAd7XV14h*D#2Bsz}x!o~NSF^H370Kc}lP(EMpTQhzrepmGcALR>)-F36GTk3HY|Tz(DJ>XXU+kh|-o`n#Wm$-nseYgGOVm9`7v=w1H# z)~B;{w_>%oR0I6{>t5%csB&x%S-+Tm6k+TmPyFWVr?&Vcxaf5v_4DkyASe$>!i1&#{LAxx7F?au57wCT z{bAu%K`l)nb;U6y42_4lbD%rH&D zoD)x){Gkft4_o&A3u=)I$ok)#zN)zNqZc_}W;3TJ>ZI)kuhabVOX(DXoz_WmKaN{l z6TEmO9xSW*=U3&{$#B*&Lsb7`&#x_|j%fEX7c|uP_rr@9*h9+RYZAAYviQ%=*Wc0) z!oo=Dj`?SN{R|(l1a79^A@}19cL>Kpi(8<3&50)d+4{xqDeJ-a`BQSfEZ#gE)2v(I zUjJEK{is~@g|5nP$@8mYK`<;1`6Dw5{KdwsF$Gi8E_9wfa zKqaFZ$^Ytu?0j*HHmOjdp-bwgs;j9mp|kY!-hBOx9d;S)g}$W!d*)^;s5zfNzf`_{ z`aUay5k7{benxnh3cAZqU|2L?KV>uD!1U=BW7gM+ZFv>qP%@b&TV?P5^>EA2mt?tjRO^8cWUaP)jFkDl(b^M$>CyYKCK zP%C~y*2hbf!%=R4Jnr_N$<>GPJzwem>MAmS8umCCMnC^9q2_nwpND~^2Ca`V<6_}w zZCg?O0hsrx+{L{XJo1>R{Y%vSElg&*T_FTrLz|y5TY)duV?4m4o(mt{$moUk71D}sB`id z3{c8z;)Ct4cI!C>*6ExR-A`flF))4sCWTysK@0fj$EU;gaOqYy* zeL?g28*;v9@y}pbt@@43e-@~QgZh9LJe zR2Vr{htx+G9YH8K7LTzL`1){&xD0kGy~+7~rB~ww4<+dvgX8%9*YM-TpfP_WWZmZL zqo8t}a7sB5zb=;bhuHpWpKouVS>6P)KNO~HCX5=8i1vN>{nyQkayY8{JhFdOaX}SZ zDQ+O^2VV#3;R~f*uu_SypIr*3(&_vp@_tv@0~6GaJSx%;F!KphHcx?bf6tKl%P(Um ze7EZ=Y{`@92SB`^twp{)^j>>~JYQU5f-oz;mekJ$1!s79<`(I{4t@wj$zM72p3K)z za5Hxpw&o$(KiaY_OuBnk4ohrpx%$D5elTY4Yf?W?=Y(VF+-A7W?BeDB`6B@F{@E?k z-2}sDe6nlB{{@32!v0z@SLiS(3Z9>89;W4~CP1b*9=YKAwOZ}OaHtElf z#-Oma;TRq{XWEn>u>IGZjLQ)ELXWI}=NvN=(&i_i(SE+Zw6ls~cdHR(eIO>(Oz3W% zfD^9r^|kox8*myko}B+Neq|;U?MuKZxiWpR^FPZM$YEH^x$yJ@zdit!syJ|oJE^Zd z^Yt)AcPFW@)TaW-Hf@EC}=M`pICjha<_s5%g#u4D$43x?D^!h$O)$n z&XLZL@%6Q<-X6B;To%nYu=VdVFM=@C_5+#U)J<`Q!udBzeMM%4VMU761D{Rco=+A2 z?vOdWlsupMP6)$Rm4D#mBkkyHl#u;JuR~S{aJ#- zn>k0Zb`)Pjyo_`a!En&ndWLR8{$ za=uOyTL~JbX5@T#jPH2i^X=oN&u@?mI?mNs(m)T0EWc0YM<>+6(7@_9Bu}>C>Z>ux4`$lGB=uGIGz|M5ZG`L2 z=bQ9(ggL*?Gy>cM2l)7Zhp=Up5^l=ffXuli=juM?1=cW5uiT=}=8T)a^pYL$sP8?T%E5Epd;rkNOKkk3KAH%==00+TX$ z_`$8jGO|8#>q!_M@&5(QZ=Gw>pN~ZBA46K~g0l}lO3I$__4mtutYE$E5N5a3Z2I{h z8U00;hr`dYQgM9zvK>!F| zjnR0(n6JNv!&ji&&hDiCM*f^2`1h0QFPN{tAv;RI-gp@4FaH!w5QfRe1 zzkNSdf?j`t)ZY*#b3u1RJl+_}zuz>WNDfC^%p~=vyFm?0g|%dTP+g%Hstyb!>mMdg zreLHUFRGuj=U>?w33lon4K<%+`eXfN_vKb#`!|)We=L~hgykzQiQf-FasKAwIvesU zFOd3cyc3L1yS#<^44M9b(ck*^OF_PKE?NJOjNgxmZNI^ISDF6U{_g}^4>*`oO!l8% zmhQ*vzrTUz+i6Ywmoxk2``__{mhghq-+YyD6n_4IRTX^wRX^GZYWcNfeZ-{KSmDL6 zNL(;mgR8$i$_L=?p1%@mKQRUz1sCI1qWTHzKh5g<3$K)RVi&j4CjGJd>5nF*!K*gv z6X&W(v9&%f=8fQMQ|k@;PK)>KGWOBK!Evge{C7W!(chn_*$}fKL$u$UJ^#Aj3dYsls^HfQzW!=)DZGlfM(zhx7`7k1AAW&T zEoJ)qe{`L9T+Z+J$6I7)D}0QMb`%n&_c>R4X^_a?TbYGWDGju@Btp~3$Sj475E4md zL`Gyr*6;p3zW1H?^>|#@-yZLl_w#<8^E!*JU%hDbf$d9gar-Y!|HR=s$&H!o_t^Y( zY8eQl&pzbFpLZqw8>>3~0E_*y{EpVY9uK!eOzArzv{9BH)BPFx6B9wc?zh03|2T3# z9jx42f!Y(9ex_0Wec1zT5^-rOS{k$Y%6fhnHvH<$Lfeg4J*^xMm&DVjBMKE)E zU#`BjSZhoET-b|hy4$6E(0r}_UJhY5^kIDzF`rS-)SA13~Ar;Mf<~PzJBIy!|qD8(0ERYQdai}}|GZ<^L`Fg0b7V6HHas87bAs%zqeSttFS$s+BTmG0p z*gmpauwL*lzZCa3{hSgGdy?LA>%&*?nUG!+60wzfSEhb-S(gX~-+u~K0WyB*`Koo# z(&3PiGS@#LgSCl6i!jvLa965d^!+&7UU_ixO(!m2k1y+zWrMfj{%ZzOJ`Pj)+wUPo z(4}u5u746c)Q$}MoQ}e3Hed3q?||_MJ+A-%QP+-OLptU-<}>xHf5s~S6*I0sdC$|1 z%o)5FXVkIzG9E9Fe_oH{`jfjmcfy%-mvZ};THG3hOV$U2|3bF^-#FX?n)dDC*3V4V z13tg8gR5U@-<=@0N3Q5T1+8BrPR+r#FHb_=7@2<}NAcy5I|bU><%|4(ny(ZeiGOmt z2HGpj_@d*-Ysm{CJ*SA3m=j#ZjUS&c3WxTR*(Y9odFAay__(o2m|Du_XO#Y4h@RGxn|~=1EfQxK zg57piNcoAR@~;C^^T7E_M{fOWLZLQ!IXe^$<%Txvi+F#8>w+TKqWmA1pX85rWWktp zoO4OWPa+lnE%UhpI&QjLee$TWBRU4@n0Q#m&kQR6GH+D})%Q%f`Ikpudoo~FI!>9! z-kB{A&t$ruGp0${(PwpQF;j2wsz{G{kPs0EU*fwmpu)bKfKZ?%33`+oC z9!Z9_nr#1Zd7(1|n&fcxDcEi;o0o<-nu?;O|vDA9|@E8`kq@p(2sN6xQ>y-%-k=i^WRjmKZRKf;WkYqcYH$UG~4%ff% z%d{tD3-+LHpA*vOX?~VWtAidJOn|qaDDS;J$xYjXwGC{3;t$K?mS4`$rJZd4o!-B7 z%Dxje-dV`4j}`VFj1$&N?zdaA`I-OB91OPX65M*q_$dO>uP>*eh}d;ql87JLzgSV{ z3}dfnar>K;gXW^YMLuL~Ve|8|ZVJpbKgyjCIW}$^eo1%?)ot1QnC@Hzy*d|i>tmO) z;&DUmd(buAFO8q*{HbopI_TvgnLp2Jgn9 z!EAoyFW12+wb9)E4VMxJl7C}2ngp}=m$tkkkEV7`(D;j8U*5j16At(}U&IgXzo%^( zj2Geqp>;BwpT52ppi`YH+V4g4^JM@^@`FTC{6^Qm{)}{i9d|Oh`s18G7p?v~4xt;^ z{QP}01u}l+as7wO{@ZY=%_GQDXY+IM^CBqxah6;Enmj52uXTJ6yI->Ti49u^e)?Cr z^{?Y{iP&WG0m|cL^<|nLh2TI)-&!HKUy<$C@B?vv^khf`d^4@(`s+{Zl0d!VSAnVQnDxExp5x?+PE~K|x7-Zhg6bmL_qS9*CzO z=}Gk=lG3L`FN$pUp4$R}u z5Bnw!#=Ik&A$>KQF9*r)vn2&PMe~a^U#eb+UnD&`y!g&6-bJ#2KZEPG@&3^&s57ER+u&@?CxtuQ{S>~#B0y*0bFMz2 zOA;8~`^5Ffy?*GCNtVGPzLco_6uWcx!p6}G-2Qd>=bGe~>t-B#l+D-gfkzbA5PriQ3;{k??#V~N+uG~C)ZqM1)|{CA|R0^FiB;7P+jKE(H7 z<9m-K;lt9$#uXe;Dy)9G@gJ8DgJ}7T~ zaaL>usNR1j^#AhDUl891^gW&ga?3t){f9%H^@;K5EnL1#4fes_ZSq|I{Emqh>E|DS zB^7MGLM3w-cb~O|asL1Gr?n^nsPxt%4u=A8_%K;~NbA>#o5fHN*+Vp+=tu3h%zZtU z{MfJy%~#9#3Zde|U+*d)$8s=Nzrt^fCGHD$p=m9fudEHP;ZqMIE?;d7oXE3dyKth- zb1C2SeV^Wj3i$h~9aq0%lsco0`fQOuLC1%a4Ky&Y+Fw!wVe=K<*9sOq*}?7az40CK zYr8mjYc1o8jt^7kxPrr|ecb*G$L{lS?1VhHtIg(X%89Aq|KI>OKHU6nI}X}b1?f#} zzAF1Hfx8tag;#Ic`W0!Hgg2hNf!s;W{k;@lb#Cin+R}?$zIN|T!fp%S!XlH2Oukyl z2SMwUo1*xT-hXMF5CQGaJrO2lviaK4F&T97KM2n{{d>Q~`!C&X_QCP_a-#T;?vH=@ zL6a=&;E&bIWc-9s{$8-(5qQ3?4LAPlZ7IpmItQTZ0U1BEKk+NR7^0iHiQ+$+pTC!# zh-y|U_N`#^Bky<@Y~%)U^=V_G6L}GsiWA14lD_}6K7Gx64J!kObNxN{M^0qQsZ_ju zjLnbvI0anN-IiN_iqP(ir%YyY`zuPvYGBT3KhW9F=0|J4m8AZYEQ~Oay?=6)KT)Gc zaM;%vE+9$5k{Po5AoEdIrB;`s0G%Ow1C=QTKX%$C0Yv_J7+$9l;7b)L)5wdu)tDeMhA zh@ZsdM`2wMc*K=){k>r~B4F*%$6SA}pieTWUajZ)6HlV|!AI4<0DEX=BJbMd5E{@Cfcu5MCp(AN@w!z?oP~8 zjg-Fsew6-fioXk|B>lY~6lC|a>HW%GCC|Tq0_nk#ON3eB*!*!_2*2TH6#Zn3;vsA z@1LI_l6SeKOC<}eBsX5Sy0Z0W(+XEmU$}?sPrPlIheNdwisrLueu|e&gZ(pexc=Up zY2kQt)jb#_u=%;rWhp34&KII)%6|Sd5c6ZbJsA%itApNm*!)x&`@;1j#lo3AvgZNB z^`#LvlF_T{Yp^r)VDi)2I|wTBuXE>1&R>s!dV`1D{`RF~l3~`}x7_%y--Ufp-s3ly zpU4@SyQ5|*C7*r`=MXz5b67uM)?mf)}DuHlK!Oj*)n~k z`8nX|LKdm)#BgsmKR-X-1&clEprXO%r(SR&|FzhO(`-*S^VduC0vh&t16>LYxcx;V zJzYqM=1#OIXY(`ar~)eMS#k5DRAo0(Q?(2APRj19pQP>+{mSZ$N4iggzYE#<)8=Cu z=(=MAI38i^(*o7E!rmdqLY+!K+2=RKSLbSiOB zaY8aYRg+w3;OsZwe{>(z{Av<-`^{|wwaDL%zWCFd9p5E59+ljNQs(m2ceyU9S?q`1 zo7jBirksblKRS!{&pxH}sX)_}$gN1hUk})Pc|X1jCN}-K`H@w7SCTX}1^ZoK^VRh0 z4Osjb3i~Yo@hSHA;%r^Xg0K{<@UE5eN#Ae3Qmuev?^MK~ShzG;oyphpzXT2LM1pO!j4#@sm~z<_RDSK^#((%~ z9x7Pnz<-xz{e84QQKLE?da7h`{Rt=Ma9mtf4xJ)p`4i38mY&O?-G9e~eP3kyL+jVZ z&>eVV{7X=&W%IRci!U5HTgc@rN-qUNtzN;3GgFxQm9Dr2+%!wM`_ETP;-Ud=It72OKQZR_KG3!JA@J^_*4@@3^;gzmWfYsgUFJu@Z(&Prer3`} zmmJsGh__8v)nOvia&UW*i(ZN#*L-oCEXGLqA&- zAJTly#p%!xn!(ktbrQZ-+`I*DrZT?h{Az&pGT5}~h+tC5=Ifby3ifY$0f7;+{bh81 zb-mmde)lTi^7Z0%3i|ba35D&aG5LBYzXb*wT;ckEJzXQgW=tj5U-w8$h8!{egr4u4PO~wAyj^)+Vd?G+}GpQ zf1NDH5zWPt8!W%s`n9T$A|~!dZhZLr_&74TAQ{uPu=yIS-UY`fOyb6ezb0$qswQu! ztYOE8+g!(!=pj4MPZ%z}k6DC$Me%QJra5l#3x}+SGQMd4Z|;$CU=_Yow11QC?^E2p z0FRHzg3rTb{+}G>U$h%L9a??d$E{zDi3-P`18#!+A{k$DRD7tiav4-SJ1pEhCF9GF ziVrp3q+s6T=g?|1d;jLN(Ho#4{ETpPi|lzi|5|!$C(hHUh183({m^uLsA07Q4ALa` z-2!C(5AFXMY={K!S$Da7l|4*`$eFrEfBuFaZnbIrLVy@ci8o-9YzB!wE_klJJ9q!gr4&uHuU`$lezN&ey7*E!u~}b;wp3&4*VLRZn}Pn$7Yp#IZEZvT>1K_qDYy~Fhf>lJpu@)I>&zBXRi568nl3-xVf z{sKMU(bis*>^{33<=?aUi7`9|tL7_m>r+juv`FOqmAJ8`jGqw7--yz=0Hysqi29d0 zQvB#l)FZh+e9+_hDk(qo{C;udJ#bg<&F!Bx+v!T=4H7VYBby)Bu(y!bL5IuF)N)tS z(LDj!Mzf9}bGT((* z@@PK#(tY}@sZ*;7~J3|{rjX*^Nn`1wm=V;3tYYiq(*|({oCC6#WtOGK&Xx+J928oZ>>=5Orxd+@HhCpSMEr{_wHeB$u< zceXztMBYK@cP*~}ai)zc$($aCvAtyeB3&OoDbcU)`KH|co1Tsm|0W_157;V8`ME{q zXT45J`1~;r{L^IqBF(4V7fr0_vx2K{pI*9>#-DLm5@Xo>^~Leyrx7oO87ex0O=Axx zpEDyZ@ZN^45bDC_^Y7^K&{&(q&fvw9N;p6IQSygF%R*Cp*p!mG}WIxn;e&G5e z8iE$7yt@nw7Rmg7I=;LTaSVJtCi@4?>$HLgBx$aEni9>rka1u{PA`t$bw@4(haliPnd?U)OR zs*OSKSa$vSa+o4cSZ>0dFCO^Dg)C_si{~0zO8L1@@!9Tq7wogj75X2P@d?mD6d#p$ z)xxuOUhv~RJN`@$b0u?qV^L9^&1Xl2TEQS$Q?MA&z4`qWeR;WoB^H?C9LD7nh4G-U zDv?`%ThX)-4ai>Dca*K4uDxeK+Nm@ypD$D+F+-&k^jz3{`e!eLGf%R){U5tr&Z6xj zMNHCu-2D5A`CKx1BP8V<=lUxvp5)--YYm{Duu1wnt)EMhw!mqvB5r*kqkj}+R+Vx2 z^nK$*>V+sQ8?G-m!wN3HzdlHIBTK#muf8xh{TSry z%W>-mf_64i!lA$9uS_f`BR%T1MDX6;_|mw!e4Lo zD_nilF!O}ey;>}_;y_7_CSoa@zdlYI!K&RcZvV*ebvao1xgL&~Y-IAceRASFr_7WM*N6h%Y*R?cgri-M{@UH-7!SXAseM zn~PbFHwD@L3RTg6@F>ab#OIhlf_agQ9{_QGqig*@V(u{qPrlNW^5;zHqqpltI9S?R zq>r@!@~+JYl9I9xt+Y2tpT9-*m$%*^OT5t|1TLSE@k#qP zVg21;LZ^6cf27WdMHnl&p|kTBo6mVIXF`!-D%ZbRsTYY;M_l6Oml<}RF#U4|H@^hK zT)edT9W3lA`+TDFOWpMw!O!gocYZTKa$A6Od<%zv`ZD=^@q7zZl%D140E4b^ z`5e-)1A?NexcYZFHUoTpUkjVR%K8K7{>Z@8L8RixEbKj)&0mM_$6#>jPhmD;^A{1Q zLB>bV#mq9c{_PIE2-`wiiTI=I4>rMiM5%NsZfwWSAEORc!qT*E-1xL8#F@M;562~c z+4E=TKE8t#&4JwhuB;=@B>F=*{;g-vpSibC!uW$m-2URWFP%wV=Lnqov4xb6I*Pw% zi@Kt#nj_4-%I2@)fEE^LFM=`3viFPDzdvp21iSl#gnR|IKias{60;k&KQ!!k|Eg9ga5%q`+yC`=*iaH`<|)!YdVa>OFazGlyb|$8`=^^?2a&`F zGce*$nZVLNALZk)Cgz9WsmkVWh^Ho5b8-%jozKn>H+;Pazhaa{{teCFn8UiHZ2cl! z_i%+&|LFMh_1#JsGqo#s|CGW2XL16zbLT&G{;P-2mn8jVocXl#?VX9M;dXqe%I0sr zo)Sik9>Lu|;5*BiJJZnN%Izj$K<1 zZRT6--w>}?Ldu%~T>obOJ4>{wlk~vfmhnmJU$vJTRE5QG`P6V;EQ!r`!ANa3pAlX>V6NxD!F2JPGY(9M-dBRPreOx|=w9Uack{y~iO4xkfciaTi(hqU@9Ilp) zz30?I*~PU?K4-fG!{+)^-2Ub*IZ<%5{4!VnJQY*m)v>!=|7P2(40x4Y%jK`l^+6=1 z>vTNRhOK|ew2 zXL4U*%hyiL`XEXVe{F?a}KwD zF{{>zpkEk{Rvyy){l)qx-?L7*?%H2aAI6hf_V|J}`?Jot+A{iOLUb#Vievyt5S z)8CbganQmPh_Phr-~C>*;G<@e=za{nzvtciNQA%VxbbO~kr$+_+{4ZP%2l$_vF9@| zKP~Hjp!wYRauZZs$>q)`42jA@@0CxX^rAPD&w$;*VEZbc+aGiCZw~Ixcn%$}zGdz& zJ|Pzk^P?_u{nN0M1|&Rt5mxkSl0KhF`KJfgrNG5$<=psI=cxwidSoh>?{4igVaLvA z-1^5hiN7fNsI!Lgwa*I$io z7)#<}L-61dHvirBDxq2RP;P%siH#FEP!@u@K{EcoQ~KKeZddFu)QYRGo(r{6KXn%D z(_!bAE~%3GhH4+7sY14&ke)BHeP)Gzg#n;3na%HkbT??+6v5Tk>KBW#T}?7ncVP2- zbnQ$~G)~~|hs;xt!Z{NQL2&_FUq9z~flB|~TzxI}%EFgzA4A@T!shrvoL|1_;s^ak z=WzM08k>c=PaeUQi))ztcE1=5rg)soZ$o?zZmxO?NZ=Q;mz<6~#Z^Ujjz2S1SQNB&Oj zcTl^bgsmKhaP_;5Wd1#>UogJ=kIk=%W;dL?#{%RlW$_=KpT?zYqjAOzcx}$+S6{OG zqtC6LLYXH!J`Vb0g@2a#gS82p-)#K}lKoWS-1^A+O-pd^t|V~uW%FxOKNA+bjN{fv zj&_K`izCm%-LLHao*py3AZpYu?*50Sepz_Jx*DFJmgO(B{wDw21W)X;xc;lzh%9_G zvl@o?WAl4oDFn{#Kg#VN*lUu5xBonXG{-t7zYiRuLE~)^SAX4G+7jJw{y49upY;8v z?^|nKm+anMQ^wWb%l?`0U(6$J{p3sXVDjGI9SwEa`D^X#;~@9+J=Z_dT&qJ=N~hws z!7@JS{<~Hhm%#LmyogVF{-RBVE;$rB9evu#{3DuA?Tq`-=0SU|zCP_YmS|%THfgi@ zyt@27c)sq%t)HBjHkNc+7=*T~Wqis}_jh$0l+Y(dkIUzW4P(iO4MB)E6{Yd59QjWa zAAe}m4ddnz(S8=XemNs=ESZ-YgkH(2(&yVz@%8gOZJgjX4Q6&>^Sd#yM#%o4DomTx zv00x)-(D_G*BZNw_2csEJaYp4>As!IuSWh7>}H?H<#)IGEa;gW%jGv}U=(HspXSz2 z&L??6!u_3Gej~j6;GB@j-4E;4Aq(56R>8!DtC{+G-1^GODs5c7U<#MN`qMSSSjiE&fBez= zDY~w;#c^ymtvJt0%Rqy_0uYQ7L@zPaQ!9CNm01}&q;27 z!KK#AAvQUM+ux&AT!6O2KZ47)N6nuv;`sNqwI38O-OueWFm98Dw|?G(i%M)hziEWP z!MTUI@o%G~zSB6S3UXCmO8KPkU;UUH4QW#fxci;wTicMfEjFTs7MssYEq6ldtx_(Z zcNRO4?A_w|##YpP$b?^+@ac1v;I1z7XX*Nk_p`wyuy7pi(O~miur?nomEQ`JmdKu` z`x7?(&?23)-0{j;nLkYPd#2|lICJxl5K|y~p5|Bex&ujk?2lzhTc!Nb^I2!Ks-V=n zEtlWLa~;WUApq^iviY@r`X0(gsB!gG)!dQPX$9ag1vbAu2DiXtk=oq+wP%(i@mUmr zO=>cJl_-6kwX7R{&=o}e3ADc2y>=u$Vgk_YW)G>pcBJ(6NDmzxp6CIWN3!+REc&@n znbBSNq$`V$X}&+iTcd%YF9bWY`Hqm>KG8iK#;wmp7%au3*>SKnoXxl9g;}6EAevi0 z4b6?hJ3CHr^V_qxCH~Z>WbS@k`xgbcxb+7Z9w@?*&kh~a7M z_}IU92#ni(kXt`BZJmR0k{-1{VDqgS9}O4IpW)6Y!vkxwp~ZT9Z`?=v`9$Bh8xyb- zuCKf*Y)2U%^nHZZjhWE@RwXw+-kP9Ij=4|Z&Zm3`%7B_1%DJJTg^XXi z|MueMOK|MLFCnX~EPqX-^w;{J16dyGhbBwe{7#u%1xcoDxcvV4=|Bdb_QUu}_WjoI z@9!b;N)N97X0&u9cZ>WmBuRF^wG|Z~XN+rsPU>2)aFop7r1w+L({Ln{@A~2BBMMUf zT2cHS-qj7;M~)Ho-_rcPHqyb!w255*$$$EDp{TK|FgimP|I&P}t+mEKU)F;1dN!X6 z9#4R_W})2qa&onm%^!(TC1tHLV$N{eYPWT)R1IpR|O ztVyZ451O9)kI7$^^G>+i=Q3AcJ7n0CqJA4h{!%+iUrokj!MN9Vx$|TD*J_jf-^ZcZ z3HJO-eO^BJCcotJY1mhXC|nwkhv%^4Cgwh=<()WYr^Prjy{wnZ> zj373jf{Hr?$cJ$G^nAAz{nTQh_%)kPv(B@jab^T}{<*wOG$u_s297(~{_tC}9NwrV za`n^YM*+IHzJYzJY(BTw`N3)PJ>2~D%BXC-(6Jo$o{{lM&p+Ev34w-1Ib8jmWe@}H zPMs8Hi}pv0_lx##97cRYr{X*R-_rQ`Fjc=9U9c1M50nTewAlJMU}P4YD!IemKXBu9 zK2#;X5T?8TdtTgM8@oZ9ke4p_=ZZ}K==inMhfCmS^<5a!m#u$))f`Bv{(9W}B#arq z+T>Ni)(}44&-LedURHm@zsvfzgIuIVa$-xT>th^u>(2(Ydxx_cbDpC zS1Nu@U!#MYqQ-OiTWRt_cs#8$H-2q&wLw#})nFaT=5PP!3E;kX3%|aqvJBsaMsfA= zd%$d{Z5z(bPoqamW)Gr|z<^_H{w{1<4zt7Jx%|bd7UHa`SKuhe=5NzuKX^YcjjNBk z+1YqYxCKTtWc5{=zZcs=K<`Wz*FTc$5CcOt zxb>H7PYubSf=MEMr1Q^?o+ zT!w`SUxk13o3#F&3$Z7|4|(ILr7}KGQvL4>u1exl!*>Cpb>Tn;lQ;_l5j*3tB9BF~2t^>L8>BEr{zBl`z?=5*LUo@X(ow}py z2xBNdBdf2_@oE2!4#cF&2fMkl`OLYjgZ445(AJrqU&h>cE?n5#QRE*1i2d97Ha58C z%nEpADdUsw{~PMz4(U!o-1)Gbid$7h3E!8R_RorGw-ef=<0Z)Ef7 zdVD$D)`;Ws>F-mB9e&h8up67tRzLk(AzQOsfZw@K=djfBCS^o`CvlR99v5yRq^EbnD%jn_sF0*%KfA z)i`Lu1F61tr1&+t(gI^8{lC2ZsB3Q7lWw7_@t)+)*#GLo9cg{l?v4uUjJWxw+&vu( z3U=n^mlO8C5LP9qi1d@@(=yHmQ`dRHd@nYiYEABNLI~u}r_^UILx-Ah_^-u{=J;5A z-+5WfIq-YoR&Iap^sUi&2M$48Ih)UlK`Ws9tr%{7<=c-!tW|pftE<_3u7B?bIhs4U z_0fL$Irw_W4H(^z-Jfez6#}*~`?>wO`-jEAx#vf?{_P|jM$`|v;mPYir20ws9}U+{ z1*?X0-1v2f(J=C0w;Pwwj<2)8?&S@xe>?eu9?_ocguUzU2(tbI@qF0}$=#wTwZ{T) zfBu=x!$|i(ZWy`JQ2KtKr0Oqg9WTS1>IUIoe=p6a#x*-)e{eaLUJaE#UqtEak%TAaOT4C$X4x;{FnqTGJHn^|LGLgR0{e>Uzxr5Q|0B-)dx{W7x-@hFyP1yVf%guqt zAE8`-s8vEV+65kfpj$3#d?kFCmW|``nNpqw ztMjgL^Us}=hLKMx<4|4UzLd|yRD63T-~^m0tLFMY@0Lm8^Zapm(UQ%l>%z-Wv*kTk zKlk|Bk=m+d_&$KmXH4(|m>j6UK9Wh+yi9avPHRqS&{soO`-SP7)LoS~e%_Mvl zdg9n#Y(9%@bW!cN1Gp?;$G;n2)Cx(n+6yy`J4@d`n$LxAY;ft<#Ug#B`E2vX9Tso) z=f=P7MtI^<+ih^lkj>|Zz&YSl9m2hTn_Cx+b!xe=UgeJT=cD&`rDU&wA!<=vKF39z zK~?W+Xxrg_^Yh~RX$0|yt!~NO{(O^{xj1T8Ddd{S=F@0C!_`A!O@QRS0cSs+Qe+Gi zWgg=4>AgJ_%GR6}=1%(O--zQ|_xr<0hJq`X&v{+5p?&RDQGY%?AL`R*IGH-$6(?+5Z66m`VDR zIR25!96RD?y##~rAC~GL&8Jy$1623vz}+vjX|5g7vt5F6H}6ZIr};dt(GutB_TlEI zk(qYHC1D9FZesJhU?8fBNM8y`X0~d<=8|eJ>XU~ZcXyC`?bFGIbE-Md%_5Ij_}k;Jjx5UTsYO7k>eC7a0Ua^HX7m z(P^%KlvqBTOuOwY;+L+kxZ7sKq*s?k`6`-#o((`P5(NmM1*|Lxdg z7;!8gi`z;Jr0@S>D*g>>dj+Bl-UvqxW&ST6|6VS&B|n=M;NH3r>GM~p__yli1Nip# zufXd+ifv&>&YCSm?$U~hO4h# zV_ylCquL4~SGzFz?Q3p}8H46?^>vB8r1o04fy?jqcb*uU6bkj*W&F_d-yyzpB)fZq zxcsgj6oai|GU16bTVGo_uY}v?;oSKe`yF0+k{h#q7_#^M|F5D+~3efIPAgJ&nwGpv1`E`E`JZ=C&DG;_1ye(@K7(b8x{gO zX>9(kzMKQkw+3?k-LM5Q*!jnPnC`&lZARuQ_cN2y z$K(}PVCk}2;op1*CZS7Lpn@JH9=>;&ys%}>7PuM6=5u1|Tu@8hEaaX4 z=dUP;et>kJ7~C>#A8Z}L=F_k3N~rF+Rk$XTg-|7C_(N2cM(#0C5Rj~OiSa$_ZXg?SAFVK80O|l`rdNXj+`(P;_^nS2h$!t-E z@Lk~Lp8-ua}ty9bF+lc;8Cr({XzBZY>DH+85r>39+S`1l`S!*pa*w9O8G!r z^5x15e7^io^YdbV$h&@Vfjk}KlifvTvuXC z)O}~-u}d1w`Kx$-+HB#7)31Q)i>D&K>G=2CcpK8fdn#@?#OC|v z_G)N6|CP)4>0Aw_+rp{4?x@9rKw@cTJUQGQD6?+;a5V&yaq%f5A%@=5c(y{8_=pOf5w z;P^|KHnyZ@^EA9-$>v*Q=sV$Lj0api zXEPjH&(`O=V_1n#wyv`Q)7twr0Y3G1(i$X46`_G?* zvv;p^>z|6N42XO=;`;`6e?s?LSD@GU$0ELH{ha>6nsjvaz&9Q;zV1{0PoZRXFSPa( zH@;PNvmy73Jn-5&HedErK0QBo09d(@%@0)11>CcdTVF|O z8H;lB(_m8~o1c|?SHkbYE!_B4A*={*%#hp%Q)TbJwf^c4odYAd^J#6?AHip%ib1O( zK>GOtlz*G_G!%NYPZZ^!e$YY`zdEdog=cHix%ubCxFYmfdJEF_CNcGI*`i$%f9nu8 z|Gd%5nzU7R7wMlSrGFd8e@=HYAR!?F_x{(NZdc)#?n6=j zN$X#SNNeIAD48E`&*t;YwQ5-B-XQS$|C)YS6TffnII+8oPdO_8R382bew!)5m`ld-k#_}zxhXaC17(WF}!E}!zIHY9t@M0{TUi^-?g$sX8W7zDG8WPH;8 zY;u$yPQ7Nz<#R(?z2La2glsN9?U)miHkQk|Nn~b6ZL2l246$sx%Ew3%R-#6?;2>XZ{Pg)700K=A+fOH zfa0{$wbzYcNG6TbX_)QvOh&+*L5zTgC0q?Of62Yob2V4S$_DAbptQ^SZ(_yhSnfQG?_Q|S{K0lC(PY)|AqrxL%gGCl`V{_T{E9@yS}0PKFj_J?NY=%G^CXs-YBkh~X8^i<;RpDtN! zhXKbXaQQ@i4_NHJgv)1~>2f^0eG}LJ`C2*`u1ENA<4g5ru^8HRCz!lr^Z8-jDwv=U z$mO%unqutlc^xX-K9TZ4*GKdve7bvVl-2QmQ zV+D9x;*sc2Y1jO`n9sXgV_{m}E^hx{>oe!@LrN*gY3DQf{IO{lco^q!{h=|Ft%#wv zi-=EMNy)pUH${b(mRtx{DuUw((E4qy*;j_{uuD%+C4<$9m zqj6cizV!X4`JFTAD%>QM-1x#!s+5C3!_ylpo<+=SuBP^{Y_iJ2HbuydZ>D`oZdZh|iUlV<;$#D-?Y>4~W z%)dDP75?KOhztP29oP*X^s|)V2U_ zeMM<;G4|+O3fIoF_4V3}0NBwK#?{wVKhNUMRV6SxDZH6KF~7P!!r+!%4A;MXm>&yk zI;3*@6P^U0!v(#rz|-JDCZBB@cY*4KETL1Vj4yirI$Y6;WO|O}@_B7<4xD*?oEzW9 z28|*!yb$+qVe>gp>l9$q1+KoDxeg^aAC1Jr`#5~gyb66DREXxY>G-!e+KTK|azZyF zHlJ6W9)kC_I&S={^wf&9a&yAj&vK=F(E9pg(kHmQ?ytbxfBmMLHR-+G2`yU7_|&BI zb+m>uj%V57IExK$&qJ^}n?I+nVNf|XihEz>OL;8R zPfp?Tm(%+kE}m5aX~x%?{CT!a1KnpCg2{3=e^pN{N$z`l5r0D|eKgL`0n3+1Mg8$~ zf6z(e(PYI(0rS4H`Eyuw3TFK&7I^zj`hFQgYG;l>ISUzo^nSnF7p?-{EEmpA`loN= z`?s~Dt%$9?1G>ErlJZ0A++TwC z?SK6X;{0<_gcTXN#{rMcz9aqqG=DdYm2udqcHI5fSH4-1kamt}y0@wMd9glLwNk|< z#Xj8n=P(0(>{>RQtB*dP8-%pyazbK#Zzg~3KiFaRWhbsa9(g+n{GQF`?&nOeU5?>X zyum(;&0kH(JZQ-C;_9Q~r&t`-HxXj2E1G{k@qNH*TrIi(u!-xRs!TeIQwA4-d%(Ts z=f(BS)iD7uDQ<4PhV*t2XQ&cT>q!B zun-mE&jXa)XY%>&%`VCQ`F-5{^0J*JnNwlI<+Ihd9C+D~C(18rK7Uq?CVHdHFxc&( z@W1%=78Sof-*gHti*; zUMT%C`{xhQ`*WjI?QzWrM=qZY!#!Z0&P;CnnyoLHy_vI$8^5->I}eiXEamFsneVZf zG$MCowyq2&+z5eFF$=hgB4~4F!|_RCZAX51;Bw1L0tV@{NoHd2nAr;uub~B z9Ocjc^$vrMEyKC_XUjfu@b*X|*Z(=VtPlt0pM$4*FPMC0J=q1T*QaymS7KEx$?h+f zB0h&x`nhUkE@)RD68^52=`UTM{Pt=TsV*6fZ8vfB^WrHu=2gJ0ue_K!gtQqo6jOJy z`7C^O6*i^b5b;UZSAOiWB(sC8aP522>rWz?!Gr{L-YxlH9y(g{2pBqCGICSRd#(;(@@ZhrrImIb*x(wxgz{)Aj`tv$fy z>*MxOFxc(3#UOp0DJ^L5miv64K8!d@ZTMM+G%I3>p`DgHQ`y%YKWc#nq zM=VJfGYd56$L32VK^eciQs(+M$6i~KPpd32@zr;x{w?uS#p{`>P^>A-4{81TP@#`y zm-WG0yQKN^TSWxWJUuI-aMA*wUm76oAJC-gmzM{86`Xy3nHf&&&*Tp#*&|7|;qDK* zROun<@1MfmzxRII3heh|8I;^$$FD|~^I_)h1>E{&VPG5v_K$(-#cckneOAN!;5A%- zr~TsqSTSldH$H9W6$TUcgmL4~G^03JsvpPoPamErzy<40gWP~$O#Uo2(;(}`E-rs{ z6D^2o42bwMrt~diUM|Ew&Efi|6Gn|9?GBH?UzZ*T|BF9q{)qBv7(Vh8SKq>~>64mu zI%v}*+s{Swmm-vce~+tN|J3T91^Lt-v9>f&`u@`T)~)j+xVE{P+n@eX*OHXXLiAH) z^LKm0XSlukqrj_w6e?Ph6{8V-Cft^O|Dja;d8AMok1lJ;t$#RAwj^4Sh%-UOy86qXYc8{Wnj~hrvS2P_F(3FN=fQ@iE-^vi`pU^x1m?X2>g#`QQ6b&u;~d zlknF!m0Q0ke`QYUZ;#>fr=Fe*8p_$i!f1AUX?@R_{QYkjCd^{A)u9;lt*@|P5% zPu6H?;l@L3{=P<*LRI4>!E)(8{Sx~#-Wx1P+AK3{9Vp|kfr>9xM?C@qg(@z8E>A6p z(RnkpI+!ixr-<@r&SZXu&d1(!`AbN*ARB|t@X7sKO#XUYR>o`hl(_o0_lE^J`oIj6 z{Trpv52yH>k*|tXM%}plbx<6F^_R54pfj7l{gU{5)OrEC4v^`eE~S41((KW>g$0*C z*K!Xy+Q*%n|8<0wXz_R?Q6l@`hUB1abQ>x#q~!o%}9fy zF)3VqtIshf3f3kfzDy~7n|34@Udm^365{^gR!@{j4ygWUQJvnn1o*x#h0|d^4QXXw0&TLJDk~k9Wi(W)5qTvDsTSdQygE8 zlklmiVv3G7Y`&U4eugC~@3`@0yKoEgtB)zhr_1;nPU+iV5Jr9lFoIOx$zJ*e4z-k#Yl7FBN%h}sjJC_ zrmB5hed;sAn5eea$9{LKr12rm&xp>ap@-!WVWpx>-{|=al_z>+!oY#};um|rWI}Z* z9PWCat51r5%!zuFF`nzh=0|h=BN)8v4%h#9Fu;Ob`fn80zRY6kQ@`V%VNQ4*w|>wt z)PksKkHX)B*!&!jYlWAS<+=PE4zeKc){erTnctZDRMGai=c)a}__`ICW&!7+UVg075 z-2CgzfOvdowGGA%Wb^a#v!s5oWf6Bj-R9B&7~X!ZFnd3He&Vz3R+zdZkUPKc_gLcp zV>q|}I;YcF{J7;1z+qKp{Fiez4eaM9a{IHdbucHJ_mAN6H7YX~hI^)S=Yzc}N0L9I zbg*I^n=em#jy6<@d+v!)(5+E|fy~!gC^jk=Cc%OU+67pAq;xd$aWY z{7%JxCB={6PRH9^|KCdz|5ke%;r*R#zJ}?4fx=g{-1u*ok_Gt@W`vKbZZ`ALTjW0^ zwQhwD6@P^;?aoQ#6MBES%4iFce%1)>v}Al4Q}N&3p=zjKtpd-Nu=Oc1Y6xP+K=|vy z)+d`-3*y^xB+ig$>r;%=dtrykOEa5B+58P%AE;1qK&41iu6}u@O@?nKPF(+EZr4?k z{c$tFGoH=g1eXO8@6|(ioBodv@qD71T|Bl94&%m$4-c+^fHn)b{^NxCyU?a48V-eJ zGULN%e*z$;%NoJ^@xSjco^Sf2wiTxP1aSLTF1p0S%;If=mT13?c)qZ*=UIGVcmSL$ z)TDeCQTsJ=uB5^CN%7qL%=G{vN!5lTK7ooKRZiwYo!xHkew^0_MiR?Qnz*$Wo6p9= z(?B#1a_18VF4iNpQ~P3@)iOTm`vT8eT!T|x3PkZE?N5dpo0BneD(n?7jmzKP$qQh9&xzdowC}Cr@oYf|JZr($zpnS!K&sJP zE`McXcH#X8kzg=D#vgz*5C9TE>U6=B@_lr>!o zvFKth+#06H)W?k#Y0$HAOfm-+Y$# znIEw}>KM1eto1**`Z#BkIgxiVz{M?O{FzevcyE;&UUF{-gFHtfEJ^W_=LJw_Ko|1OEOnlG~p>t^X9j8Ft+Mu?MBA@KT>CAm9F`^y}06 zYYylwfV=^2-2N5g>G2pQnSJ5$H~l|vIIw<}P%v1QKLUv7^PSG7;`lA$P%&zha0{xQ1#UAtV5ycydI^9Hc_Yd`7?c=X8@M!jM4S5}}) zS{>|(ekIz{_m|ecqe0i8+rg89Q|v$gL+npR#1fJ@R3Dwb1xTNlBRxegn9+>K@HOZv zcfXX=T|)dMJsx8ucQ*g$@6!Bv%>D`uT^|cO-*WgHWKJ&U>0|6Z8Gojf{;gQr3Qwng z{(ZRoUAXdIm~rzFSO2=Mbij7m zBe?OW+J-3*(Aq{QwwAsB^!$?Kx*q-?UFRK^47j&_Zb{EecUKQBlZ93K^l&u&R%(l<~WN$M?B;uH(3_@4p@Q_bH$I^}OHb`#jI< zs!5*<=Bw%aDTJ*C?c>v!_1_TR7&K&g5cKOM=${mS--^Wl3_M_N_+qC19eA0HCJqyv8prhb7`aP9D^`;b1JiV8B zf6gzB6A-&0ky-!k7(D`S)a-}WG?i2J&2{Bv=%$#(nf{^kwPM|HylDwP1H4(_%bD0e z`Vw*%sz;xf$X7^zneT-0&Fo>wfxiR%e|(VjUq8!g_n=uUX@VxR{_EV*#C>pnDguX|f4~1F-d?HMQB%|4~|@aN?i`(_c=W9|P(!LCpN+%do3Rqc#(q zjbBjt+6bu-q!P)TzYNzu0hVs@67?IYUvc9vgVwpj+{EK_e*86ur8)m))ZsI$p+}w<4p1UOX|~<<=>#^ z=%-w29G#zZ6O8%r1G(-L_yIznX64GEi-{k(XItp`iQ-0#*Z3PCz2yQwK={MCW&O}k z!$Ru4t2`^%LIr=a(DjhOS3Blj+Vu3ItFAMQN1 z1&N+dho}HLKW$a3VZ`q#On#<^#~{BG{26F}``08tMLr%79x|7yPuGHzQOwR=Q0qqL zXUo|D=oq$&=?}NB4~5Teo0S1LU08_wKc zUlDKutX9WL%qNrl%+3+v9T#=b>Yp#g`t+2T&yowd482{_Ij)k<*T(8$cxAjAT3clx ze!oe5di4G-blq}F!vB$cIr||zZqQ(KWgwleNdIb>wDcNNpX#0<4DN%`o2_)dwmE%+ z#+FAMYk&Rse+Vo24@L_I()nuR`3n5e%=CXR24Gxrd@yRL`7HkXNxq&)siRgWSr}a^ z=o87;&N)UXd~07=^^OZxZP9k7eZxp!PX0 zPmKL_v(H;ld>1FCJ}uq58a9_qWbVhxZHz%VuD+1&PS>ZKhdrP@U>1|FZ?#D%>t_%g zopAW?-zTY0#g_vhyk;45KGHBI6wVFWz&xMjc0>%kf8@{9C;aRhQeBV%5OayjSJvuO z2>!i?nLk$epMV1M1I+rW%OVk0>NOBqWzzYYueVBeyP4hxI#`By>b`$8bj!pZVz>| zbz^7#j9fZjsSAxz#n|3V|2G0!IP=xzqJQUulKH+!c`8~oYB+=(rt?*PaRL09Y{$$O zOU$++``z{sS}N!lfaLtuw=QcSFnm07{(s%7804ww1NlY*UnzwD^WEeD{i3Eb=NqRz zPeOIJfuN*K=PUnI0K`9cX6B2NcZ5Rjb9Zj`EqcDVIwJ;Bt^AmL>AfmKqx+dOy?k3LYJWtpuaZViMU&GFB={oFKZ>bd z0E!!In0%?*Z$*WRCd1S`I$!I1tby~J#xV24xB4;2`J@Mo-!1H)lKxP4#5O2-;>Zmd zBjhJ!eptOB329gO!{C`2RQ<|%8~_6&7c%Rs*)^fypYOt)Z`4^41Dv!E^L)-SgJQI% zC}8{ljvo8N$)2L?m;ON`)WxI+=&Yjq!_zC8xaSvdiPQ^(`&&r; z%9=S94VgDYVn2rD>(umxP&w3!nGbf`vlTtho&ZNH>3qqrT>~Ls5wreM=pKV6NN2_ptNZoQ@ICn~;@?}tz3YS*}G5J~&d;)GXMM&HaO7_1dx!U2}o&C_&6Lh|mTP_3M zm%!|QO)nmb$GIt>DW?U#fbfT>QXZpjv zv4G>$G?AJ)B!5Y`s>r7X6|X)P0>mvx_+5#nTnP+>N5Fqe7^vu zcQt3`gS9zZQC;3xCST@T*MONU$MlERRR_@ZFY6@k&nES2+JbFxqHYqi|K*_^2$62H znf29)zG1L<)N*EjD>^p@u4`;z=Ib*`Qz3d~0JDC&@bUySb_$os&q+Sc%iG}*{2d)l zQ|Wv>wY&oL>*JXDxx$*EIIyc6Dw<2@qf+f2C{!Qjq{sX_UqG@yW!nw#@-h9;r5}Fc z_lw+LDKV@8vx#S!eEggMc;u#jsJ`;B`1z~Ee8%2a-=Ji{P3HX6-pPPRZRv-kI}3b} z^SzxW$)o9(FS!xvbUu2f1O6|sA5!zB^P%mhj)tYSarMvW`qTE-h_C&+!R}DH{_N%N ze)8X0EXod6`|E!s^NFKgJRds;G4sFBMGK)@p$RkpiyGvC`kIc08l&>R{!_Aky6C+I zieVJf-$gt>fc&?*ft`nNKM~1C)<+M}jUUftM*W*_lI#y3whM&$(KDF)VLR$WVeA2C zX8&neWeg-1ZD8hmk^R#kHs7Cl|5xzS6Oi?BkHq{0ncoer8ikt!d!qDS0w3i0ScP4# zK&WaAGhcYFKNRnOCW{h!)A?{(d=D0$Oy~CP5cnYTJG~qZ*XHwgyq;z7VP69Y*G@6{ zF!+zdGd}QlJp0i3u=@556m}Ie=a;_s0BoVu2lYI2N6Z(=#{_qI1m;yt{gAc;Y&N0~ zdhz~)_<6E_d*g&U>O1k9gnp3uopcXlBxk7v_tWWoq|IpIv{zgcY3`@%hhgDVblY(N zthzzZ7qo^hggu`}GWBElR1frM1Hdn9Iv)d)*6`5F75qge-@DB{aaa0 zsgN?$mpLENXX8*T-B(6pJ|d2oPbwO95-u3+X4XG($wRS=jSRYBUM8-8fXK(QzFY=$ zH;OsGYxC9suQ|~ft$#Q~{C<)5&o1z}2jz29CHNx!S&}=4b)0&lb-r}Io-e9_(h)h# z{pHFu4o~#zi98MIeBEyQ2D3A-a+#k6z5yi9*J-}Y;hgZEC~=&?7r8%~<0OyfS3G9s zcN0Ey`22;QX#Z9^U%QIc(ZIW(n0(a_HAd1_3QWE{s^4=#hpsUDPvaEr(FYxE(38FW zS3guF1SI9wy{( zr2hEZ8lyN9IXDqZ*Pqp@@3=|I7ezgKcNhQnC-Z@}9`@+d77ZBRDCiHF57@UY1lg}c znfbu4>mF!owhdfZPv>JuxC``JY{qSQ_0L~P&abOJia~0fmod+Ovx?mYA+JOdeE1Rb zdr|WOq5tPe%=#sGWEeaqcUFDsSOV9Y8HWlgF%Ic3E?H^2Y8c^?<+!dH$1e zygd4|vYc7J_-y8|dvbTAnn~wlk(>tVJ%zi}YL*x8=PR;GSsP}sn zDj%Xn_Nf2(e$Z8qt{-!Y7Q$tHeP%ulCq2-+OO_J#3#lKoY+XQUo-s2&vzZf%o{e#a z-N%If4|)Ibw(g$LIDQnfzVEy!5TJ5AGk@NT!yv`6P_s?{5$I_V4F%68alI{R({659e6t6HflEkFTHl0WM90#ov#) z#QVQHUBBNQ7s7QbPG!^!HysS|0V(zsJ-E=Qa`Eq^OL#{cNG? z!y07`RQK*Rw?c)k55T|w@_#zRryTnG?^*Sp+vRYE`TjS!*(0aq-f*Kk{r#`0UkKYK z=`r8`pJ^WG&t@~wYZvn46v96lc)I{vZOHUbQ7*CQmg@p&N)z6HvVNB~_kbJN)$tCKO+*N7N z>;5`sK75mZeqekTiTZ@RA9&b`lhAs=Pl6w^{%_rEjqUe!L7D@eiS>ot-;GSV0#{${ zVa~^;T-C=qpTEMbqXJ(82)>4Vxd-`cW10Tzn3V{-$S9z-I&{9Kb*qJ2doq~&g+(VQE z6jywcnXj$fAi`$tUC{+SI$t-}X`s_3HC)L$I$u#a#>mO%569B4*Rt=qOHZ;zcM|FK z&DiJmsPu;_=*<)Ki>z-d`!9l-T?a7r>$t85`Zm%Kxc-8E)e`#U?(YI`PU|!KGhQoW zQJld{80kRgD`}u7JpE`QQQwgB1=FqtLZ3AvX1?}(aTql8oXG5NHo3%teb^jk{+z91 zgI%LKA-@H5zGNq)!JOh%Tu#D2|0e1067+1aT3ROw{UZ5lPdf?5s-6<{5vgBB4mQ}N zuoJ2~MCZ%4<_bjm1vC4f3B&Ypb?;`d>qF=3^@K7QaC$$NbeQfBy$;!78&z4fcNCqk z|C(!HpVA@j+;KWzTCeT!DJ+W?FQ@a>pw|i+4mr&E)1o#zT<9Q+j5`T@k@vIYH^`&Q z3yYcc(O^XpPF*02N}`&@-w&jIb>E_aq*|YIAv5TFrIi>XADa#)Ur(f(xB<_PiEJ|I z^-(~FJz7xS9d0Za_#*XdgUup{OVeWWrRsq`Y#IhZZ~yMU6Z$3d#RWdC8qC~(?=vA5 z^|;^!PrlIS3qBn1geAU468c5*)p{lnN>we+!0HdgAwsyg%j4`Z7=n-OCNUB=AM**EKUcT$k4gjXSoT zs$WaG)pF5#w1v+2urmc{CIGdTzWhK~QUFpuKJgP+e`6OTG?#ZJN z+pEm|qa~GgIMtvt8fYi*MV|jBe~6!*xc8J>wVlov{4_=m8LgaWE!`ik-u9jwbvRRW zq?)c@?V1iq-Cr42tfTX_d=}4FPYottJ^Ff}SqJsO;GV!2sb4`Vt`Kofhsjs0O)T=! zvzNGEldQjN&Ur%r^bt(HoHGOAxP=w7{xWV0gK^tObFoSP@u(qKjD%0FKYdD{9qdVs&r=Z6?4)WkDc}t65{)b>nF1QYB+QfUiaU?owz0FpC3r( z7a_Z?ahCxpUqGF-qWzyx)4vl3F-5If0q)x!CaU_g*O^eKk$Y2k8&>by^|f(otsrbw6i^ z2SiJuIYR`#$on}Bf6JqT6Y`n!aoO|iu8}2*wr?G>(IU^{`~+X^Y1U}u_#}868xG@*Dr-+Pe>axl-Ym%_&5;8 zelcU}*TR}Gh)&~}`sGm(3;D+O%zWdB9iLCMe21&uep31BekKh*9$UcV>!hT5wqx%j7GdV-&W0(*g3^>3qe_Xobzm zN0{|j-S1KObW;bMtGFrte3Gxmz6$7S`6Z@59HVWAH}v`msb&IS!-@R~-x3XUVP=Jd zevy35voS#>#vi!CHoAVv=r?hZb*Z97%jy2m#?=AkY?Xttk#xSA_ALT#doLzmFLFK5 z!E1wHyRlGz0a1U=cW{M$Wm-)Ay4VtfO0>s;X%&6G!7$YmUJn_x^QafAqOB7Dlh1#GG&V^1}*G>-HJG{%oi6CH*Z89)6p{%r|sLSmU8ipC$N` zBl3-}3OP`ezgi;SAo(h5vcgpzpTO9j&R6Nkd^lz9&E#ug-yvB0Tovr9jmqQs z{Q4b+c?o=J68p7^ofXiIDd(B~u=yST`AFW%$E9})Z^$=7p7 z6C~U6p2=6wmG3$4h-A^nIdp&Mbld?gwdn#YuG9G{oxKR8FZN*Ge{iAF10DI*AChe7 zd^Lu+g7*jw=J~WT#W85TJBH4y>3r?!z5+!r2}z@U9n~uVpjy;oQ%y%zUGN%U~RO?{bA;YRxrAr!t8$qj~<1e z%YKG$UvG$?C;8gK^A+9i47bLbKEHakcod#@>@)0-r}H)Hmj-&Ne}~JAqw_W9unC%M z{f4WUOZSJ@__IMPmL-VH{s{M@lJgOXXC09J+0GLFkjxMLq!z>exhl;0p?ggp$hVUg zQ@{Eib_GNGzD&LxD*5wO9*LNI%~|UOT@McA_AUA6FD2(!Z}bj=^uS@v{q#5A!XV4d zoZ0`XE{KJxe=u`?sLtC8r)Ix}r@z|7`bF|(shkdF)=td+SD2p__C5Vpf-f0DzfShf zfxC;HnfXSZyA>`^cndCNPsH_C7EymqT$m4Pvo|vJ%lXJ){L|(E1V_>N(x@*3OB4Qn zmcRKS=@0Af+Tw>#njtKV&ezHGT6noIl9|t6;^#wp^lJg7P=PP<{>k97Rw)0J#LPFU z`R9Rue%c{{ufBwSH4jrjM_%VJ=kvzvkHYFxS|GjbotRJZ{z+FUO(Zk>Cet6vTsA?O zpX!)=8K%DHQgh;%`ZZP75tYo7hM*sUevy35TfZ2tJW^(!|GabVHgwre9nORa`sGLX z!~AQmkhQiKlP}x)7?fge%ip0T=$90+U#nT;32wUD%>CNk=0UK0o<1|5U-~W#{yaBk z>esY0v2bZP$DFS?XJLiopVot1b1RjvGSzgrX*QL)UlHSAh3#AGnS2fWeG=-M=1c4+ zk^1GUYlR0C)kAYIov-}m`A~7nojJdxyKpf6RDKWarwV-e5&p2PqYUny@n`Zi)YBGw zRKJ1TUUa^C<_mh&3+u|#lZ(*wqoiC43 z3TVWEY$jhD+ih`|9dALypU#*6Buy0evWP2rLDw%`WP)1SUUIDSAz)%7C%U^|w5>w! zZ~h@MUL$pTkR$pr?>DC>bLVgVAUXfKsd^D4%PKO@r?raOhF+iU10zofe3A9np2@DT zC!z;)zT9?nEJ|Br1&7-NzR3Bd-kDwyP_4n#uQKN#n3Sf+-6;5{Z<6QF&gc2+f5VX3 z|1v9%g%2&ZOuqQpEUY)B2INM4r}8C_(jn>PL}vZftHlzV@8NeG{^p0Iei=&Vzy+;2 z-19_wei-}N64&kJcZjCb`SRJ857k*~n0(FaKNvs%d>d}6()sEba38v>`7-nQWjeNa z)4F;wkC6A9KXbRmS8vyY|F0DB^Q3+`d~b#RQ{tF>1$x>O-;}# z@8a+iMXlkkU9Aj#K>rH<%+MUr1ua<>rhW}L6^lG<&EZm}kROtKEx+ys%Paaa`C2z72s#-JV*11K z(cyqk4P)kqw?4S`wKj{yrj?hHw11?L`sGLPb?EwA?)2vf(Yz}{{YCOM$jcEOiux+S7l5RGefqWtJOcOy*-W8- zM4oSXyM7xQRIbWAf5j!m4ca`Exu6CA^hGkCU;a84)!sA)+h#gn+ONEzxwsdTuP$SQ zVBafkX1=l1FC3&j^qKuHRkb)Ux@pFokD6$0i8qu~Li4DvV*N@X@(l-Tp08_&$(P&| zp3j$+Oukg2bHGu@k;zx9yCuFM^B9(vKNiz$eVAB_omc-EL}5WY{~ zi#$Ip@k<#zIJ%iRA61uXgJ%~$gIzB?#qTG{*VFN@V474A^L&Wo4K}!sausyjO6TiM zIp6=%-p{;0WMjS!UR(1F-fIhdsSx`0nCI)n%QSB4Pp38C?Y?W&&TjL_Xgv z(nMj`FEIHs_c7t`f8_J~zvqXMd~L6J%X!O%G5ON;cSIS1AGprCbp3K1wipgobz=I% z34J`#nTBrg<_+B+>UMX7KvM-~KJPvx4t-u|$h?0Xt9!%Yn?1OW9sl^0%r_?Ue0fA^ zF!TB1W#RDdkuFoex|qhnfg#4s{LtvD1um1V04w7!RK6~+Nrw?1?U?z-h7p!nZF~ij zFZG)_5ZZML^ZrIPOH15sS_P=b(fN8OTL5z7`2O49^JD!$Uc#V!ny!amwp@Yb_H@4X z8r+AE{Cu*qD_y@#`1!0J&mO_|Rdl{Q2fYHX!8@7xhUtDAyhX1P*75gT{%?Ms^oPf? z+CV!pl6ijE=5QOVIG_?Ns*Ako75pKoUz2{@;1em85cOMDe1BD6tS#~H+nv|9_h$FF%UI}-k^Cj?ddoR0?iQt3 z(DiM`c}KMVJHNwdPv@^eelg4$D#gt26RkXvx~39z{Y2;Qvw|D^aPP{T{~fa~4t+Ep z20EvO`9#t`j#}#to?TS9`XswKYCRw}_?8?pa8d{GWK`;KSkA5-32V7+^#aL|#? zpPWJgY_6Zpod4a@RS&0BT!i6r0)LK#e;j9jAMT8BWzN^v{kFyiqH_4!x{a!DZw+1n z8tBW+KiW)f@HWqKFn@T6%3rBj8$X*I#?0@FrrY432g{-H0G+?jzWmuUK?j-rvG!0K zeD`@dRJaTL4IuQb+iFd8E;yH&FZR!|!QDDnfM34AUr&NRZlejZ7<`-icmEv8pR2|j zPGd@tD0!&@H6Pjh)e%+cyynsa=={Cfx)@%GIz$`Z(EX*Nt0($tC=bh&==Iy>u5RG9 zU52^ebu=>$MduBH(ZA{Z0iSzqxu7I*{usI6qR7{8_w{=*=kIHH{p+Wo&CK`zEQy1k z%0rp+i<{P1VA+Zic+vlpn7=r}UuG{#hY2bc%>BrWWD7i0@fMT64<~Zqc;IN}e6TV9 ze73?Z(2}R~cds@d(&eW!>$eY;y8QWeXW?GuAo2T8^7nlIeNb7lQX(HA=c__)SY!3= zccE`8oxfM;6^uCN$>i@1Kff7y{Vw>Y(fRY@c>QzT&D_5a{b`LyUAhbM#sYszgumRF ztbjUjJad0cZ6weC$Gb4#zt`fwpXBc$uYV{zn>k-~e4`DXV^a#wyXgF>C7Gc1AJ@5m z_iK^-={FI za)X$GotXJa=&3lg%vTpOztj0UpYILT(-b({CxZTw{M~d90)Mw2O#k`7Hyn=j&|uDo z=uC@)nB#+)`lp|m4ws5enEvwhbPHVbuvmhxkA%J%cjQ2A7hw9!bIUAnc|$Q&mRC~i zw`U^@fCC4nzU77MV&9TnFo+iTBF`WDKH)wXL@kl1-$=e@@%wMy)+JCT68O4EDWnD7XYtR?zwS_OJ~mD}^xk$F5(r#$7#1K=W0Rm=BV#1&InsAIC8D zExN@Tr{t7C`d&I;?ZKMp=+>i5ecNtqgIBecK#P;WmkOb8^KO`+u~V-x>$^j0Z@A+A zzM`W3bbZrU>4a+XUT~x9>3o@IEQYuvADMhzyyA&!wsw}-UncX(gm5?B+y54wDiZXO zoNu&#ABSGv8vr-3a6bs?FHN3#^H(o)W%AW2Gzg9wXEf<~#*)sXlHL<`8WePzn zN#HMz$WOBL3Lt6pB<6fb2hznZkPV-w()nAq<30>tvp}N0Bl-JnZH@noECQP<5Apj? z@@Ek73WnLQW9E~QYpn6LB}K4OMc_{bX-L#ZJNC9g&)fj!{8i;9em}vj2%N(O{^SUK zdwp90Nx$6BoF6U-w8q9eiePkSfj>>cUtT+;iPi-jX4ZFI60Q03L5o2Cm5jK)Bl!z{ zYl5a$Ug7?ouR-eD`kk-2;nJQW!`bpweM{Wngi1S}aOqF!{B7&L7|I{L7d;s)@I&U8 z-5WfSL#`BPji&2cwu>7m`L&6L1PRZR{CWM1LnTYKVA&)(e^raUVeOmF68@6hk2&BP z1a1|IOn;elFdX)n_GIc?kK{P`w6#BT{&Dtxb3D*C4|0FDQ28@Ikq&ci4Q2MXPga=Y zFWz}f{&qabfi)JE%=wWzo?qqkJg8hw=TBF^0KU8$%bXwKy6NJc_E`|6A@FBJ)OX8M z@57to*%I{~*&oP!Vucm>jP&DdI)9Nxui%`M3se8jXz}ya&+}o~on$e;B!36DwLx=< zAM^a^#WvQs$B%qy9Y^P{M~MP@bTpFbFV}I_7=Gu2Woo1N^GW`CR%;^L5or?rZLw=8>(Le`)baKKx2%}Xm&u~Vke|>fl3yk8LGrbr zrx()n>)^Z>(fRu2?*=+oJ~R1Rt`U!hl=g$l)pWidHG4y^9@5PGRUxv zI2=CA&zCXIcap!t=O+&|nDhHDSDItJ>~o+$PT*@VQNNAKPY2ltgPDAFnQx9AQqD>6 z^_K9Ls~_dS@7E^G^Pyg4nq$qDb5Nl{=Syo+0jSJFOntk5M+Z+<%Ya`m28!P=lCSuf z`~2NC)3}h?^!!q^*9w1rbP*PP*(!cMm++U9FTH|0Ma!A`mQZVjIlW6DA4%s+??W57 zeD!9|XK7Yi;o^RmAouY#@#o7B`X+rs0V$6NWA+C=YFgtxOD@5GE9iWM-q1voaWZrM z@zO|Z?6~<76zmlAO^NWAkqV{=1)OE-n~LZ)mvzRSIbX8*f)jGeF5`4M-~Fq9lKr`< zH~IWT>y>D337tRJiC(Dtyzkt%opk=bac(f*sYUcmUwEF>xA)!Sk)d~Q=KaTV$Gzdq zik~9Ze56KW4BEG#C+JR(761NzoaFr@T>^tZ@4PHi|H|UR!6QkT$>-Nwad0A{FOyF{ zO>_Jx=oGlwG>i3*sv`yc=?yJ&@-COr%|l}id?pvsecKD zR@kHGIk@+}LCiO)fBWk+QJPdD_vQ?}zwoHR3fEelgZ6QBKEtI=(eU(K34H{je_phu zk=tCfQq<*U*T4Kp*l#JN1}EgX={DC{ht6lli^Whl<2jSh<~3fZPU$1pD~!&k+Z{Jp zefW)tbwByU$?<4yNe^g@pzGtP-`=ooz<1G#gY zr7wjy9c7C#VCp$a&2DoT}MYc;Js5FzQa{vqb3!Y#X!6sd9966Yt7d}_M9<{s%UW$NdXZ%!!j(sd@E%aojlN9rcT!KPXj=KPp}ml+N*&H~5J@2LE3Z%c;@8#S2x{irmf`%*Gh7pu1rt`#`73oVfNsiW%=&OzCmlTYODvS@3H+%L^ysHCMcJ0h7Nq`qNP7ib5`6DqSCY%Q!>Mg>t4owg!5k zQ0E4&(vz-_kCWWs=)f1Er15nBnztq%mE|gee+->Jzo9;`)$+ZBK9c!NOnnd(&u^Ezn_Fb z(yq7Q)uW$+yw{ z=^4%nr{hehxk%@)%T7}iqMX4cH4FI-$zOS=H=O>g+01-&jKMUN*7Y(s+DhP$obTM( z+Zk@{yUXOyIMoZK->8pYF&VPMJIrvCbb>8RP@cW;HPNttRdO>Q^ZP_f!s0 z>%(P5K@i#UNfg?f&R=SBILMX%5#^kqpU*wJTRhy8R^V!?g#7>j$@96RznS9r$%i0J zkWp3a|9=nr^dy_ne_T(->;uV0Y{Fk0ZR4N2Z#-o2k98nSB} z(|_Kqw8Tvp(qMYLz+X?of94u%q2pYbL_SK+pFJ(K#9BNUbNmomRcWvTQUtjSbLsZ<}UC@?k|jfxEPuT-el&dnw4H?hv*r%A(O6u zg}>Y&YHI~EKfQj<8;%XD7EPD`$B*QE=L6RRsBXM8L|u-i@;9p>2u7W268X3P(^pCV zxv?=EqVs=<9QywIx#ammn}5cEl1mq+{+&BuiftPc;Ahcms{T#vkpWY_c4y|NhA&NV z{-8uAe}_iqg5wf(iTW>vIRE5NwJEmOO$1GUfxlfu{r4!m0PYkFX3oFt8Z!uY{T&K3 zJO%!w2>;n}0C;a^DIoV{8`%x%Y8vwPKgHF@ z()rsm+Zh_RY&SxjJa@cp(NFqNa^|5!h1rF7ZhvwOI zKGhuS;Cv@wo^S5jXu+Qk7!M1t()pAv{sAQ^(>eKF`QrD3ydNg6iJ#9~7|-`$=zQ+% zuZYHNab@~bSw&0y-6I~09C%d*ea5zLU5zlYAJ`ng8#&c!jJp#k*#w8zV7==j`h4%N~5ykhJO54v3zvG$MbgS^m?pi(YX zo34-b-tLg`_y*ITIy*!o@AscL&lKVF$@!Vy@;(rpQ6b77OxMq%#slci_OD#dRJwot zc_RqUSXYZYs{egINa|-dr3g?u(j@v}^6%%8`YEdy54M@VM2Xkv{x#&`O?2nOK=5na zOT9mHp-TpswRL6Qf0j1e6o-}Vli;(Q@UO{se6|;+^MrG-K&{h0ZUhP)*XxEBrn*XexD(=BG>plO@=k%A*C&QVIT*YKgwDDILs=xJ9oQ|sa`%kYa3HnC*+Z{2^e13jj z6y8^wev#Stv5N={nDG)xxHK<* zQA8ULEMod!)gTL87qAy{Uc3_j{v^M5u@-vK*_+Al(J=n`-Fv~rMc}s$N$x)d_T~8v zi{!qnpz~}0)&fs@uou?43j8WzNq#q~yyk+>TQmEYmcyr`S7*{V=|KWNB)|Q__kOy{?ATLH*=^{(dDq}%s?i;iIwK~#@tYNZ%OA@ zGrA7moE^!WubbT20-y5<1&`K5F+XJey8PY`80dkR`YYGT0vC9PLQG15`1!Yl{)UfN zMB6scX6oHH2|tc9NU-z0Iq1(_dR_p-pMPeb9;3_8Ds7G`K;*HEVZ z2A#FQHZozb#G20Uo7e`fR?k!<^O>G64NRPl5^a(>-&8uk7QW7qJ^wf}-;KHDi5epF zIB8}2e&gx>?vR#umf2tFwJsXX^?%9q&n63f`2DD>q9J4c@h6!-O^=I4kp(ZgTLyG~ z6QzP78w0+!d#(1Csn2qT zH&NMfHSn91LFKy(&Va5FZ6edUf8P(1_cz45nP9K;flR*DQ*&Y67FlNfn|ag(->DCT z)2jr&{fK-j^;-c*^;Kc!!y>JLIO_5`Fj-6IJGyf@48E$#HGTW1?~?a>wYZyO_fNr) za&9A4pU0l5gXziq{BRdxK9D@WCaTmNAGZtv(G5D^Qonydz#Cg;KAgaRzbq1kz*JW{ z-*?t4BDFbA+{DxL{r?#~Ebw~Q5a?k?=lk7UEtK2h%GBp=ygzaE2!TC4=zRaeW+<{X zn8|k{|NSy*e+X2)Q2X0omDJ~@R~tF0P(zU;(CcH%YtzxZUGd!FYjnPs&;0-V>WD}$ zM9?qNU+>EDMD1l~x$%#M^RvnQ61z3-ps*>2nIG%zi$<+&k2#$(dVQ?EmhbPNJSN{= z7xMo6#A9w!(SE8v?~@OPrhpqvzGsh)fVg=TOnp9erx=adrVJ0hDhdDpAjx;w;&@P+ z^Gd|(|4hiffgV2S2DS00sC-}FodL(zd=iBtL4N@x`7Rr7g3bN?n0!Cokqd_$q$Toa zvVJaDVuI~6{a}Uxo$nR(1<>QTA~Sy;{b&I8R$L9qBL%)w2>tHy@II(L@55DQ()re% zZjQIy*a=2^=zPbYu7lU>^qBf>9%PPv-tB~^!F0aA|Mvsd=vy%LJ2TlFmv-y~|KW7L zU+q>zlLt=b{LATl&nq^^X1xPo>*HGS_mdJ)KcmfBNc;VArhbo6x4>6t1OS$$^ZjY9 z8FKi&le>13?!TQCEU?qW0DvQOzQ3Js;G`DlGxa-p_6)RB=K%L-%RTY?OZx9cmz*I_ zE0yWL&#v=C7Jp81#({Lcr=50(Yx>8S{(HS$0{TAWDc5!RV}Tz|GM~;$^nvp5vl8_) zxu5wXI2uVCmvg^A)A=s^8U!s?h0OXnY)S-VR^4Ipy~n>8nLL$)gw1rmSIp!6`IstZ zKGqm=1MNWyAT{(no$r+yFzxs|k$gK{zhAZ)e_>r`ihcfAuw~-)h>0Fnvo`razx}XaH8{J=_#2I^S2d%VEER8dJZs^vv-k z&Fx?`iO%=?KXp*FZ2)t=aFI37m(_MyIhM}%U{O0{W*afj7pWR!jx8r_hk5t%#eCKh z{#5AKe_Y6|dQYFPc%5L5M_%0yhmJ~%_4gxD zUkC3uLk%6s92HME*@O6A29uQ?Ccw; zaj7ggS6`;`yKQL(1f;%V`tP(XW1P(U-+$*vlKg%u&V|w`pGC6=(fN&hW{iD*t%H-N z>HI!zE`ZdNotWouIXe%)|81QEb8c&k-+w+_Oep8sQWU}LZO zg8v3}iTb6XTRj|-)?o7c>XRAf^f!Z4S318H;q6fJU??a1oSu)Z=ATa*vKiiOqVxMP zT@kq%h`6L0x<0Ghnd6Y~&5)o==l9ZjEwpC9e?F;hO*2r=flzK?FM%&oe|tT4hM=u6O#N+-@kCQM zrgKi=!tTtBR?7+8oV*m7A)V z{@G@_F;1VjipghV4&Q(3_g=)h-}+**F|Iql3cl~4^J!^O2vt(QM6CPQHfRsPa~d6? zdM}+%SA%kR6C%&8sH5{4H*Nrq@8<;i#q+3q258p9mKVL4d>*@IhAXbR!po`z@$*K+ z{Dva0ue;vqGV9~sIc7K`%N62>34A^!^mTH!A_{(H$>g*8y%}E5pMiSea*g=&gT}RubJP?93Rqk14WU*=UYNwHRH|DBMo=1K9A1lQO!m!YEmC2pBc3?(3nBN z-1cvRegbhmWh<|rashjp{b5}>FO+sd|FxH+;L+YdcL1!2{A(WXvSs8jEld@Q@e{Xue?BL}Ns}-V{`SR1K z1oUdbWhQ^Q6MW!uYocg-nUH^x{P4w`Zr|% zbz~y-ALkcZLFX?&15$S0Vd~%7XGS>Z%1kDIi@xN7)2L^nYgTmrX2=+0mya_+_h-4d zz9jiuX;=soSG*TZJT5#>&PVOM-5)0yAdnd?@aM-#&R_iG`?qJ_{}#O}qwC-EEB)~t zbp-lqbpF!E*TaVI3fyFSI)AbJ{IvGnxsbY)&ff#?cKGzAFSEYfKGX~cUzrQ733UFn z@)eQxx}i+|2JJS(nTGSg(45X+w*y*e#TSm54=e=)fBla-!`9LuCVyqiy--}!KJM~p zI)8th*23a*;Ud=ki3M2+C`#chvwn2h>;uOd4v5|~(fOOm_ix-AlSRvp{QJ4&{8NN> z1Wccj#hl+)UJwtD9M6d=xBSazBQvW`d8etEsso-&!&fmB>g>csX6;uDd2lmIG%&ei4 zJe|Ky_T{kS%U2Q0f1cmfA5XHjhUl`nRR6huMm;>=F3aREy2BK=ym5p&Lpp!nm)haJ zyc*|vhpvAaA53w-Dn}SSPvEbd@Spv7{s!jiF!S5{-Ff}{;|Q%O)l~oa<%SmO5@jWk z?~v!4ES+SAjYc~`Tc*HYE#W^0KjZV;DbqRkCOUtsKG$;@QeBw*)n1>8IR&R+yt3)v%fG4mV!$^`TaPH>mhpNPL7$oZzCWFOc# zd@r*;yvyrfb3+`nKKxHF0#wUVnf&SRjEDW3PD=PsKVpAo%Eap^d*yR3Wl|NDKkw8G z7+;yk%vZBV8R4e1F%tac68`g0ms4;$^%hhAWW9{A#hWo86GG=NbweQ>Jo!{){a)ag z)W6*E{qg!DW6-SB62E_>{zXqLhZ}2~nELm78PD%4W0-PK;Lnf9X9gM9gN~gP^L`K6 zL#BBCstItrE?)fkWc`;ryB%8kD>M5in-Wd&(q$7MuM?fW;g1xN#s)3!@_+Pv#6aVoedH%^d<0UXobsKZOu;HpVQqK+H_T>um z!Q_0B?ss>9nw`w^6*j+3K(}ul;UbOc{CV}?4z0iTF!$T4tb-xTG>Yjz1Niz+yChLG z`__5!zYl=q{O_?Fd_Jm^C0eHZ@BNk3zhTYAXvKvGoL^}@l|KVMe=)sxhRL7$U?Uu% zVaMce=bv1#l)1*tM-?25@T&24@Y7k~&zY$I0^$pye^$AOIY0PA8-F=B6r>K&`8&eT zA6@pZ6S4BqgR1>;m-3--(UQ*J1DATpm2DNV{O3IkKZ;TR z4IgESAFTn%PQ5JVm(;(EDn(=#*oVpAah_kTasW>SI)4k3w9x!LLz(C6Z9Hv?1Kt9x zv7+;Lsm=`T@EFbXpHELWaE?CT?WVX1{R@)6dnU7xIa-> zMo(w@b0;p*`TN~zEo|B1$>cAX=g*@#nVUI?&fn|qJb$YLnfXh`qG0H|CXBfs)4nbO zdLE8u?yqH~#KU`)6lVQ5;9N1fy7v}0pza-&zs=*;)^K+?$yE4c9cqyDcptXA_;jxi#(ZBukpD-NI5FE2mVbIF{{2b)yPU6uPNoiG>fdY+Qyd#@2}n`k z?rT4tFyIR}r1R@aOH|Zqh1Z&Cd_M zV}kF_HH05}bp8VSDxtmA^4yY%SO5AOWr_E%vX?1dmu?7K7t{G0dru3!>#M<>-$B-< zxbcP|gkJh1=9lEpe1ti|PmDQRGdh1W1~hP6KULfP%U?+Tdas*>j=vqxc_-8PbGhye zhu+O(@>f322Tf{m;W}#z{P}T`{52Q3L*<7h%>1)Y=R}lXxR)DdP1nB+h3ycfww^hE z_eT^Arxx#E)_*>0BcP=ynAv|&=JhX8d!I!8N1mVHlu(Q;3eIs-s{c{>(;t2qx|b!2 z-lYioMfM+L){Mk|at2B8mqpZnqZLlU%G*aoEsDbPr2btF7>O_58U)Gb>HJ+gR|ruH z&NBH6oTZH~)c1hC3UvNXPb-HWSBgcf`ME6q`Dgs|lcv!5!(sI>KDd&pe^Pr*aAATT z`2LO)zrSStcce=PC_^L^54Fb6=F`{AHat!9fLj zFs$i?_<1R!{@Yxtg>3!QnEJQ!5kKElr3V^A>HMWEG)Fxh47kSibpE>jw82kTjDY3c z`iSdCO=5p#=F$f4%A!Yh(XWMkl;pEd+$7vG1Kh{p4h3KHAO62R(~k%;a;u z&RVFNHk;{B``aX<_NBYIfM`0O)vZ2|w`4hUe{{z5V5m0Q$ka!)KLUo$_ha_&jd#UE zo%9}NKDuE$KY#N$n;WqG6P3?vuQMP|CYq^_I=x5Y4MFNmK8JQX1yv`KCG?Tx^Y-wO zcxk*k99d82Q~O>aEIE5zWMJ^GzaY6^hLyE(M35rvEz=agpJYDs%%vQfXXY{Wu|z`~ z&)TmDx}E8K?mJKq>n-jw`5dvp1TR>n1q&X~`FyL=0g3fBOg=qkn_!D&S}-zO;PWcs zPhWmjM8hZj5V7)^r3Xy#m3S@Kn@{Jn?z0wp{IUd>ZVUgMhQP(lQ4(rUze{6hChE+ zFz4T-TqD3}#U^I|F!xzJ1VMmk;8%M8!nCOvd9BLeoIBo7`7~?E0N5GE^eM9f|xVme3 z-T@av9x?fR`r8=eKD{7+8lBH>LzR%l*JcsRzfN>8!9MeP!TXhTKL5PcLU-(Cxgq!I z^Qq1&Oz>y7Uf>q=Tm1Kve14j5jt;-!`=4{@e9qn6z&$E2VCv)76Eo44v3&p2SLk1m z^D{b5OW@>KOD2D5(LSiR!bA!F$o$lQ-CAfmjF|InnRbb&ta2+iF^H~@SId21x9n6V ze{p`bg9_>3dGWn6DAc{^6q;+IViC4sLBtk+^;Y=qvI3$kIY6 zvq@n3*B@uKu(x_UcRhg4-<`?juxxy$=(gWKeU;qr^1Q5ti*?(%-@EDj8Ob())~oZP z6M6LdF}R4IkAJ5Gku&N1MUL)(O`~s%EPvAbhf8i5V}t*cAhRExzXjcukWuei5zD{6 zR5HQSb(P^!Pda~htF=%J{wZRe4?S_130^iz8QhKN{DsdmM~>yV)FOSHyFllpUUK~->C?AbAB#!{(C8(-&po^Va|7J{3u3& z5B4+lFRIUB*rw~voL`$U{S^E@9n93X&?s#jZP&udDil-sT2x#Jcem|h>f44zTG)Pl z6W5cY^VRHM4i>FRO#fLFqJ>*eG;zNt()ltjtA`Z}vqi2O>3mfu8RHudWgy<1&ezsa z9U%QIU&QK9?29tSy-Q_aYuzQWzFZ{yr;(--TH^Uo)LoNaA3nHXjCJ0~fYr(8;^*6t z*8kCUo>5UOT^B|SfTE%jB;*D=By0noDtBkzxB>srq`mQ}da$>I?vOO{V6fXv9Srn6{BoGJj6gxAJcJ;7*?f)cLd;LnjpR z^oxSN?G@xRnhpiPs&x%DpV>RW2_5P1m3eURx{N=ezw~{8!7sZ6s=jqMH$*)qK43h$ zk@+*7S_h72Zl~&7*9C^CSMdYpo(Y*h&0Tyx`e_fmoZk& zU=unerp?DVjB!Q&qkb}7v&sA=+p0tBwHL+q_GJDlBVEy#Ek7ABm&{*4XCt^6J{Hr? zKRrI+ik@Ej$v7>Q^LJHH|Gi%22CtR0iYw-j{bjg&BV*q;n_A!b`TE1mqRv!(8?zt~ zWbM|X>RYZ!B>WR(!Gzo*^QXQk6sT((QT-*Hl?Bgb4QD1FCG%JLE&}|TVNKPyT_bnG z{eFX)>%lu@`LvQ?zuvUb@nHKpS1O+gy#E~g&y(7}NV$;#(oc?{^7)`cKB%;qOs((i zD;&{{x@QXf?Go^pHnsr#YrlXxA2a#ABl^?vIinm*=1=uA2CmX@YW||zY=DMYS1||P z>&xDMVgB;>WF6R7zL7egrloF(`iZI-vojOq&kO3il&(@R8K#S~4w3cGtkngzYnC#e zg=GHpW;BCsKKrTu^1hBMiZX0ue$FEEr)Q-OvzyLQ_3!KmS7b4>k(qBv=5NVAL)g&% zx|mkq9UA9~4Cgm82bx-Be}5r=c_D5v6TKJH`hzyrQbx5pMbx%mR+z6$i1CNRYTGfb z#`5}3=r8v_3jpU*x`;mwDU!Y4!uT$f#NyqsQUNyrUA;lAYqb1$^0$P zZvef=BvSS7X`Kt&*KnITyN%3W==x^RcrHU6WXQ_?{|Wb3b|`m2>-f8GeY?u}J0gi=^mx>H;tcfziN7iQM>U##*ff{9nz0eClP_fu*s*)cSDTAp^7__XN{2kj&?>ss@l698K*{42tLH*NZPQQ~bz$ ziun5Q>hi5re|kOE1)VOu$Ru1ZmhmOzGuvAos^Z<${L`q=1tq+@$apW6^Z8j&AFA0H zK`ysIe7GZ-&&(nhH1E?zCfZESCnxZyTNB*irJO3NKTUL&GHJ8JsP*BXMt@l8`$+sa zP0pt<|2#h<5Ul?7UPQY;@ARlhcxJRRQ}v0=XZ*(yFuk@(M7uvPh0i}bZ8m1wjV1Fb z{TBgtXLX?Z(~gtl!TDTus{aHlB(V1e#N^t``Qv~he^)mrfdpkODt|wlGr;V#Ce(bi z!*2()2^KIdL+WJvvw+}!5-UC*P1JLs>St4XM^xccpulIcz`q)27Xa(W1H`obb^{z8 z(Wg}fOyf;5pC->RzrScGmCq{!43LA_US{ohGM^26elvK*B=MLuaz1)|z5%lI-OD6> z^e6gP_3{Sr%5;%XAa_Gbz#qjd)ndSU8jUywB@r{FFQ@p9c=RpqZ*?nT*b4K7XaU!N0@Ki)sCR zE&T@OTm4K?a?kcMeGvNBs1kqJAiXL!^q2FgB*;fix&?yNFLy<>`(@88i-hUlKZw0G zZ_4#cFke&X7z&hJq$1jWcG0*jxaVLGW_c)?&s%1ZAlBlmh<1O%cAIM0ejvl#9n$#U z?<@M(y=&q@?J^~5e_x}&1U?(;%0#?KkUcNtxAs~RnBGs7ny=3N$M-i5_oVX6{wuc~5zPJKyXD(%SpUd^uqAqTvv`nto+0L|^Pof(`><~Oym0W@Vz z6w}TJZ}{bmw72YMN*i{__!s6sT05IT%efG$|NYq01s%@c&wv?neh&%!ukm1Yczx=6 zv9|{~{~7Awg2qVpGc#-N%YI*|ufEns&{#cPOuJub>nInr=;3}wFR@wne6c`ZpYr;e z@$iV4)?a*ZM9PR-hf(_*F?amo`SEAOtt-gPqwRyXU(^;2-Z*e$URBr|;dPSIcdQXi%1#xnE$$^5!@ zmV$;gKpeiFtiMw(@biUxw=;$%WPYVvn!$lCepLOPA#q0cv$r$rJCpepjZue}MT@BV zo7~O??Y_O8`It%O_r9JHy!mmx_{t;le83AW7Zm?;JJUl<=GU>%4K7UGCH6@t*RNk{ z8kkNCT}2iT$@=SB>JPVG&JjnBAoFY9FAy|cJ|d#+mt2}23H9yD#CgtSe#4SN!R9@M zRDSoQW%2(0r8xH)S$}^AMS_Fdv52-mwsLwkj2WiG)NUg4yL3rB@M*3T(e7Wkcd`uP z;x0@$BJ+ElO9EQryCT~C3}=33fJK*IiD>&Ji%lKS)Fn~OvBNb)epgS<2cMIFi)j4D z+d7~p;ZX|wZWQ?Eh6M%SvSUYTeH*>l0rhBzV(LX?eqZZxK&8C~Rew9?>LWG1d5rWv zncvEsIzF>OwwuS?(jfDz{HXzeP&=yrPK$L$lCv>PL%f{dtAhES@Z4sw z=9MQ^fAJ<~^_s>9eXlgT#nm=h(J0soqF^tw!Ilr$3_3d+SBj|l8 zSp3F>T;E>$?2N2bVwrEMWPTG*xZp46@Vc+??trzADo8+^4cHBaGG+yT?F~E>n9A3b^9lx&F>XX)kjZvjAX+0 zllitPuLG+#bf%vFDvr@d$yY}*Tb}sI^3wk=#`G%U|&WOvK%al)%^F3C; z_YePOkUiOonqSrT;phK1%w>Y&hQ+wfmFU1uXILN9`V2b^PcR_FXY=} zk`X-DeVo|Vi_G_R))}4jn#VL${EdkY?-togN3MB6Vp zJU0ve;!cPkej@AltUnQ8&humuZ9mVGcGXZ^Eft^nB_-C+UAD)AwAUFT+Wntzdz8U| zzciDbT2FC~E`J@Tmf4fy=)@y?S}zKze>qy651=`gjLsNc7ld@#YOOhntSb@r@1 za^jz-@m)Hz0MwOS6VdihZvJMEz-GYweO%4_FP|3j-K7Tyip?L0X!G;wCi0q&MSJ+)bw6_n@MFyJ|?8RKKTQ zwEoi8?f!6W>`*c8OxEv%qCgOJWdhZoclic)!G`^oiNc)!xC_34QEjwkaSb+8UR2)!txonKS^r-zPcX)q^-lKGDP-2h%syd$FJV>c?CP>+RX z%%E@SGW`?kw|;grP#W}JM9a5NR5_t(OU;->BQoEoW~##jdF{pPCXw^8?~k33Pplc^ zIF!tH+zKPOF-TL~WiDC2Z5~iTzKK`L-S$ z3cP3aqvqe-^DNk3HAt*Bi_CX`VI;Wh$B1bAy?hr{!)rb}#f{tKd<*llQ>Wv>8UK+Y z+Wkw-vFG92+ndFmUu_`z^97Mfpy}oWD&JoWGC}0eAQ5dp%Ek3|XiTRTF}iq_$anSl zeBcdW>rkx9PW#?}*p}VB)z!MB9()b4&_geuO2r1f$b4_+^RtkMBO==T@yw0< z`J&%SOy(sy-$MQV5Y-I8mGdIn{IN}}6LR^k#F*VXC*y0Ez@O^`s>6{}Zir}nw?FBG z25GfpmTSoQekQ2Db;68bWBd0a8sF?KC#31xj;To?^X>e`4c-{3B5t}t=G&^H3ySTb z%sfdZ^L^!qlyU2n;6RYHIiXkP z72>Zu$$X#t#GjvwN)lDgB=@HWdO4vBJu1ZU>14jO7plYKxjCY&AhLd6PIN*!3oFF) zU)`1c`GtIY1R24jC8tGI!^!$ReWw#jUR5Dp=_cpC>O8-_v&b!>7yhsC*~v3IwtJPkGVm@BELE(5CkVQArG$ zZ?~bLV8{IuFIxY4-_tAzl|PC?rjYqwu{sh+W?%B6<>y)n?|JP1>vI#T ze>Vu!LusbLV!c!{|HoS!fKrw-)xSS%bwqQ+){A#elk+e1?*|H+L6>YOqRn^WH;%|S zXuUXQD4GA7W$JKi)l`{-$W6uJ~u(m=**%G;(;w)W%ap`|6h9>87He^&$jy)h4U-7*ZIQ> zv&}_q=lg{I{l(cpaCVG~7w!JzoL`Yp!xV{V_4!Z!{E_R|fnL@d+Vokm|LyZS3pV!% z73D7=^RGTF5{ww@?M1u4d~K&1IC)aG$Z{!}|2%$vMa5>E7p;GGK~f5ztVj~6sgU`< z8khtO?5BIpTut6@81S(aR%axM9_h9c`5&*52`0V`Rp4K^f97?l9ePyJPV5y<_V*`w z{@+xrqw=2-W`_!|wNv1KiJ*SB++P4%r*HD2>HoLOc1Y4mnd9mJd6 z$^1{d&+M z;rZ`u_RWjN|84&JadU46@xfDM{#{$#;P&NRM54E3{f{tmMjE~y#qXYx`QIASz+CHi zY+$H=`~UP$Vf;j?{;EGr_SEyF_0N?f1HoT)D-YUysppkQsPoj_v#q}-Jl|^{8w#$^ zboQY2*Vgj<2ZsiD()b_nDgtDj80bNpf0^^M8lIY%>UnJvng4+Y;(^s7Zx5ROf7((C z*Vx2+I@Yb1{rd>#*KY1k0?xO`deG)y9*B6p!vj5DF>U#p;(k-BA$I6$=y%V}?Z|w; zpOX&;tytz`j8X@~BIefMnBcOl;w=M@0p8{B9c?(^ zEKT&F&96n5>Y@W>k34_QBlEpCv<{q3-06WQx6QvPp3j&3(?zw$k3HvDlKC$B+W@3n z^F3(!oFjjJ<$dQS&$BIQGJU)!$ltpvw}2P;oX6ZHWWFn79Z^D$CeP(B&&r-p7S!*) zsp@b@PL+rC88Y9?PdlP({!N~iU+(<(`-?>Np_7R^9`%(fO^u- zGFtsU>#{CNS^P*ct8u)H58?jsaFGosX;(J0ja5zaFtPKjQK5@dYsI+Gtc*^p;cuxzQa~IBA1=NB^^$Z`98DD2xfL^EZdYt=KEr$ zBO2MQNwU$3%y)lYzum;`B{cosp5TPU27e@Wi^+V4^7Z?k4Gv|r{5^1+Kh(UDAu&`U z_t*0I`hDDk{4!eo{`YSroKtd6fp6jd0F#_hFyHoM8Et;`z{4!~qUEXN#&|N{PA~cU z(`S~H(e(TB&T5!+yC-|8nw-yxdH=3=?_wFvzaN&Cz#*$TvJy=)-~IUd-65r}j8?z5 z7-jP3=buse?)umk-C44n^{To||e6) z+g?FFSJd7e-X0Vuq3QSED1QHh##&Z)0h#aLIgO0(sr6;F`h34XfBtLuJ4xGq5Mh1p z&FAkvMXhDD{5^=z-!FDhXKDF+Z8pEZT)&fq#&__)EI2FQp7q^H=DSkLpO1duRYK!C zp`sd|Q3+%v-O2hrHX$C&xuh+j&8Ii8C9u8wC^q9=9MPW#A58)ePZ&#Re81UI3Zu+? z*hRW6#QOX-fBvMswu6K=|9WGUE%N$a!uHO+MC3nnSw0Zu43NLSr?r*J;W9$k@+uwQwMbW&X>^U zXV#CW%}N zvtPpQ8Y1U^qrkswu2qLk30V?aeSTQe5gmFhVN)QP|7kmo;GAhEB{Y3s(8CewHA>jJ zeq{ci>$$_Py4NIE^sdU@PbHvuKgg*;PH0v?%o>Qu{BQ3mW!|J0l+osAw5Rz)`*0(6 zIw#)`B;@}K!=F#NW+$P|x2JkVLAM+)_R}M|e;4Ze0P9e&b5uVG&A$))n*}RegQ)x; z@`wcg7BCXp`LeuqCGhOzO>FL%YqEbI;rvXm^mveOJ5oZMk2?}n0@a3XVs|CV`QIxz zA3C%o3EZ`tC>hhct^QEFe`HiZDV+Fk6MJlJvy5L(aDVgv_usqx43g0NeYgI$s6zJ- zyIOjY$p8QM-wPvGOKAP~fa$i#d;A|N|8Z^wz*u>Mq;3C#FrU}nW{b9G{b5Zs$^1{$ z;y`%QHVJKh&f`^Y6srD$9bDC0?#~71S7Pqf0Vn@#3GIF^{cgIb-1`OlU6;)N)qzs* zG3N-C|GG2>v`ph4TRK+Gzfk`#CpCk#o9898{dx~m9FVs9KekGR%>S2->hMt74M~^% zWc`18)B(ly`Ns~exlOF!t#gdv2Jw4|{b92HA8d3$`xE}LYOOzs`tSM04MvSqVQKxj zZ~q+8w^SwEy^EZGPEfy3;^*ha?0ZDz|I-nF*u}-0-EBwq_aDOoLCb7E2`!&HI3)`H zSh0`|Zdd;we~SCtad;?rF*ZO#%jfLxWx+2I+gO^v|DzWPO3sEzX!ZN(?IrMS(Gj*s zsGNTw*iV$bFCNTWA0eUTbMN|}3f`N|D$(XnA^^EXcl9Ff`@V;p=#UDlry^1r{Ulrg#6 zUP9CV^@sf7yF4l zT(ILP8yQXZ|C8JzfscL?RsRjmO86^ktJs2Ta(^V$|7CIf{k9c5sQ%yRc`;NUTE+S_ z#mc^4Lj7OG@2|cUyhoyzO771^@$>QXG>=jJ{ik;}X#0$TIJP^P?#~HF-~H}wi=J&8h`+LAzU$j@!1wHJs=vP!-W#RPw8je~$$TeV ztOKXIy{7U#FS$3e3A4u6lgWJhSV}>zcdI0E2bu5izxL?pc`t0$kSgQznSk$!sx83i zTo<-An#_0CPCVZgUU=k2GT$$btHX>6eKzA0S>JyE2eh<<2)9g<^Ia#HuWQ(61V=7% zrt*Dhh6B>F6ye!p$$ana=nfZm8qUTk%imw2zaMi(%2b=`OKA5yn7#CeKSDOMZTqW* z{=Mr`{`}g9G^&2zS|0`34f|Qk0c8EonG^~V`|p;}`s+2nvtZ{1*Qow|o@OLic;bM9 zehcU4<`on}r!gN{e@pq_U#Q<>l6n1ZJw^5Ja}O88#=#%iXA&~MK0A_t*QoPU{oZ4h z3Bs%^CHYq5{#sz74O*u@8E5~xAg}KQ`Fmt=KHzfiQTbKfX@gelPgdY}te`&6O)LP| z?X@I*uKf3f{v2PnL6;^?#yN3hepUJXF2{2INZRuEXrQa@qGA0LA;0vYYME^i|U_+m+1kzC%Xv zPJ<5{e37ir<>n6P^O5PeeJ3)%9_H@wVb?`$*S_-iSIDn=Cn+=VT_39chQ0NNcMbQl zqRnLgZGIpSOqh2}LYt4t92x~{^jOyCH@W_H_`!|6TWu&o!#`di4K zFQ3)1Ttb_V%S|bU-HX+5(I0t#aj(FCuM3O^#-Y^`+Wy{}ImNJihZ;V=g3NEpz9e9I z`W`iZ(?^*=^y`hpcCwrw;rvU(U>j7tXDz`_^LwGL8H9w1sQjws+M}A? z>+l07GQW{2>d=DmrTS~7YI~IbcpXlCcuS`LLjA2zH-g(cgtD~y+FWXn%9WzA@3|kc z=Y{_IV|RDBdih3{mam;WDrFqM45sSup@05x%-xf$;Sn;wjy{24c~hB$mY;JGQLy9V zI;#HGg@l6XC$3QI=Yy}ZV9f4+RR8R*9trkm)>HNON^CKIeoY52e=X-%=%2SA=KJ5z zpGj!vQ|w)fq4b$HekvmKdxqcd^7`@zs{USd$pkN_E3vfsmNi;7$Y9|n{QFQjQGeg? z`&~*_sOj?32bPwP7k286uIyWl*Z&yZ;HP? zs?gYi-!3Hc`}a{Za8nt}()!=~X4@k#gDv>TuQT%B7wGSllj`ud&V2UFU$TF`lw^+< zGF$NS3^KndSw_&{NG#Pque@fDhArlw-y!EWSx_HuaCC<=8q(QuBgy)EQ@fFg{5?ZL zyT5nY3xBvP_cB#~?+y(FG23oa`F#);1!L6SQ~B+%D zu7PzolJz&*JQBD$<#{FzxeO_R*$?E@GTWcOuapksZuVC_6Ip8W>c^*`vpLIrzz7GM{JXwtz8N!L0ocvOhj% zW{`{57SA0Jp^ zkCx5L!BQ(SpA%f&VaMRZ?DC0ZKHuDvGXCdQN@(Z9w)6W*os1u{ZTm@u_3aPKKoGg~ z9koC8eMuBdcTmQ(`Zkd7PdAu0QTYrt%!a?V8snp1$$Tm`M1ajjp#tgY-{eyVY`j zmk9LrWwJUfNlIn|Z;ob0S)a`63)gN!Imoj7jtf%t3uZ}f1|WtdUbjF&?}Q z6Zt(dB_HgHA4t{TZOPUs>RB3VB*9DRDNTZ>!98i2l0%#WPax^kb=^WQB-~(9I`{n!^-f9 zuiIts|7$_Myw;-yJlej6ZK@~pt9jTC)$z}_^CR;ccS#+7E6ipsJ<0kjeP)Nm@nu-G zpVXVfAWJJ@=YtlkJroj-6-(KpL@H*Y}ZQGnIY@1 zv_m7)AEr?K@jl)kS1xXc+xGVh_4mT!K)`S4U}^K82?deRZL%&7Uo6k308s1?e_Iv` zOnddB@~hP@8?FxU!dca1em6Qsf==)CS=#xnBUVLlO6xQ{vH8+}`l-mTV|F}fOtPfv zZ)e{kc(~7WJaRIb-?SA;;8e2{OWTh&sC_2Td*a2?=07g!Sfj%J*Ra(qR>to$psk=U zn}_6s4|7LQ_4jmNYXm1>qw;H!%I8xKld1Z9Cd3+j&bfw%rjq$xd{i+q*>@ zl{`L+y%v-CMF;r%6=R}UTK{+G5FK>i{Tx2jpUm%%@%;UYJrh}4|98&}JG9ce27hA7 z`~ve9&@Lc@4XhyZJ88KcnhI*LzZIF^&=PehYCgiMIgt7F=J~gXslh5o$o#4vGlIW2 zbL_|uWdAHWXNQWDYj7AM^LxFoJIt+p#Fi{3^ShS6e`oA1=NEP}U|hTv3tGQaWs{Zy&{JgNM? z_?rQyza2s4msPe#N_zM3+H+)nCkNz%zFCu5T-@frRTTIh(ajpYvAIX(*C43?aJ~x^ z_!aI)y2tZBYw|r@8cgQ5-3<()%fhMrcD|vFHub5%UgOF9ifik@-`gA6rD|>YlH&QR zgrC~z!>kId*)T?4KMUqJ;`sS(=Y{E1ej6=#ek~v289T}Rj!|y`p6q`1+G#Ssk+ybd zw*4c#ukp0(_X7m}IaHz!-6Ta+{jCbIL)+pW;jl$yes}Wq?|_!;tfMwrf3qgoq1?HT z@Tbaevfmf#Z(KKbn9=hCRevM;HZbKa2PCxflRh>6(DA7jrq#c}Hi6)wfhkMNmrwVN zg3isZ3jR4-!0+?fq2Tg3JF5P=AIXAcrIT^9Cz;>Pha!MG(~s((J)fL|ThiBImAzzs zwYYd-@rz;4?`!*hDBkZ_tX%|cr0eivGcv!aYm>nE;t^E;T&p$rh}A|GzBlpb!(@J!{eOO? zlS}o_7O!m)Zheo3gp&E~Jg5a^vjx=r%B0m6ebxJb*OZg_W%sJX=C_xq{apu3J9K>f z2kdSt=a&=YSN(1pK^?EBY*&WN@8w~3Xu$dpcr-`mH_FBx=AZpX)!!%l-FNF+3M91i z6}R~PM#HR)Fzx=1`5gnnP%S%_HebEeA_}4(o;b0yy#5vPduIpV-|g0qrOj8R^vZ@; zch18xYWHRSH=0r0PdF+!0^FJ@rt*7$I|o0$jK}N3$^4>a@nEO#2x|R1*1ZVM7bW1- zk#c^4V7@viEeV(po50fMtGln&MwXW!yp;xk~`fRvC8_m7*7{`W^`Sub^!9v|5RDJ%PZi_BI zYQjtUk@?;>wFSi7JkL(m#8LUKC3*mMMKda?CdV*J6cd5Pvz$~?y0F@n!h#>Ntwuz5(({m zq&oJ84o0?AeLfu;2zG0@v$XjQv&T^|XZ~=!w2{pBN#9WL#|2RJd0cB295*NocYR0J z=L3Zi0EdsH=F^g&=U~CuWPIa}oNwX$Rr=<504GhN*2ld+6~VGzDR_yQyuT#m`x@V0 zGEte!(#}8cw9f>$9ad5E=|2Ol(D;YS+>`BPM159q%?A$R^;CWhW?7-Tf0Vhl`Dmd& zfAA>)LFHSi{iV`PR_MEKdv1TzRpx*5(ZYOs^CJv8xnxlJee9x*-o(Gh4;r;)@2^mw zZ)es4#|a0h{U!Us+Q>8iJs#jd=6A;&DOmOFEZg0hoKHVoWQ!Ke=*Xq$k@>A2*8(md zxk}~t$Xxz>%A}5*otVt8IaY`NQlGNZCzI>r&;zz;Z(>JIyobzh<|iXqY}vv(#>w>= z2=Xnh{kG`prjFc_pI>GFenNiNdAY;EGc_>WORkSE{A^@g;;%_|m3I2?`=lTrN_kKH z;jt%uaO*Yl{06HL2#hTO)nCsz8U+WJ`Qf`oa(;#Rw8Qrh(Cr>yKh7ife~0t?$xd~P z#j_=3ey=u0fNRV|w(b0raDTxzSOm2zcj1(=&@zi0LHL3mLjOFQ2*vzrxq z;nn}K&pJ+;4d)yWq5URLL#H01n_71YPS%GKfY$?w@U^U3^Hth7Z;yRO{S#bkbO zG#NoOsv{1`A@j>7*dj-bu3Z27WPZPTyF-t>-Z-IH&My$0Z(KiH%5?5jPo2N&b%S)eJjcQT5pR7L%J_zY5Paa<|TmvSE8u(?>m0K$gliORDJDS zWQp!h=)wJTCG!dS^M|!dQ(4-6?-P}lsMGu&R6bRr3cyR994epsuPxD~82{;XP5LeV|?x%q*66zObTyHZ&WRf=`B% z>t6@{{<|@c7gP21nMDos-Ol2Zrmz01KNb5&W^3cY@9HS3zV_kI5C2w4U_ZsS>A&Ln z;SKLHz=Sy|RQ>FnVaeZ*s>`WO@Yr#$N{QN(p!E;LHcr%*rHTNs$EDWv98N@-ds>S|}MTNIg3tCTuW z`lEuXpD)g9p}8MAbNdgH`HZlYg1tI-sQDCEWP@U&3^@ONWIk8%{h=j8-?J4R$@Obj z{`p6d2Hd9OWInsG>hN$;dz`+Cte+12_aUXwfYW<-L&mqTeqH>?2-b#cVw(Rw)zcOo zylKFdk0bNBM%x{B_+yJ(6Uh2`Ra?sJQ+-3_vp=6N=LL+#S+~f14vY-|tpPLHyH@h| zS9t#K&Z8(8p}QJ)>2*uShfqIXbPokFk&CE&X1Zm=lMOquPaK)gWr-2ME_$s({VMdo zMFur6sm~QEpN(_l!6JhVEbaX7ci%Gj=Ephg>XPsu--`aXXg+_x?4vEz`KnJtc)o_1 za2Fbm$euTWiushml??Fk;ZExOWXCar z`7Q`80KX+CsQSBWmn8z}CfxhUWWLumV=($g8QUwe?farQKl$8G3yr(4!Hx4J^WDPV zuaWt+n*C)!?jM~C(?VVTXmD2p$b4U5`18LnpHlVr?P44B(9fL9T}tNL&b9?)s{W$Z zw|BPMpqi!ToXb`+-+`Pu+PZmdN#2 zIKOfJ6aRgxGv`tqO+3qftUnL(cr1V{fdq0rOZ~9;<@cs6dTHj6_WP<|w+H+nL$o#HvZ3Z{u z+F{!Kb7vnLG*D#Ez2tq&|MEGZe=aUihjSNeQ1w}Jkqs)HX3uS(L*_T8n=yRV(;Pd0 zCiCli#s;b9+jB9mzQ}%G$nVD)?$A`?fmd}U^ZUKT23=-xRSY92p8<@@8Y2#|1i6Ww2{*1%-;0ad^ACdGr{4%?~vy=OrZxXNZy`$t>% z8K5yQthoE#a%B7i!G4|v{Cw7(o(HM*v2lY13OMM@Ezu zI#c-`F`d6ZqXAR(dAgA$n()$@tM5$ayWf2b42IRRy7S3=*L>GR-X%sH(kAmgbwwR$ z`0$MCzZ2E9Q1neB?tPPw?EMCU{HkG?6x1pGWSvKn^DA3b8}#~bAI`;v%=avQKi{^a zD)^Tb*?)iQZiAdv`f`h`3t6hAK^>-X<*@nFHYT~xjoMf2zP19RCuKJxkl0LA)w z@8b**{_8k(zQgpG1!8Zzb5R?MiTa#mpAYIHN~!tQ`Em<%^n*KL&j@!8{Sg& zdBr_Vq%+!*+joV`?-71~uC0R-rt#bFhBaC?&VzI6O6IrxRx{Y+)fLn7Er-YaeCrGk zF6{3q`S(M>?<;jtX-KG0_!+z*L%b7*r2Fp1kr-JFRw~~zb{q~~{v9$Xq?|#hyqyL?y>hHZ(7U=IM zF?UXt%nK0+ru)D=bjfd$9t)8iM@mrAGm{_M?uIta)V~kI&Acq+k$1YoxLiadYk@%lHxYkA`Tq0L}Vdcw2w6{w8giMOeJ{D+zd}|m7ewYeHdYFL1$4owMP$C4$6KTPE5o@BWpciM z3;M&gDlOn$ye^e*_nFpc>Yd^IzaN=z+iZ1sUCW-De>HEhM!{W2aB<0UzE27AuZ}B? z;e-ni*WV@c9dW=K={bzx=A8K~`#uE-@~`?~?(ocj>G-@QS)bkSS)&g@Be-`QneQ;E zlnJ-iVcX_2h5GzC#UJ)biKq6bmR=12(zIl%zb^g|1+Rtf#p|Nwd<*mMu!<0%e`Xgo z|1PV_f=8cJ;Pbu7d`EdifMzzAnt$7*R>SX0lsNsumqdMDz}L^aJ0GL+ed29zbo?U2 zr5)Xy^tXuCtY#eF{>>rdwYy0#R&$k(9y z^AQ@>C@pLp_d12l|E6orKzX$>ruDae_OV7^bH{ODjhufMfj_^L$L|k#mH@$oyx<8N)>zhT}6z^7#f~eLZ}RHOhNBj_a_1%zqCjcWC}}E;T>%-fNAH z+KuN_bIAPv9NNe{UT46Tt&-Q*LjIq#{;*&FL^RnT-w2aa~XMRMPG;CZls zT3?$iP6BSD%Gjav$@MjpVUDhL_Tya6ACiAx1bo*Y%>euBE2;Xv51XTfUVdD^eq_Ek zYVr3|rQc_RUz5*A4S#5k>;wF$e5dhsWkU07h4ab6^HBr3TcB}ye%zlxGT-bx3@o#o zseDiQ+6(o#&Tt=>k@-HnrVdoxRmJTFllk^j)kNWM8BU`;neP{T|Jri979O{ltnYj8 zS)n4)B<^J>neT6%TY!$TCB~D;{{8taEA({0B+l2C%r}$9_qT5Kr{-rPjIEJo#w6~Q zEt&5xM~va~*s*x|crxF51Fg}@(n;JSPcq*FHQnK>h!E`hL*Bm@_O}MEvPPFXPv$B% zkomqfpphvQn^F0G9N-T#4U_S7Ozv;jdIo^u*_rI8A@cWM*x&wqB?^9eaum;8Mb`It zJ^udL*LhUF`@PJ9%Drz={d?~f5r9cJPWA7m!PW5Kb~Uadi>&Yc4dQ{WZZY-z#n6HL z{;j49RQ(=M%jajYH>vu3FVh@tXqd|BHJ&Bv^J3e4@Q1H|b$hqv&x-x6A6e$8edAOG zew76E_eqxmu=?Q_mcerVh51=iy*V;;nZ~Uak@<~XgModFGN$bp7|r!U-S!RP=J}EN zJtnFH8`!RxcD`}stzPIs*$}Q<{V16~73SZnEe)Xlj~-Q@hooB}_W4Y1_+T=>ecv^M zF`ewO^)NEO?xj{}aIXMPSC7o^uM6t1;fWZh{v+$NEC2ln^9J&J3ga^Ee}G#AXC=*(1pOUQv6=m}c0pc5y0l zeG%l}pT_&civH;e{0jBCa&7?7678kVk1fRf`KdnzRDYhbHU#tHkW zsrgw{G@pNSXB7I^LVcd9#NQwLq8mr+Uytt<4{~?2RDO^9B!MNJE2;VS`vVyusro)O z|9&#U9GQ-q&3R~(`Asm&2e*sgQ28A;%^Z!LGn>kwIm*C)*!>7Jg=z1Jf1 zJD?PUgZ?U5?O@yYLvg;O)An9y)+!(F{Qxq*7Gvtb&3iqm{#xfyFVty=57+M)ncu!6 zrJ%Ohgj!!$Ot(Un$wAz8Gcv!&9yEg~nyyrScPz6)g~x+9<>x15{0aTF>UREqi3Q%c zVP~SEax2_=T@4#&VV8F9{YJENW zTog>!D#p7vk@YvohtI!NPEzNy*VSaf-(Q~L`*XsPmsHe{|7&Je}**L4_mL*SE(ffzK*8sQx?eUIysK*RNmp%k@#X ze{YesInw#KkaMpoB@B2aI<}Xx#y~@fQ6~A9do>`nTH>DLyOG!Y}Yz)?xqf=&5vzb(+jPi z@5gnEBlEpST?%5gtZ-lq*EPyjaba>Juc_l zL{L93<@a|T=r@X*k2675=)tjRM3oT%$a1o=){66{600#B5r`E?o zpDod$MPb~u=i6kzFU-Gnem8?>$|9V&ne4AM-&msBz%Xvp3NpVn=hR{E+v9PS;RV_I zDcmow?qP+>?}u?FlgRu&d}a*Y2QJ1xevtW1n!%q>?Y@e;>__G|m%rcjcS{1!(3R)k z(Tw8#ZzFjA4acwItiO}_HDA!kXgwW3ogeFB;t%7bd00|N=J)rd0I+b`DQbUfPx%)XS$ukr0Hcw6riHq9jSTjm@A?#;NQP#+8DLsj_uA5~r&aJQF` z=S!Ao#q;`pgR0N1oG$7!KA3y1e_yEI_<hUjOyz&qwJd15`6reCLW2nKDW*z+ zf1y7&Q>%g9I-7AvKa=^N&?O!m*1AXK-*&4WD)_mabEqNv^FzEpUu@LK?%XZU2Zi%z z^McIKBim^1>v%H%KE)ZpMB^9LzegsTA@3p4oLK;w|6P3l%WZlGOv~45GtH3S_-HEs zAw3H~-?v?<{I@@3#?L=Tb06c${I5yF;Ge%PZkrz$-Y>JhxF=e>FNiZKB=djLw+<+6 zu)--(Wc@d5=!sGrgE*I#kuv=j=4&m-8-Pu@8#P}$8fl4|cgAv0v*r9NA$^4b>4cTd zAauU?SCMoUz-Hmiv3XRDYgGKuUizqQNxR$K{e`~|Rzuq^f=cn_^tD)vfD{g5Png1ag@xWxv6Ken4ZekL+ zbM76>6qEUG49oyucePUcTkXf0A>E5{T%TK~iT?eUaz60xuZk}XZS&8H`FN9$8Oke< zQ{eX*&{24Q{}i7BDrb6N+WxTmNHa9+bsT57gv@WvFbu9n8dB@;u^W0KgKr_+u5>cL zDsFY)x2rww8cgQ*?!lf&#XgjqaEZ*X^P>h}Y2b;MrjqM#$3eXRwu-P%~3HL_c!m~%n&sPJ%e!%%IAz-L(6_wxg zn^|!C4rNZ|E}37wpW$Ho!n;)cjyhZo`;M`v=Hs2rM_>LCLr(De34}9Nr!L;+4txcw= zbXEeD@8|bUfi*_jxUK&s>|YN@W~kks1kTil%y*CB7!0;Cqx$oE;-08^(+bXS0h#ZR zj&&f+z=i71D^~VI+ZtDJuQSMeN0&B$_nQGVUrX(1iAvvZ;wJi&`R=&58JrvKN6pWl zsavADuba55H&4j)QA3cgWo%G~&;Kr>^8Ht2i7x7I=58(}^WBZ_U;D0%$NsO$^||#- zOSG{6X3lvKneT1e++pmN4E$}FoNrF3q&s5o`Yn4-uh<)STW%pRi9r@PXd!mo7in1$ohP9W>0jaI-Kht zvF$&9qj>(>F(?D%`E|my{rUYXOi`F_A~$0VneQ*5`$0`*cTBrq>d+%oG|V}X%D3V9 zQ^0eg9yNbU)i6UhrY3UOmCW}GUcU|Nt*H6iZHu00RZuv$e+HTF4jt-%j-wkje`7p* zqIX-vIlsANzDMn90PBByE97rVK=J;IQ&koy`pj1DQC~9O4Og4Ntl}xyzl@x}+1}^p zhw)Z!&j~W$zxey%a$YXS?Y+qQJx$dTCBE9q4H!)3yQ$0=E}pX)-!_u#w{ZR}$J7$J zwQl8>v?udj%eljGW;wXy5i;KsMp~l3CP`eR3x)60mrTd(3GC_{DXXH^-yZFvpzfUKxN*GPe+&7(93BG9yWOSEr+hh<1&jWuajqO$zg4Tl0Xp75 z<-0kq8s6^W#yM^x^ZliD0~qn`3pGD4u+u^&4RKt{w{|l9)P<7}Lv6iaud0#D1LQM*%>q+K+eXTL%{E`&>yO95Lk1deq z`4q1B{0Eu85c>C>CGId}(>`o{j?Di-TT9gWZwfcwl*~U9)X4muGnG2ua%q_#)RdM} z`DZ2v07-`%)cpPW=13T9_)1}asIdOt;TQrc^Bz(4{nz;{s8ZFHTl0g=zk7W+82$SH z=sN4Ds+#YO6G}@f+@i$+ve)gU{@2T@GmQ%~&%Ui>+&rCA^ofLO~_B}tS z{(bU?DDZTXGDADxsp`x1zdv+gX#MZ#Dds4|cOO2n`V7&Z?}|u>K$J=AG^2tKSz=GXq^YjDxYg(><-uD_e-SfP>97`&xv zcgOdipPyZlwu3bPrPTUcI?f86>>Yz=jw18BXQ~!Fy*rTc`b?g0(M+^Ld$+{kymz-c zK0le4pEsT~h1U)CF)a_;eYRsQ~6DLYK5B4#^93ADjofA ze*HcB={xE3VG9dwXQ==6mvZrpg0qhsTz2(3b-u-T+kEhL{zIyMKU%#N*4+HSxIFvo z&!zJBFMD2eMA65=W&mM*Ub0qV7y(ttJ zo%>DY*Wz~+aI8>aX#34X771XKwH`y;&mEv^j-I`b!O2fg6Z!qVCkDSM2} z(W=ieRDSa~{ax3$2UGiZK9%49N^&(vHa%nUg{x$KPmE&#+%t&zb^D+G%g?8c3eZD0 zHihBuKMiF3@b>S=^yTJPz!>JF-2JTb_h&RF>7j9Z!*IW6lVtkC+plmw>NRK>HJu4Q zM&?(=#tJRJ6^~<|lKIt7Xa`^Ru3|oxll3>q%nFsV@i?f5j9&#_eO)|V3x2p6Ox52Z z3$0Mu?|A(9BAMT;G*dV^Cx$T^PUg3A33q-+DFN?-GJgB<^0S9|_AuQlgE{+-tiN5e zt&qdm1RVNU#_u{_e)jv_TdB>%rPTU*#xge;99~A{cbe0DV87-mwZ1M|>JO*Id|}R( zlJB>gH+wZ`dRSY?j+EtZ04T}5K(6jO2%n!d#FaP5`fKgt2b4{ksQGuXK{=fB4B_WC zWPVllg@QF*l^ELnI7@AIgRWyW7+QVZvp^38{SL?Q&hEeOKY4%MW|#nM(+uVK4g~V| zONwusp<8YVIA}DPZ=0iO;K>nFhPJ;ju)z#ftx2Hr{c7zQaQ#VdIeq5mXO=qVsBljL zPDzmQ9mwl%k9l7R6psw0=HuBOdgy#=I6m`{%=gF-l|YXR*=hPbd5azrUkS(Fg=D^6 zeP4rROJ`I0PHMD7$T11)Tq5&*WlTHhqPl@P--6y*B9}2q_}H&3+53sdcfvyM{&meT zYJIK3y&sTY5{~vG^WA*W6dqWez{IU1^WE%fg-&E9;o%NszNeMhL!$+!nGr^1f4^Vy z^DRhr*LoWHg*#w};ae52ET;H`6e;ob%R-Ve%hzreHiWpMb+ z@pzg#neXDtP+;iUnLD5R?|J$Aa}GX?0;=484%+#yxOEA@bf+=1`4PE3{*Yyc9zRLK zr&P%NZrGFtRFEZAp9dD1p*^3HsQktZI0L4hwPpU@@66}7xzP;S3J>A05oCV%KQ08# z-yNv@uC>rZd6%N_fl@NRN$)Fx=l=hgL);nr|M_W zCQB5jm5ftollgsrlj~1gA7TXQWPXo#wL%yBBxB#7A3EM2e0|=YY7ecJpJ(oUCF`@< za4R&zDH-34A@e)A&pYYyjT@->*w2}6uxaZ9D!)!~^FishcZGd!%D(^n`4lG?f4FV_ zFGlB`OrQDrSifeD-$!4m_vcK^J_t*?i*W*c(((P^-=8Cl^8;%yD=`1~<>%jzYRaH4 zaKs5BGQVH0h64W#H7dV<`t1f^4E31j7P8-uKYvoyO%Hvx*^3i@NBw>O$?NmS?g`+X zvY6W68nVRQs+-JyXc`FR$P9wgv|HO z`LBUSx24qcA$s1H$SO1y8*}%7{_p+4=X;83J7_q)mHFaB_TQo)OVl$u6{}w%^W7h6 zLGP$2rnWCR|JEtAMD3-iSk0EqcTNene?jvo<9?OQcYn@bD7UBL#Ajr_ho7>C3twKM z>hm=f?)49xqj|8(UQCWEgg^H z`ivxg!)CXGW*EenHd6TIo*&6Q-*$k^@7dv6(7<{x)n8i%TcTtp9b5k{@A!Ov{xzC4 zg(>F8n3hU1ziU}bwD3C$QVkRzGj!fTwro}|NEDhsHEx(MgTVXRB$+jI155N@=d%J(u=OXS#c3J)1V=KJS^ zHZZt4gsRUM1eR!>Mg|VsLgrgAO$#pdJ-|eVk@fi^v_z8!W#I1DWPHc-^6guSW^j?t zNoK@M+5Q8-yZ>tFVN0YJlYyTkk@;S8*dDfB#LUqVZD6w1Qlwp(fsQl<;qV5@BMD@cf%WI#30%JQU3XB@r`-FTcw%WpL%n`AAWzOihYt~ zeDlwDDV$jaHojM6X!lp1pKuWFyl+jNFT3FA2lic7m-FBJ`S7xFWiZ%m7T>%(vf- zP|&_ypQ(I8<~wRT*MH6sGPL{aYOb0hn|>KM(=Dyz@0ZLw|8Z9}0i^u2rt-Vdt7U#EKJV0~Mm`ZC%46~De7>Fp2m zGBmJgyNqvs|GB!yYLL~~iP1^?$CrHmy&&-*Ov&qwFGZ2->nE%IfKsj&vn1)?^YZyv z#Jn>2?d4p&xtz>*Y(^*;y1Xk@zoW~eK*e|yruMGv_v6>s569`E+>eKFs(`HDmpQ(t zhWDoSr(5=#qAf?Vv05UT?=eH+S_T2*<8+{Vo3ajs;e_NObcM&Xkh*wmMJ=9(G;InCJe}fBF1u zn~N@*-FgV)+Y>v!-~96(D~w))6AS&Qd@oC|K#d>I;%DtqM1S5drws^W!m0W9YwmpA z5 z0rTg9?0yQ&`dZodpU?O6Oh5SAu?yaOnVg@kS-1+sZBS)s`%6U}-xWc&xKAdT?}ur= zz-*Zg)t~1|%3#TkMO6Kk9ts6ax-pgS&QGI2d6hXcMD5@EL*Ab+uZjm+Cbrak?8S0Z z)YthOR&gQoJHROogw+nG&W9=ao1(BK=cxRSc0B`FrwP>l^zoynXh-xpyzw!a--MV# zzzm&9t*>u?*Fk#vN3paAncvR&l^}SwCo@F#Uwtgk?`x4RIyLero_dVTuTgak@SYt= z?O(l~ZGjFY=HU6<93QE^9)GG0SRRdHx*sI#^MZvI=;_fMtlE;<@jPFj8@c*A2pncg zj*<2GNs0w3eV>D`j3@IenrsU5L(fzDSFzmr+Fr^Raak6b-&KRVVd(7Ew4WpRCXKR=UBtnco73z|kLChwI{h z_vi8TIVyh@Xk4MegwFZLhrB)y-Et7x)c41t9b|q#r~87S>H5sS`)T?9TcTJ7_h~N2 zE?dd^T$&jQRzDI^^RWx}b&&6nG_2mgwZp&g@0U&}hyv~^-KqWS<)3v>=NW0ZXL00T z|0AD|pLiV4-EZ5U>d&<-Oi@~D4$jZaAo_C!y)=-!eiYT8uN-fR>?(4o{M*4ZV9ZoU zD*v};nWE8eIDSr(`Hx}>!Hv6fm~U<5`IPTvIw-^@4KFt!^Z#ghB@mRYrRw+VH#(?x zB9{+(k@*+a)qp?0gQ)u5MPz}DRdVr@95Vl^z4Q+V3&64SDftlzy(TA+97xm5o99I}W01$UT7 zC&>DJ^0Ebr%+19=uaWt`lvOMJ&v`es{_eu@|Ep&!)4q|+Kb|xXlwat~(C(KXRp}3h z7#rea;O~4mZ@w&a64(D4+l5+x_g;Pwsy!P__2;9UeL=+9uGD;dEK!I+OX;d0qp0eF$aFKmDiw z^5;8LKbs?mKlwN|mCUbNa2t@G+0PVYko7z7r#b4ZU4VyQCiA<$lNNmcGL7oLp``_? z9$tVSy&&_uU(FQGP`*N)FPpr{0u4`{jTKBZ{;m}$h2M{^ILg@+s{*0fY-8Q zeuuoNlhz*FTR7+sS-+KR+~9*vznG_^$owvMo(KBds4?k1WcthZ-z`i0VZ^>}c>P;h zea+9$RJw8b8KXn>-_I8xgct0F;pjB7epg5N0#jFGrodYE`F#C8{jn5|i&&2z9VPP{ zz91y2GgRDRwtZkY{c_ zo~uOW+vr6qP%#`wt*@uPFhNi5=gaXO$jirv4m$%Tga^@87>pMxaDU$^Y#MS zpIbJVqr?puk337}d#M?>KRmjS85Tg+XGbe;|II~=)B4Ex*5&1Ad7JIw_F+$``fTlB z!QHQmao%zymDrpw8Zg1p}!BA?~`NPVEKGSd@z8__eA@7p!J;wmG6yr{9#O; z0MqUd*x2R?RFd_ne5;Q?2s=M?pz3oH$9M1bBIe)yntZzaw{=aQpQz z4)Q-m^xyrSqyi|JMD^cA=_Y9AI!xueN6TrTe{CkU|22X&;pQ_ip1O$4cOI9IU%0fA zsao_;f93UigN+Vad@&1eWXOD9MU`M+N&r>APfpiCur3St)gtr#^GOXz=@Y@c)%$n9 zyu5yY_vhwcpBLerr82(Nc=KnYGupte{RxbV4*pwTY02f^&!fz_{ZvKx{aP~LQ<^nl z?{OJSMl6}{gL&p?TF+vv9!=(Zpo%G+F#RgE{(kYu92HD1#)n?iclaMZ-)VvN(4p`J zv!IHs-vt5-wDw>zj^9k?d%i=Rblu=MIlcp>a=*U9-O+Avc&jp|vnoURP*{(9xH2cgbkK+Vq@2m69%cN1#;J#U`K2~ma`z05i)s1${g6MO`6e+6s9hRBolk4%se_Vi&f=t&h`;X_`TE=V zV?1a)4VaOZGJWNr&)hW91Pv%H!d7=rcJQyjn{UaxlnS;hPNC}igH%{{0LNJVxe!wPq!7D%eid_shL> zP@?Tw-1ozTj_*G|KmQNcfc5X9sQlj?Y>xJAx`C~vWd3_NwE?AdN!0qg6mk9_QkXRh%D8cF8V{Jzim72d_ z=H4H5$8J#hZ!I_t+y^Y6p3k1K!~|V?bOVFoWd6SmECkXe8>#+YyGR>-?#=!FJIVYj zDRJ{{V?(It!&WtGqgc-i*!dcn|0y$Sz^}D?9O?Pln=aT&H&C-WcjQxnd#JI4&GA?tsTvpF&dDZ@dK%zr?g30(K5gzE18_wakrQWd45_aOVrVl;boZ(k?)L-wQvmH*7unH_|ED#law|5>pwSW;}ojCk~q zU-|xcNJ1GL+Z2Rp_ji`VQ1J4JEp`5-ak@6TUV9O*&usqtewWw(8oek`{Cp_&e2Gh- zHmVR`!g`!X{a^n_f#?5M&5s8av&K{VZ#~{g(Bns?xYKYl|8BQZ0sDIzm4CZ-2`c|u zO66bA|1{8TSxlXesj@afg}uvgi7}b~A3lZPLtk&^*_zLXD{X6~d@6Y%D+b_0)sTwKN z{R~~6nxQL4EAajHjE?8|^}Rlq-}Uv%VWM@&`Y+HjM+d4a@OCva{}UdX!2U6}sQl;l zH%Fzqm3W6Eng2!0?V+@!fzj+%{`dPOe}2q(t~ok3u@Z09BlCZC)qClq{mF#^|B?A$ zIm``i-JnV3|5w>u(CXcl>i;tq`NQsM-7)R{g43%#!P6WGbM~sN|IR-j+J&p{b@xxk zSGqm@>reFM{1tBX0lNnDpyqdKv1O2*6p9U|*8Tna$k+G%R6;>RR)4DgyA9PwJ38m# z^^s)$yG@P)oxL2W`fm`ajfytp;mT=b{)hO*16F%7b-sPYeQhMZlZP`cyovRHRb(p2 z32>*@|NXe<@7&Il;~((yy@ac$L5AlF#>GxnfAI7B-TPIv`}-MlQ7y}yj*{{B;~ z3&Dzh{?z_k)&gy`c|;yQK7-8v)z1~cOLG@<{@cIzhkSmo7OjmAZ^^^Xo5}pE1akei z@))Lx+oAuzpAYc%GZ`E*L&KEs;%?26ME>WlYy~$8)8y_q2n6!=|NMM2q}BH>Uh$dC zzv!7JGzq#))&I5c&Cs2tcQI-%?f87Y|Mz)n0s|)Aq0YyNHM#s^-(B3?pUi*#277p4 z`!f?Wj?8~FSO17g@8SvtGXKD~Ub?6@wea&yoxgm^{qrge@8<^RRd>Nx)NcRfM}B^0 z*sZzXgV30v?N_WA><^Ex?TKmkhxIk~1k*;FF|_-KRz6FFlM|=lv1`fxKk$bSIAPJ7 zn(rwEltF|2VO0K;`h|i8Dub#0w_e}6pbek$aZFb-|9izzKrvj((DtXE9j=WQO)0=8 z-^2g@{p9QaH9GOYLVpVN{CIGIHtPJd0QdauMdW`@Tq-b`??FA^GVhu;+Ne@Uw5}E&aokGwG0;&8nKpU-^UVzt4Ci7q4Tmde5M=*@=U;j;> z|4%ct(SXebxMm`mfB$JUV4iC{wf_II#0*t72fh{HXnW_kKzCY@r8G5Gh z5La}P@vp$k_eEU3e{0frrhO%u|4IdOG<(=X+_|<>$NUXH-_NjpFa6K+I931G7`VYN z(YjRrRkq9p-yaC6{y)jp9}X|;gJ)oJ{Xd=Y1mb&^)cKoz-x8senTi#Q$oxP4>H~7t z*ih^L&lk&}gGV@SxI@Rsa9#g6L|KeXdD1BZLj&IvW8$~$pZmyK1|D)d(fWB!#OzT^jf8h7`{Ca4k+pjTxHjd1{du9cg z_A83&|I;0`(G~?3=L0hT!f`dg2ppv9f1lxI$Yy30{#HWff6dNTu=VFDx%szzm(bTZQM9 zzVGl4eE#+P?O|ruRwncynSXY_8CrU$3QtIr@eg?YJ+rDhsY|Dmg=rdO{~uiC3g14{ z$0J^l>wnW(bAfcRgv$T1G5*jt(-z0vCG#&e@C1{)TT}giXmKL6Gnh{8@8w_g0eM6E zQT2aya~UkEiNsYi-v8BKdH+A^UI@5pJA&%}&nxMmfSK2@>YX1Q&-3T+B3dFr%ffL~ z{Wl&E4-y|vqw@VCR}Trhmf%xsLWz8zO-KbJb}nHiM*rhWet&x4y3^qG-OW^foj>TI z9kWWXqv#5eU#E`+VC<_9YJR_PfDRHTUc*KvfHKC*DRc6{3a(>spj~V*@{TbF;NapuOm{hSa@jO4jPb+hUyJEXi>-T=c z=Ymh1|EA5)jZpW8kIVYwVVB7KcKYfG&c5o!#Qn|R0(twL-Zv(~i_>P|U{!McKH1#| zw2vD|?cdE`T?WVWipGBD$@&d(2*^zsMdkPKMSavFt-x*P74ZM`D-g)%cgJ+1z(g>K zIv*d@B_51E=`J@P%ir%*In)3JG*{q#cHu;R$Bjz`cNVXp?svl02FT`l1y!G;XPgF~ zoP4Q#o6R#oL;6a8rllgY`F@f=(-2Ispf8HWCLsIou_~t?~-$ohs za9C(E>g(2o-zTNX&q4i@UEc#8>=LIw7f`Z!? z)cV}%ydSKZJcwGKKfUY;zEAJV+`BBx*ZF+=bM<*pya$!i8{lq=IGFpkq_v25I;84H+sQKJ`<9P7gz=N8< zsRS6JV@>z)*I~Pfd>?gA1#OzEsrma$S3{JRdymR@oXcsj-y(ooe~(HuM0X|k@xqY> zM81Qr6o5R}T~z(v(Wr+4oNwb|NAmrmTl^}(BWVnk?}U=WahJ)&*I*-m#`JNNy3KQIf_-P%P@5pEm;Mt`+(>+XlbxJ4jZcQ(2ubl{s{2;Z-@2c z!M(@xsr~o2qEw)He;rl7bC#Y4>zubU(Hms`oS&cf8{G|E?ehdjM-_JP%b$Y?NhKIFGQUT@)Jt6)E*5_6tJm@U;`?u(?XK_?E2ir6f4@DzCWW5V{@L}le(<;1aH>A< zyR{M=S=FD~KW{sp2s@u!%-s)2=C``p8@N6iLG|Cg(z*Wm;#lkzMCLazF$6T1jHl*j zYxRs!$b%O+wyrZ#pUodfg1zrusr(MyWW@DPUSiXv1R}pF)p6j3)naOWZLg9FK8J6j z^7};pH1M$qruyqX=ZsK0`w|~M%MkgU7FPg9-Hu}3Tm9=_$8Td!?JAye$p*#3(YqKNr+X zi?c2l4o@fh>#kc};rT(PxK%>#f8C1k0PCjoX54R(^>_R@Ke(dN0ZZ4A>*ww7R)UNP zgBaR=S^5^+*C%!OYyN!efIlgqXofen zzm?YWG|)t$O!qlt{e87qfF@MF#Y@y#BER8l3c#O+XsUlM+0YGnEq{dz-x8}aQkbsfKdH87ET|NR_c52w4UN%>cJawK?g zVivVNPPY)EwV&&;%jZKx{Y|KhuU^|R@nY;ejYj5@zQJ5-1Qb~NC=O=SKP=NACMqJ32T*3d9UM{q4(Y9o~K%j18u zQ3W_@bcEW!&KzxwMjF>)@n|>M^F02`vtI%2pIOY1Rb>5+IA?-dUVg#ldSw1}+JAs+ zXBj5>fboKXbf2OuDW~)o*|9{gaUK6(7_h^FPg|L3%%uDcsRS_TL63u5g;O z6_tOR#U8+_$&R`|!cgP~>j#deo?kgOaV79*;Lc~h`ltW$^XvajNQ92DYw@BhWd9xZ z(iv>PYKYbPK|hZ(=^%hJpS##D-iB=hFX8m zT5o~^mNemqUm`l5=hxrcntp(rH?A@brZWBK`}b+lCa7|M6E;3c=6}NsO_)(o#r&E~ z_U}E5Owh~MO}K6onSYZO2?W8-)O`HoQ||nNMl&v1MCRYQi#@#ftP7^~zY;og`+p`i z<9RL09rG)E{r^_@UK;uzTR3+y*}tz=tBvg>+c7nLcoVbZdCm@)DR)# z!f&|vjs_;_zw?eruxZ``YW*F#GY*_f*+A9z0a+4MP~C#9g2;U1Ybju$c@Q-p7w1XP zukS5XzE$e8!LZ{I)O>9<_kP)K_XGD%CiAU3tN;vt5lh`K@zO?whBbe~d(MhweDe4n zQE&^4yOT<-&)uZ2zzgwts(+V`HbH9TKk&YnWPY8ct)O$`HAZki#&00czoQi`xpy*@=?Cxp>B1jVp~b{rc(wt#{&u(U08a-F zrs}s*sW0sQX99Kpe5m_M@FrI(SAX;Qo#~ngcN%!%rtakW`)Z6gaMqnn<#&x?8C>F# zLgjbQ_z=*3a|U&P+l6mpcB){c)4NR|D4 zdHHwn!Z@HYWQ$yXn}7av=0*uhS=o*+2+4exmZpH7{X?kpDI@$P=%#nO9N+x?67TnA z1JnK7et*jSWYOsoR94WA?}y3w=I7`5S3X#&oj|SMFJ6@(t@rKNFwdleZ+?EhH~$uJ zTYQ}A-~0WPpx7}#@rJImJDyMG>9>yL6)3!$L*;*?jtLsG=qDasO6I?B{tpnGa+3+} zC*wbv$NwHvuKxG`i6^fl^MA=!6Am9yP1WykC+_@z$xm$Doy>pkV+mZ=^o#1>eb<by+Wwd|fxd8S@MNq!N0z_w_rE2qUkU10A-Vn+;LWe>>zxRn4e-Ua zf5`s5a=JIzmG&RC|7B283I*`>^o=A)Y20rd*F@ew(Ksp&52> z)~Eia^6$j?ck=_$)ckIww*JL`9Oy<9H-4C!Kq>R}XEaRW= z-{*7Z|1KW*gEc0Q`TuR82}hZ~rsnU<#U|)W!yo)ciOhe(c?q18pnz%fEn5ehprINH zZ2ODaj^Cf3-!1FL?O&f@h<%Qe`7fWy5S4+YW=P)bcJ1}+v2Ky zWd4shdjOlX;nefz{dW06#}iYi{$2g)3J}WmpK1HouYOH{KQgvb=g)oYyusL0&Q$&{ zFDZp35yz?X=bOz!0Q-PDzd^ZQVZu!@x^!QGrSU&`d?ZL3!0j)k>~}qJTa5NURbc0x zmhsQ;f1e){2LkQ6`+3r2^*dkxV-+PRTUn94Kbg$`l^ZGGlEzNv)%}M{K#868 zPz(Q$55B*D*eMcdxvZh;yW#~gD#}q}$DSnfeP&r4IDIsbX;uHnr~Lh-_pXYO(N!gO z_+#?<@|>&`@Kh7r%LWeR`>Fc=LxJ=6O-k(TQDna7UCIaNGLKO6 z`CeiP^3+mhZ?BW_&G+}=^KOByJF}>KpO`2?;|3_Rof64>2X=Y|;;IW6_dVo%UT3ug zXZ52psEQUDAqHsK4iYrj!4jLA7yq_ zCYkU32@*JaQzx8zfqcF!^`QjqO;=`Xj>`DPy#Ack+rdyX!x$etN9MavtprWYQDz%A zk@;>;Y>-aGcM3Ci7!dgmZJr9Z_z%SH1!TUTUYG+$7E7t~>7UhoA@p;T^Y{GykWtfD zfWkGCfe*o#7O&KCo1397iEK>?=jST?)5z}YQD-nZ%5`^^+Y~ctB^wV?}lH*=+M(nto|Yy z-+cX^HR=}lt$2pY_W@%GYWdlTjSV34edBgDz&kN@epPi4r=NzM*;-FB-|E|cfLXil zQ}uh}aE>oQXSS^VWQYFp^*cjB6K>e>k%@?-@V!ZbE==mo=Ejlv-m^{uPfSw5wEGwA z0wkztYG?MfBbo31mj^?GG9gvJPo_vv^!m+k@|0kE<@%h%v=Krx$ zB*4oyQ~mq#*JmprhvMLC~E)R zVY3+ZS)xMaUobu!)at}j`QMr?Mnhv&SYK;0|IdB$L66~SRDD0iy}!EcQ(>E>fBEO- z^ZO^=0xMF^F;3IS=g0dth|!Qz6*g}fng8aDYA|JF5taXRB?+4LLWNCpC-c8B_6PWp z_lVj0kgV^$lqIN`dtO>W=KuFq4R|f|Gc~{S93eqJv{l)W8_E3FOqalmHfmJs>~+@>}Qe^i(8&)4^QjTNBcn-f*v2ZkoVc`7@o`=gYH zd4a8C=1}inIhY>|_AFRQ<$H072)Q0pW$RbU{5xOYuYHIB;fdZ}Q&(fN&B=U^9gqS(rA1TodDZ@6H2se%mGAT}Tt5FL zL9RaM_t)W4F^aZPV}B@;`QGN455{>Or|P@cRxaOwYV5gwGQI(?KL77yIdEk!Q0MEE zkBU*;d^PrfEt&7vBdS47=rw9Sx8pkZe%r3bN=K3THn;czwvK-ym(TI@`Jd0kDC>Y4 z`vH^r&MVe{&u)LC`uB-?5+t~)#$K9B=6mQk34Gb6j%oLk7us_9%u_X1vpbpZZo3D= z(R!v-|L(=rKd-;4QTcv5@uReH%Co{TmSla`U%~L~K z_0jba8mwbqGXJI9t3hzwO=d+3xqc6d=lU!EX|SqxGXA;y-sJL0XZs&una^|P)is&E z173fwbCwtx&eLFjXOQ{Vi`9Tjel}C}eJfWV{Rq@xGY6CT?xc1TD?f zV9RvK{NG+S7#_7Zr{?oNR3&KOX$|&GH?qFh9BY(jj;Su3&_dRCJzH0pabqN&kuT$) z@9%f|%mH=olc@RJ>DfN;{{4B>{g7)0EC*{U+?cAKviUl`zb~GU0B^3|MfLYFv%P?} z+d?Y;Dapa$;r4aZ{N2M}gv`}7+4@OjzN1ni!1mGrYX5z8tO(6B(`4JvlKFPJ9SgEN zc2Uot>Ewve*%6womYB@9PxVo7VZ?swe9hfT5!&ObN#$ErKN~z29cC6Ck-Z=IeE(4p zqt)9qSa~fFJE8^F8{{Y_O1Vr0RP}t2g|S zv{25!^ZW0u-Is%-`7@Y9x-TO>f`ArW|60J(lIGVlUT4oj%{oKbu*Xsy^t)$frH z1gOQ2<12(bANMCG0-PDOovPneULq9Hti`^{AoE>b91F@uMNsEs{encOr$QH2?Or-j zzlAkNfwE%^)xQsq5h00Q7b@S^A7lZ6D4ANHd)yYG_;Fp>GbLocSxG+d>6}I1@5=d? z15>-Ov7aS>^DX)FZQe?^z){D1W=X0{zXO5%ez%@FVzh8u7xusl_m1cJ^EI1=)nLHh zTh#iztfv_5jqSod{uAEu{7jyHpLy5<7O1^uCgza!+jocFR^av5ymx9q z3$I_y+MVQl?yIL5Io|8SihkVa_J_dV%Rt%c=df*&Bj^ zbL|$Yevj@XL@oQfu*r|fd`~(Q0hrH0RK7b87NJEM+U(smWWMcA#e%i^QB=O;CyEd# z)Mksl$b6rnQyanF9xv)iM7emEYgo_3;*PdX^{EpR4Z(2FF+UQv2s! zZwirMs4koGn4GVV;rg=MQ$nbGn_Lv4Wj%D+z7La$^|$7tSa3dnH#J}1`dNsMd+4%O zSB?|)`^1T(z{@^?s^4~GE^-S75uLYE{rRm7AsTgGkJY|U z<~wy@1h>LElsX@C{04V^wUPV#b|dTev(Q+O8NG)(A7jq-@29Kkv-_&ZeDBUY3Pxyg z`$r39^)r9|?WO|f@2&Kye6PKn1zhGIXNHu^p6A!!)qOzU2!M5lJ%&zNXzE?(y zkaxO18&E9co3Gy`y;^|f`UbgtozM5uC=pt6LZ8J3WWGzG28<3>rt$67^ z$$Z~mDTX@|45|Kn1XrJIwJ=}}H_G@<=FP_>u!Gg@i1C51y)|2x!>n&5^Wrs=Bd@U_uHaHhHgR0+ngg2ap)=>TV)}&>?_~$}q z(Nc2#Jvt;F7TWK_yF_HZhvaSnaZA=y{dwJlU|0(c0ukvanA93F-z(~c=%$Gw`*szX?|ZwhfSPwXRQ*2GMTBMn zLv~D>jBkFvc4lEY_|kHXc^OUi=l}nHu=O%z*KH>A?NIU(Eb)HKBs?bb{c*YojoD$y z4nIfcJ4(F;G^I7l&ByThzPCh#d=410BQ?l;*Xn3Mv;LhiZNAkuTZDY845@tQZ4|@D zdEKb`eTaMh4fp&tV=~`+w+({ZPTEkEuY~&#_-$S}ig^PzeV)tcaect0f z8^n~lQ|Dg}8F<6DFW1TO%g@i|?^_0pVz~S(l+5q7dGXNp`hJ|#iOlaXr7hrC&_?R~ zi&!lfRBzi(?SETr6`-?Q4B6=y$@R6XO$0bFdl$9;?Xy6L+NXA9JKZAt@2~-}!1dRD zYCirjScoh)b!DsPk@=m!=O~E#ewayZl<~*cXWw`s(%RXT%I~T(E@VP+dx6=R->MQQX3Qo%S<@@hm3N65S!531);e3Pw0t*@gubM=QuH`a0sS)UX7h@snHW9-%UMn`?70JP=a|J&n4sB1tscD0Di zuW`a4IQP08wg3I-0+;V3c4Kvqkok4!_C(GV$N~Rqo>z{s^bS{yI+7`g+8~ z*&yr69I8GG?|H$6-!{tC*L=R;FIom>?ORUeyKZDWe4QPGjeb@A{rTkUYwh^W;M|ri z)crDZzutrwU9M5jr%n191QJIEQ}eZq0|N9Tp&O^)Wd3!{BEYeM5!Cv7r;!jf3yj#R zU1a{>c8&$`Sq!!RT`m=(nb3$G^Whk={)R?J!P?Ww)c%Plzt~8L?9kng5C&S3rbK9`$_c{!Agdl3~Q!hsgNn>-PiWa+?y7o_{c6 zXWSz5zp+UjwgsqB{rUO+BJ|0|n7uuT%>RBvF`PV9NcHDA)42M|#h5+R@b+*2Kz_fJ zhT0%F;8=g0t0wd30LbrG|H}1ucX}DKGb70SKhkKH+DR0cfJ}?Oe97~l{L2NJZ*q~F zZv#O7ek2u6-*dg@QR{CdZ!ee>wFO_wmgVPs{>8&NeIM>g9n4eP8okfO5->+0?CMzEfIb zz>VZMs=lA^CPc?R8nc-!neXU^WUzco3Uxo+$iYJNN>f1PTk}^YIK4cZ+8=YDB1HLC z0yb$7nQvdKDSnMls)fmF!5!akzCZtTONi7`1#HR{y|t11`xOb;!4fjxj_*Yh99eJ^0GbIE*v{4@|+T^K00 zKQ55Rcj!r^7B#!d@y(xadEYz>lzd!3)%Ry% zUeK2Hq55}+UdzCz9&4!gpBG8uVZ37kF6vF@o5|V?aE?DUUsE1_6P^hx!A-l#^KCg* zLE!Pi9n}2I-d}*mj1{uU#$^8Ea5yNNvYR^pGWC`K?T;0*^Vg91|IP8gBszhbzr{2N zQ2hlVYZyo7e@A&Tc)mQ1%Kx~}0(3Z6Nag=&K_+;z;0!fi@6k($Qojn>Fk3SJaVA&5 zt+GPueA|uz96vvW>_Zna|3hz;0khCbs=nLK6rvJy5o`T=rmVlr+dpAZ`U2SRuA%C? z<`yB!m5Ny3*<}7rHZ_B}#*RDEx}?FHKvwo>=6@3dbA z>Q&cM`{Td#;^AezgH(P0wrDd5U$KpP|EZD7P3Wgoj>p!M`EP9t0^`LynU+c9^QpV9 z8zDCjA?qzA=X1gF;o#YWXlnkRb4Y;T2r*mbMCO0pxfpQD_#oBa>tqVh?TKP`PcJh6 zw#msL-S#;3{MwFk0b*8)sr)-cXM*&J=cxBDd zKS8Nc+M`T?S+i3>|Uz>7cCW_J>Mm4&z@xd1swk()kDnWy|F6q01Fm8BnWpDt|IhpopxzNC-24og|Ih3Tuv)i{+JB1`3QWv!gk8Uf%>T43b+|)Ahsu8|m#-XpX~Iq@Ci8EyPy{Q7nPa0{*E{&* z=X;I@-T>WKg%8u+o=Ko;z7pcUt6N3Xxi2SP` zcY$F(v+)eQyMKQ^`TAZ^J`1dES;6R>koBkd_pbzu=JbEucItfl$(>8VpPpN&_5G?{ zaqz*I!?@)PnSZXZ1MjW}QTM-JT6Pmo)VM?6KbH{%CU%XW@_!`97){eRWv9oI^F7y$ za8R;%Kea#CX2qK!W&IlY4cSn>3qwK*gW8GbB$X6e~cHP zt-np#&k{2KtzKnd*`Px@s9_7^p5QRM|0;69cQef_V31x@`5#=g5>-^0D5u(;+x@1!RF3B)c*VT zkT`gHax#YR$o#*p+ys8uhEVwpo&wwuJ*M ziJ|8EznYBE_{HXI$>Sq``I5i?ywm;|AibVU?ayl(bN+j$IV<)d^Pj#e89Z^yWK7d# z`8>bBx4)+Vg(R3$`ByrU3Hqz%Qv358Tm|Upb#pfOEt&tV2lGH5<_2@mn|%LE{&E3Q ze{Rm^>B;!#`~S(dWx%>$6}A3%;rc7J8WyZVIGO*W;um0y_#?IcpT+H;?q*@ZstINM z8}j(yaG?p<{!qfS`S=AT0#t}B*q*b={4d<14hPKCr}FRG#`&);7F7OM%@RR_zTK(( zPw&g+x2G)FPvgk^XS)xCs;fuI)&B~-{BIrL?hn8gtd$9we^u=-QWqmtMy*xS@%`lA z-?Vjr3;aB5K9&Feb?%_%${OnVm!UddFv2y2%D>&$B|sSIM?L>Cba5Q4YdeaMy&&^1 z2-yUhc7#&<_q)n(z_Ec3aG5rF|73`J5IAAEo0|VM&NN1I_gS#T>&g1xXL~q^xf9FS z&6N2c{(R2JB4ZS+Y{?G1MCQM4W(=sBog(M|`TOTITaD2T2TN9MBbomVqmn_z_bh6E zuhR=-)XB_}%KzMfnIIuMkDC7{nF-LFrIzf?`(*wT`sRVUs1j;_@AgOmY7MnyHB@E% z^ZkF)pfcc|{ghc-O4k24cLCa&YRO()M&@6t_yUBU`9wV*Gd)y*jPF{qUkzmZ^ZR?9 z(we}CRh{s^{S|!u@3c*T=9XEqi|xq#JB6#m+HQt8%(VFL`@M^tzA2v*pks{vWw-j6SG!r}7_bk_nvd#FF_pvdRO~KbBGbzc%;& z>fNt9t5Gl8FVE-yq(&LAH-ACp-@l&#J@f3&PMSmJ-&ywsP&oXR>i?%q7ohk9-PvoZ zGXDAVJvgul%xvt8Y3FCExcAS>`0i|WFEanBbJgLy%&yo;k<5R=9`5~huRE*eL*~ER zAQ9|R)02Asb~#mYU?WxkUG{8&D(Yc!`|0@nE2=I9J&p%b&(D08 zaP`0IF4={DNsQk~n$GyL> zHM_iq%>S6T|3}w-hhzP{aR3(z4f8S5URDy7M9MjbN<)+tQbs6AB9$gmMo1YcZKaS> zB3jSqB!!AfLz0FDqNV+9{GRLj_0;pZu52z>)8E&Q(w`1*j!y2y+G{Wi+8@}wNfAaV4VSYeok(+==+E3QsH&B|Db21 za8aNQ`2HAw(ep<)S(i3HVEaeK9aaZh6eRphA&K~u+L9s4|DXUc|Cji>p-+A*K>t!Y zD{z@_9H-w`e7=V7Ut_Ny3V#y?=KqN|8Tg&j5zZr*?f=5sU%{3v`sc{1pK=Ty=AyUg@y(mA&Og?1fQp~gKV>VLlfwp0h4_ihol@;$r%cc_mW z>T-1z`2HF17vZ?yg?NekFZllTj`*RPc^kp}zgL-oJ4%mogLbj~um2o|wmNSC^S`m~ z3JxFD1m^#dp3!KvLmJrs)3j6~Cm#=>i3_Ee_5Y;-3CPxN59t4JrzY8ws!yL7v;D_B zNki6?a>4q4qnZ|xIipX#hO+%XYS@Qd*A;{Le{+NunRZ7X^xt<^K1xry1l~{m)>4b~ zf1ytgMYH{Xx?P48{ceN%|C1fG$l>q$^uJ?l|0e%cqo#E)gqn{3_U|R{$2c6XMItQ> z=ujE9f78TA2x?FJ^0zBv%7!TQ2s`&;R6uAJM`N(fx9N-#^7)|9cl`k;y&= zls;hl*ZwSzRV=hY|9WqroBDVpE9Za{x0vi<*v8ij*a z*>XF6i2MKi`hU#u-o){Z0q8%vUz=5)Mi1e?`)~OEJJ&ein&Uy>{-2Ah8#<`67To`D zxgL)9&)vcW7_swzgo_`_u8sls|C5hrVB_38F#kUv2t#A*6D8LFh`0VXs=0zQpFH7? z2-*3+=t&fM-kuKTzk#e0`MO=yf45`%KP$?WuFZSF{{KOtCW%-yocgP?{a-kdhMx7y z2j_oN?`x9KnBjEt-Gj{azd^}9bTs}9=>K!8CehzH9Q2Medbw&3ktLZ-c8ANf8**hIg*w z{N>I6y6Op919H>5^VZ2yNgi}L^ZNG@H5J^%Ceo)#H=$dHDFvi*OYItus8o5ndl zXZsI-t3}F%hV6ZnfIFvM1<&&L{``syP_!|0^4~A){^ULH~DVgyZYm61mZJ z;`x4l{@W8jpMMFh|NQ({yP!q7dKuBY zOt$|(wN|S`DZPXXpQ!)+d`c{zq=d2#Sjl@C=wGI34zf;+1n2+fj19+m+Q}00|9t;1 z4Ezu|5DU)#mf2_EhAzjs@F2E-Q|B-=q-rbZzx`GPzFqR1ds_DD@A^ve{n3-_qR?cc zonZfe<1t0Dnj1>{j$r%mJQ9xzM;!$Fe{Uvg5}$oW^k^a5e^yo+8diH8-2ZnB)g&nm zM)a6B+yC0geJI2I9N7QwSguL7J~9IRN9yOJr&lW_{PX934rOVQVckd4&$HP6H}xw+ z{U6kW`+tWoX%Z!~k<@<++yBft)yTB49rUmBPLqT$9!Uq6v;FHnYD6cxbm9KpZ_D>T zv8NWP-7=CI?-Kjxum3ZQKccFoilBeoU5muTkE9=WvHeFLlE;&b2Y~bcGImLJ_z935?J>^2&l|Em%8f0zFnNgXDz{hw4Hg*#eiO3eT9{XbZ%MOO7PrhbuZ|J$Cl zSapA=2>O5BVvlXB!zAvv=AZv5emMtCejNqQ|LZ(oj;Acz3g-XrOAAoutvIm$Keajo z50fth&-a?$2u0t1q=5I=kDqk~uQ~M!tpEEYMWLouyTJPY;dTw8T`-b%k74)!Zzsf~ znHAZf|Jy2>|UU!0!LA6|J8VJWZ(Pakl?W z>e_gUo++6Bt>d(aS*8gM=_mG&c=LZt&YIwD`3_uF5xf5H=Bq`L=WcV1cj zs#Owxza#kj`%C=#QqM2jV`~G^`P^>o`QJs;=AbXF(P01oxb<=z9iPH&bY$26;|mrb z=}`$_{cq%&fxj1>{8zvTPrehkzg5C1c!-G{RMe;FN*lm&;u^M5OzX%LskCiG!6+kZ?%8oKCoN=Tjm z`IX%NoBCCQ{Qhb}2j?GPuK&{q>_aUNE`s-Gu2B~C57bA2{+}D_MfJ;& z8Kda1@ofL4y~{-N&yPU={pM+svXD{KFPQEB`M_$V8u%Xce`b>=nYwQjZAfAJpIgv~ z;&#h$|L*7E`!7GNNxobjMY%O>{}ol8=-?<7F#lsuYLe@>M^UqAwtqigc}yk@2K#>( zpJ|fZo}+18F5ACdM{jJ^IF>7JVAua+ME&3FNuz0mI@|w)A``s!=4^2NzoxGi+2Syo z?)GQPob-@V2$u-_O6KfBgb`e4ei2cIdGEhic71{VZcZ{{bCg*rRCy+~Qic|A3vLXvdFKu>V)&UV)wCUvo-V*!92h z`Y2RUwg;^LKbmWhyWK^9zlCi7HwVX~nA#lh{dH?DX^?&eqiNeFw*R%RX=vV{)1ZIT zMh$Z6+Gx7q0^5I2-F>M0e;l~~_wJqsSyC|?^#83a4|SZck*NRq`+q)innd>ZXc}n1 z_FsIf6xpnM46gsT4;G!D9599^yNmtv=YQ)fs*vHKPT?l4i+?|VlKual4x;>a9z%ac zu>G4SG@|9-WVwIm|M>oUhiHl3=Q1R_Fs_S8~02Z$C(~t`@i@=w0`C#!xhd^GhwXoeSsIGF zT@3n<+N(j%&M~EZec1jF4BCfG-&_Lk_xhZpL7w@Tg8m!Q@{ro`o1p)&It?;2)0B?s z!}dSoUMWJ?pMw4Wk~R%8;j}5Wv=#g3&;QBXt3tA4KMS+`+5U%WYZ8+VQ`+Fg_U}Et z5g8bF1M`23g(f+vHkMXy0iVO>n}hTLy|%NS9hi3^86A`W+vPJ6Wvf0_AUd=f2Cs;_*KvM;QQy@hDD)| z=l6sA|K5Ey$o1=EsZ$0!|NHihM_P;W!1>?QnHuD>f*Cz*$@cH7nuY?(&Vc?`&eb3X zwasXKH@5#lN|T&{vUq+ zUli3ZN88Nk;8|k-PCWlzOghnj`_#et|7cB3QuEV{UT|Rh4|yzyWxwcv_j@5x{k7$| z87+Br`A>d3@aF%Lf_h^GTTAZlNw)t70h+{n{x}+0%J!d)P4F*sH*o$pJ4Tbti5^E! zB6j`{d-&XH@GODQYn=G~^L+mcb7$g(hc<9#vF!Pu*bT0z+&B)b{~!Je#XtLJaBmyM z>j!@SKWL#Zl8f95p8uJ5JRN(SDdo~j+5U-6D6&Y*1n>9SQ*#+lPWixn5wi1t)7MC} ze!@Yp|JSyx7unp;h#ofm{U;yz@3+jq8Hb{p^1<`}Lp3x=_p)(RS@e!6@%dTF{lDPb zsc5!$8QA}8)fM$0YQ|B)&Hc>ve@yUR?1nYnQTN>omUURzEi0%JY zjT|1Eug4w9VfX(=7m3!75$2$OJM-SSYtM;XdIsBn4H7-SbS9oD|)^p9`qkp zABqh&@8CwfW&0l<VHH?;p^`d?TRhlX!20PBCf4t285(}F%wWcy#$n2L%fpA&Xn z%I^P-=u{^k7g*4VscioTR_sMv7FUA#|6TO_aoJ`8`ggL;Lwi*3gZF==i~1jy=Pjt= zCu${reo4OHa-~lxvJ~B|2IYUxDH^2Xx&;l@X8RA`ScR5V{}i5-xSv;Y{jacDgLLgP zo~9VF{eN|Si2U9waArXl|9*ZY=YQ=)>nCmV@pRl6v44L4AE6)6n{X{K|Ba7nkXh5l z(*gsw|M)^V{B^Ve=zm*!BO&OQQTw-wyWw+HBJCzGvsa{eQhX%g_VgEQ$L+`0Iatg9@DS z;0xEKp6!3|^+>do90vV=QRzjJ`kTJapnwJvjd-{H{(^CtK3F zO>F;X#+9OlIc=c-jl(oZ)*4IDf0J_+s#1{RApgDWG)Uh9OFCGM?f**EL)4McgL^%S zo&U1SG|12fOR6!P?Y}kQ0}8p@8}vUZOjQ3gTGIP!Z2zMU$l>7H;o$sF<|a}7&}m7p zONrP2{QAF_Y;W9{ioyE-M!5#5!V_qeFWdjxx5n6Y^L%d52=V=Y{QduF?V|c?`2>o4 zv;9{|J-2#nuO;04Nu2-u^Zx=e6HkrU2%i5Lc*6xfYTW|*_f8JQw}W?aSNpR4-#_e& zVs7mg%_U`UOsSfL;GT%3OxZ8+S|i=g>D7sZL6T6X;9_wtr>Ay=dsr>tO!RFH|SmO%p)>9~*K}>FWm2zse0! z|5JJ*|KFrVostQc_OXTV*3vX{(w$-_TixWe?OaPkp1x!X_ucl;`w9V z`5)OhIb0nv0^I+*K0t#gE}lpy6|wU_;=UF>Ki?Yc|Nq<}s$XQR=(9O&|ATXk@riZb z;QW98lN#j3U@NL9$M)a5y4gzhXm8N}ymmXx#m9i_|Gp(I$jdAVtpDG-gyKurvOxc# z(!Qv#YC5?8pQE3S-IIji{BOwGWk_n)Uhw>%n`{M6Dfq!n7{T^mzB>|4oOe{%VZ`e(QA*aCozxFxmL_uoSlX^zxn>}G^-QOuU7O&tBcqlZ~nh!%tNHtLy;@{A%1@F z*Z&W@YLL1ih#D%g{d*{UK(+h&g8Tm_@*1R82hkI6+5TII9LBed!2aL1XX=FeY(?Et z+5U$d*1`o{Cvl(R*z5l*qWZ(45K#*kw*R~|W1N!d3!eWQC#pX-UO{x#Z>c}`fAIJJ znnypkIvCJLsC`k~|KsO>^?5t&bZQgmzpBgyEzL*<=YI{xhGGY^J>0Ny?EIIK^+lsL zW(dut*!%y_RMYWSTMFL)xoZA0WLdFKSX=h*>m}!Ze%-r_zd!p0`aioX61o4E3(o%( zCH5qTub9%q>0n2iINe87@d(?0y-q5scuB$jpR&F>iGGS` zX!Sm3|F3T69+cu$E9|ZHuYVvX(ZE?Odj6#K$Dn_i#9XwsvI+FRSoHkpFv0ZsdA9%9 zk~1i}*L$%3*G*9;EBrBa`O@c)U;h5zwilIXUX~1)|3$^><9M$hae3SIF-=h&)NPXZ;Sj- z?{4utF{R?|gPQop){y!{G zCu{c+(7#<&E(&RU0`~u$MyeC@ON8njWBdPa-WjCb_5tkwo6c4z*>4H`{FLo~R7E8^ zS1HTkx8nTf=l{fbbu!(|n%3WB`%gO1fE*VogY&=FcB+&58P@dN+qgf^AAbMu?uYlt ze#ZcAr9ON9*L=4+>Ed8b_f@g|Kar8cQy!bZ`7iRXwZxhRA7lG>S)zrT5^TZxUrSnp z9KK^s2lrB6_fDD$mp{tbG{#`ZWkp1*C;Qs%uZNl099S`h5qqFP4`v2BL0TC>+0sTL5%tb=EX3+nC za_Yn++XnP+FyIWzH2MUt|Mdr`lT*}&*3`58fAy(Ej-6e>{$HVuI#KVmp~=VD{sn0b zXzgniu>P<2Q74zQC(*6VV*mX8Ka)-GQK`%zaQz=WU!8bqOrnLS+5WHH?1uM5j|SiG zw|0bu!}fm;SE4}!R<&JqmXn4DSEm)l(<8j!vdW53v3F-|L1i zS(t+L|Il!CGD2|*U2vZ5|K&t2Jj;CsIRCF5t4`!}rqHwZ*#2wNN8-!wi@8l%?ESxo zqW~pJUO@oBUUcCRu&wusw8Tioj1g=buo&U!)T#&)@RPg-Yx#i2S zxm-5)C|K;DKmW7A*$3Ux-VOHu9b?mQ{On5b{_hg45G3Vt81zrRZ$R&VoB;cKBkN*O z_sFwgejh;s;t@E7zBOd~)lS`xie6WO`R%t@Ku%^)p_w*pzf@}v8l`X_oZtDBC?KUb zr+|LLe;-BmQm?@L?wuhZ|20mbV-wkaOKz7S!^Cf3{a$rmK%Oew($AOKem#C)MSZ5r zgZZt|A|PL<+0xTH*nTU%KR~zL1)$%>QtD*)Vq02K%k~@5_dP0a8Umi*JKG^3@w08| z*+jNq{XN}q!P&83{r7^RB-^7rS zSg>IUcjO4$Z|)Y+{)^63>Ql}3yTRd&)x}@>!nO4SnfZOwW(H32+`^eZy7@Q%B;ViR z7VeCG-Ax1YJ8kMR{9n)^u1}QMFF(H(rG3y7r#;~QeV#`eZv9XN_V1n_UW!Una=`f= z*Y3%9gdgR8+ok>e{Ur0d`@RjR&Fdt%e>br)7X6rfUa0%`{UrSRxi1V9khNMkb3+`SCFUF}pXF8ilZZTQBK` zlZT7W*95Zra}$(B{rS1m=&Idp-&w~sv3;C9=-XhZIytv;8Xa|-?K{bCBwoC6DOjIB zo}o_eAD>2birK!Slv=IcDeFnx&&ki{kNs!hto?~x#0R$T>`-TP#Wn-%&o93bg0B}H zmgvv%efPNHjcD;+(D%jAG_2b5I(N%~{eI3P)0U$7okzg?`IA$U@Z*D*IOWRJKfV#K zKA-%0JsNcI6u3TD#0RlTdlMJ;U%=nzgFvD_l-V7NlCE3;@8_BQLyZh?nntz8vi%3x zZb!!Ru7mmB*h4@9JEzgSE^Pl+_jjY98x7$7{Ms6#ukSJ)^xw4ZC^9(L2A;d{uRuf#G%kL176DOzB#b?<552n6DHivY;_4!dh0Wk`mPVd;W{WmP_hDZG{2kY}` z4FZzgYX-GQVEezaM-w-%ngy=UUwsk~-_bK@YA)OV;{hY_{@u$!|7JSsWLfwO(0_sD z8>^m%BZQ;o4f^}}miTx}CEuNnt4fl%owwQkPYrTLP9ZzM_wzWGhTvSiBOLW(=ljy5 z-Y7`0AFR*wb<=QW)D5sde}2+ZRIn-+?$3`;!UsN6&XsJRC=sWYW8ac3d1|6KXm%0CTvUN9F^|BE> ze{0{QMzpui0DaH!If}lNwS)U_JEcU=hl?|4^%A!4faN9Vriv5?&EHNQCR%^LpFvv= ziG3r~TjB%c)c-0{9XG90eSyp2EAd)_I+Ki8Y~Q;>G_l7}N6vW- zyM7NU6_9S{?P!l!w(nQ%M%Z#o7+AmS)``{R=Hb%kna_=Hz2_K@~Yy#Kc<+*BP!^D}O-;>ry(WLut!1FV@m1^Yf!kJXt zi|sdEvjnO2>cTznWuKp`X;&l9vS!lZJJ^1;TSdbiDl3+-!Z2}^}$JddNYIVH+{i$ zd_XaU`*xM>cX);q8t{B4xW4|eNK}8T=7D}Yk9wh@UI)SZv9jAz@eSEqobC{I{XOVd zFzRA{3|wDFUQWcRU$1bFN3#7&om`I|u08|y&sNLFqFc6?!2WlKqZ&~>U{6yXvHdQ5 zu?@{nx&`ike-2h7y{_8Rl5n=)U!J?sbDJk%ecc?XMy#ILgMI^Tj-nmE-hubu_-3h* z^<5pPtUKGUO=~e~QkMq(jytPH?if4JwTW!MH-fI9^M$=Q=>FTpr)s44LI;{Wk)6Ml zDi2U=wKiB^&yy1nvd4j{?qmDS8S@V5^%~Aud$9Mv-;3&>msSoG4`k7|vdTkloZ+W2+mcFtQJpa;jwSa_7 zoJ9w1X8YCcGaY-{Z3FZ7O{f!^;+h54&%e||uuM`uH$Fj}zx@98%ROGm{(CmKzuh+? z5mzKtawkt*`&-|uO4Mgxrv)Sb69wSGReEGjh?p`R{uky(C=-cN~Fn_~-ZbptH zE`$B=ZQ5#NsQ)ZFq=N0&xoR8w9$5$OU%8D}BL!)*=nPl3-|>OF(ViX8!20={lj!+T zHVgDSw&e)YZutP_ug+XGGO>IXwVlfLtCdrX1g0|F{l*omk-=m(wXtOTZQfCjo=W!x&#!l_RwHKfXVZqQY`-Jj-=Yu$LvViW*)BC= z*LODPm(+E|aR`C;S9pki{%3eL?e&uF_t+~9T)1Hl*dNoh5Drq6nVuJtA9WbaXQgq8*iBH)En3a?eO5jgwGTc4`XBX5%ljVeH10SeiHWhChpJk&#%WA zsF6V{9O-c^_Rk^7^Q(%>i_rx;Sjj#Rp|>a_*Ncnf_PjY(~0Mu7c;+cAQZqna7-H zvgjEpKL0J*KfADc8!CTu5A-irp-Q@PPBi-d9%lb+Ph%G9_WlJ}zt4E7O8UKX0{yq< z9YGq>U%>g59BEPiptm#CLt_7k=fBds7?lQg<)HUhYbmRdctdA;Z2{Z=p0gDwVY~|W z=@HxiEgLmLS2@#xYHa^0xE@{E*B|Vk-C3YU^(+HBw~b zOxJ!qES{g?onM=k+7**U*5LW|`AKTz&{Jo6RE^y~+Y_mQH$U~@Mw_wyKf9wwWT(2& z#JOz$UyY6MxPj{>=GPJL{ncw9s*$a;UFfv{w*P7QudPO_mazdwd_ksS``!2=D_nhE7QrY$Wp5pnaPvH?T|C8Tu!Oa72NaR1_`_Ef~mOVTP zuFnIXB;f%cYPssi>3{u7=70CS>rmR73*h?PIxYzxURKL-^UeQ$y=4A>iP?~LRh5KAyUt7myd!=pQ@J8|c z3*UdEsQ&nU&Xo$B*#2KXnu?EYP3OM#WBY!A91;1s51db5_$wF-8VbRD4~>|Q-hVv` z`W_d!1dSV41p4)FPsCl_Z*skMu;*8Dx~)SGPhJG`dqqhiKHL2!=WyAK>GzY@W~4)^ zLBEscsFFLPzu&hgwqI|xZRp2;4?w@8m#LD~Ph6>18QbriXIZH7v1mT!jkx~i-#N;Mb+*6(LU^+T6ybLjVQw%==sZ%|H=2{_-f zUi9;)InJRukJx@sjq8fT#!TiMBiQpTKBAxBJb4Z^&0*K?K870DZQy(^RiEwmw7aN& zF>|9swb_0fTu0!MnUUOx!EC>Jt3>@9UpLV2-0f3w)U^!moV?gCLXz`oQ>7fyFpmSE zU)e{&ST*7ln9rYo%|m7+Pw49}KA(b+}84c074(@O7(Nrb&%iXA- z7u$E-rxbL)<005ze_*9b6bjwwy&Sgh$(~v0=KR-SKKHa$C8p=yK;K?1Imkcyhs68} zLh=#~8udU`a`ufIy*iYg&o2v4BlWfN;QIVsjHo`*aHn0I*!g^MQU%&yE#RR0rQI*6 z5|==Cn*59HJA40qWDqzQoL@V0QI*UMa;NdGY~Rlv-=LY+qrv%=i;=2ip0YdLTg~`ef6V^)*(f39pm12M*eCz~*!O9{_`rWf62AHK zY3Vxi(J0wtV1Io}P7XlA2Tx(D&gdIcUhsU*PjN| z4)vtN+}XaXm8RkodONu_owa{I-;((~>g;Ufta%9B|6XDgjE%+?OVr=|{j;W)dB|c$ z0q8q*+!pMfUB?ZWB=#L?CD~s)&>Dn1pPm8xYlDln;LN#qxLkks{#kUyS~TcTIk>() zyJQP4?5yK5?wN|~bKd$h-xGrHMcmL>LA3Wb- zpGD87^YiG|*=*nU>uvG0X}dt*i)v@1!wHAM{#n|OCD=E!g!{RY-9Jlrn}>S490%`z z2n*kWO{(v53O)WlpLo6>^bbPU?v#S>e=}%Jz@8uPaLr!Z|9t-U^YZ)G%(X~wcm;U> z!^^}?Xyme+;QO7VJyTFb`x7vK=`IyAE^!|HK9KD*Z9ot z^w|)TgI>+)!ujqKe?5Qy>+K~KvZ87pt?nZB$xgOy9x!|J;nW8?Qj^4it3W z44hvXb6bU+e=?6w*ul=!S|Q{!8;jFFF^oeNJ6vi*vlPIFF0s{N>lz z(^F=n;5#{>&)!#-;3}n3aDHX*!g=WQ+Y?~^I#+MUy5F901C$<$^N;6qzCjRDj5!O| z*SBTXqRyf#pub*wHX(2S+hBgW%}ha`?mq+9w>ryJ$TB-GI&=ivpIhE8H22B}aDBUN zg$mK18g5{_LDjqsjrjxMI;Au;TqS1&M$ECudcN=~*u- zWybdB`m-FJ(C-cIKbtnHkX0RC^wb%)zt%4I(c~&!u9qu&|M^}QRpP4aO(#!c`x`pD z1Eszn2lk&$E~}9EN-tVj#P(OZN*1>o%>?^b`l9-#_=Ok!}&R>#iQ8%zKpTOg}%GF zKDlgv$rEOy@MlNB^H;5VmtZxYGH&N#aX#|bx7`~((Wd4?Fdt9d+KvscJ?A0<+5X&b zE=G@w&Vl{ub-NRAoNB#9K89e){iVd&Yfy6ORj_|`*>e**om&UaZ{K;l71j25E)2ha z_V4Fg^894YWEB!r=}l_{Y@cyayO76{kD$+i(^W|ST5r&&?VH1Bw2F*`Pkug@hN_S? zJ$*o*GPOm>>vk`2eL7{E3aKCOLpw*aecrDsM_a~dgFY9OsF3;LKA=yZW%rPCt{#|= z1vM%}I?IRdvtaw&_o^K&SFr%=*Hx=jh@ZL-ElXniY+oRYO$zM6`7r4m74qG~hfc9$ z`~2`#fWOXL#Eq_I`!pS`N^Xty1?$(PtMu^RYa6*?{r=X!Qj+-?FiA9D;OI*ghp~Oi zMNUD_zw8%AEfU}F$v;0CqhpKx%l2>&TiAZ*RL(+`U2?(o>wu|C@CtfXqCdr7zlOGY zBHMMR!2ImU*p5rXUUFS$u>J0CSd7wqFM#XUJ}VP&jqm~Y-CtbaBA#E%+STZcpb9)c zIbe+_UyJVwHzfT#AJSFg`MK%IRE%Bve+jcYOJM_GFp%p%#!TByv zZ55Ih=?nUmmCZptrpaMYjkmskQnZ_`(OV&zq5yl<^u-#Q9UEJUz@R$(EIKC zg|Dxd{LK%EkEfK)g(-Mo(Erpx+!PPh^={1m;L5qX(4d&F;C%MT*UH3aj34MX{nlaBIjt+`7t5)T zTrWSW^q#X4e}BpO%u{+rXv|F|u5~E8KK?jJg;XT?QSE_jzhqK5>Wt|Nu1_7ERESxF zAN`)o_B;LET~s$=IGDewL8A4wls{c(BKFI_U&x@g9SxZ>0bHLB>ZL;37x~fZRcycW z-pSyf`(|@Lr?c0m>rSc=y(RwiK{?xR*aZQ8K41yx_w73sVsXo#c7A004e6zeyLH*b zg)P7Q$Db6>@64wvB(>C^hG?_>_B5G0_BUr`^8#qw_}Cpt=t3;w%`6w1JT}lLU2C&OpgTI zqq>pvv}F5z7qS}l9eW+DpL=B`;BN(wxC{;P{!pZq!DmrK%7FPb^ z3? z(0`Wb`LSnl08QM>_TO~sF6y`35cID&R)q{o450UP#QypD9oz64rK?N?^Lxw_WwKi) zfc{v{_W%2q3|_471nv*bQd1$#P62fFShjz;7y*7(9L$Bi_?y4H{FV|uKMvY21lPyU z4(Q;}OPe@vHMalUb1EdmYaxy3$M)~zVuP+^92Ab8BF^tfB_0J zUh3Jz^)_JpPYGX*On%(}_m75LiN{;4n>d{{WBxo}`ToD2k3m?W0nGQW>ih5rb1ACa zQS-+?LX!S3#%)C-++Tz9*)dPcutSMDeX@3wr8s{j^Z%IQE~GO42iTwfI8T`~y{ zP+VW|=D)_}I-r*B$HDgtRR;y(CHpyU*$a06tZdU-XVu+i~IH4$wc23`FGP zC9r=zc~?Bnmwv(tRoMPNc3X{_Vrs$r$)pP7@!erhIO$Vt|DRG~(6oyWLH|-O_hK@k z3$^_w_Rr6Mvk6<#R@n}){?~67;^S}oP^p(r=UDz{pWKN)y!{E@FHUAFlWUfNp#Lu8 z4x=Zc`vIZ#dq|)%dE*;MZ6C4y8yr7{IAb-?|LS$hL>L`N^}4bB2kpCrGBpQEtl#

        #0g)6vzfAvtAr1n`%uY0ror-;7!S;tVW?mj#JpPQ%Com)(YOSAol{%4H_zda;8uu$xuJly6fx8U10@%QKT--7ZYkim(Y;QGBwXFNWo^Nedc`geYWSO2dM zjzM)Qk3j!ZPbAcw$I1KIvJ_EaIps!OQ$+uwhFfByYO%5pa7(()XM{vAL6 zQGpIVGe3cQ>B9E^ez*fNURDU^e`k~~-mAEUi@YNCzn^!%_^nxU(bC|vVE^6v{x&?v z;5~P^k?p^|a}jboQ~~DyR*QJNUaA@NpSCOl*?Hdv^M8C=JpP*6%t?=8`!BJNK?fU~ z!1cdI&jhUQ_MGe4m?-wotN%M5B%{8g-husl(|1aw-D?SzPiObmc_qfGkW zT0$L^*#5E7CG=p-V9@`f$;#x^nIeC(S{CHS%dz+^iw8=$Cl8K-faIH^=0sIS9j3=>nvq5YfUhHx|;3(QjHoOb0!?D z{|DA6lja-2bZ!#czx>moc*=`7t~2_QxIX9g|B^-h->JWXX`u`||2?l+qplgE^O1l1 z_x$yL+IJlsP_~8J)FWG*pS=2i@@;$cCg~)2{^M7vE;e^f5CD>h;gLaUJaZAD|O~p4ZfY{%;?N$0-|M za5FBm{rBz}g9M|VfbSPNUKx)S&c5KbZx;LKc>deBC!?{4--G+_8dqy^$P+_4(8lM& z|MM#nNv{7d>Fz|;JGyXFx3c|TIjck#zYYfd|DJgWIo#{c%^E5GdcOZ<4N9bKz*3r7 z%l6;B-zgM6MFZTw`~6XgyqUg~ZvLhHCx7_&8yb~TbY<)it_rjBzoEA>k&9nS3j^5x z-(=oFPK~3$`oDd&GMRXKDSgt7?H?a+Lox=F!2S2S*GlA^tFKMuD>W(ST6*X4`re}4X-o2iS#w3E2Y)nfnr`L)dL_NY5|3iPjMycoOIR&e*v zu-E_Hy39qp28;I3`~TbDmX=sQtd87<< zC+I&eyB4PnG@?&3egF7Z#*+T~KgvWW=1YV5-*cZ5N!uR+`j>M#gob_U!F`Kk`%gKc zL=4Y|fc}TRI*AgdX@dS6Zzz##Z$fBV7k2)ST}qL*%}~zTi0yx{$Y0TbWwgI9+yCb0 zb!hvE(O~|M=&DS{PG3gv$cX*R^Y-sw&uK%&%O->QpKwNrL{^1>^?%qAX}smjT+aNN z*dIc@BtE|r|5GA+ESAw@1K9pki5ebPvWipL%&!0A{X{>1`!aexlM?$CB zqaT{5LH{SaF2*YtUzORTshgSr)i&!_ID>xpkfF{C`xw5NW1Vf%D~B z+v0H7gjZZ}3EThmg{zQ<@E*AScl3zI&zoAf^N-p7=ag(jFZ`Rq{0}XS#|>**xr|`3 ze}4bZeReW>V*3fK|D_abalPS4TDWWeAOBK3|H&np$lqUvTeec{mtX(ypQc1~Mu&p_ zUz;C7p4z>@^?$`OB{C>HlzzC(&i~6$D+5d0X&&x5;)T zay37cPMpim|BQXoIJ;>cS205DkMDoeaV4_(VJKbs^U|O1&%Yma*Z?(LP_UYtb%5de(e||sy`7xhY z3(-P+4Ltv?;uVMMyS8#TkL~|<+$to9s|W8duWO3K!ymPBX&P+*{c<-VtoZ_5|BoWc zNI~lhxW7-<*5D;d#*|y^!SwC2I8${0qbyf3h3)&Msc3!wF%0xQMl1_e!rrF-yjR=fiNe5*d7aIkovM_Ra6_xuv(F`Ta!aH`BO3pC5#JN(7wxY$akf zbUAgH!uI_&O&ZTj@B;h$rw=NTQ3cEC_@V544{cV(ITO}``99#gsJ_ABG|7|gd$x-X zKAD}&Eix6)_eEMs&e!%8^(O|e3#UyF*!eDOBk0boV?wt#?0m0$WrHuY=5l?0v-3Uu z_)JvqTOzbN!tU>nToH)vl&ZmePswpd>ko3EZ<${y_(u9S?(u7OzQ5F5h=vWlE?ie5 z{{H;;2Ui=#Vfm;wPOz8lTfS%|y0hT{IN#&3HxA38*WB61?ESsjBHyl$UxN2LR1Zl; zn`^&<`}Y(2)Zo3^CbY2Fjp8eD$V#7h-zLqD^_)u-Iem}0SM1+^a>G3wU@8BaGqK9-jp*B0eV`eB3U#S(ea0=VE z+J-umRbd9+Z%zW0$js3z=$?;a-~9Z}J=BVl&rSpHZ)lNHA|KX=Q#6R}+uKhXr+)DU z*YD=GN<`sXIJJ1q&hLKvRq=3c9XHaGo!>e&qMyHM1?by%qYjpRxs}tcWBcy$ONrPS zuLSdZ8y3~?1_cuN&0oKdUtoimKg#3Q?PL3{pE(m1rJMopckt;Eh`)GT<2pI^`rUTB zJCfG91kUfdw5MRjnE$v6J$8N{GF^zey}lu_evd>l63^$kzhd!v?RM_x4z}-3o0Vul zTZ6FT;=lfZti;!E_KCyuueNhK=h(iT)@?+$SG9n?_tht%wmILy{W;bG2i0xa!ybdMyFb91% zj8-DuAFiaE--vzl^Lz9A7Br@MI=5jXJHPW^Dv~cHUoL#0_b-2?CI0)z(QxalOHE6pg z+jrN}LgW$O7hHcY;}l7dRs`MrlFM8+i}6 z0PFK%KNU%@=m@&Bh3&h8YZ0CQumk7s63!@+xAGC7@1t_kxUGjDxc?^Gu1KsFM9`=X zc76|VR>j?mBfEJ!hhiOU{D(@BLOU!ab(eaHH$k`Q5SH4J{A34Emn* zFa=v2{LM|c$@V?-cmS$@eG^=NmnFwyYlpX7QiRwyzyH21a|K#1EqcEXkl)sVIDEk3 z9ax_ie2qrER=)<<-<}8J@T5`ixrJxM`)~aI+dTIq6nN^V@XR~*`PX9AW7woflX7uv z|M^urkV_YN(7*oPV|d#LEztjx{@Li(2NiIAK4$qb%*kufrvkSB?7%{#v9}+1|5{Cq zA~C$Pnm&KP_CMo}5Um?JT*5zp{w|_Ik>pKUL;E|j{VT4$jT|?Q2mQy_D3Vm?HFV8u zwtu-XEy!{EOwQhio$tD_iey^-YN{ccQ~b04$-5tU$n7qeN0M^Sw-aVEwod=R{n*R)Z|0VS6gK<@`*WjhccAy1N!kwJ{@M@^Me@OMEtv1o>0NN?;{a}}61%_tI$n_+ z%vnqGU$T8qt5?CdW=3;c?b-Ev{dYw&A$T3_I-c$Ov5zhepOem+=Ckv?xStYvl)sJ! zpJMxdZ~!BtF{1tPzx}uUJl|-xH9i@9f}4=Q_Ra0LL*JUugXd#YdoRL=G;VP{)Wp7} zc=I(5v)s^kyQ|=Q&9jv$czs|ODnr@6qn`OAy#;k({hmE877z3I0Q&A9xdO%6Jq7QN z85kXlHJUzf!FFul-?F1o*s3>RzQ1}Gi&tcKa!%W~i0A8g=j-D2lF*l3Qrrg1e|{zJ zx9C}rk9QpDO}%u*`R>KrUwb!w2hzz_0Qc8Pk7Ib#f4wF0eLv6t+#?6k45|kD*L{(X zQy=uE#&T@`Zl_M5_W1+2Z!iA+{F45&_6yO_Z6hS+=cKUY`S(*sx6w1LiQs%pL69P` zU%j6CyDa04d>%cc3m$B-i0fC!-XG7KsYveHtOxVC zty~2QZ8u8P=ZJSc&XFpT!73Z*g%NDOxQ{M=IX#1WyPfSf>WLyLwB0~Q?P2@PUxSgx zq9Td&v3$Q;uLyScD&*EpWBcvuX@}maUIhJK7cRslb8btlzxjT1Cb}W{3zgt}tg2oL z7W9>-8`iS@2A%Xr#Yfhe&nXv zi2Wko{fbXFN2741ci{a{H7;>DZRBTge;k)5qEfRi9CSa;iImak0<7dZV{pI7qy zUig)PTKv0nZ~xA>@%P7%AJ501Zfb*mM_U|357!95`M96|qwCDWa_YK2p5|GG5|Rco z#Z#22(%MI4E=99hAyZ_^nC3|nWvYbcQe-ANTasCNDs#vXGCs(x-+f(gcb)UQ_Im$) zuG9Uh`*XhE^<8VPEqQ;qNS?>|ZO0dZ?mo%+7Ucf2lewi3-!O<@epQ;Er;GI2GV3(4 z^XNk(PV2Vlvkd7bFo>oPZ^JWdTQpzOwAJLSRRRTki}SV1TN*$=*9q;9eUjJYO!BtS z>o#n@6V%%gwMbw7N+z4{ie8%Bq-R@b^dq)D4-e}=%rryz+rDgl{#2~VkrjdTg$JAO z>9Tl9N|;9u=(Z>Pl6fG z&ZGJH>k|vf*=PUqFPx=Am z7@0okD}R3+n{S7{s?VCk^2xGo-39gcDG}fAUnRplFEv!34{pvU{cd(g`8IMt0Pe@M(fn=0 zntXEQQg@W^dxwjlU%4T=KXu;~4Q}?1K3IFH*5$LzL{?>S}!8sidq(A$y z>+fw#Zo~YsfY#qjH8i;+w*#qry;R@D{0IDe2_r5#^T(&M>+j0@8r<81fpiaH^S@uO z9of8K37@ae_UD$LHMrlW15tg~8qk4UI~Brr=*s3lF+!3blC9KYHk*F~N&oDv!Y#eB zPA|~@xTAbH(JTHYsK0rUzMmc*1UH;Nqx;e4uL&ppg1+-+Wv%{PH2;1&G6wo}l;drT z+x)H2pYJ%I3>Rjrqy4k{?)l`|Pdx$OPelIvn9Koqo}q*K?|qW@OThy@l<&b~ilD=J zBUHb+tr{HoY^5O=*?b!ppNDq0%mnkTfg*h$U9Q26&e%#14`cJ4W_26JpCD-cZCa_p zSr%@k=kBxl-uCMyL`6?W&$sRj)!>HsZl&%$*?cdeGQ_!LDc|lQTi@$XYH;m$ZKZX$ z*!u2vSBvOHh4OLrt@CLj|K78|CTArRMD>l?e4kliLWWxJM*aI7drj_5w;-w<%jVna z5P(I~34wnX^L@8JM|L+JMfu*?Z4%_Jp{Tx-#s%a^YOR28v40PK?+QDnUq|mZxt9?~ zX7chh?f{!_Lnm)2Ie1qv|03>>pKuH#T|B?@i~6(qesypaXqHScX*ah8h>)+5G?BcpjF>4i@BZV*dZLI!}Hl{6mXn^;-NrFUsG{Ybs$w9f#_B z#&!*^enSx5dz;Pw-%BqcLd6w5-x9J%gR=+wCm?4Q{~U zAR1!Ao_`zrUW>TrhoSyHqpK#T`YnjQb7J#f-qD1d=(>j=B*0qM~FE^q8D)ps%fkm(9! z`wf);y3{!0c}#&$ZesIqI?Ws0M%@?WZ({y88H5qf+8?}AFE;eJbB zZ2ptSCBu}inyA13Se8c`YV}e6pBLv@XovKTDnG7Zkr zA(#%k$L4@EUdr5;kk{(QN^kDP<>UwWd_G=H{Y{TaNqs0H*$_u9Hi`e|HEwcsxTc=9fM@i>j zLFDgmg%A?@{Wzc6pIzUV_n8QzmY0>DRh06d4#NEw14|c><@@gOT??iBi|hN}ajvke z-7PeKzn&OJx@0QSMcgB){)+aqzfscL4)h@C5|ML4BBn+?+@Gq|Kr%gLT91Tq97Wd9A`VS)gAEsXk zojZ>~_tWYQ*5Dd6LTLO=HvbDxzkt}0?r43lKj6jtY_(CNVD-zvX1nc2LTUoe-=f4ZdpSRNIE z`v1#A0NfMLly+DpY#&vL^1s0~jx;Y+qDceT{96Xi2ma7Q^n6>^rBEV!?>DOdn&tlRL9P+4 z?=OD}B^v$z@DoDV{12P46>Jv_GEN|xZy0Xu=DP4(%r%sA!eP3&kN4_Q+ zP_0XB{jX6=hS;X|e9vq)|6a@U$mxd$0{+GI|0M1GP&cg`>i;_q%Om%)4QSMFw*G&b zUI@(4AUP z{72eqk@<3wDF1E?G`N#PLs9)dJHIz6c#?wVdxw%WxIyzm>7*>S{;RmzLO_qRf_zWR zf2jx|E8Zm%wO~tl>dVFxx_rykgjTC^WRgw5WG+ILG@o{w>md@aVYJ2h0VX-taA`Le5hc4 zUabG;kLHnraYl4qB%A+JX}3UmlRe6R?p<|mYj!9#{FlvtAO9Di)7uNp|Kwh%bLK}w z>Dc9L{g+phA*6qkMsY&xjpH8DH6^13nyxDZk@x>`J2tAy~(&+sVM)O zTr{{u{V*yM&E`K!-4+}?O9cD}iu`~04IqpBPow?&WfLdBe(ef@|JNcy|G(ve4|$vO zi2s$r*8kmEE@1q)3e|sE#W>M}HvbWc^Wlrh6Li1b1lLd!`L3D&p~mLFeyl$< z4SbLK{}VexiI=$yZR1~@??lYm?WkbCmB{}u84(RxkCf2*Uv6(M z`5kLSwcMohH)8+4c2yE|N$-Hx|HnV(l9DGzDF4&iOQ2p1Oat>Y{946@RiSs}G{p#G`h%hw&?-G6s3>3$s`Tx*Vb#8QM z80!DGTzn3_#?L_ge_XCQrLGCV(0&{_3E5&MHsr@cI(^rWLH%b zI$x{)Tb(=mIE>b4v;Du$mtJH{eHxno9qgmQO;rh}MmyR3|JAaE$(85O{BM9KkYK+v ze5oqi|GO5C2Q%f%rAxD<{$EDK|Dxlzc3g?3eDy=3gsiCCGYxK=c0~uTV0sNrv{?Ak}{{|9%~| z!sT&)(fen zoXIz=WcT-*mZ@__v%}H-c6a(U!&UcnsQ(W=q0TjCgi{qOw*S`(ZBO28j^=OuVfX)R z?x=IKE{0Q`0c`#&&-WtQFZZGK|J?u7xixj+wA&6g|4DB~!K_c`OD)aW^?#=UKo$m_ z<^S}Q@-NI%fX& zHhdm@npH2D-xKHm_P;_%?dogCVgr><-LH;k&fBmabV6i}jA99|3zQ)fem#DAoC7ACK>pxXX0_AC)Q2lQT$|b9B z^+NgYW|$6VHS`7NXT|5^^QYvJ`zgKXj%K$1|Lc1QN?!Lz`+u7Msc|1}g;TGyZ2zAU zTms>tBhd3Tj{ViS*@_XA(_`~rd+sJE^_z(L|35^Xo6sXd;Qz(*_p4?;hg&+c(fohH z6p8=u7lHc!=9ItSvM~Ui@0%1VdH>CfK<~Fmo8O*{b%;Uz|F2ASPJMF(E$_|d|IXH4 zo!~oesq_YtjB+c~LCcb4QKl-e>E-f$ThZvi=#W|B;m;ByPAY zs{eo5uY~(1|DpAN&f5_3%~_U?vt#q0x;hX_9cB1o%5CTCh4;^`KORboy2#OubEN%$ zasBU~6$MVVs;K|J`#y&#F6oWt|HH5B05gNmX#GFfE|*x8_D1<%@oFFFe#7}sRn8?w zp}o=mUwO|%u<7mq)cq}J(d z{a^Rl26jK^1@*s}f8~R=WMR!YwEx#^H6F;%Yl8m2xc>in#G70g{*3?hj?MqKsnen4 z-W~LOUHpz%(s*B;ZtKF<|4uP;!Se2NH2*K$5kmBpA@(P3tquTM|Hf;XS-VG&d$I7Gm-|fgK_+ca2FNyU37N+Kqxyww@^Yw8j zcEBBLZS;JttU@m7S8amw|G8`*EYLMT=l?>ku*i-;^?Iq`H)|IsQGXUZF zo5|^F-0ZkWwEln9p#(}_TA}={J+pw=gzA|q5Z$_n(c{~UM&BCu={__ zlhrx7kx{hJhOPh6-;GIj_5rm2Z!}Y#s~aDM*8koyHejlB0qy@6&#)!^I+gM^mQwu} z`~Tyw$H5Q#8v_2t_5X%=Z_@qcbN= z{pPt4pYl@R|3S1Lr@vPSd2(NlUT=!lLeqrnX`1MhsG(nxG)7$EIVg3K!DTgdt+Xt=xn`iETMr|F` z|9ckYkoQ%6Q2u8G?}KUjh64V@`*S93ki38P^`Sq%vHgF+jsm!^ISAGNS^j6qqXi@B z*NE4)|2uzcK!oRSyI(pB{kuu-mqhm4I>f7SF*~Cq^RI0F?>63m*&Q8F{!7x-xSGr; zRR1@Qe+G+2&PUJh{mxV4nvO)#wTs#Lzf#g4_&ItrI{%~iT8*3kAquVkb$Lw^@gWxV z|GzcWxnG^5sm2gC|0jx!$-caU{3CO={+}~a=c4;YQ>_HH{x6$v1J_K-1o|(|{|ksM zIXZ&pXZT9_7yJKn8ROv4jGHL`p6=dco%u`N-igh>+^%WxaqNB6|2L6X@+w)Aju^w{ zKk4@zn2_Fp`v0b`A!PAdc`Dh{(ZYYAXuoyG$9^znO%tmB9an`AtK0Hu{(s@e78r0r z7S;cEX`!V1F9rHso!$SBH;Mv}$Lgs5|254aBbM|<^Z)1eJ7Can9aR4(Z_Xih=lY`j z$Nfx$`bQ9{i?d#5hlKLn?e@~q6YtK~U z<~l^v7=1S1dq>}ZK9?Q%J|5>=^+T=g|DH^NuOwgajHaR2*!n)O>oZsu?Tzlwxwln~ zQ}&Oh16Q#5-fjB_{*&yt!sh#bo|C*E3Zv;RTXw$J5TQv*bL03GYHWS~_En9$_%a%u z?{$qeCfidp(E9$@8#S)#K{S22mCg6MNj9)6=%V2Ko|x}x)uV{nNGi~GG2b1G$3gM@ zTY~!DK$Pz{DtnV@I~#a!PbuHxe80|a8qC`M0Ofm`SqSltQlP63NZ()L{k0w$b3n7* zYm{%3#$fWVodWfG%H}&~uOEz3{*Ko7;X^}6NW21-S;^M-xf`~?(+zU`BO|uIcdQB_ zpG_61tU6oYAD)PW16wrsPZ{idZ%AD>QJ&e4R(50O`{!hK!1C%Y==mPSQ8|P=-w)-R zdzl8IG9FDZasgUrzLd*iPZlC_RzwAuS{i@x(9)b~MV zXJOqyTa^HS`%Z? z`)fD6{SB9P2BPQlwKq!mUlW7Q_uLwpvJ8|7lZoy-{-Aiopm|t?=Nl|MLL^Y;Ad#F^}W8y9t^iv3i|tE z{(Um%lW8Yj@hTwYU+nL7e>ua1Qx8%8&sGMLekzLe*)Zw9Pt1QumpM>B>VYW4i#+v?LF1FXRwXh$g%m~uVPH{e6rB`UMWhAGxpnt zp6{_NwFciKmjwDR&i6)eqll|p8Jh3;W!uBN>$e5`i}Ssqp7Tkp(Hqp?-{hS^MZXTs z_sZ&LgU+T#G`|Z?4JHm%ih}wbME>3L^>RqM@)OnfMlwG|NcaDey`x*X0UuN zkJj&9mPEp;f$hRy(g&dY{@9!bvkvq^`L&ME zCS=I~G@q9nn-BLh%=tf+ZT?=E&s~({3sVQ1(psPUE&44Z;2EI_qP?Q z+~woj(E8jV;yOIq>Wtn$bMk>I_uo&yE;UfR&&5hRjNO=E@otix~ov0Gb=ZN+DFE^iX z7aI8)8EpMNKHM4RSUfIGwQtiuSwa1E%qN(X?Np-nW>Wo@Asq$(T`O`n40o;1TceoZzj{a4miM3My4y3c-`Ht?J;qOTW z)W3Tzj)ZO_wb1$7<(Anbf2t{}&pq9@L#IXEP=9V8mQ9i}Oi{k$2B$%JWN(2#7x&+- zT(Zd&e^a#nzA_*mhTI*@ziW@=?}KtkqvJq2dW)3rbdf(-U3><1ZQ#)S?Ouv1H)=;L ztu|xV=QoyLhvKGbX#RG&P*t*jE|!jdDAi~2evOo@r%-#!7tP;nCC}?fo}aap&G*a; zzd)G}LiKrAk}BsL6N{d|AC;;>mOV>E&)-j1RpTP$fSDc|D!eUYp^+;ONz^|@2UJn};O9shI-oA1Ip zCooQYg7O_}7)&P4P^L8NyY8=CjMNAvf|D?^CKX%!mQWqa%UNyxWOujRmB z{e$ZFkW3DQ5FM_}wN5k5okYUi&KolAdd!`knJCiA%7m24urejuvfna}dT|Kkvp@7MpGhS6I`^G82R`4{W+ zYzI|NX;vIMKlkR(HQ3O{1+A|&*Q#==5pneLBR0Q=XP-c~os0SKN2M))U-A7hQ#+_~ z_4;x2xICL*YlB~KaCtBv7tZdVk2X-{rVomvX(8J zL-*e;w>2V>9=T|K?)pWQi%^NDb_dz|e3x25iRM+o{jg$w4-d5=pSNE^_4z>XSlA({ zox?Akkn$nQ*A9ozBRZ?z^EP|g{F*&*f@0lzw13v4If&fqt0K^6M-jiqXJ)~vO&Z}krfe8SI`0FH#{$kT(KX7^1H7l5sHoVQ2*WIR~E_MI|${s>#s0kwZZ&m14TdDqn zh+oa?vtZbePpJN$IU7Xes#FC1uXK^WUg5k9%!kVG*nau)p24JMq$6;3FCiF$mx4Xn=5sexD zpz|$SetGcugC%-DOooJyvWM~1_knc2Eznk&e|!6!2CvjHs6OYlQ{^%h643K4>Mqw{ z<3cy|e0$Py74H4b4qPui z=+ve!g7Q$NuF9Hd)L%yPuLE*p!6oC4p#LQ!(&s&;bBX5jk33z&=KD?KRM4<^j{55l zc|pYauqr(}Mas9hetz9&7WC@>A6h@VJz5Hb@5u0H5482Cg!enG`Wi$&{Z*xH`>VwD z@!X`1aCDC{s=pRXA|P)p^Fv%iQ_07=vw3n`l@R0UE=Tm#cWJ&IyHADIR z?UD-dp8e4CDR+Fc$QvIsbU&TCTOMraGz`_>q$4Wa`9ldb@j08{j^j_mp4zd3`dI9* zJ6~1dk}49Y{t$M3Ja+Ik$Uf_i*2iwKDqKQD0(DK1@*6?A3%;P~BcDKN<8oA=-QTHj z*WM=3DM4(0>l%K5{MJz3brIWN2gEjz4f?C8{?n}1{aQT)pYL=hHQjm&MGLsYj*~dzA5Td$DDosEMQgy z6j^sh^RGYOGl`mkIpv$!`zIF4C&JV9`sn_dsh(M6eS|s6w{CL^sP*cP`s=?Z53ZR5-Vk zM7nSco9|K2uR=t<2gj>O>;d3uE)$ZT$~$ z9~8#hc(D1tQ>Vhk-cLm5Pkm$5$=C16X#Q1irpg^Q-;Um|ZrsO^^mtIfn}22B-!{-f zl{2&4P7}|w`QE={B+Lo9iTdvW1FXr)&eu@BJvxnnxYB!q{S)GR+t6Vyne^f_|Lr!L z?{vSZ@aU&xeiXUiMSuECsJrw9t&i_I1raMJb=tN+R@|T3KX@tRxXPmb`gnd2nRY~- zF4M4(<|m^3TIcZw*l(_i_NUytg^;2VnpCGCmU+L!(O=;(^uNxie(N2~B>VIRQ@_*f z^W~pzCqS2gp6GtbZdzGnbi!bi?|n5X5XTKb^?TEkOfqHWV4A1E=6h{YF1R)fNAs_~ zyKBj#tv=Kss$GkI1&Z=*<@Kk)_0Bj!eJ$4S_j6RZO)IxkJ8L%I>Bp~vtA`i5KmM?< z3ioKkc0s-^uCHAa9>d;(l_=lF*(%(&lI^rpA)D_v-G9IvnQ&CU4G*hu121i-C&#h< z_k5yGCfwYK_Maz>t|T^RW>H?DsP*@!FVO$WKL(^@^C48fmA|QQ>K%8`h_h_IA0HYC zigJ|#{~ZW|A20J=!J0ITzmD#gNc(07Yjht7@-cD$Sx#{-nLP3CnMmI)YnDKPf*i{K z>Wm;#uvdecY>@IVK3_gJc>_3oS4H#fSf@jnR3{d`0{F_OlgNLB}E6q)TYi|ee4Xyj>#Qm+NluQykZV0+x?qOsu z=yV;4`uAX+Q*g6z^VocIFTO+VwQ#gQoww#5xzlSgElfyjDfs3{P=)> zXMkDyH*~)2fp!r2DXU4_?q?L|XB#q?K-hgb)W2uG3L-@fnpD2nvgQ3^Akz0J(+yxy zqK5L_@oENHoHv9fb-FxliUaETs>Z?PKzP{;V2Nao^1^O=I`JRs^YV ziU*QtwJ&=a0GtQ8}xqGy&IxQ(D<&jW)hqKx>YkE<>z;l|4tf9 zAZd*}s^2@dt%uih)zSLf{!#{+_tt{Cy3aLzL~@&-4f;ZXxUzHJvvapuXsNEvRNi6n{7!Qwb=YVs>*@I->uMmJijQD zENZl*=^oPg6B&^|U$pTgy!|s#px@&DSEuUBnZ5_DzvnJe;cSwVY33d_zh3PONT=k(eC|a=zr9pA=ZIu9 zUt2YL1pIteB{=^j?qA0~7)k2p+(P@;AAXGn&Es_fe=e@SyVT7l5tcvD`up+^2QY1D zMD=^otOyeEpAI$deYZtFWk5Jz=JVSNY={3u^YNMbNyOwwFZyC%ajU-<_OFdDEQUI3 z1^(83cK+t8ydE}n(Lm?Fjbbv$w$GMyvyzPT=Zo|?u}?Sz*y^I^yKa+Avi|H)`f=AJ z>3%2B5fn&sf5pSw_Qt3_TN-7OBfEwQ_!i%v-h6Q{+94KTN(Y z7G8m|edeHi{~4mpb#O{X`(GQrKY~G**P{E~W{gtiHq1z-QQg^m`>g&3{oX{P`Wzpx z%zZqWO!qgj=Tj2Q)yVeud-!du+4>x(r^5Z6x|1&5#O7P;WKWV7e1s1_#pe6Ii3&G$ z#!gAT$<}8(?Gex{UybH#-06{IWoRX;&xS`vgVDvuDBs82W|K#f`%QW#vg_{+O%CAg z@eaMe$?tDCQCZuC{&V3@3qK&@`#bf5fuX-peZFb27(6d1p#87fvH&=HTLabS@X|0C zdR`YjpEZB@5%OGb43#nMZY@2(EaY?Q<9PV~*%+M<%ibrMAKf?-<@4gkz3}MRKWP5_ z$*h7D_|2fJPVQ&&d1GP@BtEl2^*8L>3D7l~g67-teQHSl%O%vnlFi@iF;_r$!Cd~2 zopioS288D?SFcv)mPhWSsb8e}D(+wX8<;7>+$|Cz7pUO1m@hR%n)Ty=>go6e-J(QN)U%jH0Q!zh%$tM6)v+S29J zTwk`eeiP1z9NTsREcG4u)J%4MbwS}S$-c0H_8Mc()W@SAF2kDCc_^Q54$7R|@?F$Z zA)@7ZF`sYs9>GPu^=N+8(W{2UUtLD8J`ZjEd_93bNM6(grv0M%B26}*SG1J5(fxLz z_nX>Qs*(ZmDg2FiHlL1Hl{tg&yXcrqHlK@)dXl{1NBN#R*nFDZQs(0S?4mZm*nH}q z8xDI?YEeEFyNx7;d=;vXFBXjk+1>R5KA(v8pWmH0i`)tR&0iVF=F{=v6qxM)0i6%= zHxDA~J9nb*?60@*A0gEFUO2|L3x}_2&!E zPsEG}fFVKc(ftO*I}B_$cSGyfrOV?%^I~uGegeH`7l`~RPn6F({k^cX%v`XaM4T_J zpH)sGgJ#mfBcyx=iu~*7L)nn{&=&0<`AYJoDce`j0)IB2amFVgqN^jHuvyBd*uQ?5 zUqcGF_|e!(wthZWyaEMNym`s^ee3&8sGr(>l(|h#yXp4MY(Bq#c?ix$8_@d+ZVXoD zvS#h3-6&f>Z$A49?e0YLYd_MK&j-*D@H>67GUvBxH+5RWu20kUs*+wyQ_*}WdAl+< z_4;nQBah9eaiu3AG@;`qIqWaTcIUcmvnxOTkT31TWkHGm&$lL=4YX_tH z+R5u8x%YY|&3&J4`@hc@^J}#w8@BufJRja%Ltc$rNl#g``R(`TI4IAVisnllR@D%H zo0Zf^+pJaJg!hM+th)@kV|{p=ZESw87ASFn_jU`;M~L&K4>KM@-|~&9z9vfiudMAJ zI<1n;Z@$A<2;LaO8eDbt47)4n4~hA8vmQaRBC7dw z$ED|+#QCsp1qXxgJs0S!c>c2Jrw1`^{K?Ne2fCRK5$x{~>*LNOiovay$8@0tbtj3aEm zCKM`hB%O3YI}BmyJ7Pk0%~h$(k^LzDg#3QYSR1#s`_u^ZK~LO zUC>kJ-i+T%4KK0zy6{7V{3=i5HEh{@sdiE37LDFZrzNrZDzVomuj+8VmRTrscjxb= zRE5n~)3ad^seWHDUm@me$(rHB(V~VgRg>~1K0mn1fP)DYFVOksW#JxVv(0b*q#v8F zi#I1jWxvlTUx&X(l2W;z^uJt5wkc>bBUm;1bvY z)xQ;&UXjMCP^zcDu7yu=eaWv51+QItd_Q+-|57~PoM{sWTW|E?lPcT(yYPO!iKEUE z&j44{zZMPJ1HD}>(0nIz2_+G+Gikx+eJ%PY=5u^a77VQAQ2*Mswu%f5T1hv1v-y;p zdmL(>vwW5P3t1%Q>=fFXFPxer%eO=L6HpBl2kFX6pPps`dRK){3cV+9}Pi19pu1gB_>&E8OA!r!beYlU-mp8f& zCsVX*`NxgY`cBMeg**rUsW+hKi>}#wkj#yLctbep7iT3 zHlOdn1M)Yw$0G6&uFy&q1kYh40dv) zDobCr@C%~;=2DI0@Nm&ILB1odAIpmWCEtInqQCdD`MYzw0(PkT^80^C`4Q)@?UyQX zZ<11|=1?hr;(TYA@&j<`8i?|DF!l?)z7@;MS+nz-35rVG@}4QQ!+-32wSJ!pc@vn9 z_BTRqD{*I3QmOZSHeVVAJ;=t?ll;_)Y`!+%P~vnHQt7PDY`$JS84A(Y9-#e=W8H_5 zR~u{jr*Eb8nV2t&H3YJ>UkUV2+`qhc&ViJ5`OMFl(RRPLus%G#b28KpXewR(v`xQc z1^zekKqTov4d|kiY`&^KxkEjXMfETIbu!U1HKRoxr2bNT{xM&o!^7)PaUSJkT}Qv{A3Td{(Xs2;-c$P>5?iopGK2= z5VO!z{A&|7pF8&{asPZtrBTLgJ~z!73LW=9M9=RGleHwveQWsaf28N%#C%GwPk{AV zuS-=HNcj@?Kek+$Oo}AucY2JJ{(i*!=W^Fh0;3g8r4EhK^Ys8iJ~J~SN!oQodTThl z{yQ+v9V(B@@-}OvpD)gDN=uFto$1r*=PU19{iSfepyI;o} zBdyO1^PTj`Yv5a6C)D4LEvLlMdmjDo$k5j3wFU2=VIM<4t$Rv@fA|O#s2oTS{8&| zAA|N!e!sg-UfZvs7gn+PF5i9(G%vdd=KsX{x+I~BG%Bv8#qMmr&-qorv45BFaz1VK zqcETKx29xK`CPijXbO|>G`suY<+~Nt*JG(A#9-D8x+}xK^?9McJu>_=Kyw_ga7_CB z73Z@L(iFM9*Hh_EMK<3-T~vrdmjfu@eI1mztUYOT)m1j%RVF>i;fT|yznwf&iSsB( zqhGtT`R+bqD5R^@q59iYV?nymTHbrPl+?c>RSt&0#+N-&ede2w5sP*% zl$RUVlHWcN@jKEZ7RI>@K=s>s&JmJ(ekxkOu9Mphvd@O0^ZSd6i^-aa&UDX!J+}XQ ze~9^xm7H4(O&yEwpIf}(Hc?x#7Oh_g*c^j-A6!wsPyH$)$GSRF+df@e`4Z;0O(QB` z?D%E;kQ6rGYpoTzyp3ss`ys^sIpNzqm}eTq_k1t)-{Sgp_|9rF(|iL}S7hf)>QDZI zB{lJAzGS{Zkqf+(Mmr8*^R4+vnJE1|fabS{J1TKC>-N!$x7d7tuGb^qC5K(isDfCZS)w;Z=Z%)5X(b%`11K|zDK7LXngRt^uYpYe#(pbqaB8O z5nWd~>Y&2zkFIi=1UF-Upyzk&`$ZD9*~WB;Ih%j?({AuePadsb$EzGA*P5o$y{3(= z{0aH5Te<*V-d0EF109@Bk@k}Q$LNNGtnL$}I-OdVv-xh6+>6ju zXpiPo?iX(p4bK2td4#RsW(`N7ca0l5pR~xMh*<4$q_-P&nS9sWyaZE*FXub0WAlCF zRW*t4w24MtoYnHYmgs!_gOGdRaX1Lo@0EQiX(;lho$Ui!KVPWd>MQ<(t}7GJ{>&-u zDzfNo01f+*((-&D2+!}_305XKu?P7Z#%zB+`L!Z<)HJSB<_5I=EujaEXbQHcTxS;9!(%n?Y)5SbP?ZOZg`S$zvQU744dzr zbrV75$WQeAt*mw=@tfC+M#r%E)(Cfl5t99_n7+@rSU|qLpF)>cKWX7pTt8p9ku2-y1?qWZr3 z`%SX>#9Df)u9E4`XaCp+9kd6c`B?m_LSp-$Bg%hj%q}>8cm&#??W7OHekeH#dfhz)`(?%c-Ny1Z88&A<{XKx~->rNu z!Br1G)W2U1ROBpc)2Z`fc0Oi4;T~A}1@ou>vh{t&a|P~r_jLMf4ZA*n{qhr-=_T@w z8EpT)Jxr17{wSToEw;WN9;HmQ-7@%rI&A)*r(P$G4Xdb+*WuRphwyxEy_Oz1_v0+z zy{@A5`_*1h|1GFc>P>U+viYy>;|8mO6;S@0X6`4!+d0~4 zi?shG=6|`b4{YwBiSqw?UNPy^>_R*IO_9DoMEj#-=B|P}D|PstsnYrdK-k|^vpYq~ z)MnDFtNOP7eT4iw%7wrvDi-+Rs_kbSs<_pV~=f3blgSH5sR zy)&N8e?{ke(AOjcJ^!ttX(_Y=`TmSt+{vZD7PQG?N$7>8>`+M14irl+z`>C@H zoBvDtmauzQJ<7jPswAJA|A;3s?EciOZIXIu(MOd3clSKVJ#)$ZF3A1wrX>@g{mI{@ z+Ny2*2=h7J#t5?8*M!=PZqsk!`5(0?SNPLK5%u@h0sBd=j-6ybxAcAsG5;ev_<+u1 zO|*ZtETNFhf9*`2{B|+k*#jXbx(wL^o@`u^~zo$yb9mB8Nv2=8}t2|7Z|*1FREW>UU+(R_&Uk_?!% zZ35c=sx&Deb$=XbaN@HTzIjpqOH<`2T(I;)&;K+QH<3A!N%Tp-aV_6(5S{Pa-&_u# zditY$e;Rk5xHS0Cxk{5;o=*p1{+^w37rxvKLFcdTDt&^wxb3KZ`&lY-IXMUD4~2^@ zKi`oE{d;bK5*hzAlb`rb+8>euO@aO%nXbs~zjXlRS1Y+YdGYZaA1uq}ckW_E?#}B2 zG~9vB@1YkKaFISk`^%j|Es58mI^Omvn_s#2wlK`}lVCnFP~_h?ulFF1w{U*V%_cx` z=AY8&>+F1eeNhB){ihGgZ#yqn_*AWk>i5;-2gsf3vDE)wYkym`e|FS5Zy3I)J(|zm z|F3{_9p_A+9!qBO>!0iohyQj#=d)gXEhc++deCY&gO=yT^CJs(1cUMmV|2bUJinNj z+IY~wTs`J|@cEJzPCMa_4MB@yg8z-WCXY|V_26|KJ?WXz`zQy|Ox33s>b)A9M@Ava+$&eq_LU4edg7|U!aKZhn?>NaSlcExlQpOL1n09zbvB97e6X+ z4qgZ8#P4iyEbtzWI|NUl;RjZ{|Vl!WC)T{mf#2{!?ZG9M^9a=yRZ` zf0h&-LH-!_rG|lQeV$k50=YAlPsuS3Oz9QUNX7PI+o=MoINkMu(MzLa>B%(&@Ap~oC1-{qfU zV8~iCv_7AwQbaNU=i6=XPB0I$LHB13>TsCE2fNXi)w^5x6!YD+_8^>FKMCdg%a}sq zGu4H5`TC;ed9i-m`xisZ%$aC??!KFnn?IIP*9P`{=ak3gpx1j1-+ecmZn-3_?8jz?OJpP@_yiaSHviApMD&q#DMM3m&<>I*>yYkq_u6IFFgM+phkgj4>bnl0O(ANbXc+$@ybpZtbhpZm!ua^c|_G}n{O ze|OFTR@{Ao>ifPclKegS2~SV3^*!+MD2RXaUuo}fslOKUKkLBl%sZ<{^M7&wJb!8mxwMYZO;g^*_E!UWb?nLZ!y$PorUs$JG6+*)_14XR?_{N z;{6;|E6QPRhqb(9#I5D;1ETZ8kN+zoxf$-X?^MF%|Nf>sFfcO=_3z4sA0Ra{Num#J zKVQiA%LD~(^|uWAL7UC@@;i!TmuwC{AeYT|x04FonBJN6s0Ewv(Pz7n&_EvL`$eq+ zw|G(}y|#eO_wphONUCfoJ!mcELk0xpgUrO07Q`m;DQ{T7=DRF?6s$G+g6eydjXRM| zQlh^ys#|~m!uhpOhw%_mB;=bH>H8AN`TUwK{pg(uQohCeH@@_Afrfp`==@p-gFVFR zn=Q4qmHvLk`d;EWALg#;faY(qCiz6S{dAfXB;{L1#P`T4D`B;EH`Kp>Z7e30hiB4b zFAQ7${bK*V;#m;n^)^BI9wuKz)bC69p1tz)|M(X7*EN>Jz_qXD=zPpK?K~oPUeX`m z-PKmwAMYag0}p(b46ELa64dAaZ+<5A5V_LBjRwlI`PQ6%5LDc!pnM-Gk-T5Fy3_to zUbcL`*uVEoJ_6CQv(fp~e3K$lBJV+c%%pq=it6(KQVtb!*6{=K+xQducYXWgCT>Gn;bX9*g-77Cr(+ z`!_CCPKQz#6+wL-2*UFjH_djDihoDZXg9v~d13$DKyf};4C#pGYpbU0BcG1i(|;Vp zTAvs8&tKhL0p?XW-@7{;BRhA`q1Ib^wLCB8J0dCwOmCZ@{WZnvLSm)mNo6JtW$L$& zW(=$;8jR|9ntLw!Gjf`M??BOhfl2U0N` z?}VF$WQmF=Egs%rEA=13{Q`I42)yq+2j#nJPLX6j%aiKIvibhE&qc`1S;vnll>U9i z`dvM`h!pMhq(AN0`u*ykS{SrFoc|QS?yoJ%m*>v@%%nfwu={HsTi!!JNiwe@$OnY_ z?sih1OI69DqmtS6yZJOlQW~AhNA8vCk2s(E;4abU>MZ(T4x9hF-(5+E4j1^zNo@XW z7AtV)-(=C1tJ(bTQ5^zRZ(pJFGlS0zAs^{8l>g|%HgI856Uskb?nYj{$N8VMemtaZ zljW(6)L*2F^nJ$NP(ph4qgReRY~@dwuh*`h4qO*ifqxhCzhGe!@yoZS-rw8&rI3G_ zG4o&w-x2lisY}vG(O-KyC_c3H^M(9(_F4hiyStpiizG zYRS(7Me}jPo?(c!T+wyOLy_3<~G=w~^d(O|IY<+)q$_75yeJfqjAk}BFzF$*x zBU8duQ2%}a#=-AoS%JQb`Hn6KCPhp8(9A`5rF@C@6D%A*9d`b!%J;F8z8}PVpR(IQ zF8Nr~q9xMrx7fd{yUzoM6P?iWC*eh@ANHX59qdBrEO#Y1mqG8We3-o;FkFPo8!ZsI_ z|8^Bg5a>$K`S*#-3dp*T9<=}4UAF(zXK_Afx9|Wwn>-ce|AK8k(OcM*H@*fk!*jT_SGJykCx-x?q?SJ`!gPaid_OX~cK)1iFr6 z`}+s6e&D6k1I_0~x*jFB2YAy}&20YXe%cBJbNZqChq4EqA^$yIO5+cjG5K#^5Doc@ zEzx{_Q%MdnE5!3T&+|#(n8=~^`@xC%B>RI0eI766KV8&cw|KrEb}BmYD%oxRNq9fI zyIn3(^mLQlCIJ|7PhIU}^paUUEfO%lldE?~^3@ zU-2@B9z4jNpYd+2hU|5by!#@y{s$krPA(n|qCfOPTi+i-{eL|89oW9v#rL*i^AE}L z+~YyHRAC{zzF)XYf$06sNAtV=LGs*d?Od8~&E|iXR##Gg;UcfHiOs)ejXYPrIhWqs z&E|jhh`}(=`K=(I7xUj-KA3E*e~I$1yWbi#GJl}{-fy5Qd2mjZo=ar&zkR1YoURq} zFV_E86E~3Z2ZnTXH>v*+^MB2J8pJoK3F>=sK7TqUf!IyAqH7bS{w7d#e`NBjIS^IY znNOV}eLslzpZwjNO1|xzK%D~E{=U0{AEce=f%^N6lKR%~@@(oB(WB-2DX#A?ZI$p} z*AG2EUR6|0iVsB4%6qEP`*B46f2B+`C@2m^>-$r0a*1J>hd}?u`vZ?GPJ+Q+qtX2< zCIhpHuDmNA zZX?^C4Wn0!4@;jH@jt+O4lK3P=931q`M>ZekyH&DMJFwi?k@vTet&7sae0?VW2d8d@l!E@K|NnhAm;9*kq&1L zg!?7L`CgS;64Z6JL-RfEOcoha=1LFUX7j&i>weHOoQC@U`gYkQtfw1wJpHug{UPSR zy-yJYDfsZ=t|cwMAMyOG=Y(wXaHAX58Ku+0zc{}SJ3-<3-c5r2gkt@_RCkEjHO;1l ztJ(aI39bgy*HLJGUzsPz6?e&_b$!_Wf4%iv&@tPC`u`fq`=hsZ9{qluUH>0bRv^E; z5Aovz+4VnPC&wjwj!cD|Jufd)V@@s#@=lHGq|x3kS)*4#Yy#9 z%>NF*b!1uxBWm6xo!=Mh|07*z*z!Z2$M*Y{$V&LH8AeC0DPr=kJ!%eQ_tHV9 znNRi0+5TSNq8fUnMWg3qhK-fu@{Z)uhGw?D@A};c>y-DR`u=ms4Kg+?l-{yPZGArp z=W7?=kSEGkh5YMnY`*7rm*fkV@@dt1w!T}n*CnUTD|jmlHs8O7O6r@}`Sie1Dc?^- z`wM%%Hv@|v9|Y&y#rl4YHz(uXy+-xDqQ(jwT>hYZyKJ3K=Gm*$xcC3I@*(WcckDbC zICllUZNB!2D8G07vzjEXF{Ifb#&>I8RoXrO#Mtc)R9BZgCpH-${TL#k#& zx2rhcKiy@z2wU>$^A|S=>Bir(T9oiM<2TRo*|R(#J7QP+}RZE z&u>|fN0v^SMFS5$w)&sGi}`*qEDFA@9FFq6W_UK4*IT&1=KtyY>>c2Fbc}#+@%(&j za3+arbfcxQY`%ler9*Sobaa2ss>_8ivDZRgV=-Ible-j=k7c4Mb5XMM*@6NcDP33E3lW zduP6F-b(qM-|cf=^?H79&*vZT(oyIBdR*7zT93u~_y42s9|ahDb&U{E(vY7^>+{oQ z9>(uI-AR`?QQztQyS%7da7bf|P?+8DyoSW!_DfTfpC5RL^v`DNd#CB|VOeY!fjMO~hidx-4*$>zVq!?u`cST5|HF7hD*>3p25 zwW7XIc8EMKXY+5o*cATh`B`!whvvU_vKgMKdB@fF`6-sr{Yo9z-#hI!8DEBLkj>56 z{1d?z{4^U24f|{KQC0H$zvsFTa~|rGFRrEa?+=qQhEB>UVU0U+B3R=XV}L z2F4t&e_rbEnS%=?FKo;8_hwv-#Q|nEq`UrnCjTiv758sL6!#-J{(g?#5gcOeO;QDY zCjVn*g~EdK{kZ!6J2@K{`MVL>fs?~n@%_4w5inrtP%i(Dn={c=XAU>NAM6(gLpqP< z&c|6Q?&Eb^H0> zF0{+WwMDMPBaqF%FiC)(ZlOZ|6%G7K`LA(OlWW%Ve?;WppJVo6!+=Iu=!6Ot0uqj z!f`Nn6ZOyU5l5{Hu!hPs(BP`ZAmU!-Gws+n6t0{dZ_-hP^aDaP|MsEK7JP zlL?uIVt!1=_iY@VaCw#n@$7uFoGoc3gjN#Mc;HW@AIDclt8<-+k2|j!y2z z_4i*+KZ^HT`jS-39!&nNM})$xWBs}QUi|q8Sct>8^?TTwfiJrA`M!B~JNy?jnp?lu zSKQD0mNbiWzQX2v5T?SSU(>kx`vbQubbRPSuGYR}@}1i@2UNh9tMAbPS=j!g3)vJQ z?!Tb*J^f8FbbJ*mbe8zz0O2UzU?8O z?{x#;!QZ<{!m6iizCB#j&z^$z%m;dT{ z={SC_)W4_i<2mJShp7kbxc>dHMj4oVSFyisaJ-UV+P~L*o&u8}Pv_?EYZ4Bk(Fb?( zWvnM zX=e_pd(7tFd)!Uf^*xFk-}h8iliL^Pkmia#)c=c5==t}odvBp4DOosP$L4=^H#K?f zn;fEjN#y??H9s30riLHXa)qo$Z2pa^ROSAOIplH>Ti-pO>!EqsC9b}=U8N?ka63Zg z{$%r?_}2uQeEL@0Iz;4;j_gNyg$pPA02UwbycBX^}h zVg3v*zulf>p&@t>s1xIJpyt~*rXPl#YvyzJs|S5MfZx^K$)Pkhzhq1?w9;HB*{@FX z>s+cTUq1f`dGw#iuZCROf8*ceCK&IC=I*a@bWxR0dzC|exUl)19Pt*=L2)01(|;2b ztSaALn?nlwiTu*@@A`IXXnvBZ8I{UsW_ic>vyf|NLaSMDK|d%TR0!zjL;{3hZ^E5seb#smVzID|P=4$m2ew&NGKf3=e z`t@OKW9dgG=IAr|{@HE~e9$oE*5C5KD!%_Qiv6}X%a#5dQ1$nI-!{SWyy0B^zGR+; zlb2EcoQ-sT=HT0Hkll5x#Gj-4>kp-8VAl{=(xIHqKQT;!%*2`8{5)svK{UwnB7Wkfs&bY0M@V}+Hva)SY8aDoOo%XM z>vzmQs`7oOkCHZhUMTdqkM~^lorO@E7N%ed9n-QSf zxS6E>PV0ByZywmruoLk-A@UVU`SVlUCqmEVt-1NR`kdJ~YN{TYx_vQ||0{;hV0Wbh zxBeFSGYSLTk!-SL^RG7359So|`R}B42v_v+CGeBofAg+lH6*?@<@)mmWeWaJc#=@P zd?x>1ft#RhZ^ixE)Q0$9y1z=JZ5nE4&X)Ldbo^d&W*elnv**^|H(4J*>sk+zy)VH= z^arK)tsP$Pf$F$f-2Jpa+hk&}w>!D0E9UPs|Lr~$xcpbXKY^}&7L&fl-I)A8 z{Z`a*Q`9NxaW%|MEiufZ&_+`+bFVg&d_8S#>&+wzf zIFQYMT;vctQV)VE;taf13YI6{_-Kr*la}BNgR+F}gnYyT}Aa4gIh9V`@FW6#qwSjB(q( z&jQh4^Z#}2Q1C8M<@$4zJVxP8+oq(OeZ&7x%KxcXBj9XhGr@4Z$T!XZMs&s0?H$M( z^%F{dY5v2FCPKJH8;L(33ex#H6U&(>zobjvtysw9|KZy?@OW!S?tESKglOE`WCW4F zou_=Bj_%MI4Df1)iF0=U`qP7~^1etN;`|W*-@mIwIFIoc|{BA4>W2{et#@w%u&* z{<@nj58{AIAEMg2O8Nev^Y^q}hrnxl0GI#4{~pIB_KQiMBDVfFGgk1g8zwXw#OB}p zpo%=-CYM-ei}63bpW12tbyz=_)kUtIV+c>Tx9d#sKpyd9h=J4|NsB~2#Cui zn^&^=58SJY4g*eb{rM%)s`84($B6F=4*zz#IB(At;hQI$e*=Yo*(dQBaqPi-?B)Icfa=>HY+m^tg@Wz97xN!N3`4R;x>%y9YD*?`}2+j;VIy z=J&S0qww3=5hSvJ&A*PCAG}`Ci|fz-D2v4>aifX;)(2w$tc`Sk<+!1%p!Am+w?5~p zsBfDt@gXt;XQuwg7;aMJ4>sKRKh7@$pMxit|LWe`VDtHLT>anPB?||C_aVESb}9L# z`PVVo1M6W9xBos;(O)q5lrPCUB=Y~1&i{Q6!M2h>$$q;~Xf8=WJzkfi&WK2I*POk- zwtv!Dh*=RPlzc3#|NBb)d-*yQd3pO|BuWtZr}O`rbFV{WldatRzj-rN`PQ4q$giH6 z%J_ly@2*r-L9X6jZvTCpv8udjc$&jPZ`!SAm>r@ZY5OC!RDO z3QJq6bN&0Jw?|;Qc~esLxWV6)>c7!VIrO-$xW80CUr+O&Q#>8NrRounISu~1l>gh^ zCxF@nZEpPE{lhd=Z>2{@Jr1n@en|8GJrT2kM0Mi!-yYVE#!7u#a`%ep-via3V`}NE z$j1%1_4)C;VsTHR9nttJ@(&>8KjFnn==8*#yT4v#;Zd9x6+#4y3gvz*dj2-y&_>Ws zv=NH)+429(-}^DBy%(4N<`1^QpiBoY|Ksmx;ev&JWXg4se}U5fwpWwkN)KnQ{y$z+ zh|3|2oF4JJ{{11HulIV84b3(Nap!Ng8x-P&W?^K|YC~rHU$yis+!z`z=-RRMfA(1w zdCHdK|F?Rnnb#$WtF5 zCl{%Wbpy;M$+W*gZ2KdIEgDO;}zBuCVLn*ZAaROO4z zPLSXI*!)}FHHP2&YKkwvVC(5TZ_%qC=3 z%Z9&?l>ZLDH zvA3arUdn%Po7wPvXlE|}d6Q!>zN;NMqb@!lY9sBxHS6jNzp4$m`|(Vc?Z9st6N$&A zf0_Dk7qSvMY;IKa2k?2qU2-|1tU38J7*y#{_fx@5eh{ zL`%mln3RTsZ!Kt^b~(D)OQ^C&>6=BLB4h-+grzZavs4lr&=J|8-F+ z@;!kkh?xbO|IIsI!&-+lZhy|-5*7LGf)hk#Hk<#82UO4*PICFzs8W%S`f!3o9%b`y z=Bk5RtglPrf13Ypbt-a4jXaV%jLrY7xyDcs|EGA?IX3@2+V{t|9li@;4s8CH?ivgR zMe0Js{VAINHg^GYDw`1UwBhd~igC%C-Fr58d7vLg~@kX&t#}>;lkDTs?mj*R}oGOue0^N#fyVr4GRU8k?j84 zDHba7@OF8mZj3k|Pxt3k4=aEnE!GQR`y0ML()hk&tctv9a2`>yWAl9_>?$~hZxd$e zvH6}7q#_sm^T;DtHs3ugUPJHJ>0Ezr!$uW3*^)r+CX;SK(mbiZ}G zTow7fvOE%0&gT2`XKmE@eq9*dhpq3OU#iHvw>(K&xv}}a^RYi{SXRsR_dLps(B$|x zq4cyk-$K{t_2&(ST(3q#!+s5#?^BDc(YdBES=hZ{{#wfSA}u+rexV`co)h_yQT;hb zMvuYnJ6n|)qxjA?u&R?ueMh^C@e_pEZuW%L&Pw2w!zkBg8 z2rqUtBHO02`TlJ<4_?mh&DHmT$K$YBPe-!PNYr;az8~bf0#wWga`k;h=aZ-v9ZH18 zc1(S@P2T{kic#>C+*gUQgoQu=)SE`5?R=62j%*HR%|3Gg(Q_wqg7GwY>`< z`r>-wRqKZMQOf_*YMH$G!#u9OXZc)(3lq0<{k;c*OujNQkIa6~_V-*XUV%DE=hpXM ze~`&N%k#*n4{U$WzqblLyL?J$_8&XG*V?KgH#l;VY^`PUf6G@Jofh8^w9kt5Gg{x@ zrK!lR%K7}~=Jf}+hjrZe-s)5zyzKi`=+i{(|D*3q+PxkGNB(UjG|bo0{M&9sxV2DI zc%RPZd-oqZoHV5s>Ez7jyQ*p&#DwY!-j?F?w0@7jAB5d)`jKPhTbX=6&zcFo!@F|h zcfa<57^z}J?j0~wJ|9Zu?`{D;P*UBS>)-F%5QpE#IT6z$k?&B-zq|K&IqYmRh+Dsx z*&af@*C8Zy&~oN}>*d=wK*t|)Zv0-cU_Y)N>c{2#Yf3B(?LUdj_mKl>m^IFuEHxJS zPNn$v*^mUS)!n%9`;LMFyyCu|=yhfDZKie*9=2a31T|yp`|OXo7*n;9TfaXYaR%C3 zZxGTivi035SSFw6c#kFZja{|GuoQa`f!zS~M0LuTI;z8n$xmZ5aM z#%6|!yx*=OZ~eK!XW6lp)ogq zFVr1`i_%odl@!r`e@glH>Ba~bK1=zh=j)>F#^8-HTEwSQQa!&?eZO{N9Bdk_$JKZ9 z*8wT~;dW;zF8$y_6%Z^`CAw2==qiS5JXKSCabt+d9H z**bTW@jI>WUA&gVtG$D``mQ}P8#@$*5a>CH$-mds4KQi%2rmDRoilLT1%EF8lWb#Q z{JBZo`rU`{G&FJWA?7x0{&(3V!Kur9{;j&5L8~v}r0Ux*8)g40<=?-$mIZtD77Hs( z+5A6r&c)yJR}u9*cKxoj_Zf)F-XLs0#pb`yX_rflc$eAMJi-sd{6i9h3%7}CZ6W%`z9R~`2wSS zV%qej(to7;cmBQ721n`L;`6U~e@yetCv#Sb@x2VYN&s(irXT#ak_o)}-QQaVIJxf^ zAz+dCexmig|L#HXZ9)@C{f^f6B^DNVueU0B8!yhc3Kai#?*S@~wUqdGq11fsh`wXc zwQp-OXN|~zD%HQU=C?gGP1X}?JG1qFo^v2ZS@tKN$Fuc+`HvaUB2}MTzk4%p0S>!k zMD89it$+VX{kvY{ydke&U#@>2|7$Zgj~PQkLvJwoKf8As)Q(f!cjolpXZARV*UyCz z*`;1g{tN$I4<$24a`Sr^Sr!&`Tgc`AMzdIGcgvBh|6|S4@TKcKQZj{y-m&@+&R;Oyy*2r$v@q{BXh|DuMSIuU!BYpU6FXax|4^!b@4?bGcuM^?m;ZrHRpf0a zpC&q6+5FGm(;rsvQxU?P#QG22zx!F!5KG>D75dL*>wmz+L6BP2L{h(_`G4y_0Pi}h zlIlhx|EU!J@%{i-rmZCTeJaKO*caxgTBAay+l7hzQTsCwe6WYpOWJbv|LUIr45;Z( z#(J~)-*9OLScG)r_U|lO;*W>>_9Jq2HveuBUQoNYFSmcU^Pfn3GGz?W`goPe|IW~5 zuzu_iu75YOMHag4RmA@@zZLvXKk4~;6S5vA%5Ay&uckNvF3WP4@K5*e-OP;v-|bFZ z|Nfdm8vZ@*ONM!h{L}gUFqcHw>gB=B?>o5f!7rmdNu80%Ki$6**FOu+j$X?3?^Dvx zV?R>`|LfTN5AJ;$F74kaObTH0Z!}&ePjWd;I>fR0k14Kz46=jUzuQF-|Bs44P1FgS z|NHx1K!J6J;CiE>J}sTEowY+I?|I=gaed3?e{fG3W<5T`jsN9}_~k+MY4UU$oBxmf z+Th@OeE$31mC0B2JVPLr&Ht~={%~WXqW`X%&3{g@0S?srF0@+1=HDh@Ah;Vf<@$Sd z3Vs*eQzdiniSwk_o3IPgZqtc-2C6$*B>9+_9xZ3Z2l*kdco2#Bd&kn_gp0EOdm_O$geT^ z&kR}$bBc#>`*-Fi9>5kUi%96mk4paO{{4}P?wQ=Xwt{7l`1hml&pO{q!j6$t{~p!9 z-)LS8tl2u5tN&(`_u|&pex%k!A@%XEw15BQ$9&Ln+r*9kQ*>qWGh@z>%6)A9 zO`l$dQC)U&>vx6SW%An2(hM41xerlveh{!js@29uez)CMIiN4eE{r+-u?6^~n zJk||Y@=5c3)077t4d@laNVlzUQCb4MpBwT)s`V zB;oW}Pcp45oA3OQ2f(fGa&CODXnaJ6fZb$j9h>ht%kp7M)h2HJ?q#FDXt3uDx#KMI zP5XOuZ(oLPjpMocp84l5_I4~F&d=C<`;YN6%?yK=s*zKzM80YL&N^xhwtKWB{dY9q(Jjp}@|GGIm(A91 zBe$_|&Ah#EYr6P;q5E&Ez69Xo;bvs%RW{#dxznKZXLn(3wfHqJIh?-G6s~Yy!5= zb|G56c1pf!{qAul9L6pmEwqkc>$k?R4AkwiND{x(^|^<~qG3&^sa(DnlJl5Qo4?<->$RjApOr-!SEWJ?@u~1dEcnBBqo#1_jAYAxF@+%SoW07_c05Z z{6fK5a`8Hw?|`NTxG?gUa79~up7!SkTUkKP6)E2`s=v-g#|%4vR3nz}4=MHUDV3jB zpR|U;h}K;FcKmCGIlI*fwq)zK+TAg5tGGQ^ztvR(Fge4FwDM>3eamASEIrqQ8=t4A z&&SuVO^AMh=+6t3es}!k0f#U2=lb(17dGMA-u7gh1)J~AXBNYUm%{{i%?3WDe7E1b z1OM&rOk!{Qiu#Sx{kB@$!{O^{J8ph%si?mjKI8LU>K_fJ8q>J>`4@*YjJO|2#&k|l z#@968uUhVg#Y23!`faY3gui3F$rCF!-)$fhmLFds+>z|Zm&WHeZ{%Z*Mg-Zn%uvZU zy&t1l+9`1S8X*L2XXodqtLkug#aU8woz3^n@0Xx(Py$!KLps%=;h?j`)sM~h_>gB{ zaqEEaDUQvzY=E*{M#^K&%cCM`_S_l_F*=e^kf zPV?=4-3pc^x0cM$0_DFYYMEl-KWgN-@jB)E0jT`DhshX7((E7@z7Y4{()vB&*#exn z#GG_K$>w|3oN17=y(hQ+R;SSKLUU76ZN}zXp5_6G^A-DRZnE_|biyW#UTaVO^SH#+ z@3=*a!7$U3>%YIX+JTLaJCoGN`AWW1srVcwheKxXFu6Y) zJWZIlO?UXG(bbgkk?t=BDK0=>94f(UQzh+KEBHnE7L$tNn ze5;veLcyz*T>bXY$VW5d2=c**&9{8|DOeg9$&JsWwQl00l}Y4`o3HZy@RYhQ-9POT zG$M-o6P){1^VZhk>m`Nc**iAhj+IZL!|*I&P5u2t0IC0Wu&qM>s|v~OsqFaNb3rYX zEG**o&&DVGMZM8Q#H7h9<>#mU_xR?m@kho#f^M+LcPf>CXQ%(g2@{IAd@mVlfFT9d zLiR@Sd0M|aoE-qREm{a@K*`{Zqe1FjTd_LJ7?p`w% zQXJU)o+;mi%cC4fyO~#*{7!ki2u24F=kgoceFqLwaUsG-A11#A@512GqcPn2*{&Ul zSe-tP%Wuf7C^(lrovY8A?Dpb*!(cM_JDcC5A-mvm3tw*h?R|DPuAJ*bMjv>j)OXrH zOS_u^7R^_4^XrPHdvShw5E<^>mZ{IT&Yc8}cadEGe8%J(`1Ds2dD)xI@0<>o;Q8!b zTzwukx(;`3E+TEZ9}xMmk=~!#-TNsVyqhH$8L{>Gp96Kc{&o>r79#Q+NX@?$KKlb< z_QhQPtgfaG_qHh}8`RnS#{Hv(b1Uu(FV2Yk(fn@e`xm_i7L&1cY<-@fZ-BNMe}wm6 z#OG;#=L8IZ*?U_^>f@m{Qva-DFH^LNYDBb+#Qd7p=O}$E*#B0_FRjm7F(w$=sS#PQ zPSj`GKhu0;2OcFI1?^msFM;CsU6*NSb+zuScCpCy@YLe+;3M0FtBKXab82m%bOxP0rz#o>!(E)so~QSoeUE#UlS=;-v8Tl>I#v-@kI6K+|OhxqQ#E zs>5fg#iVW%oA0yJ|A2?8z~y`RnL0dKS4@6cv-v(%q=oO^JrI6$6#G+w(r1hEI<#me zkX2f$%Ka8}e~e-_6Jwleg@{Sw^EBT{>&)RyQ47iZ3a!ub)h0OiZX;4$ChD^crTy)` zSBJxy4ce0Zb2Q)6i_I`JvI(&XTVKzowEyk=7(3`@(MdADM)RGa?}tyT6#9Em?0=){ zU&5RzFjLQf>z_HL`J&GzbMhyb9e=+{bAvOTO}YBrs^unpa(_J8a)Hfv*{KkyxnRYu zf2q`N!-cMM$;9Y2%>25QR~Xz0vggjP9z4ApEwrWmuXOxfGdK!%kD1BUZ`U!&IN|F8 zlJ6t(P1nD={gVI@kNmjvE$8hMvDs%o;&6%0cfh~o=g(ze3Z|-Q2T2}Szm-}Yj<n7E4l zEwp}bUq2jTN9joV+iAWJ2LpN~X%n=MSMp8g*UvAHhTix2e9ye)jmKlnNZa<&_0LQ7 zTeHa&5Z)PZ{j;WtzSt&b0I3TyS3Xb2=f8B^;KMyW-^&yY{BG(K$iJ=F{@Lv=A#i-F zHJ9&My|&{JT~`9%mN4V9MTyRZeOXw2f~*NqI5an1NZ zvS&S;@56Qp&?;)a(8IccPb$C0L`?PbCx_cVvH73=(ee3{?fb#eJyh^~-tfFsza1A{ z!y|rs$jS@s`qz=jJkZ~?g&Ut|&b*3QammCvi_P~f*+o#Dn#jEmwYOC*+H@i$&Wp{r z-JZu_dm&qB)rrmbp9!^S;Xuf_BO>1xa_Rk;15g72F@($apXgfDUqwj9P&VIv-nGI> zZjXdU7sU8lM(Ou}r?pshhL8#U*?f~N256NjBaN1e^Jz5S{mz@gtT!5x`4pP(iJ>MK z5!!?#zhlSeONuQaXtR!_{zda$SP5uaszdHsC)D#P)o*##C|lsu`?4gYeoN#o7`L>&T81Kl}lSaDYd>TEU8fl&fsk%{u>sq#c+rF&9NmB{&`y~3~v6Ox{ zA5{(-If>l<^@x)-=rn+kiyzqjnbnxbuxtGxL9xQO{`)2M&#b%s!T-VuSz;;jP4}-@ zJgkP+36>&IVGetw$omy686ewC)AzD@I;cgO_q`!yw_jn}b5+Eb&1PpWLb&Ab1>ntkWU z1qXKiy=!zi%-oqIOlsA@r*yyM%PlpiYkrPA?Zwvb7UU7U?sQnN9oF!?lyA$Cf3RQi zIkM}d$T#h;T@I^;7uF@*`%j^LYH@c!2`RkH=G*F3OAPRMEUACd`W-T$7Dp~AA+zVQ z`97FwfGXQrY_LS>^-}KKAC$pH$2I zkeCl9s^$ZgKc9}zlVV)J=C(OE|8~pSgc`3Wlfa@|O8=amKOM0m7(7k@H$K0XzYW8K zJ&1mp$T#h;)wNuw;B!2;|1>2i8>8l|m+(#ZuME7j8J_sh5&o`V>v!|>yV0d8kUV(4 z!{&eSHJyKt8W|5+0|L15`G}1P=pN`#B37~e^JOmkV7b8OyQ(+~3pB$?fL2##{@tnW zI9#ZV5}tf+m|v03mk%na!OD##M9-bgcfj=vP-vRW<$LzK8k}*cgzP>c@+||YfBvlb zBZx>nEL7Gu?5B|OJp=yW$A3%6z|I$xpP%OY@txmr{(T8|f8@s8KNvIWJjr;$=6iZ_ zOZ0JiBJ}Fa*6#(`f3OnI6Ms)O->=6S;JVAIe-+L5ft4oM z|3@=oAJ68y(UoCPxlWIpf6usPjh$ZUa`n6Txh-t&)m2jeqWMyg84<5?oJG_YtEDIaJ<-7CcO}O86DoLHgo-a*$69j{T zkjr=Rq@8#?#E-}pS}65fpz7OO?yZFj_7k}Ice{0)p=5?LH@`OU+>KsWgUHlpY<}_W zPH533kjt;XB0iA)T|n%fv-$P-k`5|^)^Yn&E_!F;YsLPz9y#Luby}YvmK=xW5z$=# z%m8X|<*f5$L;#!LO9mI1+yZUpZg7iGhg($`rNp= zHQpVlN4o!I>+{2hws60LzT|!j&F{K?PI$P?fK+^2rsR*Ve=R%g2y%nI-2E?Y+Xtbs zr8W8LW5eXPYV}-jFt_0H>#%(jUYj|MOe|*en_v|LUpvUT{b!K71Mk1{BcJyUQSz%r z)xY)!tp(ZV30!@Stvrq<@ljlT?$K;BC~nwr^XraFcVWccAo4tk&G(_TJE8DJUh-%h>Vv`;2txRKAYuk56fI0F9i&iOjQ$^7~Em-9PX+oHmT%&WC1JR^w-@ zQnD?a&9}|%GRT~{hkJk7azG8{uP-H?ezW-=Yw-|@Iv(Nj-OsHC!w!~`Pfl#UZx8$p z>i0^8>?bAl`Xb%`v@)p%hukYA)<4<$eCC5Drq(?b)LOIkdDin9tZ7+Bg5%hHyC(I* z@EdBRM3c?;8)6FQ+_kv+-2a*h9)Hk+6qx1K^C7K&sWch}HAmY@`b+8j+PlaKpH}J- z^Iq)y+I+1oR2J!Tl-Iv&i6nP>ZqmU zo9-X)KVU6P6DIQgGs_&jQ4_)Cd)(oA*0?uqwg!X+n0b{KL(K)SCMZzzxFiR z2_vruarti9Hv#h${c9fGMZRhOta^AlY#$iL&9BSWXJE@WVZ<(;t=|iakHP+c7;gMM zd`UId=#-JCyV!hd?=6FxjwwRkq=x)hnqT)kTa6C(Wn@9)torz08h`(j`~V^{k8u6* z%wN?wczGF7_h<9%*Zw!ezA6(OW{UF}^#0b4_BE(-wv6QUX6tuIo+hsN_DqOEHs7DZ zYVg{dGBO~W&3DbjUifF4VnbDbHsAmCFoUrhS_^CDiTN2Fe`n~K;?n0Dq|We|l8;oX zfBaxcb9yNN3~(WWZ(E^%I9U&e&$E(1HtXW z2=0ED#xC(#I3b9*XzMch9xP$ZAa1 zx>1KHu3xtgxbQJ7Tzrt>3pdj)1Jj-GnIz#QGEMj~BL^gr@4fNz3e| z^?XVF@g;_n;Q9+Au0P(cYXC<6upt#s*nIapF-Ot=Jdms35&l~-f6zR#MOLHq&uG5q zUJ3ve$B|t9e)eex7J3Jg&sTdf`6jNR@ZwN+uEP!p9zVF{`22Buj&HvFlO_e_~AZicFX1VuQ>Iu#$G+j$+!b-zT4^k2g_Z{ zg{Va$-?V<`9IM8aQRQT0g2=Z()xTP5YT}f2FSvZq%CAP%ZRI5GrpUKG)xR>!wI}Wx z)QIb!?N-chIK{UlHIt7k`JwfBfz1%Oq1v8XzpnXig(-#YNzYn#{n}=!;{J+ycgcL0 zjH+*~s-1{K)ccU;%f4&+Jng7#H-C H8$bU)P`6SA literal 0 HcmV?d00001 diff --git a/core_perception/points_preprocessor/test/data/transformed_structured.txt b/core_perception/points_preprocessor/test/data/transformed_structured.txt new file mode 100644 index 00000000000..c9b41d2478b --- /dev/null +++ b/core_perception/points_preprocessor/test/data/transformed_structured.txt @@ -0,0 +1,30 @@ +1 +1427157650 +349046016 +base_link +1 +55631 +0 +32 +1780192 +1 +x +0 +7 +1 +y +4 +7 +1 +z +8 +7 +1 +intensity +16 +7 +1 +ring +20 +4 +1 \ No newline at end of file diff --git a/core_perception/points_preprocessor/test/include/sensor_msg_comparison.h b/core_perception/points_preprocessor/test/include/sensor_msg_comparison.h new file mode 100644 index 00000000000..a835e146ebe --- /dev/null +++ b/core_perception/points_preprocessor/test/include/sensor_msg_comparison.h @@ -0,0 +1,414 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include + +#include +#include + +bool equals(const sensor_msgs::PointCloud2& lhs, const sensor_msgs::PointCloud2& rhs) +{ + //header + bool are_header_equals = (lhs.header.seq == rhs.header.seq) && + (lhs.header.stamp.sec == rhs.header.stamp.sec) && + (lhs.header.stamp.nsec == rhs.header.stamp.nsec) && + (lhs.header.frame_id == rhs.header.frame_id); + if (!are_header_equals) + { + return false; + } + + //sensor_msg + bool are_parameters_equals = (lhs.height == rhs.height) && + (lhs.width == rhs.width) && + (lhs.is_bigendian == rhs.is_bigendian) && + (lhs.point_step == rhs.point_step) && + (lhs.row_step == rhs.row_step) && + (lhs.is_dense == rhs.is_dense); + if (!are_parameters_equals) + { + return false; + } + + //fields + bool are_all_fields_equals = true; + if (lhs.fields.size() == rhs.fields.size()){ + for (uint i=0; i < lhs.fields.size(); i++) + { + if (!((lhs.fields[i].name == rhs.fields[i].name) && + (lhs.fields[i].offset == rhs.fields[i].offset) && + (lhs.fields[i].datatype == rhs.fields[i].datatype) && + (lhs.fields[i].count == rhs.fields[i].count))) + { + are_all_fields_equals = false; + break; + } + } + } + else + { + are_all_fields_equals = false; + } + if (!are_all_fields_equals) + { + return false; + } + + //binary blob + bool is_data_equal = (lhs.data.size() == rhs.data.size()) && + (memcmp(lhs.data.data(),rhs.data.data(),lhs.data.size())) == 0; + if (!is_data_equal) + { + return false; + } + + return true; +} + +std::string decode_chunk(const sensor_msgs::PointCloud2& sensor_msg, uint index) +{ + std::stringstream output_buffer; + + size_t point_size = sensor_msg.row_step/sensor_msg.width; // in Byte + + const uint8_t* chunk_start_ptr = reinterpret_cast(sensor_msg.data.data()) + (index*point_size); + + output_buffer << "chunk#" << index << " : "; + + for (uint i = 0; i < sensor_msg.fields.size(); i++) + { + uint offset = sensor_msg.fields[i].offset; // In Byte from the chunk's start + for (uint current_count = 0; current_count < sensor_msg.fields[i].count ; current_count++) + { + uint read_size; // In byte + switch(sensor_msg.fields[i].datatype) + { + case sensor_msgs::PointField::INT8 : + read_size = 1; + int8_t val8; + memcpy(&val8, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << val8 << "; "; + break; + case sensor_msgs::PointField::UINT8 : + read_size = 1; + uint8_t valu8; + memcpy(&valu8, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << valu8 << "; "; + break; + case sensor_msgs::PointField::INT16 : + read_size = 2; + int16_t val16; + memcpy(&val16, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << val16 << "; "; + break; + case sensor_msgs::PointField::UINT16 : + read_size = 2; + int16_t valu16; + memcpy(&valu16, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << valu16 << "; "; + break; + case sensor_msgs::PointField::INT32 : + read_size = 4; + int32_t val32; + memcpy(&val32, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << val32 << "; "; + break; + case sensor_msgs::PointField::UINT32 : + read_size = 4; + uint32_t valu32; + memcpy(&valu32, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << valu32 << "; "; + break; + case sensor_msgs::PointField::FLOAT32 : + read_size = 4; + float valf32; + memcpy(&valf32, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << valf32 << "; "; + break; + case sensor_msgs::PointField::FLOAT64 : + read_size = 8; + double valf64; + memcpy(&valf64, chunk_start_ptr+offset+(current_count*read_size), read_size); + output_buffer << sensor_msg.fields[i].name << " : " << valf64 << "; "; + break; + } + } + } + return output_buffer.str(); +} + +// Get a hex string of the first mismatch between two uint8_t vectors. They are considered containing data aligned on chunk_size +std::string get_first_mismatch(const std::vector& expected, + const std::vector& tested, + uint chunk_size, uint* out_index = nullptr) +{ + uint min_size = std::min(expected.size(),tested.size()); + for (uint i = 0; i < min_size; i++) + { + if (expected[i]!=tested[i]) + { + // We have a mismatch. We make the string for up to chunk_size bytes + uint chunk_id = i / chunk_size; // Use the rounding down + uint chunk_start_index = chunk_id * chunk_size; + std::stringstream output_buffer; + output_buffer << "first mismatch at index " << i << " (chunk #" << chunk_id << ") : "; + for (uint j = chunk_start_index; j < std::min(chunk_start_index+chunk_size, min_size); j++) + { + output_buffer << std::hex << static_cast(expected[j]); + } + output_buffer << " | "; + for (uint j = chunk_start_index; j < std::min(chunk_start_index+chunk_size, min_size); j++) + { + output_buffer << std::hex << static_cast(tested[j]); + } + if (out_index != nullptr) + { + *out_index = chunk_id; + } + return output_buffer.str(); + } + } + if (out_index != nullptr) + { + *out_index = ~0; + } + return ""; +} + +std::string find_mismatches(const sensor_msgs::PointCloud2& expected, + const sensor_msgs::PointCloud2& tested, + bool locate_first_data_disparity = false) +{ + std::stringstream output_buffer; + + //header + if (expected.header.seq != tested.header.seq) + { + output_buffer << "header.seq are differents : expected : " << expected.header.seq + << "; got : " << tested.header.seq << std::endl; + } + if (expected.header.stamp.sec != tested.header.stamp.sec) + { + output_buffer << "header.stamp.sec are differents : expected : " << expected.header.stamp.sec + << "; got : " << tested.header.stamp.sec << std::endl; + } + if (expected.header.stamp.nsec != tested.header.stamp.nsec) + { + output_buffer << "header.stamp.nsec are differents : expected : " << expected.header.stamp.nsec + << "; got : " << tested.header.stamp.nsec << std::endl; + } + if (expected.header.frame_id != tested.header.frame_id) + { + output_buffer << "header.frame_id are differents : expected : " << expected.header.frame_id + << "; got : " << tested.header.frame_id << std::endl; + } + + //sensor_msg + if (expected.height != tested.height) + { + output_buffer << "height are differents : expected : " << expected.height + << "; got : " << tested.height << std::endl; + } + if (expected.width != tested.width) + { + output_buffer << "width are differents : expected : " << expected.width << + "; got : " << tested.width << std::endl; + } + if (expected.is_bigendian != tested.is_bigendian) + { + output_buffer << "is_bigendian are differents : expected : " << expected.is_bigendian + << "; got : " << tested.is_bigendian << std::endl; + } + if (expected.point_step != tested.point_step) + { + output_buffer << "point_step are differents : expected : " << expected.point_step + << "; got : " << tested.point_step << std::endl; + } + if (expected.row_step != tested.row_step) + { + output_buffer << "row_step are differents : expected : " << expected.row_step + << "; got : " << tested.row_step << std::endl; + } + if (expected.is_dense != tested.is_dense) + { + output_buffer << "is_dense are differents : expected : " << expected.is_dense + << "; got : " << tested.is_dense << std::endl; + } + + //fields + if (expected.fields.size() != tested.fields.size()) + { + output_buffer << "field sizes are differents : expected : " << expected.fields.size() + << "; got : " << tested.fields.size() << std::endl; + } + + uint min_field_size = std::min(expected.fields.size(),tested.fields.size()); + for (uint i=0; i < min_field_size; i++) + { + if (expected.fields[i].name != tested.fields[i].name) + { + output_buffer << "fields[" << i << "].name are differents : expected : " + << expected.fields[i].name << "; got : " << tested.fields[i].name << std::endl; + } + if (expected.fields[i].offset != tested.fields[i].offset) + { + output_buffer << "fields[" << i << "].offset are differents : expected : " + << expected.fields[i].offset << "; got : " << tested.fields[i].offset << std::endl; + } + if (expected.fields[i].datatype != tested.fields[i].datatype) + { + output_buffer << "fields[" << i << "].datatype are differents : expected : " + << expected.fields[i].datatype << "; got : " << tested.fields[i].datatype << std::endl; + } + if (expected.fields[i].count != tested.fields[i].count) + { + output_buffer << "fields[" << i << "].count are differents : expected : " + << expected.fields[i].count << "; got : " << tested.fields[i].count << std::endl; + } + } + + //binary blob + if(expected.data.size() != tested.data.size()) + { + output_buffer << "data sizes are differents : expected : " << expected.data.size() + << "; got : " << tested.data.size() << std::endl; + } + if (memcmp(expected.data.data(),tested.data.data(),expected.data.size()) != 0) + { + output_buffer << "data are differents"; + if (locate_first_data_disparity) + { + uint point_size = expected.row_step/expected.width; // In Byte + uint mismatch_index = 0; + output_buffer << " : " << get_first_mismatch(expected.data, tested.data, point_size, &mismatch_index); + output_buffer << std::endl << "expected : " << decode_chunk(expected, mismatch_index); + output_buffer << std::endl << " got : " << decode_chunk(tested, mismatch_index); + } + output_buffer << std::endl; + } + + return output_buffer.str(); +} + + + +bool count_data_mismatch(const sensor_msgs::PointCloud2& expected_ground, + const sensor_msgs::PointCloud2& expected_no_ground, + const sensor_msgs::PointCloud2& tested_ground, + const sensor_msgs::PointCloud2& tested_no_ground, + uint* out_false_ground_count, + uint* out_false_no_ground_count) +{ + uint point_size = expected_no_ground.row_step/expected_no_ground.width; // In Byte + if (((expected_ground.data.size()%point_size) != 0) || + ((expected_no_ground.data.size()%point_size) != 0) || + ((tested_ground.data.size()%point_size) != 0) || + ((tested_no_ground.data.size()%point_size) != 0)) + { + return 0; + } + + uint expected_ground_point_count = expected_ground.data.size()/point_size; + uint expected_no_ground_point_count = expected_no_ground.data.size()/point_size; + uint tested_ground_point_count = tested_ground.data.size()/point_size; + uint tested_no_ground_point_count = tested_no_ground.data.size()/point_size; + + uint tested_no_ground_index = 0; + uint expected_no_ground_index = 0; + + *out_false_ground_count = 0; + *out_false_no_ground_count = 0; + + bool all_mismatches_are_legit = true; + + while ((tested_no_ground_index < tested_no_ground_point_count) && + (expected_no_ground_index < expected_no_ground_point_count)) + { + // Progress on the no_ground point until we hit a mismatch + bool is_equal; + do{ + is_equal = memcmp(tested_no_ground.data.data() + tested_no_ground_index*point_size, + expected_no_ground.data.data() + (expected_no_ground_index)*point_size, + point_size) == 0; + tested_no_ground_index++; + expected_no_ground_index++; + }while (is_equal && (tested_no_ground_index < tested_no_ground_point_count) && + (expected_no_ground_index < expected_no_ground_point_count)); + + if (!is_equal) + { + // ---- Test for a false no_ground (a true ground point in the no_ground vector) ---- + bool is_false_no_ground = false; + for (uint i=0; i +#include +#include +#include + +#include +#include + +bool serialize_sensor_msg(const sensor_msgs::PointCloud2::ConstPtr& cloud, + const std::string text_file_name, + const std::string binary_blob_file_name) +{ + std::ofstream blob_file, text_file; + + blob_file.open (binary_blob_file_name.c_str(), + std::ios::out | std::ios::binary | std::ios::trunc); + if ( !blob_file.is_open() ){ + return false; + } + blob_file.write(reinterpret_cast(cloud->data.data()),cloud->data.size()); + blob_file.close(); + + text_file.open (text_file_name.c_str(), std::ios::out | std::ios::trunc); + if ( !text_file.is_open() ){ + return false; + } + //header + text_file << cloud->header.seq << std::endl; + text_file << cloud->header.stamp.sec << std::endl; + text_file << cloud->header.stamp.nsec << std::endl; + text_file << cloud->header.frame_id << std::endl; + + //sensor_msg + text_file << cloud->height << std::endl; + text_file << cloud->width << std::endl; + text_file << +(cloud->is_bigendian) << std::endl; + text_file << cloud->point_step << std::endl; + text_file << cloud->row_step << std::endl; + text_file << +(cloud->is_dense); + + //fields + for (uint i=0; i < cloud->fields.size(); i++) + { + text_file << std::endl; + text_file << cloud->fields[i].name << std::endl; + text_file << cloud->fields[i].offset << std::endl; + text_file << +(cloud->fields[i].datatype) << std::endl; + text_file << cloud->fields[i].count; + } + + text_file.close(); + return true; +} + +bool unserialize_sensor_msg(const sensor_msgs::PointCloud2::Ptr& cloud, + const std::string text_file_name, + const std::string binary_blob_file_name) +{ + std::ifstream blob_file, text_file; + + text_file.open (text_file_name.c_str(), std::ios::in); + if ( !text_file.is_open() ){ + return false; + } + //header + text_file >> cloud->header.seq; + text_file >> cloud->header.stamp.sec; + text_file >> cloud->header.stamp.nsec; + text_file >> cloud->header.frame_id; + + //sensor_msg + text_file >> cloud->height; + text_file >> cloud->width; + int int_buffer = 0; + text_file >> int_buffer; + cloud->is_bigendian = int_buffer; + text_file >> cloud->point_step; + text_file >> cloud->row_step; + int_buffer = 0; + text_file >> int_buffer; + cloud->is_dense = int_buffer; + + //fields + uint i = 0; + while(text_file.peek() != EOF ) + { + cloud->fields.resize(i+1); + int int_buffer; + text_file >> cloud->fields[i].name >> cloud->fields[i].offset \ + >> int_buffer >> cloud->fields[i].count; + cloud->fields[i].datatype = static_cast(int_buffer); + i++; + } + + text_file.close(); + + size_t point_size = cloud->row_step/cloud->width; // in Byte + size_t cloud_count = cloud->width*cloud->height; + + blob_file.open (binary_blob_file_name.c_str(), std::ios::in | std::ios::binary); + if ( !blob_file.is_open() ){ + return false; + } + cloud->data.resize(cloud_count*point_size); + blob_file.read(reinterpret_cast(cloud->data.data()),cloud_count*point_size); + blob_file.close(); + return true; +} \ No newline at end of file diff --git a/core_perception/points_preprocessor/test/include/test_fast_atan2.h b/core_perception/points_preprocessor/test/include/test_fast_atan2.h new file mode 100644 index 00000000000..98193557e57 --- /dev/null +++ b/core_perception/points_preprocessor/test/include/test_fast_atan2.h @@ -0,0 +1,44 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include + +#include + +#include "points_preprocessor/ray_ground_filter/atan2_utils.h" + +TEST(RayGroundFilter, fast_atan2) +{ + double nb_of_sample = 100; + double epsilon_rad = 1.0E-5F; // to avoid the non defined value of tan/atan + double max_error_expected = 0.005; // radian + + double step_size = PI/nb_of_sample; + for( double angle = -PI_2+epsilon_rad; angle < PI_2-epsilon_rad; angle += step_size) + { + double y_value = tan(angle); + double reference_value = atan2(y_value, 1); + double tested_value = fast_atan2(y_value, 1); + ASSERT_LT(fabsf(reference_value-tested_value), max_error_expected) \ + << "atan2 approximation's error is above the expected error : " \ + << fabsf(reference_value-tested_value); + reference_value = atan2(y_value, -1); + tested_value = fast_atan2(y_value, -1); + ASSERT_LT(fabsf(reference_value-tested_value), max_error_expected) \ + << "atan2 approximation's error is above the expected error : " \ + << fabsf(reference_value-tested_value); + } +} diff --git a/core_perception/points_preprocessor/test/include/test_ray_groundfilter.h b/core_perception/points_preprocessor/test/include/test_ray_groundfilter.h index 497d58e92f4..5d8557d1cb6 100644 --- a/core_perception/points_preprocessor/test/include/test_ray_groundfilter.h +++ b/core_perception/points_preprocessor/test/include/test_ray_groundfilter.h @@ -1,55 +1,141 @@ +/* + * Copyright 2015-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ #include #include +#include +#include -#include "ray_ground_filter.h" +#include "points_preprocessor/ray_ground_filter/ray_ground_filter.h" +#include "sensor_msg_serialization.h" +#include "sensor_msg_comparison.h" -// test fixtures are necessary to use friend classes -TEST(RayGroundFilter, clipCloud) +TEST(RayGroundFilter, callback) { - char* argv = "test_points_preprocessor"; + char arg0[] = "test_points_preprocessor"; + char* argv[] = {&arg0[0], NULL}; int argc = 1; - ros::init(argc, &argv, "test_raygroundfilter_clipcloud"); - pcl::PointCloud::Ptr in_cloud_ptr(new pcl::PointCloud); - pcl::PointCloud::Ptr out_cloud_ptr(new pcl::PointCloud); + ros::init(argc, argv, "test_raygroundfilter_callback"); + std::string package_path = ros::package::getPath("points_preprocessor"); + std::string test_data_path = package_path + "/test/data"; RayGroundFilter rgfilter; + rgfilter.general_max_slope_ = 5.0; + rgfilter.local_max_slope_ = 8.0; + rgfilter.concentric_divider_distance_ = 0.0; + rgfilter.min_height_threshold_ = 0.5; + rgfilter.clipping_height_ = 2.0; + rgfilter.min_point_distance_ = 1.85; + rgfilter.reclass_distance_threshold_ = 0.2; + rgfilter.radial_divider_angle_ = 0.08; + rgfilter.radial_dividers_num_ = ceil(360.0 / rgfilter.radial_divider_angle_); - // add a few test points - pcl::PointXYZI pt; - pt.x = 0.0F; pt.y = 0.0F; pt.z = 1.0F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 1.0F; pt.z = 1.3F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 2.0F; pt.z = 1.5F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 3.0F; pt.z = 1.7F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 4.0F; pt.z = 1.9F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 5.0F; pt.z = 1.7F; - in_cloud_ptr->push_back(pt); - pt.x = 0.0F; pt.y = 6.0F; pt.z = 1.5F; - in_cloud_ptr->push_back(pt); - - // clip cloud - const float CLIP_HEIGHT = 1.5F; - rgfilter.ClipCloud(in_cloud_ptr, CLIP_HEIGHT, out_cloud_ptr); - - // make sure everything worked correctly - ASSERT_EQ(out_cloud_ptr->points.size(), 4); - const float TOL = 1.0E-6F; - ASSERT_LT(fabsf(out_cloud_ptr->points[0].x), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[0].y), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[0].z - 1.0F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[1].x), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[1].y - 1.0F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[1].z - 1.3F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[2].x), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[2].y - 2.0F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[2].z - 1.5F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[3].x), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[3].y - 6.0F), TOL); - ASSERT_LT(fabsf(out_cloud_ptr->points[3].z - 1.5F), TOL); + // 0.2% of mismatch accepted. This is because of the floating points error possibly being different + //from the the error on the machine on which the expected data was created. This would lead to a different + //sort radius, a different sort order or a different verdict on being in a cone or not. All those errors may + //misclassify a point. The ray ground filter algorithm is based upon heuristics, so having a few points + //misclassified is acceptable. + const float error_margin = 0.002; // 1 out of 500 + + sensor_msgs::PointCloud2::Ptr input_cloud(new sensor_msgs::PointCloud2); + sensor_msgs::PointCloud2::Ptr expected_trans_sensor_cloud(new sensor_msgs::PointCloud2); + sensor_msgs::PointCloud2::Ptr expected_ground_output_cloud(new sensor_msgs::PointCloud2); + sensor_msgs::PointCloud2::Ptr expected_no_ground_output_cloud(new sensor_msgs::PointCloud2); + ASSERT_TRUE(unserialize_sensor_msg(input_cloud, + test_data_path+"/input_structured.txt", + test_data_path+"/input_blob.bin")) + << "cannot find the input sensor_msg files"; + ASSERT_TRUE(unserialize_sensor_msg(expected_trans_sensor_cloud, + test_data_path+"/transformed_structured.txt", + test_data_path+"/transformed_blob.bin")) + << "cannot find the transformed sensor_msg files"; + ASSERT_TRUE(unserialize_sensor_msg(expected_ground_output_cloud, + test_data_path+"/output_ground_structured.txt", + test_data_path+"/output_ground_blob.bin")) + << "cannot find the ground output sensor_msg files"; + ASSERT_TRUE(unserialize_sensor_msg(expected_no_ground_output_cloud, + test_data_path+"/output_no_ground_structured.txt", + test_data_path+"/output_no_ground_blob.bin")) + << "cannot find the no_ground output sensor_msg files"; + const int expected_ground_points = expected_ground_output_cloud->width*expected_ground_output_cloud->height; + const int expected_no_ground_points = expected_no_ground_output_cloud->width*expected_no_ground_output_cloud->height; + + const uint error_allowed = error_margin * (expected_ground_points+expected_no_ground_points); + + //apply the callback's functions + sensor_msgs::PointCloud2::Ptr trans_sensor_cloud(new sensor_msgs::PointCloud2); + const bool succeeded = rgfilter.TransformPointCloud("base_link", input_cloud, trans_sensor_cloud); + EXPECT_TRUE(succeeded) << "cannot transform"; + EXPECT_TRUE(equals(*trans_sensor_cloud, *expected_trans_sensor_cloud)) << "we don't get the expected transform"; + + std::vector radial_ordered_clouds; + std::vector ground_ptrs, no_ground_ptrs; + rgfilter.ConvertAndTrim(expected_trans_sensor_cloud, rgfilter.clipping_height_, rgfilter.min_point_distance_, &radial_ordered_clouds, &no_ground_ptrs); + const size_t point_count = input_cloud->width*input_cloud->height; + + rgfilter.ClassifyPointCloud(radial_ordered_clouds, point_count, &ground_ptrs, &no_ground_ptrs); + EXPECT_LE(static_cast(std::abs(static_cast(ground_ptrs.size())-expected_ground_points)), error_allowed) + << "Wrong number of ground point"; + EXPECT_LE(static_cast(std::abs(static_cast(no_ground_ptrs.size())-expected_no_ground_points)), error_allowed) + << "Wrong number of non_ground point"; + + sensor_msgs::PointCloud2::Ptr produced_ground_output_cloud(new sensor_msgs::PointCloud2); + sensor_msgs::PointCloud2::Ptr produced_no_ground_output_cloud(new sensor_msgs::PointCloud2); + rgfilter.filterROSMsg(input_cloud, ground_ptrs, produced_ground_output_cloud); + rgfilter.filterROSMsg(input_cloud, no_ground_ptrs, produced_no_ground_output_cloud); + + produced_ground_output_cloud->header = expected_ground_output_cloud->header; + produced_no_ground_output_cloud->header = expected_no_ground_output_cloud->header; + + bool ground_output_is_as_expected = equals(*produced_ground_output_cloud, *expected_ground_output_cloud); + bool no_ground_output_is_as_expected = equals(*produced_no_ground_output_cloud, *expected_no_ground_output_cloud); + + if ( !ground_output_is_as_expected || !no_ground_output_is_as_expected ) + { + uint false_ground_count; + uint false_no_ground_count; + bool all_legit = count_data_mismatch(*expected_ground_output_cloud, + *expected_no_ground_output_cloud, + *produced_ground_output_cloud, + *produced_no_ground_output_cloud, + &false_ground_count, + &false_no_ground_count); + + uint error_count = false_ground_count + false_no_ground_count; + if (!ground_output_is_as_expected) + { + if (error_count > error_allowed) + { + std::string diff = find_mismatches(*expected_ground_output_cloud, *produced_ground_output_cloud,true); + EXPECT_TRUE(ground_output_is_as_expected) << "ground points output doesn't match the expected result :" << std::endl + << diff << std::endl + << false_ground_count << " false ground found" << std::endl; + } + } + + if (!no_ground_output_is_as_expected || !all_legit) + { + if (error_count > error_allowed) + { + std::string diff = find_mismatches(*expected_no_ground_output_cloud, *produced_no_ground_output_cloud,true); + EXPECT_TRUE(no_ground_output_is_as_expected) << "no_ground points output doesn't match the expected result :" << std::endl + << diff << std::endl + << false_no_ground_count << " false no_ground found" << std::endl; + } + } + } } diff --git a/core_perception/points_preprocessor/test/src/test_points_preprocessor.cpp b/core_perception/points_preprocessor/test/src/test_points_preprocessor.cpp index cabde2c77aa..8aa7fe383da 100644 --- a/core_perception/points_preprocessor/test/src/test_points_preprocessor.cpp +++ b/core_perception/points_preprocessor/test/src/test_points_preprocessor.cpp @@ -1,6 +1,22 @@ +/* + * Copyright 2015-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ #include "gtest/gtest.h" +#include "test_fast_atan2.h" #include "test_ray_groundfilter.h" int32_t main(int32_t argc, char ** argv) diff --git a/core_perception/points_preprocessor/test/test_points_preprocessor.test b/core_perception/points_preprocessor/test/test_points_preprocessor.test index 93e140a6861..71b5197d6ec 100644 --- a/core_perception/points_preprocessor/test/test_points_preprocessor.test +++ b/core_perception/points_preprocessor/test/test_points_preprocessor.test @@ -3,15 +3,12 @@ - - - - - + + + type="test_points_preprocessor" name="test_ray_ground_filter"> diff --git a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h index cc626f54011..0af4eff77d5 100644 --- a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h +++ b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h @@ -76,6 +76,8 @@ class FeatProjLanelet2 int adjust_proj_x_ = 0; int adjust_proj_y_ = 0; + float near_plane_ = 1.0; + float far_plane_ = 200.0; autoware_msgs::LaneArray waypoints_; diff --git a/core_perception/trafficlight_recognizer/launch/feat_proj_lanelet2.launch b/core_perception/trafficlight_recognizer/launch/feat_proj_lanelet2.launch index 737559cc9f3..0d888ecb848 100644 --- a/core_perception/trafficlight_recognizer/launch/feat_proj_lanelet2.launch +++ b/core_perception/trafficlight_recognizer/launch/feat_proj_lanelet2.launch @@ -1,11 +1,17 @@ + - - + + + + + + + diff --git a/core_perception/trafficlight_recognizer/launch/feat_proj_option.launch b/core_perception/trafficlight_recognizer/launch/feat_proj_option.launch index d8917ffba64..cbda1ae3380 100644 --- a/core_perception/trafficlight_recognizer/launch/feat_proj_option.launch +++ b/core_perception/trafficlight_recognizer/launch/feat_proj_option.launch @@ -1,21 +1,29 @@ + - - + + + + - - - - + + + + + + + - - - - - - - + + + + + + + + + \ No newline at end of file diff --git a/core_perception/trafficlight_recognizer/nodes/feat_proj/feat_proj.cpp b/core_perception/trafficlight_recognizer/nodes/feat_proj/feat_proj.cpp index 80e262e1f5a..43760a4568a 100644 --- a/core_perception/trafficlight_recognizer/nodes/feat_proj/feat_proj.cpp +++ b/core_perception/trafficlight_recognizer/nodes/feat_proj/feat_proj.cpp @@ -46,6 +46,8 @@ static constexpr uint32_t SUBSCRIBE_QUEUE_SIZE = 1000; static int adjust_proj_x = 0; static int adjust_proj_y = 0; +static float near_plane_ = 0.0; +static float far_plane_ = 0.0; typedef struct { @@ -370,6 +372,8 @@ int main(int argc, char* argv[]) ros::NodeHandle private_nh("~"); std::string cameraInfo_topic_name; private_nh.param("camera_info_topic", cameraInfo_topic_name, "/camera_info"); + private_nh.param("roi_search_min_distance", near_plane_, 1.0); + private_nh.param("roi_search_max_distance", far_plane_, 200.0); /* get camera ID */ camera_id_str = cameraInfo_topic_name; diff --git a/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp b/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp index e776ec6d90f..ec6c7cb6245 100644 --- a/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp +++ b/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp @@ -159,9 +159,7 @@ bool FeatProjLanelet2::project2(const Eigen::Vector3f& pt, int* u, int* v, const ROS_ERROR_STREAM(__FUNCTION__ << ": u or v is null pointer!"); return false; } - float nearPlane = 1.0; - float farPlane = 200.0; - + Eigen::Vector3f transformed_pt = transform(pt, camera_to_map_tf_); float _u = transformed_pt.x() * fx_ / transformed_pt.z() + cx_; @@ -169,8 +167,8 @@ bool FeatProjLanelet2::project2(const Eigen::Vector3f& pt, int* u, int* v, const *u = static_cast(_u); *v = static_cast(_v); - if (*u < 0 || image_width_ < *u || *v < 0 || image_height_ < *v || transformed_pt.z() < nearPlane || - farPlane < transformed_pt.z()) + if (*u < 0 || image_width_ < *u || *v < 0 || image_height_ < *v || transformed_pt.z() < near_plane_ || + far_plane_ < transformed_pt.z()) { *u = -1, *v = -1; return false; @@ -467,6 +465,8 @@ void FeatProjLanelet2::init() roi_sign_pub_ = rosnode_.advertise("roi_signal", 100); private_nh_.param("use_path_info", use_path_info_, false); + private_nh_.param("roi_search_min_distance", near_plane_, 1.0); + private_nh_.param("roi_search_max_distance", far_plane_, 200.0); waypoint_subscriber_ = rosnode_.subscribe("final_waypoints", 1, &FeatProjLanelet2::waypointsCallback, this); diff --git a/core_perception/vel_pose_diff_checker/CMakeLists.txt b/core_perception/vel_pose_diff_checker/CMakeLists.txt index 9f232bd8ed4..bd5464378d6 100755 --- a/core_perception/vel_pose_diff_checker/CMakeLists.txt +++ b/core_perception/vel_pose_diff_checker/CMakeLists.txt @@ -7,74 +7,72 @@ if(NOT CMAKE_CXX_STANDARD) endif() find_package(catkin REQUIRED COMPONENTS - roscpp - tf - std_msgs - geometry_msgs - autoware_msgs amathutils_lib + autoware_health_checker + autoware_msgs + autoware_system_msgs + geometry_msgs + roscpp roslint + std_msgs + tf ) find_package(autoware_build_flags REQUIRED) catkin_package( - INCLUDE_DIRS include - CATKIN_DEPENDS tf - std_msgs - geometry_msgs - autoware_msgs - amathutils_lib + INCLUDE_DIRS include ) -########### -## Build ## -########### - include_directories( include ${catkin_INCLUDE_DIRS} ) -add_executable(${PROJECT_NAME} src/vel_pose_diff_checker_node.cpp - src/vel_pose_diff_checker_core.cpp - src/value_time_queue.cpp) +add_executable(${PROJECT_NAME} + src/vel_pose_diff_checker_node.cpp + src/vel_pose_diff_checker_core.cpp + src/value_time_queue.cpp +) -add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) target_link_libraries(${PROJECT_NAME} - ${catkin_LIBRARIES} + ${catkin_LIBRARIES} ) -############# -## Install ## -############# - install(TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + PATTERN ".svn" EXCLUDE ) -############# -## Testing ## -############# +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config + PATTERN ".svn" EXCLUDE +) set(ROSLINT_CPP_OPTS "--filter=-build/c++14") roslint_cpp() -if (CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING) roslint_add_test() find_package(rostest REQUIRED) - add_rostest_gtest(vel_pose_diff_checker-test test/test_vel_pose_diff_checker.test - test/src/test_vel_pose_diff_checker.cpp - src/vel_pose_diff_checker_core.cpp - src/value_time_queue.cpp) + add_rostest_gtest( + vel_pose_diff_checker-test + test/test_vel_pose_diff_checker.test + test/src/test_vel_pose_diff_checker.cpp + src/vel_pose_diff_checker_core.cpp + src/value_time_queue.cpp + ) target_link_libraries(vel_pose_diff_checker-test ${catkin_LIBRARIES}) endif() diff --git a/core_perception/vel_pose_diff_checker/config/health_checker.yaml b/core_perception/vel_pose_diff_checker/config/health_checker.yaml new file mode 100644 index 00000000000..6bca1d4eb30 --- /dev/null +++ b/core_perception/vel_pose_diff_checker/config/health_checker.yaml @@ -0,0 +1,13 @@ +health_checker: + vel_pose_diff_checker_diff_pose_topic_time: + default + vel_pose_diff_checker_diff_twist_topic_time: + default + vel_pose_diff_checker_diff_position: + default + vel_pose_diff_checker_diff_position_median: + default + vel_pose_diff_checker_diff_angle: + default + vel_pose_diff_checker_diff_angle_median: + default diff --git a/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/value_time_queue.h b/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/value_time_queue.h index f629b0341ca..56fefc651c6 100644 --- a/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/value_time_queue.h +++ b/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/value_time_queue.h @@ -25,9 +25,7 @@ class ValueTimeQueue { struct ValueTime { - ValueTime(const double a_value, const ros::Time &a_stamp) - : value(a_value) - , stamp(a_stamp) + ValueTime(const double a_value, const ros::Time& a_stamp) : value(a_value), stamp(a_stamp) { } @@ -35,16 +33,16 @@ class ValueTimeQueue ros::Time stamp; }; - public: - ValueTimeQueue(); - explicit ValueTimeQueue(const double window_size_sec); - void addValueTime(const double value, const ros::Time &a_stamp); - double getMedianValue() const; - void setWindowSizeSec(const double time_window_size_sec); +public: + ValueTimeQueue(); + explicit ValueTimeQueue(const double window_size_sec); + void addValueTime(const double value, const ros::Time& a_stamp); + double getMedianValue() const; + void setWindowSizeSec(const double time_window_size_sec); - private: - double window_size_sec_; - std::deque queue_; +private: + double window_size_sec_; + std::deque queue_; }; #endif // VEL_POSE_DIFF_CHECKER_VALUE_TIME_QUEUE_H diff --git a/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/vel_pose_diff_checker_core.h b/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/vel_pose_diff_checker_core.h index 172512acde0..954cb7ca8af 100644 --- a/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/vel_pose_diff_checker_core.h +++ b/core_perception/vel_pose_diff_checker/include/vel_pose_diff_checker/vel_pose_diff_checker_core.h @@ -17,61 +17,92 @@ #ifndef VEL_POSE_DIFF_CHECKER_VEL_POSE_DIFF_CHECKER_CORE_H #define VEL_POSE_DIFF_CHECKER_VEL_POSE_DIFF_CHECKER_CORE_H +#include #include +#include #include +#include #include #include -#include "vel_pose_diff_checker/value_time_queue.h" +#include +#include "vel_pose_diff_checker/value_time_queue.h" class VelPoseDiffChecker { friend class VelPoseDiffCheckerTestSuite; - - public: - enum class Status { ERROR = 0, OK = 1, INVALID = 2 }; - - VelPoseDiffChecker(const ros::NodeHandle& nh, const ros::NodeHandle& private_nh); - void run(); - - private: - void callbackPose(const geometry_msgs::PoseStamped::ConstPtr& msg); - void callbackTwist(const geometry_msgs::TwistStamped::ConstPtr& msg); - VelPoseDiffChecker::Status checkDiff(); - - ros::NodeHandle nh_; - ros::NodeHandle private_nh_; - - ros::Subscriber pose_sub_; - ros::Subscriber twist_sub_; - - ros::Publisher diff_position_pub_; - ros::Publisher diff_position_median_pub_; - ros::Publisher diff_angle_rad_pub_; - ros::Publisher diff_angle_rad_median_pub_; - ros::Publisher diff_angle_deg_pub_; - ros::Publisher diff_angle_deg_median_pub_; - ros::Publisher remote_cmd_pub_; - - ValueTimeQueue dist_time_queue_; - ValueTimeQueue angle_time_queue_; - std::deque< boost::shared_ptr > pose_ptr_queue_; - std::deque< boost::shared_ptr > twist_ptr_queue_; - - double loop_rate_hz_; - double comparison_window_size_sec_; - double topic_timeout_sec_; - double moving_median_window_size_sec_; - - double diff_position_threshold_meter_; - double diff_position_median_threshold_meter_; - double diff_angle_threshold_rad_; - double diff_angle_median_threshold_rad_; - - bool enable_emergency_to_twist_gate_; + struct CheckValues + { + double diff_pose_topic_time = 0.0; + double diff_twist_topic_time = 0.0; + double diff_position = 0.0; + double diff_position_median = 0.0; + double diff_angle = 0.0; + double diff_angle_median = 0.0; + }; + + struct CheckValueThresholds + { + std::string key; + double warn_value; + double error_value; + double fatal_value; + std::string error_description; + }; + +public: + VelPoseDiffChecker(const ros::NodeHandle& nh, const ros::NodeHandle& private_nh); + +private: + void callbackPose(const geometry_msgs::PoseStamped::ConstPtr& msg); + void callbackTwist(const geometry_msgs::TwistStamped::ConstPtr& msg); + void callbackTimer(const ros::TimerEvent& e); + CheckValues checkDiff(); + uint8_t getErrorLevelWithHealthChecker(const CheckValues& check_values); + void publishCheckValues(const CheckValues& check_values); + std::pair calcDeltaTfPoseAndTime( + const boost::shared_ptr& current_pose_ptr, + const ros::Time& ros_time_now, const ros::Time& ros_time_past); + std::deque>::iterator + searchCurrentTwistPtrItr(const ros::Time& pose_time_current); + tf::Transform calcDeltaTfOdom( + const std::deque>::iterator& current_twist_ptr_it, + const ros::Time& pose_time_past); + + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + + ros::Subscriber pose_sub_; + ros::Subscriber twist_sub_; + ros::Timer timer_; + + ros::Publisher diff_position_pub_; + ros::Publisher diff_position_median_pub_; + ros::Publisher diff_angle_rad_pub_; + ros::Publisher diff_angle_rad_median_pub_; + ros::Publisher diff_angle_deg_pub_; + ros::Publisher diff_angle_deg_median_pub_; + + autoware_health_checker::HealthChecker health_checker_; + + ValueTimeQueue dist_time_queue_; + ValueTimeQueue angle_time_queue_; + std::deque > pose_ptr_queue_; + std::deque > twist_ptr_queue_; + + double loop_rate_hz_; + double comparison_window_size_sec_; + double moving_median_window_size_sec_; + + CheckValueThresholds diff_pose_topic_time_thresholds_; + CheckValueThresholds diff_twist_topic_time_thresholds_; + CheckValueThresholds diff_position_thresholds_; + CheckValueThresholds diff_position_median_thresholds_; + CheckValueThresholds diff_angle_thresholds_; + CheckValueThresholds diff_angle_median_thresholds_; }; #endif // VEL_POSE_DIFF_CHECKER_VEL_POSE_DIFF_CHECKER_CORE_H diff --git a/core_perception/vel_pose_diff_checker/launch/vel_pose_diff_checker.launch b/core_perception/vel_pose_diff_checker/launch/vel_pose_diff_checker.launch index fb308cabff8..52c1aac881c 100644 --- a/core_perception/vel_pose_diff_checker/launch/vel_pose_diff_checker.launch +++ b/core_perception/vel_pose_diff_checker/launch/vel_pose_diff_checker.launch @@ -5,14 +5,15 @@ - + - - + + + @@ -27,7 +28,6 @@ - - + diff --git a/core_perception/vel_pose_diff_checker/package.xml b/core_perception/vel_pose_diff_checker/package.xml index bb041a686c0..d42e5378a2d 100755 --- a/core_perception/vel_pose_diff_checker/package.xml +++ b/core_perception/vel_pose_diff_checker/package.xml @@ -14,7 +14,9 @@ std_msgs geometry_msgs autoware_msgs + autoware_system_msgs amathutils_lib + autoware_health_checker roslint diff --git a/core_perception/vel_pose_diff_checker/src/value_time_queue.cpp b/core_perception/vel_pose_diff_checker/src/value_time_queue.cpp index e2d84ad6e97..a8b0097f123 100644 --- a/core_perception/vel_pose_diff_checker/src/value_time_queue.cpp +++ b/core_perception/vel_pose_diff_checker/src/value_time_queue.cpp @@ -20,18 +20,15 @@ #include #include - -ValueTimeQueue::ValueTimeQueue() - : window_size_sec_(1.0) +ValueTimeQueue::ValueTimeQueue() : window_size_sec_(1.0) { } -ValueTimeQueue::ValueTimeQueue(const double window_size_sec) - : window_size_sec_(window_size_sec) +ValueTimeQueue::ValueTimeQueue(const double window_size_sec) : window_size_sec_(window_size_sec) { } -void ValueTimeQueue::addValueTime(const double value, const ros::Time &a_stamp) +void ValueTimeQueue::addValueTime(const double value, const ros::Time& a_stamp) { const auto ros_time_now = ros::Time::now(); queue_.push_back(ValueTime(value, a_stamp)); @@ -58,10 +55,7 @@ double ValueTimeQueue::getMedianValue() const std::deque queue_tmp = queue_; const size_t median_index = queue_tmp.size() / 2; std::nth_element(std::begin(queue_tmp), std::begin(queue_tmp) + median_index, std::end(queue_tmp), - [](const ValueTime &lhs, const ValueTime &rhs) - { - return lhs.value < rhs.value; - }); // NOLINT + [](const ValueTime& lhs, const ValueTime& rhs) { return lhs.value < rhs.value; }); // NOLINT return queue_tmp.at(median_index).value; } diff --git a/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_core.cpp b/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_core.cpp index 87a00dd3731..b13204163ba 100755 --- a/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_core.cpp +++ b/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_core.cpp @@ -19,19 +19,20 @@ #include #include #include +#include +#include #include -#include #include #include #include #include +#include #include // referenced by lane_select -tf::Point convertPointIntoRelativeCoordinate(const geometry_msgs::Point &input_point, - const geometry_msgs::Pose &pose) +tf::Point convertPointIntoRelativeCoordinate(const geometry_msgs::Point& input_point, const geometry_msgs::Pose& pose) { tf::Transform inverse; tf::poseMsgToTF(pose, inverse); @@ -46,35 +47,73 @@ tf::Point convertPointIntoRelativeCoordinate(const geometry_msgs::Point &input_p VelPoseDiffChecker::VelPoseDiffChecker(const ros::NodeHandle& nh, const ros::NodeHandle& private_nh) : nh_(nh) , private_nh_(private_nh) + , health_checker_(nh, private_nh) , loop_rate_hz_(10.0) , comparison_window_size_sec_(1.0) - , topic_timeout_sec_(0.3) , moving_median_window_size_sec_(2.0) - , diff_position_threshold_meter_(1.0) - , diff_position_median_threshold_meter_(0.5) - , diff_angle_threshold_rad_(0.1) - , diff_angle_median_threshold_rad_(0.05) - , enable_emergency_to_twist_gate_(true) + , diff_pose_topic_time_thresholds_ + { + "vel_pose_diff_checker_diff_pose_topic_time", 0.24, 0.3, DBL_MAX, + "[vel_pose_diff_checker] pose topic is timeout" + } + , diff_twist_topic_time_thresholds_ + { + "vel_pose_diff_checker_diff_twist_topic_time", 0.24, 0.3, DBL_MAX, + "[vel_pose_diff_checker] twist topic is timeout" + } + , diff_position_thresholds_ + { + "vel_pose_diff_checker_diff_position", 0.8, 1.0, DBL_MAX, + "[vel_pose_diff_checker] detect position difference" + } + , diff_position_median_thresholds_ + { + "vel_pose_diff_checker_diff_position_median", 0.4, 0.5, DBL_MAX, + "[vel_pose_diff_checker] detect position_median difference" + } + , diff_angle_thresholds_ + { + "vel_pose_diff_checker_diff_angle", 0.08, 0.1, DBL_MAX, + "[vel_pose_diff_checker] detect angle difference" + } + , diff_angle_median_thresholds_ + { + "vel_pose_diff_checker_diff_angle_median", 0.04, 0.05, DBL_MAX, + "[vel_pose_diff_checker] detect angle_median difference" + } { private_nh_.getParam("loop_rate_hz", loop_rate_hz_); private_nh_.getParam("comparison_window_size_sec", comparison_window_size_sec_); - private_nh_.getParam("topic_timeout_sec", topic_timeout_sec_); private_nh_.getParam("moving_median_window_size_sec", moving_median_window_size_sec_); dist_time_queue_.setWindowSizeSec(moving_median_window_size_sec_); angle_time_queue_.setWindowSizeSec(moving_median_window_size_sec_); - private_nh_.getParam("diff_position_threshold_meter", diff_position_threshold_meter_); - private_nh_.getParam("diff_position_median_threshold_meter", diff_position_median_threshold_meter_); - private_nh_.getParam("diff_angle_threshold_rad", diff_angle_threshold_rad_); - private_nh_.getParam("diff_angle_median_threshold_rad", diff_angle_median_threshold_rad_); + private_nh_.getParam("topic_timeout_sec", diff_pose_topic_time_thresholds_.error_value); + private_nh_.getParam("topic_timeout_sec", diff_twist_topic_time_thresholds_.error_value); + private_nh_.getParam("diff_position_threshold_meter", diff_position_thresholds_.error_value); + private_nh_.getParam("diff_position_median_threshold_meter", diff_position_median_thresholds_.error_value); + private_nh_.getParam("diff_angle_threshold_rad", diff_angle_thresholds_.error_value); + private_nh_.getParam("diff_angle_median_threshold_rad", diff_angle_median_thresholds_.error_value); - private_nh_.getParam("enable_emergency_to_twist_gate", enable_emergency_to_twist_gate_); + constexpr double error_to_warn_value_ratio = 0.8; + std::vector thresholds + { + &diff_pose_topic_time_thresholds_, &diff_twist_topic_time_thresholds_, + &diff_position_thresholds_, &diff_position_median_thresholds_, + &diff_angle_thresholds_, &diff_angle_median_thresholds_ + }; + + for (auto* th : thresholds) + { + th->warn_value = th->error_value * error_to_warn_value_ratio; + } pose_sub_ = nh_.subscribe("current_pose", 10, &VelPoseDiffChecker::callbackPose, this, ros::TransportHints().tcpNoDelay(true)); twist_sub_ = nh_.subscribe("current_velocity", 10, &VelPoseDiffChecker::callbackTwist, this, - ros::TransportHints().tcpNoDelay(true)); + ros::TransportHints().tcpNoDelay(true)); + timer_ = nh_.createTimer(ros::Rate(loop_rate_hz_), &VelPoseDiffChecker::callbackTimer, this); // for visualize diff_position_pub_ = private_nh_.advertise("diff_position", 10); @@ -84,30 +123,32 @@ VelPoseDiffChecker::VelPoseDiffChecker(const ros::NodeHandle& nh, const ros::Nod diff_angle_deg_pub_ = private_nh_.advertise("diff_angle_deg", 10); diff_angle_deg_median_pub_ = private_nh_.advertise("diff_angle_deg_median", 10); - // to twist_gate - remote_cmd_pub_ = nh_.advertise("remote_cmd", 10); + health_checker_.ENABLE(); } -void VelPoseDiffChecker::run() +void VelPoseDiffChecker::callbackTimer(const ros::TimerEvent& e) { - ros::Rate rate(loop_rate_hz_); - - while (ros::ok()) + const CheckValues check_values = checkDiff(); + const auto error_level = getErrorLevelWithHealthChecker(check_values); + if (error_level >= autoware_system_msgs::DiagnosticStatus::ERROR) { - ros::spinOnce(); - - VelPoseDiffChecker::Status status = checkDiff(); - - if (enable_emergency_to_twist_gate_ && status == VelPoseDiffChecker::Status::ERROR) - { - ROS_WARN("Publish Emergency Flag!!!"); - autoware_msgs::RemoteCmd remote_cmd; - remote_cmd.vehicle_cmd.emergency = true; - remote_cmd_pub_.publish(remote_cmd); - } - - rate.sleep(); + ROS_WARN("Difference Detection!!!!!"); + ROS_WARN("diff_pose_topic_time %lf[sec], diff_twist_topic_time %lf[sec], diff_pos %lf[m], diff_pos_median " + "%lf[m], diff_ang %lf[rad], diff_ang_median %lf[rad]" // NOLINT + , + check_values.diff_pose_topic_time, check_values.diff_twist_topic_time, check_values.diff_position, + check_values.diff_position_median, check_values.diff_angle, check_values.diff_angle_median); } + else + { + ROS_DEBUG("diff_pose_topic_time %lf[sec], diff_twist_topic_time %lf[sec], diff_pos %lf[m], diff_pos_median " + "%lf[m], diff_ang %lf[rad], diff_ang_median %lf[rad]" // NOLINT + , + check_values.diff_pose_topic_time, check_values.diff_twist_topic_time, check_values.diff_position, + check_values.diff_position_median, check_values.diff_angle, check_values.diff_angle_median); + } + + publishCheckValues(check_values); } void VelPoseDiffChecker::callbackPose(const geometry_msgs::PoseStamped::ConstPtr& msg) @@ -121,7 +162,8 @@ void VelPoseDiffChecker::callbackPose(const geometry_msgs::PoseStamped::ConstPtr { pose_ptr_queue_.pop_front(); } - else if (pose_ptr_queue_.front()->header.stamp < msg->header.stamp-ros::Duration(comparison_window_size_sec_*2.0)) + else if (pose_ptr_queue_.front()->header.stamp < + msg->header.stamp - ros::Duration(comparison_window_size_sec_ * 2.0)) { pose_ptr_queue_.pop_front(); } @@ -132,7 +174,6 @@ void VelPoseDiffChecker::callbackPose(const geometry_msgs::PoseStamped::ConstPtr } } - void VelPoseDiffChecker::callbackTwist(const geometry_msgs::TwistStamped::ConstPtr& msg) { twist_ptr_queue_.push_back(msg); @@ -144,7 +185,8 @@ void VelPoseDiffChecker::callbackTwist(const geometry_msgs::TwistStamped::ConstP { twist_ptr_queue_.pop_front(); } - else if (twist_ptr_queue_.front()->header.stamp < msg->header.stamp-ros::Duration(comparison_window_size_sec_*2.0)) + else if (twist_ptr_queue_.front()->header.stamp < + msg->header.stamp - ros::Duration(comparison_window_size_sec_ * 2.0)) { twist_ptr_queue_.pop_front(); } @@ -155,23 +197,86 @@ void VelPoseDiffChecker::callbackTwist(const geometry_msgs::TwistStamped::ConstP } } -VelPoseDiffChecker::Status VelPoseDiffChecker::checkDiff() +std::pair VelPoseDiffChecker::calcDeltaTfPoseAndTime( + const boost::shared_ptr& current_pose_ptr, + const ros::Time& ros_time_now, const ros::Time& ros_time_past) { - const auto ros_time_now = ros::Time::now(); - if (ros_time_now.toSec() == 0.0) + tf::Transform delta_tf_pose(tf::Quaternion(0.0, 0.0, 0.0, 1.0), tf::Vector3(0.0, 0.0, 0.0)); + // NOTE: ros_time_past-ros::Duration(0.05) -> To stabilize the acquisition time + const auto past_pose_ptr_it = + std::lower_bound(std::begin(pose_ptr_queue_), std::end(pose_ptr_queue_), ros_time_past - ros::Duration(0.05), + [](const boost::shared_ptr& x_ptr, ros::Time t) + { + return x_ptr->header.stamp < t; + }); // NOLINT + const auto past_pose_ptr = + past_pose_ptr_it == pose_ptr_queue_.end() ? *(pose_ptr_queue_.end() - 1) : *past_pose_ptr_it; + + delta_tf_pose.setOrigin(convertPointIntoRelativeCoordinate(current_pose_ptr->pose.position, past_pose_ptr->pose)); + tf::Quaternion current_pose_orientation, past_pose_orientation; + tf::quaternionMsgToTF(current_pose_ptr->pose.orientation, current_pose_orientation); + tf::quaternionMsgToTF(past_pose_ptr->pose.orientation, past_pose_orientation); + delta_tf_pose.setRotation(past_pose_orientation.inverse() * current_pose_orientation); + std::pair pair = std::make_pair(delta_tf_pose, past_pose_ptr->header.stamp); + return pair; +} + +std::deque>::iterator + VelPoseDiffChecker::searchCurrentTwistPtrItr(const ros::Time& pose_time_current) +{ + auto current_twist_ptr_it = + std::lower_bound(std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), pose_time_current, + [](const boost::shared_ptr& x_ptr, ros::Time t) + { + return x_ptr->header.stamp < t; + }); // NOLINT + current_twist_ptr_it = + current_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end() - 1) : current_twist_ptr_it; + return current_twist_ptr_it; +} + +tf::Transform VelPoseDiffChecker::calcDeltaTfOdom( + const std::deque>::iterator& current_twist_ptr_it, + const ros::Time& pose_time_past) +{ + tf::Transform delta_tf_odom(tf::Quaternion(0.0, 0.0, 0.0, 1.0), tf::Vector3(0.0, 0.0, 0.0)); + auto past_twist_ptr_it = std::lower_bound( + std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), pose_time_past, + [](const boost::shared_ptr& x_ptr, ros::Time t) + { + return x_ptr->header.stamp < t; + }); // NOLINT + past_twist_ptr_it = past_twist_ptr_it == twist_ptr_queue_.end() ? twist_ptr_queue_.end() - 1 : past_twist_ptr_it; + + ros::Time prev_time = (*past_twist_ptr_it)->header.stamp; + double x = 0.0, y = 0.0, yaw = 0.0; + for (auto twist_ptr_it = past_twist_ptr_it + 1; twist_ptr_it != current_twist_ptr_it + 1; ++twist_ptr_it) { - ROS_WARN_STREAM_THROTTLE(1, "ros_time_now is not yet valid"); - return VelPoseDiffChecker::Status::INVALID; + const double dt = ((*twist_ptr_it)->header.stamp - prev_time).toSec(); + const double dis = (*twist_ptr_it)->twist.linear.x * dt; + yaw += (*twist_ptr_it)->twist.angular.z * dt; + x += dis * std::cos(yaw); + y += dis * std::sin(yaw); + prev_time = (*twist_ptr_it)->header.stamp; } - const auto ros_time_past = ros_time_now-ros::Duration(comparison_window_size_sec_); + delta_tf_odom.setOrigin(tf::Vector3(x, y, 0.0)); + tf::Quaternion tf_quat; + tf_quat.setRPY(0.0, 0.0, yaw); + delta_tf_odom.setRotation(tf_quat); + return delta_tf_odom; +} + +VelPoseDiffChecker::CheckValues VelPoseDiffChecker::checkDiff() +{ + const auto ros_time_now = ros::Time::now(); + const auto ros_time_past = ros_time_now - ros::Duration(comparison_window_size_sec_); auto pose_time_current = ros_time_now; auto pose_time_past = ros_time_past; - bool is_topic_timeout = false; - tf::Transform delta_tf_pose(tf::Quaternion(0.0, 0.0, 0.0, 1.0), tf::Vector3(0.0, 0.0, 0.0)); + double diff_pose_topic_time = 0; if (pose_ptr_queue_.empty()) { @@ -180,37 +285,25 @@ VelPoseDiffChecker::Status VelPoseDiffChecker::checkDiff() else { const auto current_pose_ptr = pose_ptr_queue_.back(); + const auto delta_pose_and_time = calcDeltaTfPoseAndTime(current_pose_ptr, ros_time_now, ros_time_past); + delta_tf_pose = delta_pose_and_time.first; + const auto& past_pose_stamp = delta_pose_and_time.second; - // NOTE: ros_time_past-ros::Duration(0.05) -> To stabilize the acquisition time - const auto past_pose_ptr_it = - std::lower_bound(std::begin(pose_ptr_queue_), std::end(pose_ptr_queue_), ros_time_past-ros::Duration(0.05), - [](const boost::shared_ptr &x_ptr, ros::Time t) - { - return x_ptr->header.stamp < t; - }); // NOLINT - const auto past_pose_ptr = past_pose_ptr_it == pose_ptr_queue_.end() ? *(pose_ptr_queue_.end()-1) - : *past_pose_ptr_it; - - delta_tf_pose.setOrigin(convertPointIntoRelativeCoordinate(current_pose_ptr->pose.position, past_pose_ptr->pose)); - tf::Quaternion current_pose_orientation, past_pose_orientation; - tf::quaternionMsgToTF(current_pose_ptr->pose.orientation, current_pose_orientation); - tf::quaternionMsgToTF(past_pose_ptr->pose.orientation, past_pose_orientation); - delta_tf_pose.setRotation(past_pose_orientation.inverse() * current_pose_orientation); - - if (std::fabs((ros_time_now-current_pose_ptr->header.stamp).toSec()) > topic_timeout_sec_) + diff_pose_topic_time = std::abs((ros_time_now - current_pose_ptr->header.stamp).toSec()); + if (diff_pose_topic_time > diff_pose_topic_time_thresholds_.error_value) { ROS_WARN("current_pose.header.stamp is late. ros_time_now is %lf. current_pose.header.stamp is %lf", - ros_time_now.toSec(), current_pose_ptr->header.stamp.toSec()); - is_topic_timeout = true; + ros_time_now.toSec(), current_pose_ptr->header.stamp.toSec()); } else { pose_time_current = current_pose_ptr->header.stamp; - pose_time_past = past_pose_ptr->header.stamp; + pose_time_past = past_pose_stamp; } } tf::Transform delta_tf_odom(tf::Quaternion(0.0, 0.0, 0.0, 1.0), tf::Vector3(0.0, 0.0, 0.0)); + double diff_twist_topic_time = 0; if (twist_ptr_queue_.empty()) { @@ -218,95 +311,79 @@ VelPoseDiffChecker::Status VelPoseDiffChecker::checkDiff() } else { - auto current_twist_ptr_it = - std::lower_bound(std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), pose_time_current, - [](const boost::shared_ptr &x_ptr, ros::Time t) - { - return x_ptr->header.stamp < t; - }); //NOLINT - current_twist_ptr_it = current_twist_ptr_it == twist_ptr_queue_.end() ? (twist_ptr_queue_.end()-1) - : current_twist_ptr_it; - - auto past_twist_ptr_it = - std::lower_bound(std::begin(twist_ptr_queue_), std::end(twist_ptr_queue_), pose_time_past, - [](const boost::shared_ptr &x_ptr, ros::Time t) - { - return x_ptr->header.stamp < t; - }); //NOLINT - past_twist_ptr_it = past_twist_ptr_it == twist_ptr_queue_.end() ? twist_ptr_queue_.end()-1 - : past_twist_ptr_it; - - if (std::fabs((ros_time_now-(*current_twist_ptr_it)->header.stamp).toSec()) > topic_timeout_sec_) + auto current_twist_ptr_it = searchCurrentTwistPtrItr(pose_time_current); + + diff_twist_topic_time = std::abs((ros_time_now - (*current_twist_ptr_it)->header.stamp).toSec()); + if (diff_twist_topic_time > diff_twist_topic_time_thresholds_.error_value) { ROS_WARN("current_twist.header.stamp is late. ros_time_now is %lf. current_twist.header.stamp is %lf", - ros_time_now.toSec(), (*current_twist_ptr_it)->header.stamp.toSec()); - is_topic_timeout = true; + ros_time_now.toSec(), (*current_twist_ptr_it)->header.stamp.toSec()); } + delta_tf_odom = calcDeltaTfOdom(current_twist_ptr_it, pose_time_past); + } - ros::Time prev_time = (*past_twist_ptr_it)->header.stamp; - double x = 0.0, y = 0.0, yaw = 0.0; - for (auto twist_ptr_it = past_twist_ptr_it+1; twist_ptr_it != current_twist_ptr_it+1; ++twist_ptr_it) - { - const double dt = ((*twist_ptr_it)->header.stamp - prev_time).toSec(); - const double dis = (*twist_ptr_it)->twist.linear.x * dt; - yaw += (*twist_ptr_it)->twist.angular.z * dt; - x += dis * std::cos(yaw); - y += dis * std::sin(yaw); - prev_time = (*twist_ptr_it)->header.stamp; - } + CheckValues check_values; + check_values.diff_pose_topic_time = diff_pose_topic_time; + check_values.diff_twist_topic_time = diff_twist_topic_time; - delta_tf_odom.setOrigin(tf::Vector3(x, y, 0.0)); - tf::Quaternion tf_quat; - tf_quat.setRPY(0.0, 0.0, yaw); - delta_tf_odom.setRotation(tf_quat); - } + check_values.diff_position = (delta_tf_pose.getOrigin() - delta_tf_odom.getOrigin()).length(); + check_values.diff_angle = (delta_tf_odom.getRotation().inverse() * delta_tf_pose.getRotation()).getAngle(); - const double diff_position = (delta_tf_pose.getOrigin()-delta_tf_odom.getOrigin()).length(); - const double diff_angle = (delta_tf_odom.getRotation().inverse() * delta_tf_pose.getRotation()).getAngle(); + dist_time_queue_.addValueTime(check_values.diff_position, ros_time_now); + check_values.diff_position_median = dist_time_queue_.getMedianValue(); - dist_time_queue_.addValueTime(diff_position, ros_time_now); - const double diff_position_median = dist_time_queue_.getMedianValue(); + angle_time_queue_.addValueTime(check_values.diff_angle, ros_time_now); + check_values.diff_angle_median = angle_time_queue_.getMedianValue(); - angle_time_queue_.addValueTime(diff_angle, ros_time_now); - const double diff_angle_median = angle_time_queue_.getMedianValue(); + return check_values; +} +uint8_t VelPoseDiffChecker::getErrorLevelWithHealthChecker(const CheckValues& check_values) +{ + const auto health_check_max_value_func = [this](const double check_value, const CheckValueThresholds& thresholds) + { + return health_checker_.CHECK_MAX_VALUE(thresholds.key, check_value, thresholds.warn_value, thresholds.error_value, + thresholds.fatal_value, thresholds.error_description); + }; + + health_checker_.NODE_ACTIVATE(); + const auto a_error_level = + health_check_max_value_func(check_values.diff_pose_topic_time, diff_pose_topic_time_thresholds_); + const auto b_error_level = + health_check_max_value_func(check_values.diff_twist_topic_time, diff_twist_topic_time_thresholds_); + const auto c_error_level = health_check_max_value_func(check_values.diff_position, diff_position_thresholds_); + const auto d_error_level = + health_check_max_value_func(check_values.diff_position_median, diff_position_median_thresholds_); + const auto e_error_level = health_check_max_value_func(check_values.diff_angle, diff_angle_thresholds_); + const auto f_error_level = health_check_max_value_func(check_values.diff_angle_median, diff_angle_median_thresholds_); + + return std::max({ a_error_level, b_error_level, c_error_level, // NOLINT + d_error_level, e_error_level, f_error_level }); // NOLINT +} + +void VelPoseDiffChecker::publishCheckValues(const CheckValues& check_values) +{ std_msgs::Float32 diff_position_msg; - diff_position_msg.data = diff_position; + diff_position_msg.data = check_values.diff_position; diff_position_pub_.publish(diff_position_msg); std_msgs::Float32 diff_position_median_msg; - diff_position_median_msg.data = diff_position_median; + diff_position_median_msg.data = check_values.diff_position_median; diff_position_median_pub_.publish(diff_position_median_msg); std_msgs::Float32 diff_angle_rad_msg; - diff_angle_rad_msg.data = diff_angle; + diff_angle_rad_msg.data = check_values.diff_angle; diff_angle_rad_pub_.publish(diff_angle_rad_msg); std_msgs::Float32 diff_angle_rad_median_msg; - diff_angle_rad_median_msg.data = diff_angle_median; + diff_angle_rad_median_msg.data = check_values.diff_angle_median; diff_angle_rad_median_pub_.publish(diff_angle_rad_median_msg); std_msgs::Float32 diff_angle_deg_msg; - diff_angle_deg_msg.data = amathutils::rad2deg(diff_angle); + diff_angle_deg_msg.data = amathutils::rad2deg(check_values.diff_angle); diff_angle_deg_pub_.publish(diff_angle_deg_msg); std_msgs::Float32 diff_angle_deg_median_msg; - diff_angle_deg_median_msg.data = amathutils::rad2deg(diff_angle_median); + diff_angle_deg_median_msg.data = amathutils::rad2deg(check_values.diff_angle_median); diff_angle_deg_median_pub_.publish(diff_angle_deg_median_msg); - - if ( is_topic_timeout - || diff_position > diff_position_threshold_meter_ - || diff_position_median > diff_position_median_threshold_meter_ - || diff_angle > diff_angle_threshold_rad_ - || diff_angle_median > diff_angle_median_threshold_rad_ ) - { - ROS_WARN("Difference Detection!!!!!"); - ROS_WARN("is_topic_timeout %d, diff_pos %lf[m], diff_pos_median %lf[m], diff_ang %lf[rad], diff_ang_median %lf[rad]" - , is_topic_timeout, diff_position, diff_position_median, diff_angle, diff_angle_median); - return VelPoseDiffChecker::Status::ERROR; - } - - ROS_DEBUG("is_topic_timeout %d, diff_pos %lf[m], diff_pos_median %lf[m], diff_ang %lf[rad], diff_ang_median %lf[rad]" - , is_topic_timeout, diff_position, diff_position_median, diff_angle, diff_angle_median); - return VelPoseDiffChecker::Status::OK; } diff --git a/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_node.cpp b/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_node.cpp index 562f66c6e80..f3d2265a0bd 100644 --- a/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_node.cpp +++ b/core_perception/vel_pose_diff_checker/src/vel_pose_diff_checker_node.cpp @@ -16,14 +16,14 @@ #include "vel_pose_diff_checker/vel_pose_diff_checker_core.h" -int main(int argc, char **argv) +int main(int argc, char** argv) { ros::init(argc, argv, "vel_pose_diff_checker"); ros::NodeHandle nh; ros::NodeHandle private_nh("~"); VelPoseDiffChecker node(nh, private_nh); - node.run(); + ros::spin(); return 0; } diff --git a/core_perception/vel_pose_diff_checker/test/src/test_vel_pose_diff_checker.cpp b/core_perception/vel_pose_diff_checker/test/src/test_vel_pose_diff_checker.cpp index fe390289fdd..543a899d127 100644 --- a/core_perception/vel_pose_diff_checker/test/src/test_vel_pose_diff_checker.cpp +++ b/core_perception/vel_pose_diff_checker/test/src/test_vel_pose_diff_checker.cpp @@ -37,12 +37,10 @@ class VelPoseDiffCheckerTestSuite : public ::testing::Test ~VelPoseDiffCheckerTestSuite() { } - - void getStatus(VelPoseDiffChecker::Status* status) + uint8_t getErrorLevel() { - *status = obj_ptr_->checkDiff(); + return obj_ptr_->getErrorLevelWithHealthChecker(obj_ptr_->checkDiff()); } - std::unique_ptr obj_ptr_; ros::NodeHandle nh_; @@ -51,6 +49,7 @@ class VelPoseDiffCheckerTestSuite : public ::testing::Test protected: virtual void SetUp() { + nh_.setParam("/health_checker/vel_pose_diff_checker_diff_position", "default"); obj_ptr_ = std::make_unique(nh_, private_nh_); }; virtual void TearDown() @@ -85,7 +84,6 @@ TEST_F(VelPoseDiffCheckerTestSuite, checkDiff) constexpr double dt = 0.1; constexpr double linear_x = 1.0; constexpr double noise = 1.0; - VelPoseDiffChecker::Status status; // TEST No Difference for (size_t i = 0; i < 10; ++i) @@ -103,8 +101,7 @@ TEST_F(VelPoseDiffCheckerTestSuite, checkDiff) ros::spinOnce(); ros::Duration(dt).sleep(); } - getStatus(&status); - ASSERT_TRUE(status == VelPoseDiffChecker::Status::OK); + ASSERT_EQ(getErrorLevel(), autoware_system_msgs::DiagnosticStatus::OK); // TEST Detect Difference for (size_t i = 0; i < 5; ++i) @@ -122,8 +119,7 @@ TEST_F(VelPoseDiffCheckerTestSuite, checkDiff) ros::spinOnce(); ros::Duration(dt).sleep(); } - getStatus(&status); - ASSERT_TRUE(status == VelPoseDiffChecker::Status::ERROR); + ASSERT_EQ(getErrorLevel(), autoware_system_msgs::DiagnosticStatus::ERROR); } int main(int argc, char** argv) diff --git a/core_planning/astar_search/CMakeLists.txt b/core_planning/astar_search/CMakeLists.txt index 184138ddcba..ea24d79c327 100644 --- a/core_planning/astar_search/CMakeLists.txt +++ b/core_planning/astar_search/CMakeLists.txt @@ -3,8 +3,8 @@ project(astar_search) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") +find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS - autoware_build_flags autoware_msgs geometry_msgs pcl_ros @@ -17,14 +17,6 @@ find_package(catkin REQUIRED COMPONENTS catkin_package( INCLUDE_DIRS include LIBRARIES astar_search - CATKIN_DEPENDS - autoware_msgs - geometry_msgs - pcl_ros - roscpp - sensor_msgs - tf - tf_conversions ) include_directories( @@ -46,18 +38,25 @@ add_dependencies(astar_search ) install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.h" + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" ) install(TARGETS astar_search - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) - add_rostest_gtest(astar_search-test test/test_astar_search.test test/src/test_main.cpp test/src/test_astar_util.cpp test/src/test_astar_search.cpp test/src/test_class.cpp) + add_rostest_gtest( + astar_search-test + test/test_astar_search.test + test/src/test_main.cpp + test/src/test_astar_util.cpp + test/src/test_astar_search.cpp + test/src/test_class.cpp + ) target_link_libraries(astar_search-test ${catkin_LIBRARIES} astar_search) endif() diff --git a/core_planning/astar_search/src/astar_search.cpp b/core_planning/astar_search/src/astar_search.cpp index e2bd2041f7f..185df4180ab 100644 --- a/core_planning/astar_search/src/astar_search.cpp +++ b/core_planning/astar_search/src/astar_search.cpp @@ -198,13 +198,13 @@ bool AstarSearch::makePlan(const geometry_msgs::Pose& start_pose, const geometry { if (!setStartNode(start_pose)) { - // ROS_WARN_STREAM("Invalid start pose"); + ROS_DEBUG("Invalid start pose"); return false; } if (!setGoalNode(goal_pose)) { - // ROS_WARN_STREAM("Invalid goal pose"); + ROS_DEBUG("Invalid goal pose"); return false; } @@ -285,7 +285,7 @@ bool AstarSearch::setGoalNode(const geometry_msgs::Pose& goal_pose) if (!wavefront_result) { - // ROS_WARN("Reachable is false..."); + ROS_DEBUG("Reachable is false..."); return false; } } @@ -345,7 +345,7 @@ bool AstarSearch::search() double msec = (now - begin).toSec() * 1000.0; if (msec > time_limit_) { - // ROS_WARN("Exceed time limit of %lf [ms]", time_limit_); + ROS_DEBUG("Exceed time limit of %lf [ms]", time_limit_); return false; } @@ -360,7 +360,7 @@ bool AstarSearch::search() // Goal check if (isGoal(current_an->x, current_an->y, current_an->theta)) { - // ROS_INFO("Search time: %lf [msec]", (now - begin).toSec() * 1000.0); + ROS_DEBUG("Search time: %lf [msec]", (now - begin).toSec() * 1000.0); setPath(top_sn); return true; } @@ -455,7 +455,7 @@ bool AstarSearch::search() } // Failed to find path - // ROS_INFO("Open list is empty..."); + ROS_DEBUG("Open list is empty..."); return false; } diff --git a/core_planning/astar_search/test/src/test_astar_util.cpp b/core_planning/astar_search/test/src/test_astar_util.cpp index 824e19a3bee..654e47c890c 100644 --- a/core_planning/astar_search/test/src/test_astar_util.cpp +++ b/core_planning/astar_search/test/src/test_astar_util.cpp @@ -23,138 +23,138 @@ //class TestSuite2: public ::testing::Test { //public: -// TestSuite2(){} -// ~TestSuite2(){} +// TestSuite2(){} +// ~TestSuite2(){} //}; TEST_F(TestSuite, CheckGreaterThanOperator){ - int x = 0; - int y = 0; - int theta = 0; - double gc = 0; - double hc = 10; + int x = 0; + int y = 0; + int theta = 0; + double gc = 0; + double hc = 10; - SimpleNode simple_node1; - SimpleNode simple_node2(x, y, theta, gc, hc); + SimpleNode simple_node1; + SimpleNode simple_node2(x, y, theta, gc, hc); - ASSERT_TRUE(simple_node2 > simple_node1) << "Should be true"; - ASSERT_TRUE(!(simple_node1 > simple_node2)) << "Should be false"; + ASSERT_TRUE(simple_node2 > simple_node1) << "Should be true"; + ASSERT_TRUE(!(simple_node1 > simple_node2)) << "Should be false"; } TEST_F(TestSuite, CalculateDistanceBetween2Points){ - // Point 1 - double x1 = 0.0; - double y1 = 0.0; - // Point 2 - double x2 = 3.0; - double y2 = 4.0; - ASSERT_EQ(calcDistance(x1, y1, x2, y2), sqrt(x2*x2 + y2*y2)) << "Distance should be " << sqrt(x2*x2 + y2*y2); + // Point 1 + double x1 = 0.0; + double y1 = 0.0; + // Point 2 + double x2 = 3.0; + double y2 = 4.0; + ASSERT_EQ(calcDistance(x1, y1, x2, y2), sqrt(x2*x2 + y2*y2)) << "Distance should be " << sqrt(x2*x2 + y2*y2); } TEST_F(TestSuite, CheckThetaWrapAround){ - double theta = -90; //Degrees - double theta_new = (theta+360)*M_PI/180; - ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; + double theta = -90; //Degrees + double theta_new = (theta+360)*M_PI/180; + ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; - theta = 400; - theta_new = (theta-360)*M_PI/180; - ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; + theta = 400; + theta_new = (theta-360)*M_PI/180; + ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; - theta = 60; - theta_new = theta*M_PI/180; - ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; + theta = 60; + theta_new = theta*M_PI/180; + ASSERT_DOUBLE_EQ(modifyTheta(theta*M_PI/180), theta_new) << "Angle should be " << theta_new; } TEST_F(TestSuite, CheckTransformPose){ - // Check translation of 1 along X axis - tf::Quaternion q(0,0,0,1); - tf::Vector3 v(1,0,0); - geometry_msgs::Pose in_pose, out_pose, expected_pose; - - in_pose.position.x = 0; - in_pose.position.y = 0; - in_pose.position.z = 0; - in_pose.orientation.x = 0; - in_pose.orientation.y = 0; - in_pose.orientation.z = 0; - in_pose.orientation.w = 1; - expected_pose.position.x = 1; - expected_pose.position.y = 0; - expected_pose.position.z = 0; - expected_pose.orientation.x = 0; - expected_pose.orientation.y = 0; - expected_pose.orientation.z = 0; - expected_pose.orientation.w = 1; - tf::Transform translation(q, v); - - out_pose = transformPose(in_pose, translation); - - ASSERT_DOUBLE_EQ(out_pose.position.x, expected_pose.position.x) << "X Coordinate should be " << expected_pose.position.x; - ASSERT_DOUBLE_EQ(out_pose.position.y, expected_pose.position.y) << "Y Coordinate should be " << expected_pose.position.y; - ASSERT_DOUBLE_EQ(out_pose.position.z, expected_pose.position.z) << "Z Coordinate should be " << expected_pose.position.z; - ASSERT_DOUBLE_EQ(out_pose.orientation.x, expected_pose.orientation.x) << "X Quaternion should be " << expected_pose.orientation.x; - ASSERT_DOUBLE_EQ(out_pose.orientation.y, expected_pose.orientation.y) << "Y Quaternion should be " << expected_pose.orientation.y; - ASSERT_DOUBLE_EQ(out_pose.orientation.z, expected_pose.orientation.z) << "Z Quaternion should be " << expected_pose.orientation.z; - ASSERT_DOUBLE_EQ(out_pose.orientation.w, expected_pose.orientation.w) << "W Quaternion should be " << expected_pose.orientation.w; + // Check translation of 1 along X axis + tf::Quaternion q(0,0,0,1); + tf::Vector3 v(1,0,0); + geometry_msgs::Pose in_pose, out_pose, expected_pose; + + in_pose.position.x = 0; + in_pose.position.y = 0; + in_pose.position.z = 0; + in_pose.orientation.x = 0; + in_pose.orientation.y = 0; + in_pose.orientation.z = 0; + in_pose.orientation.w = 1; + expected_pose.position.x = 1; + expected_pose.position.y = 0; + expected_pose.position.z = 0; + expected_pose.orientation.x = 0; + expected_pose.orientation.y = 0; + expected_pose.orientation.z = 0; + expected_pose.orientation.w = 1; + tf::Transform translation(q, v); + + out_pose = transformPose(in_pose, translation); + + ASSERT_DOUBLE_EQ(out_pose.position.x, expected_pose.position.x) << "X Coordinate should be " << expected_pose.position.x; + ASSERT_DOUBLE_EQ(out_pose.position.y, expected_pose.position.y) << "Y Coordinate should be " << expected_pose.position.y; + ASSERT_DOUBLE_EQ(out_pose.position.z, expected_pose.position.z) << "Z Coordinate should be " << expected_pose.position.z; + ASSERT_DOUBLE_EQ(out_pose.orientation.x, expected_pose.orientation.x) << "X Quaternion should be " << expected_pose.orientation.x; + ASSERT_DOUBLE_EQ(out_pose.orientation.y, expected_pose.orientation.y) << "Y Quaternion should be " << expected_pose.orientation.y; + ASSERT_DOUBLE_EQ(out_pose.orientation.z, expected_pose.orientation.z) << "Z Quaternion should be " << expected_pose.orientation.z; + ASSERT_DOUBLE_EQ(out_pose.orientation.w, expected_pose.orientation.w) << "W Quaternion should be " << expected_pose.orientation.w; } TEST_F(TestSuite, CheckWaveFrontNodeConstruct){ - WaveFrontNode node; - ASSERT_EQ(node.index_x, 0) << "index_x should be " << 0; - ASSERT_EQ(node.index_y, 0) << "index_y should be " << 0; - ASSERT_EQ(node.hc, 0) << "hc should be " << 0; - - int x = 0; - int y = 0; - double cost = 10; - node = getWaveFrontNode(x, y, cost); - ASSERT_EQ(node.index_x, x) << "index_x should be " << x; - ASSERT_EQ(node.index_y, y) << "index_y should be " << y; - ASSERT_EQ(node.hc, cost) << "hc should be " << cost; + WaveFrontNode node; + ASSERT_EQ(node.index_x, 0) << "index_x should be " << 0; + ASSERT_EQ(node.index_y, 0) << "index_y should be " << 0; + ASSERT_EQ(node.hc, 0) << "hc should be " << 0; + + int x = 0; + int y = 0; + double cost = 10; + node = getWaveFrontNode(x, y, cost); + ASSERT_EQ(node.index_x, x) << "index_x should be " << x; + ASSERT_EQ(node.index_y, y) << "index_y should be " << y; + ASSERT_EQ(node.hc, cost) << "hc should be " << cost; } TEST_F(TestSuite, CheckRelativeCoordinate){ - geometry_msgs::Pose in_pose; - in_pose.position.x = 1; - in_pose.position.y = -4; - in_pose.position.z = 8; - in_pose.orientation.x = 0; - in_pose.orientation.y = 0; - in_pose.orientation.z = 0; - in_pose.orientation.w = 1; - - tf::Point point = tf::Point(0,0,0); - - geometry_msgs::Point relative_point = calcRelativeCoordinate(in_pose, point); - geometry_msgs::Point expected_point; - expected_point.x = -in_pose.position.x; - expected_point.y = -in_pose.position.y; - expected_point.z = -in_pose.position.z; - - ASSERT_EQ(relative_point.x, expected_point.x) << "X coord should be " << expected_point.x; - ASSERT_EQ(relative_point.y, expected_point.y) << "Y coord should be " << expected_point.y; - ASSERT_EQ(relative_point.z, expected_point.z) << "Z coord should be " << expected_point.z; + geometry_msgs::Pose in_pose; + in_pose.position.x = 1; + in_pose.position.y = -4; + in_pose.position.z = 8; + in_pose.orientation.x = 0; + in_pose.orientation.y = 0; + in_pose.orientation.z = 0; + in_pose.orientation.w = 1; + + tf::Point point = tf::Point(0,0,0); + + geometry_msgs::Point relative_point = calcRelativeCoordinate(in_pose, point); + geometry_msgs::Point expected_point; + expected_point.x = -in_pose.position.x; + expected_point.y = -in_pose.position.y; + expected_point.z = -in_pose.position.z; + + ASSERT_EQ(relative_point.x, expected_point.x) << "X coord should be " << expected_point.x; + ASSERT_EQ(relative_point.y, expected_point.y) << "Y coord should be " << expected_point.y; + ASSERT_EQ(relative_point.z, expected_point.z) << "Z coord should be " << expected_point.z; } TEST_F(TestSuite, CheckRadianDifference){ - // Diff < 180 degrees - double a = 0*M_PI/180; - double b = 90*M_PI/180; - ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 90*M_PI/180) << "diff should be " << 90*M_PI/180; + // Diff < 180 degrees + double a = 0*M_PI/180; + double b = 90*M_PI/180; + ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 90*M_PI/180) << "diff should be " << 90*M_PI/180; - // 180 degrees < Diff < 360 degrees - a = 0*M_PI/180; - b = 190*M_PI/180; - ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 170*M_PI/180) << "diff should be " << 170*M_PI/180; + // 180 degrees < Diff < 360 degrees + a = 0*M_PI/180; + b = 190*M_PI/180; + ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 170*M_PI/180) << "diff should be " << 170*M_PI/180; - // Diff > 360 degrees - a = 0*M_PI/180; - b = 400*M_PI/180; - ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 40*M_PI/180) << "diff should be " << 40*M_PI/180; + // Diff > 360 degrees + a = 0*M_PI/180; + b = 400*M_PI/180; + ASSERT_DOUBLE_EQ(calcDiffOfRadian(a, b), 40*M_PI/180) << "diff should be " << 40*M_PI/180; } diff --git a/core_planning/astar_search/test/src/test_main.cpp b/core_planning/astar_search/test/src/test_main.cpp index ee162efd169..c595b9258d5 100644 --- a/core_planning/astar_search/test/src/test_main.cpp +++ b/core_planning/astar_search/test/src/test_main.cpp @@ -19,12 +19,12 @@ class TestSuite: public ::testing::Test { public: - TestSuite(){} - ~TestSuite(){} + TestSuite(){} + ~TestSuite(){} }; int main(int argc, char **argv) { - testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "TestNode"); - return RUN_ALL_TESTS(); + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "TestNode"); + return RUN_ALL_TESTS(); } diff --git a/core_planning/decision_maker/include/decision_maker/decision_maker_node.hpp b/core_planning/decision_maker/include/decision_maker/decision_maker_node.hpp index 3556ae55e0a..f510cf0ae23 100644 --- a/core_planning/decision_maker/include/decision_maker/decision_maker_node.hpp +++ b/core_planning/decision_maker/include/decision_maker/decision_maker_node.hpp @@ -48,7 +48,7 @@ #include #include -#include +#include namespace decision_maker { @@ -403,6 +403,7 @@ class DecisionMakerNode private_nh_.getParam("stopline_reset_count", stopline_reset_count_); private_nh_.getParam("sim_mode", sim_mode_); private_nh_.getParam("use_ll2", use_lanelet_map_); + private_nh_.getParam("insert_stop_line_wp", insert_stop_line_wp_); private_nh_.param("stop_sign_id", stop_sign_id_, "stop_sign"); current_status_.prev_stopped_wpidx = -1; diff --git a/core_planning/decision_maker/launch/decision_maker.launch b/core_planning/decision_maker/launch/decision_maker.launch index 9e3e6dcaf02..4c0bbd77ec4 100644 --- a/core_planning/decision_maker/launch/decision_maker.launch +++ b/core_planning/decision_maker/launch/decision_maker.launch @@ -19,6 +19,7 @@ + @@ -40,5 +41,6 @@ + diff --git a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp index f14997784b6..bee95e20f6e 100644 --- a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp +++ b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp @@ -158,7 +158,7 @@ void DecisionMakerNode::setWaypointStateUsingVectorMap(autoware_msgs::LaneArray& } } - // STOP + // Get stoplines associated with stop signs (not traffic lights) std::vector stoplines = g_vmap.findByFilter([&](const StopLine& stopline) { return ((g_vmap.findByKey(Key(stopline.signid)).type & (autoware_msgs::WaypointState::TYPE_STOP | autoware_msgs::WaypointState::TYPE_STOPLINE)) != 0); @@ -204,7 +204,7 @@ void DecisionMakerNode::setWaypointStateUsingVectorMap(autoware_msgs::LaneArray& target_wp_idx = wp_idx + 1; lane.waypoints.at(target_wp_idx).wpstate.stop_state = g_vmap.findByKey(Key(stopline.signid)).type; - ROS_INFO("Change waypoint type to stopline: #%zu(%f, %f, %f)\n", target_wp_idx, + ROS_INFO("Change waypoint type to stopline: #%d(%f, %f, %f)\n", target_wp_idx, lane.waypoints.at(target_wp_idx).pose.pose.position.x, lane.waypoints.at(target_wp_idx).pose.pose.position.y, lane.waypoints.at(target_wp_idx).pose.pose.position.z); @@ -285,7 +285,9 @@ void DecisionMakerNode::setWaypointStateUsingLanelet2Map(autoware_msgs::LaneArra } lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_); - lanelet::ConstLineStrings3d stoplines = lanelet::utils::query::stopSignStopLines(all_lanelets, stop_sign_id_); + + // Get stop lines associated with stop signs (not traffic lights) + lanelet::ConstLineStrings3d stoplines = lanelet::utils::query::getStopSignStopLines(all_lanelets, stop_sign_id_); for (auto& lane : lane_array.lanes) { diff --git a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_init.cpp b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_init.cpp index 4c18f63d7d5..de3a75d2481 100644 --- a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_init.cpp +++ b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_init.cpp @@ -276,11 +276,9 @@ void DecisionMakerNode::initVectorMap(void) { // Map must be populated before setupStateCallback() is called // in DecisionMakerNode constructor - ROS_INFO("Subscribing to vector map topics."); - g_vmap.subscribe( nh_, Category::POINT | Category::LINE | Category::VECTOR | Category::AREA | Category::STOP_LINE | Category::ROAD_SIGN | Category::CROSS_ROAD, - ros::Duration(5.0)); + ros::Duration(1.0)); vmap_loaded = g_vmap.hasSubscribed(Category::POINT | Category::LINE | Category::AREA | @@ -288,8 +286,12 @@ void DecisionMakerNode::initVectorMap(void) if (!vmap_loaded) { - ROS_WARN("Necessary vectormap topics have not been published."); - ROS_WARN("DecisionMaker will wait until the vectormap has been loaded."); + ROS_WARN_THROTTLE(5, "Necessary vectormap topics have not been published."); + ROS_WARN_THROTTLE(5, "DecisionMaker will wait until the vectormap has been loaded."); + } + else + { + ROS_INFO("Vectormap loaded."); } } diff --git a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_state_motion.cpp b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_state_motion.cpp index 5f3bd983ecd..d5128ad1641 100644 --- a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_state_motion.cpp +++ b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_state_motion.cpp @@ -54,51 +54,54 @@ void DecisionMakerNode::updateDriveState(cstring_t& state_name, int status) } } +// Iterate every waypoint in received /final_waypoints and find the first +// stop sign waypoint within certain search distance. If it is found, its +// gid and stop sign state (either TYPE_STOPLINE or TYPE_STOP) is returned +// as a std::pair. Otherwise, a pair of (NULLSTATE, -1) is returned. std::pair DecisionMakerNode::getStopSignStateFromWaypoint(void) { - static const size_t ignore_idx = 0; static const double mu = 0.7; // dry ground/ asphalt/ normal tire static const double g = 9.80665; static const double margin = 5; static const double reaction_time = 0.3 + margin; // system delay(sec) - static const size_t reset_count = stopline_reset_count_; + const double velocity = amathutils::kmph2mps(current_status_.velocity); const double free_running_distance = reaction_time * velocity; const double braking_distance = velocity * velocity / (2 * g * mu); const double distance_to_target = (free_running_distance + braking_distance) * 2 /* safety margin*/; - std::pair ret(0, -1); + std::pair ret(autoware_msgs::WaypointState::NULLSTATE, -1); double distance = 0.0; geometry_msgs::Pose prev_pose = current_status_.pose; - uint8_t state = 0; - if (ignore_idx > current_status_.finalwaypoints.waypoints.size() || - 3 > current_status_.finalwaypoints.waypoints.size()) + // Index 0 holds ego-vehicle's current pose + if (current_status_.finalwaypoints.waypoints.size() < 3) { return ret; } - // reset previous stop + // reset previous stop sign waypoint if (current_status_.finalwaypoints.waypoints.at(1).gid > current_status_.prev_stopped_wpidx || (unsigned int)(current_status_.prev_stopped_wpidx - current_status_.finalwaypoints.waypoints.at(1).gid) > - reset_count) + stopline_reset_count_) { current_status_.prev_stopped_wpidx = -1; } - for (unsigned int idx = 0; idx < current_status_.finalwaypoints.waypoints.size() - 1; idx++) + // start from index 1 since index 0 holds ego-vehicle's current pose. + for (size_t idx = 1; idx < current_status_.finalwaypoints.waypoints.size() - 1; ++idx) { - distance += amathutils::find_distance(prev_pose, current_status_.finalwaypoints.waypoints.at(idx).pose.pose); - state = current_status_.finalwaypoints.waypoints.at(idx).wpstate.stop_state; + const autoware_msgs::Waypoint ¤t_wpt = current_status_.finalwaypoints.waypoints.at(idx); + distance += amathutils::find_distance(prev_pose, current_wpt.pose.pose); - if (state) + if (current_wpt.wpstate.stop_state != autoware_msgs::WaypointState::NULLSTATE) { - if (current_status_.prev_stopped_wpidx != current_status_.finalwaypoints.waypoints.at(idx).gid) + if (current_status_.prev_stopped_wpidx != current_wpt.gid) { - ret.first = state; - ret.second = current_status_.finalwaypoints.waypoints.at(idx).gid; + ret.first = current_wpt.wpstate.stop_state; + ret.second = current_wpt.gid; break; } } @@ -108,7 +111,7 @@ std::pair DecisionMakerNode::getStopSignStateFromWaypoint(void) break; } - prev_pose = current_status_.finalwaypoints.waypoints.at(idx).pose.pose; + prev_pose = current_wpt.pose.pose; } return ret; } diff --git a/core_planning/decision_maker/test/src/test_node_decision.cpp b/core_planning/decision_maker/test/src/test_node_decision.cpp index c432a849b9a..2c234ccedc0 100644 --- a/core_planning/decision_maker/test/src/test_node_decision.cpp +++ b/core_planning/decision_maker/test/src/test_node_decision.cpp @@ -67,10 +67,10 @@ TEST_F(TestSuite, isLocalizationConvergence) { } TEST_F(TestSuite, isArrivedGoal) { - test_obj_.createFinalWaypoints(); + test_obj_.createFinalWaypoints(); - test_obj_.setCurrentPose(100, 0, 0); - test_obj_.setCurrentVelocity(0.0); + test_obj_.setCurrentPose(100, 0, 0); + test_obj_.setCurrentVelocity(0.0); ASSERT_TRUE(test_obj_.isArrivedGoal()) << "Current pose is outside the target range." << "It should be true"; diff --git a/core_planning/decision_maker/test/src/test_node_state_drive.cpp b/core_planning/decision_maker/test/src/test_node_state_drive.cpp index 82c6f962b51..5cbdd562e81 100644 --- a/core_planning/decision_maker/test/src/test_node_state_drive.cpp +++ b/core_planning/decision_maker/test/src/test_node_state_drive.cpp @@ -41,7 +41,7 @@ class TestSuite : public ::testing::Test { }; TEST_F(TestSuite, getSteeringStateFromWaypoint) { - test_obj_.createFinalWaypoints(); + test_obj_.createFinalWaypoints(); ASSERT_EQ(test_obj_.getSteeringStateFromWaypoint(), autoware_msgs::WaypointState::STR_STRAIGHT) << "Could not get the expected state" @@ -61,9 +61,9 @@ TEST_F(TestSuite, getSteeringStateFromWaypoint) { } TEST_F(TestSuite, getEventStateFromWaypoint) { - test_obj_.setCurrentPose(0, 0, 0); + test_obj_.setCurrentPose(0, 0, 0); - test_obj_.createFinalWaypoints(); + test_obj_.createFinalWaypoints(); ASSERT_EQ(test_obj_.getEventStateFromWaypoint(), autoware_msgs::WaypointState::TYPE_EVENT_NULL) << "Could not get the expected state" @@ -103,10 +103,10 @@ TEST_F(TestSuite, getEventStateFromWaypoint) { } TEST_F(TestSuite, getStopSignStateFromWaypoint) { - test_obj_.setCurrentPose(0, 0, 0); - test_obj_.setCurrentVelocity(10.0); + test_obj_.setCurrentPose(0, 0, 0); + test_obj_.setCurrentVelocity(10.0); - test_obj_.createFinalWaypoints(); + test_obj_.createFinalWaypoints(); std::pair ret1 = test_obj_.getStopSignStateFromWaypoint(); ASSERT_EQ(ret1.first, autoware_msgs::WaypointState::NULLSTATE) << "Could not get the expected state" diff --git a/core_planning/lane_planner/CMakeLists.txt b/core_planning/lane_planner/CMakeLists.txt index 1f2da4f59fb..6c5cee00d2a 100644 --- a/core_planning/lane_planner/CMakeLists.txt +++ b/core_planning/lane_planner/CMakeLists.txt @@ -6,16 +6,13 @@ find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS autoware_config_msgs autoware_msgs - autoware_msgs gnss + lanelet2_extension libwaypoint_follower roscpp - rostest - rosunit std_msgs tablet_socket_msgs vector_map - lanelet2_extension ) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") @@ -23,15 +20,6 @@ set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") catkin_package( INCLUDE_DIRS include LIBRARIES lane_planner - CATKIN_DEPENDS - autoware_config_msgs - autoware_msgs - gnss - libwaypoint_follower - roscpp - std_msgs - tablet_socket_msgs - vector_map ) include_directories( @@ -148,7 +136,7 @@ install( DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) -if (CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) add_rostest_gtest(test-lane_select test/test_lane_select.test @@ -159,4 +147,4 @@ if (CATKIN_ENABLE_TESTING) add_dependencies(test-lane_select ${catkin_EXPORTED_TARGETS}) target_link_libraries(test-lane_select ${catkin_LIBRARIES}) -endif () +endif() diff --git a/core_planning/lane_planner/README.md b/core_planning/lane_planner/README.md index 251f9b1de61..01762e5f96d 100644 --- a/core_planning/lane_planner/README.md +++ b/core_planning/lane_planner/README.md @@ -12,7 +12,8 @@ This package has following nodes. ### lane_rule_lanelet2 #### Overview:
        -`lane_rule_lanelet2` detects stoplines that intersect with waypoints, and changes velocity of waypoints so that vehicle can stop before stopline when traffic_light is red. (It actually publishes both green_waypoints and red_waypoints, and `lane_stop` will choose which waypoint to use according to the recognized traffic_light color) +`lane_rule_lanelet2` detects stoplines asociated with traffic lights that intersect with waypoints, and changes velocity of waypoints so that vehicle can stop before stopline when traffic_light is red. (It actually publishes both green_waypoints and red_waypoints, and `lane_stop` will choose which waypoint to use according to the recognized traffic_light color). +Stop sign stoplines are not considered. #### Subscribed Topics |topic| type | Description| diff --git a/core_planning/lane_planner/include/lane_planner/lane_planner_vmap.hpp b/core_planning/lane_planner/include/lane_planner/lane_planner_vmap.hpp index c1a3189e111..7a2bc34ef56 100644 --- a/core_planning/lane_planner/include/lane_planner/lane_planner_vmap.hpp +++ b/core_planning/lane_planner/include/lane_planner/lane_planner_vmap.hpp @@ -44,11 +44,12 @@ constexpr int TRAFFIC_LIGHT_UNKNOWN = 2; constexpr double RADIUS_MAX = 90000000000; struct VectorMap { - std::vector points; - std::vector lanes; - std::vector nodes; - std::vector stoplines; - std::vector dtlanes; + std::vector points; + std::vector lanes; + std::vector nodes; + std::vector stoplines; + std::vector roadsigns; + std::vector dtlanes; }; void write_waypoints(const std::vector& points, double velocity, const std::string& path); @@ -70,13 +71,13 @@ VectorMap create_lane_vmap(const VectorMap& vmap, int lno); VectorMap create_coarse_vmap_from_lane(const autoware_msgs::Lane& lane); VectorMap create_coarse_vmap_from_route(const tablet_socket_msgs::route_cmd& route); VectorMap create_fine_vmap(const VectorMap& lane_vmap, int lno, const VectorMap& coarse_vmap, double search_radius, - int waypoint_max); + int waypoint_max); std::vector create_branching_points(const VectorMap& vmap); std::vector create_merging_points(const VectorMap& vmap); void publish_add_marker(const ros::Publisher& pub, const visualization_msgs::Marker& marker, - const std::vector& points); + const std::vector& points); void publish_delete_marker(const ros::Publisher& pub, const visualization_msgs::Marker& marker); } // namespace vmap diff --git a/core_planning/lane_planner/include/lane_select_core.h b/core_planning/lane_planner/include/lane_select_core.h index 05b34445bea..936b39c827e 100644 --- a/core_planning/lane_planner/include/lane_select_core.h +++ b/core_planning/lane_planner/include/lane_select_core.h @@ -23,6 +23,9 @@ #include #include #include +#include +#include +#include // C++ includes #include @@ -56,11 +59,10 @@ typename std::underlying_type::type enumToInteger(T t) class LaneSelectNode { -friend class LaneSelectTestClass; + friend class LaneSelectTestClass; public: LaneSelectNode(); - ~LaneSelectNode(); void run(); @@ -72,42 +74,61 @@ friend class LaneSelectTestClass; // publisher ros::Publisher pub1_, pub2_, pub3_, pub4_, pub5_; ros::Publisher vis_pub1_; + ros::Timer timer_; // subscriber - ros::Subscriber sub1_, sub2_, sub3_, sub4_, sub5_, sub6_; + ros::Subscriber sub1_, sub5_, sub6_; + message_filters::Subscriber sub2_; + message_filters::Subscriber sub3_; + using PoseTwistSyncPolicy = message_filters::sync_policies::ApproximateTime; + using PoseTwistSync = message_filters::Synchronizer; + std::shared_ptr pose_twist_sync_; // variables int32_t lane_array_id_; - int32_t current_lane_idx_; // the index of the lane we are driving + int32_t current_lane_idx_, prev_lane_idx_; int32_t right_lane_idx_; int32_t left_lane_idx_; - std::vector> tuple_vec_; // lane, closest_waypoint, - // change_flag - std::tuple lane_for_change_; - bool is_lane_array_subscribed_, is_current_pose_subscribed_, is_current_velocity_subscribed_, - is_current_state_subscribed_, is_config_subscribed_; + bool is_new_lane_array_; + + using LaneTuple = std::tuple; + // Hold lane array information subscribed from /traffic_waypoints_array + // order: lane, closes_waypoint on the lane to ego-vehicle, lane change flag + std::vector tuple_vec_; + + // Hold lane information used in CHANGE_LANE state. + LaneTuple lane_for_change_; + + bool is_lane_array_subscribed_; + bool is_current_pose_subscribed_; + bool is_current_velocity_subscribed_; + bool is_current_state_subscribed_; + bool is_config_subscribed_; // parameter from runtime manager - double distance_threshold_, lane_change_interval_, lane_change_target_ratio_, lane_change_target_minimum_, - vlength_hermite_curve_; + double distance_threshold_; + double lane_change_interval_; + double lane_change_target_ratio_; + double lane_change_target_minimum_; + double vlength_hermite_curve_; int search_closest_waypoint_minimum_dt_; // topics geometry_msgs::PoseStamped current_pose_; geometry_msgs::TwistStamped current_velocity_; std::string current_state_; + double update_rate_; // callbacks void callbackFromLaneArray(const autoware_msgs::LaneArrayConstPtr& msg); - void callbackFromPoseStamped(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackFromTwistStamped(const geometry_msgs::TwistStampedConstPtr& msg); void callbackFromState(const std_msgs::StringConstPtr& msg); void callbackFromDecisionMakerState(const std_msgs::StringConstPtr& msg); void callbackFromConfig(const autoware_config_msgs::ConfigLaneSelectConstPtr& msg); + void callbackFromPoseTwistStamped(const geometry_msgs::PoseStampedConstPtr& pose_msg, + const geometry_msgs::TwistStampedConstPtr& twist_msg); // initializer void initForROS(); - void initForLaneSelect(); // visualizer void publishVisualizer(); @@ -121,13 +142,12 @@ friend class LaneSelectTestClass; void resetLaneIdx(); void resetSubscriptionFlag(); bool isAllTopicsSubscribed(); - void processing(); + void processing(const ros::TimerEvent& e); void publishLane(const autoware_msgs::Lane& lane); - void publishLaneID(const autoware_msgs::Lane& lane); void publishClosestWaypoint(const int32_t clst_wp); void publishChangeFlag(const ChangeFlag flag); void publishVehicleLocation(const int32_t clst_wp, const int32_t larray_id); - bool getClosestWaypointNumberForEachLanes(); + bool updateClosestWaypointNumberForEachLane(); int32_t findMostClosestLane(const std::vector idx_vec, const geometry_msgs::Point p); void findCurrentLane(); void findNeighborLanes(); @@ -157,5 +177,5 @@ geometry_msgs::Point convertPointIntoWorldCoordinate(const geometry_msgs::Point& double getRelativeAngle(const geometry_msgs::Pose& waypoint_pose, const geometry_msgs::Pose& current_pose); bool getLinearEquation(geometry_msgs::Point start, geometry_msgs::Point end, double* a, double* b, double* c); double getDistanceBetweenLineAndPoint(geometry_msgs::Point point, double sa, double b, double c); -} +} // namespace lane_planner #endif // LANE_SELECT_CORE_H diff --git a/core_planning/lane_planner/launch/lane_navi.launch b/core_planning/lane_planner/launch/lane_navi.launch index 02d07c8b9fb..d863a8c1cb2 100644 --- a/core_planning/lane_planner/launch/lane_navi.launch +++ b/core_planning/lane_planner/launch/lane_navi.launch @@ -1,14 +1,14 @@ - - + + - - - - - - + + + + + + \ No newline at end of file diff --git a/core_planning/lane_planner/launch/lane_rule_option.launch b/core_planning/lane_planner/launch/lane_rule_option.launch index 495085b8b04..4d97643b47a 100644 --- a/core_planning/lane_planner/launch/lane_rule_option.launch +++ b/core_planning/lane_planner/launch/lane_rule_option.launch @@ -2,16 +2,6 @@ - - - - - - - - - - - - + + diff --git a/core_planning/lane_planner/launch/lane_select.launch b/core_planning/lane_planner/launch/lane_select.launch index 0447e852201..46031c7f54d 100644 --- a/core_planning/lane_planner/launch/lane_select.launch +++ b/core_planning/lane_planner/launch/lane_select.launch @@ -1,8 +1,8 @@ - + - - - + + + diff --git a/core_planning/lane_planner/lib/lane_planner/lane_planner_vmap.cpp b/core_planning/lane_planner/lib/lane_planner/lane_planner_vmap.cpp index 63117db9ecf..0fdf7e67c29 100644 --- a/core_planning/lane_planner/lib/lane_planner/lane_planner_vmap.cpp +++ b/core_planning/lane_planner/lib/lane_planner/lane_planner_vmap.cpp @@ -31,7 +31,7 @@ namespace vmap { namespace { void write_waypoint(const vector_map::Point& point, double yaw, double velocity, const std::string& path, - bool first); + bool first); double compute_direction_angle(const vector_map::Point& p1, const vector_map::Point& p2); @@ -43,734 +43,737 @@ bool is_merging_lane(const vector_map::Lane& lane); vector_map::Point find_start_point(const VectorMap& vmap, const vector_map::Lane& lane); vector_map::Point find_end_point(const VectorMap& vmap, const vector_map::Lane& lane); vector_map::Point find_departure_point(const VectorMap& lane_vmap, int lno, - const std::vector& coarse_points, - double search_radius); + const std::vector& coarse_points, + double search_radius); vector_map::Point find_arrival_point(const VectorMap& lane_vmap, int lno, - const std::vector& coarse_points, - double search_radius); + const std::vector& coarse_points, + double search_radius); vector_map::Point find_nearest_point(const VectorMap& vmap, const vector_map::Point& point); std::vector find_near_points(const VectorMap& vmap, const vector_map::Point& point, - double search_radius); + double search_radius); vector_map::Lane find_lane(const VectorMap& vmap, int lno, const vector_map::Point& point); vector_map::Lane find_prev_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane); vector_map::Lane find_next_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane); vector_map::Lane find_next_branching_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane, - double coarse_angle, double search_radius); + double coarse_angle, double search_radius); void write_waypoint(const vector_map::Point& point, double yaw, double velocity, const std::string& path, - bool first) -{ - // reverse X-Y axis - if (first) { - std::ofstream ofs(path.c_str()); - ofs << std::fixed << point.ly << "," - << std::fixed << point.bx << "," - << std::fixed << point.h << "," - << std::fixed << yaw << std::endl; - } else { - std::ofstream ofs(path.c_str(), std::ios_base::app); - ofs << std::fixed << point.ly << "," - << std::fixed << point.bx << "," - << std::fixed << point.h << "," - << std::fixed << yaw << "," - << std::fixed << velocity << std::endl; - } + bool first) +{ + // reverse X-Y axis + if (first) { + std::ofstream ofs(path.c_str()); + ofs << std::fixed << point.ly << "," + << std::fixed << point.bx << "," + << std::fixed << point.h << "," + << std::fixed << yaw << std::endl; + } else { + std::ofstream ofs(path.c_str(), std::ios_base::app); + ofs << std::fixed << point.ly << "," + << std::fixed << point.bx << "," + << std::fixed << point.h << "," + << std::fixed << yaw << "," + << std::fixed << velocity << std::endl; + } } double compute_direction_angle(const vector_map::Point& p1, const vector_map::Point& p2) { - return (atan2(p2.ly - p1.ly, p2.bx - p1.bx) * (180 / M_PI)); // -180 to 180 degrees + return (atan2(p2.ly - p1.ly, p2.bx - p1.bx) * (180 / M_PI)); // -180 to 180 degrees } bool is_branching_point(const VectorMap& vmap, const vector_map::Point& point) { - vector_map::Lane lane = find_lane(vmap, LNO_ALL, point); - if (lane.lnid < 0) - return false; + vector_map::Lane lane = find_lane(vmap, LNO_ALL, point); + if (lane.lnid < 0) + return false; - lane = find_prev_lane(vmap, LNO_ALL, lane); - if (lane.lnid < 0) - return false; + lane = find_prev_lane(vmap, LNO_ALL, lane); + if (lane.lnid < 0) + return false; - return is_branching_lane(lane); + return is_branching_lane(lane); } bool is_merging_point(const VectorMap& vmap, const vector_map::Point& point) { - vector_map::Lane lane = find_lane(vmap, LNO_ALL, point); - if (lane.lnid < 0) - return false; + vector_map::Lane lane = find_lane(vmap, LNO_ALL, point); + if (lane.lnid < 0) + return false; - return is_merging_lane(lane); + return is_merging_lane(lane); } bool is_branching_lane(const vector_map::Lane& lane) { - return (lane.jct == 1 || lane.jct == 2 || lane.jct == 5); + return (lane.jct == 1 || lane.jct == 2 || lane.jct == 5); } bool is_merging_lane(const vector_map::Lane& lane) { - return (lane.jct == 3 || lane.jct == 4 || lane.jct == 5); + return (lane.jct == 3 || lane.jct == 4 || lane.jct == 5); } vector_map::Point find_start_point(const VectorMap& vmap, const vector_map::Lane& lane) { - vector_map::Point error; - error.pid = -1; + vector_map::Point error; + error.pid = -1; - for (const vector_map::Node& n : vmap.nodes) { - if (n.nid != lane.bnid) - continue; - for (const vector_map::Point& p : vmap.points) { - if (p.pid != n.pid) - continue; - return p; - } - } + for (const vector_map::Node& n : vmap.nodes) { + if (n.nid != lane.bnid) + continue; + for (const vector_map::Point& p : vmap.points) { + if (p.pid != n.pid) + continue; + return p; + } + } - return error; + return error; } vector_map::Point find_end_point(const VectorMap& vmap, const vector_map::Lane& lane) { - vector_map::Point error; - error.pid = -1; + vector_map::Point error; + error.pid = -1; - for (const vector_map::Node& n : vmap.nodes) { - if (n.nid != lane.fnid) - continue; - for (const vector_map::Point& p : vmap.points) { - if (p.pid != n.pid) - continue; - return p; - } - } + for (const vector_map::Node& n : vmap.nodes) { + if (n.nid != lane.fnid) + continue; + for (const vector_map::Point& p : vmap.points) { + if (p.pid != n.pid) + continue; + return p; + } + } - return error; + return error; } vector_map::Point find_departure_point(const VectorMap& lane_vmap, int lno, - const std::vector& coarse_points, - double search_radius) -{ - vector_map::Point coarse_p1 = coarse_points[0]; - vector_map::Point coarse_p2 = coarse_points[1]; - - vector_map::Point nearest_point = find_nearest_point(lane_vmap, coarse_p1); - if (nearest_point.pid < 0) - return nearest_point; - - std::vector near_points = find_near_points(lane_vmap, coarse_p1, search_radius); - double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); - double score = 180 + search_radius; // XXX better way? - for (const vector_map::Point& p1 : near_points) { - vector_map::Lane l = find_lane(lane_vmap, lno, p1); - if (l.lnid < 0) - continue; - - vector_map::Point p2 = find_end_point(lane_vmap, l); - if (p2.pid < 0) - continue; - - double a = compute_direction_angle(p1, p2); - a = fabs(a - coarse_angle); - if (a > 180) - a = fabs(a - 360); - double d = hypot(p1.bx - coarse_p1.bx, p1.ly - coarse_p1.ly); - double s = a + d; - if (s <= score) { - nearest_point = p1; - score = s; - } - } - - return nearest_point; + const std::vector& coarse_points, + double search_radius) +{ + vector_map::Point coarse_p1 = coarse_points[0]; + vector_map::Point coarse_p2 = coarse_points[1]; + + vector_map::Point nearest_point = find_nearest_point(lane_vmap, coarse_p1); + if (nearest_point.pid < 0) + return nearest_point; + + std::vector near_points = find_near_points(lane_vmap, coarse_p1, search_radius); + double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); + double score = 180 + search_radius; // XXX better way? + for (const vector_map::Point& p1 : near_points) { + vector_map::Lane l = find_lane(lane_vmap, lno, p1); + if (l.lnid < 0) + continue; + + vector_map::Point p2 = find_end_point(lane_vmap, l); + if (p2.pid < 0) + continue; + + double a = compute_direction_angle(p1, p2); + a = fabs(a - coarse_angle); + if (a > 180) + a = fabs(a - 360); + double d = hypot(p1.bx - coarse_p1.bx, p1.ly - coarse_p1.ly); + double s = a + d; + if (s <= score) { + nearest_point = p1; + score = s; + } + } + + return nearest_point; } vector_map::Point find_arrival_point(const VectorMap& lane_vmap, int lno, - const std::vector& coarse_points, - double search_radius) -{ - vector_map::Point coarse_p1 = coarse_points[coarse_points.size() - 1]; - vector_map::Point coarse_p2 = coarse_points[coarse_points.size() - 2]; - - vector_map::Point nearest_point = find_nearest_point(lane_vmap, coarse_p1); - if (nearest_point.pid < 0) - return nearest_point; - - std::vector near_points = find_near_points(lane_vmap, coarse_p1, search_radius); - double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); - double score = 180 + search_radius; // XXX better way? - for (const vector_map::Point& p1 : near_points) { - vector_map::Lane l = find_lane(lane_vmap, lno, p1); - if (l.lnid < 0) - continue; - - l = find_prev_lane(lane_vmap, lno, l); - if (l.lnid < 0) - continue; - - vector_map::Point p2 = find_start_point(lane_vmap, l); - if (p2.pid < 0) - continue; - - double a = compute_direction_angle(p1, p2); - a = fabs(a - coarse_angle); - if (a > 180) - a = fabs(a - 360); - double d = hypot(p1.bx - coarse_p1.bx, p1.ly - coarse_p1.ly); - double s = a + d; - if (s <= score) { - nearest_point = p1; - score = s; - } - } - - return nearest_point; + const std::vector& coarse_points, + double search_radius) +{ + vector_map::Point coarse_p1 = coarse_points[coarse_points.size() - 1]; + vector_map::Point coarse_p2 = coarse_points[coarse_points.size() - 2]; + + vector_map::Point nearest_point = find_nearest_point(lane_vmap, coarse_p1); + if (nearest_point.pid < 0) + return nearest_point; + + std::vector near_points = find_near_points(lane_vmap, coarse_p1, search_radius); + double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); + double score = 180 + search_radius; // XXX better way? + for (const vector_map::Point& p1 : near_points) { + vector_map::Lane l = find_lane(lane_vmap, lno, p1); + if (l.lnid < 0) + continue; + + l = find_prev_lane(lane_vmap, lno, l); + if (l.lnid < 0) + continue; + + vector_map::Point p2 = find_start_point(lane_vmap, l); + if (p2.pid < 0) + continue; + + double a = compute_direction_angle(p1, p2); + a = fabs(a - coarse_angle); + if (a > 180) + a = fabs(a - 360); + double d = hypot(p1.bx - coarse_p1.bx, p1.ly - coarse_p1.ly); + double s = a + d; + if (s <= score) { + nearest_point = p1; + score = s; + } + } + + return nearest_point; } vector_map::Point find_nearest_point(const VectorMap& vmap, const vector_map::Point& point) { - vector_map::Point nearest_point; - nearest_point.pid = -1; + vector_map::Point nearest_point; + nearest_point.pid = -1; - double distance = DBL_MAX; - for (const vector_map::Point& p : vmap.points) { - double d = hypot(p.bx - point.bx, p.ly - point.ly); - if (d <= distance) { - nearest_point = p; - distance = d; - } - } + double distance = DBL_MAX; + for (const vector_map::Point& p : vmap.points) { + double d = hypot(p.bx - point.bx, p.ly - point.ly); + if (d <= distance) { + nearest_point = p; + distance = d; + } + } - return nearest_point; + return nearest_point; } std::vector find_near_points(const VectorMap& vmap, const vector_map::Point& point, - double search_radius) + double search_radius) { - std::vector near_points; - for (const vector_map::Point& p : vmap.points) { - double d = hypot(p.bx - point.bx, p.ly - point.ly); - if (d <= search_radius) - near_points.push_back(p); - } + std::vector near_points; + for (const vector_map::Point& p : vmap.points) { + double d = hypot(p.bx - point.bx, p.ly - point.ly); + if (d <= search_radius) + near_points.push_back(p); + } - return near_points; + return near_points; } vector_map::Lane find_lane(const VectorMap& vmap, int lno, const vector_map::Point& point) { - vector_map::Lane error; - error.lnid = -1; + vector_map::Lane error; + error.lnid = -1; - for (const vector_map::Node& n : vmap.nodes) { - if (n.pid != point.pid) - continue; - for (const vector_map::Lane& l : vmap.lanes) { - if (lno != LNO_ALL && l.lno != lno) - continue; - if (l.bnid != n.nid) - continue; - return l; - } - } + for (const vector_map::Node& n : vmap.nodes) { + if (n.pid != point.pid) + continue; + for (const vector_map::Lane& l : vmap.lanes) { + if (lno != LNO_ALL && l.lno != lno) + continue; + if (l.bnid != n.nid) + continue; + return l; + } + } - return error; + return error; } vector_map::Lane find_prev_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane) { - vector_map::Lane error; - error.lnid = -1; - - if (is_merging_lane(lane)) { - for (const vector_map::Lane& l : vmap.lanes) { - if (lno != LNO_ALL && l.lno != lno) - continue; - if (l.lnid != lane.blid && l.lnid != lane.blid2 && l.lnid != lane.blid3 && - l.lnid != lane.blid4) - continue; - return l; - } - } else { - for (const vector_map::Lane& l : vmap.lanes) { - if (l.lnid != lane.blid) - continue; - return l; - } - } - - return error; + vector_map::Lane error; + error.lnid = -1; + + if (is_merging_lane(lane)) { + for (const vector_map::Lane& l : vmap.lanes) { + if (lno != LNO_ALL && l.lno != lno) + continue; + if (l.lnid != lane.blid && l.lnid != lane.blid2 && l.lnid != lane.blid3 && + l.lnid != lane.blid4) + continue; + return l; + } + } else { + for (const vector_map::Lane& l : vmap.lanes) { + if (l.lnid != lane.blid) + continue; + return l; + } + } + + return error; } vector_map::Lane find_next_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane) { - vector_map::Lane error; - error.lnid = -1; - - if (is_branching_lane(lane)) { - for (const vector_map::Lane& l : vmap.lanes) { - if (lno != LNO_ALL && l.lno != lno) - continue; - if (l.lnid != lane.flid && l.lnid != lane.flid2 && l.lnid != lane.flid3 && - l.lnid != lane.flid4) - continue; - return l; - } - } else { - for (const vector_map::Lane& l : vmap.lanes) { - if (l.lnid != lane.flid) - continue; - return l; - } - } - - return error; + vector_map::Lane error; + error.lnid = -1; + + if (is_branching_lane(lane)) { + for (const vector_map::Lane& l : vmap.lanes) { + if (lno != LNO_ALL && l.lno != lno) + continue; + if (l.lnid != lane.flid && l.lnid != lane.flid2 && l.lnid != lane.flid3 && + l.lnid != lane.flid4) + continue; + return l; + } + } else { + for (const vector_map::Lane& l : vmap.lanes) { + if (l.lnid != lane.flid) + continue; + return l; + } + } + + return error; } vector_map::Lane find_next_branching_lane(const VectorMap& vmap, int lno, const vector_map::Lane& lane, - double coarse_angle, double search_radius) -{ - vector_map::Lane error; - error.lnid = -1; - - vector_map::Point p1 = find_end_point(vmap, lane); - if (p1.pid < 0) - return error; - - std::vector> candidates; - for (const vector_map::Lane& l1 : vmap.lanes) { - if (lno != LNO_ALL && l1.lno != lno) - continue; - if (l1.lnid == lane.flid || l1.lnid == lane.flid2 || l1.lnid == lane.flid3 || l1.lnid == lane.flid4) { - vector_map::Lane l2 = l1; - vector_map::Point p = find_end_point(vmap, l2); - if (p.pid < 0) - continue; - vector_map::Point p2 = p; - double d = hypot(p2.bx - p1.bx, p2.ly - p1.ly); - while (d <= search_radius && l2.flid != 0 && !is_branching_lane(l2)) { - l2 = find_next_lane(vmap, LNO_ALL, l2); - if (l2.lnid < 0) - break; - p = find_end_point(vmap, l2); - if (p.pid < 0) - break; - p2 = p; - d = hypot(p2.bx - p1.bx, p2.ly - p1.ly); - } - candidates.push_back(std::make_tuple(p2, l1)); - } - } - - if (candidates.empty()) - return error; - - vector_map::Lane branching_lane; - double angle = 180; - for (const std::tuple& c : candidates) { - vector_map::Point p2 = std::get<0>(c); - double a = compute_direction_angle(p1, p2); - a = fabs(a - coarse_angle); - if (a > 180) - a = fabs(a - 360); - if (a <= angle) { - branching_lane = std::get<1>(c); - angle = a; - } - } - - return branching_lane; + double coarse_angle, double search_radius) +{ + vector_map::Lane error; + error.lnid = -1; + + vector_map::Point p1 = find_end_point(vmap, lane); + if (p1.pid < 0) + return error; + + std::vector> candidates; + for (const vector_map::Lane& l1 : vmap.lanes) { + if (lno != LNO_ALL && l1.lno != lno) + continue; + if (l1.lnid == lane.flid || l1.lnid == lane.flid2 || l1.lnid == lane.flid3 || l1.lnid == lane.flid4) { + vector_map::Lane l2 = l1; + vector_map::Point p = find_end_point(vmap, l2); + if (p.pid < 0) + continue; + vector_map::Point p2 = p; + double d = hypot(p2.bx - p1.bx, p2.ly - p1.ly); + while (d <= search_radius && l2.flid != 0 && !is_branching_lane(l2)) { + l2 = find_next_lane(vmap, LNO_ALL, l2); + if (l2.lnid < 0) + break; + p = find_end_point(vmap, l2); + if (p.pid < 0) + break; + p2 = p; + d = hypot(p2.bx - p1.bx, p2.ly - p1.ly); + } + candidates.push_back(std::make_tuple(p2, l1)); + } + } + + if (candidates.empty()) + return error; + + vector_map::Lane branching_lane; + double angle = 180; + for (const std::tuple& c : candidates) { + vector_map::Point p2 = std::get<0>(c); + double a = compute_direction_angle(p1, p2); + a = fabs(a - coarse_angle); + if (a > 180) + a = fabs(a - 360); + if (a <= angle) { + branching_lane = std::get<1>(c); + angle = a; + } + } + + return branching_lane; } } // namespace void write_waypoints(const std::vector& points, double velocity, const std::string& path) { - if (points.size() < 2) - return; + if (points.size() < 2) + return; - size_t last_index = points.size() - 1; - for (size_t i = 0; i < points.size(); ++i) { - double yaw; - if (i == last_index) { - geometry_msgs::Point p1 = create_geometry_msgs_point(points[i]); - geometry_msgs::Point p2 = create_geometry_msgs_point(points[i - 1]); - yaw = atan2(p2.y - p1.y, p2.x - p1.x); - yaw -= M_PI; - } else { - geometry_msgs::Point p1 = create_geometry_msgs_point(points[i]); - geometry_msgs::Point p2 = create_geometry_msgs_point(points[i + 1]); - yaw = atan2(p2.y - p1.y, p2.x - p1.x); - } + size_t last_index = points.size() - 1; + for (size_t i = 0; i < points.size(); ++i) { + double yaw; + if (i == last_index) { + geometry_msgs::Point p1 = create_geometry_msgs_point(points[i]); + geometry_msgs::Point p2 = create_geometry_msgs_point(points[i - 1]); + yaw = atan2(p2.y - p1.y, p2.x - p1.x); + yaw -= M_PI; + } else { + geometry_msgs::Point p1 = create_geometry_msgs_point(points[i]); + geometry_msgs::Point p2 = create_geometry_msgs_point(points[i + 1]); + yaw = atan2(p2.y - p1.y, p2.x - p1.x); + } - write_waypoint(points[i], yaw, velocity, path, (i == 0)); - } + write_waypoint(points[i], yaw, velocity, path, (i == 0)); + } } double compute_reduction(const vector_map::DTLane& d, double w) { - return (1 - fabs(1 / d.r) * w); // 0 to 1 rates + return (1 - fabs(1 / d.r) * w); // 0 to 1 rates } bool is_straight_dtlane(const vector_map::DTLane& dtlane) { - return (dtlane.apara == 0 && dtlane.r == RADIUS_MAX); + return (dtlane.apara == 0 && dtlane.r == RADIUS_MAX); } bool is_curve_dtlane(const vector_map::DTLane& dtlane) { - return (dtlane.apara == 0 && dtlane.r != RADIUS_MAX); + return (dtlane.apara == 0 && dtlane.r != RADIUS_MAX); } // XXX better way? bool is_crossroad_dtlane(const vector_map::DTLane& dtlane) { - // take crossroad for 10 radius or less - return (fabs(dtlane.r) <= 10); + // take crossroad for 10 radius or less + return (fabs(dtlane.r) <= 10); } bool is_clothoid_dtlane(const vector_map::DTLane& dtlane) { - return (dtlane.apara != 0); + return (dtlane.apara != 0); } // XXX better way? bool is_connection_dtlane(const VectorMap& fine_vmap, int index) { - const vector_map::DTLane& dtlane = fine_vmap.dtlanes[index]; - int size = fine_vmap.dtlanes.size(); - - int change = 0; - int straight = 0; - for (int i = index - 1; i >= 0; --i) { - if (dtlane.r != fine_vmap.dtlanes[i].r) { - ++change; - if (is_straight_dtlane(fine_vmap.dtlanes[i])) - ++straight; - break; - } - } - for (int i = index + 1; i < size; ++i) { - if (dtlane.r != fine_vmap.dtlanes[i].r) { - ++change; - if (is_straight_dtlane(fine_vmap.dtlanes[i])) - ++straight; - break; - } - } - if (change == 1 && straight == 1) - return true; - if (straight == 2) - return true; - - return false; + const vector_map::DTLane& dtlane = fine_vmap.dtlanes[index]; + int size = fine_vmap.dtlanes.size(); + + int change = 0; + int straight = 0; + for (int i = index - 1; i >= 0; --i) { + if (dtlane.r != fine_vmap.dtlanes[i].r) { + ++change; + if (is_straight_dtlane(fine_vmap.dtlanes[i])) + ++straight; + break; + } + } + for (int i = index + 1; i < size; ++i) { + if (dtlane.r != fine_vmap.dtlanes[i].r) { + ++change; + if (is_straight_dtlane(fine_vmap.dtlanes[i])) + ++straight; + break; + } + } + if (change == 1 && straight == 1) + return true; + if (straight == 2) + return true; + + return false; } geometry_msgs::Point create_geometry_msgs_point(const vector_map::Point& vp) { - // reverse X-Y axis - geometry_msgs::Point gp; - gp.x = vp.ly; - gp.y = vp.bx; - gp.z = vp.h; + // reverse X-Y axis + geometry_msgs::Point gp; + gp.x = vp.ly; + gp.y = vp.bx; + gp.z = vp.h; - return gp; + return gp; } vector_map::Point create_vector_map_point(const geometry_msgs::Point& gp) { - // reverse X-Y axis - vector_map::Point vp; - vp.bx = gp.y; - vp.ly = gp.x; - vp.h = gp.z; + // reverse X-Y axis + vector_map::Point vp; + vp.bx = gp.y; + vp.ly = gp.x; + vp.h = gp.z; - return vp; + return vp; } autoware_msgs::DTLane create_waypoint_follower_dtlane(const vector_map::DTLane& vd) { - autoware_msgs::DTLane wd; - wd.dist = vd.dist; - wd.dir = vd.dir; - wd.apara = vd.apara; - wd.r = vd.r; - wd.slope = vd.slope; - wd.cant = vd.cant; - wd.lw = vd.lw; - wd.rw = vd.rw; + autoware_msgs::DTLane wd; + wd.dist = vd.dist; + wd.dir = vd.dir; + wd.apara = vd.apara; + wd.r = vd.r; + wd.slope = vd.slope; + wd.cant = vd.cant; + wd.lw = vd.lw; + wd.rw = vd.rw; - return wd; + return wd; } vector_map::DTLane create_vector_map_dtlane(const autoware_msgs::DTLane& wd) { - vector_map::DTLane vd; - vd.dist = wd.dist; - vd.dir = wd.dir; - vd.apara = wd.apara; - vd.r = wd.r; - vd.slope = wd.slope; - vd.cant = wd.cant; - vd.lw = wd.lw; - vd.rw = wd.rw; + vector_map::DTLane vd; + vd.dist = wd.dist; + vd.dir = wd.dir; + vd.apara = wd.apara; + vd.r = wd.r; + vd.slope = wd.slope; + vd.cant = wd.cant; + vd.lw = wd.lw; + vd.rw = wd.rw; - return vd; + return vd; } VectorMap create_lane_vmap(const VectorMap& vmap, int lno) { - VectorMap lane_vmap; - for (const vector_map::Lane& l : vmap.lanes) { - if (lno != LNO_ALL && l.lno != lno) - continue; - lane_vmap.lanes.push_back(l); - - for (const vector_map::Node& n : vmap.nodes) { - if (n.nid != l.bnid && n.nid != l.fnid) - continue; - lane_vmap.nodes.push_back(n); - - for (const vector_map::Point& p : vmap.points) { - if (p.pid != n.pid) - continue; - lane_vmap.points.push_back(p); - } - } - - for (const vector_map::StopLine& s : vmap.stoplines) { - if (s.linkid != l.lnid) - continue; - lane_vmap.stoplines.push_back(s); - } - - for (const vector_map::DTLane& d : vmap.dtlanes) { - if (d.did != l.did) - continue; - lane_vmap.dtlanes.push_back(d); - } - } - - return lane_vmap; + VectorMap lane_vmap; + for (const vector_map::Lane& l : vmap.lanes) { + if (lno != LNO_ALL && l.lno != lno) + continue; + lane_vmap.lanes.push_back(l); + + for (const vector_map::Node& n : vmap.nodes) { + if (n.nid != l.bnid && n.nid != l.fnid) + continue; + lane_vmap.nodes.push_back(n); + + for (const vector_map::Point& p : vmap.points) { + if (p.pid != n.pid) + continue; + lane_vmap.points.push_back(p); + } + } + + for (const vector_map::StopLine& s : vmap.stoplines) { + if (s.linkid != l.lnid) + continue; + lane_vmap.stoplines.push_back(s); + } + + for (const vector_map::DTLane& d : vmap.dtlanes) { + if (d.did != l.did) + continue; + lane_vmap.dtlanes.push_back(d); + } + } + for (const vector_map::RoadSign& r : vmap.roadsigns) { + lane_vmap.roadsigns.push_back(r); + } + + return lane_vmap; } VectorMap create_coarse_vmap_from_lane(const autoware_msgs::Lane& lane) { - VectorMap coarse_vmap; - for (const autoware_msgs::Waypoint& w : lane.waypoints) - coarse_vmap.points.push_back(create_vector_map_point(w.pose.pose.position)); + VectorMap coarse_vmap; + for (const autoware_msgs::Waypoint& w : lane.waypoints) + coarse_vmap.points.push_back(create_vector_map_point(w.pose.pose.position)); - return coarse_vmap; + return coarse_vmap; } VectorMap create_coarse_vmap_from_route(const tablet_socket_msgs::route_cmd& route) { - geo_pos_conv geo; - geo.set_plane(7); + geo_pos_conv geo; + geo.set_plane(7); - VectorMap coarse_vmap; - for (const tablet_socket_msgs::Waypoint& w : route.point) { - geo.llh_to_xyz(w.lat, w.lon, 0); + VectorMap coarse_vmap; + for (const tablet_socket_msgs::Waypoint& w : route.point) { + geo.llh_to_xyz(w.lat, w.lon, 0); - vector_map::Point p; - p.bx = geo.x(); - p.ly = geo.y(); - coarse_vmap.points.push_back(p); - } + vector_map::Point p; + p.bx = geo.x(); + p.ly = geo.y(); + coarse_vmap.points.push_back(p); + } - return coarse_vmap; + return coarse_vmap; } VectorMap create_fine_vmap(const VectorMap& lane_vmap, int lno, const VectorMap& coarse_vmap, double search_radius, - int waypoint_max) -{ - VectorMap fine_vmap; - VectorMap null_vmap; - - vector_map::Point departure_point; - departure_point.pid = -1; - if (lno == LNO_ALL) - departure_point = find_nearest_point(lane_vmap, coarse_vmap.points.front()); - else { - for (int i = lno; i >= LNO_CROSSING; --i) { - departure_point = find_departure_point(lane_vmap, i, coarse_vmap.points, search_radius); - if (departure_point.pid >= 0) - break; - } - } - if (departure_point.pid < 0) - return null_vmap; - - vector_map::Point arrival_point; - arrival_point.pid = -1; - if (lno == LNO_ALL) - arrival_point = find_nearest_point(lane_vmap, coarse_vmap.points.back()); - else { - for (int i = lno; i >= LNO_CROSSING; --i) { - arrival_point = find_arrival_point(lane_vmap, i, coarse_vmap.points, search_radius); - if (arrival_point.pid >= 0) - break; - } - } - if (arrival_point.pid < 0) - return null_vmap; - - vector_map::Point point = departure_point; - vector_map::Lane lane = find_lane(lane_vmap, LNO_ALL, point); - if (lane.lnid < 0) - return null_vmap; - - bool finish = false; - for (int i = 0; i < waypoint_max; ++i) { - fine_vmap.points.push_back(point); - - // last is equal to previous dtlane - vector_map::DTLane dtlane; - dtlane.did = -1; - for (const vector_map::DTLane& d : lane_vmap.dtlanes) { - if (d.did == lane.did) { - dtlane = d; - break; - } - } - fine_vmap.dtlanes.push_back(dtlane); - - // last is equal to previous stopline - vector_map::StopLine stopline; - stopline.id = -1; - for (const vector_map::StopLine& s : lane_vmap.stoplines) { - if (s.linkid == lane.lnid) { - stopline = s; - break; - } - } - fine_vmap.stoplines.push_back(stopline); - - if (finish) - break; - - fine_vmap.lanes.push_back(lane); - - point = find_end_point(lane_vmap, lane); - if (point.pid < 0) - return null_vmap; - if (point.bx == arrival_point.bx && point.ly == arrival_point.ly) { - finish = true; - continue; - } - - if (is_branching_lane(lane)) { - vector_map::Point coarse_p1 = find_end_point(lane_vmap, lane); - if (coarse_p1.pid < 0) - return null_vmap; - - coarse_p1 = find_nearest_point(coarse_vmap, coarse_p1); - if (coarse_p1.pid < 0) - return null_vmap; - - vector_map::Point coarse_p2; - double distance = -1; - for (const vector_map::Point& p : coarse_vmap.points) { - if (distance == -1) { - if (p.bx == coarse_p1.bx && p.ly == coarse_p1.ly) - distance = 0; - continue; - } - coarse_p2 = p; - distance = hypot(coarse_p2.bx - coarse_p1.bx, coarse_p2.ly - coarse_p1.ly); - if (distance > search_radius) - break; - } - if (distance <= 0) - return null_vmap; - - double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); - if (lno == LNO_ALL) { - lane = find_next_branching_lane(lane_vmap, LNO_ALL, lane, coarse_angle, search_radius); - } else { - vector_map::Lane l; - l.lnid = -1; - for (int j = lno; j >= LNO_CROSSING; --j) { - l = find_next_branching_lane(lane_vmap, j, lane, coarse_angle, search_radius); - if (l.lnid >= 0) - break; - } - lane = l; - } - } else { - lane = find_next_lane(lane_vmap, LNO_ALL, lane); - } - if (lane.lnid < 0) - return null_vmap; - } - - if (!finish) { - ROS_ERROR_STREAM("lane is too long"); - return null_vmap; - } - - return fine_vmap; + int waypoint_max) +{ + VectorMap fine_vmap; + VectorMap null_vmap; + + vector_map::Point departure_point; + departure_point.pid = -1; + if (lno == LNO_ALL) + departure_point = find_nearest_point(lane_vmap, coarse_vmap.points.front()); + else { + for (int i = lno; i >= LNO_CROSSING; --i) { + departure_point = find_departure_point(lane_vmap, i, coarse_vmap.points, search_radius); + if (departure_point.pid >= 0) + break; + } + } + if (departure_point.pid < 0) + return null_vmap; + + vector_map::Point arrival_point; + arrival_point.pid = -1; + if (lno == LNO_ALL) + arrival_point = find_nearest_point(lane_vmap, coarse_vmap.points.back()); + else { + for (int i = lno; i >= LNO_CROSSING; --i) { + arrival_point = find_arrival_point(lane_vmap, i, coarse_vmap.points, search_radius); + if (arrival_point.pid >= 0) + break; + } + } + if (arrival_point.pid < 0) + return null_vmap; + + vector_map::Point point = departure_point; + vector_map::Lane lane = find_lane(lane_vmap, LNO_ALL, point); + if (lane.lnid < 0) + return null_vmap; + + bool finish = false; + for (int i = 0; i < waypoint_max; ++i) { + fine_vmap.points.push_back(point); + + // last is equal to previous dtlane + vector_map::DTLane dtlane; + dtlane.did = -1; + for (const vector_map::DTLane& d : lane_vmap.dtlanes) { + if (d.did == lane.did) { + dtlane = d; + break; + } + } + fine_vmap.dtlanes.push_back(dtlane); + + // last is equal to previous stopline + vector_map::StopLine stopline; + stopline.id = -1; + for (const vector_map::StopLine& s : lane_vmap.stoplines) { + if (s.linkid == lane.lnid) { + stopline = s; + break; + } + } + fine_vmap.stoplines.push_back(stopline); + + if (finish) + break; + + fine_vmap.lanes.push_back(lane); + + point = find_end_point(lane_vmap, lane); + if (point.pid < 0) + return null_vmap; + if (point.bx == arrival_point.bx && point.ly == arrival_point.ly) { + finish = true; + continue; + } + + if (is_branching_lane(lane)) { + vector_map::Point coarse_p1 = find_end_point(lane_vmap, lane); + if (coarse_p1.pid < 0) + return null_vmap; + + coarse_p1 = find_nearest_point(coarse_vmap, coarse_p1); + if (coarse_p1.pid < 0) + return null_vmap; + + vector_map::Point coarse_p2; + double distance = -1; + for (const vector_map::Point& p : coarse_vmap.points) { + if (distance == -1) { + if (p.bx == coarse_p1.bx && p.ly == coarse_p1.ly) + distance = 0; + continue; + } + coarse_p2 = p; + distance = hypot(coarse_p2.bx - coarse_p1.bx, coarse_p2.ly - coarse_p1.ly); + if (distance > search_radius) + break; + } + if (distance <= 0) + return null_vmap; + + double coarse_angle = compute_direction_angle(coarse_p1, coarse_p2); + if (lno == LNO_ALL) { + lane = find_next_branching_lane(lane_vmap, LNO_ALL, lane, coarse_angle, search_radius); + } else { + vector_map::Lane l; + l.lnid = -1; + for (int j = lno; j >= LNO_CROSSING; --j) { + l = find_next_branching_lane(lane_vmap, j, lane, coarse_angle, search_radius); + if (l.lnid >= 0) + break; + } + lane = l; + } + } else { + lane = find_next_lane(lane_vmap, LNO_ALL, lane); + } + if (lane.lnid < 0) + return null_vmap; + } + + if (!finish) { + ROS_ERROR_STREAM("lane is too long"); + return null_vmap; + } + + return fine_vmap; } std::vector create_branching_points(const VectorMap& vmap) { - std::vector branching_points; - for (const vector_map::Point& p : vmap.points) { - if (!is_branching_point(vmap, p)) - continue; - branching_points.push_back(p); - } + std::vector branching_points; + for (const vector_map::Point& p : vmap.points) { + if (!is_branching_point(vmap, p)) + continue; + branching_points.push_back(p); + } - return branching_points; + return branching_points; } std::vector create_merging_points(const VectorMap& vmap) { - std::vector merging_points; - for (const vector_map::Point& p : vmap.points) { - if (!is_merging_point(vmap, p)) - continue; - merging_points.push_back(p); - } + std::vector merging_points; + for (const vector_map::Point& p : vmap.points) { + if (!is_merging_point(vmap, p)) + continue; + merging_points.push_back(p); + } - return merging_points; + return merging_points; } void publish_add_marker(const ros::Publisher& pub, const visualization_msgs::Marker& marker, - const std::vector& points) + const std::vector& points) { - visualization_msgs::Marker m; - m.header.frame_id = marker.header.frame_id; - m.ns = marker.ns; - m.id = marker.id; - m.type = marker.type; - m.scale = marker.scale; - m.color = marker.color; - m.frame_locked = marker.frame_locked; - for (const vector_map::Point& p : points) - m.points.push_back(create_geometry_msgs_point(p)); + visualization_msgs::Marker m; + m.header.frame_id = marker.header.frame_id; + m.ns = marker.ns; + m.id = marker.id; + m.type = marker.type; + m.scale = marker.scale; + m.color = marker.color; + m.frame_locked = marker.frame_locked; + for (const vector_map::Point& p : points) + m.points.push_back(create_geometry_msgs_point(p)); - m.header.stamp = ros::Time::now(); - m.action = visualization_msgs::Marker::ADD; + m.header.stamp = ros::Time::now(); + m.action = visualization_msgs::Marker::ADD; - pub.publish(m); + pub.publish(m); } void publish_delete_marker(const ros::Publisher& pub, const visualization_msgs::Marker& marker) { - visualization_msgs::Marker m; - m.header.frame_id = marker.header.frame_id; - m.ns = marker.ns; - m.id = marker.id; + visualization_msgs::Marker m; + m.header.frame_id = marker.header.frame_id; + m.ns = marker.ns; + m.id = marker.id; - m.header.stamp = ros::Time::now(); - m.action = visualization_msgs::Marker::DELETE; + m.header.stamp = ros::Time::now(); + m.action = visualization_msgs::Marker::DELETE; - pub.publish(m); + pub.publish(m); } } // namespace vmap diff --git a/core_planning/lane_planner/nodes/lane_navi/lane_navi.cpp b/core_planning/lane_planner/nodes/lane_navi/lane_navi.cpp index 32c50a36be4..025404048af 100644 --- a/core_planning/lane_planner/nodes/lane_navi/lane_navi.cpp +++ b/core_planning/lane_planner/nodes/lane_navi/lane_navi.cpp @@ -40,198 +40,198 @@ tablet_socket_msgs::route_cmd cached_route; std::vector split(const std::string& str, char delim) { - std::stringstream ss(str); - std::string s; - std::vector vec; - while (std::getline(ss, s, delim)) - vec.push_back(s); + std::stringstream ss(str); + std::string s; + std::vector vec; + while (std::getline(ss, s, delim)) + vec.push_back(s); - if (!str.empty() && str.back() == delim) - vec.push_back(std::string()); + if (!str.empty() && str.back() == delim) + vec.push_back(std::string()); - return vec; + return vec; } std::string join(const std::vector& vec, char delim) { - std::string str; - for (size_t i = 0; i < vec.size(); ++i) { - str += vec[i]; - if (i != (vec.size() - 1)) - str += delim; - } - - return str; + std::string str; + for (size_t i = 0; i < vec.size(); ++i) { + str += vec[i]; + if (i != (vec.size() - 1)) + str += delim; + } + + return str; } int count_lane(const lane_planner::vmap::VectorMap& vmap) { - int lcnt = -1; + int lcnt = -1; - for (const vector_map::Lane& l : vmap.lanes) { - if (l.lcnt > lcnt) - lcnt = l.lcnt; - } + for (const vector_map::Lane& l : vmap.lanes) { + if (l.lcnt > lcnt) + lcnt = l.lcnt; + } - return lcnt; + return lcnt; } void create_waypoint(const tablet_socket_msgs::route_cmd& msg) { - std_msgs::Header header; - header.stamp = ros::Time::now(); - header.frame_id = frame_id; - - if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) { - cached_route.header = header; - cached_route.point = msg.point; - return; - } - - lane_planner::vmap::VectorMap coarse_vmap = lane_planner::vmap::create_coarse_vmap_from_route(msg); - if (coarse_vmap.points.size() < 2) - return; - - std::vector fine_vmaps; - lane_planner::vmap::VectorMap fine_mostleft_vmap = - lane_planner::vmap::create_fine_vmap(lane_vmap, lane_planner::vmap::LNO_MOSTLEFT, coarse_vmap, - search_radius, waypoint_max); - if (fine_mostleft_vmap.points.size() < 2) - return; - fine_vmaps.push_back(fine_mostleft_vmap); - - int lcnt = count_lane(fine_mostleft_vmap); - for (int i = lane_planner::vmap::LNO_MOSTLEFT + 1; i <= lcnt; ++i) { - lane_planner::vmap::VectorMap v = - lane_planner::vmap::create_fine_vmap(lane_vmap, i, coarse_vmap, search_radius, waypoint_max); - if (v.points.size() < 2) - continue; - fine_vmaps.push_back(v); - } - - autoware_msgs::LaneArray lane_waypoint; - for (const lane_planner::vmap::VectorMap& v : fine_vmaps) { - autoware_msgs::Lane l; - l.header = header; - l.increment = 1; - - size_t last_index = v.points.size() - 1; - for (size_t i = 0; i < v.points.size(); ++i) { - double yaw; - if (i == last_index) { - geometry_msgs::Point p1 = - lane_planner::vmap::create_geometry_msgs_point(v.points[i]); - geometry_msgs::Point p2 = - lane_planner::vmap::create_geometry_msgs_point(v.points[i - 1]); - yaw = atan2(p2.y - p1.y, p2.x - p1.x); - yaw -= M_PI; - } else { - geometry_msgs::Point p1 = - lane_planner::vmap::create_geometry_msgs_point(v.points[i]); - geometry_msgs::Point p2 = - lane_planner::vmap::create_geometry_msgs_point(v.points[i + 1]); - yaw = atan2(p2.y - p1.y, p2.x - p1.x); - } - - autoware_msgs::Waypoint w; - w.pose.header = header; - w.pose.pose.position = lane_planner::vmap::create_geometry_msgs_point(v.points[i]); - w.pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw); - w.twist.header = header; - w.twist.twist.linear.x = velocity / 3.6; // to m/s - l.waypoints.push_back(w); - } - lane_waypoint.lanes.push_back(l); - } - waypoint_pub.publish(lane_waypoint); - - for (size_t i = 0; i < fine_vmaps.size(); ++i) { - std::stringstream ss; - ss << "_" << i; - - std::vector v1 = split(output_file, '/'); - std::vector v2 = split(v1.back(), '.'); - v2[0] = v2.front() + ss.str(); - v1[v1.size() - 1] = join(v2, '.'); - std::string path = join(v1, '/'); - - lane_planner::vmap::write_waypoints(fine_vmaps[i].points, velocity, path); - } + std_msgs::Header header; + header.stamp = ros::Time::now(); + header.frame_id = frame_id; + + if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) { + cached_route.header = header; + cached_route.point = msg.point; + return; + } + + lane_planner::vmap::VectorMap coarse_vmap = lane_planner::vmap::create_coarse_vmap_from_route(msg); + if (coarse_vmap.points.size() < 2) + return; + + std::vector fine_vmaps; + lane_planner::vmap::VectorMap fine_mostleft_vmap = + lane_planner::vmap::create_fine_vmap(lane_vmap, lane_planner::vmap::LNO_MOSTLEFT, coarse_vmap, + search_radius, waypoint_max); + if (fine_mostleft_vmap.points.size() < 2) + return; + fine_vmaps.push_back(fine_mostleft_vmap); + + int lcnt = count_lane(fine_mostleft_vmap); + for (int i = lane_planner::vmap::LNO_MOSTLEFT + 1; i <= lcnt; ++i) { + lane_planner::vmap::VectorMap v = + lane_planner::vmap::create_fine_vmap(lane_vmap, i, coarse_vmap, search_radius, waypoint_max); + if (v.points.size() < 2) + continue; + fine_vmaps.push_back(v); + } + + autoware_msgs::LaneArray lane_waypoint; + for (const lane_planner::vmap::VectorMap& v : fine_vmaps) { + autoware_msgs::Lane l; + l.header = header; + l.increment = 1; + + size_t last_index = v.points.size() - 1; + for (size_t i = 0; i < v.points.size(); ++i) { + double yaw; + if (i == last_index) { + geometry_msgs::Point p1 = + lane_planner::vmap::create_geometry_msgs_point(v.points[i]); + geometry_msgs::Point p2 = + lane_planner::vmap::create_geometry_msgs_point(v.points[i - 1]); + yaw = atan2(p2.y - p1.y, p2.x - p1.x); + yaw -= M_PI; + } else { + geometry_msgs::Point p1 = + lane_planner::vmap::create_geometry_msgs_point(v.points[i]); + geometry_msgs::Point p2 = + lane_planner::vmap::create_geometry_msgs_point(v.points[i + 1]); + yaw = atan2(p2.y - p1.y, p2.x - p1.x); + } + + autoware_msgs::Waypoint w; + w.pose.header = header; + w.pose.pose.position = lane_planner::vmap::create_geometry_msgs_point(v.points[i]); + w.pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw); + w.twist.header = header; + w.twist.twist.linear.x = velocity / 3.6; // to m/s + l.waypoints.push_back(w); + } + lane_waypoint.lanes.push_back(l); + } + waypoint_pub.publish(lane_waypoint); + + for (size_t i = 0; i < fine_vmaps.size(); ++i) { + std::stringstream ss; + ss << "_" << i; + + std::vector v1 = split(output_file, '/'); + std::vector v2 = split(v1.back(), '.'); + v2[0] = v2.front() + ss.str(); + v1[v1.size() - 1] = join(v2, '.'); + std::string path = join(v1, '/'); + + lane_planner::vmap::write_waypoints(fine_vmaps[i].points, velocity, path); + } } void update_values() { - if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) - return; + if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty()) + return; - lane_vmap = lane_planner::vmap::create_lane_vmap(all_vmap, lane_planner::vmap::LNO_ALL); + lane_vmap = lane_planner::vmap::create_lane_vmap(all_vmap, lane_planner::vmap::LNO_ALL); - if (!cached_route.point.empty()) { - create_waypoint(cached_route); - cached_route.point.clear(); - cached_route.point.shrink_to_fit(); - } + if (!cached_route.point.empty()) { + create_waypoint(cached_route); + cached_route.point.clear(); + cached_route.point.shrink_to_fit(); + } } void cache_point(const vector_map::PointArray& msg) { - all_vmap.points = msg.data; - update_values(); + all_vmap.points = msg.data; + update_values(); } void cache_lane(const vector_map::LaneArray& msg) { - all_vmap.lanes = msg.data; - update_values(); + all_vmap.lanes = msg.data; + update_values(); } void cache_node(const vector_map::NodeArray& msg) { - all_vmap.nodes = msg.data; - update_values(); + all_vmap.nodes = msg.data; + update_values(); } } // namespace int main(int argc, char **argv) { - ros::init(argc, argv, "lane_navi"); - - ros::NodeHandle n; - - int sub_vmap_queue_size; - n.param("/lane_navi/sub_vmap_queue_size", sub_vmap_queue_size, 1); - int sub_route_queue_size; - n.param("/lane_navi/sub_route_queue_size", sub_route_queue_size, 1); - int pub_waypoint_queue_size; - n.param("/lane_navi/pub_waypoint_queue_size", pub_waypoint_queue_size, 1); - bool pub_waypoint_latch; - n.param("/lane_navi/pub_waypoint_latch", pub_waypoint_latch, true); - - n.param("/lane_navi/waypoint_max", waypoint_max, 10000); - n.param("/lane_navi/search_radius", search_radius, 10); - n.param("/lane_navi/velocity", velocity, 40); - n.param("/lane_navi/frame_id", frame_id, "map"); - n.param("/lane_navi/output_file", output_file, "/tmp/lane_waypoint.csv"); - - if (output_file.empty()) { - ROS_ERROR_STREAM("output filename is empty"); - return EXIT_FAILURE; - } - if (output_file.back() == '/') { - ROS_ERROR_STREAM(output_file << " is directory"); - return EXIT_FAILURE; - } - - waypoint_pub = n.advertise("/lane_waypoints_array", pub_waypoint_queue_size, - pub_waypoint_latch); - - ros::Subscriber route_sub = n.subscribe("/route_cmd", sub_route_queue_size, create_waypoint); - ros::Subscriber point_sub = n.subscribe("/vector_map_info/point", sub_vmap_queue_size, cache_point); - ros::Subscriber lane_sub = n.subscribe("/vector_map_info/lane", sub_vmap_queue_size, cache_lane); - ros::Subscriber node_sub = n.subscribe("/vector_map_info/node", sub_vmap_queue_size, cache_node); - - ros::spin(); - - return EXIT_SUCCESS; + ros::init(argc, argv, "lane_navi"); + + ros::NodeHandle n; + + int sub_vmap_queue_size; + n.param("/lane_navi/sub_vmap_queue_size", sub_vmap_queue_size, 1); + int sub_route_queue_size; + n.param("/lane_navi/sub_route_queue_size", sub_route_queue_size, 1); + int pub_waypoint_queue_size; + n.param("/lane_navi/pub_waypoint_queue_size", pub_waypoint_queue_size, 1); + bool pub_waypoint_latch; + n.param("/lane_navi/pub_waypoint_latch", pub_waypoint_latch, true); + + n.param("/lane_navi/waypoint_max", waypoint_max, 10000); + n.param("/lane_navi/search_radius", search_radius, 10); + n.param("/lane_navi/velocity", velocity, 40); + n.param("/lane_navi/frame_id", frame_id, "map"); + n.param("/lane_navi/output_file", output_file, "/tmp/lane_waypoint.csv"); + + if (output_file.empty()) { + ROS_ERROR_STREAM("output filename is empty"); + return EXIT_FAILURE; + } + if (output_file.back() == '/') { + ROS_ERROR_STREAM(output_file << " is directory"); + return EXIT_FAILURE; + } + + waypoint_pub = n.advertise("/lane_waypoints_array", pub_waypoint_queue_size, + pub_waypoint_latch); + + ros::Subscriber route_sub = n.subscribe("/route_cmd", sub_route_queue_size, create_waypoint); + ros::Subscriber point_sub = n.subscribe("/vector_map_info/point", sub_vmap_queue_size, cache_point); + ros::Subscriber lane_sub = n.subscribe("/vector_map_info/lane", sub_vmap_queue_size, cache_lane); + ros::Subscriber node_sub = n.subscribe("/vector_map_info/node", sub_vmap_queue_size, cache_node); + + ros::spin(); + + return EXIT_SUCCESS; } diff --git a/core_planning/lane_planner/nodes/lane_rule/lane_rule.cpp b/core_planning/lane_planner/nodes/lane_rule/lane_rule.cpp index 63445d9efe6..8f6d7142b35 100644 --- a/core_planning/lane_planner/nodes/lane_rule/lane_rule.cpp +++ b/core_planning/lane_planner/nodes/lane_rule/lane_rule.cpp @@ -200,8 +200,25 @@ autoware_msgs::Lane apply_stopline_acceleration(const autoware_msgs::Lane& lane, std::vector create_stop_points(const lane_planner::vmap::VectorMap& vmap) { std::vector stop_points; + // find all lane points that belong to each stopline's LinkID for (const vector_map::StopLine& s : vmap.stoplines) { + bool match_stopsign = false; + // skip if stopline belongs to a stop sign + for (const vector_map::RoadSign& r : vmap.roadsigns) + { + if (s.signid == r.id) + { + if (r.type != 0) + match_stopsign = true; + continue; + } + } + if (match_stopsign) + { + continue; + } + for (const vector_map::Lane& l : vmap.lanes) { if (l.lnid != s.linkid) @@ -392,7 +409,7 @@ void create_waypoint(const autoware_msgs::LaneArray& msg) for (const autoware_msgs::Lane& l : msg.lanes) cached_waypoint.lanes.push_back(create_new_lane(l, header)); if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty() || all_vmap.stoplines.empty() || - all_vmap.dtlanes.empty()) + all_vmap.roadsigns.empty() || all_vmap.dtlanes.empty()) { traffic_pub.publish(cached_waypoint); return; @@ -487,7 +504,7 @@ void create_waypoint(const autoware_msgs::LaneArray& msg) void update_values() { if (all_vmap.points.empty() || all_vmap.lanes.empty() || all_vmap.nodes.empty() || all_vmap.stoplines.empty() || - all_vmap.dtlanes.empty()) + all_vmap.roadsigns.empty() || all_vmap.dtlanes.empty()) return; lane_vmap = lane_planner::vmap::create_lane_vmap(all_vmap, lane_planner::vmap::LNO_ALL); @@ -563,6 +580,12 @@ void cache_stopline(const vector_map::StopLineArray& msg) update_values(); } +void cache_roadsign(const vector_map::RoadSignArray& msg) +{ + all_vmap.roadsigns = msg.data; + update_values(); +} + void cache_dtlane(const vector_map::DTLaneArray& msg) { all_vmap.dtlanes = msg.data; @@ -644,6 +667,7 @@ int main(int argc, char** argv) ros::Subscriber lane_sub = n.subscribe("/vector_map_info/lane", sub_vmap_queue_size, cache_lane); ros::Subscriber node_sub = n.subscribe("/vector_map_info/node", sub_vmap_queue_size, cache_node); ros::Subscriber stopline_sub = n.subscribe("/vector_map_info/stop_line", sub_vmap_queue_size, cache_stopline); + ros::Subscriber roadsign_sub = n.subscribe("/vector_map_info/road_sign", sub_vmap_queue_size, cache_roadsign); ros::Subscriber dtlane_sub = n.subscribe("/vector_map_info/dtlane", sub_vmap_queue_size, cache_dtlane); ros::Subscriber config_sub = n.subscribe("/config/lane_rule", sub_config_queue_size, config_parameter); diff --git a/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp b/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp index 60b856d2d5a..d2541b1a1d8 100644 --- a/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp +++ b/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp @@ -195,10 +195,10 @@ std::vector check_waypoints_for_stoplines(const std::vector current_lanelet_stoplines = - lanelet::utils::query::stopLinesLanelet(current_lanelet); + lanelet::utils::query::getTrafficLightStopLines(current_lanelet); // check if waypoint segment intersects with stoplines - // kida awkward to force use of boost::geometry intersect. + // kinda awkward to force use of boost::geometry intersect. // 3d line segment intersection not implememented lanelet::ConstLineString3d wp_ls(lanelet::utils::getId(), { wp_p0, wp_p1 }); auto wp_ls2d = lanelet::utils::to2D(wp_ls); @@ -432,7 +432,7 @@ int main(int argc, char** argv) { g_loaded_lanelet_map = false; - ros::init(argc, argv, "lane_rule_lanelet2"); + ros::init(argc, argv, "lane_rule"); ros::NodeHandle rosnode; ros::NodeHandle pnh("~"); diff --git a/core_planning/lane_planner/nodes/lane_select/lane_select_core.cpp b/core_planning/lane_planner/nodes/lane_select/lane_select_core.cpp index 94725e283e0..d05618cd762 100644 --- a/core_planning/lane_planner/nodes/lane_select/lane_select_core.cpp +++ b/core_planning/lane_planner/nodes/lane_select/lane_select_core.cpp @@ -17,6 +17,7 @@ #include "lane_select_core.h" #include +#include namespace lane_planner { @@ -25,8 +26,10 @@ LaneSelectNode::LaneSelectNode() : private_nh_("~") , lane_array_id_(-1) , current_lane_idx_(-1) + , prev_lane_idx_(-1) , right_lane_idx_(-1) , left_lane_idx_(-1) + , is_new_lane_array_(false) , is_lane_array_subscribed_(false) , is_current_pose_subscribed_(false) , is_current_velocity_subscribed_(false) @@ -39,31 +42,28 @@ LaneSelectNode::LaneSelectNode() , vlength_hermite_curve_(10) , search_closest_waypoint_minimum_dt_(5) , current_state_("UNKNOWN") + , update_rate_(10.0) { initForROS(); } -// Destructor -LaneSelectNode::~LaneSelectNode() -{ -} - void LaneSelectNode::initForROS() { // setup subscriber sub1_ = nh_.subscribe("traffic_waypoints_array", 1, &LaneSelectNode::callbackFromLaneArray, this); - sub2_ = nh_.subscribe("current_pose", 1, &LaneSelectNode::callbackFromPoseStamped, this); - sub3_ = nh_.subscribe("current_velocity", 1, &LaneSelectNode::callbackFromTwistStamped, this); - sub4_ = nh_.subscribe("state", 1, &LaneSelectNode::callbackFromState, this); sub5_ = nh_.subscribe("/config/lane_select", 1, &LaneSelectNode::callbackFromConfig, this); sub6_ = nh_.subscribe("/decision_maker/state", 1, &LaneSelectNode::callbackFromDecisionMakerState, this); + sub2_.subscribe(nh_, "current_pose", 1); + sub3_.subscribe(nh_, "current_velocity", 1); + pose_twist_sync_.reset(new PoseTwistSync(PoseTwistSyncPolicy(10), sub2_, sub3_)); + pose_twist_sync_->getPolicy()->setMaxIntervalDuration(ros::Duration(0.1)); + pose_twist_sync_->registerCallback(boost::bind(&LaneSelectNode::callbackFromPoseTwistStamped, this, _1, _2)); // setup publisher - - pub1_ = nh_.advertise("base_waypoints", 1); + pub1_ = nh_.advertise("base_waypoints", 1, true); pub2_ = nh_.advertise("closest_waypoint", 1); pub3_ = nh_.advertise("change_flag", 1); - pub4_ = nh_.advertise("/current_lane_id", 1); + pub4_ = nh_.advertise("current_lane_id", 1); pub5_ = nh_.advertise("vehicle_location", 1); vis_pub1_ = nh_.advertise("lane_select_marker", 1); @@ -75,45 +75,33 @@ void LaneSelectNode::initForROS() private_nh_.param("lane_change_target_ratio", lane_change_target_ratio_, double(2.0)); private_nh_.param("lane_change_target_minimum", lane_change_target_minimum_, double(5.0)); private_nh_.param("vector_length_hermite_curve", vlength_hermite_curve_, double(10.0)); + private_nh_.param("update_rate", update_rate_, double(10.0)); + + // Kick off a timer to publish base_waypoints, closest_waypoint, change_flag, current_lane_id, and vehicle_location + timer_ = nh_.createTimer(ros::Duration(1.0/update_rate_), &LaneSelectNode::processing, this); } bool LaneSelectNode::isAllTopicsSubscribed() { - if (!is_current_pose_subscribed_ || !is_lane_array_subscribed_ || !is_current_velocity_subscribed_) + bool ret = true; + if (!is_current_pose_subscribed_) { - ROS_WARN("Necessary topics are not subscribed yet. Waiting..."); - return false; + ROS_WARN_THROTTLE(5, "Topic current_pose is missing."); + ret = false; } - return true; -} - -void LaneSelectNode::initForLaneSelect() -{ - if (!isAllTopicsSubscribed()) - return; - // search closest waypoint number for each lanes - if (!getClosestWaypointNumberForEachLanes()) + if (!is_lane_array_subscribed_) { - publishClosestWaypoint(-1); - publishVehicleLocation(-1, lane_array_id_); - resetLaneIdx(); - return; + ROS_WARN_THROTTLE(5, "Topic traffic_waypoints_array is missing."); + ret = false; } - findCurrentLane(); - findNeighborLanes(); - updateChangeFlag(); - createLaneForChange(); - - publishLane(std::get<0>(tuple_vec_.at(current_lane_idx_))); - publishClosestWaypoint(std::get<1>(tuple_vec_.at(current_lane_idx_))); - publishChangeFlag(std::get<2>(tuple_vec_.at(current_lane_idx_))); - publishVehicleLocation(std::get<1>(tuple_vec_.at(current_lane_idx_)), lane_array_id_); - publishVisualizer(); - - resetSubscriptionFlag(); - return; + if (!is_current_velocity_subscribed_) + { + ROS_WARN_THROTTLE(5, "Topic current_velocity is missing."); + ret = false; + } + return ret; } void LaneSelectNode::resetLaneIdx() @@ -128,16 +116,15 @@ void LaneSelectNode::resetSubscriptionFlag() { is_current_pose_subscribed_ = false; is_current_velocity_subscribed_ = false; - is_current_state_subscribed_ = false; } -void LaneSelectNode::processing() +void LaneSelectNode::processing(const ros::TimerEvent& e) { if (!isAllTopicsSubscribed()) return; // search closest waypoint number for each lanes - if (!getClosestWaypointNumberForEachLanes()) + if (!updateClosestWaypointNumberForEachLane()) { publishClosestWaypoint(-1); publishVehicleLocation(-1, lane_array_id_); @@ -145,19 +132,12 @@ void LaneSelectNode::processing() return; } - // if closest waypoint on current lane is -1, - if (std::get<1>(tuple_vec_.at(current_lane_idx_)) == -1) - { - publishClosestWaypoint(-1); - publishVehicleLocation(-1, lane_array_id_); - resetLaneIdx(); - return; + if (current_lane_idx_ == -1) { + // Note: Only call it after calling updateClosestWaypointNumberForEachLane() + findCurrentLane(); } findNeighborLanes(); - ROS_INFO("current_lane_idx: %d", current_lane_idx_); - ROS_INFO("right_lane_idx: %d", right_lane_idx_); - ROS_INFO("left_lane_idx: %d", left_lane_idx_); if (current_state_ == "LANE_CHANGE") { @@ -169,16 +149,14 @@ void LaneSelectNode::processing() std::get<1>(lane_for_change_), distance_threshold_, search_closest_waypoint_minimum_dt_); std::get<2>(lane_for_change_) = static_cast( std::get<0>(lane_for_change_).waypoints.at(std::get<1>(lane_for_change_)).change_flag); - ROS_INFO("closest: %d", std::get<1>(lane_for_change_)); publishLane(std::get<0>(lane_for_change_)); - publishLaneID(std::get<0>(lane_for_change_)); publishClosestWaypoint(std::get<1>(lane_for_change_)); publishChangeFlag(std::get<2>(lane_for_change_)); publishVehicleLocation(std::get<1>(lane_for_change_), lane_array_id_); } catch (std::out_of_range) { - ROS_WARN("Failed to get closest waypoint num\n"); + ROS_WARN_THROTTLE(2, "Failed to get closest waypoint num"); } } else @@ -186,7 +164,12 @@ void LaneSelectNode::processing() updateChangeFlag(); createLaneForChange(); - publishLane(std::get<0>(tuple_vec_.at(current_lane_idx_))); + if (is_new_lane_array_ || prev_lane_idx_ != current_lane_idx_) + { + publishLane(std::get<0>(tuple_vec_.at(current_lane_idx_))); + prev_lane_idx_ = current_lane_idx_; + is_new_lane_array_ = false; + } publishClosestWaypoint(std::get<1>(tuple_vec_.at(current_lane_idx_))); publishChangeFlag(std::get<2>(tuple_vec_.at(current_lane_idx_))); publishVehicleLocation(std::get<1>(tuple_vec_.at(current_lane_idx_)), lane_array_id_); @@ -209,6 +192,7 @@ int32_t LaneSelectNode::getClosestLaneChangeWaypointNumber(const std::vector(lane_for_change_).waypoints.clear(); @@ -219,10 +203,9 @@ void LaneSelectNode::createLaneForChange() const int32_t &clst_wp = std::get<1>(tuple_vec_.at(current_lane_idx_)); int32_t num_lane_change = getClosestLaneChangeWaypointNumber(cur_lane.waypoints, clst_wp); - ROS_INFO("num_lane_change: %d", num_lane_change); if (num_lane_change < 0 || num_lane_change >= static_cast(cur_lane.waypoints.size())) { - ROS_WARN("current lane doesn't have change flag"); + ROS_DEBUG_THROTTLE(2, "current lane doesn't have change flag"); return; } @@ -231,14 +214,13 @@ void LaneSelectNode::createLaneForChange() (static_cast(cur_lane.waypoints.at(num_lane_change).change_flag) == ChangeFlag::left && left_lane_idx_ < 0)) { - ROS_WARN("current lane doesn't have the lane for lane change"); + ROS_DEBUG_THROTTLE(2, "current lane doesn't have the lane for lane change"); return; } double dt = getTwoDimensionalDistance(cur_lane.waypoints.at(num_lane_change).pose.pose.position, cur_lane.waypoints.at(clst_wp).pose.pose.position); double dt_by_vel = std::max(fabs(current_velocity_.twist.linear.x * lane_change_target_ratio_), lane_change_target_minimum_); - ROS_INFO("dt : %lf, dt_by_vel : %lf", dt, dt_by_vel); autoware_msgs::Lane &nghbr_lane = static_cast(cur_lane.waypoints.at(num_lane_change).change_flag) == ChangeFlag::right ? std::get<0>(tuple_vec_.at(right_lane_idx_)) : @@ -260,7 +242,6 @@ void LaneSelectNode::createLaneForChange() } } - ROS_INFO("target_num : %d", target_num); if (target_num < 0) return; @@ -286,6 +267,8 @@ void LaneSelectNode::createLaneForChange() std::copy(itr, nghbr_lane.waypoints.end(), std::back_inserter(std::get<0>(lane_for_change_).waypoints)); } + +// Update change flags for each lane at the corresponding closest waypoint. void LaneSelectNode::updateChangeFlag() { for (auto &el : tuple_vec_) @@ -298,8 +281,6 @@ void LaneSelectNode::updateChangeFlag() std::get<2>(el) = ChangeFlag::unknown; else if (std::get<2>(el) == ChangeFlag::left && left_lane_idx_ == -1) std::get<2>(el) = ChangeFlag::unknown; - - ROS_INFO("change_flag: %d", enumToInteger(std::get<2>(el))); } } @@ -320,13 +301,12 @@ void LaneSelectNode::changeLane() return; } -bool LaneSelectNode::getClosestWaypointNumberForEachLanes() +bool LaneSelectNode::updateClosestWaypointNumberForEachLane() { for (auto &el : tuple_vec_) { std::get<1>(el) = getClosestWaypointNumber(std::get<0>(el), current_pose_.pose, current_velocity_.twist, std::get<1>(el), distance_threshold_, search_closest_waypoint_minimum_dt_); - ROS_INFO("closest: %d", std::get<1>(el)); } // confirm if all closest waypoint numbers are -1. If so, output warning @@ -337,7 +317,7 @@ bool LaneSelectNode::getClosestWaypointNumberForEachLanes() } if (accum == (-1) * static_cast(tuple_vec_.size())) { - ROS_WARN("Cannot get closest waypoints. All closest waypoints are changed to -1..."); + ROS_WARN_THROTTLE(2, "Cannot get closest waypoints. All closest waypoints are changed to -1 ..."); return false; } @@ -364,8 +344,15 @@ int32_t LaneSelectNode::findMostClosestLane(const std::vector idx_vec, for (const auto &el : idx_vec) { int32_t closest_number = std::get<1>(tuple_vec_.at(el)); - dist_vec.push_back( - getTwoDimensionalDistance(p, std::get<0>(tuple_vec_.at(el)).waypoints.at(closest_number).pose.pose.position)); + if (closest_number == -1) + { + dist_vec.push_back(std::numeric_limits::max()); + } + else + { + dist_vec.push_back( + getTwoDimensionalDistance(p, std::get<0>(tuple_vec_.at(el)).waypoints.at(closest_number).pose.pose.position)); + } } std::vector::iterator itr = std::min_element(dist_vec.begin(), dist_vec.end()); return idx_vec.at(std::distance(dist_vec.begin(), itr)); @@ -383,15 +370,17 @@ void LaneSelectNode::findNeighborLanes() right_lane_idx_vec.reserve(tuple_vec_.size()); for (uint32_t i = 0; i < tuple_vec_.size(); i++) { + // Skip the current lane or the other lanes which have no valid closest waypoint to the ego-vehicle. if (i == static_cast(current_lane_idx_) || std::get<1>(tuple_vec_.at(i)) == -1) continue; + // Get the closest waypoint on the target lane. int32_t target_num = std::get<1>(tuple_vec_.at(i)); const geometry_msgs::Point &target_p = std::get<0>(tuple_vec_.at(i)).waypoints.at(target_num).pose.pose.position; geometry_msgs::Point converted_p = convertPointIntoRelativeCoordinate(target_p, current_closest_pose); - ROS_INFO("distance: %lf", converted_p.y); + // If the lateral distance is too far from the ego-vehicle, skip it. if (fabs(converted_p.y) > distance_threshold_) { ROS_INFO("%d lane is far from current lane...", i); @@ -414,6 +403,7 @@ void LaneSelectNode::findNeighborLanes() else right_lane_idx_ = -1; } + visualization_msgs::Marker LaneSelectNode::createCurrentLaneMarker() { visualization_msgs::Marker marker; @@ -596,10 +586,8 @@ void LaneSelectNode::publishLane(const autoware_msgs::Lane &lane) { // publish global lane pub1_.publish(lane); -} -void LaneSelectNode::publishLaneID(const autoware_msgs::Lane &lane) -{ + // publish the global lane id std_msgs::Int32 msg; msg.data = lane.lane_id; pub4_.publish(msg); @@ -644,64 +632,31 @@ void LaneSelectNode::callbackFromLaneArray(const autoware_msgs::LaneArrayConstPt current_lane_idx_ = -1; right_lane_idx_ = -1; left_lane_idx_ = -1; + is_new_lane_array_ = true; is_lane_array_subscribed_ = true; - - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); } -void LaneSelectNode::callbackFromPoseStamped(const geometry_msgs::PoseStampedConstPtr &msg) +void LaneSelectNode::callbackFromPoseTwistStamped(const geometry_msgs::PoseStampedConstPtr& pose_msg, + const geometry_msgs::TwistStampedConstPtr& twist_msg) { - current_pose_ = *msg; + current_pose_ = *pose_msg; is_current_pose_subscribed_ = true; - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); -} - -void LaneSelectNode::callbackFromTwistStamped(const geometry_msgs::TwistStampedConstPtr &msg) -{ - current_velocity_ = *msg; + current_velocity_ = *twist_msg; is_current_velocity_subscribed_ = true; - - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); } -void LaneSelectNode::callbackFromState(const std_msgs::StringConstPtr &msg) -{ - current_state_ = msg->data; - is_current_state_subscribed_ = true; - - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); -} void LaneSelectNode::callbackFromDecisionMakerState(const std_msgs::StringConstPtr &msg) { - is_current_state_subscribed_ = true; - if (msg->data.find("ChangeTo") != std::string::npos) { current_state_ = std::string("LANE_CHANGE"); - ; } else { current_state_ = msg->data; } - - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); + is_current_state_subscribed_ = true; } void LaneSelectNode::callbackFromConfig(const autoware_config_msgs::ConfigLaneSelectConstPtr &msg) @@ -712,11 +667,6 @@ void LaneSelectNode::callbackFromConfig(const autoware_config_msgs::ConfigLaneSe lane_change_target_minimum_ = msg->lane_change_target_minimum; vlength_hermite_curve_ = msg->vector_length_hermite_curve; is_config_subscribed_ = true; - - if (current_lane_idx_ == -1) - initForLaneSelect(); - else - processing(); } void LaneSelectNode::run() @@ -785,19 +735,14 @@ int32_t getClosestWaypointNumber(const autoware_msgs::Lane ¤t_lane, const std::vector idx_vec; // if previous number is -1, search closest waypoint from waypoints in front of current pose uint32_t range_min = 0; - uint32_t range_max = current_lane.waypoints.size(); + uint32_t range_max = current_lane.waypoints.size() - 1; if (previous_number == -1) { idx_vec.reserve(current_lane.waypoints.size()); } else { - if (distance_threshold < - getTwoDimensionalDistance(current_lane.waypoints.at(previous_number).pose.pose.position, current_pose.position)) - { - ROS_WARN("Current_pose is far away from previous closest waypoint. Initilized..."); - return -1; - } + // start searching for closest waypoint from range_min (previous waypoint) range_min = static_cast(previous_number); double ratio = 3; double dt = std::max(current_velocity.linear.x * ratio, static_cast(search_closest_waypoint_minimum_dt)); @@ -808,7 +753,7 @@ int32_t getClosestWaypointNumber(const autoware_msgs::Lane ¤t_lane, const } const LaneDirection dir = getLaneDirection(current_lane); const int sgn = (dir == LaneDirection::Forward) ? 1 : (dir == LaneDirection::Backward) ? -1 : 0; - for (uint32_t i = range_min; i < range_max; i++) + for (uint32_t i = range_min; i <= range_max; i++) { geometry_msgs::Point converted_p = convertPointIntoRelativeCoordinate(current_lane.waypoints.at(i).pose.pose.position, current_pose); @@ -826,12 +771,20 @@ int32_t getClosestWaypointNumber(const autoware_msgs::Lane ¤t_lane, const dist_vec.reserve(idx_vec.size()); for (const auto &el : idx_vec) { - double dt = getTwoDimensionalDistance(current_pose.position, current_lane.waypoints.at(el).pose.pose.position); - dist_vec.push_back(dt); + double distance = getTwoDimensionalDistance( + current_pose.position, current_lane.waypoints.at(el).pose.pose.position); + dist_vec.push_back(distance); } + + // Check distance std::vector::iterator itr = std::min_element(dist_vec.begin(), dist_vec.end()); - int32_t found_number = idx_vec.at(static_cast(std::distance(dist_vec.begin(), itr))); - return found_number; + if (*itr > distance_threshold) + { + return -1; + } + + int32_t closest_waypoint_idx = idx_vec.at(static_cast(std::distance(dist_vec.begin(), itr))); + return closest_waypoint_idx; } // let the linear equation be "ax + by + c = 0" @@ -845,7 +798,7 @@ bool getLinearEquation(geometry_msgs::Point start, geometry_msgs::Point end, dou if (sub_x < error && sub_y < error) { - ROS_INFO("two points are the same point!!"); + ROS_WARN("Two points are the same point!!"); return false; } diff --git a/core_planning/lane_planner/package.xml b/core_planning/lane_planner/package.xml index b1842299ddc..7e9eb4e0cec 100644 --- a/core_planning/lane_planner/package.xml +++ b/core_planning/lane_planner/package.xml @@ -9,15 +9,15 @@ autoware_build_flags catkin + autoware_config_msgs autoware_msgs gnss + lanelet2_extension + libwaypoint_follower roscpp std_msgs - vector_map tablet_socket_msgs - libwaypoint_follower - autoware_config_msgs - lanelet2_extension + vector_map rostest rosunit diff --git a/core_planning/lane_planner/test/src/test_lane_select.cpp b/core_planning/lane_planner/test/src/test_lane_select.cpp index 7088ba90e82..da4c2d2e019 100644 --- a/core_planning/lane_planner/test/src/test_lane_select.cpp +++ b/core_planning/lane_planner/test/src/test_lane_select.cpp @@ -47,9 +47,10 @@ TEST_F(LaneSelectTestSuite, publishVehicleLocation) { test_obj_.publishTrafficWaypointsArray(dir.second); test_obj_.publishCurrentPose(-0.5 * dir.second, 0.0, 0.0); test_obj_.publishCurrentVelocity(0); + ros::WallDuration(0.1).sleep(); ros::spinOnce(); ros::WallDuration(0.1).sleep(); - test_obj_.lsnSpinOnce(); + ros::spinOnce(); ros::WallDuration(0.1).sleep(); ros::spinOnce(); @@ -63,9 +64,10 @@ TEST_F(LaneSelectTestSuite, publishVehicleLocation) { test_obj_.publishCurrentPose(0.5 * dir.second, 0.0, 0.0); test_obj_.publishCurrentVelocity(0); + ros::WallDuration(0.1).sleep(); ros::spinOnce(); ros::WallDuration(0.1).sleep(); - test_obj_.lsnSpinOnce(); + ros::spinOnce(); ros::WallDuration(0.1).sleep(); ros::spinOnce(); diff --git a/core_planning/ll2_global_planner/CMakeLists.txt b/core_planning/ll2_global_planner/CMakeLists.txt new file mode 100644 index 00000000000..2e23cb55223 --- /dev/null +++ b/core_planning/ll2_global_planner/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ll2_global_planner) + +## c++11 feature +set(CMAKE_CXX_FLAGS "-std=c++14 -Wall -Wextra ${CMAKE_CXX_FLAGS}") + +set(catkin_deps + autoware_lanelet2_msgs + autoware_msgs + geometry_msgs + lanelet2_extension + nodelet + roscpp + roslib + roslint + tf2 + tf2_ros +) + +find_package(catkin REQUIRED ${catkin_deps}) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS ${catkin_deps} + LIBRARIES ${PROJECT_NAME} ${PROJECT_NAME}_nodelet +) + +roslint_cpp() + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +# nodelet +add_library(${PROJECT_NAME}_nodelet + src/${PROJECT_NAME}_nodelet.cpp +) + +target_link_libraries(${PROJECT_NAME}_nodelet + ${catkin_LIBRARIES} +) + +# node +add_executable(${PROJECT_NAME}_node + src/${PROJECT_NAME}_node.cpp +) + +target_link_libraries(${PROJECT_NAME}_node + ${catkin_LIBRARIES} +) + +########## +## TEST ## +########## + +# if (CATKIN_ENABLE_TESTING) +# find_package(rostest REQUIRED) +# +# # ROS tests +# add_rostest_gtest(test_${PROJECT_NAME}_node +# test/rostest_launch.test +# test/rostest_integration_test.cpp +# ) +# target_link_libraries(test_${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) +# endif(CATKIN_ENABLE_TESTING) + +############# +## Install ## +############# + +install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}_nodelet + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(DIRECTORY launch config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(FILES nodelets.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/core_planning/ll2_global_planner/LICENSE b/core_planning/ll2_global_planner/LICENSE new file mode 100644 index 00000000000..ca58b6a78a7 --- /dev/null +++ b/core_planning/ll2_global_planner/LICENSE @@ -0,0 +1,19 @@ +Copyright (c) 2020 AutonomouStuff, LLC + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/core_planning/ll2_global_planner/README.md b/core_planning/ll2_global_planner/README.md new file mode 100644 index 00000000000..893b686d1e8 --- /dev/null +++ b/core_planning/ll2_global_planner/README.md @@ -0,0 +1,36 @@ +# ll2_global_planner + +This ROS package provides a global planner that finds routes in Lanelet2 maps. + +## Dependencies + +- Lanelet2 (Installed along with Autoware) + +## ROS API + +#### Subs + +- `lanelet_map_bin` (autoware_lanelet2_msgs/MapBin) +This topic is used to load the lanelet2 map. +- `move_base_simple/goal` (geometry_msgs/PoseStamped) +This topic is used to receive a waypoint goal from RViz. + +#### Pubs + +- `based/lane_waypoints_raw` (autoware_msgs/LaneArray) +The waypoints that make up the planned route. +It is expected that this topic will be fed into the waypoint_replanner to ensure speeds are comfortable around turns. + +#### Transform Listeners + +- `map` -> `base_link` dynamic TF +Used to determine the current position of the vehicle within the map. + +#### Transform Broadcasters + + +#### Configuration Parameters + +See the `config/params.yaml` file for a list of parameters and their descriptions. + +## Notes diff --git a/core_planning/ll2_global_planner/config/params.yaml b/core_planning/ll2_global_planner/config/params.yaml new file mode 100644 index 00000000000..e69de29bb2d diff --git a/core_planning/ll2_global_planner/include/ll2_global_planner/ll2_global_planner_nodelet.hpp b/core_planning/ll2_global_planner/include/ll2_global_planner/ll2_global_planner_nodelet.hpp new file mode 100644 index 00000000000..a732699c212 --- /dev/null +++ b/core_planning/ll2_global_planner/include/ll2_global_planner/ll2_global_planner_nodelet.hpp @@ -0,0 +1,69 @@ +/* +* Unpublished Copyright (c) 2009-2020 AutonomouStuff, All Rights Reserved. +* +* This file is part of the ll2_global_planner which is released under the MIT license. +* See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details. +*/ + +#ifndef ll2_global_planner_Ll2GlobalPlannerNl_H +#define ll2_global_planner_Ll2GlobalPlannerNl_H + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + + +namespace ll2_global_planner { + +class Ll2GlobalPlannerNl : public nodelet::Nodelet { + public: + Ll2GlobalPlannerNl(); + + private: + // Init + virtual void onInit(); + void loadParams(); + + // Subscriber callbacks + void laneletMapCb(const autoware_lanelet2_msgs::MapBin& map_msg); + void poseGoalCb(const geometry_msgs::PoseStamped::ConstPtr& pose_msg); + void llhGoalCb(const sensor_msgs::NavSatFix::ConstPtr& llh_msg); + + // Utility functions + void planRoute(const lanelet::BasicPoint2d& goal_point); + std::vector generateAutowareWaypoints( + const lanelet::LaneletSequence& continuous_lane, const lanelet::BasicPoint2d& goal_point); + lanelet::Lanelet getNearestLanelet(const lanelet::BasicPoint2d& point); + + // Nodehandles, both public and private + ros::NodeHandle nh_, pnh_; + + // Publishers + ros::Publisher waypoints_pub_; + + // Subscribers + ros::Subscriber lanelet_sub_; + ros::Subscriber posegoal_sub_; + ros::Subscriber llh_sub_; + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // Internal state + bool initialized_ = false; + lanelet::LaneletMapPtr lanelet_map_ = nullptr; + lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ = nullptr; + lanelet::routing::RoutingGraphUPtr routing_graph_ = nullptr; +}; + +} // namespace ll2_global_planner +#endif // ll2_global_planner_Ll2GlobalPlannerNl_H diff --git a/core_planning/ll2_global_planner/launch/ll2_global_planner_node.launch b/core_planning/ll2_global_planner/launch/ll2_global_planner_node.launch new file mode 100644 index 00000000000..c36bf5afef6 --- /dev/null +++ b/core_planning/ll2_global_planner/launch/ll2_global_planner_node.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/core_planning/ll2_global_planner/nodelets.xml b/core_planning/ll2_global_planner/nodelets.xml new file mode 100644 index 00000000000..0c20099e045 --- /dev/null +++ b/core_planning/ll2_global_planner/nodelets.xml @@ -0,0 +1,9 @@ + + + + Global planner based on Lanelet2 maps. + + + diff --git a/core_planning/ll2_global_planner/package.xml b/core_planning/ll2_global_planner/package.xml new file mode 100644 index 00000000000..b161d8effda --- /dev/null +++ b/core_planning/ll2_global_planner/package.xml @@ -0,0 +1,24 @@ + + ll2_global_planner + 0.0.1 + Global planner for generating autoware routes based on Lanelet2 maps + Ian Colwell + Ian Colwell + MIT + + catkin + autoware_lanelet2_msgs + autoware_msgs + geometry_msgs + lanelet2_extension + nodelet + roscpp + roslib + roslint + tf2_ros + tf2 + + + + + diff --git a/core_planning/ll2_global_planner/src/ll2_global_planner_node.cpp b/core_planning/ll2_global_planner/src/ll2_global_planner_node.cpp new file mode 100644 index 00000000000..4227c96729a --- /dev/null +++ b/core_planning/ll2_global_planner/src/ll2_global_planner_node.cpp @@ -0,0 +1,24 @@ +/* +* Unpublished Copyright (c) 2009-2020 AutonomouStuff, All Rights Reserved. +* +* This file is part of the ll2_global_planner which is released under the MIT license. +* See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details. +*/ + +#include +#include +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "ll2_global_planner_node"); + nodelet::Loader nodelet; + nodelet::M_string remap(ros::names::getRemappings()); + nodelet::V_string nargv; + std::string nodelet_name = ros::this_node::getName(); + nodelet.load( + nodelet_name, "ll2_global_planner/ll2_global_planner_nodelet", remap, nargv); + ros::spin(); + return 0; +} diff --git a/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp b/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp new file mode 100644 index 00000000000..cae02022a9b --- /dev/null +++ b/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp @@ -0,0 +1,260 @@ +/* +* Unpublished Copyright (c) 2009-2020 AutonomouStuff, All Rights Reserved. +* +* This file is part of the ll2_global_planner which is released under the MIT license. +* See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details. +*/ + +#include "ll2_global_planner/ll2_global_planner_nodelet.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace lanelet; + +namespace ll2_global_planner +{ + +Ll2GlobalPlannerNl::Ll2GlobalPlannerNl() : + tf_listener_(tf_buffer_) +{} + +void Ll2GlobalPlannerNl::onInit() +{ + nh_ = getNodeHandle(); + pnh_ = getPrivateNodeHandle(); + loadParams(); + + // Publishers + waypoints_pub_ = nh_.advertise("based/lane_waypoints_raw", 1, true); + + // Subscribers + lanelet_sub_ = nh_.subscribe("lanelet_map_bin", 1, &Ll2GlobalPlannerNl::laneletMapCb, this); + posegoal_sub_ = nh_.subscribe("move_base_simple/goal", 1, &Ll2GlobalPlannerNl::poseGoalCb, this); + llh_sub_ = pnh_.subscribe("llh_goal", 1, &Ll2GlobalPlannerNl::llhGoalCb, this); +} + +void Ll2GlobalPlannerNl::loadParams() +{ + ROS_INFO("Parameters Loaded"); +} + +void Ll2GlobalPlannerNl::laneletMapCb(const autoware_lanelet2_msgs::MapBin& map_msg) +{ + lanelet_map_ = std::make_shared(); + lanelet::utils::conversion::fromBinMsg(map_msg, lanelet_map_); + + traffic_rules_ = traffic_rules::TrafficRulesFactory::instance().create(Locations::Germany, Participants::Vehicle); + routing_graph_ = routing::RoutingGraph::build(*lanelet_map_, *traffic_rules_); + + initialized_ = true; + ROS_INFO("Loaded Lanelet map"); +} + +void Ll2GlobalPlannerNl::poseGoalCb(const geometry_msgs::PoseStamped::ConstPtr& pose_msg) +{ + if (!initialized_) + { + ROS_WARN("Waiting for lanelet2 map"); + return; + } + + BasicPoint2d goal_point(pose_msg->pose.position.x, pose_msg->pose.position.y); + planRoute(goal_point); +} + +void Ll2GlobalPlannerNl::llhGoalCb(const sensor_msgs::NavSatFix::ConstPtr& llh_msg) +{ + GPSPoint gps_point; + gps_point.lat = llh_msg->latitude; + gps_point.lon = llh_msg->longitude; + gps_point.ele = llh_msg->altitude; + projection::MGRSProjector projector; + BasicPoint3d goal_point_3d = projector.forward(gps_point); + BasicPoint2d goal_point(goal_point_3d.x(), goal_point_3d.y()); + planRoute(goal_point); +} + +void Ll2GlobalPlannerNl::planRoute(const BasicPoint2d& goal_point) +{ + // Find the nearest lanelet to the goal point + Lanelet goal_lanelet = getNearestLanelet(goal_point); + + // Get the current vehicle position + geometry_msgs::TransformStamped tf_msg; + try + { + tf_msg = tf_buffer_.lookupTransform("map", "base_link", ros::Time(0), ros::Duration(2.0)); + } + catch (tf2::TransformException &ex) + { + ROS_WARN_THROTTLE(2, "%s", ex.what()); + ROS_WARN_THROTTLE(2, "Waiting for map -> base_link transform"); + return; + } + + BasicPoint2d starting_point( + tf_msg.transform.translation.x, tf_msg.transform.translation.y); + const Lanelet& starting_lanelet = getNearestLanelet(starting_point); + + // Plan a route from current vehicle position + Optional shortest_path_opt = routing_graph_->shortestPath(starting_lanelet, goal_lanelet); + routing::LaneletPath shortest_path; + + if (!shortest_path_opt) + { + ROS_WARN("Could not find path in lanelet map!"); + return; + } + + shortest_path = shortest_path_opt.value(); + LaneletSequence continuous_lane = shortest_path.getRemainingLane(shortest_path.begin()); + + if (continuous_lane.size() != shortest_path.size()) + { + ROS_WARN("This route contains a lane change which is currently unsupported"); + return; + } + + ROS_INFO("Found a path containing %lu lanelets", shortest_path.size()); + + autoware_msgs::Lane lane_msg; + lane_msg.waypoints = generateAutowareWaypoints(continuous_lane, goal_point); + lane_msg.header.stamp = ros::Time(0); + lane_msg.header.frame_id = "map"; + lane_msg.is_blocked = false; + + autoware_msgs::LaneArray lane_array_msg; + lane_array_msg.lanes.push_back(lane_msg); + waypoints_pub_.publish(lane_array_msg); +} + +std::vector Ll2GlobalPlannerNl::generateAutowareWaypoints( + const LaneletSequence& continuous_lane, const BasicPoint2d& goal_point) +{ + const float duplicate_dist_threshold = 0.1; + std::vector waypoints; + + // Loop over each lanelet + for (auto& lanelet : continuous_lane.lanelets()) + { + const std::string turn_direction = lanelet.attributeOr("turn_direction", "straight"); + const traffic_rules::SpeedLimitInformation speed_limit = traffic_rules_->speedLimit(lanelet); + + // centerline() will return a series of points spaced 1 meter apart thanks + // to Autoware.AI's lanelet2_map_loader. The loader rewrites the original + // centerline with a resampled centerline for easier use with autoware. + const ConstLineString3d centerline = lanelet.centerline(); + const int wp_length = centerline.size() - 1; + + // Loop over each centerline point + for (int i = 0; i <= wp_length; i++) + { + auto point = centerline[i]; + + autoware_msgs::Waypoint new_wp; + new_wp.pose.pose.position.x = point.x(); + new_wp.pose.pose.position.y = point.y(); + new_wp.pose.pose.position.z = point.z(); + new_wp.twist.twist.linear.x = speed_limit.speedLimit.value(); // m/s + + int steering_state = autoware_msgs::WaypointState::STR_STRAIGHT; + if (turn_direction.compare("right") == 0) + { + steering_state = autoware_msgs::WaypointState::STR_RIGHT; + } + if (turn_direction.compare("left") == 0) + { + steering_state = autoware_msgs::WaypointState::STR_LEFT; + } + new_wp.wpstate.steering_state = steering_state; + + waypoints.push_back(new_wp); + } + } + + int wp_id = 0; + bool first_point = true; + float smallest_goal_dist = std::numeric_limits::infinity(); + int smallest_goal_wp_id = 0; + autoware_msgs::Waypoint* prev_waypoint = nullptr; + std::vector processed_waypoints; + + // Remove duplicates and set waypoint orientations + for (autoware_msgs::Waypoint& waypoint : waypoints) + { + geometry_msgs::Pose& pose = waypoint.pose.pose; + geometry_msgs::Pose& prev_pose = prev_waypoint->pose.pose; + + if (!first_point) + { + // Check for duplicate points + float dist = std::hypot(pose.position.x - prev_pose.position.x, pose.position.y - prev_pose.position.y); + if (dist < duplicate_dist_threshold) + { + continue; + } + + // Set orientation of the previous point, aiming at current point + float yaw = std::atan2(pose.position.y - prev_pose.position.y, pose.position.x - prev_pose.position.x); + + tf2::Quaternion orientation; + orientation.setRPY(0, 0, yaw); + tf2::convert(orientation, prev_pose.orientation); + } + else + { + first_point = false; + } + + // Calculate distance to goal point + float goal_dist = std::hypot(goal_point.x() - pose.position.x, goal_point.y() - pose.position.y); + if (goal_dist < smallest_goal_dist) + { + smallest_goal_dist = goal_dist; + smallest_goal_wp_id = wp_id; + } + + waypoint.gid = wp_id; + processed_waypoints.push_back(waypoint); + prev_waypoint = &processed_waypoints.back(); + wp_id++; + } + + // Set orientation of the last waypoint + processed_waypoints.back().pose.pose.orientation = processed_waypoints.end()[-2].pose.pose.orientation; + + // Trim waypoints to stop at goal point + processed_waypoints.resize(smallest_goal_wp_id); + + return processed_waypoints; +} + +Lanelet Ll2GlobalPlannerNl::getNearestLanelet(const lanelet::BasicPoint2d& point) +{ + std::vector> closeLanelets = geometry::findNearest(lanelet_map_->laneletLayer, point, 1); + + if (closeLanelets.size() > 1) + { + ROS_WARN("Vehicle is positioned inside multiple lanelets, choosing the first lanelet as the starting point"); + } + + Lanelet nearest_lanelet = closeLanelets[0].second; + + return nearest_lanelet; +} + +} // namespace ll2_global_planner + +PLUGINLIB_EXPORT_CLASS(ll2_global_planner::Ll2GlobalPlannerNl, nodelet::Nodelet); diff --git a/core_planning/op_global_planner/CMakeLists.txt b/core_planning/op_global_planner/CMakeLists.txt index 594789235d8..84bdbf9fdc1 100644 --- a/core_planning/op_global_planner/CMakeLists.txt +++ b/core_planning/op_global_planner/CMakeLists.txt @@ -9,7 +9,6 @@ find_package( geometry_msgs jsk_recognition_msgs libwaypoint_follower - message_generation op_planner op_ros_helpers op_simu @@ -17,7 +16,6 @@ find_package( pcl_conversions pcl_ros roscpp - rospy std_msgs tf vector_map_msgs @@ -26,18 +24,6 @@ find_package( catkin_package( INCLUDE_DIRS include LIBRARIES op_global_planner - CATKIN_DEPENDS - autoware_can_msgs - geometry_msgs - libwaypoint_follower - op_planner - op_ros_helpers - op_simu - op_utility - roscpp - rospy - std_msgs - vector_map_msgs ) include_directories( diff --git a/core_planning/op_global_planner/include/op_global_planner_core.h b/core_planning/op_global_planner/include/op_global_planner_core.h index 16ab0a877f8..230d0223de0 100644 --- a/core_planning/op_global_planner/include/op_global_planner_core.h +++ b/core_planning/op_global_planner/include/op_global_planner_core.h @@ -62,28 +62,28 @@ namespace GlobalPlanningNS class WayPlannerParams { public: - std::string KmlMapPath; - bool bEnableSmoothing; - bool bEnableLaneChange; - bool bEnableHMI; - bool bEnableRvizInput; - bool bEnableReplanning; - double pathDensity; - PlannerHNS::MAP_SOURCE_TYPE mapSource; - bool bEnableDynamicMapUpdate; - - - WayPlannerParams() - { - bEnableDynamicMapUpdate = false; - bEnableReplanning = false; - bEnableHMI = false; - bEnableSmoothing = false; - bEnableLaneChange = false; - bEnableRvizInput = true; - pathDensity = 0.5; - mapSource = PlannerHNS::MAP_KML_FILE; - } + std::string KmlMapPath; + bool bEnableSmoothing; + bool bEnableLaneChange; + bool bEnableHMI; + bool bEnableRvizInput; + bool bEnableReplanning; + double pathDensity; + PlannerHNS::MAP_SOURCE_TYPE mapSource; + bool bEnableDynamicMapUpdate; + + + WayPlannerParams() + { + bEnableDynamicMapUpdate = false; + bEnableReplanning = false; + bEnableHMI = false; + bEnableSmoothing = false; + bEnableLaneChange = false; + bEnableRvizInput = true; + pathDensity = 0.5; + mapSource = PlannerHNS::MAP_KML_FILE; + } }; @@ -91,44 +91,44 @@ class GlobalPlanner { public: - int m_iCurrentGoalIndex; + int m_iCurrentGoalIndex; protected: - WayPlannerParams m_params; - PlannerHNS::WayPoint m_CurrentPose; - std::vector m_GoalsPos; - geometry_msgs::Pose m_OriginPos; - PlannerHNS::VehicleState m_VehicleState; - std::vector m_GridMapIntType; - std::vector , timespec> > m_ModifiedMapItemsTimes; - timespec m_ReplnningTimer; - - int m_GlobalPathID; - - bool m_bFirstStart; - - ros::NodeHandle nh; - - ros::Publisher pub_MapRviz; - ros::Publisher pub_Paths; - ros::Publisher pub_PathsRviz; - ros::Publisher pub_TrafficInfo; - //ros::Publisher pub_TrafficInfoRviz; - //ros::Publisher pub_StartPointRviz; - //ros::Publisher pub_GoalPointRviz; - //ros::Publisher pub_NodesListRviz; - ros::Publisher pub_GoalsListRviz; - - ros::Subscriber sub_robot_odom; - ros::Subscriber sub_start_pose; - ros::Subscriber sub_goal_pose; - ros::Subscriber sub_current_pose; - ros::Subscriber sub_current_velocity; - ros::Subscriber sub_can_info; - ros::Subscriber sub_road_status_occupancy; + WayPlannerParams m_params; + PlannerHNS::WayPoint m_CurrentPose; + std::vector m_GoalsPos; + geometry_msgs::Pose m_OriginPos; + PlannerHNS::VehicleState m_VehicleState; + std::vector m_GridMapIntType; + std::vector , timespec> > m_ModifiedMapItemsTimes; + timespec m_ReplnningTimer; + + int m_GlobalPathID; + + bool m_bFirstStart; + + ros::NodeHandle nh; + + ros::Publisher pub_MapRviz; + ros::Publisher pub_Paths; + ros::Publisher pub_PathsRviz; + ros::Publisher pub_TrafficInfo; + //ros::Publisher pub_TrafficInfoRviz; + //ros::Publisher pub_StartPointRviz; + //ros::Publisher pub_GoalPointRviz; + //ros::Publisher pub_NodesListRviz; + ros::Publisher pub_GoalsListRviz; + + ros::Subscriber sub_robot_odom; + ros::Subscriber sub_start_pose; + ros::Subscriber sub_goal_pose; + ros::Subscriber sub_current_pose; + ros::Subscriber sub_current_velocity; + ros::Subscriber sub_can_info; + ros::Subscriber sub_road_status_occupancy; public: - GlobalPlanner(); + GlobalPlanner(); ~GlobalPlanner(); void MainLoop(); @@ -147,53 +147,53 @@ class GlobalPlanner void callbackGetRoadStatusOccupancyGrid(const nav_msgs::OccupancyGridConstPtr& msg); protected: - PlannerHNS::RoadNetwork m_Map; - bool m_bKmlMap; - PlannerHNS::PlannerH m_PlannerH; - std::vector > m_GeneratedTotalPaths; - - bool GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, std::vector >& generatedTotalPaths); - void VisualizeAndSend(const std::vector > generatedTotalPaths); - void VisualizeDestinations(std::vector& destinations, const int& iSelected); - void SaveSimulationData(); - int LoadSimulationData(); - void ClearOldCostFromMap(); - - - //Mapping Section - - UtilityHNS::MapRaw m_MapRaw; - - ros::Subscriber sub_lanes; - ros::Subscriber sub_points; - ros::Subscriber sub_dt_lanes; - ros::Subscriber sub_intersect; - ros::Subscriber sup_area; - ros::Subscriber sub_lines; - ros::Subscriber sub_stop_line; - ros::Subscriber sub_signals; - ros::Subscriber sub_vectors; - ros::Subscriber sub_curbs; - ros::Subscriber sub_edges; - ros::Subscriber sub_way_areas; - ros::Subscriber sub_cross_walk; - ros::Subscriber sub_nodes; - - - void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); - void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); - void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); - void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); - void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); - void callbackGetVMLines(const vector_map_msgs::LineArray& msg); - void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); - void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); - void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); - void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); - void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); - void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); - void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); - void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); + PlannerHNS::RoadNetwork m_Map; + bool m_bKmlMap; + PlannerHNS::PlannerH m_PlannerH; + std::vector > m_GeneratedTotalPaths; + + bool GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, std::vector >& generatedTotalPaths); + void VisualizeAndSend(const std::vector > generatedTotalPaths); + void VisualizeDestinations(std::vector& destinations, const int& iSelected); + void SaveSimulationData(); + int LoadSimulationData(); + void ClearOldCostFromMap(); + + + //Mapping Section + + UtilityHNS::MapRaw m_MapRaw; + + ros::Subscriber sub_lanes; + ros::Subscriber sub_points; + ros::Subscriber sub_dt_lanes; + ros::Subscriber sub_intersect; + ros::Subscriber sup_area; + ros::Subscriber sub_lines; + ros::Subscriber sub_stop_line; + ros::Subscriber sub_signals; + ros::Subscriber sub_vectors; + ros::Subscriber sub_curbs; + ros::Subscriber sub_edges; + ros::Subscriber sub_way_areas; + ros::Subscriber sub_cross_walk; + ros::Subscriber sub_nodes; + + + void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); + void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); + void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); + void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); + void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); + void callbackGetVMLines(const vector_map_msgs::LineArray& msg); + void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); + void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); + void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); + void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); + void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); + void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); + void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); + void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); }; diff --git a/core_planning/op_global_planner/launch/op_global_planner.launch b/core_planning/op_global_planner/launch/op_global_planner.launch index 8cfbaa0e9ca..3d7b41b1c90 100644 --- a/core_planning/op_global_planner/launch/op_global_planner.launch +++ b/core_planning/op_global_planner/launch/op_global_planner.launch @@ -1,28 +1,28 @@ - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - - - - - + + + + + + + + + + + + + + \ No newline at end of file diff --git a/core_planning/op_global_planner/nodes/op_global_planner.cpp b/core_planning/op_global_planner/nodes/op_global_planner.cpp index ae442655cb5..0e92b7fc0a4 100644 --- a/core_planning/op_global_planner/nodes/op_global_planner.cpp +++ b/core_planning/op_global_planner/nodes/op_global_planner.cpp @@ -28,8 +28,8 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "op_global_planner"); - GlobalPlanningNS::GlobalPlanner global_planner; - global_planner.MainLoop(); - return 0; + ros::init(argc, argv, "op_global_planner"); + GlobalPlanningNS::GlobalPlanner global_planner; + global_planner.MainLoop(); + return 0; } diff --git a/core_planning/op_global_planner/nodes/op_global_planner_core.cpp b/core_planning/op_global_planner/nodes/op_global_planner_core.cpp index 4fcb42fb046..1c2d746816e 100644 --- a/core_planning/op_global_planner/nodes/op_global_planner_core.cpp +++ b/core_planning/op_global_planner/nodes/op_global_planner_core.cpp @@ -22,486 +22,486 @@ namespace GlobalPlanningNS GlobalPlanner::GlobalPlanner() { - m_pCurrGoal = 0; - m_iCurrentGoalIndex = 0; - m_bKmlMap = false; - m_bFirstStart = false; - m_GlobalPathID = 1; - UtilityHNS::UtilityH::GetTickCount(m_ReplnningTimer); - - nh.getParam("/op_global_planner/pathDensity" , m_params.pathDensity); - nh.getParam("/op_global_planner/enableSmoothing" , m_params.bEnableSmoothing); - nh.getParam("/op_global_planner/enableLaneChange" , m_params.bEnableLaneChange); - nh.getParam("/op_global_planner/enableRvizInput" , m_params.bEnableRvizInput); - nh.getParam("/op_global_planner/enableReplan" , m_params.bEnableReplanning); - nh.getParam("/op_global_planner/enableDynamicMapUpdate" , m_params.bEnableDynamicMapUpdate); - nh.getParam("/op_global_planner/mapFileName" , m_params.KmlMapPath); - - int iSource = 0; - nh.getParam("/op_global_planner/mapSource", iSource); - if(iSource == 0) - m_params.mapSource = PlannerHNS::MAP_AUTOWARE; - else if (iSource == 1) - m_params.mapSource = PlannerHNS::MAP_FOLDER; - else if(iSource == 2) - m_params.mapSource = PlannerHNS::MAP_KML_FILE; - - tf::StampedTransform transform; - PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_Paths = nh.advertise("lane_waypoints_array", 1, true); - pub_PathsRviz = nh.advertise("global_waypoints_rviz", 1, true); - pub_MapRviz = nh.advertise("vector_map_center_lines_rviz", 1, true); - pub_GoalsListRviz = nh.advertise("op_destinations_rviz", 1, true); - - if(m_params.bEnableRvizInput) - { - sub_start_pose = nh.subscribe("/initialpose", 1, &GlobalPlanner::callbackGetStartPose, this); - sub_goal_pose = nh.subscribe("move_base_simple/goal", 1, &GlobalPlanner::callbackGetGoalPose, this); - } - else - { - LoadSimulationData(); - } - - sub_current_pose = nh.subscribe("/current_pose", 10, &GlobalPlanner::callbackGetCurrentPose, this); - - int bVelSource = 1; - nh.getParam("/op_global_planner/velocitySource", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 10, &GlobalPlanner::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 10, &GlobalPlanner::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 10, &GlobalPlanner::callbackGetCANInfo, this); - - if(m_params.bEnableDynamicMapUpdate) - sub_road_status_occupancy = nh.subscribe<>("/occupancy_road_status", 1, &GlobalPlanner::callbackGetRoadStatusOccupancyGrid, this); - - //Mapping Section - sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &GlobalPlanner::callbackGetVMLanes, this); - sub_points = nh.subscribe("/vector_map_info/point", 1, &GlobalPlanner::callbackGetVMPoints, this); - sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &GlobalPlanner::callbackGetVMdtLanes, this); - sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &GlobalPlanner::callbackGetVMIntersections, this); - sup_area = nh.subscribe("/vector_map_info/area", 1, &GlobalPlanner::callbackGetVMAreas, this); - sub_lines = nh.subscribe("/vector_map_info/line", 1, &GlobalPlanner::callbackGetVMLines, this); - sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &GlobalPlanner::callbackGetVMStopLines, this); - sub_signals = nh.subscribe("/vector_map_info/signal", 1, &GlobalPlanner::callbackGetVMSignal, this); - sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &GlobalPlanner::callbackGetVMVectors, this); - sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &GlobalPlanner::callbackGetVMCurbs, this); - sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &GlobalPlanner::callbackGetVMRoadEdges, this); - sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &GlobalPlanner::callbackGetVMWayAreas, this); - sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &GlobalPlanner::callbackGetVMCrossWalks, this); - sub_nodes = nh.subscribe("/vector_map_info/node", 1, &GlobalPlanner::callbackGetVMNodes, this); + m_pCurrGoal = 0; + m_iCurrentGoalIndex = 0; + m_bKmlMap = false; + m_bFirstStart = false; + m_GlobalPathID = 1; + UtilityHNS::UtilityH::GetTickCount(m_ReplnningTimer); + + nh.getParam("/op_global_planner/pathDensity" , m_params.pathDensity); + nh.getParam("/op_global_planner/enableSmoothing" , m_params.bEnableSmoothing); + nh.getParam("/op_global_planner/enableLaneChange" , m_params.bEnableLaneChange); + nh.getParam("/op_global_planner/enableRvizInput" , m_params.bEnableRvizInput); + nh.getParam("/op_global_planner/enableReplan" , m_params.bEnableReplanning); + nh.getParam("/op_global_planner/enableDynamicMapUpdate" , m_params.bEnableDynamicMapUpdate); + nh.getParam("/op_global_planner/mapFileName" , m_params.KmlMapPath); + + int iSource = 0; + nh.getParam("/op_global_planner/mapSource", iSource); + if(iSource == 0) + m_params.mapSource = PlannerHNS::MAP_AUTOWARE; + else if (iSource == 1) + m_params.mapSource = PlannerHNS::MAP_FOLDER; + else if(iSource == 2) + m_params.mapSource = PlannerHNS::MAP_KML_FILE; + + tf::StampedTransform transform; + PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_Paths = nh.advertise("lane_waypoints_array", 1, true); + pub_PathsRviz = nh.advertise("global_waypoints_rviz", 1, true); + pub_MapRviz = nh.advertise("vector_map_center_lines_rviz", 1, true); + pub_GoalsListRviz = nh.advertise("op_destinations_rviz", 1, true); + + if(m_params.bEnableRvizInput) + { + sub_start_pose = nh.subscribe("/initialpose", 1, &GlobalPlanner::callbackGetStartPose, this); + sub_goal_pose = nh.subscribe("move_base_simple/goal", 1, &GlobalPlanner::callbackGetGoalPose, this); + } + else + { + LoadSimulationData(); + } + + sub_current_pose = nh.subscribe("/current_pose", 10, &GlobalPlanner::callbackGetCurrentPose, this); + + int bVelSource = 1; + nh.getParam("/op_global_planner/velocitySource", bVelSource); + if(bVelSource == 0) + sub_robot_odom = nh.subscribe("/odom", 10, &GlobalPlanner::callbackGetRobotOdom, this); + else if(bVelSource == 1) + sub_current_velocity = nh.subscribe("/current_velocity", 10, &GlobalPlanner::callbackGetVehicleStatus, this); + else if(bVelSource == 2) + sub_can_info = nh.subscribe("/can_info", 10, &GlobalPlanner::callbackGetCANInfo, this); + + if(m_params.bEnableDynamicMapUpdate) + sub_road_status_occupancy = nh.subscribe<>("/occupancy_road_status", 1, &GlobalPlanner::callbackGetRoadStatusOccupancyGrid, this); + + //Mapping Section + sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &GlobalPlanner::callbackGetVMLanes, this); + sub_points = nh.subscribe("/vector_map_info/point", 1, &GlobalPlanner::callbackGetVMPoints, this); + sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &GlobalPlanner::callbackGetVMdtLanes, this); + sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &GlobalPlanner::callbackGetVMIntersections, this); + sup_area = nh.subscribe("/vector_map_info/area", 1, &GlobalPlanner::callbackGetVMAreas, this); + sub_lines = nh.subscribe("/vector_map_info/line", 1, &GlobalPlanner::callbackGetVMLines, this); + sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &GlobalPlanner::callbackGetVMStopLines, this); + sub_signals = nh.subscribe("/vector_map_info/signal", 1, &GlobalPlanner::callbackGetVMSignal, this); + sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &GlobalPlanner::callbackGetVMVectors, this); + sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &GlobalPlanner::callbackGetVMCurbs, this); + sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &GlobalPlanner::callbackGetVMRoadEdges, this); + sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &GlobalPlanner::callbackGetVMWayAreas, this); + sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &GlobalPlanner::callbackGetVMCrossWalks, this); + sub_nodes = nh.subscribe("/vector_map_info/node", 1, &GlobalPlanner::callbackGetVMNodes, this); } GlobalPlanner::~GlobalPlanner() { - if(m_params.bEnableRvizInput) - SaveSimulationData(); + if(m_params.bEnableRvizInput) + SaveSimulationData(); } void GlobalPlanner::callbackGetRoadStatusOccupancyGrid(const nav_msgs::OccupancyGridConstPtr& msg) { -// std::cout << "Occupancy Grid Origin (" << msg->info.origin.position.x << ", " << msg->info.origin.position.x << ") , " << msg->header.frame_id << ", Res: " << msg->info.resolution << std::endl; - - m_GridMapIntType.clear(); - - //std::cout << "Found Map Data: Zero " << std::endl; - for(unsigned int i=0; i < msg->data.size(); i++) - { - if((int8_t)msg->data.at(i) == 0) - m_GridMapIntType.push_back(0); - else if((int8_t)msg->data.at(i) == 50) - m_GridMapIntType.push_back(75); - else if((int8_t)msg->data.at(i) == 100) - m_GridMapIntType.push_back(255); - else - m_GridMapIntType.push_back(128); - - //std::cout << msg->data.at(i) << ","; - } - //std::cout << std::endl << "--------------------------------------------------------" << std::endl; - - //std::cout << "Found Map Data: Zero : " << m_GridMapIntType.size() << std::endl; - PlannerHNS::WayPoint center(msg->info.origin.position.x, msg->info.origin.position.y, msg->info.origin.position.z, tf::getYaw(msg->info.origin.orientation)); - PlannerHNS::OccupancyToGridMap grid(msg->info.width,msg->info.height, msg->info.resolution, center); - std::vector modified_nodes; - timespec t; - UtilityHNS::UtilityH::GetTickCount(t); - PlannerHNS::MappingHelpers::UpdateMapWithOccupancyGrid(grid, m_GridMapIntType, m_Map, modified_nodes); - m_ModifiedMapItemsTimes.push_back(std::make_pair(modified_nodes, t)); - - visualization_msgs::MarkerArray map_marker_array; - PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - -// visualization_msgs::Marker mkr = PlannerHNS::ROSHelpers::CreateGenMarker(center.pos.x, center.pos.y, center.pos.z, 0, 0,0,1,0.5, 1000, "TestCenter", visualization_msgs::Marker::SPHERE); +// std::cout << "Occupancy Grid Origin (" << msg->info.origin.position.x << ", " << msg->info.origin.position.x << ") , " << msg->header.frame_id << ", Res: " << msg->info.resolution << std::endl; + + m_GridMapIntType.clear(); + + //std::cout << "Found Map Data: Zero " << std::endl; + for(unsigned int i=0; i < msg->data.size(); i++) + { + if((int8_t)msg->data.at(i) == 0) + m_GridMapIntType.push_back(0); + else if((int8_t)msg->data.at(i) == 50) + m_GridMapIntType.push_back(75); + else if((int8_t)msg->data.at(i) == 100) + m_GridMapIntType.push_back(255); + else + m_GridMapIntType.push_back(128); + + //std::cout << msg->data.at(i) << ","; + } + //std::cout << std::endl << "--------------------------------------------------------" << std::endl; + + //std::cout << "Found Map Data: Zero : " << m_GridMapIntType.size() << std::endl; + PlannerHNS::WayPoint center(msg->info.origin.position.x, msg->info.origin.position.y, msg->info.origin.position.z, tf::getYaw(msg->info.origin.orientation)); + PlannerHNS::OccupancyToGridMap grid(msg->info.width,msg->info.height, msg->info.resolution, center); + std::vector modified_nodes; + timespec t; + UtilityHNS::UtilityH::GetTickCount(t); + PlannerHNS::MappingHelpers::UpdateMapWithOccupancyGrid(grid, m_GridMapIntType, m_Map, modified_nodes); + m_ModifiedMapItemsTimes.push_back(std::make_pair(modified_nodes, t)); + + visualization_msgs::MarkerArray map_marker_array; + PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + +// visualization_msgs::Marker mkr = PlannerHNS::ROSHelpers::CreateGenMarker(center.pos.x, center.pos.y, center.pos.z, 0, 0,0,1,0.5, 1000, "TestCenter", visualization_msgs::Marker::SPHERE); // -// map_marker_array.markers.push_back(mkr); +// map_marker_array.markers.push_back(mkr); - pub_MapRviz.publish(map_marker_array); + pub_MapRviz.publish(map_marker_array); } void GlobalPlanner::ClearOldCostFromMap() { - for(int i=0; i < (int)m_ModifiedMapItemsTimes.size(); i++) - { - if(UtilityHNS::UtilityH::GetTimeDiffNow(m_ModifiedMapItemsTimes.at(i).second) > CLEAR_COSTS_TIME) - { - for(unsigned int j= 0 ; j < m_ModifiedMapItemsTimes.at(i).first.size(); j++) - { - for(unsigned int i_action=0; i_action < m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.size(); i_action++) - { - if(m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.at(i_action).first == PlannerHNS::FORWARD_ACTION) - { - m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.at(i_action).second = 0; - } - } - } - - m_ModifiedMapItemsTimes.erase(m_ModifiedMapItemsTimes.begin()+i); - i--; - } - } + for(int i=0; i < (int)m_ModifiedMapItemsTimes.size(); i++) + { + if(UtilityHNS::UtilityH::GetTimeDiffNow(m_ModifiedMapItemsTimes.at(i).second) > CLEAR_COSTS_TIME) + { + for(unsigned int j= 0 ; j < m_ModifiedMapItemsTimes.at(i).first.size(); j++) + { + for(unsigned int i_action=0; i_action < m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.size(); i_action++) + { + if(m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.at(i_action).first == PlannerHNS::FORWARD_ACTION) + { + m_ModifiedMapItemsTimes.at(i).first.at(j)->actionCost.at(i_action).second = 0; + } + } + } + + m_ModifiedMapItemsTimes.erase(m_ModifiedMapItemsTimes.begin()+i); + i--; + } + } } void GlobalPlanner::callbackGetGoalPose(const geometry_msgs::PoseStampedConstPtr &msg) { - PlannerHNS::WayPoint wp = PlannerHNS::WayPoint(msg->pose.position.x+m_OriginPos.position.x, msg->pose.position.y+m_OriginPos.position.y, msg->pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.orientation)); - m_GoalsPos.push_back(wp); - ROS_INFO("Received Goal Pose"); + PlannerHNS::WayPoint wp = PlannerHNS::WayPoint(msg->pose.position.x+m_OriginPos.position.x, msg->pose.position.y+m_OriginPos.position.y, msg->pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.orientation)); + m_GoalsPos.push_back(wp); + ROS_INFO("Received Goal Pose"); } void GlobalPlanner::callbackGetStartPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg) { - m_CurrentPose = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, msg->pose.pose.position.y+m_OriginPos.position.y, msg->pose.pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.pose.orientation)); - ROS_INFO("Received Start pose"); + m_CurrentPose = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, msg->pose.pose.position.y+m_OriginPos.position.y, msg->pose.pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.pose.orientation)); + ROS_INFO("Received Start pose"); } void GlobalPlanner::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPose = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + m_CurrentPose = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); } void GlobalPlanner::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleState.speed = msg->twist.twist.linear.x; - m_CurrentPose.v = m_VehicleState.speed; - if(fabs(msg->twist.twist.linear.x) > 0.25) - m_VehicleState.steer += atan(2.7 * msg->twist.twist.angular.z/msg->twist.twist.linear.x); + m_VehicleState.speed = msg->twist.twist.linear.x; + m_CurrentPose.v = m_VehicleState.speed; + if(fabs(msg->twist.twist.linear.x) > 0.25) + m_VehicleState.steer += atan(2.7 * msg->twist.twist.angular.z/msg->twist.twist.linear.x); } void GlobalPlanner::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleState.speed = msg->twist.linear.x; - m_CurrentPose.v = m_VehicleState.speed; - if(fabs(msg->twist.linear.x) > 0.25) - m_VehicleState.steer = atan(2.7 * msg->twist.angular.z/msg->twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); + m_VehicleState.speed = msg->twist.linear.x; + m_CurrentPose.v = m_VehicleState.speed; + if(fabs(msg->twist.linear.x) > 0.25) + m_VehicleState.steer = atan(2.7 * msg->twist.angular.z/msg->twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); } void GlobalPlanner::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleState.speed = msg->speed/3.6; - m_CurrentPose.v = m_VehicleState.speed; - m_VehicleState.steer = msg->angle * 0.45 / 660; - UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); + m_VehicleState.speed = msg->speed/3.6; + m_CurrentPose.v = m_VehicleState.speed; + m_VehicleState.steer = msg->angle * 0.45 / 660; + UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); } bool GlobalPlanner::GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, std::vector >& generatedTotalPaths) { - std::vector predefinedLanesIds; - double ret = 0; - - ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, MAX_GLOBAL_PLAN_DISTANCE, m_params.bEnableLaneChange, predefinedLanesIds, m_Map, generatedTotalPaths); - - if(ret == 0) - { - std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() - << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; - return false; - } - - - if(generatedTotalPaths.size() > 0 && generatedTotalPaths.at(0).size()>0) - { - if(m_params.bEnableSmoothing) - { - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - PlannerHNS::PlanningHelpers::FixPathDensity(generatedTotalPaths.at(i), m_params.pathDensity); - PlannerHNS::PlanningHelpers::SmoothPath(generatedTotalPaths.at(i), 0.49, 0.35 , 0.01); - } - } - - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - PlannerHNS::PlanningHelpers::CalcAngleAndCost(generatedTotalPaths.at(i)); - if(m_GlobalPathID > 10000) - m_GlobalPathID = 1; - - for(unsigned int j=0; j < generatedTotalPaths.at(i).size(); j++) - generatedTotalPaths.at(i).at(j).gid = m_GlobalPathID; - - m_GlobalPathID++; - - std::cout << "New DP Path -> " << generatedTotalPaths.at(i).size() << std::endl; - } - return true; - } - else - { - std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; - } - return false; + std::vector predefinedLanesIds; + double ret = 0; + + ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, MAX_GLOBAL_PLAN_DISTANCE, m_params.bEnableLaneChange, predefinedLanesIds, m_Map, generatedTotalPaths); + + if(ret == 0) + { + std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() + << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; + return false; + } + + + if(generatedTotalPaths.size() > 0 && generatedTotalPaths.at(0).size()>0) + { + if(m_params.bEnableSmoothing) + { + for(unsigned int i=0; i < generatedTotalPaths.size(); i++) + { + PlannerHNS::PlanningHelpers::FixPathDensity(generatedTotalPaths.at(i), m_params.pathDensity); + PlannerHNS::PlanningHelpers::SmoothPath(generatedTotalPaths.at(i), 0.49, 0.35 , 0.01); + } + } + + for(unsigned int i=0; i < generatedTotalPaths.size(); i++) + { + PlannerHNS::PlanningHelpers::CalcAngleAndCost(generatedTotalPaths.at(i)); + if(m_GlobalPathID > 10000) + m_GlobalPathID = 1; + + for(unsigned int j=0; j < generatedTotalPaths.at(i).size(); j++) + generatedTotalPaths.at(i).at(j).gid = m_GlobalPathID; + + m_GlobalPathID++; + + std::cout << "New DP Path -> " << generatedTotalPaths.at(i).size() << std::endl; + } + return true; + } + else + { + std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; + } + return false; } void GlobalPlanner::VisualizeAndSend(const std::vector > generatedTotalPaths) { - autoware_msgs::LaneArray lane_array; - visualization_msgs::MarkerArray pathsToVisualize; - - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - autoware_msgs::Lane lane; - PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(generatedTotalPaths.at(i), lane); - lane_array.lanes.push_back(lane); - } - - std_msgs::ColorRGBA total_color; - total_color.r = 0; - total_color.g = 0.7; - total_color.b = 1.0; - total_color.a = 0.9; - PlannerHNS::ROSHelpers::createGlobalLaneArrayMarker(total_color, lane_array, pathsToVisualize); - PlannerHNS::ROSHelpers::createGlobalLaneArrayOrientationMarker(lane_array, pathsToVisualize); - PlannerHNS::ROSHelpers::createGlobalLaneArrayVelocityMarker(lane_array, pathsToVisualize); - pub_PathsRviz.publish(pathsToVisualize); - if((m_bFirstStart && m_params.bEnableHMI) || !m_params.bEnableHMI) - pub_Paths.publish(lane_array); - - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - std::ostringstream str_out; - str_out << UtilityHNS::UtilityH::GetHomeDirectory(); - str_out << UtilityHNS::DataRW::LoggingMainfolderName; - str_out << UtilityHNS::DataRW::GlobalPathLogFolderName; - str_out << "GlobalPath_"; - str_out << i; - str_out << "_"; - PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), generatedTotalPaths.at(i)); - } + autoware_msgs::LaneArray lane_array; + visualization_msgs::MarkerArray pathsToVisualize; + + for(unsigned int i=0; i < generatedTotalPaths.size(); i++) + { + autoware_msgs::Lane lane; + PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(generatedTotalPaths.at(i), lane); + lane_array.lanes.push_back(lane); + } + + std_msgs::ColorRGBA total_color; + total_color.r = 0; + total_color.g = 0.7; + total_color.b = 1.0; + total_color.a = 0.9; + PlannerHNS::ROSHelpers::createGlobalLaneArrayMarker(total_color, lane_array, pathsToVisualize); + PlannerHNS::ROSHelpers::createGlobalLaneArrayOrientationMarker(lane_array, pathsToVisualize); + PlannerHNS::ROSHelpers::createGlobalLaneArrayVelocityMarker(lane_array, pathsToVisualize); + pub_PathsRviz.publish(pathsToVisualize); + if((m_bFirstStart && m_params.bEnableHMI) || !m_params.bEnableHMI) + pub_Paths.publish(lane_array); + + for(unsigned int i=0; i < generatedTotalPaths.size(); i++) + { + std::ostringstream str_out; + str_out << UtilityHNS::UtilityH::GetHomeDirectory(); + str_out << UtilityHNS::DataRW::LoggingMainfolderName; + str_out << UtilityHNS::DataRW::GlobalPathLogFolderName; + str_out << "GlobalPath_"; + str_out << i; + str_out << "_"; + PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), generatedTotalPaths.at(i)); + } } void GlobalPlanner::VisualizeDestinations(std::vector& destinations, const int& iSelected) { - visualization_msgs::MarkerArray goals_array; - - for(unsigned int i=0; i< destinations.size(); i++) - { - visualization_msgs::Marker marker; - marker.header.frame_id = "map"; - marker.header.stamp = ros::Time(); - marker.ns = "HMI_Destinations"; - marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; - marker.action = visualization_msgs::Marker::ADD; - marker.scale.x = 3.25; - marker.scale.y = 3.25; - marker.scale.z = 3.25; - marker.color.a = 0.9; - marker.id = i; - if(i == iSelected) - { - marker.color.r = 1; - marker.color.g = 0; - marker.color.b = 0; - } - else - { - marker.color.r = 0.2; - marker.color.g = 0.8; - marker.color.b = 0.2; - } - marker.pose.position.x = destinations.at(i).pos.x; - marker.pose.position.y = destinations.at(i).pos.y; - marker.pose.position.z = destinations.at(i).pos.z; - marker.pose.orientation = tf::createQuaternionMsgFromYaw(destinations.at(i).pos.a); - - std::ostringstream str_out; - str_out << "G"; - marker.text = str_out.str(); - - goals_array.markers.push_back(marker); - } - pub_GoalsListRviz.publish(goals_array); + visualization_msgs::MarkerArray goals_array; + + for(unsigned int i=0; i< destinations.size(); i++) + { + visualization_msgs::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = ros::Time(); + marker.ns = "HMI_Destinations"; + marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; + marker.action = visualization_msgs::Marker::ADD; + marker.scale.x = 3.25; + marker.scale.y = 3.25; + marker.scale.z = 3.25; + marker.color.a = 0.9; + marker.id = i; + if(i == iSelected) + { + marker.color.r = 1; + marker.color.g = 0; + marker.color.b = 0; + } + else + { + marker.color.r = 0.2; + marker.color.g = 0.8; + marker.color.b = 0.2; + } + marker.pose.position.x = destinations.at(i).pos.x; + marker.pose.position.y = destinations.at(i).pos.y; + marker.pose.position.z = destinations.at(i).pos.z; + marker.pose.orientation = tf::createQuaternionMsgFromYaw(destinations.at(i).pos.a); + + std::ostringstream str_out; + str_out << "G"; + marker.text = str_out.str(); + + goals_array.markers.push_back(marker); + } + pub_GoalsListRviz.publish(goals_array); } void GlobalPlanner::SaveSimulationData() { - std::vector simulationDataPoints; - std::ostringstream startStr; - startStr << m_CurrentPose.pos.x << "," << m_CurrentPose.pos.y << "," << m_CurrentPose.pos.z << "," << m_CurrentPose.pos.a << ","<< m_CurrentPose.cost << "," << 0 << ","; - simulationDataPoints.push_back(startStr.str()); - - for(unsigned int i=0; i < m_GoalsPos.size(); i++) - { - std::ostringstream goalStr; - goalStr << m_GoalsPos.at(i).pos.x << "," << m_GoalsPos.at(i).pos.y << "," << m_GoalsPos.at(i).pos.z << "," << m_GoalsPos.at(i).pos.a << "," << 0 << "," << 0 << ",destination_" << i+1 << ","; - simulationDataPoints.push_back(goalStr.str()); - } - - std::string header = "X,Y,Z,A,C,V,name,"; - - std::ostringstream fileName; - fileName << UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::SimulationFolderName; - fileName << "EgoCar.csv"; - std::ofstream f(fileName.str().c_str()); - - if(f.is_open()) - { - if(header.size() > 0) - f << header << "\r\n"; - for(unsigned int i = 0 ; i < simulationDataPoints.size(); i++) - f << simulationDataPoints.at(i) << "\r\n"; - } - - f.close(); + std::vector simulationDataPoints; + std::ostringstream startStr; + startStr << m_CurrentPose.pos.x << "," << m_CurrentPose.pos.y << "," << m_CurrentPose.pos.z << "," << m_CurrentPose.pos.a << ","<< m_CurrentPose.cost << "," << 0 << ","; + simulationDataPoints.push_back(startStr.str()); + + for(unsigned int i=0; i < m_GoalsPos.size(); i++) + { + std::ostringstream goalStr; + goalStr << m_GoalsPos.at(i).pos.x << "," << m_GoalsPos.at(i).pos.y << "," << m_GoalsPos.at(i).pos.z << "," << m_GoalsPos.at(i).pos.a << "," << 0 << "," << 0 << ",destination_" << i+1 << ","; + simulationDataPoints.push_back(goalStr.str()); + } + + std::string header = "X,Y,Z,A,C,V,name,"; + + std::ostringstream fileName; + fileName << UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::SimulationFolderName; + fileName << "EgoCar.csv"; + std::ofstream f(fileName.str().c_str()); + + if(f.is_open()) + { + if(header.size() > 0) + f << header << "\r\n"; + for(unsigned int i = 0 ; i < simulationDataPoints.size(); i++) + f << simulationDataPoints.at(i) << "\r\n"; + } + + f.close(); } int GlobalPlanner::LoadSimulationData() { - std::ostringstream fileName; - fileName << "EgoCar.csv"; + std::ostringstream fileName; + fileName << "EgoCar.csv"; - std::string simuDataFileName = UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::SimulationFolderName + fileName.str(); - UtilityHNS::SimulationFileReader sfr(simuDataFileName); - UtilityHNS::SimulationFileReader::SimulationData data; + std::string simuDataFileName = UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::SimulationFolderName + fileName.str(); + UtilityHNS::SimulationFileReader sfr(simuDataFileName); + UtilityHNS::SimulationFileReader::SimulationData data; - int nData = sfr.ReadAllData(data); - if(nData == 0) - return 0; + int nData = sfr.ReadAllData(data); + if(nData == 0) + return 0; - m_CurrentPose = PlannerHNS::WayPoint(data.startPoint.x, data.startPoint.y, data.startPoint.z, data.startPoint.a); - m_GoalsPos.push_back(PlannerHNS::WayPoint(data.goalPoint.x, data.goalPoint.y, data.goalPoint.z, data.goalPoint.a)); + m_CurrentPose = PlannerHNS::WayPoint(data.startPoint.x, data.startPoint.y, data.startPoint.z, data.startPoint.a); + m_GoalsPos.push_back(PlannerHNS::WayPoint(data.goalPoint.x, data.goalPoint.y, data.goalPoint.z, data.goalPoint.a)); - for(unsigned int i=0; i < data.simuCars.size(); i++) - { - m_GoalsPos.push_back(PlannerHNS::WayPoint(data.simuCars.at(i).x, data.simuCars.at(i).y, data.simuCars.at(i).z, data.simuCars.at(i).a)); - } + for(unsigned int i=0; i < data.simuCars.size(); i++) + { + m_GoalsPos.push_back(PlannerHNS::WayPoint(data.simuCars.at(i).x, data.simuCars.at(i).y, data.simuCars.at(i).z, data.simuCars.at(i).a)); + } - return nData; + return nData; } void GlobalPlanner::MainLoop() { - ros::Rate loop_rate(25); - timespec animation_timer; - UtilityHNS::UtilityH::GetTickCount(animation_timer); - - while (ros::ok()) - { - ros::spinOnce(); - bool bMakeNewPlan = false; - - if(m_params.mapSource == PlannerHNS::MAP_KML_FILE && !m_bKmlMap) - { - m_bKmlMap = true; - PlannerHNS::MappingHelpers::LoadKML(m_params.KmlMapPath, m_Map); - visualization_msgs::MarkerArray map_marker_array; - PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - pub_MapRviz.publish(map_marker_array); - } - else if (m_params.mapSource == PlannerHNS::MAP_FOLDER && !m_bKmlMap) - { - m_bKmlMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_params.KmlMapPath, m_Map, true); - visualization_msgs::MarkerArray map_marker_array; - PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - - pub_MapRviz.publish(map_marker_array); - } - else if (m_params.mapSource == PlannerHNS::MAP_AUTOWARE && !m_bKmlMap) - { - std::vector conn_data;; - - if(m_MapRaw.GetVersion()==2) - { - std::cout << "Map Version 2" << endl; - m_bKmlMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, - m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_params.bEnableLaneChange, false); - } - else if(m_MapRaw.GetVersion()==1) - { - std::cout << "Map Version 1" << endl; - m_bKmlMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true, m_params.bEnableLaneChange, false); - } - - if(m_bKmlMap) - { - visualization_msgs::MarkerArray map_marker_array; - PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - pub_MapRviz.publish(map_marker_array); - } - } - - ClearOldCostFromMap(); - - if(m_GoalsPos.size() > 0) - { - if(m_GeneratedTotalPaths.size() > 0 && m_GeneratedTotalPaths.at(0).size() > 3) - { - if(m_params.bEnableReplanning) - { - PlannerHNS::RelativeInfo info; - bool ret = PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_GeneratedTotalPaths, m_CurrentPose, 0.75, info); - if(ret == true && info.iGlobalPath >= 0 && info.iGlobalPath < m_GeneratedTotalPaths.size() && info.iFront > 0 && info.iFront < m_GeneratedTotalPaths.at(info.iGlobalPath).size()) - { - double remaining_distance = m_GeneratedTotalPaths.at(info.iGlobalPath).at(m_GeneratedTotalPaths.at(info.iGlobalPath).size()-1).cost - (m_GeneratedTotalPaths.at(info.iGlobalPath).at(info.iFront).cost + info.to_front_distance); - if(remaining_distance <= REPLANNING_DISTANCE) - { - bMakeNewPlan = true; - if(m_GoalsPos.size() > 0) - m_iCurrentGoalIndex = (m_iCurrentGoalIndex + 1) % m_GoalsPos.size(); - std::cout << "Current Goal Index = " << m_iCurrentGoalIndex << std::endl << std::endl; - } - } - } - } - else - bMakeNewPlan = true; - - if(bMakeNewPlan || (m_params.bEnableDynamicMapUpdate && UtilityHNS::UtilityH::GetTimeDiffNow(m_ReplnningTimer) > REPLANNING_TIME)) - { - UtilityHNS::UtilityH::GetTickCount(m_ReplnningTimer); - PlannerHNS::WayPoint goalPoint = m_GoalsPos.at(m_iCurrentGoalIndex); - bool bNewPlan = GenerateGlobalPlan(m_CurrentPose, goalPoint, m_GeneratedTotalPaths); - - - if(bNewPlan) - { - bMakeNewPlan = false; - VisualizeAndSend(m_GeneratedTotalPaths); - } - } - VisualizeDestinations(m_GoalsPos, m_iCurrentGoalIndex); - } - - loop_rate.sleep(); - } + ros::Rate loop_rate(25); + timespec animation_timer; + UtilityHNS::UtilityH::GetTickCount(animation_timer); + + while (ros::ok()) + { + ros::spinOnce(); + bool bMakeNewPlan = false; + + if(m_params.mapSource == PlannerHNS::MAP_KML_FILE && !m_bKmlMap) + { + m_bKmlMap = true; + PlannerHNS::MappingHelpers::LoadKML(m_params.KmlMapPath, m_Map); + visualization_msgs::MarkerArray map_marker_array; + PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + pub_MapRviz.publish(map_marker_array); + } + else if (m_params.mapSource == PlannerHNS::MAP_FOLDER && !m_bKmlMap) + { + m_bKmlMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_params.KmlMapPath, m_Map, true); + visualization_msgs::MarkerArray map_marker_array; + PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + + pub_MapRviz.publish(map_marker_array); + } + else if (m_params.mapSource == PlannerHNS::MAP_AUTOWARE && !m_bKmlMap) + { + std::vector conn_data;; + + if(m_MapRaw.GetVersion()==2) + { + std::cout << "Map Version 2" << endl; + m_bKmlMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, + m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_params.bEnableLaneChange, false); + } + else if(m_MapRaw.GetVersion()==1) + { + std::cout << "Map Version 1" << endl; + m_bKmlMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true, m_params.bEnableLaneChange, false); + } + + if(m_bKmlMap) + { + visualization_msgs::MarkerArray map_marker_array; + PlannerHNS::ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + pub_MapRviz.publish(map_marker_array); + } + } + + ClearOldCostFromMap(); + + if(m_GoalsPos.size() > 0) + { + if(m_GeneratedTotalPaths.size() > 0 && m_GeneratedTotalPaths.at(0).size() > 3) + { + if(m_params.bEnableReplanning) + { + PlannerHNS::RelativeInfo info; + bool ret = PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_GeneratedTotalPaths, m_CurrentPose, 0.75, info); + if(ret == true && info.iGlobalPath >= 0 && info.iGlobalPath < m_GeneratedTotalPaths.size() && info.iFront > 0 && info.iFront < m_GeneratedTotalPaths.at(info.iGlobalPath).size()) + { + double remaining_distance = m_GeneratedTotalPaths.at(info.iGlobalPath).at(m_GeneratedTotalPaths.at(info.iGlobalPath).size()-1).cost - (m_GeneratedTotalPaths.at(info.iGlobalPath).at(info.iFront).cost + info.to_front_distance); + if(remaining_distance <= REPLANNING_DISTANCE) + { + bMakeNewPlan = true; + if(m_GoalsPos.size() > 0) + m_iCurrentGoalIndex = (m_iCurrentGoalIndex + 1) % m_GoalsPos.size(); + std::cout << "Current Goal Index = " << m_iCurrentGoalIndex << std::endl << std::endl; + } + } + } + } + else + bMakeNewPlan = true; + + if(bMakeNewPlan || (m_params.bEnableDynamicMapUpdate && UtilityHNS::UtilityH::GetTimeDiffNow(m_ReplnningTimer) > REPLANNING_TIME)) + { + UtilityHNS::UtilityH::GetTickCount(m_ReplnningTimer); + PlannerHNS::WayPoint goalPoint = m_GoalsPos.at(m_iCurrentGoalIndex); + bool bNewPlan = GenerateGlobalPlan(m_CurrentPose, goalPoint, m_GeneratedTotalPaths); + + + if(bNewPlan) + { + bMakeNewPlan = false; + VisualizeAndSend(m_GeneratedTotalPaths); + } + } + VisualizeDestinations(m_GoalsPos, m_iCurrentGoalIndex); + } + + loop_rate.sleep(); + } } @@ -509,100 +509,100 @@ void GlobalPlanner::MainLoop() void GlobalPlanner::callbackGetVMLanes(const vector_map_msgs::LaneArray& msg) { - std::cout << "Received Lanes" << msg.data.size() << endl; - if(m_MapRaw.pLanes == nullptr) - m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); + std::cout << "Received Lanes" << msg.data.size() << endl; + if(m_MapRaw.pLanes == nullptr) + m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); } void GlobalPlanner::callbackGetVMPoints(const vector_map_msgs::PointArray& msg) { - std::cout << "Received Points" << msg.data.size() << endl; - if(m_MapRaw.pPoints == nullptr) - m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); + std::cout << "Received Points" << msg.data.size() << endl; + if(m_MapRaw.pPoints == nullptr) + m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); } void GlobalPlanner::callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg) { - std::cout << "Received dtLanes" << msg.data.size() << endl; - if(m_MapRaw.pCenterLines == nullptr) - m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); + std::cout << "Received dtLanes" << msg.data.size() << endl; + if(m_MapRaw.pCenterLines == nullptr) + m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); } void GlobalPlanner::callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg) { - std::cout << "Received CrossRoads" << msg.data.size() << endl; - if(m_MapRaw.pIntersections == nullptr) - m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); + std::cout << "Received CrossRoads" << msg.data.size() << endl; + if(m_MapRaw.pIntersections == nullptr) + m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); } void GlobalPlanner::callbackGetVMAreas(const vector_map_msgs::AreaArray& msg) { - std::cout << "Received Areas" << msg.data.size() << endl; - if(m_MapRaw.pAreas == nullptr) - m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); + std::cout << "Received Areas" << msg.data.size() << endl; + if(m_MapRaw.pAreas == nullptr) + m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); } void GlobalPlanner::callbackGetVMLines(const vector_map_msgs::LineArray& msg) { - std::cout << "Received Lines" << msg.data.size() << endl; - if(m_MapRaw.pLines == nullptr) - m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); + std::cout << "Received Lines" << msg.data.size() << endl; + if(m_MapRaw.pLines == nullptr) + m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); } void GlobalPlanner::callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg) { - std::cout << "Received StopLines" << msg.data.size() << endl; - if(m_MapRaw.pStopLines == nullptr) - m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); + std::cout << "Received StopLines" << msg.data.size() << endl; + if(m_MapRaw.pStopLines == nullptr) + m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); } void GlobalPlanner::callbackGetVMSignal(const vector_map_msgs::SignalArray& msg) { - std::cout << "Received Signals" << msg.data.size() << endl; - if(m_MapRaw.pSignals == nullptr) - m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); + std::cout << "Received Signals" << msg.data.size() << endl; + if(m_MapRaw.pSignals == nullptr) + m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); } void GlobalPlanner::callbackGetVMVectors(const vector_map_msgs::VectorArray& msg) { - std::cout << "Received Vectors" << msg.data.size() << endl; - if(m_MapRaw.pVectors == nullptr) - m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); + std::cout << "Received Vectors" << msg.data.size() << endl; + if(m_MapRaw.pVectors == nullptr) + m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); } void GlobalPlanner::callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg) { - std::cout << "Received Curbs" << msg.data.size() << endl; - if(m_MapRaw.pCurbs == nullptr) - m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); + std::cout << "Received Curbs" << msg.data.size() << endl; + if(m_MapRaw.pCurbs == nullptr) + m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); } void GlobalPlanner::callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg) { - std::cout << "Received Edges" << msg.data.size() << endl; - if(m_MapRaw.pRoadedges == nullptr) - m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); + std::cout << "Received Edges" << msg.data.size() << endl; + if(m_MapRaw.pRoadedges == nullptr) + m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); } void GlobalPlanner::callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg) { - std::cout << "Received Wayareas" << msg.data.size() << endl; - if(m_MapRaw.pWayAreas == nullptr) - m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); + std::cout << "Received Wayareas" << msg.data.size() << endl; + if(m_MapRaw.pWayAreas == nullptr) + m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); } void GlobalPlanner::callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg) { - std::cout << "Received CrossWalks" << msg.data.size() << endl; - if(m_MapRaw.pCrossWalks == nullptr) - m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); + std::cout << "Received CrossWalks" << msg.data.size() << endl; + if(m_MapRaw.pCrossWalks == nullptr) + m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); } void GlobalPlanner::callbackGetVMNodes(const vector_map_msgs::NodeArray& msg) { - std::cout << "Received Nodes" << msg.data.size() << endl; - if(m_MapRaw.pNodes == nullptr) - m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); + std::cout << "Received Nodes" << msg.data.size() << endl; + if(m_MapRaw.pNodes == nullptr) + m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); } } diff --git a/core_planning/op_local_planner/CMakeLists.txt b/core_planning/op_local_planner/CMakeLists.txt index 346593894bd..e960862a563 100644 --- a/core_planning/op_local_planner/CMakeLists.txt +++ b/core_planning/op_local_planner/CMakeLists.txt @@ -24,16 +24,6 @@ find_package( catkin_package( INCLUDE_DIRS include - CATKIN_DEPENDS - autoware_can_msgs - geometry_msgs - libwaypoint_follower - map_file - op_planner - op_ros_helpers - op_simu - op_utility - roscpp ) include_directories( @@ -89,11 +79,11 @@ add_dependencies( install( TARGETS - op_common_params - op_trajectory_generator - op_trajectory_evaluator - op_behavior_selector - op_motion_predictor + op_common_params + op_trajectory_generator + op_trajectory_evaluator + op_behavior_selector + op_motion_predictor ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/core_planning/op_local_planner/include/op_behavior_selector_core.h b/core_planning/op_local_planner/include/op_behavior_selector_core.h index ed8c187246e..31fe116f203 100644 --- a/core_planning/op_local_planner/include/op_behavior_selector_core.h +++ b/core_planning/op_local_planner/include/op_behavior_selector_core.h @@ -58,92 +58,92 @@ class BehaviorGen { protected: //Planning Related variables - geometry_msgs::Pose m_OriginPos; - PlannerHNS::WayPoint m_CurrentPos; - bool bNewCurrentPos; - - PlannerHNS::VehicleState m_VehicleStatus; - bool bVehicleStatus; - - std::vector m_temp_path; - std::vector > m_GlobalPaths; - std::vector > m_GlobalPathsToUse; - bool bWayGlobalPath; - bool bWayGlobalPathLogs; - std::vector > m_RollOuts; - bool bRollOuts; - - PlannerHNS::MAP_SOURCE_TYPE m_MapType; - std::string m_MapPath; - - PlannerHNS::RoadNetwork m_Map; - bool bMap; - - PlannerHNS::TrajectoryCost m_TrajectoryBestCost; - bool bBestCost; - - PlannerHNS::DecisionMaker m_BehaviorGenerator; - PlannerHNS::BehaviorState m_CurrentBehavior; - - std::vector m_LogData; - - PlannerHNS::PlanningParams m_PlanningParams; - PlannerHNS::CAR_BASIC_INFO m_CarInfo; - - autoware_msgs::Lane m_CurrentTrajectoryToSend; - bool bNewLightStatus; - bool bNewLightSignal; - PlannerHNS::TrafficLightState m_CurrLightStatus; - std::vector m_CurrTrafficLight; - std::vector m_PrevTrafficLight; - - geometry_msgs::TwistStamped m_Twist_raw; - geometry_msgs::TwistStamped m_Twist_cmd; - autoware_msgs::ControlCommand m_Ctrl_cmd; - - //ROS messages (topics) - ros::NodeHandle nh; - - //define publishers - ros::Publisher pub_LocalPath; - ros::Publisher pub_LocalBasePath; - ros::Publisher pub_ClosestIndex; - ros::Publisher pub_BehaviorState; - ros::Publisher pub_SimuBoxPose; - ros::Publisher pub_SelectedPathRviz; - - // define subscribers. - ros::Subscriber sub_current_pose; - ros::Subscriber sub_current_velocity; - ros::Subscriber sub_robot_odom; - ros::Subscriber sub_can_info; - ros::Subscriber sub_GlobalPlannerPaths; - ros::Subscriber sub_LocalPlannerPaths; - ros::Subscriber sub_TrafficLightStatus; - ros::Subscriber sub_TrafficLightSignals; - ros::Subscriber sub_Trajectory_Cost; - ros::Publisher pub_BehaviorStateRviz; - - ros::Subscriber sub_twist_cmd; - ros::Subscriber sub_twist_raw; - ros::Subscriber sub_ctrl_cmd; - - // Callback function for subscriber. - void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); - void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); - void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); - void callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); - void callbackGetLocalTrajectoryCost(const autoware_msgs::LaneConstPtr& msg); - void callbackGetTrafficLightStatus(const autoware_msgs::TrafficLight & msg); - void callbackGetTrafficLightSignals(const autoware_msgs::Signals& msg); - - void callbackGetTwistCMD(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetTwistRaw(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCommandCMD(const autoware_msgs::ControlCommandConstPtr& msg); - - //Helper Functions + geometry_msgs::Pose m_OriginPos; + PlannerHNS::WayPoint m_CurrentPos; + bool bNewCurrentPos; + + PlannerHNS::VehicleState m_VehicleStatus; + bool bVehicleStatus; + + std::vector m_temp_path; + std::vector > m_GlobalPaths; + std::vector > m_GlobalPathsToUse; + bool bWayGlobalPath; + bool bWayGlobalPathLogs; + std::vector > m_RollOuts; + bool bRollOuts; + + PlannerHNS::MAP_SOURCE_TYPE m_MapType; + std::string m_MapPath; + + PlannerHNS::RoadNetwork m_Map; + bool bMap; + + PlannerHNS::TrajectoryCost m_TrajectoryBestCost; + bool bBestCost; + + PlannerHNS::DecisionMaker m_BehaviorGenerator; + PlannerHNS::BehaviorState m_CurrentBehavior; + + std::vector m_LogData; + + PlannerHNS::PlanningParams m_PlanningParams; + PlannerHNS::CAR_BASIC_INFO m_CarInfo; + + autoware_msgs::Lane m_CurrentTrajectoryToSend; + bool bNewLightStatus; + bool bNewLightSignal; + PlannerHNS::TrafficLightState m_CurrLightStatus; + std::vector m_CurrTrafficLight; + std::vector m_PrevTrafficLight; + + geometry_msgs::TwistStamped m_Twist_raw; + geometry_msgs::TwistStamped m_Twist_cmd; + autoware_msgs::ControlCommand m_Ctrl_cmd; + + //ROS messages (topics) + ros::NodeHandle nh; + + //define publishers + ros::Publisher pub_LocalPath; + ros::Publisher pub_LocalBasePath; + ros::Publisher pub_ClosestIndex; + ros::Publisher pub_BehaviorState; + ros::Publisher pub_SimuBoxPose; + ros::Publisher pub_SelectedPathRviz; + + // define subscribers. + ros::Subscriber sub_current_pose; + ros::Subscriber sub_current_velocity; + ros::Subscriber sub_robot_odom; + ros::Subscriber sub_can_info; + ros::Subscriber sub_GlobalPlannerPaths; + ros::Subscriber sub_LocalPlannerPaths; + ros::Subscriber sub_TrafficLightStatus; + ros::Subscriber sub_TrafficLightSignals; + ros::Subscriber sub_Trajectory_Cost; + ros::Publisher pub_BehaviorStateRviz; + + ros::Subscriber sub_twist_cmd; + ros::Subscriber sub_twist_raw; + ros::Subscriber sub_ctrl_cmd; + + // Callback function for subscriber. + void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); + void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); + void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); + void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); + void callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); + void callbackGetLocalTrajectoryCost(const autoware_msgs::LaneConstPtr& msg); + void callbackGetTrafficLightStatus(const autoware_msgs::TrafficLight & msg); + void callbackGetTrafficLightSignals(const autoware_msgs::Signals& msg); + + void callbackGetTwistCMD(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetTwistRaw(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCommandCMD(const autoware_msgs::ControlCommandConstPtr& msg); + + //Helper Functions void UpdatePlanningParams(ros::NodeHandle& _nh); void SendLocalPlanningTopics(); void VisualizeLocalPlanner(); @@ -154,40 +154,40 @@ class BehaviorGen ~BehaviorGen(); void MainLoop(); - //Mapping Section - - UtilityHNS::MapRaw m_MapRaw; - - ros::Subscriber sub_lanes; - ros::Subscriber sub_points; - ros::Subscriber sub_dt_lanes; - ros::Subscriber sub_intersect; - ros::Subscriber sup_area; - ros::Subscriber sub_lines; - ros::Subscriber sub_stop_line; - ros::Subscriber sub_signals; - ros::Subscriber sub_vectors; - ros::Subscriber sub_curbs; - ros::Subscriber sub_edges; - ros::Subscriber sub_way_areas; - ros::Subscriber sub_cross_walk; - ros::Subscriber sub_nodes; - - - void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); - void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); - void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); - void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); - void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); - void callbackGetVMLines(const vector_map_msgs::LineArray& msg); - void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); - void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); - void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); - void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); - void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); - void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); - void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); - void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); + //Mapping Section + + UtilityHNS::MapRaw m_MapRaw; + + ros::Subscriber sub_lanes; + ros::Subscriber sub_points; + ros::Subscriber sub_dt_lanes; + ros::Subscriber sub_intersect; + ros::Subscriber sup_area; + ros::Subscriber sub_lines; + ros::Subscriber sub_stop_line; + ros::Subscriber sub_signals; + ros::Subscriber sub_vectors; + ros::Subscriber sub_curbs; + ros::Subscriber sub_edges; + ros::Subscriber sub_way_areas; + ros::Subscriber sub_cross_walk; + ros::Subscriber sub_nodes; + + + void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); + void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); + void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); + void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); + void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); + void callbackGetVMLines(const vector_map_msgs::LineArray& msg); + void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); + void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); + void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); + void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); + void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); + void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); + void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); + void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); }; } diff --git a/core_planning/op_local_planner/include/op_motion_predictor_core.h b/core_planning/op_local_planner/include/op_motion_predictor_core.h index f792fa2268c..4fdd37d85b3 100644 --- a/core_planning/op_local_planner/include/op_motion_predictor_core.h +++ b/core_planning/op_local_planner/include/op_motion_predictor_core.h @@ -52,117 +52,117 @@ namespace MotionPredictorNS class MotionPrediction { protected: - PlannerHNS::WayPoint m_CurrentPos; - bool bNewCurrentPos; + PlannerHNS::WayPoint m_CurrentPos; + bool bNewCurrentPos; - PlannerHNS::VehicleState m_VehicleStatus; - bool bVehicleStatus; - bool m_bGoNextStep; + PlannerHNS::VehicleState m_VehicleStatus; + bool bVehicleStatus; + bool m_bGoNextStep; - geometry_msgs::Pose m_OriginPos; - PlannerHNS::CAR_BASIC_INFO m_CarInfo; - PlannerHNS::ControllerParams m_ControlParams; - PlannerHNS::PlanningParams m_PlanningParams; - PlannerHNS::MAP_SOURCE_TYPE m_MapType; - std::string m_MapPath; + geometry_msgs::Pose m_OriginPos; + PlannerHNS::CAR_BASIC_INFO m_CarInfo; + PlannerHNS::ControllerParams m_ControlParams; + PlannerHNS::PlanningParams m_PlanningParams; + PlannerHNS::MAP_SOURCE_TYPE m_MapType; + std::string m_MapPath; - std::vector m_TrackedObjects; - bool bTrackedObjects; + std::vector m_TrackedObjects; + bool bTrackedObjects; - PlannerHNS::RoadNetwork m_Map; - bool bMap; + PlannerHNS::RoadNetwork m_Map; + bool bMap; - bool m_bEnableCurbObstacles; - std::vector curr_curbs_obstacles; + bool m_bEnableCurbObstacles; + std::vector curr_curbs_obstacles; - PlannerHNS::BehaviorPrediction m_PredictBeh; - autoware_msgs::DetectedObjectArray m_PredictedResultsResults; + PlannerHNS::BehaviorPrediction m_PredictBeh; + autoware_msgs::DetectedObjectArray m_PredictedResultsResults; - timespec m_VisualizationTimer; - std::vector > m_all_pred_paths; - std::vector m_particles_points; + timespec m_VisualizationTimer; + std::vector > m_all_pred_paths; + std::vector m_particles_points; - visualization_msgs::MarkerArray m_PredictedTrajectoriesDummy; - visualization_msgs::MarkerArray m_PredictedTrajectoriesActual; + visualization_msgs::MarkerArray m_PredictedTrajectoriesDummy; + visualization_msgs::MarkerArray m_PredictedTrajectoriesActual; - visualization_msgs::MarkerArray m_PredictedParticlesDummy; - visualization_msgs::MarkerArray m_PredictedParticlesActual; + visualization_msgs::MarkerArray m_PredictedParticlesDummy; + visualization_msgs::MarkerArray m_PredictedParticlesActual; - visualization_msgs::MarkerArray m_CurbsDummy; - visualization_msgs::MarkerArray m_CurbsActual; + visualization_msgs::MarkerArray m_CurbsDummy; + visualization_msgs::MarkerArray m_CurbsActual; - double m_DistanceBetweenCurbs; - double m_VisualizationTime; + double m_DistanceBetweenCurbs; + double m_VisualizationTime; - timespec m_SensingTimer; + timespec m_SensingTimer; - ros::NodeHandle nh; - ros::Publisher pub_predicted_objects_trajectories; - ros::Publisher pub_PredictedTrajectoriesRviz ; - ros::Publisher pub_CurbsRviz ; - ros::Publisher pub_ParticlesRviz; + ros::NodeHandle nh; + ros::Publisher pub_predicted_objects_trajectories; + ros::Publisher pub_PredictedTrajectoriesRviz ; + ros::Publisher pub_CurbsRviz ; + ros::Publisher pub_ParticlesRviz; - // define subscribers. - ros::Subscriber sub_tracked_objects ; - ros::Subscriber sub_current_pose ; - ros::Subscriber sub_current_velocity ; - ros::Subscriber sub_robot_odom ; - ros::Subscriber sub_can_info ; - ros::Subscriber sub_StepSignal; + // define subscribers. + ros::Subscriber sub_tracked_objects ; + ros::Subscriber sub_current_pose ; + ros::Subscriber sub_current_velocity ; + ros::Subscriber sub_robot_odom ; + ros::Subscriber sub_can_info ; + ros::Subscriber sub_StepSignal; - // Callback function for subscriber. - void callbackGetTrackedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); - void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); - void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); - void callbackGetStepForwardSignals(const geometry_msgs::TwistStampedConstPtr& msg); + // Callback function for subscriber. + void callbackGetTrackedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); + void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); + void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); + void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); + void callbackGetStepForwardSignals(const geometry_msgs::TwistStampedConstPtr& msg); - //Helper functions - void VisualizePrediction(); - void UpdatePlanningParams(ros::NodeHandle& _nh); - void GenerateCurbsObstacles(std::vector& curb_obstacles); + //Helper functions + void VisualizePrediction(); + void UpdatePlanningParams(ros::NodeHandle& _nh); + void GenerateCurbsObstacles(std::vector& curb_obstacles); public: - MotionPrediction(); - virtual ~MotionPrediction(); - void MainLoop(); - - //Mapping Section - - UtilityHNS::MapRaw m_MapRaw; - - ros::Subscriber sub_lanes; - ros::Subscriber sub_points; - ros::Subscriber sub_dt_lanes; - ros::Subscriber sub_intersect; - ros::Subscriber sup_area; - ros::Subscriber sub_lines; - ros::Subscriber sub_stop_line; - ros::Subscriber sub_signals; - ros::Subscriber sub_vectors; - ros::Subscriber sub_curbs; - ros::Subscriber sub_edges; - ros::Subscriber sub_way_areas; - ros::Subscriber sub_cross_walk; - ros::Subscriber sub_nodes; - - - void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); - void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); - void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); - void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); - void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); - void callbackGetVMLines(const vector_map_msgs::LineArray& msg); - void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); - void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); - void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); - void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); - void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); - void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); - void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); - void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); + MotionPrediction(); + virtual ~MotionPrediction(); + void MainLoop(); + + //Mapping Section + + UtilityHNS::MapRaw m_MapRaw; + + ros::Subscriber sub_lanes; + ros::Subscriber sub_points; + ros::Subscriber sub_dt_lanes; + ros::Subscriber sub_intersect; + ros::Subscriber sup_area; + ros::Subscriber sub_lines; + ros::Subscriber sub_stop_line; + ros::Subscriber sub_signals; + ros::Subscriber sub_vectors; + ros::Subscriber sub_curbs; + ros::Subscriber sub_edges; + ros::Subscriber sub_way_areas; + ros::Subscriber sub_cross_walk; + ros::Subscriber sub_nodes; + + + void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); + void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); + void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg); + void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg); + void callbackGetVMAreas(const vector_map_msgs::AreaArray& msg); + void callbackGetVMLines(const vector_map_msgs::LineArray& msg); + void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); + void callbackGetVMSignal(const vector_map_msgs::SignalArray& msg); + void callbackGetVMVectors(const vector_map_msgs::VectorArray& msg); + void callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg); + void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg); + void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg); + void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg); + void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); }; } diff --git a/core_planning/op_local_planner/include/op_trajectory_evaluator_core.h b/core_planning/op_local_planner/include/op_trajectory_evaluator_core.h index cad197d7c2e..bd69777b298 100644 --- a/core_planning/op_local_planner/include/op_trajectory_evaluator_core.h +++ b/core_planning/op_local_planner/include/op_trajectory_evaluator_core.h @@ -39,76 +39,76 @@ class TrajectoryEval { protected: - PlannerHNS::TrajectoryDynamicCosts m_TrajectoryCostsCalculator; - bool m_bUseMoveingObjectsPrediction; + PlannerHNS::TrajectoryDynamicCosts m_TrajectoryCostsCalculator; + bool m_bUseMoveingObjectsPrediction; - geometry_msgs::Pose m_OriginPos; + geometry_msgs::Pose m_OriginPos; - PlannerHNS::WayPoint m_CurrentPos; - bool bNewCurrentPos; + PlannerHNS::WayPoint m_CurrentPos; + bool bNewCurrentPos; - PlannerHNS::VehicleState m_VehicleStatus; - bool bVehicleStatus; + PlannerHNS::VehicleState m_VehicleStatus; + bool bVehicleStatus; - std::vector m_temp_path; - std::vector > m_GlobalPaths; - std::vector > m_GlobalPathsToUse; - std::vector > m_GlobalPathSections; - std::vector t_centerTrajectorySmoothed; - bool bWayGlobalPath; - bool bWayGlobalPathToUse; - std::vector > m_GeneratedRollOuts; - bool bRollOuts; + std::vector m_temp_path; + std::vector > m_GlobalPaths; + std::vector > m_GlobalPathsToUse; + std::vector > m_GlobalPathSections; + std::vector t_centerTrajectorySmoothed; + bool bWayGlobalPath; + bool bWayGlobalPathToUse; + std::vector > m_GeneratedRollOuts; + bool bRollOuts; - std::vector m_PredictedObjects; - bool bPredictedObjects; + std::vector m_PredictedObjects; + bool bPredictedObjects; - struct timespec m_PlanningTimer; - std::vector m_LogData; + struct timespec m_PlanningTimer; + std::vector m_LogData; - PlannerHNS::PlanningParams m_PlanningParams; - PlannerHNS::CAR_BASIC_INFO m_CarInfo; + PlannerHNS::PlanningParams m_PlanningParams; + PlannerHNS::CAR_BASIC_INFO m_CarInfo; - PlannerHNS::BehaviorState m_CurrentBehavior; + PlannerHNS::BehaviorState m_CurrentBehavior; - visualization_msgs::MarkerArray m_CollisionsDummy; - visualization_msgs::MarkerArray m_CollisionsActual; + visualization_msgs::MarkerArray m_CollisionsDummy; + visualization_msgs::MarkerArray m_CollisionsActual; - //ROS messages (topics) - ros::NodeHandle nh; + //ROS messages (topics) + ros::NodeHandle nh; - //define publishers - ros::Publisher pub_CollisionPointsRviz; - ros::Publisher pub_LocalWeightedTrajectoriesRviz; - ros::Publisher pub_LocalWeightedTrajectories; - ros::Publisher pub_TrajectoryCost; - ros::Publisher pub_SafetyBorderRviz; + //define publishers + ros::Publisher pub_CollisionPointsRviz; + ros::Publisher pub_LocalWeightedTrajectoriesRviz; + ros::Publisher pub_LocalWeightedTrajectories; + ros::Publisher pub_TrajectoryCost; + ros::Publisher pub_SafetyBorderRviz; - // define subscribers. - ros::Subscriber sub_current_pose; - ros::Subscriber sub_current_velocity; - ros::Subscriber sub_robot_odom; - ros::Subscriber sub_can_info; - ros::Subscriber sub_GlobalPlannerPaths; - ros::Subscriber sub_LocalPlannerPaths; - ros::Subscriber sub_predicted_objects; - ros::Subscriber sub_current_behavior; + // define subscribers. + ros::Subscriber sub_current_pose; + ros::Subscriber sub_current_velocity; + ros::Subscriber sub_robot_odom; + ros::Subscriber sub_can_info; + ros::Subscriber sub_GlobalPlannerPaths; + ros::Subscriber sub_LocalPlannerPaths; + ros::Subscriber sub_predicted_objects; + ros::Subscriber sub_current_behavior; - // Callback function for subscriber. - void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); - void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); - void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); - void callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); - void callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); - void callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr & msg); + // Callback function for subscriber. + void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); + void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); + void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); + void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); + void callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); + void callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); + void callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr & msg); - //Helper Functions + //Helper Functions void UpdatePlanningParams(ros::NodeHandle& _nh); public: diff --git a/core_planning/op_local_planner/include/op_trajectory_generator_core.h b/core_planning/op_local_planner/include/op_trajectory_generator_core.h index 07bcc65a6c0..f7dddce11b6 100644 --- a/core_planning/op_local_planner/include/op_trajectory_generator_core.h +++ b/core_planning/op_local_planner/include/op_trajectory_generator_core.h @@ -36,58 +36,58 @@ namespace TrajectoryGeneratorNS class TrajectoryGen { protected: - PlannerHNS::PlannerH m_Planner; - geometry_msgs::Pose m_OriginPos; - PlannerHNS::WayPoint m_InitPos; - bool bInitPos; - - PlannerHNS::WayPoint m_CurrentPos; - bool bNewCurrentPos; - - PlannerHNS::VehicleState m_VehicleStatus; - bool bVehicleStatus; - - std::vector m_temp_path; - std::vector > m_GlobalPaths; - std::vector > m_GlobalPathSections; - std::vector t_centerTrajectorySmoothed; - std::vector > > m_RollOuts; - bool bWayGlobalPath; - struct timespec m_PlanningTimer; - std::vector m_LogData; - PlannerHNS::PlanningParams m_PlanningParams; - PlannerHNS::CAR_BASIC_INFO m_CarInfo; - - - //ROS messages (topics) - ros::NodeHandle nh; - - //define publishers - ros::Publisher pub_LocalTrajectories; - ros::Publisher pub_LocalTrajectoriesRviz; - - // define subscribers. - ros::Subscriber sub_initialpose; - ros::Subscriber sub_current_pose; - ros::Subscriber sub_current_velocity; - ros::Subscriber sub_robot_odom; - ros::Subscriber sub_can_info; - ros::Subscriber sub_GlobalPlannerPaths; - - - // Callback function for subscriber. - void callbackGetInitPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &input); - void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); - void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); - void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); - - //Helper Functions + PlannerHNS::PlannerH m_Planner; + geometry_msgs::Pose m_OriginPos; + PlannerHNS::WayPoint m_InitPos; + bool bInitPos; + + PlannerHNS::WayPoint m_CurrentPos; + bool bNewCurrentPos; + + PlannerHNS::VehicleState m_VehicleStatus; + bool bVehicleStatus; + + std::vector m_temp_path; + std::vector > m_GlobalPaths; + std::vector > m_GlobalPathSections; + std::vector t_centerTrajectorySmoothed; + std::vector > > m_RollOuts; + bool bWayGlobalPath; + struct timespec m_PlanningTimer; + std::vector m_LogData; + PlannerHNS::PlanningParams m_PlanningParams; + PlannerHNS::CAR_BASIC_INFO m_CarInfo; + + + //ROS messages (topics) + ros::NodeHandle nh; + + //define publishers + ros::Publisher pub_LocalTrajectories; + ros::Publisher pub_LocalTrajectoriesRviz; + + // define subscribers. + ros::Subscriber sub_initialpose; + ros::Subscriber sub_current_pose; + ros::Subscriber sub_current_velocity; + ros::Subscriber sub_robot_odom; + ros::Subscriber sub_can_info; + ros::Subscriber sub_GlobalPlannerPaths; + + + // Callback function for subscriber. + void callbackGetInitPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &input); + void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); + void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); + void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); + void callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg); + + //Helper Functions void UpdatePlanningParams(ros::NodeHandle& _nh); public: - TrajectoryGen(); + TrajectoryGen(); ~TrajectoryGen(); void MainLoop(); }; diff --git a/core_planning/op_local_planner/launch/op_behavior_selector.launch b/core_planning/op_local_planner/launch/op_behavior_selector.launch index 0bcd64d5228..02e955d522d 100644 --- a/core_planning/op_local_planner/launch/op_behavior_selector.launch +++ b/core_planning/op_local_planner/launch/op_behavior_selector.launch @@ -1,12 +1,12 @@ - - - - - - - - - - + + + + + + + + + + diff --git a/core_planning/op_local_planner/launch/op_common_params.launch b/core_planning/op_local_planner/launch/op_common_params.launch index ebc7efdc5b5..23c59b0574c 100644 --- a/core_planning/op_local_planner/launch/op_common_params.launch +++ b/core_planning/op_local_planner/launch/op_common_params.launch @@ -1,102 +1,102 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + diff --git a/core_planning/op_local_planner/launch/op_motion_predictor.launch b/core_planning/op_local_planner/launch/op_motion_predictor.launch index 9abe1d2808c..9ecb8393e82 100644 --- a/core_planning/op_local_planner/launch/op_motion_predictor.launch +++ b/core_planning/op_local_planner/launch/op_motion_predictor.launch @@ -1,26 +1,26 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/core_planning/op_local_planner/launch/op_trajectory_evaluator.launch b/core_planning/op_local_planner/launch/op_trajectory_evaluator.launch index b2f9ba4f116..5c07a563ba8 100644 --- a/core_planning/op_local_planner/launch/op_trajectory_evaluator.launch +++ b/core_planning/op_local_planner/launch/op_trajectory_evaluator.launch @@ -1,16 +1,16 @@ - - - - - - - - - - - - - - + + + + + + + + + + + + + + diff --git a/core_planning/op_local_planner/launch/op_trajectory_generator.launch b/core_planning/op_local_planner/launch/op_trajectory_generator.launch index aedd58bdf43..00d0ee9ece7 100644 --- a/core_planning/op_local_planner/launch/op_trajectory_generator.launch +++ b/core_planning/op_local_planner/launch/op_trajectory_generator.launch @@ -1,17 +1,17 @@ - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + diff --git a/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector.cpp b/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector.cpp index f791c74ee38..5a0328259de 100644 --- a/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector.cpp +++ b/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector.cpp @@ -23,8 +23,8 @@ using namespace std; int main(int argc, char **argv) { - ros::init(argc, argv, "op_behavior_selector"); - BehaviorGeneratorNS::BehaviorGen beh_gen; - beh_gen.MainLoop(); - return 0; + ros::init(argc, argv, "op_behavior_selector"); + BehaviorGeneratorNS::BehaviorGen beh_gen; + beh_gen.MainLoop(); + return 0; } diff --git a/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp b/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp index bd28474b048..57c7dc4512a 100644 --- a/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp +++ b/core_planning/op_local_planner/nodes/op_behavior_selector/op_behavior_selector_core.cpp @@ -23,692 +23,692 @@ namespace BehaviorGeneratorNS BehaviorGen::BehaviorGen() { - bNewCurrentPos = false; - bVehicleStatus = false; - bWayGlobalPath = false; - bWayGlobalPathLogs = false; - bNewLightStatus = false; - bNewLightSignal = false; - bBestCost = false; - bMap = false; - bRollOuts = false; - - ros::NodeHandle _nh; - UpdatePlanningParams(_nh); - - tf::StampedTransform transform; - PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_LocalPath = nh.advertise("final_waypoints", 1,true); - pub_LocalBasePath = nh.advertise("base_waypoints", 1,true); - pub_ClosestIndex = nh.advertise("closest_waypoint", 1,true); - pub_BehaviorState = nh.advertise("current_behavior", 1); - pub_SimuBoxPose = nh.advertise("sim_box_pose_ego", 1); - pub_BehaviorStateRviz = nh.advertise("behavior_state", 1); - pub_SelectedPathRviz = nh.advertise("local_selected_trajectory_rviz", 1); - - sub_current_pose = nh.subscribe("/current_pose", 10, &BehaviorGen::callbackGetCurrentPose, this); - - int bVelSource = 1; - _nh.getParam("/op_trajectory_evaluator/velocitySource", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 10, &BehaviorGen::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 10, &BehaviorGen::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 10, &BehaviorGen::callbackGetCANInfo, this); - - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &BehaviorGen::callbackGetGlobalPlannerPath, this); - sub_LocalPlannerPaths = nh.subscribe("/local_weighted_trajectories", 1, &BehaviorGen::callbackGetLocalPlannerPath, this); - sub_TrafficLightStatus = nh.subscribe("/light_color", 1, &BehaviorGen::callbackGetTrafficLightStatus, this); - sub_TrafficLightSignals = nh.subscribe("/roi_signal", 1, &BehaviorGen::callbackGetTrafficLightSignals, this); - sub_Trajectory_Cost = nh.subscribe("/local_trajectory_cost", 1, &BehaviorGen::callbackGetLocalTrajectoryCost, this); - - sub_twist_raw = nh.subscribe("/twist_raw", 1, &BehaviorGen::callbackGetTwistRaw, this); - sub_twist_cmd = nh.subscribe("/twist_cmd", 1, &BehaviorGen::callbackGetTwistCMD, this); - //sub_ctrl_cmd = nh.subscribe("/ctrl_cmd", 1, &BehaviorGen::callbackGetCommandCMD, this); - - //Mapping Section - sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &BehaviorGen::callbackGetVMLanes, this); - sub_points = nh.subscribe("/vector_map_info/point", 1, &BehaviorGen::callbackGetVMPoints, this); - sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &BehaviorGen::callbackGetVMdtLanes, this); - sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &BehaviorGen::callbackGetVMIntersections, this); - sup_area = nh.subscribe("/vector_map_info/area", 1, &BehaviorGen::callbackGetVMAreas, this); - sub_lines = nh.subscribe("/vector_map_info/line", 1, &BehaviorGen::callbackGetVMLines, this); - sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &BehaviorGen::callbackGetVMStopLines, this); - sub_signals = nh.subscribe("/vector_map_info/signal", 1, &BehaviorGen::callbackGetVMSignal, this); - sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &BehaviorGen::callbackGetVMVectors, this); - sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &BehaviorGen::callbackGetVMCurbs, this); - sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &BehaviorGen::callbackGetVMRoadEdges, this); - sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &BehaviorGen::callbackGetVMWayAreas, this); - sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &BehaviorGen::callbackGetVMCrossWalks, this); - sub_nodes = nh.subscribe("/vector_map_info/node", 1, &BehaviorGen::callbackGetVMNodes, this); + bNewCurrentPos = false; + bVehicleStatus = false; + bWayGlobalPath = false; + bWayGlobalPathLogs = false; + bNewLightStatus = false; + bNewLightSignal = false; + bBestCost = false; + bMap = false; + bRollOuts = false; + + ros::NodeHandle _nh; + UpdatePlanningParams(_nh); + + tf::StampedTransform transform; + PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_LocalPath = nh.advertise("final_waypoints", 1,true); + pub_LocalBasePath = nh.advertise("base_waypoints", 1,true); + pub_ClosestIndex = nh.advertise("closest_waypoint", 1,true); + pub_BehaviorState = nh.advertise("current_behavior", 1); + pub_SimuBoxPose = nh.advertise("sim_box_pose_ego", 1); + pub_BehaviorStateRviz = nh.advertise("behavior_state", 1); + pub_SelectedPathRviz = nh.advertise("local_selected_trajectory_rviz", 1); + + sub_current_pose = nh.subscribe("/current_pose", 10, &BehaviorGen::callbackGetCurrentPose, this); + + int bVelSource = 1; + _nh.getParam("/op_trajectory_evaluator/velocitySource", bVelSource); + if(bVelSource == 0) + sub_robot_odom = nh.subscribe("/odom", 10, &BehaviorGen::callbackGetRobotOdom, this); + else if(bVelSource == 1) + sub_current_velocity = nh.subscribe("/current_velocity", 10, &BehaviorGen::callbackGetVehicleStatus, this); + else if(bVelSource == 2) + sub_can_info = nh.subscribe("/can_info", 10, &BehaviorGen::callbackGetCANInfo, this); + + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &BehaviorGen::callbackGetGlobalPlannerPath, this); + sub_LocalPlannerPaths = nh.subscribe("/local_weighted_trajectories", 1, &BehaviorGen::callbackGetLocalPlannerPath, this); + sub_TrafficLightStatus = nh.subscribe("/light_color", 1, &BehaviorGen::callbackGetTrafficLightStatus, this); + sub_TrafficLightSignals = nh.subscribe("/roi_signal", 1, &BehaviorGen::callbackGetTrafficLightSignals, this); + sub_Trajectory_Cost = nh.subscribe("/local_trajectory_cost", 1, &BehaviorGen::callbackGetLocalTrajectoryCost, this); + + sub_twist_raw = nh.subscribe("/twist_raw", 1, &BehaviorGen::callbackGetTwistRaw, this); + sub_twist_cmd = nh.subscribe("/twist_cmd", 1, &BehaviorGen::callbackGetTwistCMD, this); + //sub_ctrl_cmd = nh.subscribe("/ctrl_cmd", 1, &BehaviorGen::callbackGetCommandCMD, this); + + //Mapping Section + sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &BehaviorGen::callbackGetVMLanes, this); + sub_points = nh.subscribe("/vector_map_info/point", 1, &BehaviorGen::callbackGetVMPoints, this); + sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &BehaviorGen::callbackGetVMdtLanes, this); + sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &BehaviorGen::callbackGetVMIntersections, this); + sup_area = nh.subscribe("/vector_map_info/area", 1, &BehaviorGen::callbackGetVMAreas, this); + sub_lines = nh.subscribe("/vector_map_info/line", 1, &BehaviorGen::callbackGetVMLines, this); + sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &BehaviorGen::callbackGetVMStopLines, this); + sub_signals = nh.subscribe("/vector_map_info/signal", 1, &BehaviorGen::callbackGetVMSignal, this); + sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &BehaviorGen::callbackGetVMVectors, this); + sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &BehaviorGen::callbackGetVMCurbs, this); + sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &BehaviorGen::callbackGetVMRoadEdges, this); + sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &BehaviorGen::callbackGetVMWayAreas, this); + sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &BehaviorGen::callbackGetVMCrossWalks, this); + sub_nodes = nh.subscribe("/vector_map_info/node", 1, &BehaviorGen::callbackGetVMNodes, this); } BehaviorGen::~BehaviorGen() { - UtilityHNS::DataRW::WriteLogData(UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::StatesLogFolderName, "MainLog", - "time,dt, Behavior_i, Behavior_str, RollOuts_n, Blocked_i, Central_i, Selected_i, StopSign_id, Light_id, Stop_Dist, Follow_Dist, Follow_Vel," - "Target_Vel, PID_Vel, T_cmd_Vel, C_cmd_Vel, Vel, Steer, X, Y, Z, Theta," - , m_LogData); + UtilityHNS::DataRW::WriteLogData(UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::StatesLogFolderName, "MainLog", + "time,dt, Behavior_i, Behavior_str, RollOuts_n, Blocked_i, Central_i, Selected_i, StopSign_id, Light_id, Stop_Dist, Follow_Dist, Follow_Vel," + "Target_Vel, PID_Vel, T_cmd_Vel, C_cmd_Vel, Vel, Steer, X, Y, Z, Theta," + , m_LogData); } void BehaviorGen::UpdatePlanningParams(ros::NodeHandle& _nh) { - _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); - if(m_PlanningParams.enableSwerving) - m_PlanningParams.enableFollowing = true; - else - _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); + _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); + if(m_PlanningParams.enableSwerving) + m_PlanningParams.enableFollowing = true; + else + _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); - _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); - _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); + _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); + _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); - _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); - _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); - _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); + _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); + _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); + _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); - _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); + _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); - _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); - if(m_PlanningParams.enableSwerving) - _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); - else - m_PlanningParams.rollOutNumber = 0; + _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); + if(m_PlanningParams.enableSwerving) + _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); + else + m_PlanningParams.rollOutNumber = 0; - _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); - _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); - _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); - _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); - _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); + _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); + _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); + _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); + _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); + _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); - _nh.getParam("/op_trajectory_evaluator/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); - _nh.getParam("/op_trajectory_evaluator/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); + _nh.getParam("/op_trajectory_evaluator/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); + _nh.getParam("/op_trajectory_evaluator/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); - _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); + _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); - _nh.getParam("/op_common_params/width", m_CarInfo.width); - _nh.getParam("/op_common_params/length", m_CarInfo.length); - _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); - _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); - _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); - _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); - _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); - m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; - m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; + _nh.getParam("/op_common_params/width", m_CarInfo.width); + _nh.getParam("/op_common_params/length", m_CarInfo.length); + _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); + _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); + _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); + _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); + _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); + m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; + m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; - PlannerHNS::ControllerParams controlParams; - controlParams.Steering_Gain = PlannerHNS::PID_CONST(0.07, 0.02, 0.01); - controlParams.Velocity_Gain = PlannerHNS::PID_CONST(0.1, 0.005, 0.1); - nh.getParam("/op_common_params/steeringDelay", controlParams.SteeringDelay); - nh.getParam("/op_common_params/minPursuiteDistance", controlParams.minPursuiteDistance ); - nh.getParam("/op_common_params/additionalBrakingDistance", m_PlanningParams.additionalBrakingDistance ); - nh.getParam("/op_common_params/giveUpDistance", m_PlanningParams.giveUpDistance ); + PlannerHNS::ControllerParams controlParams; + controlParams.Steering_Gain = PlannerHNS::PID_CONST(0.07, 0.02, 0.01); + controlParams.Velocity_Gain = PlannerHNS::PID_CONST(0.1, 0.005, 0.1); + nh.getParam("/op_common_params/steeringDelay", controlParams.SteeringDelay); + nh.getParam("/op_common_params/minPursuiteDistance", controlParams.minPursuiteDistance ); + nh.getParam("/op_common_params/additionalBrakingDistance", m_PlanningParams.additionalBrakingDistance ); + nh.getParam("/op_common_params/giveUpDistance", m_PlanningParams.giveUpDistance ); - int iSource = 0; - _nh.getParam("/op_common_params/mapSource" , iSource); - if(iSource == 0) - m_MapType = PlannerHNS::MAP_AUTOWARE; - else if (iSource == 1) - m_MapType = PlannerHNS::MAP_FOLDER; - else if(iSource == 2) - m_MapType = PlannerHNS::MAP_KML_FILE; + int iSource = 0; + _nh.getParam("/op_common_params/mapSource" , iSource); + if(iSource == 0) + m_MapType = PlannerHNS::MAP_AUTOWARE; + else if (iSource == 1) + m_MapType = PlannerHNS::MAP_FOLDER; + else if(iSource == 2) + m_MapType = PlannerHNS::MAP_KML_FILE; - _nh.getParam("/op_common_params/mapFileName" , m_MapPath); + _nh.getParam("/op_common_params/mapFileName" , m_MapPath); - _nh.getParam("/op_behavior_selector/evidence_tust_number", m_PlanningParams.nReliableCount); + _nh.getParam("/op_behavior_selector/evidence_tust_number", m_PlanningParams.nReliableCount); - //std::cout << "nReliableCount: " << m_PlanningParams.nReliableCount << std::endl; + //std::cout << "nReliableCount: " << m_PlanningParams.nReliableCount << std::endl; - m_BehaviorGenerator.Init(controlParams, m_PlanningParams, m_CarInfo); - m_BehaviorGenerator.m_pCurrentBehaviorState->m_Behavior = PlannerHNS::INITIAL_STATE; + m_BehaviorGenerator.Init(controlParams, m_PlanningParams, m_CarInfo); + m_BehaviorGenerator.m_pCurrentBehaviorState->m_Behavior = PlannerHNS::INITIAL_STATE; } void BehaviorGen::callbackGetTwistRaw(const geometry_msgs::TwistStampedConstPtr& msg) { - m_Twist_raw = *msg; + m_Twist_raw = *msg; } void BehaviorGen::callbackGetTwistCMD(const geometry_msgs::TwistStampedConstPtr& msg) { - m_Twist_cmd = *msg; + m_Twist_cmd = *msg; } void BehaviorGen::callbackGetCommandCMD(const autoware_msgs::ControlCommandConstPtr& msg) { - m_Ctrl_cmd = *msg; + m_Ctrl_cmd = *msg; } void BehaviorGen::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); - bNewCurrentPos = true; + m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + bNewCurrentPos = true; } void BehaviorGen::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed; - if(fabs(msg->twist.linear.x) > 0.25) - m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed; + if(fabs(msg->twist.linear.x) > 0.25) + m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void BehaviorGen::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleStatus.speed = msg->speed/3.6; - m_CurrentPos.v = m_VehicleStatus.speed; - m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->speed/3.6; + m_CurrentPos.v = m_VehicleStatus.speed; + m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void BehaviorGen::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed ; - if(msg->twist.twist.linear.x != 0) - m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed ; + if(msg->twist.twist.linear.x != 0) + m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void BehaviorGen::callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg) { - if(msg->lanes.size() > 0 && bMap) - { - - bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); - - m_GlobalPaths.clear(); - - for(unsigned int i = 0 ; i < msg->lanes.size(); i++) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); - PlannerHNS::Lane* pPrevValid = 0; - for(unsigned int j = 0 ; j < m_temp_path.size(); j++) - { - PlannerHNS::Lane* pLane = 0; - pLane = PlannerHNS::MappingHelpers::GetLaneById(m_temp_path.at(j).laneId, m_Map); - if(!pLane) - { - pLane = PlannerHNS::MappingHelpers::GetClosestLaneFromMapDirectionBased(m_temp_path.at(j), m_Map, 1); - - if(!pLane && !pPrevValid) - { - ROS_ERROR("Map inconsistency between Global Path and Local Planer Map, Can't identify current lane."); - return; - } - - if(!pLane) - m_temp_path.at(j).pLane = pPrevValid; - else - { - m_temp_path.at(j).pLane = pLane; - pPrevValid = pLane ; - } - - m_temp_path.at(j).laneId = m_temp_path.at(j).pLane->id; - } - else - m_temp_path.at(j).pLane = pLane; - - - //std::cout << "StopLineInGlobalPath: " << m_temp_path.at(j).stopLineID << std::endl; - } - - PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); - m_GlobalPaths.push_back(m_temp_path); - - if(bOldGlobalPath) - { - bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); - } - } - - if(!bOldGlobalPath) - { - bWayGlobalPath = true; - bWayGlobalPathLogs = true; - for(unsigned int i = 0; i < m_GlobalPaths.size(); i++) - { - PlannerHNS::PlanningHelpers::FixPathDensity(m_GlobalPaths.at(i), m_PlanningParams.pathDensity); - PlannerHNS::PlanningHelpers::SmoothPath(m_GlobalPaths.at(i), 0.35, 0.4, 0.05); - - PlannerHNS::PlanningHelpers::GenerateRecommendedSpeed(m_GlobalPaths.at(i), m_CarInfo.max_speed_forward, m_PlanningParams.speedProfileFactor); - m_GlobalPaths.at(i).at(m_GlobalPaths.at(i).size()-1).v = 0; - } - - std::cout << "Received New Global Path Selector! " << std::endl; - } - else - { - m_GlobalPaths.clear(); - } - } + if(msg->lanes.size() > 0 && bMap) + { + + bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); + + m_GlobalPaths.clear(); + + for(unsigned int i = 0 ; i < msg->lanes.size(); i++) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); + PlannerHNS::Lane* pPrevValid = 0; + for(unsigned int j = 0 ; j < m_temp_path.size(); j++) + { + PlannerHNS::Lane* pLane = 0; + pLane = PlannerHNS::MappingHelpers::GetLaneById(m_temp_path.at(j).laneId, m_Map); + if(!pLane) + { + pLane = PlannerHNS::MappingHelpers::GetClosestLaneFromMapDirectionBased(m_temp_path.at(j), m_Map, 1); + + if(!pLane && !pPrevValid) + { + ROS_ERROR("Map inconsistency between Global Path and Local Planer Map, Can't identify current lane."); + return; + } + + if(!pLane) + m_temp_path.at(j).pLane = pPrevValid; + else + { + m_temp_path.at(j).pLane = pLane; + pPrevValid = pLane ; + } + + m_temp_path.at(j).laneId = m_temp_path.at(j).pLane->id; + } + else + m_temp_path.at(j).pLane = pLane; + + + //std::cout << "StopLineInGlobalPath: " << m_temp_path.at(j).stopLineID << std::endl; + } + + PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); + m_GlobalPaths.push_back(m_temp_path); + + if(bOldGlobalPath) + { + bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); + } + } + + if(!bOldGlobalPath) + { + bWayGlobalPath = true; + bWayGlobalPathLogs = true; + for(unsigned int i = 0; i < m_GlobalPaths.size(); i++) + { + PlannerHNS::PlanningHelpers::FixPathDensity(m_GlobalPaths.at(i), m_PlanningParams.pathDensity); + PlannerHNS::PlanningHelpers::SmoothPath(m_GlobalPaths.at(i), 0.35, 0.4, 0.05); + + PlannerHNS::PlanningHelpers::GenerateRecommendedSpeed(m_GlobalPaths.at(i), m_CarInfo.max_speed_forward, m_PlanningParams.speedProfileFactor); + m_GlobalPaths.at(i).at(m_GlobalPaths.at(i).size()-1).v = 0; + } + + std::cout << "Received New Global Path Selector! " << std::endl; + } + else + { + m_GlobalPaths.clear(); + } + } } void BehaviorGen::callbackGetLocalTrajectoryCost(const autoware_msgs::LaneConstPtr& msg) { - bBestCost = true; - m_TrajectoryBestCost.bBlocked = msg->is_blocked; - m_TrajectoryBestCost.index = msg->lane_index; - m_TrajectoryBestCost.cost = msg->cost; - m_TrajectoryBestCost.closest_obj_distance = msg->closest_object_distance; - m_TrajectoryBestCost.closest_obj_velocity = msg->closest_object_velocity; + bBestCost = true; + m_TrajectoryBestCost.bBlocked = msg->is_blocked; + m_TrajectoryBestCost.index = msg->lane_index; + m_TrajectoryBestCost.cost = msg->cost; + m_TrajectoryBestCost.closest_obj_distance = msg->closest_object_distance; + m_TrajectoryBestCost.closest_obj_velocity = msg->closest_object_velocity; } void BehaviorGen::callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg) { - if(msg->lanes.size() > 0) - { - m_RollOuts.clear(); - int globalPathId_roll_outs = -1; - - for(unsigned int i = 0 ; i < msg->lanes.size(); i++) - { - std::vector path; - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), path); - m_RollOuts.push_back(path); - - if(path.size() > 0) - globalPathId_roll_outs = path.at(0).gid; - } - - if(bWayGlobalPath && m_GlobalPaths.size() > 0) - { - if(m_GlobalPaths.at(0).size() > 0) - { - int globalPathId = m_GlobalPaths.at(0).at(0).gid; - std::cout << "Before Synchronization At Behavior Selector: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; - - if(globalPathId_roll_outs == globalPathId) - { - bWayGlobalPath = false; - m_GlobalPathsToUse = m_GlobalPaths; - m_BehaviorGenerator.SetNewGlobalPath(m_GlobalPathsToUse); - std::cout << "Synchronization At Behavior Selector: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; - } - } - } - - m_BehaviorGenerator.m_RollOuts = m_RollOuts; - bRollOuts = true; - } + if(msg->lanes.size() > 0) + { + m_RollOuts.clear(); + int globalPathId_roll_outs = -1; + + for(unsigned int i = 0 ; i < msg->lanes.size(); i++) + { + std::vector path; + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), path); + m_RollOuts.push_back(path); + + if(path.size() > 0) + globalPathId_roll_outs = path.at(0).gid; + } + + if(bWayGlobalPath && m_GlobalPaths.size() > 0) + { + if(m_GlobalPaths.at(0).size() > 0) + { + int globalPathId = m_GlobalPaths.at(0).at(0).gid; + std::cout << "Before Synchronization At Behavior Selector: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; + + if(globalPathId_roll_outs == globalPathId) + { + bWayGlobalPath = false; + m_GlobalPathsToUse = m_GlobalPaths; + m_BehaviorGenerator.SetNewGlobalPath(m_GlobalPathsToUse); + std::cout << "Synchronization At Behavior Selector: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; + } + } + } + + m_BehaviorGenerator.m_RollOuts = m_RollOuts; + bRollOuts = true; + } } void BehaviorGen::callbackGetTrafficLightStatus(const autoware_msgs::TrafficLight& msg) { - std::cout << "Received Traffic Light Status : " << msg.traffic_light << std::endl; - bNewLightStatus = true; - if(msg.traffic_light == 1) // green - m_CurrLightStatus = PlannerHNS::GREEN_LIGHT; - else //0 => RED , 2 => Unknown - m_CurrLightStatus = PlannerHNS::RED_LIGHT; + std::cout << "Received Traffic Light Status : " << msg.traffic_light << std::endl; + bNewLightStatus = true; + if(msg.traffic_light == 1) // green + m_CurrLightStatus = PlannerHNS::GREEN_LIGHT; + else //0 => RED , 2 => Unknown + m_CurrLightStatus = PlannerHNS::RED_LIGHT; } void BehaviorGen::callbackGetTrafficLightSignals(const autoware_msgs::Signals& msg) { - bNewLightSignal = true; - std::vector simulatedLights; - for(unsigned int i = 0 ; i < msg.Signals.size() ; i++) - { - PlannerHNS::TrafficLight tl; - tl.id = msg.Signals.at(i).signalId; - - for(unsigned int k = 0; k < m_Map.trafficLights.size(); k++) - { - if(m_Map.trafficLights.at(k).id == tl.id) - { - tl.pos = m_Map.trafficLights.at(k).pos; - break; - } - } - - if(msg.Signals.at(i).type == 1) - { - tl.lightState = PlannerHNS::GREEN_LIGHT; - } - else - { - tl.lightState = PlannerHNS::RED_LIGHT; - } - - simulatedLights.push_back(tl); - } - - //std::cout << "Received Traffic Lights : " << lights.markers.size() << std::endl; - - m_CurrTrafficLight = simulatedLights; - -// int stopLineID = -1, stopSignID = -1, trafficLightID=-1; -// PlannerHNS::PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_BehaviorGenerator.m_Path, m_CurrentPos, stopLineID, stopSignID, trafficLightID); -// m_CurrTrafficLight.clear(); -// if(trafficLightID > 0) -// { -// for(unsigned int i=0; i < simulatedLights.size(); i++) -// { -// if(simulatedLights.at(i).id == trafficLightID) -// { -// m_CurrTrafficLight.push_back(simulatedLights.at(i)); -// } -// } -// } + bNewLightSignal = true; + std::vector simulatedLights; + for(unsigned int i = 0 ; i < msg.Signals.size() ; i++) + { + PlannerHNS::TrafficLight tl; + tl.id = msg.Signals.at(i).signalId; + + for(unsigned int k = 0; k < m_Map.trafficLights.size(); k++) + { + if(m_Map.trafficLights.at(k).id == tl.id) + { + tl.pos = m_Map.trafficLights.at(k).pos; + break; + } + } + + if(msg.Signals.at(i).type == 1) + { + tl.lightState = PlannerHNS::GREEN_LIGHT; + } + else + { + tl.lightState = PlannerHNS::RED_LIGHT; + } + + simulatedLights.push_back(tl); + } + + //std::cout << "Received Traffic Lights : " << lights.markers.size() << std::endl; + + m_CurrTrafficLight = simulatedLights; + +// int stopLineID = -1, stopSignID = -1, trafficLightID=-1; +// PlannerHNS::PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_BehaviorGenerator.m_Path, m_CurrentPos, stopLineID, stopSignID, trafficLightID); +// m_CurrTrafficLight.clear(); +// if(trafficLightID > 0) +// { +// for(unsigned int i=0; i < simulatedLights.size(); i++) +// { +// if(simulatedLights.at(i).id == trafficLightID) +// { +// m_CurrTrafficLight.push_back(simulatedLights.at(i)); +// } +// } +// } } void BehaviorGen::VisualizeLocalPlanner() { - visualization_msgs::Marker behavior_rviz; - int iDirection = 0; - if(m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory > m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) - iDirection = 1; - else if(m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory < m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) - iDirection = -1; - PlannerHNS::ROSHelpers::VisualizeBehaviorState(m_CurrentPos, m_CurrentBehavior, !m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->bTrafficIsRed , iDirection, behavior_rviz, "beh_state"); - //pub_BehaviorStateRviz.publish(behavior_rviz); + visualization_msgs::Marker behavior_rviz; + int iDirection = 0; + if(m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory > m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) + iDirection = 1; + else if(m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory < m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory) + iDirection = -1; + PlannerHNS::ROSHelpers::VisualizeBehaviorState(m_CurrentPos, m_CurrentBehavior, !m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->bTrafficIsRed , iDirection, behavior_rviz, "beh_state"); + //pub_BehaviorStateRviz.publish(behavior_rviz); - visualization_msgs::MarkerArray markerArray; + visualization_msgs::MarkerArray markerArray; - //PlannerHNS::ROSHelpers::GetIndicatorArrows(m_CurrentPos, m_CarInfo.width, m_CarInfo.length, m_CurrentBehavior.indicator, 0, markerArray); + //PlannerHNS::ROSHelpers::GetIndicatorArrows(m_CurrentPos, m_CarInfo.width, m_CarInfo.length, m_CurrentBehavior.indicator, 0, markerArray); - markerArray.markers.push_back(behavior_rviz); + markerArray.markers.push_back(behavior_rviz); - pub_BehaviorStateRviz.publish(markerArray); + pub_BehaviorStateRviz.publish(markerArray); - //To Test Synchronization Problem -// visualization_msgs::MarkerArray selected_path; -// std::vector > > paths; + //To Test Synchronization Problem +// visualization_msgs::MarkerArray selected_path; +// std::vector > > paths; // paths.push_back(std::vector >()); -// paths.at(0).push_back(m_BehaviorGenerator.m_Path); -// paths.push_back(m_GlobalPathsToUse); -// paths.push_back(m_RollOuts); -// PlannerHNS::ROSHelpers::TrajectoriesToMarkers(paths, selected_path); -// pub_SelectedPathRviz.publish(selected_path); +// paths.at(0).push_back(m_BehaviorGenerator.m_Path); +// paths.push_back(m_GlobalPathsToUse); +// paths.push_back(m_RollOuts); +// PlannerHNS::ROSHelpers::TrajectoriesToMarkers(paths, selected_path); +// pub_SelectedPathRviz.publish(selected_path); } void BehaviorGen::SendLocalPlanningTopics() { - //Send Behavior State - geometry_msgs::Twist t; - geometry_msgs::TwistStamped behavior; - t.linear.x = m_CurrentBehavior.bNewPlan; - t.linear.y = m_CurrentBehavior.followDistance; - t.linear.z = m_CurrentBehavior.followVelocity; - t.angular.x = (int)m_CurrentBehavior.indicator; - t.angular.y = (int)m_CurrentBehavior.state; - t.angular.z = m_CurrentBehavior.iTrajectory; - behavior.twist = t; - behavior.header.stamp = ros::Time::now(); - pub_BehaviorState.publish(behavior); - - //Send Ego Vehicle Simulation Pose Data - geometry_msgs::PoseArray sim_data; - geometry_msgs::Pose p_id, p_pose, p_box; - - sim_data.header.frame_id = "map"; - sim_data.header.stamp = ros::Time(); - p_id.position.x = 0; - p_pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, UtilityHNS::UtilityH::SplitPositiveAngle(m_BehaviorGenerator.state.pos.a)); - - PlannerHNS::WayPoint pose_center = PlannerHNS::PlanningHelpers::GetRealCenter(m_BehaviorGenerator.state, m_CarInfo.wheel_base); - - p_pose.position.x = pose_center.pos.x; - p_pose.position.y = pose_center.pos.y; - p_pose.position.z = pose_center.pos.z; - p_box.position.x = m_BehaviorGenerator.m_CarInfo.width; - p_box.position.y = m_BehaviorGenerator.m_CarInfo.length; - p_box.position.z = 2.2; - sim_data.poses.push_back(p_id); - sim_data.poses.push_back(p_pose); - sim_data.poses.push_back(p_box); - pub_SimuBoxPose.publish(sim_data); - - //Send Trajectory Data to path following nodes - std_msgs::Int32 closest_waypoint; - PlannerHNS::RelativeInfo info; - PlannerHNS::PlanningHelpers::GetRelativeInfo(m_BehaviorGenerator.m_Path, m_BehaviorGenerator.state, info); - PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_BehaviorGenerator.m_Path, m_CurrentTrajectoryToSend, info.iBack); - //std::cout << "Path Size: " << m_BehaviorGenerator.m_Path.size() << ", Send Size: " << m_CurrentTrajectoryToSend << std::endl; - - closest_waypoint.data = 1; - pub_ClosestIndex.publish(closest_waypoint); - pub_LocalBasePath.publish(m_CurrentTrajectoryToSend); - pub_LocalPath.publish(m_CurrentTrajectoryToSend); + //Send Behavior State + geometry_msgs::Twist t; + geometry_msgs::TwistStamped behavior; + t.linear.x = m_CurrentBehavior.bNewPlan; + t.linear.y = m_CurrentBehavior.followDistance; + t.linear.z = m_CurrentBehavior.followVelocity; + t.angular.x = (int)m_CurrentBehavior.indicator; + t.angular.y = (int)m_CurrentBehavior.state; + t.angular.z = m_CurrentBehavior.iTrajectory; + behavior.twist = t; + behavior.header.stamp = ros::Time::now(); + pub_BehaviorState.publish(behavior); + + //Send Ego Vehicle Simulation Pose Data + geometry_msgs::PoseArray sim_data; + geometry_msgs::Pose p_id, p_pose, p_box; + + sim_data.header.frame_id = "map"; + sim_data.header.stamp = ros::Time(); + p_id.position.x = 0; + p_pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, UtilityHNS::UtilityH::SplitPositiveAngle(m_BehaviorGenerator.state.pos.a)); + + PlannerHNS::WayPoint pose_center = PlannerHNS::PlanningHelpers::GetRealCenter(m_BehaviorGenerator.state, m_CarInfo.wheel_base); + + p_pose.position.x = pose_center.pos.x; + p_pose.position.y = pose_center.pos.y; + p_pose.position.z = pose_center.pos.z; + p_box.position.x = m_BehaviorGenerator.m_CarInfo.width; + p_box.position.y = m_BehaviorGenerator.m_CarInfo.length; + p_box.position.z = 2.2; + sim_data.poses.push_back(p_id); + sim_data.poses.push_back(p_pose); + sim_data.poses.push_back(p_box); + pub_SimuBoxPose.publish(sim_data); + + //Send Trajectory Data to path following nodes + std_msgs::Int32 closest_waypoint; + PlannerHNS::RelativeInfo info; + PlannerHNS::PlanningHelpers::GetRelativeInfo(m_BehaviorGenerator.m_Path, m_BehaviorGenerator.state, info); + PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_BehaviorGenerator.m_Path, m_CurrentTrajectoryToSend, info.iBack); + //std::cout << "Path Size: " << m_BehaviorGenerator.m_Path.size() << ", Send Size: " << m_CurrentTrajectoryToSend << std::endl; + + closest_waypoint.data = 1; + pub_ClosestIndex.publish(closest_waypoint); + pub_LocalBasePath.publish(m_CurrentTrajectoryToSend); + pub_LocalPath.publish(m_CurrentTrajectoryToSend); } void BehaviorGen::LogLocalPlanningInfo(double dt) { - timespec log_t; - UtilityHNS::UtilityH::GetTickCount(log_t); - std::ostringstream dataLine; - dataLine << UtilityHNS::UtilityH::GetLongTime(log_t) <<"," << dt << "," << m_CurrentBehavior.state << ","<< PlannerHNS::ROSHelpers::GetBehaviorNameFromCode(m_CurrentBehavior.state) << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->m_pParams->rollOutNumber << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->bFullyBlock << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->currentStopSignID << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->currentTrafficLightID << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->minStoppingDistance << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->distanceToNext << "," << - m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->velocityOfNext << "," << - m_CurrentBehavior.maxVelocity << "," << - m_Twist_raw.twist.linear.x << "," << - m_Twist_cmd.twist.linear.x << "," << - m_Ctrl_cmd.linear_velocity << "," << - m_VehicleStatus.speed << "," << - m_VehicleStatus.steer << "," << - m_BehaviorGenerator.state.pos.x << "," << m_BehaviorGenerator.state.pos.y << "," << m_BehaviorGenerator.state.pos.z << "," << UtilityHNS::UtilityH::SplitPositiveAngle(m_BehaviorGenerator.state.pos.a)+M_PI << ","; - m_LogData.push_back(dataLine.str()); - - - if(bWayGlobalPathLogs) - { - for(unsigned int i=0; i < m_GlobalPaths.size(); i++) - { - std::ostringstream str_out; - str_out << UtilityHNS::UtilityH::GetHomeDirectory(); - str_out << UtilityHNS::DataRW::LoggingMainfolderName; - str_out << UtilityHNS::DataRW::PathLogFolderName; - str_out << "Global_Vel"; - str_out << i; - str_out << "_"; - PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), m_GlobalPaths.at(i)); - } - bWayGlobalPathLogs = false; - } + timespec log_t; + UtilityHNS::UtilityH::GetTickCount(log_t); + std::ostringstream dataLine; + dataLine << UtilityHNS::UtilityH::GetLongTime(log_t) <<"," << dt << "," << m_CurrentBehavior.state << ","<< PlannerHNS::ROSHelpers::GetBehaviorNameFromCode(m_CurrentBehavior.state) << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->m_pParams->rollOutNumber << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->bFullyBlock << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->currentStopSignID << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->currentTrafficLightID << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->minStoppingDistance << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->distanceToNext << "," << + m_BehaviorGenerator.m_pCurrentBehaviorState->GetCalcParams()->velocityOfNext << "," << + m_CurrentBehavior.maxVelocity << "," << + m_Twist_raw.twist.linear.x << "," << + m_Twist_cmd.twist.linear.x << "," << + m_Ctrl_cmd.linear_velocity << "," << + m_VehicleStatus.speed << "," << + m_VehicleStatus.steer << "," << + m_BehaviorGenerator.state.pos.x << "," << m_BehaviorGenerator.state.pos.y << "," << m_BehaviorGenerator.state.pos.z << "," << UtilityHNS::UtilityH::SplitPositiveAngle(m_BehaviorGenerator.state.pos.a)+M_PI << ","; + m_LogData.push_back(dataLine.str()); + + + if(bWayGlobalPathLogs) + { + for(unsigned int i=0; i < m_GlobalPaths.size(); i++) + { + std::ostringstream str_out; + str_out << UtilityHNS::UtilityH::GetHomeDirectory(); + str_out << UtilityHNS::DataRW::LoggingMainfolderName; + str_out << UtilityHNS::DataRW::PathLogFolderName; + str_out << "Global_Vel"; + str_out << i; + str_out << "_"; + PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), m_GlobalPaths.at(i)); + } + bWayGlobalPathLogs = false; + } } void BehaviorGen::MainLoop() { - ros::Rate loop_rate(100); - - - timespec planningTimer; - UtilityHNS::UtilityH::GetTickCount(planningTimer); - - while (ros::ok()) - { - ros::spinOnce(); - - double dt = UtilityHNS::UtilityH::GetTimeDiffNow(planningTimer); - UtilityHNS::UtilityH::GetTickCount(planningTimer); - - if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); - } - else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); - - } - else if (m_MapType == PlannerHNS::MAP_AUTOWARE && !bMap) - { - std::vector conn_data;; - - if(m_MapRaw.GetVersion()==2) - { - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, - m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, false); - - if(m_Map.roadSegments.size() > 0) - { - bMap = true; - std::cout << " ******* Map V2 Is Loaded successfully from the Behavior Selector !! " << std::endl; - } - } - else if(m_MapRaw.GetVersion()==1) - { - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, false); - - if(m_Map.roadSegments.size() > 0) - { - bMap = true; - std::cout << " ******* Map V1 Is Loaded successfully from the Behavior Selector !! " << std::endl; - } - } - } - - if(bNewCurrentPos && m_GlobalPaths.size()>0) - { - if(bNewLightSignal) - { - m_PrevTrafficLight = m_CurrTrafficLight; - bNewLightSignal = false; - } - - if(bNewLightStatus) - { - bNewLightStatus = false; - for(unsigned int itls = 0 ; itls < m_PrevTrafficLight.size() ; itls++) - m_PrevTrafficLight.at(itls).lightState = m_CurrLightStatus; - } - - m_CurrentBehavior = m_BehaviorGenerator.DoOneStep(dt, m_CurrentPos, m_VehicleStatus, 1, m_CurrTrafficLight, m_TrajectoryBestCost, 0 ); - - SendLocalPlanningTopics(); - VisualizeLocalPlanner(); - LogLocalPlanningInfo(dt); - } - else - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &BehaviorGen::callbackGetGlobalPlannerPath, this); - - loop_rate.sleep(); - } + ros::Rate loop_rate(100); + + + timespec planningTimer; + UtilityHNS::UtilityH::GetTickCount(planningTimer); + + while (ros::ok()) + { + ros::spinOnce(); + + double dt = UtilityHNS::UtilityH::GetTimeDiffNow(planningTimer); + UtilityHNS::UtilityH::GetTickCount(planningTimer); + + if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); + } + else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); + + } + else if (m_MapType == PlannerHNS::MAP_AUTOWARE && !bMap) + { + std::vector conn_data;; + + if(m_MapRaw.GetVersion()==2) + { + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, + m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, false); + + if(m_Map.roadSegments.size() > 0) + { + bMap = true; + std::cout << " ******* Map V2 Is Loaded successfully from the Behavior Selector !! " << std::endl; + } + } + else if(m_MapRaw.GetVersion()==1) + { + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, false); + + if(m_Map.roadSegments.size() > 0) + { + bMap = true; + std::cout << " ******* Map V1 Is Loaded successfully from the Behavior Selector !! " << std::endl; + } + } + } + + if(bNewCurrentPos && m_GlobalPaths.size()>0) + { + if(bNewLightSignal) + { + m_PrevTrafficLight = m_CurrTrafficLight; + bNewLightSignal = false; + } + + if(bNewLightStatus) + { + bNewLightStatus = false; + for(unsigned int itls = 0 ; itls < m_PrevTrafficLight.size() ; itls++) + m_PrevTrafficLight.at(itls).lightState = m_CurrLightStatus; + } + + m_CurrentBehavior = m_BehaviorGenerator.DoOneStep(dt, m_CurrentPos, m_VehicleStatus, 1, m_CurrTrafficLight, m_TrajectoryBestCost, 0 ); + + SendLocalPlanningTopics(); + VisualizeLocalPlanner(); + LogLocalPlanningInfo(dt); + } + else + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &BehaviorGen::callbackGetGlobalPlannerPath, this); + + loop_rate.sleep(); + } } //Mapping Section void BehaviorGen::callbackGetVMLanes(const vector_map_msgs::LaneArray& msg) { - std::cout << "Received Lanes" << endl; - if(m_MapRaw.pLanes == nullptr) - m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); + std::cout << "Received Lanes" << endl; + if(m_MapRaw.pLanes == nullptr) + m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); } void BehaviorGen::callbackGetVMPoints(const vector_map_msgs::PointArray& msg) { - std::cout << "Received Points" << endl; - if(m_MapRaw.pPoints == nullptr) - m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); + std::cout << "Received Points" << endl; + if(m_MapRaw.pPoints == nullptr) + m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); } void BehaviorGen::callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg) { - std::cout << "Received dtLanes" << endl; - if(m_MapRaw.pCenterLines == nullptr) - m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); + std::cout << "Received dtLanes" << endl; + if(m_MapRaw.pCenterLines == nullptr) + m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); } void BehaviorGen::callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg) { - std::cout << "Received CrossRoads" << endl; - if(m_MapRaw.pIntersections == nullptr) - m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); + std::cout << "Received CrossRoads" << endl; + if(m_MapRaw.pIntersections == nullptr) + m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); } void BehaviorGen::callbackGetVMAreas(const vector_map_msgs::AreaArray& msg) { - std::cout << "Received Areas" << endl; - if(m_MapRaw.pAreas == nullptr) - m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); + std::cout << "Received Areas" << endl; + if(m_MapRaw.pAreas == nullptr) + m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); } void BehaviorGen::callbackGetVMLines(const vector_map_msgs::LineArray& msg) { - std::cout << "Received Lines" << endl; - if(m_MapRaw.pLines == nullptr) - m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); + std::cout << "Received Lines" << endl; + if(m_MapRaw.pLines == nullptr) + m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); } void BehaviorGen::callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg) { - std::cout << "Received StopLines" << endl; - if(m_MapRaw.pStopLines == nullptr) - m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); + std::cout << "Received StopLines" << endl; + if(m_MapRaw.pStopLines == nullptr) + m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); } void BehaviorGen::callbackGetVMSignal(const vector_map_msgs::SignalArray& msg) { - std::cout << "Received Signals" << endl; - if(m_MapRaw.pSignals == nullptr) - m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); + std::cout << "Received Signals" << endl; + if(m_MapRaw.pSignals == nullptr) + m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); } void BehaviorGen::callbackGetVMVectors(const vector_map_msgs::VectorArray& msg) { - std::cout << "Received Vectors" << endl; - if(m_MapRaw.pVectors == nullptr) - m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); + std::cout << "Received Vectors" << endl; + if(m_MapRaw.pVectors == nullptr) + m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); } void BehaviorGen::callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg) { - std::cout << "Received Curbs" << endl; - if(m_MapRaw.pCurbs == nullptr) - m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); + std::cout << "Received Curbs" << endl; + if(m_MapRaw.pCurbs == nullptr) + m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); } void BehaviorGen::callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg) { - std::cout << "Received Edges" << endl; - if(m_MapRaw.pRoadedges == nullptr) - m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); + std::cout << "Received Edges" << endl; + if(m_MapRaw.pRoadedges == nullptr) + m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); } void BehaviorGen::callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg) { - std::cout << "Received Wayareas" << endl; - if(m_MapRaw.pWayAreas == nullptr) - m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); + std::cout << "Received Wayareas" << endl; + if(m_MapRaw.pWayAreas == nullptr) + m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); } void BehaviorGen::callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg) { - std::cout << "Received CrossWalks" << endl; - if(m_MapRaw.pCrossWalks == nullptr) - m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); + std::cout << "Received CrossWalks" << endl; + if(m_MapRaw.pCrossWalks == nullptr) + m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); } void BehaviorGen::callbackGetVMNodes(const vector_map_msgs::NodeArray& msg) { - std::cout << "Received Nodes" << endl; - if(m_MapRaw.pNodes == nullptr) - m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); + std::cout << "Received Nodes" << endl; + if(m_MapRaw.pNodes == nullptr) + m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); } } diff --git a/core_planning/op_local_planner/nodes/op_common_params/op_common_params.cpp b/core_planning/op_local_planner/nodes/op_common_params/op_common_params.cpp index c4086bd50e5..b3b06e3cd29 100644 --- a/core_planning/op_local_planner/nodes/op_common_params/op_common_params.cpp +++ b/core_planning/op_local_planner/nodes/op_common_params/op_common_params.cpp @@ -20,16 +20,16 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "op_common_params"); + ros::init(argc, argv, "op_common_params"); - UtilityHNS::DataRW::CreateLoggingFolder(); + UtilityHNS::DataRW::CreateLoggingFolder(); - ros::NodeHandle nh; - ros::Rate loop_rate(1); - while (ros::ok()) - { - ros::spinOnce(); - loop_rate.sleep(); - } - return 0; + ros::NodeHandle nh; + ros::Rate loop_rate(1); + while (ros::ok()) + { + ros::spinOnce(); + loop_rate.sleep(); + } + return 0; } diff --git a/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor.cpp b/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor.cpp index aaac025b58f..eb9ce28e7db 100644 --- a/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor.cpp +++ b/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor.cpp @@ -20,8 +20,8 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "op_motion_predictor"); - MotionPredictorNS::MotionPrediction predict_traj; - predict_traj.MainLoop(); - return 0; + ros::init(argc, argv, "op_motion_predictor"); + MotionPredictorNS::MotionPrediction predict_traj; + predict_traj.MainLoop(); + return 0; } diff --git a/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor_core.cpp b/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor_core.cpp index 245c655be10..2d9bcf2e73c 100644 --- a/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor_core.cpp +++ b/core_planning/op_local_planner/nodes/op_motion_predictor/op_motion_predictor_core.cpp @@ -23,64 +23,64 @@ namespace MotionPredictorNS MotionPrediction::MotionPrediction() { - bMap = false; - bNewCurrentPos = false; - bVehicleStatus = false; - bTrackedObjects = false; - m_bEnableCurbObstacles = false; - m_DistanceBetweenCurbs = 1.0; - m_VisualizationTime = 0.25; - m_bGoNextStep = false; - - ros::NodeHandle _nh; - UpdatePlanningParams(_nh); - - tf::StampedTransform transform; - PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_predicted_objects_trajectories = nh.advertise("/predicted_objects", 1); - pub_PredictedTrajectoriesRviz = nh.advertise("/predicted_trajectories_rviz", 1); - pub_CurbsRviz = nh.advertise("/map_curbs_rviz", 1); - pub_ParticlesRviz = nh.advertise("prediction_particles", 1); - - sub_StepSignal = nh.subscribe("/pred_step_signal", 1, &MotionPrediction::callbackGetStepForwardSignals, this); - sub_tracked_objects = nh.subscribe("/tracked_objects", 1, &MotionPrediction::callbackGetTrackedObjects, this); - sub_current_pose = nh.subscribe("/current_pose", 10, &MotionPrediction::callbackGetCurrentPose, this); - - int bVelSource = 1; - _nh.getParam("/op_motion_predictor/velocitySource", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 10, &MotionPrediction::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 10, &MotionPrediction::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 10, &MotionPrediction::callbackGetCANInfo, this); - - UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); - PlannerHNS::ROSHelpers::InitPredMarkers(100, m_PredictedTrajectoriesDummy); - PlannerHNS::ROSHelpers::InitCurbsMarkers(100, m_CurbsDummy); - PlannerHNS::ROSHelpers::InitPredParticlesMarkers(500, m_PredictedParticlesDummy); - - //Mapping Section - sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &MotionPrediction::callbackGetVMLanes, this); - sub_points = nh.subscribe("/vector_map_info/point", 1, &MotionPrediction::callbackGetVMPoints, this); - sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &MotionPrediction::callbackGetVMdtLanes, this); - sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &MotionPrediction::callbackGetVMIntersections, this); - sup_area = nh.subscribe("/vector_map_info/area", 1, &MotionPrediction::callbackGetVMAreas, this); - sub_lines = nh.subscribe("/vector_map_info/line", 1, &MotionPrediction::callbackGetVMLines, this); - sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &MotionPrediction::callbackGetVMStopLines, this); - sub_signals = nh.subscribe("/vector_map_info/signal", 1, &MotionPrediction::callbackGetVMSignal, this); - sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &MotionPrediction::callbackGetVMVectors, this); - sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &MotionPrediction::callbackGetVMCurbs, this); - sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &MotionPrediction::callbackGetVMRoadEdges, this); - sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &MotionPrediction::callbackGetVMWayAreas, this); - sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &MotionPrediction::callbackGetVMCrossWalks, this); - sub_nodes = nh.subscribe("/vector_map_info/node", 1, &MotionPrediction::callbackGetVMNodes, this); - - std::cout << "OpenPlanner Motion Predictor initialized successfully " << std::endl; + bMap = false; + bNewCurrentPos = false; + bVehicleStatus = false; + bTrackedObjects = false; + m_bEnableCurbObstacles = false; + m_DistanceBetweenCurbs = 1.0; + m_VisualizationTime = 0.25; + m_bGoNextStep = false; + + ros::NodeHandle _nh; + UpdatePlanningParams(_nh); + + tf::StampedTransform transform; + PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_predicted_objects_trajectories = nh.advertise("/predicted_objects", 1); + pub_PredictedTrajectoriesRviz = nh.advertise("/predicted_trajectories_rviz", 1); + pub_CurbsRviz = nh.advertise("/map_curbs_rviz", 1); + pub_ParticlesRviz = nh.advertise("prediction_particles", 1); + + sub_StepSignal = nh.subscribe("/pred_step_signal", 1, &MotionPrediction::callbackGetStepForwardSignals, this); + sub_tracked_objects = nh.subscribe("/tracked_objects", 1, &MotionPrediction::callbackGetTrackedObjects, this); + sub_current_pose = nh.subscribe("/current_pose", 10, &MotionPrediction::callbackGetCurrentPose, this); + + int bVelSource = 1; + _nh.getParam("/op_motion_predictor/velocitySource", bVelSource); + if(bVelSource == 0) + sub_robot_odom = nh.subscribe("/odom", 10, &MotionPrediction::callbackGetRobotOdom, this); + else if(bVelSource == 1) + sub_current_velocity = nh.subscribe("/current_velocity", 10, &MotionPrediction::callbackGetVehicleStatus, this); + else if(bVelSource == 2) + sub_can_info = nh.subscribe("/can_info", 10, &MotionPrediction::callbackGetCANInfo, this); + + UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); + PlannerHNS::ROSHelpers::InitPredMarkers(100, m_PredictedTrajectoriesDummy); + PlannerHNS::ROSHelpers::InitCurbsMarkers(100, m_CurbsDummy); + PlannerHNS::ROSHelpers::InitPredParticlesMarkers(500, m_PredictedParticlesDummy); + + //Mapping Section + sub_lanes = nh.subscribe("/vector_map_info/lane", 1, &MotionPrediction::callbackGetVMLanes, this); + sub_points = nh.subscribe("/vector_map_info/point", 1, &MotionPrediction::callbackGetVMPoints, this); + sub_dt_lanes = nh.subscribe("/vector_map_info/dtlane", 1, &MotionPrediction::callbackGetVMdtLanes, this); + sub_intersect = nh.subscribe("/vector_map_info/cross_road", 1, &MotionPrediction::callbackGetVMIntersections, this); + sup_area = nh.subscribe("/vector_map_info/area", 1, &MotionPrediction::callbackGetVMAreas, this); + sub_lines = nh.subscribe("/vector_map_info/line", 1, &MotionPrediction::callbackGetVMLines, this); + sub_stop_line = nh.subscribe("/vector_map_info/stop_line", 1, &MotionPrediction::callbackGetVMStopLines, this); + sub_signals = nh.subscribe("/vector_map_info/signal", 1, &MotionPrediction::callbackGetVMSignal, this); + sub_vectors = nh.subscribe("/vector_map_info/vector", 1, &MotionPrediction::callbackGetVMVectors, this); + sub_curbs = nh.subscribe("/vector_map_info/curb", 1, &MotionPrediction::callbackGetVMCurbs, this); + sub_edges = nh.subscribe("/vector_map_info/road_edge", 1, &MotionPrediction::callbackGetVMRoadEdges, this); + sub_way_areas = nh.subscribe("/vector_map_info/way_area", 1, &MotionPrediction::callbackGetVMWayAreas, this); + sub_cross_walk = nh.subscribe("/vector_map_info/cross_walk", 1, &MotionPrediction::callbackGetVMCrossWalks, this); + sub_nodes = nh.subscribe("/vector_map_info/node", 1, &MotionPrediction::callbackGetVMNodes, this); + + std::cout << "OpenPlanner Motion Predictor initialized successfully " << std::endl; } MotionPrediction::~MotionPrediction() @@ -89,481 +89,481 @@ MotionPrediction::~MotionPrediction() void MotionPrediction::UpdatePlanningParams(ros::NodeHandle& _nh) { - _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); - if(m_PlanningParams.enableSwerving) - m_PlanningParams.enableFollowing = true; - else - _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); - - _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); - _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); - - _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); - _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); - _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); - - - _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); - _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); - if(m_PlanningParams.enableSwerving) - _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); - else - m_PlanningParams.rollOutNumber = 0; - - std::cout << "Rolls Number: " << m_PlanningParams.rollOutNumber << std::endl; - - _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); - _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); - _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); - _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); - _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); - - _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); - _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); - - _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); - - _nh.getParam("/op_common_params/width", m_CarInfo.width); - _nh.getParam("/op_common_params/length", m_CarInfo.length); - _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); - _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); - _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); - _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); - _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); - m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; - m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; - - int iSource = 0; - _nh.getParam("/op_common_params/mapSource" , iSource); - if(iSource == 0) - m_MapType = PlannerHNS::MAP_AUTOWARE; - else if (iSource == 1) - m_MapType = PlannerHNS::MAP_FOLDER; - else if(iSource == 2) - m_MapType = PlannerHNS::MAP_KML_FILE; - - _nh.getParam("/op_common_params/mapFileName" , m_MapPath); - - _nh.getParam("/op_motion_predictor/enableGenrateBranches" , m_PredictBeh.m_bGenerateBranches); - _nh.getParam("/op_motion_predictor/max_distance_to_lane" , m_PredictBeh.m_MaxLaneDetectionDistance); - _nh.getParam("/op_motion_predictor/prediction_distance" , m_PredictBeh.m_PredictionDistance); - _nh.getParam("/op_motion_predictor/enableCurbObstacles" , m_bEnableCurbObstacles); - _nh.getParam("/op_motion_predictor/distanceBetweenCurbs", m_DistanceBetweenCurbs); - _nh.getParam("/op_motion_predictor/visualizationTime", m_VisualizationTime); - _nh.getParam("/op_motion_predictor/enableStepByStepSignal", m_PredictBeh.m_bStepByStep ); - _nh.getParam("/op_motion_predictor/enableParticleFilterPrediction", m_PredictBeh.m_bParticleFilter); - - - UtilityHNS::UtilityH::GetTickCount(m_SensingTimer); + _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); + if(m_PlanningParams.enableSwerving) + m_PlanningParams.enableFollowing = true; + else + _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); + + _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); + _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); + + _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); + _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); + _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); + + + _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); + _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); + if(m_PlanningParams.enableSwerving) + _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); + else + m_PlanningParams.rollOutNumber = 0; + + std::cout << "Rolls Number: " << m_PlanningParams.rollOutNumber << std::endl; + + _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); + _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); + _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); + _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); + _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); + + _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); + _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); + + _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); + + _nh.getParam("/op_common_params/width", m_CarInfo.width); + _nh.getParam("/op_common_params/length", m_CarInfo.length); + _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); + _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); + _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); + _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); + _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); + m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; + m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; + + int iSource = 0; + _nh.getParam("/op_common_params/mapSource" , iSource); + if(iSource == 0) + m_MapType = PlannerHNS::MAP_AUTOWARE; + else if (iSource == 1) + m_MapType = PlannerHNS::MAP_FOLDER; + else if(iSource == 2) + m_MapType = PlannerHNS::MAP_KML_FILE; + + _nh.getParam("/op_common_params/mapFileName" , m_MapPath); + + _nh.getParam("/op_motion_predictor/enableGenrateBranches" , m_PredictBeh.m_bGenerateBranches); + _nh.getParam("/op_motion_predictor/max_distance_to_lane" , m_PredictBeh.m_MaxLaneDetectionDistance); + _nh.getParam("/op_motion_predictor/prediction_distance" , m_PredictBeh.m_PredictionDistance); + _nh.getParam("/op_motion_predictor/enableCurbObstacles" , m_bEnableCurbObstacles); + _nh.getParam("/op_motion_predictor/distanceBetweenCurbs", m_DistanceBetweenCurbs); + _nh.getParam("/op_motion_predictor/visualizationTime", m_VisualizationTime); + _nh.getParam("/op_motion_predictor/enableStepByStepSignal", m_PredictBeh.m_bStepByStep ); + _nh.getParam("/op_motion_predictor/enableParticleFilterPrediction", m_PredictBeh.m_bParticleFilter); + + + UtilityHNS::UtilityH::GetTickCount(m_SensingTimer); } void MotionPrediction::callbackGetStepForwardSignals(const geometry_msgs::TwistStampedConstPtr& msg) { - if(msg->twist.linear.x == 1) - m_bGoNextStep = true; - else - m_bGoNextStep = false; + if(msg->twist.linear.x == 1) + m_bGoNextStep = true; + else + m_bGoNextStep = false; } void MotionPrediction::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); - bNewCurrentPos = true; + m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + bNewCurrentPos = true; } void MotionPrediction::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed; - if(fabs(msg->twist.linear.x) > 0.25) - m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed; + if(fabs(msg->twist.linear.x) > 0.25) + m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void MotionPrediction::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleStatus.speed = msg->speed/3.6; - m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->speed/3.6; + m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void MotionPrediction::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.twist.linear.x; - m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.twist.linear.x; + m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void MotionPrediction::callbackGetTrackedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg) { - UtilityHNS::UtilityH::GetTickCount(m_SensingTimer); - m_TrackedObjects.clear(); - bTrackedObjects = true; - - PlannerHNS::DetectedObject obj; - - for(unsigned int i = 0 ; i objects.size(); i++) - { - if(msg->objects.at(i).id > 0) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); - m_TrackedObjects.push_back(obj); - } -// else -// { -// std::cout << " Ego Car avoid detecting itself from motion prediction node! ID: " << msg->objects.at(i).id << std::endl; -// } - - } - - if(bMap) - { - if(m_PredictBeh.m_bStepByStep && m_bGoNextStep) - { - m_bGoNextStep = false; - m_PredictBeh.DoOneStep(m_TrackedObjects, m_CurrentPos, m_PlanningParams.minSpeed, m_CarInfo.max_deceleration, m_Map); - } - else if(!m_PredictBeh.m_bStepByStep) - { - m_PredictBeh.DoOneStep(m_TrackedObjects, m_CurrentPos, m_PlanningParams.minSpeed, m_CarInfo.max_deceleration, m_Map); - } - - - m_PredictedResultsResults.objects.clear(); - autoware_msgs::DetectedObject pred_obj; - for(unsigned int i = 0 ; i obj, false, pred_obj); - if(m_PredictBeh.m_ParticleInfo_II.at(i)->best_beh_track) - pred_obj.behavior_state = m_PredictBeh.m_ParticleInfo_II.at(i)->best_beh_track->best_beh; - m_PredictedResultsResults.objects.push_back(pred_obj); - } - - if(m_bEnableCurbObstacles) - { - curr_curbs_obstacles.clear(); - GenerateCurbsObstacles(curr_curbs_obstacles); - //std::cout << "Curbs No: " << curr_curbs_obstacles.size() << endl; - for(unsigned int i = 0 ; i objects.size(); i++) + { + if(msg->objects.at(i).id > 0) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); + m_TrackedObjects.push_back(obj); + } +// else +// { +// std::cout << " Ego Car avoid detecting itself from motion prediction node! ID: " << msg->objects.at(i).id << std::endl; +// } + + } + + if(bMap) + { + if(m_PredictBeh.m_bStepByStep && m_bGoNextStep) + { + m_bGoNextStep = false; + m_PredictBeh.DoOneStep(m_TrackedObjects, m_CurrentPos, m_PlanningParams.minSpeed, m_CarInfo.max_deceleration, m_Map); + } + else if(!m_PredictBeh.m_bStepByStep) + { + m_PredictBeh.DoOneStep(m_TrackedObjects, m_CurrentPos, m_PlanningParams.minSpeed, m_CarInfo.max_deceleration, m_Map); + } + + + m_PredictedResultsResults.objects.clear(); + autoware_msgs::DetectedObject pred_obj; + for(unsigned int i = 0 ; i obj, false, pred_obj); + if(m_PredictBeh.m_ParticleInfo_II.at(i)->best_beh_track) + pred_obj.behavior_state = m_PredictBeh.m_ParticleInfo_II.at(i)->best_beh_track->best_beh; + m_PredictedResultsResults.objects.push_back(pred_obj); + } + + if(m_bEnableCurbObstacles) + { + curr_curbs_obstacles.clear(); + GenerateCurbsObstacles(curr_curbs_obstacles); + //std::cout << "Curbs No: " << curr_curbs_obstacles.size() << endl; + for(unsigned int i = 0 ; i & curb_obstacles) { - if(!bNewCurrentPos) return; - - for(unsigned int ic = 0; ic < m_Map.curbs.size(); ic++) - { - - if(m_Map.curbs.at(ic).points.size() > 0) - { - PlannerHNS::DetectedObject obj; - obj.center.pos = m_Map.curbs.at(ic).points.at(0); - - if(curb_obstacles.size()>0) - { - double distance_to_prev = hypot(curb_obstacles.at(curb_obstacles.size()-1).center.pos.y-obj.center.pos.y, curb_obstacles.at(curb_obstacles.size()-1).center.pos.x-obj.center.pos.x); - if(distance_to_prev < m_DistanceBetweenCurbs) - continue; - } - - double longitudinalDist = hypot(m_CurrentPos.pos.y -obj.center.pos.y, m_CurrentPos.pos.x-obj.center.pos.x); - - if(longitudinalDist > m_PlanningParams.horizonDistance) - continue; - - obj.bDirection = false; - obj.bVelocity = false; - obj.id = -1; - obj.t = PlannerHNS::SIDEWALK; - obj.label = "curb"; - for(unsigned int icp=0; icp< m_Map.curbs.at(ic).points.size(); icp++) - { - obj.contour.push_back(m_Map.curbs.at(ic).points.at(icp)); - } - - curb_obstacles.push_back(obj); - } - } + if(!bNewCurrentPos) return; + + for(unsigned int ic = 0; ic < m_Map.curbs.size(); ic++) + { + + if(m_Map.curbs.at(ic).points.size() > 0) + { + PlannerHNS::DetectedObject obj; + obj.center.pos = m_Map.curbs.at(ic).points.at(0); + + if(curb_obstacles.size()>0) + { + double distance_to_prev = hypot(curb_obstacles.at(curb_obstacles.size()-1).center.pos.y-obj.center.pos.y, curb_obstacles.at(curb_obstacles.size()-1).center.pos.x-obj.center.pos.x); + if(distance_to_prev < m_DistanceBetweenCurbs) + continue; + } + + double longitudinalDist = hypot(m_CurrentPos.pos.y -obj.center.pos.y, m_CurrentPos.pos.x-obj.center.pos.x); + + if(longitudinalDist > m_PlanningParams.horizonDistance) + continue; + + obj.bDirection = false; + obj.bVelocity = false; + obj.id = -1; + obj.t = PlannerHNS::SIDEWALK; + obj.label = "curb"; + for(unsigned int icp=0; icp< m_Map.curbs.at(ic).points.size(); icp++) + { + obj.contour.push_back(m_Map.curbs.at(ic).points.at(icp)); + } + + curb_obstacles.push_back(obj); + } + } } void MotionPrediction::VisualizePrediction() { -// m_all_pred_paths.clear(); -// for(unsigned int i=0; i< m_PredictBeh.m_PredictedObjects.size(); i++) -// m_all_pred_paths.insert(m_all_pred_paths.begin(), m_PredictBeh.m_PredictedObjects.at(i).predTrajectories.begin(), m_PredictBeh.m_PredictedObjects.at(i).predTrajectories.end()); +// m_all_pred_paths.clear(); +// for(unsigned int i=0; i< m_PredictBeh.m_PredictedObjects.size(); i++) +// m_all_pred_paths.insert(m_all_pred_paths.begin(), m_PredictBeh.m_PredictedObjects.at(i).predTrajectories.begin(), m_PredictBeh.m_PredictedObjects.at(i).predTrajectories.end()); // -// PlannerHNS::ROSHelpers::ConvertPredictedTrqajectoryMarkers(m_all_pred_paths, m_PredictedTrajectoriesActual, m_PredictedTrajectoriesDummy); -// pub_PredictedTrajectoriesRviz.publish(m_PredictedTrajectoriesActual); +// PlannerHNS::ROSHelpers::ConvertPredictedTrajectoriesMarkers(m_all_pred_paths, m_PredictedTrajectoriesActual, m_PredictedTrajectoriesDummy); +// pub_PredictedTrajectoriesRviz.publish(m_PredictedTrajectoriesActual); // - PlannerHNS::ROSHelpers::ConvertCurbsMarkers(curr_curbs_obstacles, m_CurbsActual, m_CurbsDummy); - pub_CurbsRviz.publish(m_CurbsActual); - - m_all_pred_paths.clear(); - m_particles_points.clear(); - visualization_msgs::MarkerArray behavior_rviz_arr; - int number_of_particles = 0; - for(unsigned int i=0; i< m_PredictBeh.m_ParticleInfo_II.size(); i++) - { - m_all_pred_paths.insert(m_all_pred_paths.begin(), m_PredictBeh.m_ParticleInfo_II.at(i)->obj.predTrajectories.begin(), m_PredictBeh.m_ParticleInfo_II.at(i)->obj.predTrajectories.end()); - - for(unsigned int t=0; t < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.size(); t++) - { - PlannerHNS::WayPoint p_wp; - for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_StopPart.size(); j++) - { - p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_StopPart.at(j).pose; - p_wp.bDir = PlannerHNS::STANDSTILL_DIR; - m_particles_points.push_back(p_wp); - number_of_particles++; - } - - for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_YieldPart.size(); j++) - { - p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_YieldPart.at(j).pose; - p_wp.bDir = PlannerHNS::BACKWARD_DIR; - m_particles_points.push_back(p_wp); - number_of_particles++; - } - - if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_FORWARD_STATE) - { - for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_ForwardPart.size(); j++) - { - p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_ForwardPart.at(j).pose; - p_wp.bDir = PlannerHNS::FORWARD_DIR; - m_particles_points.push_back(p_wp); - number_of_particles++; - } - } - - if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_BRANCH_LEFT_STATE) - { - //std::cout << "Left Particles : " << m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.size() << std::endl; - for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.size(); j++) - { - p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.at(j).pose; - p_wp.bDir = PlannerHNS::FORWARD_LEFT_DIR; - m_particles_points.push_back(p_wp); - number_of_particles++; - } - } - - if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE) - { - for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_RightPart.size(); j++) - { - p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_RightPart.at(j).pose; - p_wp.bDir = PlannerHNS::FORWARD_RIGHT_DIR; - m_particles_points.push_back(p_wp); - number_of_particles++; - } - } - } - - -// visualization_msgs::Marker behavior_rviz; -// std::ostringstream ns_beh; -// ns_beh << "pred_beh_state_" << i; -// ROSHelpers::VisualizeBehaviorState(m_PredictBeh.m_ParticleInfo_II.at(i).obj.center, m_PredictBeh.m_ParticleInfo_II.at(i).m_beh, false , 0, behavior_rviz, ns_beh.str(), 3); -// behavior_rviz_arr.markers.push_back(behavior_rviz); - - } - -// pub_PredBehaviorStateRviz.publish(behavior_rviz_arr); - - PlannerHNS::ROSHelpers::ConvertParticles(m_particles_points,m_PredictedParticlesActual, m_PredictedParticlesDummy); - //std::cout << "Original Particles: " << number_of_particles << ", Total Particles Num: " << m_PredictedParticlesActual.markers.size() << std::endl; - pub_ParticlesRviz.publish(m_PredictedParticlesActual); - - //std::cout << "Start Tracking of Trajectories : " << m_all_pred_paths.size() << endl; - PlannerHNS::ROSHelpers::ConvertPredictedTrqajectoryMarkers(m_all_pred_paths, m_PredictedTrajectoriesActual, m_PredictedTrajectoriesDummy); - pub_PredictedTrajectoriesRviz.publish(m_PredictedTrajectoriesActual); - - UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); + PlannerHNS::ROSHelpers::ConvertCurbsMarkers(curr_curbs_obstacles, m_CurbsActual, m_CurbsDummy); + pub_CurbsRviz.publish(m_CurbsActual); + + m_all_pred_paths.clear(); + m_particles_points.clear(); + visualization_msgs::MarkerArray behavior_rviz_arr; + int number_of_particles = 0; + for(unsigned int i=0; i< m_PredictBeh.m_ParticleInfo_II.size(); i++) + { + m_all_pred_paths.insert(m_all_pred_paths.begin(), m_PredictBeh.m_ParticleInfo_II.at(i)->obj.predTrajectories.begin(), m_PredictBeh.m_ParticleInfo_II.at(i)->obj.predTrajectories.end()); + + for(unsigned int t=0; t < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.size(); t++) + { + PlannerHNS::WayPoint p_wp; + for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_StopPart.size(); j++) + { + p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_StopPart.at(j).pose; + p_wp.bDir = PlannerHNS::STANDSTILL_DIR; + m_particles_points.push_back(p_wp); + number_of_particles++; + } + + for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_YieldPart.size(); j++) + { + p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_YieldPart.at(j).pose; + p_wp.bDir = PlannerHNS::BACKWARD_DIR; + m_particles_points.push_back(p_wp); + number_of_particles++; + } + + if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_FORWARD_STATE) + { + for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_ForwardPart.size(); j++) + { + p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_ForwardPart.at(j).pose; + p_wp.bDir = PlannerHNS::FORWARD_DIR; + m_particles_points.push_back(p_wp); + number_of_particles++; + } + } + + if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_BRANCH_LEFT_STATE) + { + //std::cout << "Left Particles : " << m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.size() << std::endl; + for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.size(); j++) + { + p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_LeftPart.at(j).pose; + p_wp.bDir = PlannerHNS::FORWARD_LEFT_DIR; + m_particles_points.push_back(p_wp); + number_of_particles++; + } + } + + if(m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->beh == PlannerHNS::BEH_BRANCH_RIGHT_STATE) + { + for(unsigned int j=0; j < m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_RightPart.size(); j++) + { + p_wp = m_PredictBeh.m_ParticleInfo_II.at(i)->m_TrajectoryTracker.at(t)->m_RightPart.at(j).pose; + p_wp.bDir = PlannerHNS::FORWARD_RIGHT_DIR; + m_particles_points.push_back(p_wp); + number_of_particles++; + } + } + } + + +// visualization_msgs::Marker behavior_rviz; +// std::ostringstream ns_beh; +// ns_beh << "pred_beh_state_" << i; +// ROSHelpers::VisualizeBehaviorState(m_PredictBeh.m_ParticleInfo_II.at(i).obj.center, m_PredictBeh.m_ParticleInfo_II.at(i).m_beh, false , 0, behavior_rviz, ns_beh.str(), 3); +// behavior_rviz_arr.markers.push_back(behavior_rviz); + + } + +// pub_PredBehaviorStateRviz.publish(behavior_rviz_arr); + + PlannerHNS::ROSHelpers::ConvertParticles(m_particles_points,m_PredictedParticlesActual, m_PredictedParticlesDummy); + //std::cout << "Original Particles: " << number_of_particles << ", Total Particles Num: " << m_PredictedParticlesActual.markers.size() << std::endl; + pub_ParticlesRviz.publish(m_PredictedParticlesActual); + + //std::cout << "Start Tracking of Trajectories : " << m_all_pred_paths.size() << endl; + PlannerHNS::ROSHelpers::ConvertPredictedTrajectoriesMarkers(m_all_pred_paths, m_PredictedTrajectoriesActual, m_PredictedTrajectoriesDummy); + pub_PredictedTrajectoriesRviz.publish(m_PredictedTrajectoriesActual); + + UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); } void MotionPrediction::MainLoop() { - ros::Rate loop_rate(25); - - while (ros::ok()) - { - ros::spinOnce(); - - if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); - } - else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); - } - else if (m_MapType == PlannerHNS::MAP_AUTOWARE && !bMap) - { - std::vector conn_data;; - - if(m_MapRaw.GetVersion()==2) - { - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, - m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, true); - - if(m_Map.roadSegments.size() > 0) - { - bMap = true; - std::cout << " ******* Map V2 Is Loaded successfully from the Motion Predictor !! " << std::endl; - } - } - else if(m_MapRaw.GetVersion()==1) - { - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, - m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, - m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, - m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, - m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true); - - if(m_Map.roadSegments.size() > 0) - { - bMap = true; - std::cout << " ******* Map V1 Is Loaded successfully from the Motion Predictor !! " << std::endl; - } - } - } - - if(UtilityHNS::UtilityH::GetTimeDiffNow(m_VisualizationTimer) > m_VisualizationTime) - { - VisualizePrediction(); - UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); - } - - //For the debugging of prediction -// if(UtilityHNS::UtilityH::GetTimeDiffNow(m_SensingTimer) > 5) -// { -// ROS_INFO("op_motion_prediction sensing timeout, can't receive tracked object data ! Reset .. Reset"); -// m_PredictedResultsResults.objects.clear(); -// pub_predicted_objects_trajectories.publish(m_PredictedResultsResults); -// } - - loop_rate.sleep(); - } + ros::Rate loop_rate(25); + + while (ros::ok()) + { + ros::spinOnce(); + + if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); + } + else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); + } + else if (m_MapType == PlannerHNS::MAP_AUTOWARE && !bMap) + { + std::vector conn_data;; + + if(m_MapRaw.GetVersion()==2) + { + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessageV2(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, + m_MapRaw.pLanes, m_MapRaw.pPoints, m_MapRaw.pNodes, m_MapRaw.pLines, PlannerHNS::GPSPoint(), m_Map, true, m_PlanningParams.enableLaneChange, true); + + if(m_Map.roadSegments.size() > 0) + { + bMap = true; + std::cout << " ******* Map V2 Is Loaded successfully from the Motion Predictor !! " << std::endl; + } + } + else if(m_MapRaw.GetVersion()==1) + { + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(m_MapRaw.pLanes->m_data_list, m_MapRaw.pPoints->m_data_list, + m_MapRaw.pCenterLines->m_data_list, m_MapRaw.pIntersections->m_data_list,m_MapRaw.pAreas->m_data_list, + m_MapRaw.pLines->m_data_list, m_MapRaw.pStopLines->m_data_list, m_MapRaw.pSignals->m_data_list, + m_MapRaw.pVectors->m_data_list, m_MapRaw.pCurbs->m_data_list, m_MapRaw.pRoadedges->m_data_list, m_MapRaw.pWayAreas->m_data_list, + m_MapRaw.pCrossWalks->m_data_list, m_MapRaw.pNodes->m_data_list, conn_data, PlannerHNS::GPSPoint(), m_Map, true); + + if(m_Map.roadSegments.size() > 0) + { + bMap = true; + std::cout << " ******* Map V1 Is Loaded successfully from the Motion Predictor !! " << std::endl; + } + } + } + + if(UtilityHNS::UtilityH::GetTimeDiffNow(m_VisualizationTimer) > m_VisualizationTime) + { + VisualizePrediction(); + UtilityHNS::UtilityH::GetTickCount(m_VisualizationTimer); + } + + //For the debugging of prediction +// if(UtilityHNS::UtilityH::GetTimeDiffNow(m_SensingTimer) > 5) +// { +// ROS_INFO("op_motion_prediction sensing timeout, can't receive tracked object data ! Reset .. Reset"); +// m_PredictedResultsResults.objects.clear(); +// pub_predicted_objects_trajectories.publish(m_PredictedResultsResults); +// } + + loop_rate.sleep(); + } } //Mapping Section void MotionPrediction::callbackGetVMLanes(const vector_map_msgs::LaneArray& msg) { - std::cout << "Received Lanes" << endl; - if(m_MapRaw.pLanes == nullptr) - m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); + std::cout << "Received Lanes" << endl; + if(m_MapRaw.pLanes == nullptr) + m_MapRaw.pLanes = new UtilityHNS::AisanLanesFileReader(msg); } void MotionPrediction::callbackGetVMPoints(const vector_map_msgs::PointArray& msg) { - std::cout << "Received Points" << endl; - if(m_MapRaw.pPoints == nullptr) - m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); + std::cout << "Received Points" << endl; + if(m_MapRaw.pPoints == nullptr) + m_MapRaw.pPoints = new UtilityHNS::AisanPointsFileReader(msg); } void MotionPrediction::callbackGetVMdtLanes(const vector_map_msgs::DTLaneArray& msg) { - std::cout << "Received dtLanes" << endl; - if(m_MapRaw.pCenterLines == nullptr) - m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); + std::cout << "Received dtLanes" << endl; + if(m_MapRaw.pCenterLines == nullptr) + m_MapRaw.pCenterLines = new UtilityHNS::AisanCenterLinesFileReader(msg); } void MotionPrediction::callbackGetVMIntersections(const vector_map_msgs::CrossRoadArray& msg) { - std::cout << "Received CrossRoads" << endl; - if(m_MapRaw.pIntersections == nullptr) - m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); + std::cout << "Received CrossRoads" << endl; + if(m_MapRaw.pIntersections == nullptr) + m_MapRaw.pIntersections = new UtilityHNS::AisanIntersectionFileReader(msg); } void MotionPrediction::callbackGetVMAreas(const vector_map_msgs::AreaArray& msg) { - std::cout << "Received Areas" << endl; - if(m_MapRaw.pAreas == nullptr) - m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); + std::cout << "Received Areas" << endl; + if(m_MapRaw.pAreas == nullptr) + m_MapRaw.pAreas = new UtilityHNS::AisanAreasFileReader(msg); } void MotionPrediction::callbackGetVMLines(const vector_map_msgs::LineArray& msg) { - std::cout << "Received Lines" << endl; - if(m_MapRaw.pLines == nullptr) - m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); + std::cout << "Received Lines" << endl; + if(m_MapRaw.pLines == nullptr) + m_MapRaw.pLines = new UtilityHNS::AisanLinesFileReader(msg); } void MotionPrediction::callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg) { - std::cout << "Received StopLines" << endl; - if(m_MapRaw.pStopLines == nullptr) - m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); + std::cout << "Received StopLines" << endl; + if(m_MapRaw.pStopLines == nullptr) + m_MapRaw.pStopLines = new UtilityHNS::AisanStopLineFileReader(msg); } void MotionPrediction::callbackGetVMSignal(const vector_map_msgs::SignalArray& msg) { - std::cout << "Received Signals" << endl; - if(m_MapRaw.pSignals == nullptr) - m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); + std::cout << "Received Signals" << endl; + if(m_MapRaw.pSignals == nullptr) + m_MapRaw.pSignals = new UtilityHNS::AisanSignalFileReader(msg); } void MotionPrediction::callbackGetVMVectors(const vector_map_msgs::VectorArray& msg) { - std::cout << "Received Vectors" << endl; - if(m_MapRaw.pVectors == nullptr) - m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); + std::cout << "Received Vectors" << endl; + if(m_MapRaw.pVectors == nullptr) + m_MapRaw.pVectors = new UtilityHNS::AisanVectorFileReader(msg); } void MotionPrediction::callbackGetVMCurbs(const vector_map_msgs::CurbArray& msg) { - std::cout << "Received Curbs" << endl; - if(m_MapRaw.pCurbs == nullptr) - m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); + std::cout << "Received Curbs" << endl; + if(m_MapRaw.pCurbs == nullptr) + m_MapRaw.pCurbs = new UtilityHNS::AisanCurbFileReader(msg); } void MotionPrediction::callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArray& msg) { - std::cout << "Received Edges" << endl; - if(m_MapRaw.pRoadedges == nullptr) - m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); + std::cout << "Received Edges" << endl; + if(m_MapRaw.pRoadedges == nullptr) + m_MapRaw.pRoadedges = new UtilityHNS::AisanRoadEdgeFileReader(msg); } void MotionPrediction::callbackGetVMWayAreas(const vector_map_msgs::WayAreaArray& msg) { - std::cout << "Received Wayareas" << endl; - if(m_MapRaw.pWayAreas == nullptr) - m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); + std::cout << "Received Wayareas" << endl; + if(m_MapRaw.pWayAreas == nullptr) + m_MapRaw.pWayAreas = new UtilityHNS::AisanWayareaFileReader(msg); } void MotionPrediction::callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArray& msg) { - std::cout << "Received CrossWalks" << endl; - if(m_MapRaw.pCrossWalks == nullptr) - m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); + std::cout << "Received CrossWalks" << endl; + if(m_MapRaw.pCrossWalks == nullptr) + m_MapRaw.pCrossWalks = new UtilityHNS::AisanCrossWalkFileReader(msg); } void MotionPrediction::callbackGetVMNodes(const vector_map_msgs::NodeArray& msg) { - std::cout << "Received Nodes" << endl; - if(m_MapRaw.pNodes == nullptr) - m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); + std::cout << "Received Nodes" << endl; + if(m_MapRaw.pNodes == nullptr) + m_MapRaw.pNodes = new UtilityHNS::AisanNodesFileReader(msg); } } diff --git a/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator.cpp b/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator.cpp index fb89bd122d1..c43a881f3fc 100644 --- a/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator.cpp +++ b/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator.cpp @@ -23,8 +23,8 @@ using namespace std; int main(int argc, char **argv) { - ros::init(argc, argv, "op_trajectory_evaluator"); - TrajectoryEvaluatorNS::TrajectoryEval trajectory_eval; - trajectory_eval.MainLoop(); - return 0; + ros::init(argc, argv, "op_trajectory_evaluator"); + TrajectoryEvaluatorNS::TrajectoryEval trajectory_eval; + trajectory_eval.MainLoop(); + return 0; } diff --git a/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator_core.cpp b/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator_core.cpp index 27c92a8515c..df3f2e73e2b 100644 --- a/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator_core.cpp +++ b/core_planning/op_local_planner/nodes/op_trajectory_evaluator/op_trajectory_evaluator_core.cpp @@ -23,44 +23,44 @@ namespace TrajectoryEvaluatorNS TrajectoryEval::TrajectoryEval() { - bNewCurrentPos = false; - bVehicleStatus = false; - bWayGlobalPath = false; - bWayGlobalPathToUse = false; - m_bUseMoveingObjectsPrediction = false; - - ros::NodeHandle _nh; - UpdatePlanningParams(_nh); - - tf::StampedTransform transform; - PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_CollisionPointsRviz = nh.advertise("dynamic_collision_points_rviz", 1); - pub_LocalWeightedTrajectoriesRviz = nh.advertise("local_trajectories_eval_rviz", 1); - pub_LocalWeightedTrajectories = nh.advertise("local_weighted_trajectories", 1); - pub_TrajectoryCost = nh.advertise("local_trajectory_cost", 1); - pub_SafetyBorderRviz = nh.advertise("safety_border", 1); - - sub_current_pose = nh.subscribe("/current_pose", 10, &TrajectoryEval::callbackGetCurrentPose, this); - - int bVelSource = 1; - _nh.getParam("/op_trajectory_evaluator/velocitySource", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 10, &TrajectoryEval::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 10, &TrajectoryEval::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 10, &TrajectoryEval::callbackGetCANInfo, this); - - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryEval::callbackGetGlobalPlannerPath, this); - sub_LocalPlannerPaths = nh.subscribe("/local_trajectories", 1, &TrajectoryEval::callbackGetLocalPlannerPath, this); - sub_predicted_objects = nh.subscribe("/predicted_objects", 1, &TrajectoryEval::callbackGetPredictedObjects, this); - sub_current_behavior = nh.subscribe("/current_behavior", 1, &TrajectoryEval::callbackGetBehaviorState, this); - - PlannerHNS::ROSHelpers::InitCollisionPointsMarkers(50, m_CollisionsDummy); + bNewCurrentPos = false; + bVehicleStatus = false; + bWayGlobalPath = false; + bWayGlobalPathToUse = false; + m_bUseMoveingObjectsPrediction = false; + + ros::NodeHandle _nh; + UpdatePlanningParams(_nh); + + tf::StampedTransform transform; + PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_CollisionPointsRviz = nh.advertise("dynamic_collision_points_rviz", 1); + pub_LocalWeightedTrajectoriesRviz = nh.advertise("local_trajectories_eval_rviz", 1); + pub_LocalWeightedTrajectories = nh.advertise("local_weighted_trajectories", 1); + pub_TrajectoryCost = nh.advertise("local_trajectory_cost", 1); + pub_SafetyBorderRviz = nh.advertise("safety_border", 1); + + sub_current_pose = nh.subscribe("/current_pose", 10, &TrajectoryEval::callbackGetCurrentPose, this); + + int bVelSource = 1; + _nh.getParam("/op_trajectory_evaluator/velocitySource", bVelSource); + if(bVelSource == 0) + sub_robot_odom = nh.subscribe("/odom", 10, &TrajectoryEval::callbackGetRobotOdom, this); + else if(bVelSource == 1) + sub_current_velocity = nh.subscribe("/current_velocity", 10, &TrajectoryEval::callbackGetVehicleStatus, this); + else if(bVelSource == 2) + sub_can_info = nh.subscribe("/can_info", 10, &TrajectoryEval::callbackGetCANInfo, this); + + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryEval::callbackGetGlobalPlannerPath, this); + sub_LocalPlannerPaths = nh.subscribe("/local_trajectories", 1, &TrajectoryEval::callbackGetLocalPlannerPath, this); + sub_predicted_objects = nh.subscribe("/predicted_objects", 1, &TrajectoryEval::callbackGetPredictedObjects, this); + sub_current_behavior = nh.subscribe("/current_behavior", 1, &TrajectoryEval::callbackGetBehaviorState, this); + + PlannerHNS::ROSHelpers::InitCollisionPointsMarkers(50, m_CollisionsDummy); } TrajectoryEval::~TrajectoryEval() @@ -69,260 +69,260 @@ TrajectoryEval::~TrajectoryEval() void TrajectoryEval::UpdatePlanningParams(ros::NodeHandle& _nh) { - _nh.getParam("/op_trajectory_evaluator/enablePrediction", m_bUseMoveingObjectsPrediction); - - _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); - _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); - _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); - if(m_PlanningParams.enableSwerving) - m_PlanningParams.enableFollowing = true; - else - _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); - - _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); - _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); - - _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); - _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); - _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); - - _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); - - _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); - if(m_PlanningParams.enableSwerving) - _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); - else - m_PlanningParams.rollOutNumber = 0; - - std::cout << "Rolls Number: " << m_PlanningParams.rollOutNumber << std::endl; - - _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); - _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); - _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); - _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); - _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); - - _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); - - _nh.getParam("/op_common_params/width", m_CarInfo.width); - _nh.getParam("/op_common_params/length", m_CarInfo.length); - _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); - _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); - _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); - _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); - _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); - m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; - m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; + _nh.getParam("/op_trajectory_evaluator/enablePrediction", m_bUseMoveingObjectsPrediction); + + _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); + _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); + _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); + if(m_PlanningParams.enableSwerving) + m_PlanningParams.enableFollowing = true; + else + _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); + + _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); + _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); + + _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); + _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); + _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); + + _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); + + _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); + if(m_PlanningParams.enableSwerving) + _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); + else + m_PlanningParams.rollOutNumber = 0; + + std::cout << "Rolls Number: " << m_PlanningParams.rollOutNumber << std::endl; + + _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); + _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); + _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); + _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); + _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); + + _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); + + _nh.getParam("/op_common_params/width", m_CarInfo.width); + _nh.getParam("/op_common_params/length", m_CarInfo.length); + _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); + _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); + _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); + _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); + _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); + m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; + m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; } void TrajectoryEval::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); - bNewCurrentPos = true; + m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + bNewCurrentPos = true; } void TrajectoryEval::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed; - if(fabs(msg->twist.linear.x) > 0.25) - m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed; + if(fabs(msg->twist.linear.x) > 0.25) + m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryEval::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleStatus.speed = msg->speed/3.6; - m_CurrentPos.v = m_VehicleStatus.speed; - m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->speed/3.6; + m_CurrentPos.v = m_VehicleStatus.speed; + m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryEval::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed; - if(fabs(msg->twist.twist.linear.x) > 0.25) - m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed; + if(fabs(msg->twist.twist.linear.x) > 0.25) + m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryEval::callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg) { - if(msg->lanes.size() > 0) - { - - bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); - - m_GlobalPaths.clear(); - - for(unsigned int i = 0 ; i < msg->lanes.size(); i++) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); - - PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); - m_GlobalPaths.push_back(m_temp_path); - - if(bOldGlobalPath) - { - bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); - } - } - - if(!bOldGlobalPath) - { - bWayGlobalPath = true; - std::cout << "Received New Global Path Evaluator! " << std::endl; - } - else - { - m_GlobalPaths.clear(); - } - } + if(msg->lanes.size() > 0) + { + + bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); + + m_GlobalPaths.clear(); + + for(unsigned int i = 0 ; i < msg->lanes.size(); i++) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); + + PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); + m_GlobalPaths.push_back(m_temp_path); + + if(bOldGlobalPath) + { + bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); + } + } + + if(!bOldGlobalPath) + { + bWayGlobalPath = true; + std::cout << "Received New Global Path Evaluator! " << std::endl; + } + else + { + m_GlobalPaths.clear(); + } + } } void TrajectoryEval::callbackGetLocalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg) { - if(msg->lanes.size() > 0) - { - m_GeneratedRollOuts.clear(); - int globalPathId_roll_outs = -1; - - for(unsigned int i = 0 ; i < msg->lanes.size(); i++) - { - std::vector path; - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), path); - m_GeneratedRollOuts.push_back(path); - if(path.size() > 0) - globalPathId_roll_outs = path.at(0).gid; - } - - if(bWayGlobalPath && m_GlobalPaths.size() > 0 && m_GlobalPaths.at(0).size() > 0) - { - int globalPathId = m_GlobalPaths.at(0).at(0).gid; - std::cout << "Before Synchronization At Trajectory Evaluator: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; - - if(globalPathId_roll_outs == globalPathId) - { - bWayGlobalPath = false; - m_GlobalPathsToUse = m_GlobalPaths; - std::cout << "Synchronization At Trajectory Evaluator: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; - } - } - - bRollOuts = true; - } + if(msg->lanes.size() > 0) + { + m_GeneratedRollOuts.clear(); + int globalPathId_roll_outs = -1; + + for(unsigned int i = 0 ; i < msg->lanes.size(); i++) + { + std::vector path; + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), path); + m_GeneratedRollOuts.push_back(path); + if(path.size() > 0) + globalPathId_roll_outs = path.at(0).gid; + } + + if(bWayGlobalPath && m_GlobalPaths.size() > 0 && m_GlobalPaths.at(0).size() > 0) + { + int globalPathId = m_GlobalPaths.at(0).at(0).gid; + std::cout << "Before Synchronization At Trajectory Evaluator: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; + + if(globalPathId_roll_outs == globalPathId) + { + bWayGlobalPath = false; + m_GlobalPathsToUse = m_GlobalPaths; + std::cout << "Synchronization At Trajectory Evaluator: GlobalID: " << globalPathId << ", LocalID: " << globalPathId_roll_outs << std::endl; + } + } + + bRollOuts = true; + } } void TrajectoryEval::callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg) { - m_PredictedObjects.clear(); - bPredictedObjects = true; - - PlannerHNS::DetectedObject obj; - for(unsigned int i = 0 ; i objects.size(); i++) - { - if(msg->objects.at(i).id > 0) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); - m_PredictedObjects.push_back(obj); - } -// else -// { -// std::cout << " Ego Car avoid detecting itself in trajectory evaluator node! ID: " << msg->objects.at(i).id << std::endl; -// } - } + m_PredictedObjects.clear(); + bPredictedObjects = true; + + PlannerHNS::DetectedObject obj; + for(unsigned int i = 0 ; i objects.size(); i++) + { + if(msg->objects.at(i).id > 0) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); + m_PredictedObjects.push_back(obj); + } +// else +// { +// std::cout << " Ego Car avoid detecting itself in trajectory evaluator node! ID: " << msg->objects.at(i).id << std::endl; +// } + } } void TrajectoryEval::callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr& msg) { - m_CurrentBehavior.iTrajectory = msg->twist.angular.z; + m_CurrentBehavior.iTrajectory = msg->twist.angular.z; } void TrajectoryEval::MainLoop() { - ros::Rate loop_rate(100); - - PlannerHNS::WayPoint prevState, state_change; - - while (ros::ok()) - { - ros::spinOnce(); - PlannerHNS::TrajectoryCost tc; - - if(bNewCurrentPos && m_GlobalPaths.size()>0) - { - m_GlobalPathSections.clear(); - - for(unsigned int i = 0; i < m_GlobalPathsToUse.size(); i++) - { - t_centerTrajectorySmoothed.clear(); - PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_GlobalPathsToUse.at(i), m_CurrentPos, m_PlanningParams.horizonDistance , m_PlanningParams.pathDensity ,t_centerTrajectorySmoothed); - m_GlobalPathSections.push_back(t_centerTrajectorySmoothed); - } - - if(m_GlobalPathSections.size()>0) - { - if(m_bUseMoveingObjectsPrediction) - tc = m_TrajectoryCostsCalculator.DoOneStepDynamic(m_GeneratedRollOuts, m_GlobalPathSections.at(0), m_CurrentPos,m_PlanningParams, m_CarInfo,m_VehicleStatus, m_PredictedObjects, m_CurrentBehavior.iTrajectory); - else - tc = m_TrajectoryCostsCalculator.DoOneStepStatic(m_GeneratedRollOuts, m_GlobalPathSections.at(0), m_CurrentPos, m_PlanningParams, m_CarInfo,m_VehicleStatus, m_PredictedObjects); - - autoware_msgs::Lane l; - l.closest_object_distance = tc.closest_obj_distance; - l.closest_object_velocity = tc.closest_obj_velocity; - l.cost = tc.cost; - l.is_blocked = tc.bBlocked; - l.lane_index = tc.index; - pub_TrajectoryCost.publish(l); - } - - if(m_TrajectoryCostsCalculator.m_TrajectoryCosts.size() == m_GeneratedRollOuts.size()) - { - autoware_msgs::LaneArray local_lanes; - for(unsigned int i=0; i < m_GeneratedRollOuts.size(); i++) - { - autoware_msgs::Lane lane; - PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_GeneratedRollOuts.at(i), lane); - lane.closest_object_distance = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).closest_obj_distance; - lane.closest_object_velocity = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).closest_obj_velocity; - lane.cost = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).cost; - lane.is_blocked = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).bBlocked; - lane.lane_index = i; - local_lanes.lanes.push_back(lane); - } - - pub_LocalWeightedTrajectories.publish(local_lanes); - } - else - { - ROS_ERROR("m_TrajectoryCosts.size() Not Equal m_GeneratedRollOuts.size()"); - } - - if(m_TrajectoryCostsCalculator.m_TrajectoryCosts.size()>0) - { - visualization_msgs::MarkerArray all_rollOuts; - PlannerHNS::ROSHelpers::TrajectoriesToColoredMarkers(m_GeneratedRollOuts, m_TrajectoryCostsCalculator.m_TrajectoryCosts, m_CurrentBehavior.iTrajectory, all_rollOuts); - pub_LocalWeightedTrajectoriesRviz.publish(all_rollOuts); - - PlannerHNS::ROSHelpers::ConvertCollisionPointsMarkers(m_TrajectoryCostsCalculator.m_CollisionPoints, m_CollisionsActual, m_CollisionsDummy); - pub_CollisionPointsRviz.publish(m_CollisionsActual); - - //Visualize Safety Box - visualization_msgs::Marker safety_box; - PlannerHNS::ROSHelpers::ConvertFromPlannerHRectangleToAutowareRviz(m_TrajectoryCostsCalculator.m_SafetyBorder.points, safety_box); - pub_SafetyBorderRviz.publish(safety_box); - } - } - else - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryEval::callbackGetGlobalPlannerPath, this); - - loop_rate.sleep(); - } + ros::Rate loop_rate(100); + + PlannerHNS::WayPoint prevState, state_change; + + while (ros::ok()) + { + ros::spinOnce(); + PlannerHNS::TrajectoryCost tc; + + if(bNewCurrentPos && m_GlobalPaths.size()>0) + { + m_GlobalPathSections.clear(); + + for(unsigned int i = 0; i < m_GlobalPathsToUse.size(); i++) + { + t_centerTrajectorySmoothed.clear(); + PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_GlobalPathsToUse.at(i), m_CurrentPos, m_PlanningParams.horizonDistance , m_PlanningParams.pathDensity ,t_centerTrajectorySmoothed); + m_GlobalPathSections.push_back(t_centerTrajectorySmoothed); + } + + if(m_GlobalPathSections.size()>0) + { + if(m_bUseMoveingObjectsPrediction) + tc = m_TrajectoryCostsCalculator.DoOneStepDynamic(m_GeneratedRollOuts, m_GlobalPathSections.at(0), m_CurrentPos,m_PlanningParams, m_CarInfo,m_VehicleStatus, m_PredictedObjects, m_CurrentBehavior.iTrajectory); + else + tc = m_TrajectoryCostsCalculator.DoOneStepStatic(m_GeneratedRollOuts, m_GlobalPathSections.at(0), m_CurrentPos, m_PlanningParams, m_CarInfo,m_VehicleStatus, m_PredictedObjects); + + autoware_msgs::Lane l; + l.closest_object_distance = tc.closest_obj_distance; + l.closest_object_velocity = tc.closest_obj_velocity; + l.cost = tc.cost; + l.is_blocked = tc.bBlocked; + l.lane_index = tc.index; + pub_TrajectoryCost.publish(l); + } + + if(m_TrajectoryCostsCalculator.m_TrajectoryCosts.size() == m_GeneratedRollOuts.size()) + { + autoware_msgs::LaneArray local_lanes; + for(unsigned int i=0; i < m_GeneratedRollOuts.size(); i++) + { + autoware_msgs::Lane lane; + PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_GeneratedRollOuts.at(i), lane); + lane.closest_object_distance = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).closest_obj_distance; + lane.closest_object_velocity = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).closest_obj_velocity; + lane.cost = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).cost; + lane.is_blocked = m_TrajectoryCostsCalculator.m_TrajectoryCosts.at(i).bBlocked; + lane.lane_index = i; + local_lanes.lanes.push_back(lane); + } + + pub_LocalWeightedTrajectories.publish(local_lanes); + } + else + { + ROS_ERROR("m_TrajectoryCosts.size() Not Equal m_GeneratedRollOuts.size()"); + } + + if(m_TrajectoryCostsCalculator.m_TrajectoryCosts.size()>0) + { + visualization_msgs::MarkerArray all_rollOuts; + PlannerHNS::ROSHelpers::TrajectoriesToColoredMarkers(m_GeneratedRollOuts, m_TrajectoryCostsCalculator.m_TrajectoryCosts, m_CurrentBehavior.iTrajectory, all_rollOuts); + pub_LocalWeightedTrajectoriesRviz.publish(all_rollOuts); + + PlannerHNS::ROSHelpers::ConvertCollisionPointsMarkers(m_TrajectoryCostsCalculator.m_CollisionPoints, m_CollisionsActual, m_CollisionsDummy); + pub_CollisionPointsRviz.publish(m_CollisionsActual); + + //Visualize Safety Box + visualization_msgs::Marker safety_box; + PlannerHNS::ROSHelpers::ConvertFromPlannerHRectangleToAutowareRviz(m_TrajectoryCostsCalculator.m_SafetyBorder.points, safety_box); + pub_SafetyBorderRviz.publish(safety_box); + } + } + else + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryEval::callbackGetGlobalPlannerPath, this); + + loop_rate.sleep(); + } } } diff --git a/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator.cpp b/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator.cpp index 201a3bf034d..641b846af0c 100644 --- a/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator.cpp +++ b/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator.cpp @@ -23,8 +23,8 @@ using namespace std; int main(int argc, char **argv) { - ros::init(argc, argv, "op_trajectory_generator"); - TrajectoryGeneratorNS::TrajectoryGen trajectory_gen; - trajectory_gen.MainLoop(); - return 0; + ros::init(argc, argv, "op_trajectory_generator"); + TrajectoryGeneratorNS::TrajectoryGen trajectory_gen; + trajectory_gen.MainLoop(); + return 0; } diff --git a/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator_core.cpp b/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator_core.cpp index 8ac7f594574..961fcd39ed0 100644 --- a/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator_core.cpp +++ b/core_planning/op_local_planner/nodes/op_trajectory_generator/op_trajectory_generator_core.cpp @@ -23,36 +23,36 @@ namespace TrajectoryGeneratorNS TrajectoryGen::TrajectoryGen() { - bInitPos = false; - bNewCurrentPos = false; - bVehicleStatus = false; - bWayGlobalPath = false; - - ros::NodeHandle _nh; - UpdatePlanningParams(_nh); - - tf::StampedTransform transform; - PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_LocalTrajectories = nh.advertise("local_trajectories", 1); - pub_LocalTrajectoriesRviz = nh.advertise("local_trajectories_gen_rviz", 1); - - sub_initialpose = nh.subscribe("/initialpose", 1, &TrajectoryGen::callbackGetInitPose, this); - sub_current_pose = nh.subscribe("/current_pose", 10, &TrajectoryGen::callbackGetCurrentPose, this); - - int bVelSource = 1; - _nh.getParam("/op_trajectory_generator/velocitySource", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 10, &TrajectoryGen::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 10, &TrajectoryGen::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 10, &TrajectoryGen::callbackGetCANInfo, this); - - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryGen::callbackGetGlobalPlannerPath, this); + bInitPos = false; + bNewCurrentPos = false; + bVehicleStatus = false; + bWayGlobalPath = false; + + ros::NodeHandle _nh; + UpdatePlanningParams(_nh); + + tf::StampedTransform transform; + PlannerHNS::ROSHelpers::GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_LocalTrajectories = nh.advertise("local_trajectories", 1); + pub_LocalTrajectoriesRviz = nh.advertise("local_trajectories_gen_rviz", 1); + + sub_initialpose = nh.subscribe("/initialpose", 1, &TrajectoryGen::callbackGetInitPose, this); + sub_current_pose = nh.subscribe("/current_pose", 10, &TrajectoryGen::callbackGetCurrentPose, this); + + int bVelSource = 1; + _nh.getParam("/op_trajectory_generator/velocitySource", bVelSource); + if(bVelSource == 0) + sub_robot_odom = nh.subscribe("/odom", 10, &TrajectoryGen::callbackGetRobotOdom, this); + else if(bVelSource == 1) + sub_current_velocity = nh.subscribe("/current_velocity", 10, &TrajectoryGen::callbackGetVehicleStatus, this); + else if(bVelSource == 2) + sub_can_info = nh.subscribe("/can_info", 10, &TrajectoryGen::callbackGetCANInfo, this); + + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryGen::callbackGetGlobalPlannerPath, this); } TrajectoryGen::~TrajectoryGen() @@ -61,209 +61,209 @@ TrajectoryGen::~TrajectoryGen() void TrajectoryGen::UpdatePlanningParams(ros::NodeHandle& _nh) { - _nh.getParam("/op_trajectory_generator/samplingTipMargin", m_PlanningParams.carTipMargin); - _nh.getParam("/op_trajectory_generator/samplingOutMargin", m_PlanningParams.rollInMargin); - _nh.getParam("/op_trajectory_generator/samplingSpeedFactor", m_PlanningParams.rollInSpeedFactor); - _nh.getParam("/op_trajectory_generator/enableHeadingSmoothing", m_PlanningParams.enableHeadingSmoothing); - - _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); - if(m_PlanningParams.enableSwerving) - m_PlanningParams.enableFollowing = true; - else - _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); - - _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); - _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); - - _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); - _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); - _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); - - _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); - _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); - if(m_PlanningParams.enableSwerving) - _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); - else - m_PlanningParams.rollOutNumber = 0; - - _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); - _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); - _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); - _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); - _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); - - _nh.getParam("/op_common_params/smoothingDataWeight", m_PlanningParams.smoothingDataWeight); - _nh.getParam("/op_common_params/smoothingSmoothWeight", m_PlanningParams.smoothingSmoothWeight); - - _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); - _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); - - _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); - - _nh.getParam("/op_common_params/width", m_CarInfo.width); - _nh.getParam("/op_common_params/length", m_CarInfo.length); - _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); - _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); - _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); - _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); - _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); - - m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; - m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; + _nh.getParam("/op_trajectory_generator/samplingTipMargin", m_PlanningParams.carTipMargin); + _nh.getParam("/op_trajectory_generator/samplingOutMargin", m_PlanningParams.rollInMargin); + _nh.getParam("/op_trajectory_generator/samplingSpeedFactor", m_PlanningParams.rollInSpeedFactor); + _nh.getParam("/op_trajectory_generator/enableHeadingSmoothing", m_PlanningParams.enableHeadingSmoothing); + + _nh.getParam("/op_common_params/enableSwerving", m_PlanningParams.enableSwerving); + if(m_PlanningParams.enableSwerving) + m_PlanningParams.enableFollowing = true; + else + _nh.getParam("/op_common_params/enableFollowing", m_PlanningParams.enableFollowing); + + _nh.getParam("/op_common_params/enableTrafficLightBehavior", m_PlanningParams.enableTrafficLightBehavior); + _nh.getParam("/op_common_params/enableStopSignBehavior", m_PlanningParams.enableStopSignBehavior); + + _nh.getParam("/op_common_params/maxVelocity", m_PlanningParams.maxSpeed); + _nh.getParam("/op_common_params/minVelocity", m_PlanningParams.minSpeed); + _nh.getParam("/op_common_params/maxLocalPlanDistance", m_PlanningParams.microPlanDistance); + + _nh.getParam("/op_common_params/pathDensity", m_PlanningParams.pathDensity); + _nh.getParam("/op_common_params/rollOutDensity", m_PlanningParams.rollOutDensity); + if(m_PlanningParams.enableSwerving) + _nh.getParam("/op_common_params/rollOutsNumber", m_PlanningParams.rollOutNumber); + else + m_PlanningParams.rollOutNumber = 0; + + _nh.getParam("/op_common_params/horizonDistance", m_PlanningParams.horizonDistance); + _nh.getParam("/op_common_params/minFollowingDistance", m_PlanningParams.minFollowingDistance); + _nh.getParam("/op_common_params/minDistanceToAvoid", m_PlanningParams.minDistanceToAvoid); + _nh.getParam("/op_common_params/maxDistanceToAvoid", m_PlanningParams.maxDistanceToAvoid); + _nh.getParam("/op_common_params/speedProfileFactor", m_PlanningParams.speedProfileFactor); + + _nh.getParam("/op_common_params/smoothingDataWeight", m_PlanningParams.smoothingDataWeight); + _nh.getParam("/op_common_params/smoothingSmoothWeight", m_PlanningParams.smoothingSmoothWeight); + + _nh.getParam("/op_common_params/horizontalSafetyDistance", m_PlanningParams.horizontalSafetyDistancel); + _nh.getParam("/op_common_params/verticalSafetyDistance", m_PlanningParams.verticalSafetyDistance); + + _nh.getParam("/op_common_params/enableLaneChange", m_PlanningParams.enableLaneChange); + + _nh.getParam("/op_common_params/width", m_CarInfo.width); + _nh.getParam("/op_common_params/length", m_CarInfo.length); + _nh.getParam("/op_common_params/wheelBaseLength", m_CarInfo.wheel_base); + _nh.getParam("/op_common_params/turningRadius", m_CarInfo.turning_radius); + _nh.getParam("/op_common_params/maxSteerAngle", m_CarInfo.max_steer_angle); + _nh.getParam("/op_common_params/maxAcceleration", m_CarInfo.max_acceleration); + _nh.getParam("/op_common_params/maxDeceleration", m_CarInfo.max_deceleration); + + m_CarInfo.max_speed_forward = m_PlanningParams.maxSpeed; + m_CarInfo.min_speed_forward = m_PlanningParams.minSpeed; } void TrajectoryGen::callbackGetInitPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg) { - if(!bInitPos) - { - m_InitPos = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, - msg->pose.pose.position.y+m_OriginPos.position.y, - msg->pose.pose.position.z+m_OriginPos.position.z, - tf::getYaw(msg->pose.pose.orientation)); - m_CurrentPos = m_InitPos; - bInitPos = true; - } + if(!bInitPos) + { + m_InitPos = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, + msg->pose.pose.position.y+m_OriginPos.position.y, + msg->pose.pose.position.z+m_OriginPos.position.z, + tf::getYaw(msg->pose.pose.orientation)); + m_CurrentPos = m_InitPos; + bInitPos = true; + } } void TrajectoryGen::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); - m_InitPos = m_CurrentPos; - bNewCurrentPos = true; - bInitPos = true; + m_CurrentPos = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + m_InitPos = m_CurrentPos; + bNewCurrentPos = true; + bInitPos = true; } void TrajectoryGen::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.linear.x; - m_CurrentPos.v = m_VehicleStatus.speed; - if(fabs(msg->twist.linear.x) > 0.25) - m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.linear.x; + m_CurrentPos.v = m_VehicleStatus.speed; + if(fabs(msg->twist.linear.x) > 0.25) + m_VehicleStatus.steer = atan(m_CarInfo.wheel_base * msg->twist.angular.z/msg->twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryGen::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleStatus.speed = msg->speed/3.6; - m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->speed/3.6; + m_VehicleStatus.steer = msg->angle * m_CarInfo.max_steer_angle / m_CarInfo.max_steer_value; + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryGen::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleStatus.speed = msg->twist.twist.linear.x; - m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); - UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); - bVehicleStatus = true; + m_VehicleStatus.speed = msg->twist.twist.linear.x; + m_VehicleStatus.steer += atan(m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); + UtilityHNS::UtilityH::GetTickCount(m_VehicleStatus.tStamp); + bVehicleStatus = true; } void TrajectoryGen::callbackGetGlobalPlannerPath(const autoware_msgs::LaneArrayConstPtr& msg) { - if(msg->lanes.size() > 0) - { - bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); - - m_GlobalPaths.clear(); - - for(unsigned int i = 0 ; i < msg->lanes.size(); i++) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); - - PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); - m_GlobalPaths.push_back(m_temp_path); - - if(bOldGlobalPath) - { - bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); - } - } - - if(!bOldGlobalPath) - { - bWayGlobalPath = true; - std::cout << "Received New Global Path Generator ! " << std::endl; - } - else - { - m_GlobalPaths.clear(); - } - } + if(msg->lanes.size() > 0) + { + bool bOldGlobalPath = m_GlobalPaths.size() == msg->lanes.size(); + + m_GlobalPaths.clear(); + + for(unsigned int i = 0 ; i < msg->lanes.size(); i++) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(msg->lanes.at(i), m_temp_path); + + PlannerHNS::PlanningHelpers::CalcAngleAndCost(m_temp_path); + m_GlobalPaths.push_back(m_temp_path); + + if(bOldGlobalPath) + { + bOldGlobalPath = PlannerHNS::PlanningHelpers::CompareTrajectories(m_temp_path, m_GlobalPaths.at(i)); + } + } + + if(!bOldGlobalPath) + { + bWayGlobalPath = true; + std::cout << "Received New Global Path Generator ! " << std::endl; + } + else + { + m_GlobalPaths.clear(); + } + } } void TrajectoryGen::MainLoop() { - ros::Rate loop_rate(100); - - PlannerHNS::WayPoint prevState, state_change; - - while (ros::ok()) - { - ros::spinOnce(); - - if(bInitPos && m_GlobalPaths.size()>0) - { - m_GlobalPathSections.clear(); - - for(unsigned int i = 0; i < m_GlobalPaths.size(); i++) - { - t_centerTrajectorySmoothed.clear(); - PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_GlobalPaths.at(i), m_CurrentPos, m_PlanningParams.horizonDistance , - m_PlanningParams.pathDensity ,t_centerTrajectorySmoothed); - - m_GlobalPathSections.push_back(t_centerTrajectorySmoothed); - } - - std::vector sampledPoints_debug; - m_Planner.GenerateRunoffTrajectory(m_GlobalPathSections, m_CurrentPos, - m_PlanningParams.enableLaneChange, - m_VehicleStatus.speed, - m_PlanningParams.microPlanDistance, - m_PlanningParams.maxSpeed, - m_PlanningParams.minSpeed, - m_PlanningParams.carTipMargin, - m_PlanningParams.rollInMargin, - m_PlanningParams.rollInSpeedFactor, - m_PlanningParams.pathDensity, - m_PlanningParams.rollOutDensity, - m_PlanningParams.rollOutNumber, - m_PlanningParams.smoothingDataWeight, - m_PlanningParams.smoothingSmoothWeight, - m_PlanningParams.smoothingToleranceError, - m_PlanningParams.speedProfileFactor, - m_PlanningParams.enableHeadingSmoothing, - -1 , -1, - m_RollOuts, sampledPoints_debug); - - autoware_msgs::LaneArray local_lanes; - for(unsigned int i=0; i < m_RollOuts.size(); i++) - { - for(unsigned int j=0; j < m_RollOuts.at(i).size(); j++) - { - autoware_msgs::Lane lane; - PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(m_RollOuts.at(i).at(j), m_CurrentPos, m_PlanningParams.minSpeed, m_PlanningParams.microPlanDistance); - PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_RollOuts.at(i).at(j), lane); - lane.closest_object_distance = 0; - lane.closest_object_velocity = 0; - lane.cost = 0; - lane.is_blocked = false; - lane.lane_index = i; - local_lanes.lanes.push_back(lane); - } - } - pub_LocalTrajectories.publish(local_lanes); - } - else - sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryGen::callbackGetGlobalPlannerPath, this); - - visualization_msgs::MarkerArray all_rollOuts; - PlannerHNS::ROSHelpers::TrajectoriesToMarkers(m_RollOuts, all_rollOuts); - pub_LocalTrajectoriesRviz.publish(all_rollOuts); - - loop_rate.sleep(); - } + ros::Rate loop_rate(100); + + PlannerHNS::WayPoint prevState, state_change; + + while (ros::ok()) + { + ros::spinOnce(); + + if(bInitPos && m_GlobalPaths.size()>0) + { + m_GlobalPathSections.clear(); + + for(unsigned int i = 0; i < m_GlobalPaths.size(); i++) + { + t_centerTrajectorySmoothed.clear(); + PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_GlobalPaths.at(i), m_CurrentPos, m_PlanningParams.horizonDistance , + m_PlanningParams.pathDensity ,t_centerTrajectorySmoothed); + + m_GlobalPathSections.push_back(t_centerTrajectorySmoothed); + } + + std::vector sampledPoints_debug; + m_Planner.GenerateRunoffTrajectory(m_GlobalPathSections, m_CurrentPos, + m_PlanningParams.enableLaneChange, + m_VehicleStatus.speed, + m_PlanningParams.microPlanDistance, + m_PlanningParams.maxSpeed, + m_PlanningParams.minSpeed, + m_PlanningParams.carTipMargin, + m_PlanningParams.rollInMargin, + m_PlanningParams.rollInSpeedFactor, + m_PlanningParams.pathDensity, + m_PlanningParams.rollOutDensity, + m_PlanningParams.rollOutNumber, + m_PlanningParams.smoothingDataWeight, + m_PlanningParams.smoothingSmoothWeight, + m_PlanningParams.smoothingToleranceError, + m_PlanningParams.speedProfileFactor, + m_PlanningParams.enableHeadingSmoothing, + -1 , -1, + m_RollOuts, sampledPoints_debug); + + autoware_msgs::LaneArray local_lanes; + for(unsigned int i=0; i < m_RollOuts.size(); i++) + { + for(unsigned int j=0; j < m_RollOuts.at(i).size(); j++) + { + autoware_msgs::Lane lane; + PlannerHNS::PlanningHelpers::PredictConstantTimeCostForTrajectory(m_RollOuts.at(i).at(j), m_CurrentPos, m_PlanningParams.minSpeed, m_PlanningParams.microPlanDistance); + PlannerHNS::ROSHelpers::ConvertFromLocalLaneToAutowareLane(m_RollOuts.at(i).at(j), lane); + lane.closest_object_distance = 0; + lane.closest_object_velocity = 0; + lane.cost = 0; + lane.is_blocked = false; + lane.lane_index = i; + local_lanes.lanes.push_back(lane); + } + } + pub_LocalTrajectories.publish(local_lanes); + } + else + sub_GlobalPlannerPaths = nh.subscribe("/lane_waypoints_array", 1, &TrajectoryGen::callbackGetGlobalPlannerPath, this); + + visualization_msgs::MarkerArray all_rollOuts; + PlannerHNS::ROSHelpers::TrajectoriesToMarkers(m_RollOuts, all_rollOuts); + pub_LocalTrajectoriesRviz.publish(all_rollOuts); + + loop_rate.sleep(); + } } } diff --git a/core_planning/op_utilities/CMakeLists.txt b/core_planning/op_utilities/CMakeLists.txt index 342b2fd4575..e34bd8c74d6 100644 --- a/core_planning/op_utilities/CMakeLists.txt +++ b/core_planning/op_utilities/CMakeLists.txt @@ -7,15 +7,16 @@ cmake_policy(SET CMP0072 NEW) find_package(autoware_build_flags REQUIRED) find_package( - catkin REQUIRED COMPONENTS - roscpp + catkin REQUIRED COMPONENTS autoware_msgs - geometry_msgs + geometry_msgs map_file op_planner op_ros_helpers op_utility pcl_conversions + rosbag + roscpp vector_map_msgs ) @@ -31,15 +32,6 @@ find_package(Threads REQUIRED) catkin_package( INCLUDE_DIRS include LIBRARIES - CATKIN_DEPENDS - geometry_msgs - map_file - op_planner - op_ros_helpers - op_utility - pcl_conversions - roscpp - vector_map_msgs ) include_directories( diff --git a/core_planning/op_utilities/include/BagTopicPlayer.h b/core_planning/op_utilities/include/BagTopicPlayer.h index 96348383a82..44a28a6af27 100644 --- a/core_planning/op_utilities/include/BagTopicPlayer.h +++ b/core_planning/op_utilities/include/BagTopicPlayer.h @@ -36,183 +36,183 @@ template class BagTopicPlayer { public: - void InitPlayer(const rosbag::Bag& _bag, const std::string& topic_name) - { - if(_bag.getSize() == 0) return; - - rosbag::View view(_bag); - std::vector connection_infos = view.getConnections(); - std::vector topics_to_subscribe; - - std::set bagTopics; - - BOOST_FOREACH(const rosbag::ConnectionInfo *info, connection_infos) - { - bagTopics.insert(info->topic); - } - - if (bagTopics.find(topic_name) == bagTopics.end()) - { - ROS_WARN_STREAM("Can't Find LIDAR Topic in ROSBag File :" << topic_name); - return; - } - else - { - topics_to_subscribe.push_back(std::string(topic_name)); - } - - m_BagView.addQuery(_bag, rosbag::TopicQuery(topics_to_subscribe)); - m_ViewIterator = m_BagView.begin(); - m_StartTime = m_BagView.getBeginTime(); - m_bReadNext = true; - } - - bool ReadNext(boost::shared_ptr& msg, ros::Time* pSyncTime) - { - - if(m_ViewIterator != m_BagView.end()) - { - if(m_bReadNext == true) - { - if(m_iPlayHead < m_PrevRecords.size()) - { - m_CurrRecord = m_PrevRecords.at(m_iPlayHead); - } - else - { - rosbag::MessageInstance m = *m_ViewIterator; - m_CurrRecord = m.instantiate(); - - if(m_CurrRecord == NULL) - { - std::cout << "Record is Null !! Skip" << std::endl; - return false; - } - } - - m_bReadNext = false; - } - - ros::Time sync_time = m_CurrRecord->header.stamp; - ros::Time prev_time = m_CurrRecord->header.stamp; - - if(pSyncTime != NULL) - sync_time = *pSyncTime; - - if(m_PrevRecord != NULL) - prev_time = m_PrevRecord->header.stamp; - - ros::Duration rec_time_diff = m_CurrRecord->header.stamp - prev_time; - ros::Duration actual_time_diff = ros::Time().now() - m_Timer; - ros::Duration sync_time_diff = m_CurrRecord->header.stamp - sync_time; - - if(actual_time_diff >= rec_time_diff && actual_time_diff >= sync_time_diff) - { - msg = m_CurrRecord; - m_PrevRecord = m_CurrRecord; - m_Timer = ros::Time().now(); - m_bReadNext = true; - m_iFrame++; - - if(m_iPlayHead == m_PrevRecords.size()) - { - m_PrevRecords.push_back(m_CurrRecord); - if(m_PrevRecords.size() > MAX_RECORDS_BUFFER) - m_PrevRecords.erase(m_PrevRecords.begin()+0); - m_iPlayHead = m_PrevRecords.size(); - m_ViewIterator++; - } - else - { - m_iPlayHead++; - } - - return true; - } - - return false; - - } - else - { - return false; - } - } - - bool ReadPrev(boost::shared_ptr& msg, ros::Time* pSyncTime) - { - if(m_PrevRecords.size() > 0 && m_iPlayHead > 0 ) - { - boost::shared_ptr currRecord; - m_iPlayHead--; - currRecord = m_PrevRecords.at(m_iPlayHead); - - ros::Time sync_time = currRecord->header.stamp; - ros::Time prev_time = currRecord->header.stamp; - - if(pSyncTime != NULL) - sync_time = *pSyncTime; - - if(m_PrevRecord != NULL) - prev_time = m_PrevRecord->header.stamp; - - ros::Duration rec_time_diff = prev_time - currRecord->header.stamp; - ros::Duration actual_time_diff = ros::Time().now() - m_Timer; - ros::Duration sync_time_diff = sync_time - currRecord->header.stamp; - - //if(actual_time_diff >= rec_time_diff && actual_time_diff >= sync_time_diff) - if(actual_time_diff >= sync_time_diff) - { - m_iFrame--; - m_Timer = ros::Time().now(); - msg = currRecord; - m_PrevRecord = currRecord; - m_bReadNext = true; - return true; - } - } - - return false; - } - - void GetReadingInfo(int& _t_sec, int& _t_nsec, int& iFrame, int& nTotalFrames) - { - if(m_CurrRecord != NULL) - { - ros::Duration dur = (m_CurrRecord->header.stamp - m_StartTime); - _t_sec = dur.sec; - _t_nsec = dur.nsec; - } - - iFrame = m_iFrame; - nTotalFrames = m_BagView.size(); - } - - - BagTopicPlayer() - { - m_bReadNext = true; - m_iFrame = 0; - m_iPlayHead = 0; - } - - virtual ~BagTopicPlayer() - { - - } + void InitPlayer(const rosbag::Bag& _bag, const std::string& topic_name) + { + if(_bag.getSize() == 0) return; + + rosbag::View view(_bag); + std::vector connection_infos = view.getConnections(); + std::vector topics_to_subscribe; + + std::set bagTopics; + + BOOST_FOREACH(const rosbag::ConnectionInfo *info, connection_infos) + { + bagTopics.insert(info->topic); + } + + if (bagTopics.find(topic_name) == bagTopics.end()) + { + ROS_WARN_STREAM("Can't Find LIDAR Topic in ROSBag File :" << topic_name); + return; + } + else + { + topics_to_subscribe.push_back(std::string(topic_name)); + } + + m_BagView.addQuery(_bag, rosbag::TopicQuery(topics_to_subscribe)); + m_ViewIterator = m_BagView.begin(); + m_StartTime = m_BagView.getBeginTime(); + m_bReadNext = true; + } + + bool ReadNext(boost::shared_ptr& msg, ros::Time* pSyncTime) + { + + if(m_ViewIterator != m_BagView.end()) + { + if(m_bReadNext == true) + { + if(m_iPlayHead < m_PrevRecords.size()) + { + m_CurrRecord = m_PrevRecords.at(m_iPlayHead); + } + else + { + rosbag::MessageInstance m = *m_ViewIterator; + m_CurrRecord = m.instantiate(); + + if(m_CurrRecord == NULL) + { + std::cout << "Record is Null !! Skip" << std::endl; + return false; + } + } + + m_bReadNext = false; + } + + ros::Time sync_time = m_CurrRecord->header.stamp; + ros::Time prev_time = m_CurrRecord->header.stamp; + + if(pSyncTime != NULL) + sync_time = *pSyncTime; + + if(m_PrevRecord != NULL) + prev_time = m_PrevRecord->header.stamp; + + ros::Duration rec_time_diff = m_CurrRecord->header.stamp - prev_time; + ros::Duration actual_time_diff = ros::Time().now() - m_Timer; + ros::Duration sync_time_diff = m_CurrRecord->header.stamp - sync_time; + + if(actual_time_diff >= rec_time_diff && actual_time_diff >= sync_time_diff) + { + msg = m_CurrRecord; + m_PrevRecord = m_CurrRecord; + m_Timer = ros::Time().now(); + m_bReadNext = true; + m_iFrame++; + + if(m_iPlayHead == m_PrevRecords.size()) + { + m_PrevRecords.push_back(m_CurrRecord); + if(m_PrevRecords.size() > MAX_RECORDS_BUFFER) + m_PrevRecords.erase(m_PrevRecords.begin()+0); + m_iPlayHead = m_PrevRecords.size(); + m_ViewIterator++; + } + else + { + m_iPlayHead++; + } + + return true; + } + + return false; + + } + else + { + return false; + } + } + + bool ReadPrev(boost::shared_ptr& msg, ros::Time* pSyncTime) + { + if(m_PrevRecords.size() > 0 && m_iPlayHead > 0 ) + { + boost::shared_ptr currRecord; + m_iPlayHead--; + currRecord = m_PrevRecords.at(m_iPlayHead); + + ros::Time sync_time = currRecord->header.stamp; + ros::Time prev_time = currRecord->header.stamp; + + if(pSyncTime != NULL) + sync_time = *pSyncTime; + + if(m_PrevRecord != NULL) + prev_time = m_PrevRecord->header.stamp; + + ros::Duration rec_time_diff = prev_time - currRecord->header.stamp; + ros::Duration actual_time_diff = ros::Time().now() - m_Timer; + ros::Duration sync_time_diff = sync_time - currRecord->header.stamp; + + //if(actual_time_diff >= rec_time_diff && actual_time_diff >= sync_time_diff) + if(actual_time_diff >= sync_time_diff) + { + m_iFrame--; + m_Timer = ros::Time().now(); + msg = currRecord; + m_PrevRecord = currRecord; + m_bReadNext = true; + return true; + } + } + + return false; + } + + void GetReadingInfo(int& _t_sec, int& _t_nsec, int& iFrame, int& nTotalFrames) + { + if(m_CurrRecord != NULL) + { + ros::Duration dur = (m_CurrRecord->header.stamp - m_StartTime); + _t_sec = dur.sec; + _t_nsec = dur.nsec; + } + + iFrame = m_iFrame; + nTotalFrames = m_BagView.size(); + } + + + BagTopicPlayer() + { + m_bReadNext = true; + m_iFrame = 0; + m_iPlayHead = 0; + } + + virtual ~BagTopicPlayer() + { + + } private: - rosbag::View::iterator m_ViewIterator; - rosbag::View m_BagView; - std::vector > m_PrevRecords; - boost::shared_ptr m_CurrRecord; - boost::shared_ptr m_PrevRecord; - bool m_bReadNext; - ros::Time m_Timer; - int m_iFrame; - ros::Time m_StartTime; - int m_iPlayHead; + rosbag::View::iterator m_ViewIterator; + rosbag::View m_BagView; + std::vector > m_PrevRecords; + boost::shared_ptr m_CurrRecord; + boost::shared_ptr m_PrevRecord; + bool m_bReadNext; + ros::Time m_Timer; + int m_iFrame; + ros::Time m_StartTime; + int m_iPlayHead; }; diff --git a/core_planning/op_utilities/include/DrawingHelpers.h b/core_planning/op_utilities/include/DrawingHelpers.h index 7d62f39cfad..a6255ebf63f 100644 --- a/core_planning/op_utilities/include/DrawingHelpers.h +++ b/core_planning/op_utilities/include/DrawingHelpers.h @@ -26,40 +26,40 @@ namespace OP_TESTING_NS class DrawingHelpers { public: - DrawingHelpers(); - virtual ~DrawingHelpers(); - static void DrawString(float x, float y, GLvoid *font_style, char* format, ...); - static void DrawGrid(const double& x, const double& y, const double& w, const double& h, const double& cell_l); - static void DrawCustomOrigin(const double& x, const double& y, const double& z, - const int& yaw, const int& roll, const int& pitch, const double& length); - static void DrawArrow(const double& x, const double& y, const double& a); + DrawingHelpers(); + virtual ~DrawingHelpers(); + static void DrawString(float x, float y, GLvoid *font_style, char* format, ...); + static void DrawGrid(const double& x, const double& y, const double& w, const double& h, const double& cell_l); + static void DrawCustomOrigin(const double& x, const double& y, const double& z, + const int& yaw, const int& roll, const int& pitch, const double& length); + static void DrawArrow(const double& x, const double& y, const double& a); - static std::vector > PreparePathForDrawing(const std::vector& path, - std::vector >& redyForDraw, double w, double resolution = 1); + static std::vector > PreparePathForDrawing(const std::vector& path, + std::vector >& redyForDraw, double w, double resolution = 1); - static void DrawPrePreparedPolygons(std::vector >& path, - double z, float color[3],int nSkipPoints = 1, const std::vector >* colorProfile = 0); + static void DrawPrePreparedPolygons(std::vector >& path, + double z, float color[3],int nSkipPoints = 1, const std::vector >* colorProfile = 0); - static void DrawWidePath(const std::vector& path_points, const double& z, - const double& width, float color[3], bool bGadient = true); + static void DrawWidePath(const std::vector& path_points, const double& z, + const double& width, float color[3], bool bGadient = true); - static void DrawCostPath(const std::vector& path_points, const double& z, const double& width); + static void DrawCostPath(const std::vector& path_points, const double& z, const double& width); - static void DrawLinePoygonFromCenterX(const PlannerHNS::WayPoint& p1, const double& z, - const PlannerHNS::WayPoint& p2, const double& z2, const double& w, const double& h, - PlannerHNS::WayPoint& prev_point); + static void DrawLinePoygonFromCenterX(const PlannerHNS::WayPoint& p1, const double& z, + const PlannerHNS::WayPoint& p2, const double& z2, const double& w, const double& h, + PlannerHNS::WayPoint& prev_point); - static void DrawLinePoygonline(const PlannerHNS::GPSPoint& p1, const PlannerHNS::GPSPoint& p2, const double& w); + static void DrawLinePoygonline(const PlannerHNS::GPSPoint& p1, const PlannerHNS::GPSPoint& p2, const double& w); - static void DrawCustomCarModel(const PlannerHNS::WayPoint& pose, const double& steeringAngle, const std::vector& carPoints,float color[3], const double& angleFix); + static void DrawCustomCarModel(const PlannerHNS::WayPoint& pose, const double& steeringAngle, const std::vector& carPoints,float color[3], const double& angleFix); - static void DrawFilledEllipse(float x, float y, float z, float width, float height); + static void DrawFilledEllipse(float x, float y, float z, float width, float height); - static void DrawWideEllipse(float x, float y, float z, float outer_width, float outer_height, float inner_width,float color[3]); + static void DrawWideEllipse(float x, float y, float z, float outer_width, float outer_height, float inner_width,float color[3]); - static void DrawSimpleEllipse(float x, float y, float z, float outer_width, float outer_height); + static void DrawSimpleEllipse(float x, float y, float z, float outer_width, float outer_height); - static void DrawPedal(float x, float y, float z, float width, float height, float inner_height, float color[3]); + static void DrawPedal(float x, float y, float z, float width, float height, float inner_height, float color[3]); }; diff --git a/core_planning/op_utilities/include/MainWindowWrapper.h b/core_planning/op_utilities/include/MainWindowWrapper.h index 8b182255089..fce6c21eb10 100644 --- a/core_planning/op_utilities/include/MainWindowWrapper.h +++ b/core_planning/op_utilities/include/MainWindowWrapper.h @@ -31,131 +31,131 @@ enum DisplayMode{DISPLAY_FREE, DISPLAY_TOP_FREE, DISPLAY_FOLLOW}; class WindowParams { public: - int x; - int y; - int w; - int h; - double info_ratio; - std::string title; - struct info_window - { - int x; - int y; - int w; - int h; - }info_window; - - struct simu_window - { - int x; - int y; - int w; - int h; - }simu_window; - - struct UI_CONST - { - int GAP; - double MAX_ZOOM; - double MIN_ZOOM; - double INIT_ZOOM; - double FOLLOW_CONST_ZOOM; - - }UI_CONST; - - bool bNew; - bool bGPU; - - - WindowParams(); - void ReCalcSimuWindow(); + int x; + int y; + int w; + int h; + double info_ratio; + std::string title; + struct info_window + { + int x; + int y; + int w; + int h; + }info_window; + + struct simu_window + { + int x; + int y; + int w; + int h; + }simu_window; + + struct UI_CONST + { + int GAP; + double MAX_ZOOM; + double MIN_ZOOM; + double INIT_ZOOM; + double FOLLOW_CONST_ZOOM; + + }UI_CONST; + + bool bNew; + bool bGPU; + + + WindowParams(); + void ReCalcSimuWindow(); }; class DisplayParams { public: - int prev_x; - int prev_y; - int currRotationZ; //degrees, scaled radians - int currRotationX; //degrees, scaled radians - int currRotationY; //degrees, scaled radians + int prev_x; + int prev_y; + int currRotationZ; //degrees, scaled radians + int currRotationX; //degrees, scaled radians + int currRotationY; //degrees, scaled radians - double centerRotX; - double centerRotY; + double centerRotX; + double centerRotY; - double translateX; - double translateY; + double translateX; + double translateY; - float eye[3]; - float at[3] ; - float up[3] ; + float eye[3]; + float at[3] ; + float up[3] ; - bool bFullScreen; - DisplayMode bDisplayMode; - double prespective_z; - double prespective_fov; + bool bFullScreen; + DisplayMode bDisplayMode; + double prespective_z; + double prespective_fov; - bool bLeftDown; - bool bRightDown; - bool bCenterDown; - int bSelectPosition; //0 nothing, 1 start , 2 goal, 3 simulation - double StartPos[3]; - double GoalPos[3]; - double StartPosFinal[3]; - double GoalPosFinal[3]; + bool bLeftDown; + bool bRightDown; + bool bCenterDown; + int bSelectPosition; //0 nothing, 1 start , 2 goal, 3 simulation + double StartPos[3]; + double GoalPos[3]; + double StartPosFinal[3]; + double GoalPosFinal[3]; - double SimulatedCarPos[3]; - double SimulatedCarPosFinal[3]; + double SimulatedCarPos[3]; + double SimulatedCarPosFinal[3]; - double zoom; - double actualViewX; - double actualViewY; - double initScreenToCenterMargin[2]; + double zoom; + double actualViewX; + double actualViewY; + double initScreenToCenterMargin[2]; - DisplayParams(); + DisplayParams(); }; class MainWindowWrapper { public: - MainWindowWrapper(DrawObjBase* pDraw); - virtual ~MainWindowWrapper(); + MainWindowWrapper(DrawObjBase* pDraw); + virtual ~MainWindowWrapper(); - void InitOpenGLWindow(int argc, char** argv); - void UpdateParams(const WindowParams& params, const DisplayParams& display_params); - static void MainReshape(int width, int height); - static void SimuReshape(int width, int height); + void InitOpenGLWindow(int argc, char** argv); + void UpdateParams(const WindowParams& params, const DisplayParams& display_params); + static void MainReshape(int width, int height); + static void SimuReshape(int width, int height); - static void MainDisplay(); - static void SimuDisplay(); + static void MainDisplay(); + static void SimuDisplay(); - static void KeyboardCommand(unsigned char key, int x, int y); - static void KeyboardExitCommand(unsigned char key, int x, int y); - static void KeyboardSpecialCommand(int key, int x, int y); + static void KeyboardCommand(unsigned char key, int x, int y); + static void KeyboardExitCommand(unsigned char key, int x, int y); + static void KeyboardSpecialCommand(int key, int x, int y); - static void InitLighting(); - static void FromScreenToModelCoordinate(int sx, int sy, double& modelX, double& modelY); - static void FromModelToScreenCoordinate(double modelX, double modelY, int& sx, int& sy); + static void InitLighting(); + static void FromScreenToModelCoordinate(int sx, int sy, double& modelX, double& modelY); + static void FromModelToScreenCoordinate(double modelX, double modelY, int& sx, int& sy); - static void DrawGrid(const double& x, const double& y, const double& w, const double& h, const double& cell_l); + static void DrawGrid(const double& x, const double& y, const double& w, const double& h, const double& cell_l); - static void CleanUp(); + static void CleanUp(); private: - static DrawObjBase* m_DrawAndControl; - static int m_MainWindow; - static int m_SimuWindow; - static int m_InfoWindow; - static int m_PopupMenu; - static WindowParams m_params; - static DisplayParams m_DisplayParam; + static DrawObjBase* m_DrawAndControl; + static int m_MainWindow; + static int m_SimuWindow; + static int m_InfoWindow; + static int m_PopupMenu; + static WindowParams m_params; + static DisplayParams m_DisplayParam; private: - //this area for code testing , remove later + //this area for code testing , remove later }; diff --git a/core_planning/op_utilities/include/op_bag_player_core.h b/core_planning/op_utilities/include/op_bag_player_core.h index bbe1d3f81c7..e4e6d55aa51 100644 --- a/core_planning/op_utilities/include/op_bag_player_core.h +++ b/core_planning/op_utilities/include/op_bag_player_core.h @@ -35,14 +35,14 @@ namespace OP_TESTING_NS class BagReaderParams { public: - std::string fileName; - std::string lidarTopic; - std::string poseTopic; - std::string imageTopic; - - std::string lidarTopic_pub; - std::string poseTopic_pub; - std::string imageTopic_pub; + std::string fileName; + std::string lidarTopic; + std::string poseTopic; + std::string imageTopic; + + std::string lidarTopic_pub; + std::string poseTopic_pub; + std::string imageTopic_pub; }; enum TESTING_MODE {SIMULATION_MODE, ROSBAG_MODE, LIVE_MODE}; @@ -51,12 +51,12 @@ enum ROSBAG_PLAY_MODE {PLAY_FORWARD, PLAY_BACKWARD, PLAY_PAUSE, PLAY_STEP_FORWAR class TestingUI : public DrawObjBase { public: - TestingUI(); - virtual ~TestingUI(); - void InitNode(const BagReaderParams& params, const int& mode); + TestingUI(); + virtual ~TestingUI(); + void InitNode(const BagReaderParams& params, const int& mode); - void DrawSimu(); - void OnKeyboardPress(const int& sKey, const unsigned char& key); + void DrawSimu(); + void OnKeyboardPress(const int& sKey, const unsigned char& key); void SimulationModeMainLoop(); double m_VehicleTargetStateAccelerator; @@ -69,35 +69,35 @@ class TestingUI : public DrawObjBase ros::Publisher pub_SimuStepSignal; ros::Publisher pub_SimuGenSignal; ros::Publisher pub_PredStepSignal; - TESTING_MODE m_TestMode; + TESTING_MODE m_TestMode; - //ROSbag reader + //ROSbag reader private: - BagReaderParams m_BagParams; - rosbag::Bag m_bag; - std::string m_ReadingInfo; + BagReaderParams m_BagParams; + rosbag::Bag m_bag; + std::string m_ReadingInfo; - bool m_bBagOpen; - ROSBAG_PLAY_MODE m_PlayMode; - bool m_bStepDone; + bool m_bBagOpen; + ROSBAG_PLAY_MODE m_PlayMode; + bool m_bStepDone; - geometry_msgs::PoseStampedPtr m_pLatestPose; - sensor_msgs::PointCloud2Ptr m_pLatestCloud; - sensor_msgs::ImagePtr m_pLatestImage; + geometry_msgs::PoseStampedPtr m_pLatestPose; + sensor_msgs::PointCloud2Ptr m_pLatestCloud; + sensor_msgs::ImagePtr m_pLatestImage; - ros::Publisher pub_Point_Raw; - ros::Publisher pub_Image_Raw; - ros::Publisher pub_NDT_pose; + ros::Publisher pub_Point_Raw; + ros::Publisher pub_Image_Raw; + ros::Publisher pub_NDT_pose; - UtilityHNS::BagTopicPlayer m_CloudReader; - UtilityHNS::BagTopicPlayer m_ImageReader; - UtilityHNS::BagTopicPlayer m_PoseReader; + UtilityHNS::BagTopicPlayer m_CloudReader; + UtilityHNS::BagTopicPlayer m_ImageReader; + UtilityHNS::BagTopicPlayer m_PoseReader; - bool OpenROSBag(); - void BagReaderModeMainLoop(); - bool ReadNextFrame(); - bool ReadPrevFrame(); + bool OpenROSBag(); + void BagReaderModeMainLoop(); + bool ReadNextFrame(); + bool ReadPrevFrame(); }; } /* namespace Graphics */ diff --git a/core_planning/op_utilities/include/op_data_logger_core.h b/core_planning/op_utilities/include/op_data_logger_core.h index 2272beace53..dbfb9159635 100644 --- a/core_planning/op_utilities/include/op_data_logger_core.h +++ b/core_planning/op_utilities/include/op_data_logger_core.h @@ -50,12 +50,12 @@ namespace DataLoggerNS class VehicleDataContainer { public: - int id; - std::vector path; - PlannerHNS::BehaviorState beh; - PlannerHNS::WayPoint pose; - ros::Time path_time; - ros::Time pose_time; + int id; + std::vector path; + PlannerHNS::BehaviorState beh; + PlannerHNS::WayPoint pose; + ros::Time path_time; + ros::Time pose_time; }; class OpenPlannerDataLogger @@ -63,41 +63,41 @@ class OpenPlannerDataLogger protected: - ros::Subscriber sub_predicted_objects; - ros::Subscriber sub_behavior_state; - std::vector sub_simu_paths; - std::vector sub_objs; - - ros::NodeHandle nh; - timespec m_Timer; - - std::vector m_SimulatedVehicle; - std::vector m_PredictedObjects; - ros::Time m_pred_time; - PlannerHNS::BehaviorState m_CurrentBehavior; - PlannerHNS::MAP_SOURCE_TYPE m_MapType; - std::string m_MapPath; - PlannerHNS::RoadNetwork m_Map; - bool bMap; - int m_iSimuCarsNumber; - - std::vector > m_LogData; - - void callbackGetSimuPose(const geometry_msgs::PoseArray &msg); - void callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); - void callbackGetSimuCarsPathAndState(const autoware_msgs::LaneConstPtr& msg); - void callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr& msg ); - PlannerHNS::BehaviorState ConvertBehaviorStateFromAutowareToPlannerH(const geometry_msgs::TwistStampedConstPtr& msg); - PlannerHNS::STATE_TYPE GetStateFromNumber(const int& iBehState); - PlannerHNS::BEH_STATE_TYPE GetBehStateFromNumber(const int& iBehState); - - void CompareAndLog(VehicleDataContainer& ground_truth, PlannerHNS::DetectedObject& predicted); - double CalculateRMS(std::vector& path1, std::vector& path2); + ros::Subscriber sub_predicted_objects; + ros::Subscriber sub_behavior_state; + std::vector sub_simu_paths; + std::vector sub_objs; + + ros::NodeHandle nh; + timespec m_Timer; + + std::vector m_SimulatedVehicle; + std::vector m_PredictedObjects; + ros::Time m_pred_time; + PlannerHNS::BehaviorState m_CurrentBehavior; + PlannerHNS::MAP_SOURCE_TYPE m_MapType; + std::string m_MapPath; + PlannerHNS::RoadNetwork m_Map; + bool bMap; + int m_iSimuCarsNumber; + + std::vector > m_LogData; + + void callbackGetSimuPose(const geometry_msgs::PoseArray &msg); + void callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg); + void callbackGetSimuCarsPathAndState(const autoware_msgs::LaneConstPtr& msg); + void callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr& msg ); + PlannerHNS::BehaviorState ConvertBehaviorStateFromAutowareToPlannerH(const geometry_msgs::TwistStampedConstPtr& msg); + PlannerHNS::STATE_TYPE GetStateFromNumber(const int& iBehState); + PlannerHNS::BEH_STATE_TYPE GetBehStateFromNumber(const int& iBehState); + + void CompareAndLog(VehicleDataContainer& ground_truth, PlannerHNS::DetectedObject& predicted); + double CalculateRMS(std::vector& path1, std::vector& path2); public: - OpenPlannerDataLogger(); - virtual ~OpenPlannerDataLogger(); - void MainLoop(); + OpenPlannerDataLogger(); + virtual ~OpenPlannerDataLogger(); + void MainLoop(); }; } diff --git a/core_planning/op_utilities/include/op_map_converter_core.h b/core_planning/op_utilities/include/op_map_converter_core.h index 6fe86d6865b..669a643d44e 100644 --- a/core_planning/op_utilities/include/op_map_converter_core.h +++ b/core_planning/op_utilities/include/op_map_converter_core.h @@ -48,62 +48,62 @@ class Vector2OP { protected: -// UtilityHNS::AisanLanesFileReader* pLanes; -// UtilityHNS::AisanPointsFileReader* pPoints; -// UtilityHNS::AisanCenterLinesFileReader* pCenterLines; -// UtilityHNS::AisanIntersectionFileReader* pIntersections; -// UtilityHNS::AisanAreasFileReader* pAreas; -// UtilityHNS::AisanLinesFileReader* pLines; -// UtilityHNS::AisanStopLineFileReader* pStopLines; -// UtilityHNS::AisanSignalFileReader* pSignals; -// UtilityHNS::AisanVectorFileReader* pVectors; -// UtilityHNS::AisanCurbFileReader* pCurbs; -// UtilityHNS::AisanRoadEdgeFileReader* pRoadedges; -// UtilityHNS::AisanWayareaFileReader* pWayAreas; -// UtilityHNS::AisanCrossWalkFileReader* pCrossWalks; -// UtilityHNS::AisanNodesFileReader* pNodes; -// UtilityHNS::AisanDataConnFileReader* pConnections; - - UtilityHNS::MapRaw m_MapRaw; - - ros::NodeHandle nh; - - ros::Subscriber sub_lanes; - ros::Subscriber sub_points; - ros::Subscriber sub_dt_lanes; - ros::Subscriber sub_intersect; - ros::Subscriber sup_area; - ros::Subscriber sub_lines; - ros::Subscriber sub_stop_line; - ros::Subscriber sub_signals; - ros::Subscriber sub_vectors; - ros::Subscriber sub_curbs; - ros::Subscriber sub_edges; - ros::Subscriber sub_way_areas; - ros::Subscriber sub_cross_walk; - ros::Subscriber sub_nodes; - - - void callbackGetVMLanes(const vector_map_msgs::LaneArrayConstPtr& msg); - void callbackGetVMPoints(const vector_map_msgs::PointArrayConstPtr& msg); - void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArrayConstPtr& msg); - void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArrayConstPtr& msg); - void callbackGetVMAreas(const vector_map_msgs::AreaArrayConstPtr& msg); - void callbackGetVMLines(const vector_map_msgs::LineArrayConstPtr& msg); - void callbackGetVMStopLines(const vector_map_msgs::StopLineArrayConstPtr& msg); - void callbackGetVMSignal(const vector_map_msgs::SignalArrayConstPtr& msg); - void callbackGetVMVectors(const vector_map_msgs::VectorArrayConstPtr& msg); - void callbackGetVMCurbs(const vector_map_msgs::CurbArrayConstPtr& msg); - void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArrayConstPtr& msg); - void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArrayConstPtr& msg); - void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArrayConstPtr& msg); - void callbackGetVMNodes(const vector_map_msgs::NodeArrayConstPtr& msg); +// UtilityHNS::AisanLanesFileReader* pLanes; +// UtilityHNS::AisanPointsFileReader* pPoints; +// UtilityHNS::AisanCenterLinesFileReader* pCenterLines; +// UtilityHNS::AisanIntersectionFileReader* pIntersections; +// UtilityHNS::AisanAreasFileReader* pAreas; +// UtilityHNS::AisanLinesFileReader* pLines; +// UtilityHNS::AisanStopLineFileReader* pStopLines; +// UtilityHNS::AisanSignalFileReader* pSignals; +// UtilityHNS::AisanVectorFileReader* pVectors; +// UtilityHNS::AisanCurbFileReader* pCurbs; +// UtilityHNS::AisanRoadEdgeFileReader* pRoadedges; +// UtilityHNS::AisanWayareaFileReader* pWayAreas; +// UtilityHNS::AisanCrossWalkFileReader* pCrossWalks; +// UtilityHNS::AisanNodesFileReader* pNodes; +// UtilityHNS::AisanDataConnFileReader* pConnections; + + UtilityHNS::MapRaw m_MapRaw; + + ros::NodeHandle nh; + + ros::Subscriber sub_lanes; + ros::Subscriber sub_points; + ros::Subscriber sub_dt_lanes; + ros::Subscriber sub_intersect; + ros::Subscriber sup_area; + ros::Subscriber sub_lines; + ros::Subscriber sub_stop_line; + ros::Subscriber sub_signals; + ros::Subscriber sub_vectors; + ros::Subscriber sub_curbs; + ros::Subscriber sub_edges; + ros::Subscriber sub_way_areas; + ros::Subscriber sub_cross_walk; + ros::Subscriber sub_nodes; + + + void callbackGetVMLanes(const vector_map_msgs::LaneArrayConstPtr& msg); + void callbackGetVMPoints(const vector_map_msgs::PointArrayConstPtr& msg); + void callbackGetVMdtLanes(const vector_map_msgs::DTLaneArrayConstPtr& msg); + void callbackGetVMIntersections(const vector_map_msgs::CrossRoadArrayConstPtr& msg); + void callbackGetVMAreas(const vector_map_msgs::AreaArrayConstPtr& msg); + void callbackGetVMLines(const vector_map_msgs::LineArrayConstPtr& msg); + void callbackGetVMStopLines(const vector_map_msgs::StopLineArrayConstPtr& msg); + void callbackGetVMSignal(const vector_map_msgs::SignalArrayConstPtr& msg); + void callbackGetVMVectors(const vector_map_msgs::VectorArrayConstPtr& msg); + void callbackGetVMCurbs(const vector_map_msgs::CurbArrayConstPtr& msg); + void callbackGetVMRoadEdges(const vector_map_msgs::RoadEdgeArrayConstPtr& msg); + void callbackGetVMWayAreas(const vector_map_msgs::WayAreaArrayConstPtr& msg); + void callbackGetVMCrossWalks(const vector_map_msgs::CrossWalkArrayConstPtr& msg); + void callbackGetVMNodes(const vector_map_msgs::NodeArrayConstPtr& msg); public: - Vector2OP(); - virtual ~Vector2OP(); - void MainLoop(); + Vector2OP(); + virtual ~Vector2OP(); + void MainLoop(); }; } diff --git a/core_planning/op_utilities/include/op_pose2tf_core.h b/core_planning/op_utilities/include/op_pose2tf_core.h index 7252d81719f..a5989ca1acf 100644 --- a/core_planning/op_utilities/include/op_pose2tf_core.h +++ b/core_planning/op_utilities/include/op_pose2tf_core.h @@ -34,16 +34,16 @@ class PoseToTF protected: - ros::Subscriber sub_ndt_pose; - ros::Publisher pub_reset_time; - ros::NodeHandle nh; + ros::Subscriber sub_ndt_pose; + ros::Publisher pub_reset_time; + ros::NodeHandle nh; - void callbackGetPose(const geometry_msgs::PoseStampedConstPtr &msg); + void callbackGetPose(const geometry_msgs::PoseStampedConstPtr &msg); public: - PoseToTF(); - virtual ~PoseToTF(); - void MainLoop(); + PoseToTF(); + virtual ~PoseToTF(); + void MainLoop(); }; } diff --git a/core_planning/op_utilities/launch/op_bag_player.launch b/core_planning/op_utilities/launch/op_bag_player.launch index d9790503c3c..de85b9acf11 100644 --- a/core_planning/op_utilities/launch/op_bag_player.launch +++ b/core_planning/op_utilities/launch/op_bag_player.launch @@ -1,37 +1,37 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/core_planning/op_utilities/launch/op_data_logger.launch b/core_planning/op_utilities/launch/op_data_logger.launch index 18c67ef422f..86540ed7121 100644 --- a/core_planning/op_utilities/launch/op_data_logger.launch +++ b/core_planning/op_utilities/launch/op_data_logger.launch @@ -1,13 +1,13 @@ - - - - - - - - - + + + + + + + + + diff --git a/core_planning/op_utilities/launch/op_map_converter.launch b/core_planning/op_utilities/launch/op_map_converter.launch index 90fb4d96f63..41d3f6b316c 100644 --- a/core_planning/op_utilities/launch/op_map_converter.launch +++ b/core_planning/op_utilities/launch/op_map_converter.launch @@ -1,6 +1,6 @@ - - - + + + diff --git a/core_planning/op_utilities/launch/op_pose2tf.launch b/core_planning/op_utilities/launch/op_pose2tf.launch index 93727b4d3f6..bff96342443 100644 --- a/core_planning/op_utilities/launch/op_pose2tf.launch +++ b/core_planning/op_utilities/launch/op_pose2tf.launch @@ -1,12 +1,12 @@ - - - - - - - - + + + + + + + + diff --git a/core_planning/op_utilities/nodes/op_bag_player/DrawingHelpers.cpp b/core_planning/op_utilities/nodes/op_bag_player/DrawingHelpers.cpp index 3aa947bf1d6..0ca1f7283bf 100644 --- a/core_planning/op_utilities/nodes/op_bag_player/DrawingHelpers.cpp +++ b/core_planning/op_utilities/nodes/op_bag_player/DrawingHelpers.cpp @@ -39,586 +39,586 @@ DrawingHelpers::~DrawingHelpers() void DrawingHelpers::DrawString(float x, float y, GLvoid* font_style, char* format, ...) { - glDisable(GL_LIGHTING); - - va_list args; - char buffer[1000], *s; - - va_start(args, format); - vsprintf(buffer, format, args); - va_end(args); - //GLuint ox = x; - GLuint oy = y; - - glRasterPos2f(x, y); - for (s = buffer; *s; s++) - { - if(*s == ',') - { - x += 220; - y = oy; - glRasterPos2f(x, y); - continue; - } - else if(*s == '\n') - { - y+=12; - glRasterPos2f(x, y); - continue; - } - - glutBitmapCharacter(font_style, *s); - } - glEnable(GL_LIGHTING); + glDisable(GL_LIGHTING); + + va_list args; + char buffer[1000], *s; + + va_start(args, format); + vsprintf(buffer, format, args); + va_end(args); + //GLuint ox = x; + GLuint oy = y; + + glRasterPos2f(x, y); + for (s = buffer; *s; s++) + { + if(*s == ',') + { + x += 220; + y = oy; + glRasterPos2f(x, y); + continue; + } + else if(*s == '\n') + { + y+=12; + glRasterPos2f(x, y); + continue; + } + + glutBitmapCharacter(font_style, *s); + } + glEnable(GL_LIGHTING); } void DrawingHelpers::DrawGrid(const double& x, const double& y, const double& w, const double& h, const double& cell_l) { - glPushMatrix(); - int nVerticalLisne = floor(w/cell_l); - int nHorizontalLines = floor(h/cell_l); - - glBegin(GL_LINES); - glColor3ub(210,210,210); - double incr = y; - for(int r=0; r<= nHorizontalLines; r++) - { - glNormal3f(1.0, 1.0, 1.0); - glVertex3f(x, incr, 0); - glVertex3f(x+w, incr, 0); - incr+=cell_l; - } - - double incc = x; - for(int r=0; r<= nVerticalLisne; r++) - { - glNormal3f(1.0, 1.0, 1.0); - glVertex3f(incc, y, 0); - glVertex3f(incc, y + h, 0); - incc+=cell_l; - } - glEnd(); - - glPopMatrix(); + glPushMatrix(); + int nVerticalLisne = floor(w/cell_l); + int nHorizontalLines = floor(h/cell_l); + + glBegin(GL_LINES); + glColor3ub(210,210,210); + double incr = y; + for(int r=0; r<= nHorizontalLines; r++) + { + glNormal3f(1.0, 1.0, 1.0); + glVertex3f(x, incr, 0); + glVertex3f(x+w, incr, 0); + incr+=cell_l; + } + + double incc = x; + for(int r=0; r<= nVerticalLisne; r++) + { + glNormal3f(1.0, 1.0, 1.0); + glVertex3f(incc, y, 0); + glVertex3f(incc, y + h, 0); + incc+=cell_l; + } + glEnd(); + + glPopMatrix(); } void DrawingHelpers::DrawArrow(const double& x, const double& y, const double& a) { - const int nSlicesStacks = 50; - const double percent = 20.0; - const double innerPercent = 15.0; - double half_length = 10/2.0; - - glPushMatrix(); - //Draw one cylender and cone - glTranslated(x, y, 0.5); - glRotated(a*RAD2DEG, 0,0,1); - - //X Axis - glPushMatrix(); - glColor3ub(200,200,200); - glRotated(90, 0,1,0); - glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); - glTranslated(0,0,half_length); - glColor3f(1,1,0); - glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); - glPopMatrix(); - - glPopMatrix(); + const int nSlicesStacks = 50; + const double percent = 20.0; + const double innerPercent = 15.0; + double half_length = 10/2.0; + + glPushMatrix(); + //Draw one cylender and cone + glTranslated(x, y, 0.5); + glRotated(a*RAD2DEG, 0,0,1); + + //X Axis + glPushMatrix(); + glColor3ub(200,200,200); + glRotated(90, 0,1,0); + glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); + glTranslated(0,0,half_length); + glColor3f(1,1,0); + glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); + glPopMatrix(); + + glPopMatrix(); } void DrawingHelpers::DrawCustomOrigin(const double& x, const double& y, const double& z, const int& yaw, const int& roll, const int& pitch, const double& length) { - const int nSlicesStacks = 50; - const double percent = 20.0; - const double innerPercent = 15.0; - double half_length = length/2.0; - - glPushMatrix(); - //Draw one cylender and cone - glTranslated(x, y, z); - glRotated(yaw, 0,0,1); - glRotated(roll, 1,0,0); - glRotated(pitch, 0,1,0); - - //Z Axis - glPushMatrix(); - glColor3f(0.65,0.65,0.65); - glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); - glTranslated(0,0,half_length); - glColor3f(0,0,1); - glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); - glPopMatrix(); - - //X Axis - glPushMatrix(); - glColor3f(0.65,0.65,0.65); - glRotated(90, 0,1,0); - glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); - glTranslated(0,0,half_length); - glColor3f(1,1,0); - glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); - glPopMatrix(); - -// //Y Axis - glPushMatrix(); - glColor3f(0.65,0.65,0.65); - glRotated(90, 1,0,0); - glutSolidCylinder(half_length/percent, half_length, nSlicesStacks, nSlicesStacks); - glTranslated(0,0,half_length); - glColor3f(1,0,0); - glutSolidCone(half_length/innerPercent, half_length/innerPercent, nSlicesStacks,nSlicesStacks); - glPopMatrix(); - - //glDisable(GL_LIGHTING); - glPopMatrix(); + const int nSlicesStacks = 50; + const double percent = 20.0; + const double innerPercent = 15.0; + double half_length = length/2.0; + + glPushMatrix(); + //Draw one cylender and cone + glTranslated(x, y, z); + glRotated(yaw, 0,0,1); + glRotated(roll, 1,0,0); + glRotated(pitch, 0,1,0); + + //Z Axis + glPushMatrix(); + glColor3f(0.65,0.65,0.65); + glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); + glTranslated(0,0,half_length); + glColor3f(0,0,1); + glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); + glPopMatrix(); + + //X Axis + glPushMatrix(); + glColor3f(0.65,0.65,0.65); + glRotated(90, 0,1,0); + glutSolidCylinder(half_length/percent, half_length,nSlicesStacks,nSlicesStacks); + glTranslated(0,0,half_length); + glColor3f(1,1,0); + glutSolidCone(half_length/innerPercent, half_length/innerPercent,nSlicesStacks,nSlicesStacks); + glPopMatrix(); + +// //Y Axis + glPushMatrix(); + glColor3f(0.65,0.65,0.65); + glRotated(90, 1,0,0); + glutSolidCylinder(half_length/percent, half_length, nSlicesStacks, nSlicesStacks); + glTranslated(0,0,half_length); + glColor3f(1,0,0); + glutSolidCone(half_length/innerPercent, half_length/innerPercent, nSlicesStacks,nSlicesStacks); + glPopMatrix(); + + //glDisable(GL_LIGHTING); + glPopMatrix(); } vector > DrawingHelpers::PreparePathForDrawing(const std::vector& path, - std::vector >& redyForDraw, double w, double resolution) + std::vector >& redyForDraw, double w, double resolution) { - vector > colorProfiles; - if(path.size() < 2) return colorProfiles; - int size = path.size(); - WayPoint p1 = path[0]; - WayPoint p2 =p1; - WayPoint prev_point = p1; - WayPoint center, prev_center ,pa, pb, pc, pd; - double a = 0; - double prev_angle = 0; - vector four_temp; - vector color_vector; + vector > colorProfiles; + if(path.size() < 2) return colorProfiles; + int size = path.size(); + WayPoint p1 = path[0]; + WayPoint p2 =p1; + WayPoint prev_point = p1; + WayPoint center, prev_center ,pa, pb, pc, pd; + double a = 0; + double prev_angle = 0; + vector four_temp; + vector color_vector; - for(int i=0; i < size ; i++) - { + for(int i=0; i < size ; i++) + { - color_vector.clear(); - four_temp.clear(); + color_vector.clear(); + four_temp.clear(); - pa = p2 = path[i]; + pa = p2 = path[i]; - color_vector.push_back(p1.v/12.0); - color_vector.push_back(p1.v/12.0); - color_vector.push_back(p1.v/12.0); - colorProfiles.push_back(color_vector); + color_vector.push_back(p1.v/12.0); + color_vector.push_back(p1.v/12.0); + color_vector.push_back(p1.v/12.0); + colorProfiles.push_back(color_vector); - if(distance2points(p1.pos, p2.pos) < resolution) - continue; + if(distance2points(p1.pos, p2.pos) < resolution) + continue; - center.pos.x = p1.pos.x + (p2.pos.x-p1.pos.x)/2.0; - center.pos.y = p1.pos.y + (p2.pos.y-p1.pos.y)/2.0; + center.pos.x = p1.pos.x + (p2.pos.x-p1.pos.x)/2.0; + center.pos.y = p1.pos.y + (p2.pos.y-p1.pos.y)/2.0; - a = atan2(p2.pos.y- p1.pos.y, p2.pos.x- p1.pos.x); + a = atan2(p2.pos.y- p1.pos.y, p2.pos.x- p1.pos.x); - pa.pos.x = p1.pos.x - w * cos(a - M_PI/2.0); - pa.pos.y = p1.pos.y - w * sin(a - M_PI/2.0); - pa.pos.z = p1.pos.z; + pa.pos.x = p1.pos.x - w * cos(a - M_PI/2.0); + pa.pos.y = p1.pos.y - w * sin(a - M_PI/2.0); + pa.pos.z = p1.pos.z; - pb.pos.x = p1.pos.x + w * cos(a - M_PI/2.0); - pb.pos.y = p1.pos.y + w * sin(a - M_PI/2.0); - pb.pos.z = p1.pos.z; + pb.pos.x = p1.pos.x + w * cos(a - M_PI/2.0); + pb.pos.y = p1.pos.y + w * sin(a - M_PI/2.0); + pb.pos.z = p1.pos.z; - pc.pos.x = p2.pos.x + w * cos(a - M_PI/2.0); - pc.pos.y = p2.pos.y + w * sin(a - M_PI/2.0); - pc.pos.z = p2.pos.z; + pc.pos.x = p2.pos.x + w * cos(a - M_PI/2.0); + pc.pos.y = p2.pos.y + w * sin(a - M_PI/2.0); + pc.pos.z = p2.pos.z; - pd.pos.x = p2.pos.x - w * cos(a - M_PI/2.0); - pd.pos.y = p2.pos.y - w * sin(a - M_PI/2.0); - pd.pos.z = p2.pos.z; + pd.pos.x = p2.pos.x - w * cos(a - M_PI/2.0); + pd.pos.y = p2.pos.y - w * sin(a - M_PI/2.0); + pd.pos.z = p2.pos.z; - if(!(prev_point.pos.x == p1.pos.x && prev_point.pos.y == p1.pos.y)) - { - prev_angle = atan2(p1.pos.y- prev_point.pos.y, p1.pos.x- prev_point.pos.x); + if(!(prev_point.pos.x == p1.pos.x && prev_point.pos.y == p1.pos.y)) + { + prev_angle = atan2(p1.pos.y- prev_point.pos.y, p1.pos.x- prev_point.pos.x); - pa.pos.x = p1.pos.x - w * cos(prev_angle - M_PI/2.0); - pa.pos.y = p1.pos.y - w * sin(prev_angle - M_PI/2.0); + pa.pos.x = p1.pos.x - w * cos(prev_angle - M_PI/2.0); + pa.pos.y = p1.pos.y - w * sin(prev_angle - M_PI/2.0); - pb.pos.x = p1.pos.x + w * cos(prev_angle - M_PI/2.0); - pb.pos.y = p1.pos.y + w * sin(prev_angle - M_PI/2.0); - } + pb.pos.x = p1.pos.x + w * cos(prev_angle - M_PI/2.0); + pb.pos.y = p1.pos.y + w * sin(prev_angle - M_PI/2.0); + } - four_temp.push_back(pa); - four_temp.push_back(pb); - four_temp.push_back(pc); - four_temp.push_back(pd); + four_temp.push_back(pa); + four_temp.push_back(pb); + four_temp.push_back(pc); + four_temp.push_back(pd); - redyForDraw.push_back(four_temp); + redyForDraw.push_back(four_temp); - prev_point = p1; - p1 = p2; - } - return colorProfiles; + prev_point = p1; + p1 = p2; + } + return colorProfiles; } void DrawingHelpers::DrawPrePreparedPolygons(std::vector >& path, - double z, float color[3],int nSkipPoints, const std::vector >* colorProfile) + double z, float color[3],int nSkipPoints, const std::vector >* colorProfile) { - if(!colorProfile) - glColor3f(color[0], color[1], color[2]); - - for(unsigned int i=0; i< path.size(); i+=nSkipPoints) - { - if(path[i].size() == 4) - { - if(path[i][0].pLane && (path[i][0].pLane->pRightLane || path[i][0].pLane->pLeftLane)) - glColor3f(1, 0, 0); - else if(colorProfile) - { - glColor3f(color[0]*(*colorProfile)[i][0], color[1] * (*colorProfile)[i][1], color[2] * (*colorProfile)[i][2]); - } - - glBegin(GL_POLYGON); - glNormal3f(0.0, 0.0, 0.1); -// glVertex3f(path[i][0].p.x, path[i][0].p.y,path[i][0].p.z+z); -// glVertex3f(path[i][1].p.x, path[i][1].p.y,path[i][1].p.z+z); -// glVertex3f(path[i][2].p.x, path[i][2].p.y,path[i][2].p.z+z); -// glVertex3f(path[i][3].p.x, path[i][3].p.y,path[i][3].p.z+z); - glVertex3f(path[i][0].pos.x, path[i][0].pos.y,z); - glVertex3f(path[i][1].pos.x, path[i][1].pos.y,z); - glVertex3f(path[i][2].pos.x, path[i][2].pos.y,z); - //glVertex3f((path[i][2].p.x+path[i][1].p.x)/2.0, (path[i][2].p.y+path[i][1].p.y)/2.0,z); - glVertex3f(path[i][3].pos.x, path[i][3].pos.y,z); - glEnd(); - } - } + if(!colorProfile) + glColor3f(color[0], color[1], color[2]); + + for(unsigned int i=0; i< path.size(); i+=nSkipPoints) + { + if(path[i].size() == 4) + { + if(path[i][0].pLane && (path[i][0].pLane->pRightLane || path[i][0].pLane->pLeftLane)) + glColor3f(1, 0, 0); + else if(colorProfile) + { + glColor3f(color[0]*(*colorProfile)[i][0], color[1] * (*colorProfile)[i][1], color[2] * (*colorProfile)[i][2]); + } + + glBegin(GL_POLYGON); + glNormal3f(0.0, 0.0, 0.1); +// glVertex3f(path[i][0].p.x, path[i][0].p.y,path[i][0].p.z+z); +// glVertex3f(path[i][1].p.x, path[i][1].p.y,path[i][1].p.z+z); +// glVertex3f(path[i][2].p.x, path[i][2].p.y,path[i][2].p.z+z); +// glVertex3f(path[i][3].p.x, path[i][3].p.y,path[i][3].p.z+z); + glVertex3f(path[i][0].pos.x, path[i][0].pos.y,z); + glVertex3f(path[i][1].pos.x, path[i][1].pos.y,z); + glVertex3f(path[i][2].pos.x, path[i][2].pos.y,z); + //glVertex3f((path[i][2].p.x+path[i][1].p.x)/2.0, (path[i][2].p.y+path[i][1].p.y)/2.0,z); + glVertex3f(path[i][3].pos.x, path[i][3].pos.y,z); + glEnd(); + } + } } void DrawingHelpers::DrawCostPath(const std::vector& path_points, const double& z, const double& width) { - if(path_points.size()==0) return; - - WayPoint p1 = *path_points[0]; - float color[3] = {0,0,0}; - - double max_cost = 0; - for(unsigned int i=0; i < path_points.size(); i++) - { - if(path_points.at(i)->cost > max_cost) - max_cost = path_points.at(i)->cost; - } - - int size = path_points.size(); - - for(int i=0; i < size; i++) - { - p1 = *path_points[i]; - double norm_cost = path_points.at(i)->cost / max_cost * 2.0; - if(norm_cost <= 1.0) - { - color[0] = norm_cost; - color[1] = 1.0; - } - else if(norm_cost > 1.0) - { - color[0] = 1.0; - color[1] = 2.0 - norm_cost; - } - - glColor3f(color[0], color[1], color[2]); - - //DrawLinePoygonFromCenterX(p1, z, p2, z, width, 0, prev_point); - DrawWideEllipse(p1.pos.x, p1.pos.y, z, 0.5, 0.5, 0.25, color); - } + if(path_points.size()==0) return; + + WayPoint p1 = *path_points[0]; + float color[3] = {0,0,0}; + + double max_cost = 0; + for(unsigned int i=0; i < path_points.size(); i++) + { + if(path_points.at(i)->cost > max_cost) + max_cost = path_points.at(i)->cost; + } + + int size = path_points.size(); + + for(int i=0; i < size; i++) + { + p1 = *path_points[i]; + double norm_cost = path_points.at(i)->cost / max_cost * 2.0; + if(norm_cost <= 1.0) + { + color[0] = norm_cost; + color[1] = 1.0; + } + else if(norm_cost > 1.0) + { + color[0] = 1.0; + color[1] = 2.0 - norm_cost; + } + + glColor3f(color[0], color[1], color[2]); + + //DrawLinePoygonFromCenterX(p1, z, p2, z, width, 0, prev_point); + DrawWideEllipse(p1.pos.x, p1.pos.y, z, 0.5, 0.5, 0.25, color); + } } void DrawingHelpers::DrawWidePath(const std::vector& path_points, const double& z, const double& width, float color[3], bool bGadient) { - if(path_points.size()==0) return; + if(path_points.size()==0) return; - WayPoint p1 = path_points[0]; - WayPoint p2 = p1; + WayPoint p1 = path_points[0]; + WayPoint p2 = p1; - float localColor[3] = {color[0],color[1],color[2]}; + float localColor[3] = {color[0],color[1],color[2]}; - int size = path_points.size(); - WayPoint prev_point = p1; + int size = path_points.size(); + WayPoint prev_point = p1; - for(int i=1; i < size; i+=2) - { - p2 = path_points[i]; - if(bGadient) - { - localColor[0] = color[0] * (float)(i+20)*3/(float)size; - localColor[1] = color[1] * (float)(i+20)*3/(float)size; - localColor[2] = color[2] * (float)(i+20)*3/(float)size; - } + for(int i=1; i < size; i+=2) + { + p2 = path_points[i]; + if(bGadient) + { + localColor[0] = color[0] * (float)(i+20)*3/(float)size; + localColor[1] = color[1] * (float)(i+20)*3/(float)size; + localColor[2] = color[2] * (float)(i+20)*3/(float)size; + } - if(p2.bDir == BACKWARD_DIR) - glColor3f(1,0, 0); - else - glColor3f(localColor[0],localColor[1],localColor[2]); + if(p2.bDir == BACKWARD_DIR) + glColor3f(1,0, 0); + else + glColor3f(localColor[0],localColor[1],localColor[2]); - DrawLinePoygonFromCenterX(p1, z, p2, z, width, 0, prev_point); + DrawLinePoygonFromCenterX(p1, z, p2, z, width, 0, prev_point); - prev_point = p1; + prev_point = p1; - p1 = p2; - } + p1 = p2; + } } void DrawingHelpers::DrawLinePoygonline(const PlannerHNS::GPSPoint& p1, const PlannerHNS::GPSPoint& p2, const double& w) { - GPSPoint center, prev_center ,pa, pb, pc, pd, prev_pa,prev_pb; - double a = 0; + GPSPoint center, prev_center ,pa, pb, pc, pd, prev_pa,prev_pb; + double a = 0; - center.x = p1.x + (p2.x-p1.x)/2.0; - center.y = p1.y + (p2.y-p1.y)/2.0; + center.x = p1.x + (p2.x-p1.x)/2.0; + center.y = p1.y + (p2.y-p1.y)/2.0; - a = atan2(p2.y- p1.y, p2.x- p1.x); + a = atan2(p2.y- p1.y, p2.x- p1.x); - pa.x = p1.x - w * cos(a - M_PI/2.0); - pa.y = p1.y - w * sin(a - M_PI/2.0); + pa.x = p1.x - w * cos(a - M_PI/2.0); + pa.y = p1.y - w * sin(a - M_PI/2.0); - pb.x = p1.x + w * cos(a - M_PI/2.0); - pb.y = p1.y + w * sin(a - M_PI/2.0); + pb.x = p1.x + w * cos(a - M_PI/2.0); + pb.y = p1.y + w * sin(a - M_PI/2.0); - pc.x = p2.x + w * cos(a - M_PI/2.0); - pc.y = p2.y + w * sin(a - M_PI/2.0); + pc.x = p2.x + w * cos(a - M_PI/2.0); + pc.y = p2.y + w * sin(a - M_PI/2.0); - pd.x = p2.x - w * cos(a - M_PI/2.0); - pd.y = p2.y - w * sin(a - M_PI/2.0); + pd.x = p2.x - w * cos(a - M_PI/2.0); + pd.y = p2.y - w * sin(a - M_PI/2.0); - glBegin(GL_POLYGON); - glNormal3f(0.1, 0.1, 0.1); - glVertex3f(pa.x, pa.y, p1.z); - glVertex3f(pb.x, pb.y, p1.z); - glVertex3f(pc.x, pc.y, p2.z); - glVertex3f(pd.x, pd.y, p2.z); - glEnd(); + glBegin(GL_POLYGON); + glNormal3f(0.1, 0.1, 0.1); + glVertex3f(pa.x, pa.y, p1.z); + glVertex3f(pb.x, pb.y, p1.z); + glVertex3f(pc.x, pc.y, p2.z); + glVertex3f(pd.x, pd.y, p2.z); + glEnd(); } void DrawingHelpers::DrawLinePoygonFromCenterX(const PlannerHNS::WayPoint& p1, const double& z, - const PlannerHNS::WayPoint& p2, const double& z2, const double& w, const double& h, - PlannerHNS::WayPoint& prev_point) + const PlannerHNS::WayPoint& p2, const double& z2, const double& w, const double& h, + PlannerHNS::WayPoint& prev_point) { - GPSPoint center, prev_center ,pa, pb, pc, pd, prev_pa,prev_pb; - double a = 0; - double prev_angle = 0; + GPSPoint center, prev_center ,pa, pb, pc, pd, prev_pa,prev_pb; + double a = 0; + double prev_angle = 0; - center.x = p1.pos.x + (p2.pos.x-p1.pos.x)/2.0; - center.y = p1.pos.y + (p2.pos.y-p1.pos.y)/2.0; + center.x = p1.pos.x + (p2.pos.x-p1.pos.x)/2.0; + center.y = p1.pos.y + (p2.pos.y-p1.pos.y)/2.0; - a = atan2(p2.pos.y- p1.pos.y, p2.pos.x- p1.pos.x); + a = atan2(p2.pos.y- p1.pos.y, p2.pos.x- p1.pos.x); - pa.x = p1.pos.x - w * cos(a - M_PI/2.0); - pa.y = p1.pos.y - w * sin(a - M_PI/2.0); + pa.x = p1.pos.x - w * cos(a - M_PI/2.0); + pa.y = p1.pos.y - w * sin(a - M_PI/2.0); - pb.x = p1.pos.x + w * cos(a - M_PI/2.0); - pb.y = p1.pos.y + w * sin(a - M_PI/2.0); + pb.x = p1.pos.x + w * cos(a - M_PI/2.0); + pb.y = p1.pos.y + w * sin(a - M_PI/2.0); - pc.x = p2.pos.x + w * cos(a - M_PI/2.0); - pc.y = p2.pos.y + w * sin(a - M_PI/2.0); + pc.x = p2.pos.x + w * cos(a - M_PI/2.0); + pc.y = p2.pos.y + w * sin(a - M_PI/2.0); - pd.x = p2.pos.x - w * cos(a - M_PI/2.0); - pd.y = p2.pos.y - w * sin(a - M_PI/2.0); + pd.x = p2.pos.x - w * cos(a - M_PI/2.0); + pd.y = p2.pos.y - w * sin(a - M_PI/2.0); - if(!(prev_point.pos.x == p1.pos.x && prev_point.pos.y == p1.pos.y)) - { - prev_angle = atan2(p1.pos.y- prev_point.pos.y, p1.pos.x- prev_point.pos.x); + if(!(prev_point.pos.x == p1.pos.x && prev_point.pos.y == p1.pos.y)) + { + prev_angle = atan2(p1.pos.y- prev_point.pos.y, p1.pos.x- prev_point.pos.x); - pa.x = p1.pos.x - w * cos(prev_angle - M_PI/2.0); - pa.y = p1.pos.y - w * sin(prev_angle - M_PI/2.0); + pa.x = p1.pos.x - w * cos(prev_angle - M_PI/2.0); + pa.y = p1.pos.y - w * sin(prev_angle - M_PI/2.0); - pb.x = p1.pos.x + w * cos(prev_angle - M_PI/2.0); - pb.y = p1.pos.y + w * sin(prev_angle - M_PI/2.0); + pb.x = p1.pos.x + w * cos(prev_angle - M_PI/2.0); + pb.y = p1.pos.y + w * sin(prev_angle - M_PI/2.0); - } + } - glBegin(GL_POLYGON); - glNormal3f(0.1, 0.1, 0.1); - glVertex3f(pa.x, pa.y,z); - glVertex3f(pb.x, pb.y, z); - glVertex3f(pc.x, pc.y,z); - glVertex3f(pd.x, pd.y, z); - glEnd(); + glBegin(GL_POLYGON); + glNormal3f(0.1, 0.1, 0.1); + glVertex3f(pa.x, pa.y,z); + glVertex3f(pb.x, pb.y, z); + glVertex3f(pc.x, pc.y,z); + glVertex3f(pd.x, pd.y, z); + glEnd(); } void DrawingHelpers::DrawCustomCarModel(const PlannerHNS::WayPoint& pose,const double& steeringAngle, const std::vector& carPoints,float color[3], const double& angleFix) { - if(carPoints.size() == 4) - { - double z_margin = 0.05; - - glPushMatrix(); - glTranslated(pose.pos.x, pose.pos.y, pose.pos.z); - glRotated(pose.pos.a*RAD2DEG + angleFix, 0,0,1); - for(unsigned int i = 0; i < 4; i++) - { - glBegin(GL_LINE_STRIP); - //glColor3f(0,1,1); - glColor3f(color[0],color[1],color[2]); - glVertex3f(carPoints[i].x, carPoints[i].y, carPoints[i].z); - glVertex3f(carPoints[i].x, carPoints[i].y, carPoints[i].z+1); - - glEnd(); - } - - glBegin(GL_POLYGON); - //glColor3f(0,0,1); - glColor3f(color[0],color[0],color[2]); - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); - glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+z_margin); - glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+z_margin); - glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+z_margin); - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); - - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); - glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+z_margin); - - glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+z_margin); - glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+z_margin); - - glEnd(); - - glBegin(GL_LINE_LOOP); - glColor3f(color[0],color[0],color[2]); - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); - glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+1); - glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+1); - glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+1); - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); - - glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); - glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+1); - - glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+1); - glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+1); - - glEnd(); - - - double width = fabs(carPoints[0].x - carPoints[2].x); - double length = fabs(carPoints[0].y - carPoints[2].y); - double innerRad = 1.0; - double scale_factor = 0.1; - glColor3f(0.05,0.05,0.05); - - glPushMatrix(); - glTranslated(width/2.0,length/2.0 - 0.5,0); - glScaled(scale_factor, scale_factor, scale_factor); - glRotated(90, 0,0,1); - glRotated(90, 1,0,0); - glutSolidTorus(innerRad, 3.0, 20, 20); - glPopMatrix(); - - glPushMatrix(); - glTranslated(-width/2.0,length/2.0 - 0.5,0); - glScaled(scale_factor, scale_factor, scale_factor); - glRotated(90, 0,0,1); - glRotated(90, 1,0,0); - glutSolidTorus(innerRad, 3.0, 20, 20); - glPopMatrix(); - - glPushMatrix(); - glTranslated(width/2.0,-length/2.0 + 0.5,0); - glScaled(scale_factor, scale_factor, scale_factor); - glRotated(90+steeringAngle*RAD2DEG, 0,0,1); - glRotated(90, 1,0,0); - glutSolidTorus(innerRad, 3.0, 20, 20); - glPopMatrix(); - - glPushMatrix(); - glTranslated(-width/2.0,-length/2.0 + 0.5,0); - glScaled(scale_factor, scale_factor, scale_factor); - glRotated(90+steeringAngle*RAD2DEG, 0,0,1); - glRotated(90, 1,0,0); - glutSolidTorus(innerRad, 3.0, 20, 20); - glPopMatrix(); - - - - - glPopMatrix(); - } - - DrawCustomOrigin(pose.pos.x, pose.pos.y, pose.pos.z, pose.pos.a*RAD2DEG, 0,0, 2); + if(carPoints.size() == 4) + { + double z_margin = 0.05; + + glPushMatrix(); + glTranslated(pose.pos.x, pose.pos.y, pose.pos.z); + glRotated(pose.pos.a*RAD2DEG + angleFix, 0,0,1); + for(unsigned int i = 0; i < 4; i++) + { + glBegin(GL_LINE_STRIP); + //glColor3f(0,1,1); + glColor3f(color[0],color[1],color[2]); + glVertex3f(carPoints[i].x, carPoints[i].y, carPoints[i].z); + glVertex3f(carPoints[i].x, carPoints[i].y, carPoints[i].z+1); + + glEnd(); + } + + glBegin(GL_POLYGON); + //glColor3f(0,0,1); + glColor3f(color[0],color[0],color[2]); + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); + glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+z_margin); + glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+z_margin); + glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+z_margin); + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); + + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+z_margin); + glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+z_margin); + + glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+z_margin); + glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+z_margin); + + glEnd(); + + glBegin(GL_LINE_LOOP); + glColor3f(color[0],color[0],color[2]); + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); + glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+1); + glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+1); + glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+1); + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); + + glVertex3f(carPoints[0].x, carPoints[0].y, carPoints[0].z+1); + glVertex3f(carPoints[2].x, carPoints[2].y, carPoints[2].z+1); + + glVertex3f(carPoints[1].x, carPoints[1].y, carPoints[1].z+1); + glVertex3f(carPoints[3].x, carPoints[3].y, carPoints[3].z+1); + + glEnd(); + + + double width = fabs(carPoints[0].x - carPoints[2].x); + double length = fabs(carPoints[0].y - carPoints[2].y); + double innerRad = 1.0; + double scale_factor = 0.1; + glColor3f(0.05,0.05,0.05); + + glPushMatrix(); + glTranslated(width/2.0,length/2.0 - 0.5,0); + glScaled(scale_factor, scale_factor, scale_factor); + glRotated(90, 0,0,1); + glRotated(90, 1,0,0); + glutSolidTorus(innerRad, 3.0, 20, 20); + glPopMatrix(); + + glPushMatrix(); + glTranslated(-width/2.0,length/2.0 - 0.5,0); + glScaled(scale_factor, scale_factor, scale_factor); + glRotated(90, 0,0,1); + glRotated(90, 1,0,0); + glutSolidTorus(innerRad, 3.0, 20, 20); + glPopMatrix(); + + glPushMatrix(); + glTranslated(width/2.0,-length/2.0 + 0.5,0); + glScaled(scale_factor, scale_factor, scale_factor); + glRotated(90+steeringAngle*RAD2DEG, 0,0,1); + glRotated(90, 1,0,0); + glutSolidTorus(innerRad, 3.0, 20, 20); + glPopMatrix(); + + glPushMatrix(); + glTranslated(-width/2.0,-length/2.0 + 0.5,0); + glScaled(scale_factor, scale_factor, scale_factor); + glRotated(90+steeringAngle*RAD2DEG, 0,0,1); + glRotated(90, 1,0,0); + glutSolidTorus(innerRad, 3.0, 20, 20); + glPopMatrix(); + + + + + glPopMatrix(); + } + + DrawCustomOrigin(pose.pos.x, pose.pos.y, pose.pos.z, pose.pos.a*RAD2DEG, 0,0, 2); } void DrawingHelpers::DrawFilledEllipse(float x, float y, float z, float width, float height) { - glDisable(GL_LIGHTING); - glBegin(GL_TRIANGLE_FAN); - //All triangles fan out starting with this point - glVertex3f (x,y,z); - for (float i = 0; i <=M_PI*2*RAD2DEG; i+=0.1) - { - glVertex3f(x + width*cos(i), y+height*sin(i), z); - } - glEnd(); - glEnable(GL_LIGHTING); + glDisable(GL_LIGHTING); + glBegin(GL_TRIANGLE_FAN); + //All triangles fan out starting with this point + glVertex3f (x,y,z); + for (float i = 0; i <=M_PI*2*RAD2DEG; i+=0.1) + { + glVertex3f(x + width*cos(i), y+height*sin(i), z); + } + glEnd(); + glEnable(GL_LIGHTING); } void DrawingHelpers::DrawWideEllipse(float x, float y, float z, float outer_width, float outer_height, - float inner_width,float color[3]) + float inner_width,float color[3]) { - //std::vector ellipse_points; - glColor3f(color[0], color[1], color[2]); - GPSPoint p1 = GPSPoint(x + outer_width*cos(0),y + outer_height*sin(0),z,0); - GPSPoint p2 = p1; - for (float i = 0.1; i <= M_PI*2 + 0.1; i+=0.1) - { - //ellipse_points.push_back(WayPoint(x + outer_width*cos(i), y+outer_height*sin(i), z, 0)); - p2.x = x + outer_width*cos(i); - p2.y = y + outer_height*sin(i); - p2.z = z; - - DrawLinePoygonline(p1,p2, outer_width - inner_width); - p1 = p2; - - } - - //DrawWidePath(ellipse_points, z, outer_width - inner_width,color); + //std::vector ellipse_points; + glColor3f(color[0], color[1], color[2]); + GPSPoint p1 = GPSPoint(x + outer_width*cos(0),y + outer_height*sin(0),z,0); + GPSPoint p2 = p1; + for (float i = 0.1; i <= M_PI*2 + 0.1; i+=0.1) + { + //ellipse_points.push_back(WayPoint(x + outer_width*cos(i), y+outer_height*sin(i), z, 0)); + p2.x = x + outer_width*cos(i); + p2.y = y + outer_height*sin(i); + p2.z = z; + + DrawLinePoygonline(p1,p2, outer_width - inner_width); + p1 = p2; + + } + + //DrawWidePath(ellipse_points, z, outer_width - inner_width,color); } void DrawingHelpers::DrawSimpleEllipse(float x, float y, float z, float outer_width, float outer_height) { - glBegin(GL_LINE_STRIP); - for (float jj = 0; jj <=M_PI*2.0; jj+=0.1) - { - glVertex3f(x + outer_width*cos(jj), y+ outer_height*sin(jj),z); - } - glEnd(); + glBegin(GL_LINE_STRIP); + for (float jj = 0; jj <=M_PI*2.0; jj+=0.1) + { + glVertex3f(x + outer_width*cos(jj), y+ outer_height*sin(jj),z); + } + glEnd(); } void DrawingHelpers::DrawPedal(float x, float y, float z, float width, float height, float inner_height, float color[3]) { - GPSPoint pa, pb, pc, pd; - double w2 = width/2.0; - double h2 = height/2.0; + GPSPoint pa, pb, pc, pd; + double w2 = width/2.0; + double h2 = height/2.0; - pa.x = x - w2; - pa.y = y - h2; + pa.x = x - w2; + pa.y = y - h2; - pb.x = x + w2; - pb.y = y - h2; + pb.x = x + w2; + pb.y = y - h2; - pc.x = x + w2; - pc.y = y + h2; + pc.x = x + w2; + pc.y = y + h2; - pd.x = x - w2; - pd.y = y + h2; + pd.x = x - w2; + pd.y = y + h2; - glBegin(GL_LINE_LOOP); - glVertex3f(pa.x, pa.y, z); - glVertex3f(pb.x, pb.y, z); - glVertex3f(pc.x, pc.y, z); - glVertex3f(pd.x, pd.y, z); - glEnd(); + glBegin(GL_LINE_LOOP); + glVertex3f(pa.x, pa.y, z); + glVertex3f(pb.x, pb.y, z); + glVertex3f(pc.x, pc.y, z); + glVertex3f(pd.x, pd.y, z); + glEnd(); - GPSPoint p1(x, y + h2, z, 0); - GPSPoint p2(x, y + h2 - inner_height, z, 0); + GPSPoint p1(x, y + h2, z, 0); + GPSPoint p2(x, y + h2 - inner_height, z, 0); - glColor3f(color[0], color[1], color[2]); - DrawLinePoygonline(p1,p2,w2); + glColor3f(color[0], color[1], color[2]); + DrawLinePoygonline(p1,p2,w2); } diff --git a/core_planning/op_utilities/nodes/op_bag_player/MainWindowWrapper.cpp b/core_planning/op_utilities/nodes/op_bag_player/MainWindowWrapper.cpp index 0a93909e501..d5b0131bff5 100644 --- a/core_planning/op_utilities/nodes/op_bag_player/MainWindowWrapper.cpp +++ b/core_planning/op_utilities/nodes/op_bag_player/MainWindowWrapper.cpp @@ -33,71 +33,71 @@ DisplayParams MainWindowWrapper::m_DisplayParam; WindowParams::WindowParams() { - title = "Testing UI"; + title = "Testing UI"; - x = 10; - y = 10; - w = 400; - h = 200; - info_ratio = 0.25; + x = 10; + y = 10; + w = 400; + h = 200; + info_ratio = 0.25; - UI_CONST.GAP = 20; - UI_CONST.MAX_ZOOM = 600000.0; - UI_CONST.MIN_ZOOM = 2.01; - UI_CONST.INIT_ZOOM = 7.0; - UI_CONST.FOLLOW_CONST_ZOOM = 2.5; + UI_CONST.GAP = 20; + UI_CONST.MAX_ZOOM = 600000.0; + UI_CONST.MIN_ZOOM = 2.01; + UI_CONST.INIT_ZOOM = 7.0; + UI_CONST.FOLLOW_CONST_ZOOM = 2.5; - ReCalcSimuWindow(); + ReCalcSimuWindow(); - bNew = true; - bGPU = true; + bNew = true; + bGPU = true; } void WindowParams::ReCalcSimuWindow() { - simu_window.x = UI_CONST.GAP; - simu_window.y = UI_CONST.GAP; - simu_window.w = w - UI_CONST.GAP * 2.0; - simu_window.h = h - UI_CONST.GAP * 2.0; + simu_window.x = UI_CONST.GAP; + simu_window.y = UI_CONST.GAP; + simu_window.w = w - UI_CONST.GAP * 2.0; + simu_window.h = h - UI_CONST.GAP * 2.0; } DisplayParams::DisplayParams() { - prev_x = prev_y = -999999; - currRotationZ = currRotationX = currRotationY = 0; + prev_x = prev_y = -999999; + currRotationZ = currRotationX = currRotationY = 0; - zoom = 15; - centerRotX = 5; - centerRotY = 5; + zoom = 15; + centerRotX = 5; + centerRotY = 5; - eye[0] = 0.0; eye[1] = 0.0; eye[2] = zoom; - at[0] = 0.0; at[1] = 0.0; at[2] = 0.0; - up[0] = 0.0; up[1] = 1.0; up[2] = 0.0; + eye[0] = 0.0; eye[1] = 0.0; eye[2] = zoom; + at[0] = 0.0; at[1] = 0.0; at[2] = 0.0; + up[0] = 0.0; up[1] = 1.0; up[2] = 0.0; - bDisplayMode = DISPLAY_TOP_FREE; + bDisplayMode = DISPLAY_TOP_FREE; - bLeftDown = bRightDown = bCenterDown = false;; + bLeftDown = bRightDown = bCenterDown = false;; - prespective_z = 100; - prespective_fov = 45; + prespective_z = 100; + prespective_fov = 45; - translateX = 5; - translateY = 5; + translateX = 5; + translateY = 5; - actualViewX = 0; - actualViewY = 0; + actualViewX = 0; + actualViewY = 0; - bFullScreen = false; + bFullScreen = false; - bSelectPosition = 0; - StartPos[0] = StartPosFinal[0] = 0; - StartPos[1] = StartPosFinal[1] = 0; - StartPos[2] = StartPosFinal[2] = 0; - GoalPos[0] = GoalPosFinal[0] = 0; - GoalPos[1] = GoalPosFinal[1] = 0; - GoalPos[2] = GoalPosFinal[1] = 0; - SimulatedCarPos[0] = SimulatedCarPos[1] = SimulatedCarPos[2] = 0; + bSelectPosition = 0; + StartPos[0] = StartPosFinal[0] = 0; + StartPos[1] = StartPosFinal[1] = 0; + StartPos[2] = StartPosFinal[2] = 0; + GoalPos[0] = GoalPosFinal[0] = 0; + GoalPos[1] = GoalPosFinal[1] = 0; + GoalPos[2] = GoalPosFinal[1] = 0; + SimulatedCarPos[0] = SimulatedCarPos[1] = SimulatedCarPos[2] = 0; } @@ -109,213 +109,213 @@ DrawObjBase* MainWindowWrapper::m_DrawAndControl = 0; MainWindowWrapper::MainWindowWrapper(DrawObjBase* pDraw) { - m_DrawAndControl = pDraw; + m_DrawAndControl = pDraw; } MainWindowWrapper::~MainWindowWrapper(){} void MainWindowWrapper::CleanUp() { - if(m_DrawAndControl) - delete m_DrawAndControl; + if(m_DrawAndControl) + delete m_DrawAndControl; } void MainWindowWrapper::InitOpenGLWindow(int argc, char** argv) { - if(m_params.bGPU) - glutInitDisplayMode(GLUT_RGBA | GLUT_MULTISAMPLE); - else - glutInitDisplayMode(GLUT_RGB | GLUT_DEPTH | GLUT_SINGLE); - glutInitWindowSize(m_params.w, m_params.h ); - glutInitWindowPosition(m_params.x, m_params.y); - glutInit(&argc, argv); + if(m_params.bGPU) + glutInitDisplayMode(GLUT_RGBA | GLUT_MULTISAMPLE); + else + glutInitDisplayMode(GLUT_RGB | GLUT_DEPTH | GLUT_SINGLE); + glutInitWindowSize(m_params.w, m_params.h ); + glutInitWindowPosition(m_params.x, m_params.y); + glutInit(&argc, argv); - m_MainWindow = glutCreateWindow(m_params.title.c_str()); - glutReshapeFunc(MainWindowWrapper::MainReshape); - glutDisplayFunc(MainWindowWrapper::MainDisplay); - glutKeyboardFunc(MainWindowWrapper::KeyboardExitCommand); + m_MainWindow = glutCreateWindow(m_params.title.c_str()); + glutReshapeFunc(MainWindowWrapper::MainReshape); + glutDisplayFunc(MainWindowWrapper::MainDisplay); + glutKeyboardFunc(MainWindowWrapper::KeyboardExitCommand); - m_SimuWindow = glutCreateSubWindow(m_MainWindow, m_params.simu_window.x, m_params.simu_window.y, m_params.simu_window.w, m_params.simu_window.h); - glutReshapeFunc(MainWindowWrapper::SimuReshape); - glutDisplayFunc(MainWindowWrapper::SimuDisplay); - glutKeyboardFunc(MainWindowWrapper::KeyboardCommand); - glutSpecialFunc(MainWindowWrapper::KeyboardSpecialCommand); + m_SimuWindow = glutCreateSubWindow(m_MainWindow, m_params.simu_window.x, m_params.simu_window.y, m_params.simu_window.w, m_params.simu_window.h); + glutReshapeFunc(MainWindowWrapper::SimuReshape); + glutDisplayFunc(MainWindowWrapper::SimuDisplay); + glutKeyboardFunc(MainWindowWrapper::KeyboardCommand); + glutSpecialFunc(MainWindowWrapper::KeyboardSpecialCommand); - glutPostRedisplay(); + glutPostRedisplay(); - KeyboardCommand('f', 0,0); + KeyboardCommand('f', 0,0); - atexit(CleanUp); + atexit(CleanUp); - cout << "Before The OpenGL Main Loop" << endl; + cout << "Before The OpenGL Main Loop" << endl; - glutMainLoop(); + glutMainLoop(); } void MainWindowWrapper::InitLighting() { - float light_ambient[] = { 0.5,1.0, 0.5, 0.0 }; - float defuse[] = {1.0, 1.0, 1.0,1.0}; - float mat_specular[] = { 1.0, 1.0, 1.0, 0.0 }; - float mat_shininess[] = { 50.0 }; - //float light_position[4] = { 0.0, 0.0, 20.0, 0.0 }; - glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, defuse); - glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, light_ambient); - glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, mat_specular); - glMaterialfv(GL_FRONT_AND_BACK, GL_SHININESS, mat_shininess); - //glLightfv(GL_LIGHT0, GL_POSITION, light_position); - glEnable(GL_LIGHTING); - glEnable(GL_LIGHT0); - glEnable(GL_COLOR_MATERIAL); - glEnable(GL_DEPTH_TEST); - glShadeModel(GL_SMOOTH); + float light_ambient[] = { 0.5,1.0, 0.5, 0.0 }; + float defuse[] = {1.0, 1.0, 1.0,1.0}; + float mat_specular[] = { 1.0, 1.0, 1.0, 0.0 }; + float mat_shininess[] = { 50.0 }; + //float light_position[4] = { 0.0, 0.0, 20.0, 0.0 }; + glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, defuse); + glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, light_ambient); + glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, mat_specular); + glMaterialfv(GL_FRONT_AND_BACK, GL_SHININESS, mat_shininess); + //glLightfv(GL_LIGHT0, GL_POSITION, light_position); + glEnable(GL_LIGHTING); + glEnable(GL_LIGHT0); + glEnable(GL_COLOR_MATERIAL); + glEnable(GL_DEPTH_TEST); + glShadeModel(GL_SMOOTH); } void MainWindowWrapper::UpdateParams(const WindowParams& params, const DisplayParams& display_params) { - m_params = params; - m_DisplayParam = display_params; - FromScreenToModelCoordinate(m_params.simu_window.w/2.0, m_params.simu_window.h/2.0, - m_DisplayParam.initScreenToCenterMargin[0], m_DisplayParam.initScreenToCenterMargin[1]); + m_params = params; + m_DisplayParam = display_params; + FromScreenToModelCoordinate(m_params.simu_window.w/2.0, m_params.simu_window.h/2.0, + m_DisplayParam.initScreenToCenterMargin[0], m_DisplayParam.initScreenToCenterMargin[1]); } void MainWindowWrapper::MainReshape(int width, int height) { - m_params.w = width; - m_params.h = height; - m_params.ReCalcSimuWindow(); - - glViewport(0,0, m_params.w, m_params.h); - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - gluOrtho2D(0, m_params.w, m_params.h, 0); - glMatrixMode(GL_MODELVIEW); - glLoadIdentity(); - glutPostWindowRedisplay(m_SimuWindow); + m_params.w = width; + m_params.h = height; + m_params.ReCalcSimuWindow(); + + glViewport(0,0, m_params.w, m_params.h); + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + gluOrtho2D(0, m_params.w, m_params.h, 0); + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + glutPostWindowRedisplay(m_SimuWindow); } void MainWindowWrapper::SimuReshape(int width, int height) { - glutPositionWindow(m_params.simu_window.x, m_params.simu_window.y); - glutReshapeWindow(m_params.simu_window.w, m_params.simu_window.h); + glutPositionWindow(m_params.simu_window.x, m_params.simu_window.y); + glutReshapeWindow(m_params.simu_window.w, m_params.simu_window.h); - glViewport(0,0, m_params.simu_window.w, m_params.simu_window.h); + glViewport(0,0, m_params.simu_window.w, m_params.simu_window.h); - //this should rely on the map not the window - double y_max = sqrt(pow(m_params.simu_window.w,2) + pow(m_params.simu_window.h,2))/2.0; - if(y_max > 0.05 && y_max < (m_params.simu_window.w*m_params.simu_window.h)) - m_DisplayParam.prespective_z = y_max; + //this should rely on the map not the window + double y_max = sqrt(pow(m_params.simu_window.w,2) + pow(m_params.simu_window.h,2))/2.0; + if(y_max > 0.05 && y_max < (m_params.simu_window.w*m_params.simu_window.h)) + m_DisplayParam.prespective_z = y_max; - m_DisplayParam.prespective_z = 10000; + m_DisplayParam.prespective_z = 10000; - glMatrixMode(GL_PROJECTION); - glLoadIdentity(); - double aspect_ratio = (double)m_params.simu_window.w/(double)m_params.simu_window.h; + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + double aspect_ratio = (double)m_params.simu_window.w/(double)m_params.simu_window.h; - gluPerspective(m_DisplayParam.prespective_fov,aspect_ratio,0.05,m_DisplayParam.prespective_z); - glMatrixMode(GL_MODELVIEW); - glLoadIdentity(); + gluPerspective(m_DisplayParam.prespective_fov,aspect_ratio,0.05,m_DisplayParam.prespective_z); + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); - if(m_DisplayParam.bDisplayMode == DISPLAY_FOLLOW && m_DrawAndControl) - { - m_DisplayParam.eye[0] = m_DisplayParam.centerRotX; - m_DisplayParam.eye[1] = m_DisplayParam.centerRotY; - m_DisplayParam.at[0] = m_DisplayParam.centerRotX; - m_DisplayParam.at[1] = m_DisplayParam.centerRotY; - } + if(m_DisplayParam.bDisplayMode == DISPLAY_FOLLOW && m_DrawAndControl) + { + m_DisplayParam.eye[0] = m_DisplayParam.centerRotX; + m_DisplayParam.eye[1] = m_DisplayParam.centerRotY; + m_DisplayParam.at[0] = m_DisplayParam.centerRotX; + m_DisplayParam.at[1] = m_DisplayParam.centerRotY; + } - gluLookAt(m_DisplayParam.eye[0], m_DisplayParam.eye[1], m_DisplayParam.zoom, - m_DisplayParam.at[0], m_DisplayParam.at[1], m_DisplayParam.at[2], - m_DisplayParam.up[0], m_DisplayParam.up[1],m_DisplayParam.up[2]); + gluLookAt(m_DisplayParam.eye[0], m_DisplayParam.eye[1], m_DisplayParam.zoom, + m_DisplayParam.at[0], m_DisplayParam.at[1], m_DisplayParam.at[2], + m_DisplayParam.up[0], m_DisplayParam.up[1],m_DisplayParam.up[2]); - InitLighting(); + InitLighting(); } void MainWindowWrapper::FromScreenToModelCoordinate(int sx, int sy, double& modelX, double& modelY) { - double whole = (double)(m_params.simu_window.w + m_params.simu_window.h)/2.0; - double actualViewX = tan(m_DisplayParam.prespective_fov*DEG2RAD) * m_DisplayParam.zoom / whole; + double whole = (double)(m_params.simu_window.w + m_params.simu_window.h)/2.0; + double actualViewX = tan(m_DisplayParam.prespective_fov*DEG2RAD) * m_DisplayParam.zoom / whole; - modelX = sx * actualViewX ; - modelY = sy * actualViewX ; + modelX = sx * actualViewX ; + modelY = sy * actualViewX ; } void MainWindowWrapper::FromModelToScreenCoordinate(double modelX, double modelY, int& sx, int& sy) { - double actualViewX = tan(m_DisplayParam.prespective_fov*DEG2RAD) * m_DisplayParam.zoom / m_params.simu_window.w; + double actualViewX = tan(m_DisplayParam.prespective_fov*DEG2RAD) * m_DisplayParam.zoom / m_params.simu_window.w; - sx = modelX / actualViewX ; - sy = modelY / actualViewX ; + sx = modelX / actualViewX ; + sy = modelY / actualViewX ; } void MainWindowWrapper::SimuDisplay() { - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - if(m_DrawAndControl) - m_DrawAndControl->DrawSimu(); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + if(m_DrawAndControl) + m_DrawAndControl->DrawSimu(); - glutSwapBuffers(); + glutSwapBuffers(); } void MainWindowWrapper::MainDisplay() { - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - - glDisable(GL_LIGHTING); - glPushMatrix(); - glBegin(GL_POLYGON); - glColor3f(0.1,0.1,0.1); - glVertex2i(0, m_params.h); - glVertex2i(m_params.w,m_params.h); - glColor3f(0.9,0.9,0.9); - glVertex2i(m_params.w, 0); - glVertex2i(0,0); - glEnd(); - glPopMatrix(); - glEnable(GL_LIGHTING); - - glPushMatrix(); - glColor3f(0.9, 0.2, 0.2); - glTranslated(m_params.simu_window.x, m_params.UI_CONST.GAP-1, 0); - DrawingHelpers::DrawString(0, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)"Command Input Window"); - glPopMatrix(); - - glutSwapBuffers(); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glDisable(GL_LIGHTING); + glPushMatrix(); + glBegin(GL_POLYGON); + glColor3f(0.1,0.1,0.1); + glVertex2i(0, m_params.h); + glVertex2i(m_params.w,m_params.h); + glColor3f(0.9,0.9,0.9); + glVertex2i(m_params.w, 0); + glVertex2i(0,0); + glEnd(); + glPopMatrix(); + glEnable(GL_LIGHTING); + + glPushMatrix(); + glColor3f(0.9, 0.2, 0.2); + glTranslated(m_params.simu_window.x, m_params.UI_CONST.GAP-1, 0); + DrawingHelpers::DrawString(0, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)"Command Input Window"); + glPopMatrix(); + + glutSwapBuffers(); } void MainWindowWrapper::KeyboardExitCommand(unsigned char key, int x, int y) { - switch (key) - { - case 27: - exit(0); - break; - } + switch (key) + { + case 27: + exit(0); + break; + } } void MainWindowWrapper::KeyboardCommand(unsigned char key, int x, int y) { - //cout << "Char : " << (int)key << endl; - if(m_DrawAndControl) - m_DrawAndControl->OnKeyboardPress(0, key); - - switch (key) - { - case 27: - exit(0); - break; - } + //cout << "Char : " << (int)key << endl; + if(m_DrawAndControl) + m_DrawAndControl->OnKeyboardPress(0, key); + + switch (key) + { + case 27: + exit(0); + break; + } } void MainWindowWrapper::KeyboardSpecialCommand(int key, int x, int y) { - //cout << "Control : " << key << endl; + //cout << "Control : " << key << endl; - if(m_DrawAndControl) - m_DrawAndControl->OnKeyboardPress(key, 0); + if(m_DrawAndControl) + m_DrawAndControl->OnKeyboardPress(key, 0); } } diff --git a/core_planning/op_utilities/nodes/op_bag_player/op_bag_player.cpp b/core_planning/op_utilities/nodes/op_bag_player/op_bag_player.cpp index 750339430d3..176f993fafd 100644 --- a/core_planning/op_utilities/nodes/op_bag_player/op_bag_player.cpp +++ b/core_planning/op_utilities/nodes/op_bag_player/op_bag_player.cpp @@ -22,42 +22,42 @@ using namespace OP_TESTING_NS; int main(int argc, char **argv) { - ros::init(argc, argv, "op_bag_player"); + ros::init(argc, argv, "op_bag_player"); - WindowParams pms; - DisplayParams dpms; - dpms.centerRotX = 0; - dpms.centerRotY = 0; - dpms.translateX = 0; - dpms.translateY = 0; - ros::NodeHandle nh; + WindowParams pms; + DisplayParams dpms; + dpms.centerRotX = 0; + dpms.centerRotY = 0; + dpms.translateX = 0; + dpms.translateY = 0; + ros::NodeHandle nh; - nh.getParam("/op_bag_player/width", pms.w); - nh.getParam("/op_bag_player/height", pms.h); - nh.getParam("/op_bag_player/info_ratio", pms.info_ratio); + nh.getParam("/op_bag_player/width", pms.w); + nh.getParam("/op_bag_player/height", pms.h); + nh.getParam("/op_bag_player/info_ratio", pms.info_ratio); - BagReaderParams bag_params; + BagReaderParams bag_params; - nh.getParam("/op_bag_player/rosbag_file", bag_params.fileName); + nh.getParam("/op_bag_player/rosbag_file", bag_params.fileName); - nh.getParam("/op_bag_player/lidar_topic_bag", bag_params.lidarTopic); - nh.getParam("/op_bag_player/pose_topic_bag", bag_params.poseTopic); - nh.getParam("/op_bag_player/image_topic_bag", bag_params.imageTopic); + nh.getParam("/op_bag_player/lidar_topic_bag", bag_params.lidarTopic); + nh.getParam("/op_bag_player/pose_topic_bag", bag_params.poseTopic); + nh.getParam("/op_bag_player/image_topic_bag", bag_params.imageTopic); - nh.getParam("/op_bag_player/lidar_topic_pub", bag_params.lidarTopic_pub); - nh.getParam("/op_bag_player/pose_topic_pub", bag_params.poseTopic_pub); - nh.getParam("/op_bag_player/image_topic_pub", bag_params.imageTopic_pub); + nh.getParam("/op_bag_player/lidar_topic_pub", bag_params.lidarTopic_pub); + nh.getParam("/op_bag_player/pose_topic_pub", bag_params.poseTopic_pub); + nh.getParam("/op_bag_player/image_topic_pub", bag_params.imageTopic_pub); - int test_mode = 0; - nh.getParam("/op_bag_player/testing_mode", test_mode); + int test_mode = 0; + nh.getParam("/op_bag_player/testing_mode", test_mode); - DrawObjBase* pSimulator = 0; - pSimulator = new TestingUI(); - ((TestingUI*)pSimulator)->InitNode(bag_params, test_mode); + DrawObjBase* pSimulator = 0; + pSimulator = new TestingUI(); + ((TestingUI*)pSimulator)->InitNode(bag_params, test_mode); - MainWindowWrapper wrapper(pSimulator); - wrapper.UpdateParams(pms, dpms); - wrapper.InitOpenGLWindow(argc, argv); + MainWindowWrapper wrapper(pSimulator); + wrapper.UpdateParams(pms, dpms); + wrapper.InitOpenGLWindow(argc, argv); - return 0; + return 0; } diff --git a/core_planning/op_utilities/nodes/op_bag_player/op_bag_player_core.cpp b/core_planning/op_utilities/nodes/op_bag_player/op_bag_player_core.cpp index 5cad3a3ebf2..ba039bed81c 100644 --- a/core_planning/op_utilities/nodes/op_bag_player/op_bag_player_core.cpp +++ b/core_planning/op_utilities/nodes/op_bag_player/op_bag_player_core.cpp @@ -35,16 +35,16 @@ using namespace std; TestingUI::TestingUI() { - m_bStepDone = false; - m_PlayMode = PLAY_PAUSE; - m_TestMode = SIMULATION_MODE; - m_bBagOpen = false; - m_bStepForward = false; - m_bPredStepForward = false; - m_bGenerateSignal = false; - - m_VehicleTargetStateAccelerator = 0; - m_VehicleTargetStateBrake = 0; + m_bStepDone = false; + m_PlayMode = PLAY_PAUSE; + m_TestMode = SIMULATION_MODE; + m_bBagOpen = false; + m_bStepForward = false; + m_bPredStepForward = false; + m_bGenerateSignal = false; + + m_VehicleTargetStateAccelerator = 0; + m_VehicleTargetStateBrake = 0; } TestingUI::~TestingUI() @@ -53,101 +53,101 @@ TestingUI::~TestingUI() void TestingUI::DrawSimu() { - glPushMatrix(); -// std::ostringstream str_out ; -// str_out << "Frame Number:" << 1; -// DrawingHelpers::DrawString(-2, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)m_ReadingInfo.c_str()); -// DrawingHelpers::DrawString(-2, -2, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out.str().c_str()); - glPopMatrix(); - - ros::Rate loop_rate(100); - - if(ros::ok()) - { - if(m_TestMode == SIMULATION_MODE) - { - SimulationModeMainLoop(); - } - else if (m_TestMode == ROSBAG_MODE) - { - BagReaderModeMainLoop(); - std::ostringstream str_out_pose, str_out_image, str_out_cloud; - int _sec=0; - int _nsec=0; - int iFrame = 0; - int nFrames = 0; - - m_PoseReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); - str_out_pose <<"* Pose : " << _sec << " (" << iFrame << "/" << nFrames << ")"; - - m_CloudReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); - str_out_cloud <<"* Cloud: " << _sec << " (" << iFrame << "/" << nFrames << ")"; - - m_ImageReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); - str_out_image <<"* Image: " << _sec << " (" << iFrame << "/" << nFrames << ")"; - - glPushMatrix(); - DrawingHelpers::DrawString(-3, 2, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_pose.str().c_str()); - DrawingHelpers::DrawString(-3, 1, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_cloud.str().c_str()); - DrawingHelpers::DrawString(-3, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_image.str().c_str()); - glPopMatrix(); - } - - ros::spinOnce(); - loop_rate.sleep(); - } + glPushMatrix(); +// std::ostringstream str_out ; +// str_out << "Frame Number:" << 1; +// DrawingHelpers::DrawString(-2, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)m_ReadingInfo.c_str()); +// DrawingHelpers::DrawString(-2, -2, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out.str().c_str()); + glPopMatrix(); + + ros::Rate loop_rate(100); + + if(ros::ok()) + { + if(m_TestMode == SIMULATION_MODE) + { + SimulationModeMainLoop(); + } + else if (m_TestMode == ROSBAG_MODE) + { + BagReaderModeMainLoop(); + std::ostringstream str_out_pose, str_out_image, str_out_cloud; + int _sec=0; + int _nsec=0; + int iFrame = 0; + int nFrames = 0; + + m_PoseReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); + str_out_pose <<"* Pose : " << _sec << " (" << iFrame << "/" << nFrames << ")"; + + m_CloudReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); + str_out_cloud <<"* Cloud: " << _sec << " (" << iFrame << "/" << nFrames << ")"; + + m_ImageReader.GetReadingInfo(_sec, _nsec, iFrame, nFrames); + str_out_image <<"* Image: " << _sec << " (" << iFrame << "/" << nFrames << ")"; + + glPushMatrix(); + DrawingHelpers::DrawString(-3, 2, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_pose.str().c_str()); + DrawingHelpers::DrawString(-3, 1, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_cloud.str().c_str()); + DrawingHelpers::DrawString(-3, 0, GLUT_BITMAP_TIMES_ROMAN_24, (char*)str_out_image.str().c_str()); + glPopMatrix(); + } + + ros::spinOnce(); + loop_rate.sleep(); + } } void TestingUI::SimulationModeMainLoop() { - if(m_bPredStepForward) - { - geometry_msgs::TwistStamped s_signal; - s_signal.header.frame_id = "velodyne"; - s_signal.header.stamp = ros::Time(); - s_signal.twist.linear.x = 1; - pub_PredStepSignal.publish(s_signal); - m_bPredStepForward = false; - } - - if(m_bStepForward) - { - geometry_msgs::TwistStamped s_signal; - s_signal.header.frame_id = "velodyne"; - s_signal.header.stamp = ros::Time(); - s_signal.twist.linear.x = 1; - pub_SimuStepSignal.publish(s_signal); - m_bStepForward = false; - m_bPredStepForward = true; - } - - if(m_bGenerateSignal) - { - geometry_msgs::TwistStamped g_signal; - g_signal.header.frame_id = "velodyne"; - g_signal.header.stamp = ros::Time(); - g_signal.twist.linear.x = 1; - pub_SimuGenSignal.publish(g_signal); - m_bGenerateSignal = false; - } + if(m_bPredStepForward) + { + geometry_msgs::TwistStamped s_signal; + s_signal.header.frame_id = "velodyne"; + s_signal.header.stamp = ros::Time(); + s_signal.twist.linear.x = 1; + pub_PredStepSignal.publish(s_signal); + m_bPredStepForward = false; + } + + if(m_bStepForward) + { + geometry_msgs::TwistStamped s_signal; + s_signal.header.frame_id = "velodyne"; + s_signal.header.stamp = ros::Time(); + s_signal.twist.linear.x = 1; + pub_SimuStepSignal.publish(s_signal); + m_bStepForward = false; + m_bPredStepForward = true; + } + + if(m_bGenerateSignal) + { + geometry_msgs::TwistStamped g_signal; + g_signal.header.frame_id = "velodyne"; + g_signal.header.stamp = ros::Time(); + g_signal.twist.linear.x = 1; + pub_SimuGenSignal.publish(g_signal); + m_bGenerateSignal = false; + } } bool TestingUI::OpenROSBag() { try { - cout << "Openning ROSbag File: " << m_BagParams.fileName << endl; - m_bag.open(m_BagParams.fileName, rosbag::bagmode::Read); + cout << "Openning ROSbag File: " << m_BagParams.fileName << endl; + m_bag.open(m_BagParams.fileName, rosbag::bagmode::Read); - m_CloudReader.InitPlayer(m_bag, m_BagParams.lidarTopic); - m_ImageReader.InitPlayer(m_bag, m_BagParams.imageTopic); - m_PoseReader.InitPlayer(m_bag, m_BagParams.poseTopic); + m_CloudReader.InitPlayer(m_bag, m_BagParams.lidarTopic); + m_ImageReader.InitPlayer(m_bag, m_BagParams.imageTopic); + m_PoseReader.InitPlayer(m_bag, m_BagParams.poseTopic); - return true; + return true; } catch (rosbag::BagIOException& e) { - std::cout << "Can't Open ROSbaf with path: " << m_BagParams.fileName << std::endl; + std::cout << "Can't Open ROSbaf with path: " << m_BagParams.fileName << std::endl; ROS_ERROR_STREAM(e.what()); return false; } @@ -155,201 +155,201 @@ bool TestingUI::OpenROSBag() void TestingUI::BagReaderModeMainLoop() { - if(m_bBagOpen) - { - bool bFreshMsg = false; - - if(m_PlayMode == PLAY_FORWARD) - { - bFreshMsg = ReadNextFrame(); - } - else if(m_PlayMode == PLAY_STEP_FORWARD) - { - if(!m_bStepDone) - { - bFreshMsg = ReadNextFrame(); - m_bStepDone = true; - } - } - else if(m_PlayMode == PLAY_STEP_BACKWARD) - { - if(!m_bStepDone) - { - bFreshMsg = ReadPrevFrame(); - m_bStepDone = true; - } - } - - if(bFreshMsg && m_pLatestCloud != NULL) - { - sensor_msgs::PointCloud2 cloud = *m_pLatestCloud; - cloud.header.stamp = ros::Time::now(); - pub_Point_Raw.publish(cloud); - } - - if(bFreshMsg && m_pLatestImage != NULL) - { - sensor_msgs::Image img = *m_pLatestImage; - img.header.stamp = ros::Time().now(); - pub_Image_Raw.publish(img); - } - - if(bFreshMsg && m_pLatestPose != NULL) - { - geometry_msgs::PoseStamped pos = *m_pLatestPose; - pos.header.stamp = ros::Time::now(); - pub_NDT_pose.publish(pos); - } - } + if(m_bBagOpen) + { + bool bFreshMsg = false; + + if(m_PlayMode == PLAY_FORWARD) + { + bFreshMsg = ReadNextFrame(); + } + else if(m_PlayMode == PLAY_STEP_FORWARD) + { + if(!m_bStepDone) + { + bFreshMsg = ReadNextFrame(); + m_bStepDone = true; + } + } + else if(m_PlayMode == PLAY_STEP_BACKWARD) + { + if(!m_bStepDone) + { + bFreshMsg = ReadPrevFrame(); + m_bStepDone = true; + } + } + + if(bFreshMsg && m_pLatestCloud != NULL) + { + sensor_msgs::PointCloud2 cloud = *m_pLatestCloud; + cloud.header.stamp = ros::Time::now(); + pub_Point_Raw.publish(cloud); + } + + if(bFreshMsg && m_pLatestImage != NULL) + { + sensor_msgs::Image img = *m_pLatestImage; + img.header.stamp = ros::Time().now(); + pub_Image_Raw.publish(img); + } + + if(bFreshMsg && m_pLatestPose != NULL) + { + geometry_msgs::PoseStamped pos = *m_pLatestPose; + pos.header.stamp = ros::Time::now(); + pub_NDT_pose.publish(pos); + } + } } bool TestingUI::ReadNextFrame() { - geometry_msgs::PoseStampedPtr pPose; + geometry_msgs::PoseStampedPtr pPose; - bool bPose = false, bCloud = false, bImage = false; + bool bPose = false, bCloud = false, bImage = false; - bPose = m_PoseReader.ReadNext(pPose, NULL); - if(pPose != NULL) - m_pLatestPose = pPose; + bPose = m_PoseReader.ReadNext(pPose, NULL); + if(pPose != NULL) + m_pLatestPose = pPose; - if(m_pLatestPose != NULL) - { - bCloud = m_CloudReader.ReadNext(m_pLatestCloud, &m_pLatestPose->header.stamp); - while(m_CloudReader.ReadNext(m_pLatestCloud, &m_pLatestPose->header.stamp)) - { - } + if(m_pLatestPose != NULL) + { + bCloud = m_CloudReader.ReadNext(m_pLatestCloud, &m_pLatestPose->header.stamp); + while(m_CloudReader.ReadNext(m_pLatestCloud, &m_pLatestPose->header.stamp)) + { + } - bImage = m_ImageReader.ReadNext(m_pLatestImage, &m_pLatestPose->header.stamp); - while(!m_ImageReader.ReadNext(m_pLatestImage, &m_pLatestPose->header.stamp)) - { + bImage = m_ImageReader.ReadNext(m_pLatestImage, &m_pLatestPose->header.stamp); + while(!m_ImageReader.ReadNext(m_pLatestImage, &m_pLatestPose->header.stamp)) + { - } - } + } + } - return bPose || bCloud || bImage; + return bPose || bCloud || bImage; } bool TestingUI::ReadPrevFrame() { - geometry_msgs::PoseStampedPtr pPose; + geometry_msgs::PoseStampedPtr pPose; - bool bPose = false, bCloud = false, bImage = false; + bool bPose = false, bCloud = false, bImage = false; - bPose = m_PoseReader.ReadPrev(pPose, NULL); - if(pPose != NULL) - m_pLatestPose = pPose; + bPose = m_PoseReader.ReadPrev(pPose, NULL); + if(pPose != NULL) + m_pLatestPose = pPose; - if(m_pLatestPose != NULL) - { - bCloud = m_CloudReader.ReadPrev(m_pLatestCloud, &m_pLatestPose->header.stamp); - bImage = m_ImageReader.ReadPrev(m_pLatestImage, &m_pLatestPose->header.stamp); - } + if(m_pLatestPose != NULL) + { + bCloud = m_CloudReader.ReadPrev(m_pLatestCloud, &m_pLatestPose->header.stamp); + bImage = m_ImageReader.ReadPrev(m_pLatestImage, &m_pLatestPose->header.stamp); + } - return bPose || bCloud || bImage; + return bPose || bCloud || bImage; } void TestingUI::InitNode(const BagReaderParams& params, const int& mode) { - m_BagParams = params; - switch(mode) - { - case 0: - m_TestMode = SIMULATION_MODE; - break; - case 1: - m_TestMode = ROSBAG_MODE; - break; - case 2: - m_TestMode = LIVE_MODE; - break; - default: - break; - } - - ros::NodeHandle nh; - if(m_TestMode == ROSBAG_MODE) - { - m_bBagOpen = OpenROSBag(); - - pub_Point_Raw = nh.advertise(m_BagParams.lidarTopic_pub, 10); - pub_Image_Raw = nh.advertise(m_BagParams.imageTopic_pub, 10); - pub_NDT_pose = nh.advertise(m_BagParams.poseTopic_pub, 10); - } - else if(m_TestMode == SIMULATION_MODE) - { - pub_SimuStepSignal = nh.advertise("simu_step_signal", 1); - pub_PredStepSignal = nh.advertise("pred_step_signal", 1); - pub_SimuGenSignal = nh.advertise("simu_generate_signal", 1); - } + m_BagParams = params; + switch(mode) + { + case 0: + m_TestMode = SIMULATION_MODE; + break; + case 1: + m_TestMode = ROSBAG_MODE; + break; + case 2: + m_TestMode = LIVE_MODE; + break; + default: + break; + } + + ros::NodeHandle nh; + if(m_TestMode == ROSBAG_MODE) + { + m_bBagOpen = OpenROSBag(); + + pub_Point_Raw = nh.advertise(m_BagParams.lidarTopic_pub, 10); + pub_Image_Raw = nh.advertise(m_BagParams.imageTopic_pub, 10); + pub_NDT_pose = nh.advertise(m_BagParams.poseTopic_pub, 10); + } + else if(m_TestMode == SIMULATION_MODE) + { + pub_SimuStepSignal = nh.advertise("simu_step_signal", 1); + pub_PredStepSignal = nh.advertise("pred_step_signal", 1); + pub_SimuGenSignal = nh.advertise("simu_generate_signal", 1); + } } void TestingUI::OnKeyboardPress(const int& sKey, const unsigned char& key) { - //std::cout << "key" << std::endl; - - if(m_TestMode == SIMULATION_MODE) - { - switch(key) - { - case 's': - { - m_bStepForward = true; - } - break; - case 'g': - { - m_bGenerateSignal = true; - } - break; - default: - break; - - } - } - else if(m_TestMode == ROSBAG_MODE) - { - switch(key) - { - case 32: - { - if(m_PlayMode == PLAY_PAUSE || m_PlayMode == PLAY_STEP_FORWARD || m_PlayMode == PLAY_STEP_BACKWARD) - m_PlayMode = PLAY_FORWARD; - else if(m_PlayMode == PLAY_FORWARD) - m_PlayMode = PLAY_PAUSE; - } - break; - default: - break; - } - - switch (sKey) - { - case 101: // Up - { - m_PlayMode = PLAY_STEP_FORWARD; - m_bStepDone = false; - } - break; - case 103: //Down - { - m_PlayMode = PLAY_STEP_BACKWARD; - m_bStepDone = false; - } - break; - case 102: //Right - { - } - break; - case 100: //Left - { - } - break; - default: - break; - } - } + //std::cout << "key" << std::endl; + + if(m_TestMode == SIMULATION_MODE) + { + switch(key) + { + case 's': + { + m_bStepForward = true; + } + break; + case 'g': + { + m_bGenerateSignal = true; + } + break; + default: + break; + + } + } + else if(m_TestMode == ROSBAG_MODE) + { + switch(key) + { + case 32: + { + if(m_PlayMode == PLAY_PAUSE || m_PlayMode == PLAY_STEP_FORWARD || m_PlayMode == PLAY_STEP_BACKWARD) + m_PlayMode = PLAY_FORWARD; + else if(m_PlayMode == PLAY_FORWARD) + m_PlayMode = PLAY_PAUSE; + } + break; + default: + break; + } + + switch (sKey) + { + case 101: // Up + { + m_PlayMode = PLAY_STEP_FORWARD; + m_bStepDone = false; + } + break; + case 103: //Down + { + m_PlayMode = PLAY_STEP_BACKWARD; + m_bStepDone = false; + } + break; + case 102: //Right + { + } + break; + case 100: //Left + { + } + break; + default: + break; + } + } } } /* namespace Graphics */ diff --git a/core_planning/op_utilities/nodes/op_data_logger/op_data_logger.cpp b/core_planning/op_utilities/nodes/op_data_logger/op_data_logger.cpp index 8a9cb2f8d12..1b15dc9a643 100644 --- a/core_planning/op_utilities/nodes/op_data_logger/op_data_logger.cpp +++ b/core_planning/op_utilities/nodes/op_data_logger/op_data_logger.cpp @@ -18,8 +18,8 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "op_data_logger"); - DataLoggerNS::OpenPlannerDataLogger logger; - logger.MainLoop(); - return 0; + ros::init(argc, argv, "op_data_logger"); + DataLoggerNS::OpenPlannerDataLogger logger; + logger.MainLoop(); + return 0; } diff --git a/core_planning/op_utilities/nodes/op_data_logger/op_data_logger_core.cpp b/core_planning/op_utilities/nodes/op_data_logger/op_data_logger_core.cpp index 75d3308aa9b..e4bf0baed58 100644 --- a/core_planning/op_utilities/nodes/op_data_logger/op_data_logger_core.cpp +++ b/core_planning/op_utilities/nodes/op_data_logger/op_data_logger_core.cpp @@ -26,350 +26,350 @@ namespace DataLoggerNS OpenPlannerDataLogger::OpenPlannerDataLogger() { - bMap = false; - m_iSimuCarsNumber = 5; + bMap = false; + m_iSimuCarsNumber = 5; - std::string first_str, second_str; - ros::NodeHandle _nh("~"); + std::string first_str, second_str; + ros::NodeHandle _nh("~"); - int iSource = 0; - _nh.getParam("mapSource" , iSource); - if(iSource == 0) - m_MapType = PlannerHNS::MAP_FOLDER; - else if(iSource == 1) - m_MapType = PlannerHNS::MAP_KML_FILE; + int iSource = 0; + _nh.getParam("mapSource" , iSource); + if(iSource == 0) + m_MapType = PlannerHNS::MAP_FOLDER; + else if(iSource == 1) + m_MapType = PlannerHNS::MAP_KML_FILE; - _nh.getParam("mapFileName" , m_MapPath); + _nh.getParam("mapFileName" , m_MapPath); - UtilityHNS::UtilityH::GetTickCount(m_Timer); + UtilityHNS::UtilityH::GetTickCount(m_Timer); - //Subscription for the Ego vehicle ! - sub_predicted_objects = nh.subscribe("/predicted_objects", 1, &OpenPlannerDataLogger::callbackGetPredictedObjects, this); + //Subscription for the Ego vehicle ! + sub_predicted_objects = nh.subscribe("/predicted_objects", 1, &OpenPlannerDataLogger::callbackGetPredictedObjects, this); - sub_behavior_state = nh.subscribe("/current_behavior", 10, &OpenPlannerDataLogger::callbackGetBehaviorState, this); + sub_behavior_state = nh.subscribe("/current_behavior", 10, &OpenPlannerDataLogger::callbackGetBehaviorState, this); - //Subscriptions for the simulated cars - VehicleDataContainer vc; - vc.id = 0; - m_SimulatedVehicle.push_back(vc); - for(int i=1; i <= m_iSimuCarsNumber; i++) - { - std::ostringstream str_path_beh, str_pose; - str_path_beh << "simu_car_path_beh_" << i; + //Subscriptions for the simulated cars + VehicleDataContainer vc; + vc.id = 0; + m_SimulatedVehicle.push_back(vc); + for(int i=1; i <= m_iSimuCarsNumber; i++) + { + std::ostringstream str_path_beh, str_pose; + str_path_beh << "simu_car_path_beh_" << i; - ros::Subscriber _sub_path_beh; - _sub_path_beh = nh.subscribe(str_path_beh.str(), 1, &OpenPlannerDataLogger::callbackGetSimuCarsPathAndState, this); + ros::Subscriber _sub_path_beh; + _sub_path_beh = nh.subscribe(str_path_beh.str(), 1, &OpenPlannerDataLogger::callbackGetSimuCarsPathAndState, this); - sub_simu_paths.push_back(_sub_path_beh); + sub_simu_paths.push_back(_sub_path_beh); - str_pose << "sim_box_pose_" << i; - ros::Subscriber _sub; - _sub = nh.subscribe(str_pose.str(), 1, &OpenPlannerDataLogger::callbackGetSimuPose, this); - sub_objs.push_back(_sub); + str_pose << "sim_box_pose_" << i; + ros::Subscriber _sub; + _sub = nh.subscribe(str_pose.str(), 1, &OpenPlannerDataLogger::callbackGetSimuPose, this); + sub_objs.push_back(_sub); - vc.id = i; - m_SimulatedVehicle.push_back(vc); - m_LogData.push_back(std::vector()); - } + vc.id = i; + m_SimulatedVehicle.push_back(vc); + m_LogData.push_back(std::vector()); + } - std::cout << "OpenPlannerDataLogger initialized successfully " << std::endl; + std::cout << "OpenPlannerDataLogger initialized successfully " << std::endl; } OpenPlannerDataLogger::~OpenPlannerDataLogger() { - for(int i=0; i < m_iSimuCarsNumber; i++) - { - ostringstream car_name; - car_name << "sim_car_no_" << i+1; - car_name << "_"; - UtilityHNS::DataRW::WriteLogData(UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::PredictionFolderName, - car_name.str(), - "time_diff,distance_diff, heading_diff, velocity_diff, rms, state_diff," , m_LogData.at(i)); - } + for(int i=0; i < m_iSimuCarsNumber; i++) + { + ostringstream car_name; + car_name << "sim_car_no_" << i+1; + car_name << "_"; + UtilityHNS::DataRW::WriteLogData(UtilityHNS::UtilityH::GetHomeDirectory()+UtilityHNS::DataRW::LoggingMainfolderName+UtilityHNS::DataRW::PredictionFolderName, + car_name.str(), + "time_diff,distance_diff, heading_diff, velocity_diff, rms, state_diff," , m_LogData.at(i)); + } } void OpenPlannerDataLogger::callbackGetSimuPose(const geometry_msgs::PoseArray& msg) { - for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) - { - if(msg.poses.size() > 3 ) - { - if(m_SimulatedVehicle.at(i).id == msg.poses.at(0).position.x) - { - //std::cout << "Receive SimuPOse Data ... " << msg.poses.at(0).position.x << ", " << msg.header.stamp << std::endl; - - m_SimulatedVehicle.at(i).pose.v = msg.poses.at(0).position.y; - m_SimulatedVehicle.at(i).pose.pos.x = msg.poses.at(1).position.x; - m_SimulatedVehicle.at(i).pose.pos.y = msg.poses.at(1).position.y; - m_SimulatedVehicle.at(i).pose.pos.z = msg.poses.at(1).position.z; - m_SimulatedVehicle.at(i).pose.pos.a = tf::getYaw(msg.poses.at(1).orientation); - - if(msg.poses.at(3).orientation.w == 0) - m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_LEFT; - else if(msg.poses.at(3).orientation.w == 1) - m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_RIGHT; - else if(msg.poses.at(3).orientation.w == 2) - m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_BOTH; - else if(msg.poses.at(3).orientation.w == 3) - m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_NONE; - - m_SimulatedVehicle.at(i).pose_time = msg.header.stamp; - - break; - } - } - } + for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) + { + if(msg.poses.size() > 3 ) + { + if(m_SimulatedVehicle.at(i).id == msg.poses.at(0).position.x) + { + //std::cout << "Receive SimuPOse Data ... " << msg.poses.at(0).position.x << ", " << msg.header.stamp << std::endl; + + m_SimulatedVehicle.at(i).pose.v = msg.poses.at(0).position.y; + m_SimulatedVehicle.at(i).pose.pos.x = msg.poses.at(1).position.x; + m_SimulatedVehicle.at(i).pose.pos.y = msg.poses.at(1).position.y; + m_SimulatedVehicle.at(i).pose.pos.z = msg.poses.at(1).position.z; + m_SimulatedVehicle.at(i).pose.pos.a = tf::getYaw(msg.poses.at(1).orientation); + + if(msg.poses.at(3).orientation.w == 0) + m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_LEFT; + else if(msg.poses.at(3).orientation.w == 1) + m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_RIGHT; + else if(msg.poses.at(3).orientation.w == 2) + m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_BOTH; + else if(msg.poses.at(3).orientation.w == 3) + m_SimulatedVehicle.at(i).beh.indicator = PlannerHNS::INDICATOR_NONE; + + m_SimulatedVehicle.at(i).pose_time = msg.header.stamp; + + break; + } + } + } } void OpenPlannerDataLogger::callbackGetSimuCarsPathAndState(const autoware_msgs::LaneConstPtr& msg ) { - //std::cout << "Receive Lane Data ... " << std::endl; - - for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) - { - if(m_SimulatedVehicle.at(i).id == msg->lane_id) - { - m_SimulatedVehicle.at(i).path.clear(); - PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(*msg, m_SimulatedVehicle.at(i).path); - m_SimulatedVehicle.at(i).beh.state = GetStateFromNumber(msg->lane_index); - m_SimulatedVehicle.at(i).path_time = msg->header.stamp; - break; - } - } + //std::cout << "Receive Lane Data ... " << std::endl; + + for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) + { + if(m_SimulatedVehicle.at(i).id == msg->lane_id) + { + m_SimulatedVehicle.at(i).path.clear(); + PlannerHNS::ROSHelpers::ConvertFromAutowareLaneToLocalLane(*msg, m_SimulatedVehicle.at(i).path); + m_SimulatedVehicle.at(i).beh.state = GetStateFromNumber(msg->lane_index); + m_SimulatedVehicle.at(i).path_time = msg->header.stamp; + break; + } + } } //Functions related to Ego Vehicle Data void OpenPlannerDataLogger::callbackGetPredictedObjects(const autoware_msgs::DetectedObjectArrayConstPtr& msg) { - m_PredictedObjects.clear(); - PlannerHNS::DetectedObject obj; - - //std::cout << "Receive Prediction Data From Ego Vehicle... " << msg->header.stamp << std::endl; - m_pred_time = msg->header.stamp; - - for(unsigned int i = 0 ; i objects.size(); i++) - { - if(msg->objects.at(i).id > 0) - { - PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); - - - obj.behavior_state = GetBehStateFromNumber(msg->objects.at(i).behavior_state); - int i_best_trajectory = -1; - double max_cost = 0; - for(unsigned int k=0; k < obj.predTrajectories.size(); k++) - { - if(obj.predTrajectories.at(k).size() > 0) - { - //std::cout << "Fins Max Traj Cost .............. " << obj.predTrajectories.at(k).at(0).collisionCost << std::endl; - - if(obj.predTrajectories.at(k).at(0).collisionCost == 1) - { - - max_cost = obj.predTrajectories.at(k).at(0).collisionCost; - i_best_trajectory = k; - } - } - } - - if(i_best_trajectory >= 0 && i_best_trajectory < obj.predTrajectories.size()) - { - std::vector pred_traj = obj.predTrajectories.at(i_best_trajectory); - obj.predTrajectories.clear(); - obj.predTrajectories.push_back(pred_traj); - } - else - obj.predTrajectories.clear(); - - m_PredictedObjects.push_back(obj); - } - } + m_PredictedObjects.clear(); + PlannerHNS::DetectedObject obj; + + //std::cout << "Receive Prediction Data From Ego Vehicle... " << msg->header.stamp << std::endl; + m_pred_time = msg->header.stamp; + + for(unsigned int i = 0 ; i objects.size(); i++) + { + if(msg->objects.at(i).id > 0) + { + PlannerHNS::ROSHelpers::ConvertFromAutowareDetectedObjectToOpenPlannerDetectedObject(msg->objects.at(i), obj); + + + obj.behavior_state = GetBehStateFromNumber(msg->objects.at(i).behavior_state); + int i_best_trajectory = -1; + double max_cost = 0; + for(unsigned int k=0; k < obj.predTrajectories.size(); k++) + { + if(obj.predTrajectories.at(k).size() > 0) + { + //std::cout << "Fins Max Traj Cost .............. " << obj.predTrajectories.at(k).at(0).collisionCost << std::endl; + + if(obj.predTrajectories.at(k).at(0).collisionCost == 1) + { + + max_cost = obj.predTrajectories.at(k).at(0).collisionCost; + i_best_trajectory = k; + } + } + } + + if(i_best_trajectory >= 0 && i_best_trajectory < obj.predTrajectories.size()) + { + std::vector pred_traj = obj.predTrajectories.at(i_best_trajectory); + obj.predTrajectories.clear(); + obj.predTrajectories.push_back(pred_traj); + } + else + obj.predTrajectories.clear(); + + m_PredictedObjects.push_back(obj); + } + } } void OpenPlannerDataLogger::callbackGetBehaviorState(const geometry_msgs::TwistStampedConstPtr& msg ) { - m_CurrentBehavior = ConvertBehaviorStateFromAutowareToPlannerH(msg); -// std::cout << "Receive Behavior Data From Ego Vehicle... " << msg->header.stamp << std::endl; + m_CurrentBehavior = ConvertBehaviorStateFromAutowareToPlannerH(msg); +// std::cout << "Receive Behavior Data From Ego Vehicle... " << msg->header.stamp << std::endl; } PlannerHNS::BehaviorState OpenPlannerDataLogger::ConvertBehaviorStateFromAutowareToPlannerH(const geometry_msgs::TwistStampedConstPtr& msg) { - PlannerHNS::BehaviorState behavior; - behavior.followDistance = msg->twist.linear.x; - behavior.stopDistance = msg->twist.linear.y; - behavior.followVelocity = msg->twist.angular.x; - behavior.maxVelocity = msg->twist.angular.y; + PlannerHNS::BehaviorState behavior; + behavior.followDistance = msg->twist.linear.x; + behavior.stopDistance = msg->twist.linear.y; + behavior.followVelocity = msg->twist.angular.x; + behavior.maxVelocity = msg->twist.angular.y; - if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT) - behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT; - else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT) - behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT; - else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH) - behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH; - else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE) - behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE; + if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT) + behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_LEFT; + else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT) + behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_RIGHT; + else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH) + behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_BOTH; + else if(msg->twist.linear.z == PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE) + behavior.indicator = PlannerHNS::LIGHT_INDICATOR::INDICATOR_NONE; - behavior.state = GetStateFromNumber(msg->twist.angular.z); + behavior.state = GetStateFromNumber(msg->twist.angular.z); - return behavior; + return behavior; } PlannerHNS::STATE_TYPE OpenPlannerDataLogger::GetStateFromNumber(const int& iBehState) { - PlannerHNS::STATE_TYPE _state; - if(iBehState == PlannerHNS::INITIAL_STATE) - _state = PlannerHNS::INITIAL_STATE; - else if(iBehState == PlannerHNS::WAITING_STATE) - _state = PlannerHNS::WAITING_STATE; - else if(iBehState == PlannerHNS::FORWARD_STATE) - _state = PlannerHNS::FORWARD_STATE; - else if(iBehState == PlannerHNS::STOPPING_STATE) - _state = PlannerHNS::STOPPING_STATE; - else if(iBehState == PlannerHNS::EMERGENCY_STATE) - _state = PlannerHNS::EMERGENCY_STATE; - else if(iBehState == PlannerHNS::TRAFFIC_LIGHT_STOP_STATE) - _state = PlannerHNS::TRAFFIC_LIGHT_STOP_STATE; - else if(iBehState == PlannerHNS::STOP_SIGN_STOP_STATE) - _state = PlannerHNS::STOP_SIGN_STOP_STATE; - else if(iBehState == PlannerHNS::STOP_SIGN_WAIT_STATE) - _state = PlannerHNS::STOP_SIGN_WAIT_STATE; - else if(iBehState == PlannerHNS::FOLLOW_STATE) - _state = PlannerHNS::FOLLOW_STATE; - else if(iBehState == PlannerHNS::LANE_CHANGE_STATE) - _state = PlannerHNS::LANE_CHANGE_STATE; - else if(iBehState == PlannerHNS::OBSTACLE_AVOIDANCE_STATE) - _state = PlannerHNS::OBSTACLE_AVOIDANCE_STATE; - else if(iBehState == PlannerHNS::FINISH_STATE) - _state = PlannerHNS::FINISH_STATE; - - return _state; + PlannerHNS::STATE_TYPE _state; + if(iBehState == PlannerHNS::INITIAL_STATE) + _state = PlannerHNS::INITIAL_STATE; + else if(iBehState == PlannerHNS::WAITING_STATE) + _state = PlannerHNS::WAITING_STATE; + else if(iBehState == PlannerHNS::FORWARD_STATE) + _state = PlannerHNS::FORWARD_STATE; + else if(iBehState == PlannerHNS::STOPPING_STATE) + _state = PlannerHNS::STOPPING_STATE; + else if(iBehState == PlannerHNS::EMERGENCY_STATE) + _state = PlannerHNS::EMERGENCY_STATE; + else if(iBehState == PlannerHNS::TRAFFIC_LIGHT_STOP_STATE) + _state = PlannerHNS::TRAFFIC_LIGHT_STOP_STATE; + else if(iBehState == PlannerHNS::STOP_SIGN_STOP_STATE) + _state = PlannerHNS::STOP_SIGN_STOP_STATE; + else if(iBehState == PlannerHNS::STOP_SIGN_WAIT_STATE) + _state = PlannerHNS::STOP_SIGN_WAIT_STATE; + else if(iBehState == PlannerHNS::FOLLOW_STATE) + _state = PlannerHNS::FOLLOW_STATE; + else if(iBehState == PlannerHNS::LANE_CHANGE_STATE) + _state = PlannerHNS::LANE_CHANGE_STATE; + else if(iBehState == PlannerHNS::OBSTACLE_AVOIDANCE_STATE) + _state = PlannerHNS::OBSTACLE_AVOIDANCE_STATE; + else if(iBehState == PlannerHNS::FINISH_STATE) + _state = PlannerHNS::FINISH_STATE; + + return _state; } PlannerHNS::BEH_STATE_TYPE OpenPlannerDataLogger::GetBehStateFromNumber(const int& iBehState) { - if(iBehState == 0) - return PlannerHNS::BEH_FORWARD_STATE; - else if(iBehState == 1) - return PlannerHNS::BEH_STOPPING_STATE; - else if(iBehState == 2) - return PlannerHNS::BEH_BRANCH_LEFT_STATE; - else if(iBehState == 3) - return PlannerHNS::BEH_BRANCH_RIGHT_STATE; - else if(iBehState == 4) - return PlannerHNS::BEH_YIELDING_STATE; - else if(iBehState == 5) - return PlannerHNS::BEH_ACCELERATING_STATE; - else if(iBehState == 6) - return PlannerHNS::BEH_SLOWDOWN_STATE; - else - return PlannerHNS::BEH_FORWARD_STATE; + if(iBehState == 0) + return PlannerHNS::BEH_FORWARD_STATE; + else if(iBehState == 1) + return PlannerHNS::BEH_STOPPING_STATE; + else if(iBehState == 2) + return PlannerHNS::BEH_BRANCH_LEFT_STATE; + else if(iBehState == 3) + return PlannerHNS::BEH_BRANCH_RIGHT_STATE; + else if(iBehState == 4) + return PlannerHNS::BEH_YIELDING_STATE; + else if(iBehState == 5) + return PlannerHNS::BEH_ACCELERATING_STATE; + else if(iBehState == 6) + return PlannerHNS::BEH_SLOWDOWN_STATE; + else + return PlannerHNS::BEH_FORWARD_STATE; } void OpenPlannerDataLogger::CompareAndLog(VehicleDataContainer& ground_truth, PlannerHNS::DetectedObject& predicted) { - //difference between actual and prediction - //time diff - //distance , orientation, velocity diff - //RMS diff (make both same density first) , -1 if no prediction - //behavior state matching (1 if match , zero if not) + //difference between actual and prediction + //time diff + //distance , orientation, velocity diff + //RMS diff (make both same density first) , -1 if no prediction + //behavior state matching (1 if match , zero if not) - double t_diff = fabs(ground_truth.path_time.toSec() - m_pred_time.toSec()); - double d_diff = hypot(ground_truth.pose.pos.y - predicted.center.pos.y, ground_truth.pose.pos.x - predicted.center.pos.x); - double o_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(ground_truth.pose.pos.a, predicted.center.pos.a); - double v_diff = fabs(ground_truth.pose.v - predicted.center.v); - double rms = -1; - int beh_state_diff = -1; + double t_diff = fabs(ground_truth.path_time.toSec() - m_pred_time.toSec()); + double d_diff = hypot(ground_truth.pose.pos.y - predicted.center.pos.y, ground_truth.pose.pos.x - predicted.center.pos.x); + double o_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(ground_truth.pose.pos.a, predicted.center.pos.a); + double v_diff = fabs(ground_truth.pose.v - predicted.center.v); + double rms = -1; + int beh_state_diff = -1; - if(predicted.predTrajectories.size() > 0) - { - rms = CalculateRMS(ground_truth.path, predicted.predTrajectories.at(0)); - } + if(predicted.predTrajectories.size() > 0) + { + rms = CalculateRMS(ground_truth.path, predicted.predTrajectories.at(0)); + } - if(ground_truth.beh.state == predicted.behavior_state) - beh_state_diff = 1; - else - beh_state_diff = 0; + if(ground_truth.beh.state == predicted.behavior_state) + beh_state_diff = 1; + else + beh_state_diff = 0; - beh_state_diff = predicted.behavior_state; + beh_state_diff = predicted.behavior_state; - std::ostringstream dataLine; - dataLine << t_diff << "," << d_diff << "," << o_diff << "," << v_diff << "," << rms << "," << beh_state_diff << ","; - m_LogData.at(ground_truth.id -1).push_back(dataLine.str()); + std::ostringstream dataLine; + dataLine << t_diff << "," << d_diff << "," << o_diff << "," << v_diff << "," << rms << "," << beh_state_diff << ","; + m_LogData.at(ground_truth.id -1).push_back(dataLine.str()); - //std::cout << "Predicted Behavior: " << predicted.behavior_state << std::endl; + //std::cout << "Predicted Behavior: " << predicted.behavior_state << std::endl; } double OpenPlannerDataLogger::CalculateRMS(std::vector& path1, std::vector& path2) { - if(path1.size() == 0 || path2.size() == 0) return -1; + if(path1.size() == 0 || path2.size() == 0) return -1; - //PlannerHNS::PlanningHelpers::FixPathDensity(path1, 0.1); - //PlannerHNS::PlanningHelpers::FixPathDensity(path2, 0.1); + //PlannerHNS::PlanningHelpers::FixPathDensity(path1, 0.1); + //PlannerHNS::PlanningHelpers::FixPathDensity(path2, 0.1); - int min_size = path1.size(); - if(path2.size() < min_size) - min_size = path2.size(); + int min_size = path1.size(); + if(path2.size() < min_size) + min_size = path2.size(); - double rms_sum = 0; - PlannerHNS::RelativeInfo info; - for(unsigned int i=0; i < min_size - 1 ; i++) - { - PlannerHNS::PlanningHelpers::GetRelativeInfo(path1, path2.at(i), info); - rms_sum += fabs(info.perp_distance); - //rms_sum += hypot(path1.at(i).pos.y - path2.at(i).pos.y, path1.at(i).pos.x - path2.at(i).pos.x); - } + double rms_sum = 0; + PlannerHNS::RelativeInfo info; + for(unsigned int i=0; i < min_size - 1 ; i++) + { + PlannerHNS::PlanningHelpers::GetRelativeInfo(path1, path2.at(i), info); + rms_sum += fabs(info.perp_distance); + //rms_sum += hypot(path1.at(i).pos.y - path2.at(i).pos.y, path1.at(i).pos.x - path2.at(i).pos.x); + } - return rms_sum / (double)min_size; + return rms_sum / (double)min_size; } void OpenPlannerDataLogger::MainLoop() { - ros::Rate loop_rate(50); - - while (ros::ok()) - { - ros::spinOnce(); - - if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); - } - else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) - { - bMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); - } - - ros::Time t; - - for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) - { - if(m_SimulatedVehicle.at(i).pose_time != t && m_SimulatedVehicle.at(i).path_time != t) - { - for(unsigned int j = 0; j < m_PredictedObjects.size(); j++) - { - //std::cout << "CarID: " << m_SimulatedVehicle.at(i).id << ", PredCarID: " << m_PredictedObjects.at(j).id << std::endl; - if(m_SimulatedVehicle.at(i).id == m_PredictedObjects.at(j).id) - { - CompareAndLog(m_SimulatedVehicle.at(i), m_PredictedObjects.at(j)); - } - } - - //std::cout << "CarID: " << m_SimulatedVehicle.at(i).id << ", PoseTime: " << m_SimulatedVehicle.at(i).pose_time.toSec() << ", PredTime: " << m_pred_time.toSec() << std::endl; - //std::cout << std::endl; - } - } - - loop_rate.sleep(); - } + ros::Rate loop_rate(50); + + while (ros::ok()) + { + ros::spinOnce(); + + if(m_MapType == PlannerHNS::MAP_KML_FILE && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::LoadKML(m_MapPath, m_Map); + } + else if (m_MapType == PlannerHNS::MAP_FOLDER && !bMap) + { + bMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_MapPath, m_Map, true); + } + + ros::Time t; + + for(unsigned int i=0; i < m_SimulatedVehicle.size(); i++) + { + if(m_SimulatedVehicle.at(i).pose_time != t && m_SimulatedVehicle.at(i).path_time != t) + { + for(unsigned int j = 0; j < m_PredictedObjects.size(); j++) + { + //std::cout << "CarID: " << m_SimulatedVehicle.at(i).id << ", PredCarID: " << m_PredictedObjects.at(j).id << std::endl; + if(m_SimulatedVehicle.at(i).id == m_PredictedObjects.at(j).id) + { + CompareAndLog(m_SimulatedVehicle.at(i), m_PredictedObjects.at(j)); + } + } + + //std::cout << "CarID: " << m_SimulatedVehicle.at(i).id << ", PoseTime: " << m_SimulatedVehicle.at(i).pose_time.toSec() << ", PredTime: " << m_pred_time.toSec() << std::endl; + //std::cout << std::endl; + } + } + + loop_rate.sleep(); + } } } diff --git a/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf.cpp b/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf.cpp index 547d265cb8a..8fe3f6c257e 100644 --- a/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf.cpp +++ b/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf.cpp @@ -20,8 +20,8 @@ int main(int argc, char **argv) { - ros::init(argc, argv, "op_pose2tf"); - PoseTFNS::PoseToTF tf_publisher; - tf_publisher.MainLoop(); - return 0; + ros::init(argc, argv, "op_pose2tf"); + PoseTFNS::PoseToTF tf_publisher; + tf_publisher.MainLoop(); + return 0; } diff --git a/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf_core.cpp b/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf_core.cpp index 42db22d17ce..c3db7995d87 100644 --- a/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf_core.cpp +++ b/core_planning/op_utilities/nodes/op_pose2tf/op_pose2tf_core.cpp @@ -24,15 +24,15 @@ namespace PoseTFNS PoseToTF::PoseToTF() { - ros::NodeHandle _nh("~"); + ros::NodeHandle _nh("~"); - std::string pose_topic_name; - _nh.getParam("pose_topic" , pose_topic_name); + std::string pose_topic_name; + _nh.getParam("pose_topic" , pose_topic_name); - sub_ndt_pose = nh.subscribe(pose_topic_name, 10, &PoseToTF::callbackGetPose, this); - pub_reset_time = nh.advertise("/reset_time", 1); + sub_ndt_pose = nh.subscribe(pose_topic_name, 10, &PoseToTF::callbackGetPose, this); + pub_reset_time = nh.advertise("/reset_time", 1); - std::cout << "PoseToTF initialized successfully " << std::endl; + std::cout << "PoseToTF initialized successfully " << std::endl; } PoseToTF::~PoseToTF() @@ -41,31 +41,31 @@ PoseToTF::~PoseToTF() void PoseToTF::callbackGetPose(const geometry_msgs::PoseStampedConstPtr &msg) { - tf::Quaternion bt_q; - tf::quaternionMsgToTF(msg->pose.orientation, bt_q); + tf::Quaternion bt_q; + tf::quaternionMsgToTF(msg->pose.orientation, bt_q); - static tf::TransformBroadcaster map_base_link_broadcaster; - geometry_msgs::TransformStamped base_link_trans; - base_link_trans.header.stamp = ros::Time::now(); - base_link_trans.header.frame_id = "/map"; - base_link_trans.child_frame_id = "/base_link"; - base_link_trans.transform.translation.x = msg->pose.position.x; - base_link_trans.transform.translation.y = msg->pose.position.y; - base_link_trans.transform.translation.z = msg->pose.position.z; - base_link_trans.transform.rotation = msg->pose.orientation; + static tf::TransformBroadcaster map_base_link_broadcaster; + geometry_msgs::TransformStamped base_link_trans; + base_link_trans.header.stamp = ros::Time::now(); + base_link_trans.header.frame_id = "/map"; + base_link_trans.child_frame_id = "/base_link"; + base_link_trans.transform.translation.x = msg->pose.position.x; + base_link_trans.transform.translation.y = msg->pose.position.y; + base_link_trans.transform.translation.z = msg->pose.position.z; + base_link_trans.transform.rotation = msg->pose.orientation; - // send the transform - map_base_link_broadcaster.sendTransform(base_link_trans); + // send the transform + map_base_link_broadcaster.sendTransform(base_link_trans); - //std::cout << "Publish TF !! " << std::endl; + //std::cout << "Publish TF !! " << std::endl; } void PoseToTF::MainLoop() { - std_msgs::Empty msg; - pub_reset_time.publish(msg); - ros::spin(); + std_msgs::Empty msg; + pub_reset_time.publish(msg); + ros::spin(); } } diff --git a/core_planning/op_utilities/package.xml b/core_planning/op_utilities/package.xml index b66de00f5b2..7539db0b799 100644 --- a/core_planning/op_utilities/package.xml +++ b/core_planning/op_utilities/package.xml @@ -17,6 +17,7 @@ op_ros_helpers op_utility pcl_conversions + rosbag roscpp vector_map_msgs diff --git a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit.h b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit.h index 039ff56cad1..14805da0153 100644 --- a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit.h +++ b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit.h @@ -35,8 +35,8 @@ namespace waypoint_follower class PurePursuit { public: - PurePursuit(); - ~PurePursuit(); + PurePursuit() = default; + ~PurePursuit() = default; // for setting data void setLookaheadDistance(const double& ld) @@ -105,23 +105,22 @@ class PurePursuit private: // constant - const double RADIUS_MAX_; - const double KAPPA_MIN_; + static constexpr double RADIUS_MAX_ = 9e10; + static constexpr double KAPPA_MIN_ = 1.0 / 9e10; // variables - bool is_linear_interpolation_; - int next_waypoint_number_; - geometry_msgs::Point next_target_position_; - double lookahead_distance_; - double minimum_lookahead_distance_; - geometry_msgs::Pose current_pose_; - double current_linear_velocity_; - std::vector current_waypoints_; + bool is_linear_interpolation_{ false }; + int next_waypoint_number_{ -1 }; + double lookahead_distance_{ 0.0 }; + double minimum_lookahead_distance_{ 6.0 }; + double current_linear_velocity_{ 0.0 }; + geometry_msgs::Pose current_pose_{}; + geometry_msgs::Point next_target_position_{}; + std::vector current_waypoints_{}; // functions - double calcCurvature(geometry_msgs::Point target) const; - bool interpolateNextTarget( - int next_waypoint, geometry_msgs::Point* next_target) const; + double calcCurvature(const geometry_msgs::Point& target) const; + bool interpolateNextTarget(int next_waypoint, geometry_msgs::Point* next_target) const; }; } // namespace waypoint_follower diff --git a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_core.h b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_core.h index 666ba49c01d..2e4caa32fef 100644 --- a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_core.h +++ b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_core.h @@ -28,13 +28,14 @@ #include #include #include +#include #include #include -#include - +// C++ includes #include #include +#include namespace waypoint_follower { @@ -42,7 +43,6 @@ enum class Mode : int32_t { waypoint, dialog, - unknown = -1, }; @@ -56,7 +56,7 @@ class PurePursuitNode { public: PurePursuitNode(); - ~PurePursuitNode(); + ~PurePursuitNode() = default; void run(); friend class PurePursuitNodeTestSuite; @@ -72,20 +72,19 @@ class PurePursuitNode PurePursuit pp_; // publisher - ros::Publisher pub1_, pub2_, - pub11_, pub12_, pub13_, pub14_, pub15_, pub16_, pub17_, pub18_; + ros::Publisher pub1_, pub2_, pub11_, pub12_, pub13_, pub14_, pub15_, pub16_, pub17_, pub18_; // subscriber ros::Subscriber sub1_, sub2_, sub3_; - // constant - const int LOOP_RATE_; // processing frequency - const int DEFAULT_VELOCITY_SOURCE_ = 0; + // control loop update rate + double update_rate_; + +const int DEFAULT_VELOCITY_SOURCE_ = 0; const double DEFAULT_CONST_VELOCITY_ = 5.0; // variables - bool is_linear_interpolation_, publishes_for_steering_robot_, - add_virtual_end_waypoints_; + bool is_linear_interpolation_, add_virtual_end_waypoints_; bool is_waypoint_set_, is_pose_set_, is_velocity_set_; double current_linear_velocity_, command_linear_velocity_; double wheel_base_; @@ -97,27 +96,25 @@ class PurePursuitNode double lookahead_distance_ratio_; // the next waypoint must be outside of this threshold. double minimum_lookahead_distance_; + std::string output_interface_; // callbacks void callbackFromCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackFromCurrentVelocity( - const geometry_msgs::TwistStampedConstPtr& msg); + void callbackFromCurrentVelocity(const geometry_msgs::TwistStampedConstPtr& msg); void callbackFromWayPoints(const autoware_msgs::LaneConstPtr& msg); // initializer void initForROS(); // functions - void publishTwistStamped( - const bool& can_get_curvature, const double& kappa) const; - void publishControlCommandStamped( - const bool& can_get_curvature, const double& kappa) const; - void publishDeviationCurrentPosition( - const geometry_msgs::Point& point, - const std::vector& waypoints) const; - void connectVirtualLastWaypoints( - autoware_msgs::Lane* expand_lane, LaneDirection direction); - // debug + void publishControlCommands(const bool& can_get_curvature, const double& kappa) const; + void publishTwistStamped(const bool& can_get_curvature, const double& kappa) const; + void publishCtrlCmdStamped(const bool& can_get_curvature, const double& kappa) const; + void publishDeviationCurrentPosition(const geometry_msgs::Point& point, + const std::vector& waypoints) const; + void connectVirtualLastWaypoints(autoware_msgs::Lane* expand_lane, LaneDirection direction); + +// debug geometry_msgs::Point getPoseOfNextWaypoint() const; void calculateNextWaypoint(); @@ -128,8 +125,7 @@ class PurePursuitNode double computeAngularGravity(double velocity, double kappa) const; }; -double convertCurvatureToSteeringAngle( - const double& wheel_base, const double& kappa); +double convertCurvatureToSteeringAngle(const double& wheel_base, const double& kappa); inline double kmph2mps(double velocity_kmph) { diff --git a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_viz.h b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_viz.h index 5051d99aa42..c72d3a61eae 100644 --- a/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_viz.h +++ b/core_planning/pure_pursuit/include/pure_pursuit/pure_pursuit_viz.h @@ -38,22 +38,18 @@ namespace waypoint_follower visualization_msgs::Marker displayNextWaypoint(geometry_msgs::Point position); // display the next target by markers. visualization_msgs::Marker displayNextTarget(geometry_msgs::Point target); -visualization_msgs::Marker displayExpandWaypoints( - const std::vector& waypoints, int size); +visualization_msgs::Marker displayExpandWaypoints(const std::vector& waypoints, int size); -double calcRadius( - geometry_msgs::Point target, geometry_msgs::Pose current_pose); +double calcRadius(geometry_msgs::Point target, geometry_msgs::Pose current_pose); // generate the locus of pure pursuit -std::vector generateTrajectoryCircle( - geometry_msgs::Point target, geometry_msgs::Pose current_pose); +std::vector generateTrajectoryCircle(geometry_msgs::Point target, + geometry_msgs::Pose current_pose); // display the locus of pure pursuit by markers. -visualization_msgs::Marker displayTrajectoryCircle( - std::vector traj_circle_array); +visualization_msgs::Marker displayTrajectoryCircle(std::vector traj_circle_array); // display the search radius by markers. -visualization_msgs::Marker displaySearchRadius( - geometry_msgs::Point current_pose, double search_radius); +visualization_msgs::Marker displaySearchRadius(geometry_msgs::Point current_pose, double search_radius); } // namespace waypoint_follower #endif // PURE_PURSUIT_PURE_PURSUIT_VIZ_H diff --git a/core_planning/pure_pursuit/src/pure_pursuit.cpp b/core_planning/pure_pursuit/src/pure_pursuit.cpp index 8898d293be8..dda5b3c8832 100644 --- a/core_planning/pure_pursuit/src/pure_pursuit.cpp +++ b/core_planning/pure_pursuit/src/pure_pursuit.cpp @@ -15,187 +15,107 @@ */ #include +#include +#include namespace waypoint_follower { -// Constructor -PurePursuit::PurePursuit() - : RADIUS_MAX_(9e10) - , KAPPA_MIN_(1 / RADIUS_MAX_) - , is_linear_interpolation_(false) - , next_waypoint_number_(-1) - , lookahead_distance_(0) - , minimum_lookahead_distance_(6) - , current_linear_velocity_(0) -{ -} - -// Destructor -PurePursuit::~PurePursuit() -{ -} - -double PurePursuit::calcCurvature(geometry_msgs::Point target) const +// Simple estimation of curvature given two points. +// 1. Convert the target point from map frame into the current pose frame, +// so it has a local coorinates of (pt.x, pt.y, pt.z). +// 2. If we think it is a cirle with a curvature kappa passing the two points, +// kappa = 2 * pt.y / (pt.x * pt.x + pt.y * pt.y). For detailed derivation, please +// refer to "Integrated Mobile Robot Control" by Omead Amidi +// (CMU-RI-TR-90-17, Equation 3.10 on Page 21) +double PurePursuit::calcCurvature(const geometry_msgs::Point& target) const { double kappa; - double denominator = pow(getPlaneDistance(target, current_pose_.position), 2); - double numerator = 2 * calcRelativeCoordinate(target, current_pose_).y; + const geometry_msgs::Point pt = calcRelativeCoordinate(target, current_pose_); + const double denominator = pt.x * pt.x + pt.y * pt.y; + const double numerator = 2.0 * pt.y; - if (denominator != 0) + if (denominator != 0.0) { kappa = numerator / denominator; } else { - if (numerator > 0) - { - kappa = KAPPA_MIN_; - } - else - { - kappa = -KAPPA_MIN_; - } + kappa = numerator > 0.0 ? KAPPA_MIN_ : -KAPPA_MIN_; } - ROS_INFO("kappa : %lf", kappa); + return kappa; } // linear interpolation of next target -bool PurePursuit::interpolateNextTarget( - int next_waypoint, geometry_msgs::Point* next_target) const +bool PurePursuit::interpolateNextTarget(int next_waypoint, geometry_msgs::Point* next_target) const { - constexpr double ERROR = pow(10, -5); // 0.00001 - - int path_size = static_cast(current_waypoints_.size()); + const int path_size = static_cast(current_waypoints_.size()); if (next_waypoint == path_size - 1) { - *next_target = current_waypoints_.at(next_waypoint).pose.pose.position; + *next_target = current_waypoints_.back().pose.pose.position; return true; } - double search_radius = lookahead_distance_; - geometry_msgs::Point zero_p; - geometry_msgs::Point end = - current_waypoints_.at(next_waypoint).pose.pose.position; - geometry_msgs::Point start = - current_waypoints_.at(next_waypoint - 1).pose.pose.position; - - // let the linear equation be "ax + by + c = 0" - // if there are two points (x1,y1) , (x2,y2), - // a = "y2-y1, b = "(-1) * x2 - x1" ,c = "(-1) * (y2-y1)x1 + (x2-x1)y1" - double a = 0; - double b = 0; - double c = 0; - double get_linear_flag = getLinearEquation(start, end, &a, &b, &c); - if (!get_linear_flag) - return false; - - // let the center of circle be "(x0,y0)", in my code , - // the center of circle is vehicle position - // the distance "d" between the foot of - // a perpendicular line and the center of circle is ... - // | a * x0 + b * y0 + c | - // d = ------------------------------- - // √( a~2 + b~2) - double d = getDistanceBetweenLineAndPoint(current_pose_.position, a, b, c); - - // ROS_INFO("a : %lf ", a); - // ROS_INFO("b : %lf ", b); - // ROS_INFO("c : %lf ", c); - // ROS_INFO("distance : %lf ", d); - - if (d > search_radius) - return false; - - // unit vector of point 'start' to point 'end' - tf::Vector3 v((end.x - start.x), (end.y - start.y), 0); - tf::Vector3 unit_v = v.normalize(); - - // normal unit vectors of v - // rotate to counter clockwise 90 degree - tf::Vector3 unit_w1 = rotateUnitVector(unit_v, 90); - // rotate to counter clockwise 90 degree - tf::Vector3 unit_w2 = rotateUnitVector(unit_v, -90); - - // the foot of a perpendicular line - geometry_msgs::Point h1; - h1.x = current_pose_.position.x + d * unit_w1.getX(); - h1.y = current_pose_.position.y + d * unit_w1.getY(); - h1.z = current_pose_.position.z; - - geometry_msgs::Point h2; - h2.x = current_pose_.position.x + d * unit_w2.getX(); - h2.y = current_pose_.position.y + d * unit_w2.getY(); - h2.z = current_pose_.position.z; - - // ROS_INFO("error : %lf", error); - // ROS_INFO("whether h1 on line : %lf", h1.y - (slope * h1.x + intercept)); - // ROS_INFO("whether h2 on line : %lf", h2.y - (slope * h2.x + intercept)); - - // check which of two foot of a perpendicular line is on the line equation - geometry_msgs::Point h; - if (fabs(a * h1.x + b * h1.y + c) < ERROR) - { - h = h1; - // ROS_INFO("use h1"); - } - else if (fabs(a * h2.x + b * h2.y + c) < ERROR) + const double search_radius = lookahead_distance_; + const geometry_msgs::Point end = current_waypoints_.at(next_waypoint).pose.pose.position; + const geometry_msgs::Point start = current_waypoints_.at(next_waypoint - 1).pose.pose.position; + + // project ego vehicle's current position at C onto the line at D in between two waypoints A and B. + const tf::Vector3 p_A(start.x, start.y, 0.0); + const tf::Vector3 p_B(end.x, end.y, 0.0); + const tf::Vector3 p_C(current_pose_.position.x, current_pose_.position.y, 0.0); + const tf::Vector3 AB = p_B - p_A; + const tf::Vector3 AC = p_C - p_A; + const tf::Vector3 p_D = p_A + AC.dot(AB) / AB.dot(AB) * AB; + const double dist_CD = (p_D - p_C).length(); + + bool found = false; + tf::Vector3 final_goal; + // Draw a circle centered at p_C with a radius of search_radius + if (dist_CD > search_radius) { - // ROS_INFO("use h2"); - h = h2; + // no intersection in between the circle and AB + found = false; } - else + else if (dist_CD == search_radius) { - return false; - } - - // get intersection[s] - // if there is a intersection - if (d == search_radius) - { - *next_target = h; - return true; + // one intersection + final_goal = p_D; + found = true; } else { - // if there are two intersection + // two intersections // get intersection in front of vehicle - double s = sqrt(pow(search_radius, 2) - pow(d, 2)); - geometry_msgs::Point target1; - target1.x = h.x + s * unit_v.getX(); - target1.y = h.y + s * unit_v.getY(); - target1.z = current_pose_.position.z; - - geometry_msgs::Point target2; - target2.x = h.x - s * unit_v.getX(); - target2.y = h.y - s * unit_v.getY(); - target2.z = current_pose_.position.z; + double s = sqrt(pow(search_radius, 2) - pow(dist_CD, 2)); + tf::Vector3 p_E = p_D + s * AB.normalized(); + tf::Vector3 p_F = p_D - s * AB.normalized(); - // ROS_INFO("target1 : ( %lf , %lf , %lf)", target1.x, target1.y, target1.z); - // ROS_INFO("target2 : ( %lf , %lf , %lf)", target2.x, target2.y, target2.z); - // displayLinePoint(a, b, c, target1, target2, h); // debug tool - - // check intersection is between end and start - double interval = getPlaneDistance(end, start); - if (getPlaneDistance(target1, end) < interval) + // verify whether these two points lie on line segment AB + if ((p_B - p_E).length2() < AB.length2()) { - // ROS_INFO("result : target1"); - *next_target = target1; - return true; + final_goal = p_E; + found = true; } - else if (getPlaneDistance(target2, end) < interval) + else if ((p_B - p_F).length2() < AB.length2()) { - // ROS_INFO("result : target2"); - *next_target = target2; - return true; + final_goal = p_F; + found = true; } else { - // ROS_INFO("result : false "); - return false; + found = false; } } -} + if (found) + { + next_target->x = final_goal.x(); + next_target->y = final_goal.y(); + next_target->z = current_pose_.position.z; + } + + return found; +} int PurePursuit::getNextWaypointNumber(bool use_lookahead_distance) { @@ -307,27 +227,22 @@ bool PurePursuit::canGetCurvature(double* output_kappa) } // if is_linear_interpolation_ is false or next waypoint is first or last if (!is_linear_interpolation_ || next_waypoint_number_ == 0 || - next_waypoint_number_ == (static_cast(current_waypoints_.size() - 1))) + next_waypoint_number_ == (static_cast(current_waypoints_.size() - 1))) { - next_target_position_ = - current_waypoints_.at(next_waypoint_number_).pose.pose.position; + next_target_position_ = current_waypoints_.at(next_waypoint_number_).pose.pose.position; *output_kappa = calcCurvature(next_target_position_); return true; } // linear interpolation and calculate angular velocity - bool interpolation = - interpolateNextTarget(next_waypoint_number_, &next_target_position_); + const bool interpolation = interpolateNextTarget(next_waypoint_number_, &next_target_position_); if (!interpolation) { - ROS_INFO_STREAM("lost target! "); + ROS_INFO("lost target!"); return false; } - // ROS_INFO("next_target : ( %lf , %lf , %lf)", - // next_target.x, next_target.y,next_target.z); - *output_kappa = calcCurvature(next_target_position_); return true; } diff --git a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp index 9134c96bf86..e038a4a7832 100644 --- a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp +++ b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp @@ -15,7 +15,10 @@ */ #include +#include + #include +#include namespace waypoint_follower { @@ -23,7 +26,7 @@ namespace waypoint_follower PurePursuitNode::PurePursuitNode() : private_nh_("~") , pp_() - , LOOP_RATE_(30) + , update_rate_(30.0) , is_waypoint_set_(false) , is_pose_set_(false) , is_velocity_set_(false) @@ -37,67 +40,96 @@ PurePursuitNode::PurePursuitNode() , minimum_lookahead_distance_(6.0) { initForROS(); - health_checker_ptr_ = - std::make_shared(nh_, private_nh_); + health_checker_ptr_ = std::make_shared(nh_, private_nh_); health_checker_ptr_->ENABLE(); // initialize for PurePursuit pp_.setLinearInterpolationParameter(is_linear_interpolation_); } -// Destructor -PurePursuitNode::~PurePursuitNode() -{ -} - void PurePursuitNode::initForROS() { // ros parameter settings + std::string out_twist, out_ctrl_cmd; private_nh_.param("is_linear_interpolation", is_linear_interpolation_, true); - private_nh_.param( - "publishes_for_steering_robot", publishes_for_steering_robot_, false); - private_nh_.param( - "add_virtual_end_waypoints", add_virtual_end_waypoints_, false); + private_nh_.param("add_virtual_end_waypoints", add_virtual_end_waypoints_, false); private_nh_.param("const_lookahead_distance", const_lookahead_distance_, 4.0); private_nh_.param("lookahead_ratio", lookahead_distance_ratio_, 2.0); - private_nh_.param( - "minimum_lookahead_distance", minimum_lookahead_distance_, 6.0); + private_nh_.param("minimum_lookahead_distance", minimum_lookahead_distance_, 6.0); private_nh_.param("vehicle_wheel_base", wheel_base_, 2.7); + private_nh_.param("update_rate", update_rate_, 30.0); + private_nh_.param("out_twist_name", out_twist, std::string("twist_raw")); + private_nh_.param("out_ctrl_cmd_name", out_ctrl_cmd, std::string("ctrl_raw")); + private_nh_.param("output_interface", output_interface_, std::string("ctrl_cmd")); + + + // Output type, use old parameter name only if it is set + if (private_nh_.hasParam("publishes_for_steering_robot")) + { + bool publishes_for_steering_robot; + private_nh_.param( + "publishes_for_steering_robot", publishes_for_steering_robot, false); + if (publishes_for_steering_robot) + { + output_interface_ = "ctrl_cmd"; + } + else + { + output_interface_ = "twist"; + } + } + else + { + private_nh_.param( + "output_interface", output_interface_, std::string("all")); + } + + if (output_interface_ != "twist" && output_interface_ != "ctrl_cmd" && + output_interface_ != "all") + { + ROS_ERROR("Control command interface type is not valid"); + ros::shutdown(); + } // setup subscriber - sub1_ = nh_.subscribe("final_waypoints", 10, - &PurePursuitNode::callbackFromWayPoints, this); - sub2_ = nh_.subscribe("current_pose", 10, - &PurePursuitNode::callbackFromCurrentPose, this); - sub3_ = nh_.subscribe("current_velocity", 10, - &PurePursuitNode::callbackFromCurrentVelocity, this); - - // setup publisher - pub1_ = nh_.advertise("twist_raw", 10); - pub2_ = nh_.advertise("ctrl_raw", 10); + sub1_ = nh_.subscribe("final_waypoints", 10, &PurePursuitNode::callbackFromWayPoints, this); + sub2_ = nh_.subscribe("current_pose", 10, &PurePursuitNode::callbackFromCurrentPose, this); + sub3_ = nh_.subscribe("current_velocity", 10, &PurePursuitNode::callbackFromCurrentVelocity, this); + + // setup publishers + pub1_ = nh_.advertise(out_twist, 10); + pub2_ = nh_.advertise(out_ctrl_cmd, 10); pub11_ = nh_.advertise("next_waypoint_mark", 0); pub12_ = nh_.advertise("next_target_mark", 0); pub13_ = nh_.advertise("search_circle_mark", 0); // debug tool pub14_ = nh_.advertise("line_point_mark", 0); - pub15_ = - nh_.advertise("trajectory_circle_mark", 0); + pub15_ = nh_.advertise("trajectory_circle_mark", 0); pub16_ = nh_.advertise("angular_gravity", 0); pub17_ = nh_.advertise("deviation_of_current_position", 0); - pub18_ = - nh_.advertise("expanded_waypoints_mark", 0); - // pub7_ = nh.advertise("wf_stat", 0); + pub18_ = nh_.advertise("expanded_waypoints_mark", 0); } void PurePursuitNode::run() { - ROS_INFO_STREAM("pure pursuit start"); - ros::Rate loop_rate(LOOP_RATE_); + ros::Rate loop_rate(update_rate_); while (ros::ok()) { ros::spinOnce(); if (!is_pose_set_ || !is_waypoint_set_ || !is_velocity_set_) { - ROS_WARN("Necessary topics are not subscribed yet ... "); + if (!is_pose_set_) + { + ROS_WARN_THROTTLE(5, "Waiting for current_pose topic ..."); + } + if (!is_waypoint_set_) + { + ROS_WARN_THROTTLE(5, "Waiting for final_waypoints topic ..."); + } + if (!is_velocity_set_) + { + ROS_WARN_THROTTLE(5, "Waiting for current_velocity topic ..."); + } + loop_rate.sleep(); continue; } @@ -108,42 +140,54 @@ void PurePursuitNode::run() double kappa = 0; bool can_get_curvature = pp_.canGetCurvature(&kappa); - publishTwistStamped(can_get_curvature, kappa); - publishControlCommandStamped(can_get_curvature, kappa); + publishControlCommands(can_get_curvature, kappa); health_checker_ptr_->NODE_ACTIVATE(); - health_checker_ptr_->CHECK_RATE("topic_rate_vehicle_cmd_slow", 8, 5, 1, - "topic vehicle_cmd publish rate slow."); + health_checker_ptr_->CHECK_RATE("topic_rate_vehicle_cmd_slow", 8, 5, 1, "topic vehicle_cmd publish rate slow."); // for visualization with Rviz pub11_.publish(displayNextWaypoint(pp_.getPoseOfNextWaypoint())); - pub13_.publish(displaySearchRadius( - pp_.getCurrentPose().position, pp_.getLookaheadDistance())); + pub13_.publish(displaySearchRadius(pp_.getCurrentPose().position, pp_.getLookaheadDistance())); pub12_.publish(displayNextTarget(pp_.getPoseOfNextTarget())); pub15_.publish(displayTrajectoryCircle( - waypoint_follower::generateTrajectoryCircle( - pp_.getPoseOfNextTarget(), pp_.getCurrentPose()))); + waypoint_follower::generateTrajectoryCircle(pp_.getPoseOfNextTarget(), pp_.getCurrentPose()))); if (add_virtual_end_waypoints_) { - pub18_.publish( - displayExpandWaypoints(pp_.getCurrentWaypoints(), expand_size_)); + pub18_.publish(displayExpandWaypoints(pp_.getCurrentWaypoints(), expand_size_)); } std_msgs::Float32 angular_gravity_msg; - angular_gravity_msg.data = - computeAngularGravity(computeCommandVelocity(), kappa); + angular_gravity_msg.data = computeAngularGravity(computeCommandVelocity(), kappa); pub16_.publish(angular_gravity_msg); - publishDeviationCurrentPosition( - pp_.getCurrentPose().position, pp_.getCurrentWaypoints()); + publishDeviationCurrentPosition(pp_.getCurrentPose().position, pp_.getCurrentWaypoints()); is_pose_set_ = false; is_velocity_set_ = false; - is_waypoint_set_ = false; loop_rate.sleep(); } } -void PurePursuitNode::publishTwistStamped( - const bool& can_get_curvature, const double& kappa) const +void PurePursuitNode::publishControlCommands(const bool& can_get_curvature, const double& kappa) const +{ + if (output_interface_ == "twist") + { + publishTwistStamped(can_get_curvature, kappa); + } + else if (output_interface_ == "ctrl_cmd") + { + publishCtrlCmdStamped(can_get_curvature, kappa); + } + else if (output_interface_ == "all") + { + publishTwistStamped(can_get_curvature, kappa); + publishCtrlCmdStamped(can_get_curvature, kappa); + } + else + { + ROS_WARN("[pure_pursuit] control command interface is not appropriate"); + } +} + +void PurePursuitNode::publishTwistStamped(const bool& can_get_curvature, const double& kappa) const { geometry_msgs::TwistStamped ts; ts.header.stamp = ros::Time::now(); @@ -152,21 +196,13 @@ void PurePursuitNode::publishTwistStamped( pub1_.publish(ts); } -void PurePursuitNode::publishControlCommandStamped( - const bool& can_get_curvature, const double& kappa) const +void PurePursuitNode::publishCtrlCmdStamped(const bool& can_get_curvature, const double& kappa) const { - if (!publishes_for_steering_robot_) - { - return; - } - autoware_msgs::ControlCommandStamped ccs; ccs.header.stamp = ros::Time::now(); ccs.cmd.linear_velocity = can_get_curvature ? computeCommandVelocity() : 0; ccs.cmd.linear_acceleration = can_get_curvature ? computeCommandAccel() : 0; - ccs.cmd.steering_angle = - can_get_curvature ? convertCurvatureToSteeringAngle(wheel_base_, kappa) : 0; - + ccs.cmd.steering_angle = can_get_curvature ? convertCurvatureToSteeringAngle(wheel_base_, kappa) : 0; pub2_.publish(ccs); } @@ -177,11 +213,11 @@ double PurePursuitNode::computeLookaheadDistance() const return const_lookahead_distance_; } - double maximum_lookahead_distance = current_linear_velocity_ * 10; - double ld = current_linear_velocity_ * lookahead_distance_ratio_; + const double maximum_lookahead_distance = current_linear_velocity_ * 10; + const double ld = current_linear_velocity_ * lookahead_distance_ratio_; return ld < minimum_lookahead_distance_ ? minimum_lookahead_distance_ : - ld > maximum_lookahead_distance ? maximum_lookahead_distance : ld; + ld > maximum_lookahead_distance ? maximum_lookahead_distance : ld; } int PurePursuitNode::getSgn() const @@ -208,70 +244,67 @@ double PurePursuitNode::computeCommandVelocity() const return command_linear_velocity_; } +// Assume constant acceleration motion, v_f^2 - v_i^2 = 2 * a * delta_d double PurePursuitNode::computeCommandAccel() const { const geometry_msgs::Pose current_pose = pp_.getCurrentPose(); - const geometry_msgs::Pose target_pose = - pp_.getCurrentWaypoints().at(1).pose.pose; - - // v^2 - v0^2 = 2ax - const double x = - std::hypot(current_pose.position.x - target_pose.position.x, - current_pose.position.y - target_pose.position.y); - const double v0 = current_linear_velocity_; - const double v = computeCommandVelocity(); - const double a = getSgn() * (v * v - v0 * v0) / (2 * x); - return a; + const geometry_msgs::Pose target_pose = pp_.getCurrentWaypoints().at(1).pose.pose; + + const double delta_d = + std::hypot(target_pose.position.x - current_pose.position.x, target_pose.position.y - current_pose.position.y); + const double v_i = current_linear_velocity_; + const double v_f = computeCommandVelocity(); + return (v_f * v_f - v_i * v_i) / (2 * delta_d); } -double PurePursuitNode::computeAngularGravity( - double velocity, double kappa) const +double PurePursuitNode::computeAngularGravity(double velocity, double kappa) const { const double gravity = 9.80665; return (velocity * velocity) / (1.0 / kappa * gravity); } -void PurePursuitNode::publishDeviationCurrentPosition( - const geometry_msgs::Point& point, - const std::vector& waypoints) const +void PurePursuitNode::publishDeviationCurrentPosition(const geometry_msgs::Point& point, + const std::vector& waypoints) const { - // Calculate the deviation of current position - // from the waypoint approximate line - + // Calculate the deviation of current position from the waypoint approximate line if (waypoints.size() < 3) { return; } - double a, b, c; - getLinearEquation( - waypoints.at(2).pose.pose.position, waypoints.at(1).pose.pose.position, - &a, &b, &c); + const geometry_msgs::Point end = waypoints.at(2).pose.pose.position; + const geometry_msgs::Point start = waypoints.at(1).pose.pose.position; - std_msgs::Float32 msg; - msg.data = getDistanceBetweenLineAndPoint(point, a, b, c); + const tf::Vector3 p_A(start.x, start.y, 0.0); + const tf::Vector3 p_B(end.x, end.y, 0.0); + const tf::Vector3 p_C(point.x, point.y, 0.0); + // The distance form a point C to a line passing through A and B is given by + // length(AB.crossProduct(AC))/length(AC) + const tf::Vector3 AB = p_B - p_A; + const tf::Vector3 AC = p_C - p_A; + const float distance = (AB.cross(AC)).length() / AC.length(); + + std_msgs::Float32 msg; + msg.data = distance; pub17_.publish(msg); } -void PurePursuitNode::callbackFromCurrentPose( - const geometry_msgs::PoseStampedConstPtr& msg) +void PurePursuitNode::callbackFromCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { pp_.setCurrentPose(msg); is_pose_set_ = true; } -void PurePursuitNode::callbackFromCurrentVelocity( - const geometry_msgs::TwistStampedConstPtr& msg) +void PurePursuitNode::callbackFromCurrentVelocity(const geometry_msgs::TwistStampedConstPtr& msg) { current_linear_velocity_ = msg->twist.linear.x; pp_.setCurrentVelocity(current_linear_velocity_); is_velocity_set_ = true; } -void PurePursuitNode::callbackFromWayPoints( - const autoware_msgs::LaneConstPtr& msg) +void PurePursuitNode::callbackFromWayPoints(const autoware_msgs::LaneConstPtr& msg) { if (add_virtual_end_waypoints_) @@ -304,8 +337,7 @@ void PurePursuitNode::callbackFromWayPoints( } -void PurePursuitNode::connectVirtualLastWaypoints( - autoware_msgs::Lane* lane, LaneDirection direction) +void PurePursuitNode::connectVirtualLastWaypoints(autoware_msgs::Lane* lane, LaneDirection direction) { if (lane->waypoints.empty()) { @@ -321,8 +353,7 @@ void PurePursuitNode::connectVirtualLastWaypoints( for (double dist = minimum_lookahead_distance_; dist > 0.0; dist -= interval) { virtual_last_point_rlt.x += interval * sgn; - virtual_last_waypoint.pose.pose.position = - calcAbsoluteCoordinate(virtual_last_point_rlt, pn); + virtual_last_waypoint.pose.pose.position = calcAbsoluteCoordinate(virtual_last_point_rlt, pn); lane->waypoints.emplace_back(virtual_last_waypoint); } } @@ -338,8 +369,7 @@ void PurePursuitNode::calculateNextWaypoint() pp_.setNextWaypoint(next_waypoint_number); } -double convertCurvatureToSteeringAngle( - const double& wheel_base, const double& kappa) +double convertCurvatureToSteeringAngle(const double& wheel_base, const double& kappa) { return atan(wheel_base * kappa); } diff --git a/core_planning/pure_pursuit/src/pure_pursuit_viz.cpp b/core_planning/pure_pursuit/src/pure_pursuit_viz.cpp index 8e31fbbef0a..6efb2f412b5 100644 --- a/core_planning/pure_pursuit/src/pure_pursuit_viz.cpp +++ b/core_planning/pure_pursuit/src/pure_pursuit_viz.cpp @@ -14,9 +14,10 @@ * limitations under the License. */ +#include + #include #include -#include namespace waypoint_follower { @@ -102,15 +103,15 @@ visualization_msgs::Marker displayExpandWaypoints(const std::vector generateTrajectoryCircle(geometry_msgs::Point geometry_msgs::Pose current_pose) { std::vector traj_circle_array; - double radius = calcRadius(target, current_pose); - double range = M_PI / 8; - double increment = 0.01; + const double radius = calcRadius(target, current_pose); + const double range = M_PI / 8; + const double increment = 0.01; for (double i = 0; i < range; i += increment) { @@ -226,88 +227,5 @@ visualization_msgs::Marker displaySearchRadius(geometry_msgs::Point current_pose marker.frame_locked = true; return marker; } -/* -// debug tool for interpolateNextTarget -void displayLinePoint(double a, double b, double c, geometry_msgs::Point target, geometry_msgs::Point target2, - geometry_msgs::Point target3) -{ - visualization_msgs::Marker line; - line.header.frame_id = MAP_FRAME; - line.header.stamp = ros::Time(); - line.ns = "line_marker"; - line.id = 0; - line.type = visualization_msgs::Marker::LINE_STRIP; - line.action = visualization_msgs::Marker::ADD; - - std_msgs::ColorRGBA white; - white.a = 1.0; - white.b = 1.0; - white.r = 1.0; - white.g = 1.0; - for (int i = -100000; i < 100000;) - { - geometry_msgs::Point p; - if (fabs(a) < ERROR) // linear equation y = n - { - p.y = (-1) * c / b; - p.x = i; - } - else if (fabs(b) < ERROR) // linear equation x = n - { - p.x = (-1) * c / a; - p.y = i; - } - else - { - p.x = i; - p.y = (-1) * (a * p.x + c) / b; - } - p.z = _current_pose.pose.position.z; - line.points.push_back(p); - i += 5000; - } - - line.scale.x = 0.3; - line.color = white; - line.frame_locked = true; - _line_point_pub.publish(line); - - visualization_msgs::Marker marker; - marker.header.frame_id = MAP_FRAME; - marker.header.stamp = ros::Time(); - marker.ns = "target_marker"; - marker.id = 0; - marker.type = visualization_msgs::Marker::SPHERE_LIST; - marker.action = visualization_msgs::Marker::ADD; - // marker.pose.position = target; - marker.points.push_back(target); - std_msgs::ColorRGBA green; - green.a = 1.0; - green.b = 0.0; - green.r = 0.0; - green.g = 1.0; - marker.colors.push_back(green); - marker.points.push_back(target2); - std_msgs::ColorRGBA yellow; - yellow.a = 1.0; - yellow.b = 0.0; - yellow.r = 1.0; - yellow.g = 1.0; - marker.colors.push_back(yellow); - marker.points.push_back(target3); - std_msgs::ColorRGBA color; - color.a = 1.0; - color.b = 1.0; - color.r = 0.0; - color.g = 1.0; - marker.colors.push_back(color); - - marker.scale.x = 1.0; - marker.scale.y = 1.0; - marker.scale.z = 1.0; - marker.frame_locked = true; - _line_point_pub.publish(marker); -} - */ } // namespace waypoint_follower diff --git a/core_planning/pure_pursuit/test/src/test_pure_pursuit.cpp b/core_planning/pure_pursuit/test/src/test_pure_pursuit.cpp index d1aa9f5891c..f067ed8a6dd 100644 --- a/core_planning/pure_pursuit/test/src/test_pure_pursuit.cpp +++ b/core_planning/pure_pursuit/test/src/test_pure_pursuit.cpp @@ -17,6 +17,8 @@ #include #include #include +#include +#include namespace waypoint_follower { @@ -44,8 +46,8 @@ class PurePursuitNodeTestSuite : public ::testing::Test } public: - PurePursuitNodeTestSuite() {} - ~PurePursuitNodeTestSuite() {} + PurePursuitNodeTestSuite() = default; + ~PurePursuitNodeTestSuite() = default; LaneDirection getDirection() { return obj_->direction_; @@ -54,8 +56,7 @@ class PurePursuitNodeTestSuite : public ::testing::Test { obj_->callbackFromWayPoints(msg); } - void ppConnectVirtualLastWaypoints( - autoware_msgs::Lane* expand_lane, LaneDirection direction) + void ppConnectVirtualLastWaypoints(autoware_msgs::Lane* expand_lane, LaneDirection direction) { obj_->connectVirtualLastWaypoints(expand_lane, direction); } @@ -103,14 +104,11 @@ TEST_F(PurePursuitNodeTestSuite, inputPositivePath) for (int i = 0; i < 3; i++) { original_lane.waypoints[i].pose.pose.position.x = i; - original_lane.waypoints[i].pose.pose.orientation = - tf::createQuaternionMsgFromYaw(0.0); + original_lane.waypoints[i].pose.pose.orientation = tf::createQuaternionMsgFromYaw(0.0); } - const autoware_msgs::LaneConstPtr - lp(boost::make_shared(original_lane)); + const autoware_msgs::LaneConstPtr lp(boost::make_shared(original_lane)); ppCallbackFromWayPoints(lp); - ASSERT_EQ(getDirection(), LaneDirection::Forward) - << "direction is not matching to positive lane."; + ASSERT_EQ(getDirection(), LaneDirection::Forward) << "direction is not matching to positive lane."; } TEST_F(PurePursuitNodeTestSuite, inputNegativePath) @@ -120,22 +118,18 @@ TEST_F(PurePursuitNodeTestSuite, inputNegativePath) for (int i = 0; i < 3; i++) { original_lane.waypoints[i].pose.pose.position.x = -i; - original_lane.waypoints[i].pose.pose.orientation = - tf::createQuaternionMsgFromYaw(0.0); + original_lane.waypoints[i].pose.pose.orientation = tf::createQuaternionMsgFromYaw(0.0); } - const autoware_msgs::LaneConstPtr - lp(boost::make_shared(original_lane)); + const autoware_msgs::LaneConstPtr lp(boost::make_shared(original_lane)); ppCallbackFromWayPoints(lp); - ASSERT_EQ(getDirection(), LaneDirection::Backward) - << "direction is not matching to negative lane."; + ASSERT_EQ(getDirection(), LaneDirection::Backward) << "direction is not matching to negative lane."; } // If original lane is empty, new lane is also empty. TEST_F(PurePursuitNodeTestSuite, inputEmptyLane) { autoware_msgs::Lane original_lane, new_lane; ppConnectVirtualLastWaypoints(&new_lane, LaneDirection::Forward); - ASSERT_EQ(original_lane.waypoints.size(), new_lane.waypoints.size()) - << "Input empty lane, and output is not empty"; + ASSERT_EQ(original_lane.waypoints.size(), new_lane.waypoints.size()) << "Input empty lane, and output is not empty"; } // If the original lane exceeds 2 points, @@ -152,8 +146,7 @@ TEST_F(PurePursuitNodeTestSuite, inputNormalLane) autoware_msgs::Lane new_lane(original_lane); ppConnectVirtualLastWaypoints(&new_lane, LaneDirection::Forward); - ASSERT_LT(original_lane.waypoints.size(), new_lane.waypoints.size()) - << "Fail to expand waypoints"; + ASSERT_LT(original_lane.waypoints.size(), new_lane.waypoints.size()) << "Fail to expand waypoints"; } @@ -169,7 +162,7 @@ TEST_F(PurePursuitNodeTestSuite, checkWaypointIsAheadOrBehind) */ autoware_msgs::Lane original_lane; - original_lane.waypoints.resize(4, autoware_msgs::Waypoint()); + original_lane.waypoints.resize(5, autoware_msgs::Waypoint()); original_lane.waypoints[0].pose.pose.position.x = 0; original_lane.waypoints[1].pose.pose.position.x = 1; original_lane.waypoints[2].pose.pose.position.x = 3; diff --git a/core_planning/state_machine_lib/CMakeLists.txt b/core_planning/state_machine_lib/CMakeLists.txt index c47aa4e58f6..bc164a511b4 100644 --- a/core_planning/state_machine_lib/CMakeLists.txt +++ b/core_planning/state_machine_lib/CMakeLists.txt @@ -5,14 +5,13 @@ find_package(autoware_build_flags REQUIRED) find_package( catkin REQUIRED COMPONENTS - roscpp autoware_msgs + roscpp ) catkin_package( INCLUDE_DIRS include LIBRARIES state_machine_lib - CATKIN_DEPENDS roscpp autoware_msgs ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") @@ -44,7 +43,6 @@ install( FILES_MATCHING PATTERN "*.hpp" ) - install( TARGETS state_machine_lib ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/core_planning/state_machine_lib/include/state_machine_lib/state_flags.hpp b/core_planning/state_machine_lib/include/state_machine_lib/state_flags.hpp index 6a5c1236cc7..86e6b305fd3 100644 --- a/core_planning/state_machine_lib/include/state_machine_lib/state_flags.hpp +++ b/core_planning/state_machine_lib/include/state_machine_lib/state_flags.hpp @@ -9,14 +9,6 @@ enum class CallbackType ENTRY, EXIT }; - -enum TrafficLightColors -{ - E_RED = 0, - E_YELLOW = 0, - E_GREEN = 1, - E_COLOR_ERROR = 2 -}; } #endif diff --git a/core_planning/way_planner/CMakeLists.txt b/core_planning/way_planner/CMakeLists.txt index cf85b53dbe3..1cb1081715f 100644 --- a/core_planning/way_planner/CMakeLists.txt +++ b/core_planning/way_planner/CMakeLists.txt @@ -20,19 +20,12 @@ find_package( std_msgs tf vector_map_msgs + roslint ) catkin_package( INCLUDE_DIRS include LIBRARIES way_planner - CATKIN_DEPENDS - geometry_msgs - libwaypoint_follower - op_planner - op_simu - op_utility - std_msgs - vector_map_msgs ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall -Wno-unused-result -DROS ${CMAKE_CXX_FLAGS}") @@ -43,6 +36,8 @@ include_directories( ${catkin_INCLUDE_DIRS} ) +roslint_cpp() + add_executable( way_planner nodes/way_planner.cpp @@ -59,7 +54,7 @@ install( LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) - + install( DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch diff --git a/core_planning/way_planner/include/ROSHelpers.h b/core_planning/way_planner/include/ROSHelpers.h index b24cdeaa8aa..66f17b9f7b4 100644 --- a/core_planning/way_planner/include/ROSHelpers.h +++ b/core_planning/way_planner/include/ROSHelpers.h @@ -1,3 +1,19 @@ +/* + * Copyright 2016-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + /* * ROSHelpers.h * @@ -30,121 +46,135 @@ #include #include "op_planner/RoadNetwork.h" +#include +#include + namespace WayPlannerNS { - enum MSG_TYPE{COMMAND_MSG = 0, CONFIRM_MSG = 1, OPTIONS_MSG = 2, CURR_OPTION_MSG = 3, UNKNOWN_MSG = 5}; class HMI_MSG { -public: - MSG_TYPE type; - std::vector options; - PlannerHNS::ACTION_TYPE current; - int currID; - bool bErr; - std::string err_msg; - HMI_MSG() - { - currID = -1; - type = OPTIONS_MSG; - current = PlannerHNS::FORWARD_ACTION; - bErr = false; - } - - static HMI_MSG FromString(std::string msg) - { - HMI_MSG recieved_msg; - std::vector sections = SplitString(msg, ","); - if (sections.size() == 6) - { - int type_str = atoi(sections.at(0).c_str()); - switch (type_str) - { - case 0: - recieved_msg.type = COMMAND_MSG; - break; - case 1: - recieved_msg.type = CONFIRM_MSG; - break; - case 2: - recieved_msg.type = OPTIONS_MSG; - break; - case 3: - recieved_msg.type = CURR_OPTION_MSG; - break; - default: - recieved_msg.type = UNKNOWN_MSG; - break; - } - - std::vector directions = SplitString(sections.at(1), ";"); - for (unsigned int i = 0; i < directions.size(); i++) - { - int idirect = atoi(directions.at(i).c_str()); - if(idirect == 0) - recieved_msg.options.push_back(PlannerHNS::FORWARD_ACTION); - else if (idirect == 3) - recieved_msg.options.push_back(PlannerHNS::LEFT_TURN_ACTION); - else if (idirect == 4) - recieved_msg.options.push_back(PlannerHNS::RIGHT_TURN_ACTION); - } - recieved_msg.currID = atoi(sections.at(3).c_str()); - recieved_msg.bErr = atoi(sections.at(4).c_str()); - recieved_msg.err_msg = sections.at(5); - } - return recieved_msg; - } - - static std::vector SplitString(const std::string& str, const std::string& token) - { - std::vector str_parts; - int iFirstPart = 0; - int iSecondPart = str.find(token, iFirstPart); - - while (iSecondPart > 0 && iSecondPart < str.size()) - { - str_parts.push_back(str.substr(iFirstPart, iSecondPart- iFirstPart)); - iFirstPart = iSecondPart+1; - iSecondPart = str.find(token, iFirstPart); - } - - return str_parts; - } + public: + MSG_TYPE type; + std::vector options; + PlannerHNS::ACTION_TYPE current; + int currID; + bool bErr; + std::string err_msg; + HMI_MSG() + { + currID = -1; + type = OPTIONS_MSG; + current = PlannerHNS::FORWARD_ACTION; + bErr = false; + } + + static HMI_MSG FromString(std::string msg) + { + HMI_MSG recieved_msg; + std::vector sections = SplitString(msg, ","); + if (sections.size() == 6) + { + int type_str = atoi(sections.at(0).c_str()); + switch (type_str) + { + case 0: + recieved_msg.type = COMMAND_MSG; + break; + case 1: + recieved_msg.type = CONFIRM_MSG; + break; + case 2: + recieved_msg.type = OPTIONS_MSG; + break; + case 3: + recieved_msg.type = CURR_OPTION_MSG; + break; + default: + recieved_msg.type = UNKNOWN_MSG; + break; + } + + std::vector directions = SplitString(sections.at(1), ";"); + for (unsigned int i = 0; i < directions.size(); i++) + { + int idirect = atoi(directions.at(i).c_str()); + if (idirect == 0) + { + recieved_msg.options.push_back(PlannerHNS::FORWARD_ACTION); + } + else if (idirect == 3) + { + recieved_msg.options.push_back(PlannerHNS::LEFT_TURN_ACTION); + } + else if (idirect == 4) + { + recieved_msg.options.push_back(PlannerHNS::RIGHT_TURN_ACTION); + } + } + recieved_msg.currID = atoi(sections.at(3).c_str()); + recieved_msg.bErr = atoi(sections.at(4).c_str()); + recieved_msg.err_msg = sections.at(5); + } + return recieved_msg; + } + + static std::vector SplitString(const std::string& str, const std::string& token) + { + std::vector str_parts; + int iFirstPart = 0; + int iSecondPart = str.find(token, iFirstPart); + + while ((iSecondPart > 0) && (iSecondPart < str.size())) + { + str_parts.push_back(str.substr(iFirstPart, iSecondPart - iFirstPart)); + iFirstPart = iSecondPart+1; + iSecondPart = str.find(token, iFirstPart); + } + + return str_parts; + } }; class ROSHelpers { -public: - ROSHelpers(); - virtual ~ROSHelpers(); - static void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform); - static void ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, - autoware_msgs::LaneArray& laneArray); + public: + ROSHelpers(); + virtual ~ROSHelpers(); + static void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, + tf::StampedTransform &transform); + static void ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, + autoware_msgs::LaneArray& laneArray); - static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, - const std::vector >& paths, - visualization_msgs::MarkerArray& markerArray); + static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, + const std::vector>& paths, + visualization_msgs::MarkerArray& markerArray); - static void ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector >& globalPaths, - visualization_msgs::MarkerArray& markerArray); + static void ConvertFromPlannerHToAutowareVisualizePathFormat( + const std::vector>& globalPaths, + visualization_msgs::MarkerArray& markerArray); - static void ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray); + static void ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, + visualization_msgs::MarkerArray& markerArray); - static void createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, + const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray); - static void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array, + visualization_msgs::MarkerArray& markerArray); - static void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray); + static void createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array, + visualization_msgs::MarkerArray& markerArray); - static void ConvertFromPlannerHPointsToAutowarePathFormat(const std::vector& path, - autoware_msgs::LaneArray& laneArray); + static void ConvertFromPlannerHPointsToAutowarePathFormat(const std::vector& path, + autoware_msgs::LaneArray& laneArray); - static void FindIncommingBranches(const std::vector >& globalPaths, const PlannerHNS::WayPoint& currPose, const double& min_distance, - std::vector& branches, PlannerHNS::WayPoint* currOptions); + static void FindIncommingBranches(const std::vector>& globalPaths, + const PlannerHNS::WayPoint& currPose, const double& min_distance, + std::vector& branches, PlannerHNS::WayPoint* currOptions); }; -} -#endif /* ROSHELPERS_H_ */ +} // namespace WayPlannerNS + +#endif // ROSHELPERS_H_ diff --git a/core_planning/way_planner/include/SocketServer.h b/core_planning/way_planner/include/SocketServer.h index 997aa304d9c..44df55a2416 100644 --- a/core_planning/way_planner/include/SocketServer.h +++ b/core_planning/way_planner/include/SocketServer.h @@ -1,3 +1,19 @@ +/* + * Copyright 2017-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + /* * SocketServer.h * @@ -8,49 +24,46 @@ #ifndef SOCKETSERVER_H_ #define SOCKETSERVER_H_ - #include #include #include #include -#include #include #include #include "ROSHelpers.h" namespace WayPlannerNS { + class HMISocketServer { -public: - HMISocketServer(); - virtual ~HMISocketServer(); - int InitSocket(int port_send, int port_receive); - void SendMSG(HMI_MSG msg); - int GetLatestMSG(HMI_MSG& msg); - -private: - int m_ConnPortSend; - int m_ConnPortReceive; - int m_Socket_send; - int m_Socket_receive; - pthread_mutex_t sock_mutex_send; - pthread_t sock_thread_tid_send; - HMI_MSG m_msg_send; - bool m_bLatestMsg_send; - pthread_mutex_t sock_mutex_receive; - pthread_t sock_thread_tid_receive; - HMI_MSG m_msg_receive; - bool m_bLatestMsg_receive; - - //socklen_t m_Len; - bool m_bExitMainLoop; - - static void* ThreadMainSend(void* pSock); - static void* ThreadMainReceive(void* pSock); + public: + HMISocketServer(); + virtual ~HMISocketServer(); + int InitSocket(int port_send, int port_receive); + void SendMSG(HMI_MSG msg); + int GetLatestMSG(HMI_MSG& msg); + + private: + int m_ConnPortSend; + int m_ConnPortReceive; + int m_Socket_send; + int m_Socket_receive; + pthread_mutex_t sock_mutex_send; + pthread_t sock_thread_tid_send; + HMI_MSG m_msg_send; + bool m_bLatestMsg_send; + pthread_mutex_t sock_mutex_receive; + pthread_t sock_thread_tid_receive; + HMI_MSG m_msg_receive; + bool m_bLatestMsg_receive; + + bool m_bExitMainLoop; + static void* ThreadMainSend(void* pSock); + static void* ThreadMainReceive(void* pSock); }; -} +} // namespace WayPlannerNS -#endif /* SOCKETSERVER_H_ */ +#endif // SOCKETSERVER_H_ diff --git a/core_planning/way_planner/include/way_planner_core.h b/core_planning/way_planner/include/way_planner_core.h index adbdb220f27..b7d16fbc62b 100644 --- a/core_planning/way_planner/include/way_planner_core.h +++ b/core_planning/way_planner/include/way_planner_core.h @@ -1,5 +1,5 @@ /* - * Copyright 2016-2019 Autoware Foundation. All rights reserved. + * Copyright 2016-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,8 +14,8 @@ * limitations under the License. */ -#ifndef WAYPLANNERCORE_H_ -#define WAYPLANNERCORE_H_ +#ifndef WAY_PLANNER_CORE_H_ +#define WAY_PLANNER_CORE_H_ #include @@ -50,177 +50,177 @@ #include "ROSHelpers.h" #include "SocketServer.h" -namespace WayPlannerNS { +#include +#include +namespace WayPlannerNS +{ #define MAX_GLOBAL_PLAN_DISTANCE 10000 -#define _ENABLE_VISUALIZE_PLAN +#define ENABLE_VISUALIZE_PLAN #define REPLANNING_DISTANCE 25 + class AutowareRoadNetwork { -public: - vector_map_msgs::PointArray points; - vector_map_msgs::LaneArray lanes; - vector_map_msgs::NodeArray nodes; - vector_map_msgs::StopLineArray stoplines; - vector_map_msgs::DTLaneArray dtlanes; //center lines - vector_map_msgs::AreaArray areas; - vector_map_msgs::LineArray lines; - vector_map_msgs::SignalArray signals; - vector_map_msgs::VectorArray vectors; - - bool bPoints; - bool bLanes; - bool bNodes; - bool bStopLines; - bool bDtLanes; - bool bAreas; - bool bLines; - bool bSignals; - bool bVectors; - - AutowareRoadNetwork() - { - bPoints = false; - bLanes = false; - bStopLines = false; - bDtLanes = false; - bNodes = false; - bAreas = false; - bLines = false; - bSignals = false; - bVectors = false; - } + public: + vector_map_msgs::PointArray points; + vector_map_msgs::LaneArray lanes; + vector_map_msgs::NodeArray nodes; + vector_map_msgs::StopLineArray stoplines; + vector_map_msgs::DTLaneArray dtlanes; // center lines + vector_map_msgs::AreaArray areas; + vector_map_msgs::LineArray lines; + vector_map_msgs::SignalArray signals; + vector_map_msgs::VectorArray vectors; + + bool bPoints; + bool bLanes; + bool bNodes; + bool bStopLines; + bool bDtLanes; + bool bAreas; + bool bLines; + bool bSignals; + bool bVectors; + + AutowareRoadNetwork() + { + bPoints = false; + bLanes = false; + bStopLines = false; + bDtLanes = false; + bNodes = false; + bAreas = false; + bLines = false; + bSignals = false; + bVectors = false; + } }; enum MAP_SOURCE_TYPE{MAP_AUTOWARE, MAP_FOLDER, MAP_KML_FILE}; class WayPlannerParams { -public: - std::string KmlMapPath; - bool bEnableSmoothing; - bool bEnableLaneChange; - bool bEnableHMI; - bool bEnableRvizInput; - bool bEnableReplanning; - double pathDensity; - MAP_SOURCE_TYPE mapSource; - - - WayPlannerParams() - { - bEnableReplanning = false; - bEnableHMI = false; - bEnableSmoothing = false; - bEnableLaneChange = false; - bEnableRvizInput = true; - pathDensity = 0.5; - mapSource = MAP_KML_FILE; - } + public: + std::string KmlMapPath; + bool bEnableSmoothing; + bool bEnableLaneChange; + bool bEnableHMI; + bool bEnableRvizInput; + bool bEnableReplanning; + double pathDensity; + double fallbackMinGoalDistanceTh; + int planningMaxAttempt; + MAP_SOURCE_TYPE mapSource; + + + WayPlannerParams() + { + bEnableReplanning = false; + bEnableHMI = false; + bEnableSmoothing = false; + bEnableLaneChange = false; + bEnableRvizInput = true; + pathDensity = 0.5; + fallbackMinGoalDistanceTh = 0.0; + planningMaxAttempt = 0; + mapSource = MAP_KML_FILE; + } }; class way_planner_core { -protected: - - WayPlannerParams m_params; - AutowareRoadNetwork m_AwMap; - //geometry_msgs::Pose m_StartPos; - PlannerHNS::WayPoint m_CurrentPose; - //bool bStartPos; - //bool bUsingCurrentPose; - int m_iCurrentGoalIndex; - std::vector m_GoalsPos; - //bool bGoalPos; - geometry_msgs::Pose m_OriginPos; - PlannerHNS::VehicleState m_VehicleState; - - - std::vector m_NodesList; - - ros::NodeHandle nh; - - ros::Publisher pub_MapRviz; - ros::Publisher pub_Paths; - ros::Publisher pub_PathsRviz; - ros::Publisher pub_TrafficInfo; - ros::Publisher pub_TrafficInfoRviz; - ros::Publisher pub_StartPointRviz; - ros::Publisher pub_GoalPointRviz; - ros::Publisher pub_NodesListRviz; - - ros::Subscriber sub_robot_odom ; - ros::Subscriber sub_start_pose; - ros::Subscriber sub_goal_pose; - ros::Subscriber sub_current_pose; - ros::Subscriber sub_current_velocity; - ros::Subscriber sub_nodes_list; - ros::Subscriber sub_map_points; - ros::Subscriber sub_map_lanes; - ros::Subscriber sub_map_nodes; - ros::Subscriber sup_stop_lines; - ros::Subscriber sub_dtlanes; - ros::Subscriber sub_can_info ; - -public: - way_planner_core(); - ~way_planner_core(); - void PlannerMainLoop(); - -private: - - void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform); - - // Callback function for subscriber. - void callbackGetGoalPose(const geometry_msgs::PoseStampedConstPtr &msg); - void callbackGetStartPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &input); - void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); - void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); - void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); - void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); - - void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); - void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); - void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); - void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); - void callbackGetVMCenterLines(const vector_map_msgs::DTLaneArray& msg); - void callbackGetNodesList(const vector_map_msgs::NodeArray& msg); - protected: - PlannerHNS::RoadNetwork m_Map; - bool m_bKmlMap; - PlannerHNS::PlannerH m_PlannerH; - std::vector > m_GeneratedTotalPaths; - - void UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map); - bool GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, std::vector >& generatedTotalPaths); - void VisualizeAndSend(const std::vector > generatedTotalPaths); - - - - private: //debug variables - PlannerHNS::WayPoint* m_pCurrGoal; + WayPlannerParams m_params; + AutowareRoadNetwork m_AwMap; + PlannerHNS::WayPoint m_CurrentPose; + int m_iCurrentGoalIndex; + std::vector m_GoalsPos; + geometry_msgs::Pose m_OriginPos; + PlannerHNS::VehicleState m_VehicleState; + + std::vector m_NodesList; + + ros::NodeHandle nh; + + ros::Publisher pub_MapRviz; + ros::Publisher pub_Paths; + ros::Publisher pub_PathsRviz; + ros::Publisher pub_TrafficInfo; + ros::Publisher pub_TrafficInfoRviz; + ros::Publisher pub_StartPointRviz; + ros::Publisher pub_GoalPointRviz; + ros::Publisher pub_NodesListRviz; + + ros::Subscriber sub_robot_odom; + ros::Subscriber sub_start_pose; + ros::Subscriber sub_goal_pose; + ros::Subscriber sub_current_pose; + ros::Subscriber sub_current_velocity; + ros::Subscriber sub_nodes_list; + ros::Subscriber sub_map_points; + ros::Subscriber sub_map_lanes; + ros::Subscriber sub_map_nodes; + ros::Subscriber sup_stop_lines; + ros::Subscriber sub_dtlanes; + ros::Subscriber sub_can_info; + + public: + way_planner_core(); + ~way_planner_core(); + void PlannerMainLoop(); + + private: + void GetTransformFromTF(const std::string parent_frame, const std::string child_frame, + tf::StampedTransform &transform); + + // Callback function for subscriber. + void callbackGetGoalPose(const geometry_msgs::PoseStampedConstPtr &msg); + void callbackGetStartPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &input); + void callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg); + void callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg); + void callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg); + void callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg); + + void callbackGetVMPoints(const vector_map_msgs::PointArray& msg); + void callbackGetVMLanes(const vector_map_msgs::LaneArray& msg); + void callbackGetVMNodes(const vector_map_msgs::NodeArray& msg); + void callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg); + void callbackGetVMCenterLines(const vector_map_msgs::DTLaneArray& msg); + void callbackGetNodesList(const vector_map_msgs::NodeArray& msg); + + protected: + PlannerHNS::RoadNetwork m_Map; + bool m_bKmlMap; + PlannerHNS::PlannerH m_PlannerH; + std::vector> m_GeneratedTotalPaths; + + void UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map); + bool GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, + std::vector>& generatedTotalPaths); + void VisualizeAndSend(const std::vector> generatedTotalPaths); + + private: // debug variables + PlannerHNS::WayPoint* m_pCurrGoal; #ifdef ENABLE_VISUALIZE_PLAN - ros::Publisher pub_GlobalPlanAnimationRviz; - void CreateNextPlanningTreeLevelMarker(std::vector& level, visualization_msgs::MarkerArray& markerArray, double max_cost = 1); - std::vector m_PlanningVisualizeTree; - std::vector m_CurrentLevel; - visualization_msgs::MarkerArray m_AccumPlanLevels; - unsigned int m_iCurrLevel; - unsigned int m_nLevelSize; - double m_CurrMaxCost; - int m_bSwitch; + ros::Publisher pub_GlobalPlanAnimationRviz; + void CreateNextPlanningTreeLevelMarker(std::vector& level, + visualization_msgs::MarkerArray& markerArray, double max_cost = 1); + std::vector m_PlanningVisualizeTree; + std::vector m_CurrentLevel; + visualization_msgs::MarkerArray m_AccumPlanLevels; + unsigned int m_iCurrLevel; + unsigned int m_nLevelSize; + double m_CurrMaxCost; + int m_bSwitch; #endif - - double m_AvgResponseTime; //seconds - HMISocketServer m_SocketServer; - std::vector m_ModifiedWayPointsCosts; - bool HMI_DoOneStep(); - + double m_AvgResponseTime; // seconds + HMISocketServer m_SocketServer; + std::vector m_ModifiedWayPointsCosts; + bool HMI_DoOneStep(); }; -} +} // namespace WayPlannerNS -#endif +#endif // WAY_PLANNER_CORE_H_ diff --git a/core_planning/way_planner/launch/way_planner.launch b/core_planning/way_planner/launch/way_planner.launch index 8bc82d8eb96..06c40bc61ba 100644 --- a/core_planning/way_planner/launch/way_planner.launch +++ b/core_planning/way_planner/launch/way_planner.launch @@ -1,27 +1,28 @@ - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/core_planning/way_planner/nodes/ROSHelpers.cpp b/core_planning/way_planner/nodes/ROSHelpers.cpp index 013449a1cbb..fbb3d3147cb 100644 --- a/core_planning/way_planner/nodes/ROSHelpers.cpp +++ b/core_planning/way_planner/nodes/ROSHelpers.cpp @@ -1,3 +1,19 @@ +/* + * Copyright 2016-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + /* * ROSHelpers.cpp * @@ -10,343 +26,316 @@ #include #include #include +#include +#include #include #include "op_planner/PlanningHelpers.h" -namespace WayPlannerNS { - -ROSHelpers::ROSHelpers() { +namespace WayPlannerNS +{ +ROSHelpers::ROSHelpers() +{ } -ROSHelpers::~ROSHelpers() { +ROSHelpers::~ROSHelpers() +{ } -void ROSHelpers::GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform) +void ROSHelpers::GetTransformFromTF(const std::string parent_frame, + const std::string child_frame, + tf::StampedTransform &transform) { - static tf::TransformListener listener; - - while (1) - { - try - { - listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); - break; - } - catch (tf::TransformException& ex) - { - ROS_ERROR("%s", ex.what()); - ros::Duration(1.0).sleep(); - } - } + static tf::TransformListener listener; + + while (1) + { + try + { + listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); + break; + } + catch (tf::TransformException& ex) + { + ROS_ERROR("%s", ex.what()); + ros::Duration(1.0).sleep(); + } + } } void ROSHelpers::ConvertFromPlannerHPointsToAutowarePathFormat(const std::vector& path, - autoware_msgs::LaneArray& laneArray) + autoware_msgs::LaneArray& laneArray) { - autoware_msgs::Lane l; - - for(unsigned int i=0; i < path.size(); i++) - { - autoware_msgs::Waypoint wp; - wp.pose.pose.position.x = path.at(i).x; - wp.pose.pose.position.y = path.at(i).y; - wp.pose.pose.position.z = path.at(i).z; - //wp.pose.pose.position.z = 5; - wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).a)); - - l.waypoints.push_back(wp); - } - - if(l.waypoints.size()>0) - laneArray.lanes.push_back(l); + autoware_msgs::Lane l; + + for (unsigned int i = 0; i < path.size(); i++) + { + autoware_msgs::Waypoint wp; + wp.pose.pose.position.x = path.at(i).x; + wp.pose.pose.position.y = path.at(i).y; + wp.pose.pose.position.z = path.at(i).z; + + wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).a)); + + l.waypoints.push_back(wp); + } + + if (l.waypoints.size() > 0) + { + laneArray.lanes.push_back(l); + } } void ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(const std::vector& path, - autoware_msgs::LaneArray& laneArray) + autoware_msgs::LaneArray& laneArray) { - autoware_msgs::Lane l; - - for(unsigned int i=0; i < path.size(); i++) - { - autoware_msgs::Waypoint wp; - wp.pose.pose.position.x = path.at(i).pos.x; - wp.pose.pose.position.y = path.at(i).pos.y; - wp.pose.pose.position.z = path.at(i).pos.z; - //wp.pose.pose.position.z = 5; - wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw(UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); - wp.twist.twist.linear.x = path.at(i).v; - wp.twist.twist.linear.y = path.at(i).laneId; - wp.twist.twist.linear.z = path.at(i).stopLineID; - wp.twist.twist.angular.x = path.at(i).laneChangeCost; - wp.twist.twist.angular.y = path.at(i).LeftPointId; - wp.twist.twist.angular.z = path.at(i).RightPointId; - //std::cout << "PathID: " << i << ", LID:" << path.at(i).laneId << ", LeftLaneID: " << path.at(i).LeftLaneId << ", RightLaneID: " << path.at(i).RightLaneId << std::endl; - - for(unsigned int iaction = 0; iaction < path.at(i).actionCost.size(); iaction++) - { - if(path.at(i).actionCost.at(iaction).first == PlannerHNS::RIGHT_TURN_ACTION) - wp.dtlane.dir = 1; - else if(path.at(i).actionCost.at(iaction).first == PlannerHNS::LEFT_TURN_ACTION) - wp.dtlane.dir = 2; - else - wp.dtlane.dir = 0; - } - - - //wp.dtlane.dir = path.at(i).pos.a; - - //PlannerHNS::GPSPoint p = path.at(i).pos; - //std::cout << p.ToString() << std::endl; - - l.waypoints.push_back(wp); - } - - if(l.waypoints.size()>0) - laneArray.lanes.push_back(l); + autoware_msgs::Lane l; + + for (unsigned int i = 0; i < path.size(); i++) + { + autoware_msgs::Waypoint wp; + wp.pose.pose.position.x = path.at(i).pos.x; + wp.pose.pose.position.y = path.at(i).pos.y; + wp.pose.pose.position.z = path.at(i).pos.z; + + wp.pose.pose.orientation = tf::createQuaternionMsgFromYaw( + UtilityHNS::UtilityH::SplitPositiveAngle(path.at(i).pos.a)); + wp.twist.twist.linear.x = path.at(i).v; + wp.twist.twist.linear.y = path.at(i).laneId; + wp.twist.twist.linear.z = path.at(i).stopLineID; + wp.twist.twist.angular.x = path.at(i).laneChangeCost; + wp.twist.twist.angular.y = path.at(i).LeftPointId; + wp.twist.twist.angular.z = path.at(i).RightPointId; + + for (unsigned int iaction = 0; iaction < path.at(i).actionCost.size(); iaction++) + { + if (path.at(i).actionCost.at(iaction).first == PlannerHNS::RIGHT_TURN_ACTION) + { + wp.dtlane.dir = 1; + } + else if (path.at(i).actionCost.at(iaction).first == PlannerHNS::LEFT_TURN_ACTION) + { + wp.dtlane.dir = 2; + } + else + { + wp.dtlane.dir = 0; + } + } + + l.waypoints.push_back(wp); + } + + if (l.waypoints.size() > 0) + { + laneArray.lanes.push_back(l); + } } -void ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, visualization_msgs::MarkerArray& markerArray) +void ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(const PlannerHNS::RoadNetwork& map, + visualization_msgs::MarkerArray& markerArray) { - markerArray.markers.clear(); - autoware_msgs::LaneArray map_lane_array; - for(unsigned int i = 0; i< map.roadSegments.size(); i++) - for(unsigned int j = 0; j < map.roadSegments.at(i).Lanes.size(); j++) - ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(map.roadSegments.at(i).Lanes.at(j).points, map_lane_array); - - std_msgs::ColorRGBA total_color; - total_color.r = 1; - total_color.g = 0.5; - total_color.b = 0.3; - total_color.a = 0.85; - - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "vector_map_center_lines_rviz"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.25; - lane_waypoint_marker.scale.y = 0.25; - lane_waypoint_marker.scale.z = 0.25; - lane_waypoint_marker.color = total_color; - //lane_waypoint_marker.frame_locked = false; - - int count = 0; - for (unsigned int i=0; i< map_lane_array.lanes.size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < map_lane_array.lanes.at(i).waypoints.size(); j++) - { - geometry_msgs::Point point; - point = map_lane_array.lanes.at(i).waypoints.at(j).pose.pose.position; - lane_waypoint_marker.points.push_back(point); - } - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } - - ROSHelpers::createGlobalLaneArrayOrientationMarker(map_lane_array, markerArray); - total_color.r = 0.99; - total_color.g = 0.99; - total_color.b = 0.99; - total_color.a = 0.85; - - visualization_msgs::Marker stop_waypoint_marker; - stop_waypoint_marker.header.frame_id = "map"; - stop_waypoint_marker.header.stamp = ros::Time(); - stop_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - stop_waypoint_marker.action = visualization_msgs::Marker::ADD; - stop_waypoint_marker.scale.x = 0.4; - stop_waypoint_marker.scale.y = 0.4; - stop_waypoint_marker.scale.z = 0.4; - stop_waypoint_marker.color = total_color; - // stop_waypoint_marker.frame_locked = false; - - - for (unsigned int i=0; i< map.stopLines.size(); i++) - { - std::ostringstream ns_id; - ns_id << "stop_lines_rviz_" ; - ns_id << map.stopLines.at(i).id; - stop_waypoint_marker.ns =ns_id.str(); - - autoware_msgs::LaneArray lane_array_2; - ROSHelpers::ConvertFromPlannerHPointsToAutowarePathFormat(map.stopLines.at(i).points, lane_array_2); - - stop_waypoint_marker.points.clear(); - stop_waypoint_marker.id = count; - for (unsigned int j=0; j< lane_array_2.lanes.size(); j++) - { - - - for (unsigned int k=0; k < lane_array_2.lanes.at(j).waypoints.size(); k++) - { - geometry_msgs::Point point; - point = lane_array_2.lanes.at(j).waypoints.at(k).pose.pose.position; - stop_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(stop_waypoint_marker); - count++; - } - } - - - - //ROSHelpers::createGlobalLaneArrayOrientationMarker(map_lane_array, markerArray); + markerArray.markers.clear(); + autoware_msgs::LaneArray map_lane_array; + for (unsigned int i = 0; i < map.roadSegments.size(); i++) + { + for (unsigned int j = 0; j < map.roadSegments.at(i).Lanes.size(); j++) + { + ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(map.roadSegments.at(i).Lanes.at(j).points, map_lane_array); + } + } + + std_msgs::ColorRGBA total_color; + total_color.r = 1; + total_color.g = 0.5; + total_color.b = 0.3; + total_color.a = 0.85; + + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "vector_map_center_lines_rviz"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.25; + lane_waypoint_marker.scale.y = 0.25; + lane_waypoint_marker.scale.z = 0.25; + lane_waypoint_marker.color = total_color; + + int count = 0; + for (unsigned int i = 0; i < map_lane_array.lanes.size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j = 0; j < map_lane_array.lanes.at(i).waypoints.size(); j++) + { + geometry_msgs::Point point; + point = map_lane_array.lanes.at(i).waypoints.at(j).pose.pose.position; + lane_waypoint_marker.points.push_back(point); + } + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } + + ROSHelpers::createGlobalLaneArrayOrientationMarker(map_lane_array, markerArray); + total_color.r = 0.99; + total_color.g = 0.99; + total_color.b = 0.99; + total_color.a = 0.85; + + visualization_msgs::Marker stop_waypoint_marker; + stop_waypoint_marker.header.frame_id = "map"; + stop_waypoint_marker.header.stamp = ros::Time(); + stop_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + stop_waypoint_marker.action = visualization_msgs::Marker::ADD; + stop_waypoint_marker.scale.x = 0.4; + stop_waypoint_marker.scale.y = 0.4; + stop_waypoint_marker.scale.z = 0.4; + stop_waypoint_marker.color = total_color; + + for (unsigned int i = 0; i < map.stopLines.size(); i++) + { + std::ostringstream ns_id; + ns_id << "stop_lines_rviz_"; + ns_id << map.stopLines.at(i).id; + stop_waypoint_marker.ns = ns_id.str(); + + autoware_msgs::LaneArray lane_array_2; + ROSHelpers::ConvertFromPlannerHPointsToAutowarePathFormat(map.stopLines.at(i).points, lane_array_2); + + stop_waypoint_marker.points.clear(); + stop_waypoint_marker.id = count; + for (unsigned int j = 0; j < lane_array_2.lanes.size(); j++) + { + for (unsigned int k = 0; k < lane_array_2.lanes.at(j).waypoints.size(); k++) + { + geometry_msgs::Point point; + point = lane_array_2.lanes.at(j).waypoints.at(k).pose.pose.position; + stop_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(stop_waypoint_marker); + count++; + } + } } void ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector& curr_path, - const std::vector >& paths, - visualization_msgs::MarkerArray& markerArray) + const std::vector >& paths, + visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - std_msgs::ColorRGBA roll_color, total_color, curr_color; - roll_color.r = 0; - roll_color.g = 1; - roll_color.b = 0; - roll_color.a = 0.5; - - lane_waypoint_marker.color = roll_color; - lane_waypoint_marker.frame_locked = false; - - int count = 0; - for (unsigned int i = 0; i < paths.size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < paths.at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = paths.at(i).at(j).pos.x; - point.y = paths.at(i).at(j).pos.y; - point.z = paths.at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - } - - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - lane_waypoint_marker.scale.x = 0.1; - lane_waypoint_marker.scale.y = 0.1; - curr_color.r = 1; - curr_color.g = 0; - curr_color.b = 1; - curr_color.a = 0.9; - lane_waypoint_marker.color = curr_color; - - for (unsigned int j=0; j < curr_path.size(); j++) - { - geometry_msgs::Point point; - - point.x = curr_path.at(j).pos.x; - point.y = curr_path.at(j).pos.y; - point.z = curr_path.at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + std_msgs::ColorRGBA roll_color, total_color, curr_color; + roll_color.r = 0; + roll_color.g = 1; + roll_color.b = 0; + roll_color.a = 0.5; + + lane_waypoint_marker.color = roll_color; + lane_waypoint_marker.frame_locked = false; + + int count = 0; + for (unsigned int i = 0; i < paths.size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j = 0; j < paths.at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = paths.at(i).at(j).pos.x; + point.y = paths.at(i).at(j).pos.y; + point.z = paths.at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } + + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + lane_waypoint_marker.scale.x = 0.1; + lane_waypoint_marker.scale.y = 0.1; + curr_color.r = 1; + curr_color.g = 0; + curr_color.b = 1; + curr_color.a = 0.9; + lane_waypoint_marker.color = curr_color; + + for (unsigned int j=0; j < curr_path.size(); j++) + { + geometry_msgs::Point point; + + point.x = curr_path.at(j).pos.x; + point.y = curr_path.at(j).pos.y; + point.z = curr_path.at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; } -void ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(const std::vector >& globalPaths, - visualization_msgs::MarkerArray& markerArray) +void ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat( + const std::vector >& globalPaths, + visualization_msgs::MarkerArray& markerArray) { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.ns = "global_lane_array_marker"; - lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - - - std_msgs::ColorRGBA roll_color, total_color, curr_color; - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = 1; - lane_waypoint_marker.scale.x = 0.35; - lane_waypoint_marker.scale.y = 0.35; - total_color.r = 1; - total_color.g = 0; - total_color.b = 0; - total_color.a = 0.5; - lane_waypoint_marker.color = total_color; - lane_waypoint_marker.frame_locked = false; - - int count = 0; - for (unsigned int i = 0; i < globalPaths.size(); i++) - { - lane_waypoint_marker.points.clear(); - lane_waypoint_marker.id = count; - - for (unsigned int j=0; j < globalPaths.at(i).size(); j++) - { - geometry_msgs::Point point; - - point.x = globalPaths.at(i).at(j).pos.x; - point.y = globalPaths.at(i).at(j).pos.y; - point.z = globalPaths.at(i).at(j).pos.z; - - lane_waypoint_marker.points.push_back(point); - } - - markerArray.markers.push_back(lane_waypoint_marker); - count++; - -// visualization_msgs::MarkerArray tmp_marker_array; -// visualization_msgs::Marker dir_marker; -// dir_marker.header.frame_id = "map"; -// dir_marker.header.stamp = ros::Time(); -// dir_marker.type = visualization_msgs::Marker::ARROW; -// dir_marker.action = visualization_msgs::Marker::ADD; -// dir_marker.scale.x = 0.5; -// dir_marker.scale.y = 0.1; -// dir_marker.scale.z = 0.1; -// dir_marker.color.r = 1.0; -// dir_marker.color.a = 1.0; -// dir_marker.frame_locked = true; -// dir_marker.id = count; -// dir_marker.ns = "direction_marker"; -// -// for (unsigned int j=0; j < globalPaths.at(i).size(); j++) -// { -// geometry_msgs::Point point; -// -// point.x = globalPaths.at(i).at(j).pos.x; -// point.y = globalPaths.at(i).at(j).pos.y; -// point.z = globalPaths.at(i).at(j).pos.z; -// -// dir_marker.pose.position = point; -// dir_marker.pose.orientation = tf::createQuaternionMsgFromYaw(globalPaths.at(i).at(j).pos.a); -// tmp_marker_array.markers.push_back(dir_marker); -// } -// -// markerArray.markers.insert(markerArray.markers.end(), tmp_marker_array.markers.begin(), -// tmp_marker_array.markers.end()); -// count++; - - - } + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.ns = "global_lane_array_marker"; + lane_waypoint_marker.type = visualization_msgs::Marker::LINE_STRIP; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + + + std_msgs::ColorRGBA roll_color, total_color, curr_color; + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = 1; + lane_waypoint_marker.scale.x = 0.35; + lane_waypoint_marker.scale.y = 0.35; + total_color.r = 1; + total_color.g = 0; + total_color.b = 0; + total_color.a = 0.5; + lane_waypoint_marker.color = total_color; + lane_waypoint_marker.frame_locked = false; + + int count = 0; + for (unsigned int i = 0; i < globalPaths.size(); i++) + { + lane_waypoint_marker.points.clear(); + lane_waypoint_marker.id = count; + + for (unsigned int j = 0; j < globalPaths.at(i).size(); j++) + { + geometry_msgs::Point point; + + point.x = globalPaths.at(i).at(j).pos.x; + point.y = globalPaths.at(i).at(j).pos.y; + point.z = globalPaths.at(i).at(j).pos.z; + + lane_waypoint_marker.points.push_back(point); + } + + markerArray.markers.push_back(lane_waypoint_marker); + count++; + } } void ROSHelpers::createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, - const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray) + const autoware_msgs::LaneArray &lane_waypoints_array, visualization_msgs::MarkerArray& markerArray) { visualization_msgs::Marker lane_waypoint_marker; lane_waypoint_marker.header.frame_id = "map"; @@ -360,12 +349,12 @@ void ROSHelpers::createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, lane_waypoint_marker.frame_locked = false; int count = 0; - for (unsigned int i=0; i< lane_waypoints_array.lanes.size(); i++) + for (unsigned int i = 0; i < lane_waypoints_array.lanes.size(); i++) { lane_waypoint_marker.points.clear(); lane_waypoint_marker.id = count; - for (unsigned int j=0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) + for (unsigned int j = 0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) { geometry_msgs::Point point; point = lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose.position; @@ -374,11 +363,10 @@ void ROSHelpers::createGlobalLaneArrayMarker(std_msgs::ColorRGBA color, markerArray.markers.push_back(lane_waypoint_marker); count++; } - } -void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray) +void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneArray &lane_waypoints_array, + visualization_msgs::MarkerArray& markerArray) { visualization_msgs::MarkerArray tmp_marker_array; // display by markers the velocity of each waypoint. @@ -387,7 +375,7 @@ void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneAr velocity_marker.header.stamp = ros::Time(); velocity_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING; velocity_marker.action = visualization_msgs::Marker::ADD; - //velocity_marker.scale.z = 0.4; + velocity_marker.color.a = 0.9; velocity_marker.color.r = 1; velocity_marker.color.g = 1; @@ -395,26 +383,25 @@ void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneAr velocity_marker.frame_locked = false; int count = 1; - for (unsigned int i=0; i< lane_waypoints_array.lanes.size(); i++) + for (unsigned int i = 0; i < lane_waypoints_array.lanes.size(); i++) { - - std::ostringstream str_count; - str_count << count; + std::ostringstream str_count; + str_count << count; velocity_marker.ns = "global_velocity_lane_" + str_count.str(); - for (unsigned int j=0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) + for (unsigned int j = 0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) { - //std::cout << _waypoints[i].GetX() << " " << _waypoints[i].GetY() << " " << _waypoints[i].GetZ() << " " << _waypoints[i].GetVelocity_kmh() << std::endl; velocity_marker.id = j; geometry_msgs::Point relative_p; relative_p.y = 0.5; - velocity_marker.pose.position = calcAbsoluteCoordinate(relative_p, lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose); + velocity_marker.pose.position = calcAbsoluteCoordinate(relative_p, + lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose); velocity_marker.pose.position.z += 0.2; // double to string std::ostringstream str_out; str_out << lane_waypoints_array.lanes.at(i).waypoints.at(j).twist.twist.linear.x; - //std::string vel = str_out.str(); - velocity_marker.text = str_out.str();//vel.erase(vel.find_first_of(".") + 2); + + velocity_marker.text = str_out.str(); tmp_marker_array.markers.push_back(velocity_marker); } @@ -422,11 +409,11 @@ void ROSHelpers::createGlobalLaneArrayVelocityMarker(const autoware_msgs::LaneAr } markerArray.markers.insert(markerArray.markers.end(), tmp_marker_array.markers.begin(), - tmp_marker_array.markers.end()); + tmp_marker_array.markers.end()); } -void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array - , visualization_msgs::MarkerArray& markerArray) +void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::LaneArray &lane_waypoints_array, + visualization_msgs::MarkerArray& markerArray) { visualization_msgs::MarkerArray tmp_marker_array; visualization_msgs::Marker lane_waypoint_marker; @@ -439,91 +426,91 @@ void ROSHelpers::createGlobalLaneArrayOrientationMarker(const autoware_msgs::Lan lane_waypoint_marker.scale.z = 0.1; lane_waypoint_marker.color.r = 1.0; lane_waypoint_marker.color.a = 0.8; - //lane_waypoint_marker.frame_locked = false; lane_waypoint_marker.ns = "global_lane_waypoint_orientation_marker"; int count = 1; - for (unsigned int i=0; i< lane_waypoints_array.lanes.size(); i++) + for (unsigned int i = 0; i < lane_waypoints_array.lanes.size(); i++) { -// std::ostringstream str_ns; -// str_ns << "global_lane_waypoint_orientation_marker_"; -// str_ns << i; -// lane_waypoint_marker.ns = str_ns.str(); - - for (unsigned int j=0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) + for (unsigned int j = 0; j < lane_waypoints_array.lanes.at(i).waypoints.size(); j++) { - lane_waypoint_marker.id = count; - lane_waypoint_marker.pose = lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose; - - if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 1) - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 1.0; - lane_waypoint_marker.color.b = 0.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - else if(lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 2) - { - lane_waypoint_marker.color.r = 0.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 1.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } - else - { - lane_waypoint_marker.color.r = 1.0; - lane_waypoint_marker.color.g = 0.0; - lane_waypoint_marker.color.b = 1.0; - tmp_marker_array.markers.push_back(lane_waypoint_marker); - } + lane_waypoint_marker.id = count; + lane_waypoint_marker.pose = lane_waypoints_array.lanes.at(i).waypoints.at(j).pose.pose; + + if (lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 1) + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 1.0; + lane_waypoint_marker.color.b = 0.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + else if (lane_waypoints_array.lanes.at(i).waypoints.at(j).dtlane.dir == 2) + { + lane_waypoint_marker.color.r = 0.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 1.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } + else + { + lane_waypoint_marker.color.r = 1.0; + lane_waypoint_marker.color.g = 0.0; + lane_waypoint_marker.color.b = 1.0; + tmp_marker_array.markers.push_back(lane_waypoint_marker); + } count++; } } markerArray.markers.insert(markerArray.markers.end(), tmp_marker_array.markers.begin(), - tmp_marker_array.markers.end()); + tmp_marker_array.markers.end()); } -void ROSHelpers::FindIncommingBranches(const std::vector >& globalPaths, const PlannerHNS::WayPoint& currPose,const double& min_distance, - std::vector& branches, PlannerHNS::WayPoint* currOptions) +void ROSHelpers::FindIncommingBranches(const std::vector>& globalPaths, + const PlannerHNS::WayPoint& currPose, const double& min_distance, + std::vector& branches, PlannerHNS::WayPoint* currOptions) { - static int detection_range = 30; // meter - if(globalPaths.size() > 0) - { - int close_index = PlannerHNS::PlanningHelpers::GetClosestNextPointIndex_obsolete(globalPaths.at(0), currPose); - PlannerHNS::WayPoint closest_wp = globalPaths.at(0).at(close_index); - double d = 0; - for(unsigned int i=close_index+1; i < globalPaths.at(0).size(); i++) - { - d += hypot(globalPaths.at(0).at(i).pos.y - globalPaths.at(0).at(i-1).pos.y, globalPaths.at(0).at(i).pos.x - globalPaths.at(0).at(i-1).pos.x); - - if(d - min_distance > detection_range) - break; - - if(d > min_distance && globalPaths.at(0).at(i).pFronts.size() > 1) - { - for(unsigned int j = 0; j< globalPaths.at(0).at(i).pFronts.size(); j++) - { - PlannerHNS::WayPoint* wp = globalPaths.at(0).at(i).pFronts.at(j); - - - bool bFound = false; - for(unsigned int ib=0; ib< branches.size(); ib++) - { - if(wp->actionCost.size() > 0 && branches.at(ib)->actionCost.size() > 0 && branches.at(ib)->actionCost.at(0).first == wp->actionCost.at(0).first) - { - bFound = true; - break; - } - } - - if(wp->actionCost.size() > 0 && !bFound && closest_wp.laneId != wp->laneId) - branches.push_back(wp); - } - } - } - } + static int detection_range = 30; // meter + if (globalPaths.size() > 0) + { + int close_index = PlannerHNS::PlanningHelpers::GetClosestNextPointIndex_obsolete(globalPaths.at(0), currPose); + PlannerHNS::WayPoint closest_wp = globalPaths.at(0).at(close_index); + double d = 0; + for (unsigned int i = close_index + 1; i < globalPaths.at(0).size(); i++) + { + d += hypot(globalPaths.at(0).at(i).pos.y - globalPaths.at(0).at(i-1).pos.y, + globalPaths.at(0).at(i).pos.x - globalPaths.at(0).at(i-1).pos.x); + + if (d - min_distance > detection_range) + { + break; + } + + if ((d > min_distance) && (globalPaths.at(0).at(i).pFronts.size() > 1)) + { + for (unsigned int j = 0; j < globalPaths.at(0).at(i).pFronts.size(); j++) + { + PlannerHNS::WayPoint* wp = globalPaths.at(0).at(i).pFronts.at(j); + + bool bFound = false; + for (unsigned int ib = 0; ib < branches.size(); ib++) + { + if ((wp->actionCost.size() > 0) && (branches.at(ib)->actionCost.size() > 0) + && (branches.at(ib)->actionCost.at(0).first == wp->actionCost.at(0).first)) + { + bFound = true; + break; + } + } + + if (wp->actionCost.size() > 0 && !bFound && closest_wp.laneId != wp->laneId) + { + branches.push_back(wp); + } + } + } + } + } } -} +} // namespace WayPlannerNS diff --git a/core_planning/way_planner/nodes/SocketServer.cpp b/core_planning/way_planner/nodes/SocketServer.cpp index 0da3063e04c..11be04fdc56 100644 --- a/core_planning/way_planner/nodes/SocketServer.cpp +++ b/core_planning/way_planner/nodes/SocketServer.cpp @@ -1,3 +1,19 @@ +/* + * Copyright 2017-2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + /* * SocketServer.cpp * @@ -6,267 +22,275 @@ */ #include "SocketServer.h" +#include namespace WayPlannerNS { + HMISocketServer::HMISocketServer() { - m_ConnPortSend = 10001; - m_ConnPortReceive = 10002; - m_Socket_send = 0; - m_Socket_receive = 0; - sock_mutex_send = PTHREAD_MUTEX_INITIALIZER; - sock_mutex_receive = PTHREAD_MUTEX_INITIALIZER; - sock_thread_tid_send = 0; - sock_thread_tid_receive = 0; - m_bLatestMsg_send = false; - m_bLatestMsg_receive = false; - m_bExitMainLoop = false; + m_ConnPortSend = 10001; + m_ConnPortReceive = 10002; + m_Socket_send = 0; + m_Socket_receive = 0; + sock_mutex_send = PTHREAD_MUTEX_INITIALIZER; + sock_mutex_receive = PTHREAD_MUTEX_INITIALIZER; + sock_thread_tid_send = 0; + sock_thread_tid_receive = 0; + m_bLatestMsg_send = false; + m_bLatestMsg_receive = false; + m_bExitMainLoop = false; } HMISocketServer::~HMISocketServer() { - std::cout << " >> Call The Constructor !!!!! " << std::endl; - HMISocketServer* pRet; - - shutdown(m_Socket_send, SHUT_RDWR); - close(m_Socket_send); + std::cout << " >> Call The Constructor !!!!! " << std::endl; + HMISocketServer* pRet; - shutdown(m_Socket_receive, SHUT_RDWR); - close(m_Socket_receive); + shutdown(m_Socket_send, SHUT_RDWR); + close(m_Socket_send); - m_bExitMainLoop = true; - if(sock_thread_tid_send>0) - pthread_join(sock_thread_tid_send, (void**)&pRet); + shutdown(m_Socket_receive, SHUT_RDWR); + close(m_Socket_receive); - if(sock_thread_tid_receive>0) - pthread_join(sock_thread_tid_receive, (void**)&pRet); + m_bExitMainLoop = true; + if (sock_thread_tid_send > 0) + { + pthread_join(sock_thread_tid_send, reinterpret_cast(&pRet)); + } - std::cout << " >> Destroy everything !!!!! " << std::endl; + if (sock_thread_tid_receive > 0) + { + pthread_join(sock_thread_tid_receive, reinterpret_cast(&pRet)); + } + std::cout << " >> Destroy everything !!!!! " << std::endl; } int HMISocketServer::InitSocket(int port_send, int port_receive) { - if(port_send > 0) - m_ConnPortSend = port_send; - if(port_receive > 0) - m_ConnPortReceive = port_receive; - - // Step 1: Creat Socket - m_Socket_send = socket(AF_INET, SOCK_STREAM, 0); - if(m_Socket_send == -1){ - std::perror("socket"); - return -1; - } - - sockaddr_in addr; - - std::memset(&addr, 0, sizeof(sockaddr_in)); - addr.sin_family = PF_INET; - addr.sin_port = htons(m_ConnPortSend); - addr.sin_addr.s_addr = INADDR_ANY; - - int ret = bind(m_Socket_send, (struct sockaddr *)&addr, sizeof(addr)); - if(ret == -1) - { - std::perror("bind"); - return -1; - } - - ret = listen(m_Socket_send, 5); - if(ret == -1) - { - std::perror("listen"); - return -1; - } - - if(pthread_create(&sock_thread_tid_send, nullptr,&HMISocketServer::ThreadMainSend , this) != 0) - { - std::perror("pthread_create"); - } - - - m_Socket_receive = socket(AF_INET, SOCK_STREAM, 0); - if(m_Socket_receive == -1){ - std::perror("socket"); - return -1; - } - - sockaddr_in addr_receive; - - std::memset(&addr_receive, 0, sizeof(sockaddr_in)); - addr_receive.sin_family = PF_INET; - addr_receive.sin_port = htons(m_ConnPortReceive); - addr_receive.sin_addr.s_addr = INADDR_ANY; - - int ret_r = bind(m_Socket_receive, (struct sockaddr *)&addr_receive, sizeof(addr_receive)); - if(ret_r == -1) - { - std::perror("bind"); - return -1; - } - - ret = listen(m_Socket_receive, 5); - if(ret == -1) - { - std::perror("listen"); - return -1; - } - - if(pthread_create(&sock_thread_tid_receive, nullptr,&HMISocketServer::ThreadMainReceive , this) != 0) - { - std::perror("pthread_create"); - } - - return 1; + if (port_send > 0) + { + m_ConnPortSend = port_send; + } + if (port_receive > 0) + { + m_ConnPortReceive = port_receive; + } + + // Step 1: Creat Socket + m_Socket_send = socket(AF_INET, SOCK_STREAM, 0); + if (m_Socket_send == -1) + { + std::perror("socket"); + return -1; + } + + sockaddr_in addr; + + std::memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = PF_INET; + addr.sin_port = htons(m_ConnPortSend); + addr.sin_addr.s_addr = INADDR_ANY; + + int ret = bind(m_Socket_send, (struct sockaddr *)&addr, sizeof(addr)); + if (ret == -1) + { + std::perror("bind"); + return -1; + } + + ret = listen(m_Socket_send, 5); + if (ret == -1) + { + std::perror("listen"); + return -1; + } + + if (pthread_create(&sock_thread_tid_send, nullptr, &HMISocketServer::ThreadMainSend, this) != 0) + { + std::perror("pthread_create"); + } + + m_Socket_receive = socket(AF_INET, SOCK_STREAM, 0); + if (m_Socket_receive == -1) + { + std::perror("socket"); + return -1; + } + + sockaddr_in addr_receive; + + std::memset(&addr_receive, 0, sizeof(sockaddr_in)); + addr_receive.sin_family = PF_INET; + addr_receive.sin_port = htons(m_ConnPortReceive); + addr_receive.sin_addr.s_addr = INADDR_ANY; + + int ret_r = bind(m_Socket_receive, (struct sockaddr *)&addr_receive, sizeof(addr_receive)); + if (ret_r == -1) + { + std::perror("bind"); + return -1; + } + + ret = listen(m_Socket_receive, 5); + if (ret == -1) + { + std::perror("listen"); + return -1; + } + + if (pthread_create(&sock_thread_tid_receive, nullptr, &HMISocketServer::ThreadMainReceive, this) != 0) + { + std::perror("pthread_create"); + } + + return 1; } void* HMISocketServer::ThreadMainSend(void* pSock) { - HMISocketServer* pS = (HMISocketServer*)pSock; - - while(!pS->m_bExitMainLoop) - { - pthread_mutex_lock(&pS->sock_mutex_send); - HMI_MSG msg = pS->m_msg_send; - if(!pS->m_bLatestMsg_send) - msg.options.clear(); - pS->m_bLatestMsg_send = false; - pthread_mutex_unlock(&pS->sock_mutex_send); - - - - //std::cout << "Waiting access..." << std::endl; - - int client_sock = 0; - sockaddr_in client; - socklen_t len = sizeof(client); - - client_sock = accept(pS->m_Socket_send, reinterpret_cast(&client), &len); - if(client_sock == -1){ - std::perror("accept"); - usleep(500); - continue; - } - - std::ostringstream oss; - oss << msg.type << ","; - for(unsigned int i=0; i< msg.options.size(); i++) - oss << msg.options.at(i) << ";"; - - oss << "," << msg.current; - oss << "," << msg.currID; - oss << "," << msg.bErr ; - oss << "," << msg.err_msg << ","; - - std::string cmd(oss.str()); - ssize_t n = write(client_sock, cmd.c_str(), cmd.size()); - if(n < 0){ - std::perror("write"); - usleep(500); - continue; - } - - shutdown(client_sock, SHUT_RDWR); - if(close(client_sock) == -1){ - std::perror("close"); - usleep(500); - continue; - } - - std::cout << "cmd: " << cmd << ", size: " << cmd.size() << std::endl; - - } - return 0; + HMISocketServer* pS = reinterpret_cast(pSock); + + while (!pS->m_bExitMainLoop) + { + pthread_mutex_lock(&pS->sock_mutex_send); + HMI_MSG msg = pS->m_msg_send; + if (!pS->m_bLatestMsg_send) + { + msg.options.clear(); + } + pS->m_bLatestMsg_send = false; + pthread_mutex_unlock(&pS->sock_mutex_send); + + int client_sock = 0; + sockaddr_in client; + socklen_t len = sizeof(client); + + client_sock = accept(pS->m_Socket_send, reinterpret_cast(&client), &len); + if (client_sock == -1) + { + std::perror("accept"); + usleep(500); + continue; + } + + std::ostringstream oss; + oss << msg.type << ","; + for (unsigned int i = 0; i < msg.options.size(); i++) + { + oss << msg.options.at(i) << ";"; + } + + oss << "," << msg.current; + oss << "," << msg.currID; + oss << "," << msg.bErr; + oss << "," << msg.err_msg << ","; + + std::string cmd(oss.str()); + ssize_t n = write(client_sock, cmd.c_str(), cmd.size()); + if (n < 0) + { + std::perror("write"); + usleep(500); + continue; + } + + shutdown(client_sock, SHUT_RDWR); + if (close(client_sock) == -1) + { + std::perror("close"); + usleep(500); + continue; + } + + std::cout << "cmd: " << cmd << ", size: " << cmd.size() << std::endl; + } + + return 0; } void* HMISocketServer::ThreadMainReceive(void* pSock) { - HMISocketServer* pS = (HMISocketServer*)pSock; - - while(!pS->m_bExitMainLoop) - { - //std::cout << "Waiting access..." << std::endl; - - int client_sock = 0; - sockaddr_in client; - socklen_t len = sizeof(client); - - - client_sock = accept(pS->m_Socket_receive, reinterpret_cast(&client), &len); - if(client_sock == -1){ - std::perror("accept"); - usleep(500); - continue; - } - - char recvdata[1024]; - std::string can_data(""); - ssize_t nr = 0; - while(true){ - nr = recv(client_sock, recvdata, sizeof(recvdata), 0); - - if(nr<0){ - std::perror("recv"); - can_data = ""; - break; - }else if(nr == 0){ - break; - } - - can_data.append(recvdata,nr); - } - - //std::cout << "Command Recieved >> " << can_data << std::endl; - - shutdown(client_sock, SHUT_RDWR); - - if(close(client_sock)<0) - { - std::perror("close"); - usleep(500); - continue; - } - - if(can_data.size() > 0) - { - pthread_mutex_lock(&pS->sock_mutex_receive); - pS->m_bLatestMsg_receive = true; - pS->m_msg_receive = HMI_MSG::FromString(can_data); - //std::cout << "Command Recieved >> " << can_data << std::endl; - pthread_mutex_unlock(&pS->sock_mutex_receive); - } - - - } - return 0; + HMISocketServer* pS = reinterpret_cast(pSock); + + while (!pS->m_bExitMainLoop) + { + int client_sock = 0; + sockaddr_in client; + socklen_t len = sizeof(client); + + client_sock = accept(pS->m_Socket_receive, reinterpret_cast(&client), &len); + if (client_sock == -1) + { + std::perror("accept"); + usleep(500); + continue; + } + + char recvdata[1024]; + std::string can_data(""); + ssize_t nr = 0; + while (true) + { + nr = recv(client_sock, recvdata, sizeof(recvdata), 0); + + if (nr < 0) + { + std::perror("recv"); + can_data = ""; + break; + } + else if (nr == 0) + { + break; + } + + can_data.append(recvdata, nr); + } + + shutdown(client_sock, SHUT_RDWR); + + if (close(client_sock) < 0) + { + std::perror("close"); + usleep(500); + continue; + } + + if (can_data.size() > 0) + { + pthread_mutex_lock(&pS->sock_mutex_receive); + pS->m_bLatestMsg_receive = true; + pS->m_msg_receive = HMI_MSG::FromString(can_data); + pthread_mutex_unlock(&pS->sock_mutex_receive); + } + } + + return 0; } void HMISocketServer::SendMSG(HMI_MSG msg) { - pthread_mutex_lock(&sock_mutex_send); - m_bLatestMsg_send = true; - m_msg_send = msg; - pthread_mutex_unlock(&sock_mutex_send); + pthread_mutex_lock(&sock_mutex_send); + m_bLatestMsg_send = true; + m_msg_send = msg; + pthread_mutex_unlock(&sock_mutex_send); } int HMISocketServer::GetLatestMSG(HMI_MSG& msg) { - int res = -1; - pthread_mutex_lock(&sock_mutex_receive); - if(m_bLatestMsg_receive) - { - msg = m_msg_receive; - m_bLatestMsg_receive = false; - res = 1; - } - pthread_mutex_unlock(&sock_mutex_receive); - - return res; -} - + int res = -1; + pthread_mutex_lock(&sock_mutex_receive); + if (m_bLatestMsg_receive) + { + msg = m_msg_receive; + m_bLatestMsg_receive = false; + res = 1; + } + pthread_mutex_unlock(&sock_mutex_receive); + + return res; } - - +} // namespace WayPlannerNS diff --git a/core_planning/way_planner/nodes/way_planner.cpp b/core_planning/way_planner/nodes/way_planner.cpp index 5f2f3626f8a..2fa63f10136 100644 --- a/core_planning/way_planner/nodes/way_planner.cpp +++ b/core_planning/way_planner/nodes/way_planner.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2016-2019 Autoware Foundation. All rights reserved. + * Copyright 2016-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -24,12 +24,12 @@ */ #include -#include "way_planner_core.h" +#include int main(int argc, char **argv) { - ros::init(argc, argv, "way_planner"); - WayPlannerNS::way_planner_core global_planner; - global_planner.PlannerMainLoop(); - return 0; + ros::init(argc, argv, "way_planner"); + WayPlannerNS::way_planner_core global_planner; + global_planner.PlannerMainLoop(); + return 0; } diff --git a/core_planning/way_planner/nodes/way_planner_core.cpp b/core_planning/way_planner/nodes/way_planner_core.cpp index 5a2062e2def..71a76157abe 100644 --- a/core_planning/way_planner/nodes/way_planner_core.cpp +++ b/core_planning/way_planner/nodes/way_planner_core.cpp @@ -1,5 +1,5 @@ /* - * Copyright 2016-2019 Autoware Foundation. All rights reserved. + * Copyright 2016-2020 Autoware Foundation. All rights reserved. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -14,798 +14,832 @@ * limitations under the License. */ -#include "way_planner_core.h" +#include +#include +#include -namespace WayPlannerNS { +namespace WayPlannerNS +{ -void way_planner_core::GetTransformFromTF(const std::string parent_frame, const std::string child_frame, tf::StampedTransform &transform) +void way_planner_core::GetTransformFromTF(const std::string parent_frame, const std::string child_frame, + tf::StampedTransform &transform) { - static tf::TransformListener listener; - - int nFailedCounter = 0; - while (1) - { - try - { - listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); - break; - } - catch (tf::TransformException& ex) - { - if(nFailedCounter > 2) - { - ROS_ERROR("%s", ex.what()); - } - ros::Duration(1.0).sleep(); - nFailedCounter ++; - } - } + static tf::TransformListener listener; + + int nFailedCounter = 0; + while (1) + { + try + { + listener.lookupTransform(parent_frame, child_frame, ros::Time(0), transform); + break; + } + catch (tf::TransformException& ex) + { + if (nFailedCounter > 2) + { + ROS_ERROR("%s", ex.what()); + } + ros::Duration(1.0).sleep(); + nFailedCounter++; + } + } } way_planner_core::way_planner_core() { - m_pCurrGoal = 0; - m_iCurrentGoalIndex = 1; - m_bKmlMap = false; - //bStartPos = false; - //bGoalPos = false; - //bUsingCurrentPose = false; - nh.getParam("/way_planner/pathDensity" , m_params.pathDensity); - nh.getParam("/way_planner/enableSmoothing" , m_params.bEnableSmoothing); - nh.getParam("/way_planner/enableLaneChange" , m_params.bEnableLaneChange); - nh.getParam("/way_planner/enableRvizInput" , m_params.bEnableRvizInput); - nh.getParam("/way_planner/enableReplan" , m_params.bEnableReplanning); - nh.getParam("/way_planner/enableHMI" , m_params.bEnableHMI); - - int iSource = 0; - nh.getParam("/way_planner/mapSource" , iSource); - if(iSource == 0) - m_params.mapSource = MAP_AUTOWARE; - else if (iSource == 1) - m_params.mapSource = MAP_FOLDER; - else if(iSource == 2) - m_params.mapSource = MAP_KML_FILE; - - nh.getParam("/way_planner/mapFileName" , m_params.KmlMapPath); - - - tf::StampedTransform transform; - GetTransformFromTF("map", "world", transform); - m_OriginPos.position.x = transform.getOrigin().x(); - m_OriginPos.position.y = transform.getOrigin().y(); - m_OriginPos.position.z = transform.getOrigin().z(); - - pub_Paths = nh.advertise("lane_waypoints_array", 1, true); - pub_PathsRviz = nh.advertise("global_waypoints_rviz", 1, true); - pub_StartPointRviz = nh.advertise("Global_StartPoint_rviz", 1, true); - pub_GoalPointRviz = nh.advertise("Global_GoalPoints_rviz", 1, true); - pub_NodesListRviz = nh.advertise("Goal_Nodes_Points_rviz", 1, true); - pub_MapRviz = nh.advertise("vector_map_center_lines_rviz", 100, true); - pub_TrafficInfoRviz = nh.advertise("Traffic_Lights_rviz", 1, true); + m_pCurrGoal = 0; + m_iCurrentGoalIndex = 1; + m_bKmlMap = false; + nh.getParam("/way_planner/pathDensity", m_params.pathDensity); + nh.getParam("/way_planner/enableSmoothing", m_params.bEnableSmoothing); + nh.getParam("/way_planner/enableLaneChange", m_params.bEnableLaneChange); + nh.getParam("/way_planner/enableRvizInput", m_params.bEnableRvizInput); + nh.getParam("/way_planner/enableReplan", m_params.bEnableReplanning); + nh.getParam("/way_planner/enableHMI", m_params.bEnableHMI); + nh.getParam("/way_planner/fallbackMinGoalDistanceTh", m_params.fallbackMinGoalDistanceTh); + nh.getParam("/way_planner/planningMaxAttempt", m_params.planningMaxAttempt); + + // The planning max attempt feature parameter cannot be below zero + if (m_params.planningMaxAttempt < 0) + { + m_params.planningMaxAttempt = 0; + } + + // The fallback min goal distance threshold feature parameter cannot be below zero + if (m_params.fallbackMinGoalDistanceTh < 0) + { + m_params.fallbackMinGoalDistanceTh = 0; + } + + int iSource = 0; + nh.getParam("/way_planner/mapSource", iSource); + if (iSource == 0) + { + m_params.mapSource = MAP_AUTOWARE; + } + else if (iSource == 1) + { + m_params.mapSource = MAP_FOLDER; + } + else if (iSource == 2) + { + m_params.mapSource = MAP_KML_FILE; + } + + nh.getParam("/way_planner/mapFileName", m_params.KmlMapPath); + + + tf::StampedTransform transform; + GetTransformFromTF("map", "world", transform); + m_OriginPos.position.x = transform.getOrigin().x(); + m_OriginPos.position.y = transform.getOrigin().y(); + m_OriginPos.position.z = transform.getOrigin().z(); + + pub_Paths = nh.advertise("lane_waypoints_array", 1, true); + pub_PathsRviz = nh.advertise("global_waypoints_rviz", 1, true); + pub_StartPointRviz = nh.advertise("Global_StartPoint_rviz", 1, true); + pub_GoalPointRviz = nh.advertise("Global_GoalPoints_rviz", 1, true); + pub_NodesListRviz = nh.advertise("Goal_Nodes_Points_rviz", 1, true); + pub_MapRviz = nh.advertise("vector_map_center_lines_rviz", 100, true); + pub_TrafficInfoRviz = nh.advertise("Traffic_Lights_rviz", 1, true); #ifdef ENABLE_VISUALIZE_PLAN - m_CurrMaxCost = 1; - m_iCurrLevel = 0; - m_nLevelSize = 1; - m_bSwitch = 0; - pub_GlobalPlanAnimationRviz = nh.advertise("AnimateGlobalPlan", 1, true); + m_CurrMaxCost = 1; + m_iCurrLevel = 0; + m_nLevelSize = 1; + m_bSwitch = 0; + pub_GlobalPlanAnimationRviz = nh.advertise("AnimateGlobalPlan", 1, true); #endif -if(m_params.bEnableHMI) -{ - m_AvgResponseTime = 0; - m_SocketServer.InitSocket(10001, 10002); + if (m_params.bEnableHMI) + { + m_AvgResponseTime = 0; + m_SocketServer.InitSocket(10001, 10002); + } + + /** @todo To achieve perfection, you need to start sometime */ + + sub_start_pose = nh.subscribe("/initialpose", 1, &way_planner_core::callbackGetStartPose, this); + sub_goal_pose = nh.subscribe("move_base_simple/goal", 1, &way_planner_core::callbackGetGoalPose, this); + + sub_current_pose = nh.subscribe("/current_pose", 100, &way_planner_core::callbackGetCurrentPose, this); + + int bVelSource = 1; + nh.getParam("/dp_planner/enableOdometryStatus", bVelSource); + if (bVelSource == 0) + { + sub_robot_odom = nh.subscribe("/odom", 100, &way_planner_core::callbackGetRobotOdom, this); + } + else if (bVelSource == 1) + { + sub_current_velocity = nh.subscribe("/current_velocity", 100, &way_planner_core::callbackGetVehicleStatus, this); + } + else if (bVelSource == 2) + { + sub_can_info = nh.subscribe("/can_info", 100, &way_planner_core::callbackGetCANInfo, this); + } + + sub_nodes_list = nh.subscribe("/GlobalNodesList", 1, &way_planner_core::callbackGetNodesList, this); + + if (m_params.mapSource == MAP_AUTOWARE) + { + sub_map_points = nh.subscribe("/vector_map_info/point", 1, &way_planner_core::callbackGetVMPoints, this); + sub_map_lanes = nh.subscribe("/vector_map_info/lane", 1, &way_planner_core::callbackGetVMLanes, this); + sub_map_nodes = nh.subscribe("/vector_map_info/node", 1, &way_planner_core::callbackGetVMNodes, this); + sup_stop_lines = nh.subscribe("/vector_map_info/stop_line", 1, &way_planner_core::callbackGetVMStopLines, this); + sub_dtlanes = nh.subscribe("/vector_map_info/dtlane", 1, &way_planner_core::callbackGetVMCenterLines, this); + } } - /** @todo To achieve perfection , you need to start sometime */ - - //if(m_params.bEnableRvizInput) - { - sub_start_pose = nh.subscribe("/initialpose", 1, &way_planner_core::callbackGetStartPose, this); - sub_goal_pose = nh.subscribe("move_base_simple/goal", 1, &way_planner_core::callbackGetGoalPose, this); - } -// else -// { -// sub_start_pose = nh.subscribe("/GlobalStartPose", 1, &way_planner_core::callbackGetStartPose, this); -// sub_goal_pose = nh.subscribe("/GlobalGoalPose", 1, &way_planner_core::callbackGetGoalPose, this); -// } - - sub_current_pose = nh.subscribe("/current_pose", 100, &way_planner_core::callbackGetCurrentPose, this); - - int bVelSource = 1; - nh.getParam("/dp_planner/enableOdometryStatus", bVelSource); - if(bVelSource == 0) - sub_robot_odom = nh.subscribe("/odom", 100, &way_planner_core::callbackGetRobotOdom, this); - else if(bVelSource == 1) - sub_current_velocity = nh.subscribe("/current_velocity", 100, &way_planner_core::callbackGetVehicleStatus, this); - else if(bVelSource == 2) - sub_can_info = nh.subscribe("/can_info", 100, &way_planner_core::callbackGetCANInfo, this); - - //sub_current_velocity = nh.subscribe("/current_velocity", 100, &way_planner_core::callbackGetVehicleStatus, this); - sub_nodes_list = nh.subscribe("/GlobalNodesList", 1, &way_planner_core::callbackGetNodesList, this); - - if(m_params.mapSource == MAP_AUTOWARE) - { - sub_map_points = nh.subscribe("/vector_map_info/point", 1, &way_planner_core::callbackGetVMPoints, this); - sub_map_lanes = nh.subscribe("/vector_map_info/lane", 1, &way_planner_core::callbackGetVMLanes, this); - sub_map_nodes = nh.subscribe("/vector_map_info/node", 1, &way_planner_core::callbackGetVMNodes, this); - sup_stop_lines = nh.subscribe("/vector_map_info/stop_line", 1, &way_planner_core::callbackGetVMStopLines, this); - sub_dtlanes = nh.subscribe("/vector_map_info/dtlane", 1, &way_planner_core::callbackGetVMCenterLines, this); - } -} - -way_planner_core::~way_planner_core(){ +way_planner_core::~way_planner_core() +{ } void way_planner_core::callbackGetGoalPose(const geometry_msgs::PoseStampedConstPtr &msg) { - PlannerHNS::WayPoint wp; - wp = PlannerHNS::WayPoint(msg->pose.position.x+m_OriginPos.position.x, msg->pose.position.y+m_OriginPos.position.y, - msg->pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.orientation)); - - if(m_GoalsPos.size()==0) - { - ROS_INFO("Can Not add Goal, Select Start Position Fist !"); - } - else - { - m_GoalsPos.push_back(wp); - ROS_INFO("Received Goal Pose"); - } + PlannerHNS::WayPoint wp; + wp = PlannerHNS::WayPoint(msg->pose.position.x+m_OriginPos.position.x, msg->pose.position.y+m_OriginPos.position.y, + msg->pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.orientation)); + + if (m_GoalsPos.size() == 0) + { + ROS_INFO("Can Not add Goal, Select Start Position Fist !"); + } + else + { + m_GoalsPos.push_back(wp); + ROS_INFO("Received Goal Pose"); + } } void way_planner_core::callbackGetStartPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg) { -// if(m_GeneratedTotalPaths.size()>0) -// { -// PlannerHNS::RelativeInfo info; -// PlannerHNS::WayPoint p1(msg->pose.pose.position.x+m_OriginPos.position.x, msg->pose.pose.position.y+m_OriginPos.position.y, msg->pose.pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.pose.orientation)); -// bool ret = PlannerHNS::PlanningHelpers::GetRelativeInfo(m_GeneratedTotalPaths.at(0), p1, info); -// std::cout << "Perp D: " << info.perp_distance << ", F D: "<< info.to_front_distance << ", B D: " << info.from_back_distance << ", F Index: "<< info.iFront << ", B Index: " << info.iBack << ", Angle: "<< info.angle_diff << std::endl; -// } - - m_CurrentPose = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, msg->pose.pose.position.y+m_OriginPos.position.y, - msg->pose.pose.position.z+m_OriginPos.position.z, tf::getYaw(msg->pose.pose.orientation)); - - if(m_GoalsPos.size() <= 1) - { - m_GoalsPos.clear(); - m_GoalsPos.push_back(m_CurrentPose); - ROS_INFO("Received Start pose"); - } + m_CurrentPose = PlannerHNS::WayPoint(msg->pose.pose.position.x+m_OriginPos.position.x, + msg->pose.pose.position.y+m_OriginPos.position.y, + msg->pose.pose.position.z+m_OriginPos.position.z, + tf::getYaw(msg->pose.pose.orientation)); + + if (m_GoalsPos.size() <= 1) + { + m_GoalsPos.clear(); + m_GoalsPos.push_back(m_CurrentPose); + ROS_INFO("Received Start pose"); + } } void way_planner_core::callbackGetCurrentPose(const geometry_msgs::PoseStampedConstPtr& msg) { - m_CurrentPose = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, - msg->pose.position.z, tf::getYaw(msg->pose.orientation)); - - if(m_GoalsPos.size() <= 1) - { - m_GoalsPos.clear(); - m_GoalsPos.push_back(m_CurrentPose); - } + m_CurrentPose = PlannerHNS::WayPoint(msg->pose.position.x, msg->pose.position.y, + msg->pose.position.z, tf::getYaw(msg->pose.orientation)); + + if (m_GoalsPos.size() <= 1) + { + m_GoalsPos.clear(); + m_GoalsPos.push_back(m_CurrentPose); + } } void way_planner_core::callbackGetRobotOdom(const nav_msgs::OdometryConstPtr& msg) { - m_VehicleState.speed = msg->twist.twist.linear.x; - //m_VehicleState.steer += atan(m_LocalPlanner.m_CarInfo.wheel_base * msg->twist.twist.angular.z/msg->twist.twist.linear.x); - - UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); -// if(msg->vector.z == 0x00) -// m_VehicleState.shift = AW_SHIFT_POS_BB; -// else if(msg->vector.z == 0x10) -// m_VehicleState.shift = AW_SHIFT_POS_DD; -// else if(msg->vector.z == 0x20) -// m_VehicleState.shift = AW_SHIFT_POS_NN; -// else if(msg->vector.z == 0x40) -// m_VehicleState.shift = AW_SHIFT_POS_RR; - - //std::cout << "PlannerX: Read Odometry ("<< m_VehicleState.speed << ", " << m_VehicleState.steer<<")" << std::endl; + m_VehicleState.speed = msg->twist.twist.linear.x; + + UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); } void way_planner_core::callbackGetVehicleStatus(const geometry_msgs::TwistStampedConstPtr& msg) { - m_VehicleState.speed = msg->twist.linear.x; - UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); + m_VehicleState.speed = msg->twist.linear.x; + UtilityHNS::UtilityH::GetTickCount(m_VehicleState.tStamp); } void way_planner_core::callbackGetCANInfo(const autoware_can_msgs::CANInfoConstPtr &msg) { - m_VehicleState.speed = msg->speed/3.6; - m_VehicleState.steer = msg->angle * 0.45 / 660; - std::cout << "Can Info, Speed: "<< m_VehicleState.speed << ", Steering: " << m_VehicleState.steer << std::endl; + m_VehicleState.speed = msg->speed / 3.6; + m_VehicleState.steer = (msg->angle * 0.45) / 660; + std::cout << "Can Info, Speed: "<< m_VehicleState.speed << ", Steering: " << m_VehicleState.steer << std::endl; } void way_planner_core::callbackGetVMPoints(const vector_map_msgs::PointArray& msg) { - ROS_INFO("Received Map Points"); - m_AwMap.points = msg; - m_AwMap.bPoints = true; + ROS_INFO("Received Map Points"); + m_AwMap.points = msg; + m_AwMap.bPoints = true; } void way_planner_core::callbackGetVMLanes(const vector_map_msgs::LaneArray& msg) { - ROS_INFO("Received Map Lane Array"); - m_AwMap.lanes = msg; - m_AwMap.bLanes = true; + ROS_INFO("Received Map Lane Array"); + m_AwMap.lanes = msg; + m_AwMap.bLanes = true; } void way_planner_core::callbackGetVMNodes(const vector_map_msgs::NodeArray& msg) { - //ROS_INFO("Received Map Nodes"); - - } void way_planner_core::callbackGetVMStopLines(const vector_map_msgs::StopLineArray& msg) { - //ROS_INFO("Received Map Stop Lines"); } void way_planner_core::callbackGetVMCenterLines(const vector_map_msgs::DTLaneArray& msg) { - ROS_INFO("Received Map Center Lines"); - m_AwMap.dtlanes = msg; - m_AwMap.bDtLanes = true; + ROS_INFO("Received Map Center Lines"); + m_AwMap.dtlanes = msg; + m_AwMap.bDtLanes = true; } void way_planner_core::callbackGetNodesList(const vector_map_msgs::NodeArray& msg) { - } void way_planner_core::UpdateRoadMap(const AutowareRoadNetwork& src_map, PlannerHNS::RoadNetwork& out_map) { - std::vector lanes; - for(unsigned int i=0; i < src_map.lanes.data.size();i++) - { - UtilityHNS::AisanLanesFileReader::AisanLane l; - l.BLID = src_map.lanes.data.at(i).blid; - l.BLID2 = src_map.lanes.data.at(i).blid2; - l.BLID3 = src_map.lanes.data.at(i).blid3; - l.BLID4 = src_map.lanes.data.at(i).blid4; - l.BNID = src_map.lanes.data.at(i).bnid; - l.ClossID = src_map.lanes.data.at(i).clossid; - l.DID = src_map.lanes.data.at(i).did; - l.FLID = src_map.lanes.data.at(i).flid; - l.FLID2 = src_map.lanes.data.at(i).flid2; - l.FLID3 = src_map.lanes.data.at(i).flid3; - l.FLID4 = src_map.lanes.data.at(i).flid4; - l.FNID = src_map.lanes.data.at(i).fnid; - l.JCT = src_map.lanes.data.at(i).jct; - l.LCnt = src_map.lanes.data.at(i).lcnt; - l.LnID = src_map.lanes.data.at(i).lnid; - l.Lno = src_map.lanes.data.at(i).lno; - l.Span = src_map.lanes.data.at(i).span; - l.RefVel = src_map.lanes.data.at(i).refvel; - l.LimitVel = src_map.lanes.data.at(i).limitvel; - -// l.LaneChgFG = src_map.lanes.at(i).; -// l.LaneType = src_map.lanes.at(i).blid; -// l.LimitVel = src_map.lanes.at(i).; -// l.LinkWAID = src_map.lanes.at(i).blid; -// l.RefVel = src_map.lanes.at(i).blid; -// l.RoadSecID = src_map.lanes.at(i).; - - lanes.push_back(l); - } - - std::vector points; - - for(unsigned int i=0; i < src_map.points.data.size();i++) - { - UtilityHNS::AisanPointsFileReader::AisanPoints p; - double integ_part = src_map.points.data.at(i).l; - double deg = trunc(src_map.points.data.at(i).l); - double min = trunc((src_map.points.data.at(i).l - deg) * 100.0) / 60.0; - double sec = modf((src_map.points.data.at(i).l - deg) * 100.0, &integ_part)/36.0; - double L = deg + min + sec; - - deg = trunc(src_map.points.data.at(i).b); - min = trunc((src_map.points.data.at(i).b - deg) * 100.0) / 60.0; - sec = modf((src_map.points.data.at(i).b - deg) * 100.0, &integ_part)/36.0; - double B = deg + min + sec; - - p.B = B; - p.Bx = src_map.points.data.at(i).bx; - p.H = src_map.points.data.at(i).h; - p.L = L; - p.Ly = src_map.points.data.at(i).ly; - p.MCODE1 = src_map.points.data.at(i).mcode1; - p.MCODE2 = src_map.points.data.at(i).mcode2; - p.MCODE3 = src_map.points.data.at(i).mcode3; - p.PID = src_map.points.data.at(i).pid; - p.Ref = src_map.points.data.at(i).ref; - - points.push_back(p); - } - - - std::vector dts; - for(unsigned int i=0; i < src_map.dtlanes.data.size();i++) - { - UtilityHNS::AisanCenterLinesFileReader::AisanCenterLine dt; - - dt.Apara = src_map.dtlanes.data.at(i).apara; - dt.DID = src_map.dtlanes.data.at(i).did; - dt.Dir = src_map.dtlanes.data.at(i).dir; - dt.Dist = src_map.dtlanes.data.at(i).dist; - dt.LW = src_map.dtlanes.data.at(i).lw; - dt.PID = src_map.dtlanes.data.at(i).pid; - dt.RW = src_map.dtlanes.data.at(i).rw; - dt.cant = src_map.dtlanes.data.at(i).cant; - dt.r = src_map.dtlanes.data.at(i).r; - dt.slope = src_map.dtlanes.data.at(i).slope; - - dts.push_back(dt); - } - - std::vector areas; - std::vector inters; - std::vector line_data; - std::vector stop_line_data; - std::vector signal_data; - std::vector vector_data; - std::vector curb_data; - std::vector roadedge_data; - std::vector way_area; - std::vector crossing; - std::vector nodes_data; - std::vector conn_data; - - PlannerHNS::GPSPoint origin;//(m_OriginPos.position.x, m_OriginPos.position.y, m_OriginPos.position.z, 0); - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(lanes, points, dts, inters, areas, line_data, stop_line_data, signal_data, vector_data, curb_data, roadedge_data,way_area, crossing, nodes_data, conn_data, origin, out_map); + std::vector lanes; + for (unsigned int i = 0; i < src_map.lanes.data.size(); i++) + { + UtilityHNS::AisanLanesFileReader::AisanLane l; + l.BLID = src_map.lanes.data.at(i).blid; + l.BLID2 = src_map.lanes.data.at(i).blid2; + l.BLID3 = src_map.lanes.data.at(i).blid3; + l.BLID4 = src_map.lanes.data.at(i).blid4; + l.BNID = src_map.lanes.data.at(i).bnid; + l.ClossID = src_map.lanes.data.at(i).clossid; + l.DID = src_map.lanes.data.at(i).did; + l.FLID = src_map.lanes.data.at(i).flid; + l.FLID2 = src_map.lanes.data.at(i).flid2; + l.FLID3 = src_map.lanes.data.at(i).flid3; + l.FLID4 = src_map.lanes.data.at(i).flid4; + l.FNID = src_map.lanes.data.at(i).fnid; + l.JCT = src_map.lanes.data.at(i).jct; + l.LCnt = src_map.lanes.data.at(i).lcnt; + l.LnID = src_map.lanes.data.at(i).lnid; + l.Lno = src_map.lanes.data.at(i).lno; + l.Span = src_map.lanes.data.at(i).span; + l.RefVel = src_map.lanes.data.at(i).refvel; + l.LimitVel = src_map.lanes.data.at(i).limitvel; + + lanes.push_back(l); + } + + std::vector points; + + for (unsigned int i = 0; i < src_map.points.data.size(); i++) + { + UtilityHNS::AisanPointsFileReader::AisanPoints p; + double integ_part = src_map.points.data.at(i).l; + double deg = trunc(src_map.points.data.at(i).l); + double min = trunc((src_map.points.data.at(i).l - deg) * 100.0) / 60.0; + double sec = modf((src_map.points.data.at(i).l - deg) * 100.0, &integ_part) / 36.0; + double L = deg + min + sec; + + deg = trunc(src_map.points.data.at(i).b); + min = trunc((src_map.points.data.at(i).b - deg) * 100.0) / 60.0; + sec = modf((src_map.points.data.at(i).b - deg) * 100.0, &integ_part) / 36.0; + double B = deg + min + sec; + + p.B = B; + p.Bx = src_map.points.data.at(i).bx; + p.H = src_map.points.data.at(i).h; + p.L = L; + p.Ly = src_map.points.data.at(i).ly; + p.MCODE1 = src_map.points.data.at(i).mcode1; + p.MCODE2 = src_map.points.data.at(i).mcode2; + p.MCODE3 = src_map.points.data.at(i).mcode3; + p.PID = src_map.points.data.at(i).pid; + p.Ref = src_map.points.data.at(i).ref; + + points.push_back(p); + } + + + std::vector dts; + for (unsigned int i = 0; i < src_map.dtlanes.data.size(); i++) + { + UtilityHNS::AisanCenterLinesFileReader::AisanCenterLine dt; + + dt.Apara = src_map.dtlanes.data.at(i).apara; + dt.DID = src_map.dtlanes.data.at(i).did; + dt.Dir = src_map.dtlanes.data.at(i).dir; + dt.Dist = src_map.dtlanes.data.at(i).dist; + dt.LW = src_map.dtlanes.data.at(i).lw; + dt.PID = src_map.dtlanes.data.at(i).pid; + dt.RW = src_map.dtlanes.data.at(i).rw; + dt.cant = src_map.dtlanes.data.at(i).cant; + dt.r = src_map.dtlanes.data.at(i).r; + dt.slope = src_map.dtlanes.data.at(i).slope; + + dts.push_back(dt); + } + + std::vector areas; + std::vector inters; + std::vector line_data; + std::vector stop_line_data; + std::vector signal_data; + std::vector vector_data; + std::vector curb_data; + std::vector roadedge_data; + std::vector way_area; + std::vector crossing; + std::vector nodes_data; + std::vector conn_data; + + PlannerHNS::GPSPoint origin; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromROSMessage(lanes, points, dts, inters, areas, line_data, + stop_line_data, signal_data, vector_data, curb_data, roadedge_data, way_area, crossing, nodes_data, + conn_data, origin, out_map); } -bool way_planner_core::GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, std::vector >& generatedTotalPaths) +bool way_planner_core::GenerateGlobalPlan(PlannerHNS::WayPoint& startPoint, PlannerHNS::WayPoint& goalPoint, + std::vector>& generatedTotalPaths) { + generatedTotalPaths.clear(); - generatedTotalPaths.clear(); #ifdef ENABLE_VISUALIZE_PLAN - if(m_PlanningVisualizeTree.size() > 0) - { - m_PlannerH.DeleteWaypoints(m_PlanningVisualizeTree); - m_AccumPlanLevels.markers.clear(); - m_iCurrLevel = 0; - m_nLevelSize = 1; - } - - std::vector predefinedLanesIds; - double ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, - MAX_GLOBAL_PLAN_DISTANCE, predefinedLanesIds, - m_Map, generatedTotalPaths, &m_PlanningVisualizeTree); - - m_pCurrGoal = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(goalPoint, m_Map); + if (m_PlanningVisualizeTree.size() > 0) + { + m_PlannerH.DeleteWaypoints(m_PlanningVisualizeTree); + m_AccumPlanLevels.markers.clear(); + m_iCurrLevel = 0; + m_nLevelSize = 1; + } + + std::vector predefinedLanesIds; + double ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, + MAX_GLOBAL_PLAN_DISTANCE, m_params.bEnableLaneChange, predefinedLanesIds, + m_Map, generatedTotalPaths, &m_PlanningVisualizeTree, + m_params.fallbackMinGoalDistanceTh); + + m_pCurrGoal = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(goalPoint, m_Map); #else - std::vector predefinedLanesIds; + std::vector predefinedLanesIds; - double ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, - MAX_GLOBAL_PLAN_DISTANCE, m_params.bEnableLaneChange, - predefinedLanesIds, - m_Map, generatedTotalPaths); + double ret = m_PlannerH.PlanUsingDP(startPoint, goalPoint, + MAX_GLOBAL_PLAN_DISTANCE, m_params.bEnableLaneChange, + predefinedLanesIds, + m_Map, generatedTotalPaths, nullptr, + m_params.fallbackMinGoalDistanceTh); #endif -if(m_params.bEnableHMI) -{ - for(unsigned int im = 0; im < m_ModifiedWayPointsCosts.size(); im++) - m_ModifiedWayPointsCosts.at(im)->actionCost.at(0).second = 0; - - m_ModifiedWayPointsCosts.clear(); -} - if(ret == 0) generatedTotalPaths.clear(); - - - if(generatedTotalPaths.size() > 0 && generatedTotalPaths.at(0).size()>0) - { - if(m_params.bEnableSmoothing) - { - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - PlannerHNS::PlanningHelpers::FixPathDensity(generatedTotalPaths.at(i), m_params.pathDensity); - PlannerHNS::PlanningHelpers::SmoothPath(generatedTotalPaths.at(i), 0.49, 0.35 , 0.01); - } - } - - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - PlannerHNS::PlanningHelpers::CalcAngleAndCost(generatedTotalPaths.at(i)); - std::cout << "New DP Path -> " << generatedTotalPaths.at(i).size() << std::endl; - } - - return true; - } - else - { - std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() - << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; - } - return false; + if (m_params.bEnableHMI) + { + for (unsigned int im = 0; im < m_ModifiedWayPointsCosts.size(); im++) + { + m_ModifiedWayPointsCosts.at(im)->actionCost.at(0).second = 0; + } + + m_ModifiedWayPointsCosts.clear(); + } + if (ret == 0) + { + generatedTotalPaths.clear(); + } + + if ((generatedTotalPaths.size() > 0) && (generatedTotalPaths.at(0).size() > 0)) + { + if (m_params.bEnableSmoothing) + { + for (unsigned int i = 0; i < generatedTotalPaths.size(); i++) + { + PlannerHNS::PlanningHelpers::FixPathDensity(generatedTotalPaths.at(i), m_params.pathDensity); + PlannerHNS::PlanningHelpers::SmoothPath(generatedTotalPaths.at(i), 0.49, 0.35, 0.01); + } + } + + for (unsigned int i = 0; i < generatedTotalPaths.size(); i++) + { + PlannerHNS::PlanningHelpers::CalcAngleAndCost(generatedTotalPaths.at(i)); + std::cout << "New DP Path -> " << generatedTotalPaths.at(i).size() << std::endl; + } + + return true; + } + else + { + std::cout << "Can't Generate Global Path for Start (" << startPoint.pos.ToString() + << ") and Goal (" << goalPoint.pos.ToString() << ")" << std::endl; + } + return false; } void way_planner_core::VisualizeAndSend(const std::vector > generatedTotalPaths) { - autoware_msgs::LaneArray lane_array; - visualization_msgs::MarkerArray pathsToVisualize; - - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(generatedTotalPaths.at(i), lane_array); - - std_msgs::ColorRGBA total_color; - total_color.r = 0; - total_color.g = 0.7; - total_color.b = 1.0; - total_color.a = 0.9; - ROSHelpers::createGlobalLaneArrayMarker(total_color, lane_array, pathsToVisualize); - ROSHelpers::createGlobalLaneArrayOrientationMarker(lane_array, pathsToVisualize); - ROSHelpers::createGlobalLaneArrayVelocityMarker(lane_array, pathsToVisualize); - //ROSHelpers::ConvertFromPlannerHToAutowareVisualizePathFormat(generatedTotalPaths, pathsToVisualize); - pub_PathsRviz.publish(pathsToVisualize); - pub_Paths.publish(lane_array); + autoware_msgs::LaneArray lane_array; + visualization_msgs::MarkerArray pathsToVisualize; + + for (unsigned int i = 0; i < generatedTotalPaths.size(); i++) + { + ROSHelpers::ConvertFromPlannerHToAutowarePathFormat(generatedTotalPaths.at(i), lane_array); + } + + std_msgs::ColorRGBA total_color; + total_color.r = 0; + total_color.g = 0.7; + total_color.b = 1.0; + total_color.a = 0.9; + ROSHelpers::createGlobalLaneArrayMarker(total_color, lane_array, pathsToVisualize); + ROSHelpers::createGlobalLaneArrayOrientationMarker(lane_array, pathsToVisualize); + ROSHelpers::createGlobalLaneArrayVelocityMarker(lane_array, pathsToVisualize); + + pub_PathsRviz.publish(pathsToVisualize); + pub_Paths.publish(lane_array); #ifdef OPENPLANNER_ENABLE_LOGS - for(unsigned int i=0; i < generatedTotalPaths.size(); i++) - { - std::ostringstream str_out; - str_out << UtilityHNS::UtilityH::GetHomeDirectory(); - str_out << UtilityHNS::DataRW::LoggingMainfolderName; - str_out << "GlobalPath_"; - str_out << i; - str_out << "_"; - PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), generatedTotalPaths.at(i)); - } + for (unsigned int i = 0; i < generatedTotalPaths.size(); i++) + { + std::ostringstream str_out; + str_out << UtilityHNS::UtilityH::GetHomeDirectory(); + str_out << UtilityHNS::DataRW::LoggingMainfolderName; + str_out << "GlobalPath_"; + str_out << i; + str_out << "_"; + PlannerHNS::PlanningHelpers::WritePathToFile(str_out.str(), generatedTotalPaths.at(i)); + } #endif } #ifdef ENABLE_VISUALIZE_PLAN -void way_planner_core::CreateNextPlanningTreeLevelMarker(std::vector& level, visualization_msgs::MarkerArray& markerArray, double max_cost) +void way_planner_core::CreateNextPlanningTreeLevelMarker(std::vector& level, + visualization_msgs::MarkerArray& markerArray, double max_cost) { - if(level.size() == 0 && m_pCurrGoal) - return; - - std::vector newlevel; - - //lane_waypoint_marker.frame_locked = false; - - for(unsigned int i = 0; i < level.size(); i++) - { - visualization_msgs::Marker lane_waypoint_marker; - lane_waypoint_marker.header.frame_id = "map"; - lane_waypoint_marker.header.stamp = ros::Time(); - lane_waypoint_marker.type = visualization_msgs::Marker::ARROW; - lane_waypoint_marker.ns = "tree_levels"; - lane_waypoint_marker.action = visualization_msgs::Marker::ADD; - lane_waypoint_marker.scale.x = 1.0; - lane_waypoint_marker.scale.y = 0.5; - lane_waypoint_marker.scale.z = 0.5; - lane_waypoint_marker.color.a = 0.8; - lane_waypoint_marker.color.b = 1-0.0; - - float norm_cost = level.at(i)->cost / max_cost * 2.0; - if(norm_cost <= 1.0) - { - lane_waypoint_marker.color.r = 1-norm_cost; - lane_waypoint_marker.color.g = 1-1.0; - } - else if(norm_cost > 1.0) - { - lane_waypoint_marker.color.r = 1-1.0; - lane_waypoint_marker.color.g = 1- (2.0 - norm_cost); - } - - if(markerArray.markers.size() == 0) - lane_waypoint_marker.id = 0; - else - lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size()-1).id + 1; - - lane_waypoint_marker.pose.position.x = level.at(i)->pos.x; - lane_waypoint_marker.pose.position.y = level.at(i)->pos.y; - lane_waypoint_marker.pose.position.z = level.at(i)->pos.z; - double a = UtilityHNS::UtilityH::SplitPositiveAngle(level.at(i)->pos.a); - lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a); - markerArray.markers.push_back(lane_waypoint_marker); - - if(level.at(i)->pLeft) - { - lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a + M_PI_2); - newlevel.push_back(level.at(i)->pLeft); - lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size()-1).id + 1; - markerArray.markers.push_back(lane_waypoint_marker); - } - if(level.at(i)->pRight) - { - newlevel.push_back(level.at(i)->pRight); - lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a - M_PI_2); - lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size()-1).id + 1; - markerArray.markers.push_back(lane_waypoint_marker); - } - - for(unsigned int j = 0; j < level.at(i)->pFronts.size(); j++) - if(level.at(i)->pFronts.at(j)) - newlevel.push_back(level.at(i)->pFronts.at(j)); - - if(hypot(m_pCurrGoal->pos.y - level.at(i)->pos.y, m_pCurrGoal->pos.x - level.at(i)->pos.x) < 0.5) - { - newlevel.clear(); - break; - } - - std::cout << "Levels: " << lane_waypoint_marker.id << ", pLeft:" << level.at(i)->pLeft << ", pRight:" << level.at(i)->pRight << ", nFront:" << level.at(i)->pFronts.size() << ", Cost: "<< norm_cost<< std::endl; - } - - level = newlevel; - - //std::cout << "Levels: " << level.size() << std::endl; + if ((level.size() == 0) && m_pCurrGoal) + { + return; + } + + std::vector newlevel; + + for (unsigned int i = 0; i < level.size(); i++) + { + visualization_msgs::Marker lane_waypoint_marker; + lane_waypoint_marker.header.frame_id = "map"; + lane_waypoint_marker.header.stamp = ros::Time(); + lane_waypoint_marker.type = visualization_msgs::Marker::ARROW; + lane_waypoint_marker.ns = "tree_levels"; + lane_waypoint_marker.action = visualization_msgs::Marker::ADD; + lane_waypoint_marker.scale.x = 1.0; + lane_waypoint_marker.scale.y = 0.5; + lane_waypoint_marker.scale.z = 0.5; + lane_waypoint_marker.color.a = 0.8; + lane_waypoint_marker.color.b = 1-0.0; + + float norm_cost = (level.at(i)->cost / max_cost) * 2.0; + if (norm_cost <= 1.0) + { + lane_waypoint_marker.color.r = 1 - norm_cost; + lane_waypoint_marker.color.g = 1 - 1.0; + } + else if (norm_cost > 1.0) + { + lane_waypoint_marker.color.r = 1 - 1.0; + lane_waypoint_marker.color.g = 1 - (2.0 - norm_cost); + } + + if (markerArray.markers.size() == 0) + { + lane_waypoint_marker.id = 0; + } + else + { + lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size() - 1).id + 1; + } + + lane_waypoint_marker.pose.position.x = level.at(i)->pos.x; + lane_waypoint_marker.pose.position.y = level.at(i)->pos.y; + lane_waypoint_marker.pose.position.z = level.at(i)->pos.z; + double a = UtilityHNS::UtilityH::SplitPositiveAngle(level.at(i)->pos.a); + lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a); + markerArray.markers.push_back(lane_waypoint_marker); + + if (level.at(i)->pLeft) + { + lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a + M_PI_2); + newlevel.push_back(level.at(i)->pLeft); + lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size()-1).id + 1; + markerArray.markers.push_back(lane_waypoint_marker); + } + if (level.at(i)->pRight) + { + newlevel.push_back(level.at(i)->pRight); + lane_waypoint_marker.pose.orientation = tf::createQuaternionMsgFromYaw(a - M_PI_2); + lane_waypoint_marker.id = markerArray.markers.at(markerArray.markers.size() - 1).id + 1; + markerArray.markers.push_back(lane_waypoint_marker); + } + + for (unsigned int j = 0; j < level.at(i)->pFronts.size(); j++) + { + if (level.at(i)->pFronts.at(j)) + { + newlevel.push_back(level.at(i)->pFronts.at(j)); + } + } + + if (hypot(m_pCurrGoal->pos.y - level.at(i)->pos.y, m_pCurrGoal->pos.x - level.at(i)->pos.x) < 0.5) + { + newlevel.clear(); + break; + } + + std::cout << "Levels: " << lane_waypoint_marker.id << ", pLeft:" << level.at(i)->pLeft << ", pRight:" + << level.at(i)->pRight << ", nFront:" << level.at(i)->pFronts.size() << ", Cost: " + << norm_cost << std::endl; + } + + level = newlevel; } - #endif - bool way_planner_core::HMI_DoOneStep() { - double min_distance = m_AvgResponseTime * m_VehicleState.speed; - std::vector branches; - - PlannerHNS::WayPoint startPoint; - - if(m_GoalsPos.size() > 1) - startPoint = m_CurrentPose; - - PlannerHNS::WayPoint* currOptions = 0; - ROSHelpers::FindIncommingBranches(m_GeneratedTotalPaths,startPoint, min_distance, branches, currOptions); - if(branches.size() > 0) - { - HMI_MSG msg; - msg.type = OPTIONS_MSG; - msg.options.clear(); - for(unsigned int i = 0; i< branches.size(); i++) - msg.options.push_back(branches.at(i)->actionCost.at(0).first); - - std::cout << "Send Message (" << branches.size() << ") Branches (" ; - for(unsigned int i=0; i< branches.size(); i++) - { - if(branches.at(i)->actionCost.at(0).first == PlannerHNS::FORWARD_ACTION) - std::cout << "F,"; - else if(branches.at(i)->actionCost.at(0).first == PlannerHNS::LEFT_TURN_ACTION) - std::cout << "L,"; - else if(branches.at(i)->actionCost.at(0).first == PlannerHNS::RIGHT_TURN_ACTION) - std::cout << "R,"; - - } - - std::cout << ")" << std::endl; - - int close_index = PlannerHNS::PlanningHelpers::GetClosestNextPointIndex_obsolete(m_GeneratedTotalPaths.at(0), startPoint); - - for(unsigned int i=close_index+1; i < m_GeneratedTotalPaths.at(0).size(); i++) - { - bool bFound = false; - for(unsigned int j=0; j< branches.size(); j++) - { - //if(wp != 0)sadasd - { - if(branches.at(j)->id == m_GeneratedTotalPaths.at(0).at(i).id) - { - currOptions = branches.at(j); - bFound = true; - break; - } - } - } - if(bFound) - break; - } - - if(currOptions !=0 ) - { -// std::cout <<" Current Option : " ; -// if(currOptions->actionCost.at(0).first == PlannerHNS::FORWARD_ACTION) -// std::cout << "F,"; -// else if(currOptions->actionCost.at(0).first == PlannerHNS::LEFT_TURN_ACTION) -// std::cout << "L,"; -// else if(currOptions->actionCost.at(0).first == PlannerHNS::RIGHT_TURN_ACTION) -// std::cout << "R,"; -// std::cout <actionCost.at(0).first); -// m_SocketServer.SendMSG(currOpMsg); - msg.current = currOptions->actionCost.at(0).first; - msg.currID = currOptions->laneId; - - } - - m_SocketServer.SendMSG(msg); - - double total_d = 0; - for(unsigned int iwp =1; iwp < m_GeneratedTotalPaths.at(0).size(); iwp++) - { - total_d += hypot(m_GeneratedTotalPaths.at(0).at(iwp).pos.y - m_GeneratedTotalPaths.at(0).at(iwp-1).pos.y, m_GeneratedTotalPaths.at(0).at(iwp).pos.x - m_GeneratedTotalPaths.at(0).at(iwp-1).pos.x); - } - - HMI_MSG inc_msg; - int bNew = m_SocketServer.GetLatestMSG(inc_msg); - if(bNew>0) - { - for(unsigned int i = 0; i< branches.size(); i++) - { - for(unsigned int j = 0; j< inc_msg.options.size(); j++) - { - if(branches.at(i)->actionCost.at(0).first == inc_msg.options.at(j)) - { - branches.at(i)->actionCost.at(0).second = -total_d*4.0; - m_ModifiedWayPointsCosts.push_back(branches.at(i)); - } - } - } - - return true; - } - } - - return false; + double min_distance = m_AvgResponseTime * m_VehicleState.speed; + std::vector branches; + + PlannerHNS::WayPoint startPoint; + + if (m_GoalsPos.size() > 1) + { + startPoint = m_CurrentPose; + } + + PlannerHNS::WayPoint* currOptions = 0; + ROSHelpers::FindIncommingBranches(m_GeneratedTotalPaths, startPoint, min_distance, branches, currOptions); + if (branches.size() > 0) + { + HMI_MSG msg; + msg.type = OPTIONS_MSG; + msg.options.clear(); + for (unsigned int i = 0; i < branches.size(); i++) + { + msg.options.push_back(branches.at(i)->actionCost.at(0).first); + } + + std::cout << "Send Message (" << branches.size() << ") Branches ("; + for (unsigned int i = 0; i < branches.size(); i++) + { + if (branches.at(i)->actionCost.at(0).first == PlannerHNS::FORWARD_ACTION) + { + std::cout << "F,"; + } + else if (branches.at(i)->actionCost.at(0).first == PlannerHNS::LEFT_TURN_ACTION) + { + std::cout << "L,"; + } + else if (branches.at(i)->actionCost.at(0).first == PlannerHNS::RIGHT_TURN_ACTION) + { + std::cout << "R,"; + } + } + + std::cout << ")" << std::endl; + + int close_index = PlannerHNS::PlanningHelpers::GetClosestNextPointIndex_obsolete(m_GeneratedTotalPaths.at(0), + startPoint); + for (unsigned int i = close_index + 1; i < m_GeneratedTotalPaths.at(0).size(); i++) + { + bool bFound = false; + for (unsigned int j = 0; j < branches.size(); j++) + { + if (branches.at(j)->id == m_GeneratedTotalPaths.at(0).at(i).id) + { + currOptions = branches.at(j); + bFound = true; + break; + } + } + if (bFound) + { + break; + } + } + + if (currOptions != 0) + { + msg.current = currOptions->actionCost.at(0).first; + msg.currID = currOptions->laneId; + } + + m_SocketServer.SendMSG(msg); + + double total_d = 0; + for (unsigned int iwp = 1; iwp < m_GeneratedTotalPaths.at(0).size(); iwp++) + { + total_d += hypot(m_GeneratedTotalPaths.at(0).at(iwp).pos.y - m_GeneratedTotalPaths.at(0).at(iwp-1).pos.y, + m_GeneratedTotalPaths.at(0).at(iwp).pos.x - m_GeneratedTotalPaths.at(0).at(iwp-1).pos.x); + } + + HMI_MSG inc_msg; + int bNew = m_SocketServer.GetLatestMSG(inc_msg); + if (bNew > 0) + { + for (unsigned int i = 0; i < branches.size(); i++) + { + for (unsigned int j = 0; j < inc_msg.options.size(); j++) + { + if (branches.at(i)->actionCost.at(0).first == inc_msg.options.at(j)) + { + branches.at(i)->actionCost.at(0).second = -total_d * 4.0; + m_ModifiedWayPointsCosts.push_back(branches.at(i)); + } + } + } + return true; + } + } + + return false; } void way_planner_core::PlannerMainLoop() { - ros::Rate loop_rate(10); - timespec animation_timer; - UtilityHNS::UtilityH::GetTickCount(animation_timer); - - while (ros::ok()) - { - ros::spinOnce(); - bool bMakeNewPlan = false; - - if(m_params.bEnableHMI) - bMakeNewPlan = HMI_DoOneStep(); - - //std::cout << "Main Loop ! " << std::endl; - if(m_params.mapSource == MAP_KML_FILE && !m_bKmlMap) - { - m_bKmlMap = true; - PlannerHNS::MappingHelpers::LoadKML(m_params.KmlMapPath, m_Map); - //PlannerHNS::MappingHelpers::WriteKML("/home/hatem/SimuLogs/KmlMaps/ToyotaMap2017.kml", "/home/hatem/SimuLogs/KmlMaps/PlannerX_MapTemplate.kml", m_Map); - visualization_msgs::MarkerArray map_marker_array; - ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - pub_MapRviz.publish(map_marker_array); - } - else if (m_params.mapSource == MAP_FOLDER && !m_bKmlMap) - { - m_bKmlMap = true; - PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_params.KmlMapPath, m_Map, true); - //PlannerHNS::MappingHelpers::WriteKML("/home/hatem/SimuLogs/KmlMaps/Moriyama_NoTransform_2017.kml", "/home/hatem/SimuLogs/KmlMaps/PlannerX_MapTemplate.kml", m_Map); - visualization_msgs::MarkerArray map_marker_array; - ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - - pub_MapRviz.publish(map_marker_array); - - } - else if(m_params.mapSource == MAP_AUTOWARE) - { - if(m_AwMap.bDtLanes && m_AwMap.bLanes && m_AwMap.bPoints) - { - m_AwMap.bDtLanes = m_AwMap.bLanes = m_AwMap.bPoints = false; - UpdateRoadMap(m_AwMap,m_Map); - visualization_msgs::MarkerArray map_marker_array; - ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); - pub_MapRviz.publish(map_marker_array); - } - } - - if(m_GoalsPos.size() > 1) - { - //std::cout << m_CurrentPose.pos.ToString() << std::endl; - PlannerHNS::WayPoint startPoint = m_CurrentPose; - PlannerHNS::WayPoint goalPoint = m_GoalsPos.at(m_iCurrentGoalIndex); - - if(m_GeneratedTotalPaths.size() > 0 && m_GeneratedTotalPaths.at(0).size() > 3) - { - if(m_params.bEnableReplanning) - { - PlannerHNS::RelativeInfo info; - bool ret = PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_GeneratedTotalPaths, startPoint, 0.75, info); - if(ret == true && info.iGlobalPath >= 0 && info.iGlobalPath < m_GeneratedTotalPaths.size() && info.iFront > 0 && info.iFront < m_GeneratedTotalPaths.at(info.iGlobalPath).size()) - { - double remaining_distance = m_GeneratedTotalPaths.at(info.iGlobalPath).at(m_GeneratedTotalPaths.at(info.iGlobalPath).size()-1).cost - (m_GeneratedTotalPaths.at(info.iGlobalPath).at(info.iFront).cost + info.to_front_distance); - if(remaining_distance <= REPLANNING_DISTANCE) - { - m_iCurrentGoalIndex++; - if(m_iCurrentGoalIndex >= m_GoalsPos.size()) - m_iCurrentGoalIndex = 0; - bMakeNewPlan = true; - } - } - } - } - else - bMakeNewPlan = true; - - if(bMakeNewPlan) - { - - bool bNewPlan = GenerateGlobalPlan(startPoint, goalPoint, m_GeneratedTotalPaths); - - if(bNewPlan) - { - bMakeNewPlan = false; - VisualizeAndSend(m_GeneratedTotalPaths); + ros::Rate loop_rate(10); + timespec animation_timer; + UtilityHNS::UtilityH::GetTickCount(animation_timer); + int newPlanTry = 0; + + while (ros::ok()) + { + ros::spinOnce(); + bool bMakeNewPlan = false; + + if (m_params.bEnableHMI) + { + bMakeNewPlan = HMI_DoOneStep(); + } + + if ((m_params.mapSource == MAP_KML_FILE) && !m_bKmlMap) + { + m_bKmlMap = true; + PlannerHNS::MappingHelpers::LoadKML(m_params.KmlMapPath, m_Map); + visualization_msgs::MarkerArray map_marker_array; + ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + pub_MapRviz.publish(map_marker_array); + } + else if ((m_params.mapSource == MAP_FOLDER) && !m_bKmlMap) + { + m_bKmlMap = true; + PlannerHNS::MappingHelpers::ConstructRoadNetworkFromDataFiles(m_params.KmlMapPath, m_Map, true); + visualization_msgs::MarkerArray map_marker_array; + ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + + pub_MapRviz.publish(map_marker_array); + } + else if (m_params.mapSource == MAP_AUTOWARE) + { + if (m_AwMap.bDtLanes && m_AwMap.bLanes && m_AwMap.bPoints) + { + m_AwMap.bDtLanes = m_AwMap.bLanes = m_AwMap.bPoints = false; + UpdateRoadMap(m_AwMap, m_Map); + visualization_msgs::MarkerArray map_marker_array; + ROSHelpers::ConvertFromRoadNetworkToAutowareVisualizeMapFormat(m_Map, map_marker_array); + pub_MapRviz.publish(map_marker_array); + } + } + + if (m_GoalsPos.size() > 1) + { + PlannerHNS::WayPoint startPoint = m_CurrentPose; + PlannerHNS::WayPoint goalPoint = m_GoalsPos.at(m_iCurrentGoalIndex); + + if ((m_GeneratedTotalPaths.size() > 0) && (m_GeneratedTotalPaths.at(0).size() > 3)) + { + if (m_params.bEnableReplanning) + { + PlannerHNS::RelativeInfo info; + bool ret = PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_GeneratedTotalPaths, startPoint, 0.75, info); + if ((ret == true) && (info.iGlobalPath >= 0) && (info.iGlobalPath < m_GeneratedTotalPaths.size()) + && (info.iFront > 0) && (info.iFront < m_GeneratedTotalPaths.at(info.iGlobalPath).size())) + { + double remaining_distance = m_GeneratedTotalPaths.at(info.iGlobalPath).at(m_GeneratedTotalPaths.at( + info.iGlobalPath).size() - 1).cost - + (m_GeneratedTotalPaths.at(info.iGlobalPath).at(info.iFront).cost + info.to_front_distance); + if (remaining_distance <= REPLANNING_DISTANCE) + { + m_iCurrentGoalIndex++; + if (m_iCurrentGoalIndex >= m_GoalsPos.size()) + { + m_iCurrentGoalIndex = 0; + } + bMakeNewPlan = true; + } + } + } + } + else + { + bMakeNewPlan = true; + } + + if (bMakeNewPlan) + { + bool bNewPlan = GenerateGlobalPlan(startPoint, goalPoint, m_GeneratedTotalPaths); + // If the maximum attempt feature is enabled, increase the counter + if (m_params.planningMaxAttempt != 0) + { + newPlanTry++; + } + + if (bNewPlan) + { + // Reset the newPlanTry as we have found the path + newPlanTry = 0; + bMakeNewPlan = false; + VisualizeAndSend(m_GeneratedTotalPaths); #ifdef ENABLE_VISUALIZE_PLAN - //calculate new max_cost - if(m_PlanningVisualizeTree.size() > 1) - { - m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(0)); - m_CurrMaxCost = 0; - for(unsigned int itree = 0; itree < m_PlanningVisualizeTree.size(); itree++) - { - if(m_PlanningVisualizeTree.at(itree)->cost > m_CurrMaxCost) - m_CurrMaxCost = m_PlanningVisualizeTree.at(itree)->cost; - } - } + // calculate new max_cost + if (m_PlanningVisualizeTree.size() > 1) + { + m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(0)); + m_CurrMaxCost = 0; + for (unsigned int itree = 0; itree < m_PlanningVisualizeTree.size(); itree++) + { + if (m_PlanningVisualizeTree.at(itree)->cost > m_CurrMaxCost) + { + m_CurrMaxCost = m_PlanningVisualizeTree.at(itree)->cost; + } + } + } #endif - } - } + } + else + { + // If we retried enough, remove the goal from the queue + if (newPlanTry >= m_params.planningMaxAttempt) + { + ROS_WARN("%s (tried %d times), %s", + "way_planner: Unable to plan the path", + m_params.planningMaxAttempt, + "removing the goal"); + m_GoalsPos.erase(m_GoalsPos.begin() + m_iCurrentGoalIndex); + newPlanTry = 0; + } + else + { + // Retry for m_params.planningMaxAttempt times + ROS_WARN("way_planner: Unable to plan the requested goal path, will retry"); + } + } + } #ifdef ENABLE_VISUALIZE_PLAN - if(UtilityHNS::UtilityH::GetTimeDiffNow(animation_timer) > 0.5) - { - UtilityHNS::UtilityH::GetTickCount(animation_timer); - m_CurrentLevel.clear(); - - for(unsigned int ilev = 0; ilev < m_nLevelSize && m_iCurrLevel < m_PlanningVisualizeTree.size() ; ilev ++) - { - m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(m_iCurrLevel)); - m_nLevelSize += m_PlanningVisualizeTree.at(m_iCurrLevel)->pFronts.size() - 1; - m_iCurrLevel++; - } - - - if(m_CurrentLevel.size() == 0 && m_GeneratedTotalPaths.size() > 0) - { - m_bSwitch++; - m_AccumPlanLevels.markers.clear(); - - if(m_bSwitch == 2) - { - for(unsigned int il = 0; il < m_GeneratedTotalPaths.size(); il++) - for(unsigned int ip = 0; ip < m_GeneratedTotalPaths.at(il).size(); ip ++) - m_CurrentLevel.push_back(&m_GeneratedTotalPaths.at(il).at(ip)); - - std::cout << "Switch On " << std::endl; - - m_bSwitch = 0; - - } - else - { - for(unsigned int ilev = 0; ilev < m_PlanningVisualizeTree.size()+200 ; ilev ++) - m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(0)); - - std::cout << "Switch Off " << std::endl; - } - - CreateNextPlanningTreeLevelMarker(m_CurrentLevel, m_AccumPlanLevels, m_CurrMaxCost); - pub_GlobalPlanAnimationRviz.publish(m_AccumPlanLevels); - } - else - { - CreateNextPlanningTreeLevelMarker(m_CurrentLevel, m_AccumPlanLevels, m_CurrMaxCost); - - if(m_AccumPlanLevels.markers.size() > 0) - pub_GlobalPlanAnimationRviz.publish(m_AccumPlanLevels); - } - } + if (UtilityHNS::UtilityH::GetTimeDiffNow(animation_timer) > 0.5) + { + UtilityHNS::UtilityH::GetTickCount(animation_timer); + m_CurrentLevel.clear(); + + for (unsigned int ilev = 0; (ilev < m_nLevelSize) && (m_iCurrLevel < m_PlanningVisualizeTree.size()); ilev++) + { + m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(m_iCurrLevel)); + m_nLevelSize += m_PlanningVisualizeTree.at(m_iCurrLevel)->pFronts.size() - 1; + m_iCurrLevel++; + } + + if ((m_CurrentLevel.size() == 0) && (m_GeneratedTotalPaths.size() > 0)) + { + m_bSwitch++; + m_AccumPlanLevels.markers.clear(); + + if (m_bSwitch == 2) + { + for (unsigned int il = 0; il < m_GeneratedTotalPaths.size(); il++) + { + for (unsigned int ip = 0; ip < m_GeneratedTotalPaths.at(il).size(); ip++) + { + m_CurrentLevel.push_back(&m_GeneratedTotalPaths.at(il).at(ip)); + } + } + std::cout << "Switch On " << std::endl; + m_bSwitch = 0; + } + else + { + for (unsigned int ilev = 0; ilev < (m_PlanningVisualizeTree.size() + 200); ilev++) + { + m_CurrentLevel.push_back(m_PlanningVisualizeTree.at(0)); + } + + std::cout << "Switch Off " << std::endl; + } + + CreateNextPlanningTreeLevelMarker(m_CurrentLevel, m_AccumPlanLevels, m_CurrMaxCost); + pub_GlobalPlanAnimationRviz.publish(m_AccumPlanLevels); + } + else + { + CreateNextPlanningTreeLevelMarker(m_CurrentLevel, m_AccumPlanLevels, m_CurrMaxCost); + + if (m_AccumPlanLevels.markers.size() > 0) + { + pub_GlobalPlanAnimationRviz.publish(m_AccumPlanLevels); + } + } + } #endif + } - } - - //ROS_INFO("Main Loop Step"); - loop_rate.sleep(); - } + loop_rate.sleep(); + } } -} +} // namespace WayPlannerNS diff --git a/core_planning/way_planner/package.xml b/core_planning/way_planner/package.xml index 904e077f9d3..22409539a31 100644 --- a/core_planning/way_planner/package.xml +++ b/core_planning/way_planner/package.xml @@ -9,6 +9,7 @@ autoware_build_flags catkin + roslint autoware_can_msgs geometry_msgs diff --git a/documentation/.github/workflows/native-ci.yaml b/documentation/.github/workflows/native-ci.yaml new file mode 100644 index 00000000000..8795c03d399 --- /dev/null +++ b/documentation/.github/workflows/native-ci.yaml @@ -0,0 +1,42 @@ +name: Native CI workflow + +on: + pull_request: + push: + branches: + - master + +jobs: + + build-melodic: + + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-latest] #[ubuntu-latest, self-hosted] + fail-fast: false + + container: + image: autoware/autoware:bleedingedge-melodic-base + env: + ROS_DISTRO: melodic + options: --user 1001 + + steps: + + - name: Checkout repo + uses: actions/checkout@v2 + + - name: Prepare repo + run: | + mkdir -p src_tmp/ && mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/ && mv src_tmp/ src/ + rosdep update + rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO + + - name: Build and test repo + run: | + bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ + colcon build --cmake-args -DCMAKE_CXX_FLAGS="${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_C_FLAGS="${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_BUILD_TYPE=Debug; \ + colcon build --cmake-target tests --cmake-args -DCMAKE_CXX_FLAGS="${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_C_FLAGS="${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_BUILD_TYPE=Debug; \ + colcon test; \ + colcon test-result --verbose' diff --git a/documentation/.gitlab-ci.yml b/documentation/.gitlab-ci.yml deleted file mode 100644 index 29fd16d72f5..00000000000 --- a/documentation/.gitlab-ci.yml +++ /dev/null @@ -1,95 +0,0 @@ -variables: - CI_SOURCE_PATH: $CI_PROJECT_DIR - GIT_SUBMODULE_STRATEGY: recursive - -.build: &build_common - before_script: - - mkdir -p src_tmp/${CI_PROJECT_NAME} && mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/${CI_PROJECT_NAME} && mv src_tmp/ src/ - - apt-get update - - apt-get install -y wget python3-pip python3-setuptools python3-colcon-common-extensions - # Update setuptools from PyPI because the version Ubuntu ships with is too old - - pip3 install -U setuptools - - rosdep update - script: - - source /opt/ros/${ROS_DISTRO}/setup.bash - - rosdep install -y --from-paths src --ignore-src --rosdistro ${ROS_DISTRO} - # We first build the entire workspace normally - - colcon build --cmake-args -DCMAKE_CXX_FLAGS="${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_C_FLAGS="${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_BUILD_TYPE=Debug - # And then build the tests target. catkin (ROS1) packages add their tests to the tests target - # which is not the standard target for CMake projects. We need to trigger the tests target so that - # tests are built and any fixtures are set up. - - colcon build --cmake-target tests --cmake-args -DCMAKE_CXX_FLAGS="${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_C_FLAGS="${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage" -DCMAKE_BUILD_TYPE=Debug - - colcon test - - colcon test-result - coverage: /\s*lines.*:\s(\d+\.\d+\%\s\(\d+\sof\s\d+.*\))/ - only: - - merge_requests - - master - -.build_cross_vars: &build_cross_vars - AUTOWARE_HOME: $CI_PROJECT_DIR - AUTOWARE_TARGET_ARCH: aarch64 - AUTOWARE_TARGET_PLATFORM: generic-aarch64 - AUTOWARE_BUILD_PATH: $CI_PROJECT_DIR/build-${AUTOWARE_TARGET_PLATFORM} - AUTOWARE_INSTALL_PATH: $CI_PROJECT_DIR/install-${AUTOWARE_TARGET_PLATFORM} - AUTOWARE_TOOLCHAIN_FILE_PATH: $CI_PROJECT_DIR/cross_toolchain.cmake - AUTOWARE_SYSROOT: /sysroot/${AUTOWARE_TARGET_PLATFORM} - -.build_cross: &build_cross_common - script: - - wget https://gitlab.com/autowarefoundation/autoware.ai/autoware/raw/master/ros/cross_toolchain.cmake - - 'docker run - -e AUTOWARE_SYSROOT=${AUTOWARE_SYSROOT} - --rm - -v ${AUTOWARE_HOME}:${AUTOWARE_HOME} - -w ${AUTOWARE_HOME} - autoware/build:${AUTOWARE_TARGET_PLATFORM}-${ROS_DISTRO}-${AUTOWARE_DOCKER_DATE} - bash - -c " - source ${AUTOWARE_SYSROOT}/opt/ros/${ROS_DISTRO}/setup.bash && - colcon build - --merge-install - --build-base ${AUTOWARE_BUILD_PATH} - --install-base ${AUTOWARE_INSTALL_PATH} - --cmake-args - -DCMAKE_TOOLCHAIN_FILE=${AUTOWARE_TOOLCHAIN_FILE_PATH} - -DCMAKE_SYSTEM_PROCESSOR=${AUTOWARE_TARGET_ARCH} - -DCMAKE_PREFIX_PATH=\"${AUTOWARE_SYSROOT}/opt/ros/${ROS_DISTRO};${AUTOWARE_INSTALL_PATH}\" - -DCMAKE_FIND_ROOT_PATH=${AUTOWARE_INSTALL_PATH} - " - ' - only: - - merge_requests - - master - -build_kinetic: - image: ros:kinetic-perception - variables: - ROS_DISTRO: kinetic - <<: *build_common - -build_melodic: - image: ros:melodic-perception - variables: - ROS_DISTRO: melodic - <<: *build_common - -build_kinetic_cross: - image: docker - services: - - docker:dind - variables: - ROS_DISTRO: kinetic - AUTOWARE_DOCKER_DATE: "latest" - <<: *build_cross_vars - <<: *build_cross_common - -build_melodic_cross: - image: docker - services: - - docker:dind - variables: - ROS_DISTRO: melodic - AUTOWARE_DOCKER_DATE: "latest" - <<: *build_cross_vars - <<: *build_cross_common diff --git a/documentation/.gitlab/issue_templates/bug_report.md b/documentation/.gitlab/issue_templates/bug_report.md deleted file mode 100644 index d634fee7c34..00000000000 --- a/documentation/.gitlab/issue_templates/bug_report.md +++ /dev/null @@ -1,57 +0,0 @@ -/label ~bug - - -### Required information: - -- Operating system and version: - - -- Autoware installation type: - - -- Autoware version or commit hash - - -- ROS distribution and version: - - -- ROS installation type: - - -- Package or library, if applicable: - - - -### Description of the bug - - - -### Steps to reproduce the bug - - - - -### Expected behavior - - - -### Actual behavior - - - -### Screenshots - - - -### Additional information - - diff --git a/documentation/.gitlab/issue_templates/feature_request.md b/documentation/.gitlab/issue_templates/feature_request.md deleted file mode 100644 index 2291a8dbb6d..00000000000 --- a/documentation/.gitlab/issue_templates/feature_request.md +++ /dev/null @@ -1,26 +0,0 @@ -/label ~enhancement - - -### Description - - - -### Implementation considerations - - - -### Alternatives - - - -### Additional information - - diff --git a/documentation/.gitlab/issue_templates/other_issue.md b/documentation/.gitlab/issue_templates/other_issue.md deleted file mode 100644 index fd91d284964..00000000000 --- a/documentation/.gitlab/issue_templates/other_issue.md +++ /dev/null @@ -1,13 +0,0 @@ -/assign @gbiggs - - -IF YOU ARE ASKING FOR SUPPORT please read the support guidelines: https://gitlab.com/autowarefoundation/autoware.ai/autoware/wikis/Support-guidelines -Ask support requests at ROS Answers: https://answers.ros.org/questions/ask/?tags=autoware - diff --git a/documentation/.gitlab/merge_request_templates/bug_fix.md b/documentation/.gitlab/merge_request_templates/bug_fix.md deleted file mode 100644 index 737a343726d..00000000000 --- a/documentation/.gitlab/merge_request_templates/bug_fix.md +++ /dev/null @@ -1,69 +0,0 @@ -/label ~bug - - -### Fixed bug - -- Autoware installation type: - - -- Autoware version or commit hash - - -- ROS distribution and version: - - -- ROS installation type: - - -- Package or library, if applicable: - - - -### Description of the bug - - - -### Steps to reproduce the bug - - - - -### Expected behavior - - - -### Actual behavior - - - -### Screenshots - - - -### Additional information - - ---> - -### Fix applied - - diff --git a/documentation/.gitlab/merge_request_templates/feature_implementation.md b/documentation/.gitlab/merge_request_templates/feature_implementation.md deleted file mode 100644 index 0c3a26fe208..00000000000 --- a/documentation/.gitlab/merge_request_templates/feature_implementation.md +++ /dev/null @@ -1,39 +0,0 @@ -/label ~enhancement - - -### Implemented feature - - - -### Implementation considerations - - - -### Alternatives - - - -### Additional information - - ---> - -### Implementation description - - diff --git a/documentation/CONTRIBUTING.md b/documentation/CONTRIBUTING.md index 3973501dc91..8b1dfbda427 100644 --- a/documentation/CONTRIBUTING.md +++ b/documentation/CONTRIBUTING.md @@ -7,7 +7,7 @@ we adhere to the [Contributor Covenant](https://www.contributor-covenant.org/), used [code of conduct](/CODE_OF_CONDUCT.md) adopted by many other communities such as Linux, Ruby on Rails and GitLab. -Everyone participating in the Autoware.Auto community is expected to follow the code of +Everyone participating in the Autoware.AI community is expected to follow the code of conduct. If someone in the community happens to be violating these terms, please let the project @@ -15,7 +15,7 @@ leads know, and we will address it as soon as possible. ## License -Autoware.Auto is licensed under Apache 2, and thus all contributions will be licensed as such +Autoware.AI is licensed under Apache 2, and thus all contributions will be licensed as such as per clause 5 of the Apache 2 License: ~~~ @@ -30,7 +30,7 @@ as per clause 5 of the Apache 2 License: ## Detailed contribution guidelines -For more detailed information on contributing to Autoware, including development processes, -please see the contributing guidelines on the Autoware Wiki: +For more detailed information on contributing to Autoware.AI, please see the contributing +guidelines on the Autoware Wiki: -https://github.com/autowarefoundation/autoware/wiki/Contributing-to-Autoware +https://github.com/Autoware-AI/autoware.ai/wiki/Contributing-to-Autoware diff --git a/documentation/DISCLAIMER.md b/documentation/DISCLAIMER.md new file mode 100644 index 00000000000..d0d6f97da09 --- /dev/null +++ b/documentation/DISCLAIMER.md @@ -0,0 +1,50 @@ +DISCLAIMER + +The open-source software for self-driving vehicles, Autoware.AI, Autoware.IO, +Autoware.Auto. (collectively, referred to as “Autoware”) will be provided by +The Autoware Foundation under the Apache 2.0 License. This “DISCLAIMER” will be +applied to all users of Autoware (a “User” or “Users”) with the Apache 2.0 +License and Users shall hereby approve and acknowledge all the contents +specified in this disclaimer below and will be deemed to consent to this +disclaimer without any objection upon utilizing or downloading Autoware. + + +Disclaimer and Waiver of Warranties + +1. AUTOWARE FOUNDATION MAKES NO REPRESENTATION OR WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, WITH RESPECT TO PROVIDING AUTOWARE (the “Service”) +including but not limited to any representation or warranty (i) of fitness or +suitability for a particular purpose contemplated by the Users, (ii) of the +expected functions, commercial value, accuracy, or usefulness of the Service, +(iii) that the use by the Users of the Service complies with the laws and +regulations applicable to the Users or any internal rules established by +industrial organizations, (iv) that the Service will be free of interruption or +defects, (v) of the non-infringement of any third party's right and (vi) the +accuracy of the content of the Services and the software itself. + +2. The Autoware Foundation shall not be liable for any damage incurred by the +User that are attributable to the Autoware Foundation for any reasons +whatsoever. UNDER NO CIRCUMSTANCES SHALL THE AUTOWARE FOUNDATION BE LIABLE FOR +INCIDENTAL, INDIRECT, SPECIAL OR FUTURE DAMAGES OR LOSS OF PROFITS. + +3. A User shall be entirely responsible for the content posted by the User and +its use of any content of the Service or the Website. If the User is held +responsible in a civil action such as a claim for damages or even in a criminal +case, the Autoware Foundation and member companies, governments and academic & +non-profit organizations and their directors, officers, employees and agents +(collectively, the “Indemnified Parties”) shall be completely discharged from +any rights or assertions the User may have against the Indemnified Parties, or +from any legal action, litigation or similar procedures. + + +Indemnity + +A User shall indemnify and hold the Indemnified Parties harmless from any of +their damages, losses, liabilities, costs or expenses (including attorneys' +fees or criminal compensation), or any claims or demands made against the +Indemnified Parties by any third party, due to or arising out of, or in +connection with utilizing Autoware (including the representations and +warranties), the violation of applicable Product Liability Law of each country +(including criminal case) or violation of any applicable laws by the Users, or +the content posted by the User or its use of any content of the Service or the +Website. diff --git a/documentation/README.md b/documentation/README.md index 027b694548c..79b74855392 100644 --- a/documentation/README.md +++ b/documentation/README.md @@ -1,5 +1,7 @@ # Autoware Documentation +![Native CI workflow](https://github.com/Autoware-AI/documentation/workflows/Native%20CI%20workflow/badge.svg) + This repository contains documentation for Autoware as a project. Documentation specific to a particular package lives in that package's repository. Documentation for the whole project, such as tutorials and examples, lives here. diff --git a/documentation/SUPPORT.md b/documentation/SUPPORT.md index 54c7aaa50d9..44606e1ff3c 100644 --- a/documentation/SUPPORT.md +++ b/documentation/SUPPORT.md @@ -1,5 +1,3 @@ # Support -To get support for Autoware, see the support guidelines on the Autoware wiki: - -https://github.com/autowarefoundation/Autoware/wiki/Support-guidelines +For detailed instructions on getting help, see the [support guidelines](https://github.com/Autoware-AI/autoware.ai/wiki/Support-guidelines). diff --git a/documentation/autoware_quickstart_examples/README.md b/documentation/autoware_quickstart_examples/README.md index 0ad33cd0c72..8e4393ec099 100644 --- a/documentation/autoware_quickstart_examples/README.md +++ b/documentation/autoware_quickstart_examples/README.md @@ -41,13 +41,13 @@ $ roslaunch runtime_manager runtime_manager.launch 3. Go to the _Simulation_ tab of Autoware Runtime Manager (ARM), and load the sample ROSBAG data, which is located in `~/.autoware`. _Show Hidden Files_ needs to be checked for the `.autoware` folder to be displayed.

        - +

        4. Set the start time to `140`, then click _Play_ and _Pause_ just after it has started playing.

        - +

        5. Launch RViz through the _RViz_ button in the bottom-right corner of the ARM. @@ -55,12 +55,12 @@ $ roslaunch runtime_manager runtime_manager.launch 6. Go to the _Quick Start_ tab of ARM, and load the preinstalled roslaunch scripts one by one. The scripts are located in _Autoware/src/autoware/documentation/launch/rosbag_demo_. The scripts need to be enabled by clicking on the left button as shown in the image for the _Map_.

        - +

        Un-pausing the simulation after starting the _Map_ will show the pointcloud map in Rviz.

        - +

        diff --git a/documentation/autoware_quickstart_examples/launch/rosbag_demo/README.md b/documentation/autoware_quickstart_examples/launch/rosbag_demo/README.md index 6bba293bd96..8fc0ce98f98 100644 --- a/documentation/autoware_quickstart_examples/launch/rosbag_demo/README.md +++ b/documentation/autoware_quickstart_examples/launch/rosbag_demo/README.md @@ -1,4 +1,4 @@ # Quick Start -See [Demo](https://gitlab.com/autowarefoundation/autoware.ai/autoware/wikis/ROSBAG-Demo). +See [Demo](https://github.com/Autoware-AI/autoware.ai/wiki/ROSBAG-Demo). diff --git a/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_map.launch b/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_map.launch index df563073fd4..6423831174b 100644 --- a/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_map.launch +++ b/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_map.launch @@ -4,7 +4,11 @@ - + + +[$(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00167_-00864.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00153_-00852.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00159_-00859.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00160_-00861.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00148_-00849.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00168_-00866.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00147_-00851.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00149_-00847.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00156_-00854.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00158_-00858.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00147_-00847.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00154_-00852.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00158_-00857.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00154_-00851.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00167_-00866.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00168_-00865.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00169_-00868.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00147_-00849.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00153_-00850.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00154_-00853.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00161_-00861.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00168_-00867.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00151_-00849.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00153_-00851.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00152_-00850.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00150_-00848.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00156_-00856.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00167_-00865.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00157_-00856.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00148_-00848.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00152_-00851.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00156_-00855.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00168_-00868.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00161_-00860.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00159_-00857.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00150_-00847.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00164_-00863.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00157_-00857.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00162_-00861.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00151_-00850.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00165_-00864.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00149_-00848.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00155_-00852.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00160_-00859.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00163_-00861.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00160_-00858.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00158_-00856.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00155_-00854.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00160_-00860.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00159_-00858.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00147_-00850.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00148_-00847.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00163_-00862.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00151_-00848.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00155_-00853.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00152_-00849.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00149_-00846.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00166_-00865.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00147_-00846.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00167_-00867.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00165_-00863.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00166_-00864.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00155_-00855.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00162_-00862.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00150_-00846.pcd, $(env HOME)/.autoware/data/map/pointcloud_map/bin_Laser-00164_-00862.pcd] + + diff --git a/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_mission_planning.launch b/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_mission_planning.launch index c081099d340..5dd3eff28d3 100644 --- a/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_mission_planning.launch +++ b/documentation/autoware_quickstart_examples/launch/rosbag_demo/my_mission_planning.launch @@ -22,7 +22,7 @@ /> - + diff --git a/utilities/autoware_launcher/plugins/leaf/waypoint_loader.xml b/utilities/autoware_launcher/plugins/leaf/waypoint_loader.xml index eb1351fcb07..f7f7a0860e7 100644 --- a/utilities/autoware_launcher/plugins/leaf/waypoint_loader.xml +++ b/utilities/autoware_launcher/plugins/leaf/waypoint_loader.xml @@ -2,22 +2,17 @@ - - + - - - - @@ -25,6 +20,7 @@ + diff --git a/utilities/autoware_launcher/plugins/leaf/waypoint_loader.yaml b/utilities/autoware_launcher/plugins/leaf/waypoint_loader.yaml index 29e5aa29b8d..b98ab6f6060 100644 --- a/utilities/autoware_launcher/plugins/leaf/waypoint_loader.yaml +++ b/utilities/autoware_launcher/plugins/leaf/waypoint_loader.yaml @@ -7,16 +7,12 @@ args: - {name: velocity_min, type: real, default: 4.0} - {name: accel_limit, type: real, default: 0.5} - {name: decel_limit, type: real, default: 0.3} -- {name: radius_thresh, type: real, default: 20.0} +- {name: lateral_accel_limit, type: real, default: 2.0} - {name: radius_min, type: real, default: 6.0} - {name: resample_mode, type: bool, default: true} - {name: resample_interval, type: real, default: 1.0} -- {name: velocity_offset, type: int, default: 4} -- {name: end_point_offset, type: int, default: 1} -- {name: braking_distance, type: int, default: 5} - {name: replan_curve_mode, type: bool, default: false} - {name: replan_endpoint_mode, type: bool, default: true} -- {name: overwrite_vmax_mode, type: bool, default: false} - {name: realtime_tuning_mode, type: bool, default: false} panel: @@ -29,14 +25,11 @@ panel: - {target: args.velocity_min, widget: basic.real} - {target: args.accel_limit, widget: basic.real} - {target: args.decel_limit, widget: basic.real} - - {target: args.radius_thresh, widget: basic.real} + - {target: args.lateral_accel_limit, widget: basic.real} - {target: args.radius_min, widget: basic.real} - {target: args.resample_mode, widget: basic.bool} - {target: args.resample_interval, widget: basic.real} - - {target: args.velocity_offset, widget: basic.int} - - {target: args.end_point_offset, widget: basic.int} - - {target: args.braking_distance, widget: basic.int} - {target: args.replan_curve_mode, widget: basic.bool} - {target: args.replan_endpoint_mode, widget: basic.bool} - - {target: args.overwrite_vmax_mode, widget: basic.bool} - {target: args.realtime_tuning_mode, widget: basic.bool} + \ No newline at end of file diff --git a/utilities/calibration_publisher/CMakeLists.txt b/utilities/calibration_publisher/CMakeLists.txt index 6c09da7778a..2f0cf4f1e5a 100644 --- a/utilities/calibration_publisher/CMakeLists.txt +++ b/utilities/calibration_publisher/CMakeLists.txt @@ -2,53 +2,45 @@ cmake_minimum_required(VERSION 2.8.3) project(calibration_publisher) find_package(autoware_build_flags REQUIRED) - -find_package(autoware_msgs REQUIRED) find_package(catkin REQUIRED COMPONENTS - roscpp - std_msgs - sensor_msgs - cv_bridge - image_transport - autoware_msgs - tf - ) + autoware_msgs + cv_bridge + geometry_msgs + image_transport + roscpp + sensor_msgs + std_msgs + tf2 + tf2_geometry_msgs + tf2_ros +) find_package(OpenCV REQUIRED) -catkin_package( - CATKIN_DEPENDS - roscpp - std_msgs - sensor_msgs - cv_bridge - image_transport - autoware_msgs - tf -) +catkin_package() include_directories( - ${catkin_INCLUDE_DIRS} - ${OpenCV_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} ) add_executable(calibration_publisher - src/calibration_publisher.cpp - ) + src/calibration_publisher.cpp +) add_dependencies(calibration_publisher - ${catkin_EXPORTED_TARGETS} - ) + ${catkin_EXPORTED_TARGETS} +) target_link_libraries(calibration_publisher - ${catkin_LIBRARIES} - ) + ${catkin_LIBRARIES} +) install(TARGETS calibration_publisher - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) # Mark cpp header files for installation install(DIRECTORY include/${PROJECT_NAME}/ diff --git a/utilities/calibration_publisher/package.xml b/utilities/calibration_publisher/package.xml index 52ffd2a3899..6dba7059616 100644 --- a/utilities/calibration_publisher/package.xml +++ b/utilities/calibration_publisher/package.xml @@ -13,9 +13,12 @@ autoware_msgs cv_bridge + geometry_msgs image_transport roscpp sensor_msgs std_msgs - tf + tf2_geometry_msgs + tf2_ros + tf2 diff --git a/utilities/calibration_publisher/src/calibration_publisher.cpp b/utilities/calibration_publisher/src/calibration_publisher.cpp index b9a1765485e..df7b148b6a5 100644 --- a/utilities/calibration_publisher/src/calibration_publisher.cpp +++ b/utilities/calibration_publisher/src/calibration_publisher.cpp @@ -16,8 +16,10 @@ */ #include #include -#include -#include +#include +#include +#include +#include #include #include #include @@ -46,31 +48,26 @@ static bool extrinsics_parsed_; static sensor_msgs::CameraInfo camera_info_msg_; static autoware_msgs::ProjectionMatrix extrinsic_matrix_msg_; -void tfRegistration(const cv::Mat &camExtMat, const ros::Time &timeStamp) +void tfRegistration(const cv::Mat &camExtMat) { - tf::Matrix3x3 rotation_mat; - double roll = 0, pitch = 0, yaw = 0; - tf::Quaternion quaternion; - tf::Transform transform; - static tf::TransformBroadcaster broadcaster; + static tf2_ros::StaticTransformBroadcaster broadcaster; + tf2::Vector3 origin(camExtMat.at(0, 3), camExtMat.at(1, 3), camExtMat.at(2, 3)); + tf2::Matrix3x3 rotation_mat; rotation_mat.setValue(camExtMat.at(0, 0), camExtMat.at(0, 1), camExtMat.at(0, 2), camExtMat.at(1, 0), camExtMat.at(1, 1), camExtMat.at(1, 2), camExtMat.at(2, 0), camExtMat.at(2, 1), camExtMat.at(2, 2)); - rotation_mat.getRPY(roll, pitch, yaw, 1); + tf2::Transform transform(rotation_mat, origin); - quaternion.setRPY(roll, pitch, yaw); - - transform.setOrigin( - tf::Vector3(camExtMat.at(0, 3), camExtMat.at(1, 3), camExtMat.at(2, 3))); - - transform.setRotation(quaternion); - - broadcaster.sendTransform(tf::StampedTransform(transform, timeStamp, target_frame_, camera_frame_)); + geometry_msgs::TransformStamped output_tf_msg; + output_tf_msg.header.frame_id = target_frame_; + output_tf_msg.child_frame_id = camera_frame_; + tf2::convert(transform, output_tf_msg.transform); + broadcaster.sendTransform(output_tf_msg); } -void projectionMatrix_sender(const cv::Mat &projMat, const ros::Time &timeStamp) +void projectionMatrix_sender(const cv::Mat &projMat) { if (!extrinsics_parsed_) { @@ -83,7 +80,7 @@ void projectionMatrix_sender(const cv::Mat &projMat, const ros::Time &timeStamp) } extrinsics_parsed_ = true; } - extrinsic_matrix_msg_.header.stamp = timeStamp; + extrinsic_matrix_msg_.header.stamp = ros::Time::now(); extrinsic_matrix_msg_.header.frame_id = camera_frame_; projection_matrix_pub.publish(extrinsic_matrix_msg_); } @@ -137,26 +134,14 @@ void cameraInfo_sender(const cv::Mat &camMat, const cv::Mat &distCoeff, const cv static void image_raw_cb(const sensor_msgs::Image &image_msg) { - // ros::Time timeStampOfImage = image_msg.header.stamp; - ros::Time timeStampOfImage; timeStampOfImage.sec = image_msg.header.stamp.sec; timeStampOfImage.nsec = image_msg.header.stamp.nsec; - /* create TF between velodyne and camera with time stamp of /image_raw */ - if (isRegister_tf) - { - tfRegistration(CameraExtrinsicMat, timeStampOfImage); - } - if (isPublish_cameraInfo) { cameraInfo_sender(CameraMat, DistCoeff, ImageSize, DistModel, timeStampOfImage); } - if (isPublish_extrinsic) - { - projectionMatrix_sender(CameraExtrinsicMat, timeStampOfImage); - } } int main(int argc, char *argv[]) @@ -192,6 +177,7 @@ int main(int argc, char *argv[]) std::string calibration_file; private_nh.param("calibration_file", calibration_file, ""); ROS_INFO("[%s] calibration_file: '%s'", __APP_NAME__, calibration_file.c_str()); + if (calibration_file.empty()) { ROS_ERROR("[%s] Missing calibration file path '%s'.", __APP_NAME__, calibration_file.c_str()); @@ -230,7 +216,7 @@ int main(int argc, char *argv[]) extrinsics_parsed_ = false; std::string name_space_str = ros::this_node::getNamespace(); - + ros::Subscriber image_sub; image_sub = n.subscribe(image_topic_name, 10, image_raw_cb); @@ -239,7 +225,21 @@ int main(int argc, char *argv[]) projection_matrix_pub = n.advertise(projection_matrix_topic, 10, true); + /* Static TF between velodyne and camera */ + if (isRegister_tf) + { + tfRegistration(CameraExtrinsicMat); + } + + /* Autoware extrinsic matrix (Same information as the static TF) */ + /* TODO: Remove this code duplication, subscribing nodes should instead use TF */ + if (isPublish_extrinsic) + { + projectionMatrix_sender(CameraExtrinsicMat); + } + ros::spin(); return 0; } + diff --git a/utilities/data_preprocessor/nodes/get_Depth/get_Depth.cpp b/utilities/data_preprocessor/nodes/get_Depth/get_Depth.cpp index 468e2285667..354bdb8ed33 100644 --- a/utilities/data_preprocessor/nodes/get_Depth/get_Depth.cpp +++ b/utilities/data_preprocessor/nodes/get_Depth/get_Depth.cpp @@ -166,8 +166,8 @@ void SaveDepth::create_depth(){ // cout << "ok1" << endl; cv::minMaxLoc(depth, &min, &max); // cout << "ok2 " << max << endl; - for (int w; w(h, w) != 0){ depth.at(h, w) = depth.at(h, w) / max; } diff --git a/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_receiver.cpp b/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_receiver.cpp index d48cf6e1634..dcc089bb3c7 100644 --- a/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_receiver.cpp +++ b/utilities/mqtt_socket/nodes/mqtt_receiver/mqtt_receiver.cpp @@ -143,7 +143,7 @@ static void MqttReceiver::on_message(struct mosquitto *mosq, void *obj, const st msg.vehicle_cmd.steer_cmd.steer = stof(cmds[0]) * steer_max_val; msg.vehicle_cmd.accel_cmd.accel = stof(cmds[1]) * accel_max_val; msg.vehicle_cmd.brake_cmd.brake = stof(cmds[2]) * brake_max_val; - msg.vehicle_cmd.gear = stoi(cmds[3]); + msg.vehicle_cmd.gear_cmd.gear = stoi(cmds[3]); // lamp switch(stoi(cmds[4])) { msg.vehicle_cmd.lamp_cmd.l = 0; diff --git a/utilities/multi_lidar_calibrator/CMakeLists.txt b/utilities/multi_lidar_calibrator/CMakeLists.txt index d49eb3e56aa..9b0e6086a1c 100644 --- a/utilities/multi_lidar_calibrator/CMakeLists.txt +++ b/utilities/multi_lidar_calibrator/CMakeLists.txt @@ -1,65 +1,57 @@ cmake_minimum_required(VERSION 2.8.12) project(multi_lidar_calibrator) - find_package(autoware_build_flags REQUIRED) find_package(catkin REQUIRED COMPONENTS - roscpp - std_msgs - sensor_msgs - geometry_msgs - pcl_ros - pcl_conversions - ) + geometry_msgs + pcl_conversions + pcl_ros + roscpp + sensor_msgs + std_msgs +) -catkin_package(CATKIN_DEPENDS - std_msgs - sensor_msgs - geometry_msgs - ) +catkin_package() find_package(OpenCV REQUIRED) -########### -## Build ## -########### - include_directories( - ${catkin_INCLUDE_DIRS} - include + include + ${catkin_INCLUDE_DIRS} ) SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") # MultiLidar Calibrator add_library(multi_lidar_calibrator_lib SHARED - src/multi_lidar_calibrator.cpp - include/multi_lidar_calibrator.h) + src/multi_lidar_calibrator.cpp +) target_include_directories(multi_lidar_calibrator_lib PRIVATE - ${OpenCV_INCLUDE_DIRS} - ) + ${OpenCV_INCLUDE_DIRS} +) target_link_libraries(multi_lidar_calibrator_lib - ${catkin_LIBRARIES} - ) + ${catkin_LIBRARIES} +) add_executable(multi_lidar_calibrator - src/multi_lidar_calibrator_node.cpp - ) - -target_include_directories(multi_lidar_calibrator PRIVATE - include) + src/multi_lidar_calibrator_node.cpp +) target_link_libraries(multi_lidar_calibrator - multi_lidar_calibrator_lib) + multi_lidar_calibrator_lib +) -install(TARGETS - multi_lidar_calibrator multi_lidar_calibrator_lib - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +install( + TARGETS + multi_lidar_calibrator + multi_lidar_calibrator_lib + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) \ No newline at end of file + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/utilities/multi_lidar_calibrator/README.md b/utilities/multi_lidar_calibrator/README.md index ceeff153f68..717d713fffa 100644 --- a/utilities/multi_lidar_calibrator/README.md +++ b/utilities/multi_lidar_calibrator/README.md @@ -17,7 +17,7 @@ Using rosrun Using roslaunch -`roslaunch multi_lidar_calibrator multi_lidar_calibrator points_child_src:=/lidar_child/points_raw points_parent_src:=/lidar_parent/points_raw x:=0.0 y:=0.0 z:=0.0 roll:=0.0 pitch:=0.0 yaw:=0.0` +`roslaunch multi_lidar_calibrator multi_lidar_calibrator.launch points_child_src:=/lidar_child/points_raw points_parent_src:=/lidar_parent/points_raw x:=0.0 y:=0.0 z:=0.0 roll:=0.0 pitch:=0.0 yaw:=0.0` 3. Play a rosbag with both lidar data `/lidar_child/points_raw` and `/lidar_parent/points_raw` @@ -49,7 +49,7 @@ Using roslaunch ## Output -1. Child Point cloud transformed to the Parent frame and published in `/points_calibrated`. +1. Child Point cloud transformed to the Parent frame and published in `/points_calibrated`. 1. Output in the terminal showing the X,Y,Z,Yaw,Pitch,Roll transformation between child and parent. These values can be used later with the `static_transform_publisher`. @@ -65,4 +65,4 @@ The figure below shows two lidar sensors calibrated by this node. One is shown in gray while the other is show in blue. Image obtained from rviz. -![Calibration Result](doc/calibration_result.jpg) \ No newline at end of file +![Calibration Result](doc/calibration_result.jpg) diff --git a/utilities/multi_lidar_calibrator/include/multi_lidar_calibrator.h b/utilities/multi_lidar_calibrator/include/multi_lidar_calibrator.h index c1bf7014494..030075b2d47 100644 --- a/utilities/multi_lidar_calibrator/include/multi_lidar_calibrator.h +++ b/utilities/multi_lidar_calibrator/include/multi_lidar_calibrator.h @@ -51,77 +51,77 @@ class ROSMultiLidarCalibratorApp { - ros::NodeHandle node_handle_; - ros::Publisher calibrated_cloud_publisher_; + ros::NodeHandle node_handle_; + ros::Publisher calibrated_cloud_publisher_; - ros::Subscriber initialpose_subscriber_; + ros::Subscriber initialpose_subscriber_; - double voxel_size_; - double ndt_epsilon_; - double ndt_step_size_; - double ndt_resolution_; + double voxel_size_; + double ndt_epsilon_; + double ndt_step_size_; + double ndt_resolution_; - double initial_x_; - double initial_y_; - double initial_z_; - double initial_roll_; - double initial_pitch_; - double initial_yaw_; + double initial_x_; + double initial_y_; + double initial_z_; + double initial_roll_; + double initial_pitch_; + double initial_yaw_; - int ndt_iterations_; + int ndt_iterations_; - //tf::Quaternion initialpose_quaternion_; - //tf::Vector3 initialpose_position_; + //tf::Quaternion initialpose_quaternion_; + //tf::Vector3 initialpose_position_; - std::string parent_frame_; - std::string child_frame_; + std::string parent_frame_; + std::string child_frame_; - Eigen::Matrix4f current_guess_; + Eigen::Matrix4f current_guess_; - typedef - message_filters::sync_policies::ApproximateTime SyncPolicyT; + typedef + message_filters::sync_policies::ApproximateTime SyncPolicyT; - typedef pcl::PointXYZI PointT; + typedef pcl::PointXYZI PointT; - message_filters::Subscriber *cloud_parent_subscriber_, *cloud_child_subscriber_; - message_filters::Synchronizer *cloud_synchronizer_; + message_filters::Subscriber *cloud_parent_subscriber_, *cloud_child_subscriber_; + message_filters::Synchronizer *cloud_synchronizer_; - /*! - * Receives 2 synchronized point cloud messages. - * @param[in] in_parent_cloud_msg Message containing pointcloud classified as ground. - * @param[in] in_child_cloud_msg Message containing pointcloud classified as obstacle. - */ - void PointsCallback(const sensor_msgs::PointCloud2::ConstPtr& in_parent_cloud_msg, - const sensor_msgs::PointCloud2::ConstPtr& in_child_cloud_msg); + /*! + * Receives 2 synchronized point cloud messages. + * @param[in] in_parent_cloud_msg Message containing pointcloud classified as ground. + * @param[in] in_child_cloud_msg Message containing pointcloud classified as obstacle. + */ + void PointsCallback(const sensor_msgs::PointCloud2::ConstPtr& in_parent_cloud_msg, + const sensor_msgs::PointCloud2::ConstPtr& in_child_cloud_msg); - //void InitialPoseCallback(geometry_msgs::PoseWithCovarianceStamped::ConstPtr in_initialpose); + //void InitialPoseCallback(geometry_msgs::PoseWithCovarianceStamped::ConstPtr in_initialpose); - /*! - * Obtains parameters from the command line, initializes subscribers and publishers. - * @param in_private_handle ROS private handle to get parameters for this node. - */ - void InitializeROSIo(ros::NodeHandle& in_private_handle); + /*! + * Obtains parameters from the command line, initializes subscribers and publishers. + * @param in_private_handle ROS private handle to get parameters for this node. + */ + void InitializeROSIo(ros::NodeHandle& in_private_handle); - /*! - * Applies a Voxel Grid filter to the point cloud - * @param in_cloud_ptr point cloud to downsample - * @param out_cloud_ptr downsampled point cloud - * @param in_leaf_size voxel side size - */ - void DownsampleCloud(pcl::PointCloud::ConstPtr in_cloud_ptr, pcl::PointCloud::Ptr out_cloud_ptr, double in_leaf_size); + /*! + * Applies a Voxel Grid filter to the point cloud + * @param in_cloud_ptr point cloud to downsample + * @param out_cloud_ptr downsampled point cloud + * @param in_leaf_size voxel side size + */ + void DownsampleCloud(pcl::PointCloud::ConstPtr in_cloud_ptr, pcl::PointCloud::Ptr out_cloud_ptr, double in_leaf_size); - /*! - * Publishes a PointCloud in the specified publisher - * @param in_publisher Publisher to use - * @param in_cloud_to_publish_ptr Cloud to Publish - */ - void PublishCloud(const ros::Publisher& in_publisher, pcl::PointCloud::ConstPtr in_cloud_to_publish_ptr); + /*! + * Publishes a PointCloud in the specified publisher + * @param in_publisher Publisher to use + * @param in_cloud_to_publish_ptr Cloud to Publish + */ + void PublishCloud(const ros::Publisher& in_publisher, pcl::PointCloud::ConstPtr in_cloud_to_publish_ptr); public: - void Run(); + void Run(); - ROSMultiLidarCalibratorApp(); + ROSMultiLidarCalibratorApp(); }; #endif //PROJECT_MULTI_LIDAR_CALIBRATOR_H diff --git a/utilities/multi_lidar_calibrator/launch/multi_lidar_calibrator.launch b/utilities/multi_lidar_calibrator/launch/multi_lidar_calibrator.launch index a5e81245689..1c7623a844b 100644 --- a/utilities/multi_lidar_calibrator/launch/multi_lidar_calibrator.launch +++ b/utilities/multi_lidar_calibrator/launch/multi_lidar_calibrator.launch @@ -1,32 +1,31 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator.cpp b/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator.cpp index 4c8d40bdce7..fab9181fc90 100644 --- a/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator.cpp +++ b/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator.cpp @@ -25,99 +25,99 @@ void ROSMultiLidarCalibratorApp::PublishCloud(const ros::Publisher& in_publisher, pcl::PointCloud::ConstPtr in_cloud_to_publish_ptr) { - sensor_msgs::PointCloud2 cloud_msg; - pcl::toROSMsg(*in_cloud_to_publish_ptr, cloud_msg); - cloud_msg.header.frame_id = parent_frame_; - in_publisher.publish(cloud_msg); + sensor_msgs::PointCloud2 cloud_msg; + pcl::toROSMsg(*in_cloud_to_publish_ptr, cloud_msg); + cloud_msg.header.frame_id = parent_frame_; + in_publisher.publish(cloud_msg); } void ROSMultiLidarCalibratorApp::PointsCallback(const sensor_msgs::PointCloud2::ConstPtr &in_parent_cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &in_child_cloud_msg) { - pcl::PointCloud::Ptr in_parent_cloud(new pcl::PointCloud); - pcl::PointCloud::Ptr in_child_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr in_parent_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr in_child_cloud(new pcl::PointCloud); - pcl::PointCloud::Ptr child_filtered_cloud (new pcl::PointCloud); + pcl::PointCloud::Ptr child_filtered_cloud (new pcl::PointCloud); - pcl::fromROSMsg(*in_parent_cloud_msg, *in_parent_cloud); - pcl::fromROSMsg(*in_child_cloud_msg, *in_child_cloud); + pcl::fromROSMsg(*in_parent_cloud_msg, *in_parent_cloud); + pcl::fromROSMsg(*in_child_cloud_msg, *in_child_cloud); - parent_frame_ = in_parent_cloud_msg->header.frame_id; - child_frame_ = in_child_cloud_msg->header.frame_id; + parent_frame_ = in_parent_cloud_msg->header.frame_id; + child_frame_ = in_child_cloud_msg->header.frame_id; - DownsampleCloud(in_child_cloud, child_filtered_cloud, voxel_size_); + DownsampleCloud(in_child_cloud, child_filtered_cloud, voxel_size_); - // Initializing Normal Distributions Transform (NDT). - pcl::NormalDistributionsTransform ndt; + // Initializing Normal Distributions Transform (NDT). + pcl::NormalDistributionsTransform ndt; - ndt.setTransformationEpsilon(ndt_epsilon_); - ndt.setStepSize(ndt_step_size_); - ndt.setResolution(ndt_resolution_); + ndt.setTransformationEpsilon(ndt_epsilon_); + ndt.setStepSize(ndt_step_size_); + ndt.setResolution(ndt_resolution_); - ndt.setMaximumIterations(ndt_iterations_); + ndt.setMaximumIterations(ndt_iterations_); - ndt.setInputSource(child_filtered_cloud); - ndt.setInputTarget(in_parent_cloud); + ndt.setInputSource(child_filtered_cloud); + ndt.setInputTarget(in_parent_cloud); - pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); - Eigen::Translation3f init_translation(initial_x_, initial_y_, initial_z_); - Eigen::AngleAxisf init_rotation_x(initial_roll_, Eigen::Vector3f::UnitX()); - Eigen::AngleAxisf init_rotation_y(initial_pitch_, Eigen::Vector3f::UnitY()); - Eigen::AngleAxisf init_rotation_z(initial_yaw_, Eigen::Vector3f::UnitZ()); + Eigen::Translation3f init_translation(initial_x_, initial_y_, initial_z_); + Eigen::AngleAxisf init_rotation_x(initial_roll_, Eigen::Vector3f::UnitX()); + Eigen::AngleAxisf init_rotation_y(initial_pitch_, Eigen::Vector3f::UnitY()); + Eigen::AngleAxisf init_rotation_z(initial_yaw_, Eigen::Vector3f::UnitZ()); - Eigen::Matrix4f init_guess_ = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x).matrix(); + Eigen::Matrix4f init_guess_ = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x).matrix(); - if(current_guess_ == Eigen::Matrix4f::Identity()) - { - current_guess_ = init_guess_; - } + if(current_guess_ == Eigen::Matrix4f::Identity()) + { + current_guess_ = init_guess_; + } - ndt.align(*output_cloud, current_guess_); + ndt.align(*output_cloud, current_guess_); - std::cout << "Normal Distributions Transform converged:" << ndt.hasConverged () - << " score: " << ndt.getFitnessScore () << " prob:" << ndt.getTransformationProbability() << std::endl; + std::cout << "Normal Distributions Transform converged:" << ndt.hasConverged () + << " score: " << ndt.getFitnessScore () << " prob:" << ndt.getTransformationProbability() << std::endl; - std::cout << "transformation from " << child_frame_ << " to " << parent_frame_ << std::endl; + std::cout << "transformation from " << child_frame_ << " to " << parent_frame_ << std::endl; - // Transforming unfiltered, input cloud using found transform. - pcl::transformPointCloud (*in_child_cloud, *output_cloud, ndt.getFinalTransformation()); + // Transforming unfiltered, input cloud using found transform. + pcl::transformPointCloud (*in_child_cloud, *output_cloud, ndt.getFinalTransformation()); - current_guess_ = ndt.getFinalTransformation(); + current_guess_ = ndt.getFinalTransformation(); - Eigen::Matrix3f rotation_matrix = current_guess_.block(0,0,3,3); - Eigen::Vector3f translation_vector = current_guess_.block(0,3,3,1); - std::cout << "This transformation can be replicated using:" << std::endl; - std::cout << "rosrun tf static_transform_publisher " << translation_vector.transpose() - << " " << rotation_matrix.eulerAngles(2,1,0).transpose() << " /" << parent_frame_ - << " /" << child_frame_ << " 10" << std::endl; + Eigen::Matrix3f rotation_matrix = current_guess_.block(0,0,3,3); + Eigen::Vector3f translation_vector = current_guess_.block(0,3,3,1); + std::cout << "This transformation can be replicated using:" << std::endl; + std::cout << "rosrun tf static_transform_publisher " << translation_vector.transpose() + << " " << rotation_matrix.eulerAngles(2,1,0).transpose() << " /" << parent_frame_ + << " /" << child_frame_ << " 10" << std::endl; - std::cout << "Corresponding transformation matrix:" << std::endl - << std::endl << current_guess_ << std::endl << std::endl; + std::cout << "Corresponding transformation matrix:" << std::endl + << std::endl << current_guess_ << std::endl << std::endl; - PublishCloud(calibrated_cloud_publisher_, output_cloud); - // timer end - //auto end = std::chrono::system_clock::now(); - //auto usec = std::chrono::duration_cast(end - start).count(); - //std::cout << "time: " << usec / 1000.0 << " [msec]" << std::endl; + PublishCloud(calibrated_cloud_publisher_, output_cloud); + // timer end + //auto end = std::chrono::system_clock::now(); + //auto usec = std::chrono::duration_cast(end - start).count(); + //std::cout << "time: " << usec / 1000.0 << " [msec]" << std::endl; } /*void ROSMultiLidarCalibratorApp::InitialPoseCallback(geometry_msgs::PoseWithCovarianceStamped::ConstPtr in_initialpose) { - ROS_INFO("[%s] Initial Pose received.", __APP_NAME__); - tf::Quaternion pose_quaternion(in_initialpose->pose.pose.orientation.x, - in_initialpose->pose.pose.orientation.y, - in_initialpose->pose.pose.orientation.z, - in_initialpose->pose.pose.orientation.w); + ROS_INFO("[%s] Initial Pose received.", __APP_NAME__); + tf::Quaternion pose_quaternion(in_initialpose->pose.pose.orientation.x, + in_initialpose->pose.pose.orientation.y, + in_initialpose->pose.pose.orientation.z, + in_initialpose->pose.pose.orientation.w); - //rotation - initialpose_quaternion_ = pose_quaternion; + //rotation + initialpose_quaternion_ = pose_quaternion; - //translation - initialpose_position_.setX(in_initialpose->pose.pose.position.x); - initialpose_position_.setY(in_initialpose->pose.pose.position.y); - initialpose_position_.setZ(in_initialpose->pose.pose.position.z); + //translation + initialpose_position_.setX(in_initialpose->pose.pose.position.x); + initialpose_position_.setY(in_initialpose->pose.pose.position.y); + initialpose_position_.setZ(in_initialpose->pose.pose.position.z); }*/ @@ -126,91 +126,91 @@ void ROSMultiLidarCalibratorApp::DownsampleCloud(pcl::PointCloud::ConstP pcl::PointCloud::Ptr out_cloud_ptr, double in_leaf_size) { - pcl::VoxelGrid voxelized; - voxelized.setInputCloud(in_cloud_ptr); - voxelized.setLeafSize((float)in_leaf_size, (float)in_leaf_size, (float)in_leaf_size); - voxelized.filter(*out_cloud_ptr); + pcl::VoxelGrid voxelized; + voxelized.setInputCloud(in_cloud_ptr); + voxelized.setLeafSize((float)in_leaf_size, (float)in_leaf_size, (float)in_leaf_size); + voxelized.filter(*out_cloud_ptr); } void ROSMultiLidarCalibratorApp::InitializeROSIo(ros::NodeHandle &in_private_handle) { - //get params - std::string points_parent_topic_str, points_child_topic_str; - std::string initial_pose_topic_str = "/initialpose"; - std::string calibrated_points_topic_str = "/points_calibrated"; + //get params + std::string points_parent_topic_str, points_child_topic_str; + std::string initial_pose_topic_str = "/initialpose"; + std::string calibrated_points_topic_str = "/points_calibrated"; - in_private_handle.param("points_parent_src", points_parent_topic_str, "points_raw"); - ROS_INFO("[%s] points_parent_src: %s",__APP_NAME__, points_parent_topic_str.c_str()); + in_private_handle.param("points_parent_src", points_parent_topic_str, "points_raw"); + ROS_INFO("[%s] points_parent_src: %s",__APP_NAME__, points_parent_topic_str.c_str()); - in_private_handle.param("points_child_src", points_child_topic_str, "points_raw"); - ROS_INFO("[%s] points_child_src: %s",__APP_NAME__, points_child_topic_str.c_str()); + in_private_handle.param("points_child_src", points_child_topic_str, "points_raw"); + ROS_INFO("[%s] points_child_src: %s",__APP_NAME__, points_child_topic_str.c_str()); - in_private_handle.param("voxel_size", voxel_size_, 0.1); - ROS_INFO("[%s] ndt_epsilon: %.2f",__APP_NAME__, voxel_size_); + in_private_handle.param("voxel_size", voxel_size_, 0.1); + ROS_INFO("[%s] ndt_epsilon: %.2f",__APP_NAME__, voxel_size_); - in_private_handle.param("ndt_epsilon", ndt_epsilon_, 0.01); - ROS_INFO("[%s] voxel_size: %.2f",__APP_NAME__, ndt_epsilon_); + in_private_handle.param("ndt_epsilon", ndt_epsilon_, 0.01); + ROS_INFO("[%s] voxel_size: %.2f",__APP_NAME__, ndt_epsilon_); - in_private_handle.param("ndt_step_size", ndt_step_size_, 0.1); - ROS_INFO("[%s] ndt_step_size: %.2f",__APP_NAME__, ndt_step_size_); + in_private_handle.param("ndt_step_size", ndt_step_size_, 0.1); + ROS_INFO("[%s] ndt_step_size: %.2f",__APP_NAME__, ndt_step_size_); - in_private_handle.param("ndt_resolution", ndt_resolution_, 1.0); - ROS_INFO("[%s] ndt_resolution: %.2f",__APP_NAME__, ndt_resolution_); + in_private_handle.param("ndt_resolution", ndt_resolution_, 1.0); + ROS_INFO("[%s] ndt_resolution: %.2f",__APP_NAME__, ndt_resolution_); - in_private_handle.param("ndt_iterations", ndt_iterations_, 400); - ROS_INFO("[%s] ndt_iterations: %d",__APP_NAME__, ndt_iterations_); + in_private_handle.param("ndt_iterations", ndt_iterations_, 400); + ROS_INFO("[%s] ndt_iterations: %d",__APP_NAME__, ndt_iterations_); - in_private_handle.param("x", initial_x_, 0.0); - in_private_handle.param("y", initial_y_, 0.0); - in_private_handle.param("z", initial_z_, 0.0); - in_private_handle.param("roll", initial_roll_, 0.0); - in_private_handle.param("pitch", initial_pitch_, 0.0); - in_private_handle.param("yaw", initial_yaw_, 0.0); + in_private_handle.param("x", initial_x_, 0.0); + in_private_handle.param("y", initial_y_, 0.0); + in_private_handle.param("z", initial_z_, 0.0); + in_private_handle.param("roll", initial_roll_, 0.0); + in_private_handle.param("pitch", initial_pitch_, 0.0); + in_private_handle.param("yaw", initial_yaw_, 0.0); - ROS_INFO("[%s] Initialization Transform x: %.2f y: %.2f z: %.2f roll: %.2f pitch: %.2f yaw: %.2f", __APP_NAME__, - initial_x_, initial_y_, initial_z_, - initial_roll_, initial_pitch_, initial_yaw_); + ROS_INFO("[%s] Initialization Transform x: %.2f y: %.2f z: %.2f roll: %.2f pitch: %.2f yaw: %.2f", __APP_NAME__, + initial_x_, initial_y_, initial_z_, + initial_roll_, initial_pitch_, initial_yaw_); - //generate subscribers and synchronizer - cloud_parent_subscriber_ = new message_filters::Subscriber(node_handle_, - points_parent_topic_str, 10); - ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_parent_topic_str.c_str()); + //generate subscribers and synchronizer + cloud_parent_subscriber_ = new message_filters::Subscriber(node_handle_, + points_parent_topic_str, 10); + ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_parent_topic_str.c_str()); - cloud_child_subscriber_ = new message_filters::Subscriber(node_handle_, - points_child_topic_str, 10); - ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_child_topic_str.c_str()); + cloud_child_subscriber_ = new message_filters::Subscriber(node_handle_, + points_child_topic_str, 10); + ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_child_topic_str.c_str()); - /*initialpose_subscriber_ = node_handle_.subscribe(initial_pose_topic_str, 10, - &ROSMultiLidarCalibratorApp::InitialPoseCallback, this); - ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, initial_pose_topic_str.c_str());*/ + /*initialpose_subscriber_ = node_handle_.subscribe(initial_pose_topic_str, 10, + &ROSMultiLidarCalibratorApp::InitialPoseCallback, this); + ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, initial_pose_topic_str.c_str());*/ - calibrated_cloud_publisher_ = node_handle_.advertise(calibrated_points_topic_str, 1); - ROS_INFO("[%s] Publishing PointCloud to... %s",__APP_NAME__, calibrated_points_topic_str.c_str()); + calibrated_cloud_publisher_ = node_handle_.advertise(calibrated_points_topic_str, 1); + ROS_INFO("[%s] Publishing PointCloud to... %s",__APP_NAME__, calibrated_points_topic_str.c_str()); - cloud_synchronizer_ = - new message_filters::Synchronizer(SyncPolicyT(100), - *cloud_parent_subscriber_, - *cloud_child_subscriber_); - cloud_synchronizer_->registerCallback(boost::bind(&ROSMultiLidarCalibratorApp::PointsCallback, this, _1, _2)); + cloud_synchronizer_ = + new message_filters::Synchronizer(SyncPolicyT(100), + *cloud_parent_subscriber_, + *cloud_child_subscriber_); + cloud_synchronizer_->registerCallback(boost::bind(&ROSMultiLidarCalibratorApp::PointsCallback, this, _1, _2)); } void ROSMultiLidarCalibratorApp::Run() { - ros::NodeHandle private_node_handle("~"); + ros::NodeHandle private_node_handle("~"); - InitializeROSIo(private_node_handle); + InitializeROSIo(private_node_handle); - ROS_INFO("[%s] Ready. Waiting for data...",__APP_NAME__); + ROS_INFO("[%s] Ready. Waiting for data...",__APP_NAME__); - ros::spin(); + ros::spin(); - ROS_INFO("[%s] END",__APP_NAME__); + ROS_INFO("[%s] END",__APP_NAME__); } ROSMultiLidarCalibratorApp::ROSMultiLidarCalibratorApp() { - //initialpose_quaternion_ = tf::Quaternion::getIdentity(); - current_guess_ = Eigen::Matrix4f::Identity(); + //initialpose_quaternion_ = tf::Quaternion::getIdentity(); + current_guess_ = Eigen::Matrix4f::Identity(); } \ No newline at end of file diff --git a/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator_node.cpp b/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator_node.cpp index 199a5b2f6da..639c73987ba 100644 --- a/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator_node.cpp +++ b/utilities/multi_lidar_calibrator/src/multi_lidar_calibrator_node.cpp @@ -24,11 +24,11 @@ int main(int argc, char **argv) { - ros::init(argc, argv, __APP_NAME__); + ros::init(argc, argv, __APP_NAME__); - ROSMultiLidarCalibratorApp app; + ROSMultiLidarCalibratorApp app; - app.Run(); + app.Run(); - return 0; + return 0; } diff --git a/utilities/runtime_manager/CMakeLists.txt b/utilities/runtime_manager/CMakeLists.txt index 67308c2420e..a206ec41648 100644 --- a/utilities/runtime_manager/CMakeLists.txt +++ b/utilities/runtime_manager/CMakeLists.txt @@ -2,107 +2,112 @@ cmake_minimum_required(VERSION 2.8.3) project(runtime_manager) find_package(catkin REQUIRED COMPONENTS - rospy autoware_msgs autoware_config_msgs tablet_socket_msgs std_msgs - ) - -catkin_package( - CATKIN_DEPENDS rospy autoware_msgs autoware_config_msgs tablet_socket_msgs std_msgs + autoware_config_msgs + autoware_msgs + rospy + std_msgs + tablet_socket_msgs ) -catkin_install_python(PROGRAMS - scripts/ftrace.py - scripts/proc_manager.py - scripts/rtmgr.py - scripts/runtime_manager_dialog.py - scripts/test_pub.py - scripts/test_srv.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(PROGRAMS - scripts/3dm_gx5_15.sh - scripts/add_perm.sh - scripts/adis16470.sh - scripts/avt_vimba.sh - scripts/gazebo.sh - scripts/mti300.sh - scripts/vg440.sh - scripts/cleanup - scripts/run - scripts/run_proc_manager - scripts/subnet_chk.py - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts) +catkin_package() -install(FILES - scripts/computing.yaml - scripts/data.yaml - scripts/empty.yaml - scripts/interface.yaml - scripts/main.yaml - scripts/map.yaml - scripts/qs.yaml - scripts/rtmgr_icon.xpm - scripts/rtmgr.wxg - scripts/sensing.yaml - scripts/setup.yaml - scripts/simulation.yaml - scripts/state.yaml - scripts/status.yaml - scripts/topics.yaml - scripts/vector_map_files.yaml - scripts/viewer.yaml - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +catkin_install_python( + PROGRAMS + scripts/ftrace.py + scripts/proc_manager.py + scripts/rtmgr.py + scripts/runtime_manager_dialog.py + scripts/test_pub.py + scripts/test_srv.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) -install(FILES - scripts/images/autoware_logo_1.png - scripts/images/autoware_logo_2.png - scripts/images/autoware_logo_2_white.png - scripts/images/axe.png - scripts/images/database.png - scripts/images/dec.png - scripts/images/inc.png - scripts/images/mobile.png - scripts/images/nagoya_university.png - scripts/images/tablet.png - scripts/images/vehicle.png - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}/images - #DESTINATION share/${PROJECT_NAME}/images - ) +install( + PROGRAMS + scripts/3dm_gx5_15.sh + scripts/add_perm.sh + scripts/adis16470.sh + scripts/avt_vimba.sh + scripts/gazebo.sh + scripts/mti300.sh + scripts/vg440.sh + scripts/cleanup + scripts/run + scripts/run_proc_manager + scripts/subnet_chk.py + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts +) -install(FILES - scripts/launch_files/check.launch - scripts/launch_files/control.launch - scripts/launch_files/init.launch - scripts/launch_files/map.launch - scripts/launch_files/perception.launch - scripts/launch_files/planning.launch - scripts/launch_files/sensor.launch - scripts/launch_files/set.launch +install( + FILES + scripts/computing.yaml + scripts/data.yaml + scripts/empty.yaml + scripts/interface.yaml + scripts/main.yaml + scripts/map.yaml + scripts/qs.yaml + scripts/rtmgr.wxg + scripts/rtmgr_icon.xpm + scripts/sensing.yaml + scripts/setup.yaml + scripts/simulation.yaml + scripts/state.yaml + scripts/status.yaml + scripts/topics.yaml + scripts/vector_map_files.yaml + scripts/viewer.yaml + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) - scripts/launch_files/velodyne_hdl64e_s2.launch - scripts/launch_files/velodyne_hdl64e_s3.launch - scripts/launch_files/velodyne_hdl32e.launch - scripts/launch_files/velodyne_vlp16.launch - scripts/launch_files/velodyne_vlp16_hires.launch - scripts/launch_files/velodyne_vlp32c.launch +install( + FILES + scripts/images/autoware_logo_1.png + scripts/images/autoware_logo_2.png + scripts/images/autoware_logo_2_white.png + scripts/images/axe.png + scripts/images/database.png + scripts/images/dec.png + scripts/images/inc.png + scripts/images/mobile.png + scripts/images/nagoya_university.png + scripts/images/tablet.png + scripts/images/vehicle.png + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}/images +) - scripts/vscan.launch - scripts/vehicle_socket.launch - scripts/uvc_camera.launch - scripts/traffic_light.launch - scripts/synchronization.launch - scripts/tablet_socket.launch - scripts/setup_tf.launch - scripts/setup_vehicle_info.launch - scripts/points2image.launch - scripts/mqtt_socket.launch - scripts/ex_mat_pub.launch - scripts/calibration_publisher.launch - scripts/avt_camera.launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch_files - #DESTINATION share/${PROJECT_NAME}/launch_files - ) +install( + FILES + scripts/avt_camera.launch + scripts/calibration_publisher.launch + scripts/ex_mat_pub.launch + scripts/launch_files/check.launch + scripts/launch_files/control.launch + scripts/launch_files/init.launch + scripts/launch_files/map.launch + scripts/launch_files/perception.launch + scripts/launch_files/planning.launch + scripts/launch_files/sensor.launch + scripts/launch_files/set.launch + scripts/launch_files/velodyne_hdl32e.launch + scripts/launch_files/velodyne_hdl64e_s2.launch + scripts/launch_files/velodyne_hdl64e_s3.launch + scripts/launch_files/velodyne_vlp16.launch + scripts/launch_files/velodyne_vlp16_hires.launch + scripts/launch_files/velodyne_vlp32c.launch + scripts/mqtt_socket.launch + scripts/points2image.launch + scripts/setup_tf.launch + scripts/setup_vehicle_info.launch + scripts/synchronization.launch + scripts/tablet_socket.launch + scripts/traffic_light.launch + scripts/uvc_camera.launch + scripts/vehicle_socket.launch + scripts/vscan.launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch_files +) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - PATTERN ".svn" EXCLUDE) - + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/utilities/runtime_manager/scripts/computing.yaml b/utilities/runtime_manager/scripts/computing.yaml index 0b0511fa030..97ad5ecb21e 100755 --- a/utilities/runtime_manager/scripts/computing.yaml +++ b/utilities/runtime_manager/scripts/computing.yaml @@ -13,12 +13,23 @@ subs : param: gnss gui : stat_topic : [ gnss ] + plane : + flags : [ nl ] + sim_mode : + depend : sim_mode + depend_bool : 'lambda v : v == 1' - name : nmea2tfpose desc : nmea2tfpose desc sample cmd : roslaunch gnss_localizer nmea2tfpose.launch param: gnss gui : stat_topic : [ gnss ] + plane : + depend : sim_mode + depend_bool : 'lambda v : v == 0' + flags : [ nl ] + sim_mode : + flags : [ nl ] - name : lidar_localizer desc : lidar_localizer desc sample subs : @@ -1408,6 +1419,14 @@ params : cmd_param : dash : '' delim : ':=' + - name : sim_mode + desc : Enable simulation mode - plane origin at (0°, 0°) + label : 'Simulation Mode' + kind : checkbox + v : False + cmd_param: + dash : '' + delim : ':=' - name : ndt topic : /config/ndt @@ -4304,14 +4323,6 @@ params : cmd_param : dash : '' delim : ':=' - - name : overwrite_vmax_mode - desc : Enavle overwrite velocity max mode - label : overwrite velocity max mode - kind : checkbox - v : false - cmd_param : - dash : '' - delim : ':=' - name : replan_endpoint_mode desc : Enable replan endpoint mode label : replan endpoint mode @@ -4329,15 +4340,6 @@ params : cmd_param : dash : '' delim : ':=' - - name : radius_thresh - desc : When the estimated turning radius > Rth [m], the area is recognized as a curve - label : Curve Recognize - Rth [m] - min : 10.0 - max : 100.0 - v : 20.0 - cmd_param : - dash : '' - delim : ':=' - name : radius_min desc : In curves, when the turning radius R is Rmin, velocity becomes Vmin. label : Minimum Turning Radius in curves - Rmin [m] @@ -4374,30 +4376,12 @@ params : cmd_param : dash : '' delim : ':=' - - name : velocity_offset - desc : Planned velocity offset for the response delay - label : Velocity Offset - min : 0 - max : 30 - v : 4 - cmd_param : - dash : '' - delim : ':=' - - name : braking_distance - desc : braking distance (v = vmin) for safe stopping - label : Braking Distance - min : 0 - max : 10 - v : 5 - cmd_param : - dash : '' - delim : ':=' - - name : end_point_offset - desc : Expanded end points (v = 0) for safe stopping - label : End Point Offset - min : 0 - max : 2 - v : 1 + - name : lateral_accel_limit + desc : Maximum value of lateral acceleration + label : Lateral acceleration limit [m/s^2] + min : 0.0 + max : 3.0 + v : 2.0 cmd_param : dash : '' delim : ':=' @@ -5406,7 +5390,7 @@ params : label : 'clip_min_height (~sensor height)' min : -5 max : 5 - v : -5 + v : -1.3 cmd_param : dash : '' delim : ':=' @@ -6598,11 +6582,3 @@ params : cmd_param : dash : '' delim : ':=' - - name : enable_emergency_to_twist_gate - desc : If a difference is detected, enter emergency state via twist_gate node - label : enable_emergency_to_twist_gate - kind : checkbox - v : true - cmd_param : - dash : '' - delim : ':=' diff --git a/utilities/runtime_manager/scripts/map.yaml b/utilities/runtime_manager/scripts/map.yaml index c97104c502c..bb90f2630e5 100644 --- a/utilities/runtime_manager/scripts/map.yaml +++ b/utilities/runtime_manager/scripts/map.yaml @@ -1,6 +1,6 @@ buttons : point_cloud : - run : rosrun map_file points_map_loader + run : roslaunch map_file points_map_loader.launch param : points_map_loader gui : stdout_func : self.point_cloud_progress_bar @@ -66,22 +66,20 @@ params : - name : scene_num kind : menu cmd_param : - delim : '' + dash : '' + delim : ':=' - name : path_area_list kind : path - - name : path_area_list_cmd_param - kind : hide cmd_param : - delim : '' - must : self.checkbox_auto_update.GetValue() - only_enable : True + dash : '' + delim : ':=' - name : path_pcd kind : path path_type : multi v : '' cmd_param : - delim : '' - unpack : ',' + dash : '' + delim : ':=' - name : vector_map_loader vars : diff --git a/utilities/system_monitor/CHANGELOG.rst b/utilities/system_monitor/CHANGELOG.rst new file mode 100644 index 00000000000..ce6769d12e1 --- /dev/null +++ b/utilities/system_monitor/CHANGELOG.rst @@ -0,0 +1,8 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package system_monitor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1x.0 (2020-xx-xx) +------------------- +* Initial commit +* Contributors: Fumihito Ito diff --git a/utilities/system_monitor/CMakeLists.txt b/utilities/system_monitor/CMakeLists.txt new file mode 100644 index 00000000000..154e031d35f --- /dev/null +++ b/utilities/system_monitor/CMakeLists.txt @@ -0,0 +1,293 @@ +cmake_minimum_required(VERSION 2.8.3) +project(system_monitor) + +## Compile as C++14, supported in ROS Melodic and newer +add_compile_options(-std=c++14) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + diagnostic_msgs + roslint + roscpp + std_msgs +) + +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +find_package(NVML) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++14") +roslint_cpp() + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS std_msgs +) + +########### +## Build ## +########### + +## Specify additional locations of header files + +find_path(LIBNL3_INCLUDE_DIRS + NAMES netlink/netlink.h + PATH_SUFFIXES libnl3 +) + +if (NVML_FOUND) + include_directories( + include + ${catkin_INCLUDE_DIRS} + ${LIBNL3_INCLUDE_DIRS} + ${NVML_INCLUDE_DIRS} + ) +else() + include_directories( + include + ${LIBNL3_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ) +endif() + +## Declare a C++ executable + +if (CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(CMAKE_CPU_PLATFORM "intel") + ADD_DEFINITIONS(-D_CPU_INTEL_) +elseif (CMAKE_SYSTEM_PROCESSOR STREQUAL "aarch64" OR CMAKE_SYSTEM_PROCESSOR STREQUAL "arm") + if (CMAKE_HOST_SYSTEM_VERSION MATCHES ".*raspi.*") + set(CMAKE_CPU_PLATFORM "raspi") + ADD_DEFINITIONS(-D_CPU_RASPI_) + elseif (CMAKE_HOST_SYSTEM_VERSION MATCHES ".*tegra.*") + set(CMAKE_CPU_PLATFORM "tegra") + ADD_DEFINITIONS(-D_CPU_TEGRA_) + else() + set(CMAKE_CPU_PLATFORM "arm") + ADD_DEFINITIONS(-D_CPU_ARM_) + endif() +else() + set(CMAKE_CPU_PLATFORM "unknown") +endif() + +if (NVML_FOUND) + set(CMAKE_GPU_PLATFORM "nvml") + ADD_DEFINITIONS(-D_GPU_NVML_) + set(GPU_LIBRARY ${NVML_LIBRARIES}) +else() + if (CMAKE_CPU_PLATFORM STREQUAL "tegra") + set(CMAKE_GPU_PLATFORM "tegra") + ADD_DEFINITIONS(-D_GPU_TEGRA_) + else() + set(CMAKE_GPU_PLATFORM "unknown") + endif() +endif() + +message(STATUS "HOST_SYSTEM_VERSION: " ${CMAKE_HOST_SYSTEM_VERSION}) +message(STATUS "SYSTEM_PROCESSOR: " ${CMAKE_SYSTEM_PROCESSOR}) +message(STATUS "CPU PLATFORM: " ${CMAKE_CPU_PLATFORM}) +message(STATUS "GPU PLATFORM: " ${CMAKE_GPU_PLATFORM}) + +set(CPU_MONITOR_SOURCE + src/cpu_monitor/cpu_monitor_base.cpp + src/cpu_monitor/${CMAKE_CPU_PLATFORM}_cpu_monitor.cpp +) + +add_executable(cpu_monitor + src/cpu_monitor/cpu_monitor_node.cpp + ${CPU_MONITOR_SOURCE} +) + +add_executable(hdd_monitor + src/hdd_monitor/hdd_monitor_node.cpp + src/hdd_monitor/hdd_monitor.cpp +) +add_executable(mem_monitor + src/mem_monitor/mem_monitor_node.cpp + src/mem_monitor/mem_monitor.cpp +) +add_executable(net_monitor + src/net_monitor/net_monitor_node.cpp + src/net_monitor/net_monitor.cpp + src/net_monitor/nl80211.cpp +) +add_executable(ntp_monitor + src/ntp_monitor/ntp_monitor_node.cpp + src/ntp_monitor/ntp_monitor.cpp +) +add_executable(process_monitor + src/process_monitor/process_monitor_node.cpp + src/process_monitor/process_monitor.cpp +) + +set(GPU_MONITOR_SOURCE + src/gpu_monitor/gpu_monitor_base.cpp + src/gpu_monitor/${CMAKE_GPU_PLATFORM}_gpu_monitor.cpp +) +add_executable(gpu_monitor + src/gpu_monitor/gpu_monitor_node.cpp + ${GPU_MONITOR_SOURCE} +) + +add_executable(msr_reader + reader/msr_reader/msr_reader.cpp +) + +add_executable(hdd_reader + reader/hdd_reader/hdd_reader.cpp +) + +## Add cmake target dependencies of the executable +add_dependencies(cpu_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(hdd_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(mem_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(net_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(ntp_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(process_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(gpu_monitor ${catkin_EXPORTED_TARGETS}) +add_dependencies(msr_reader ${catkin_EXPORTED_TARGETS}) +add_dependencies(hdd_reader ${catkin_EXPORTED_TARGETS}) + +find_library(NL3 nl-3) +find_library(NLGENL3 nl-genl-3) +list(APPEND NL_LIBS ${NL3} ${NLGENL3}) + +find_package(Boost REQUIRED COMPONENTS + serialization +) + +## Specify libraries to link a library or executable target against +target_link_libraries(cpu_monitor ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(hdd_monitor ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(mem_monitor ${catkin_LIBRARIES}) +target_link_libraries(net_monitor ${catkin_LIBRARIES} ${NL_LIBS}) +target_link_libraries(ntp_monitor ${catkin_LIBRARIES}) +target_link_libraries(process_monitor ${catkin_LIBRARIES}) +target_link_libraries(gpu_monitor ${catkin_LIBRARIES} ${GPU_LIBRARY}) +target_link_libraries(msr_reader ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(hdd_reader ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + +############# +## Install ## +############# + +## Mark executables for installation +install( + TARGETS + cpu_monitor + hdd_monitor + mem_monitor + net_monitor + ntp_monitor + process_monitor + gpu_monitor + msr_reader + hdd_reader + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +# Install launch +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +# Install config +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config +) + +############# +## Testing ## +############# + +if (CATKIN_ENABLE_TESTING) + roslint_add_test() + find_package(rostest REQUIRED) + + add_rostest_gtest(test_cpu_monitor + test/test_cpu_monitor.test + test/src/cpu_monitor/test_${CMAKE_CPU_PLATFORM}_cpu_monitor.cpp + ${CPU_MONITOR_SOURCE} + ) + target_link_libraries(test_cpu_monitor ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + + # Disabled since it depends on the system performing the test. + # TODO(icolwell): Re-enable or re-work test to focus on functionality of code rather + # than the system running the test. + # add_rostest_gtest(test_hdd_monitor + # test/test_hdd_monitor.test + # test/src/hdd_monitor/test_hdd_monitor.cpp + # src/hdd_monitor/hdd_monitor.cpp + # ) + # target_link_libraries(test_hdd_monitor ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + + add_rostest_gtest(test_mem_monitor + test/test_mem_monitor.test + test/src/mem_monitor/test_mem_monitor.cpp + src/mem_monitor/mem_monitor.cpp + ) + target_link_libraries(test_mem_monitor ${catkin_LIBRARIES}) + + add_rostest_gtest(test_net_monitor + test/test_net_monitor.test + test/src/net_monitor/test_net_monitor.cpp + src/net_monitor/net_monitor.cpp + src/net_monitor/nl80211.cpp + ) + target_link_libraries(test_net_monitor ${catkin_LIBRARIES} ${NL_LIBS}) + + add_rostest_gtest(test_ntp_monitor + test/test_ntp_monitor.test + test/src/ntp_monitor/test_ntp_monitor.cpp + src/ntp_monitor/ntp_monitor.cpp + ) + target_link_libraries(test_ntp_monitor ${catkin_LIBRARIES}) + + add_rostest_gtest(test_process_monitor + test/test_process_monitor.test + test/src/process_monitor/test_process_monitor.cpp + src/process_monitor/process_monitor.cpp + ) + target_link_libraries(test_process_monitor ${catkin_LIBRARIES}) + + add_rostest_gtest(test_gpu_monitor + test/test_gpu_monitor.test + test/src/gpu_monitor/test_${CMAKE_GPU_PLATFORM}_gpu_monitor.cpp + ${GPU_MONITOR_SOURCE} + ) + target_link_libraries(test_gpu_monitor ${catkin_LIBRARIES} ${GPU_LIBRARY}) + + # Dummy executables + add_executable(mpstat1 test/src/cpu_monitor/mpstat1.cpp) + add_executable(mpstat2 test/src/cpu_monitor/mpstat2.cpp) + add_executable(df1 test/src/hdd_monitor/df1.cpp) + add_executable(free1 test/src/mem_monitor/free1.cpp) + add_executable(ntpdate1 test/src/ntp_monitor/ntpdate1.cpp) + add_executable(top1 test/src/process_monitor/top1.cpp) + add_executable(top2 test/src/process_monitor/top2.cpp) + add_executable(top3 test/src/process_monitor/top3.cpp) + add_executable(echo1 test/src/process_monitor/sort1.cpp) + add_executable(sort1 test/src/process_monitor/sort1.cpp) + add_executable(sed1 test/src/process_monitor/sed1.cpp) + + install(TARGETS mpstat1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS mpstat2 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS df1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS free1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS ntpdate1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS top1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS top2 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS top3 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS echo1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS sort1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS sed1 RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +endif() diff --git a/utilities/system_monitor/README.md b/utilities/system_monitor/README.md new file mode 100644 index 00000000000..e33cce0f9b4 --- /dev/null +++ b/utilities/system_monitor/README.md @@ -0,0 +1,157 @@ +# System Monitor for Autoware + +**Further improvement of system monitor functionality for Autoware.** + +## Description +This package provides the following nodes for monitoring system: +* CPU Monitor +* HDD Monitor +* Memory Monitor +* Network Monitor +* NTP Monitor +* Process Monitor +* GPU Monitor + +### Suppoted architecture +* x86_64 +* arm64v8/aarch64 + +### Operation confirmed platform +* PC system intel core i7 +* NVIDIA Jetson AGX Xavier +* Raspberry Pi4 Model B + +## How to use +Use colcon build and launch in the same way as other packages. +``` +colcon build +source install/setup.bash +roslaunch system_monitor system_monitor.launch +``` + +CPU and GPU monitoring method differs depending on platform.
        +CMake automatically chooses source to be built according to build environment.
        +If you build this package on intel platform, CPU monitor and GPU monitor which run on intel platform are built. + +## ROS topics published by system monitor + +Every topic is published in 1 minute interval. + +- [CPU Monitor](docs/topics_cpu_monitor.md) +- [HDD Monitor](docs/topics_hdd_monitor.md) +- [Mem Monitor](docs/topics_mem_monitor.md) +- [Net Monitor](docs/topics_net_monitor.md) +- [NTP Monitor](docs/topics_ntp_monitor.md) +- [Process Monitor](docs/topics_process_monitor.md) +- [GPU Monitor](docs/topics_gpu_monitor.md) + +[Usage] ✓:Supported, -:Not supported + +| Node | Message | Intel | arm64(tegra) | arm64(raspi) | Notes | +| ---- | --- | :---: | :---: | :---: | --- | +| CPU Monitor | CPU Temperature | ✓ | ✓ | ✓ | | +| | CPU Usage | ✓ | ✓ | ✓ | | +| | CPU Load Average | ✓ | ✓ | ✓ | | +| | CPU Thermal Throttling | ✓ | - | ✓ | | +| | CPU Frequency | ✓ | ✓ | ✓ | Notification of frequency only, normally error not generated. | +| HDD Monitor | HDD Temperature | ✓ | ✓ | ✓ | | +| | HDD Usage | ✓ | ✓ | ✓ | | +| Memory Monitor | Memory Usage | ✓ | ✓ | ✓ | | +| Net Monitor | Network Usage | ✓ | ✓ | ✓ | | +| NTP Monitor | NTP Offset | ✓ | ✓ | ✓ | | +| Process Monitor | Tasks Summary | ✓ | ✓ | ✓ | | +| | High-load Proc[0-9] | ✓ | ✓ | ✓ | | +| | High-mem Proc[0-9] | ✓ | ✓ | ✓ | | +| GPU Monitor | GPU Temperature | ✓ | ✓ | - | | +| | GPU Usage | ✓ | ✓ | - | | +| | GPU Memory Usage | ✓ | - | - | | +| | GPU Thermal Throttling | ✓ | - | - | | +| | GPU Frequency | - | ✓ | - | | + +## ROS parameters + + See [ROS parameters](docs/ros_parameters.md). + +# Notes + +## CPU monitor for intel platform +Thermal throttling event can be monitored by reading contents of MSR(Model Specific Register), and accessing MSR is only allowed for root by default, so this package provides the following approach to minimize security risks as much as possible:
        + +- Provide a small program named 'msr_reader' which accesses MSR and sends thermal throttling status to CPU monitor by using socket programming. +- Run 'msr_reader' as a specific user instead of root. +- CPU monitor is able to know the status as an unprivileged user since thermal throttling status is sent by socket communication. + +### Instructions before starting +1. Create a user to run 'msr_reader'. +``` +sudo adduser +``` + +2. Load kernel module 'msr' into your target system.
        +The path '/dev/cpu/CPUNUM/msr' appears. +``` +sudo modprobe msr +``` + +3. Allow user to access MSR with read-only privilege using the Access Control List (ACL). +``` +sudo setfacl -m u::r /dev/cpu/*/msr +``` + +4. Assign capability to 'msr_reader' since msr kernel module requires rawio capability. +``` +sudo setcap cap_sys_rawio=ep install/system_monitor/lib/system_monitor/msr_reader +``` + +5. Run 'msr_reader' as the user you created, and run system_monitor as a generic user. +``` +su +install/system_monitor/lib/system_monitor/msr_reader +``` + +### See also +[msr_reader](docs/msr_reader.md) + +## HDD Monitor +Generally, S.M.A.R.T. information is used to monitor HDD temperature, and normally accessing disk device node is allowed for root user or disk group.
        +As with the CPU monitor, this package provides an approach to minimize security risks as much as possible:
        + +- Provide a small program named 'hdd_reader' which accesses S.M.A.R.T. information and sends HDD temperature to HDD monitor by using socket programming. +- Run 'hdd_reader' as a specific user. +- HDD monitor is able to know HDD temperature as an unprivileged user since HDD temperature is sent by socket communication. + +### Instructions before starting +1. Create a user to run 'hdd_reader'. +``` +sudo adduser +``` + +2. Add user to the disk group. +``` +sudo usermod -a -G disk +``` + +3. Assign capabilities to 'hdd_reader' since SCSI kernel module requires rawio capability to send ATA PASS-THROUGH (12) command and NVMe kernel module requires admin capability to send Admin Command. +``` +sudo setcap 'cap_sys_rawio=ep cap_sys_admin=ep' install/system_monitor/lib/system_monitor/hdd_reader +``` + +4. Run 'hdd_reader' as the user you created, and run system_monitor as a generic user. +``` +su +install/system_monitor/lib/system_monitor/hdd_reader +``` + +### See also +[hdd_reader](docs/hdd_reader.md) + +## GPU Monitor for intel platform +Currently GPU monitor for intel platform only supports NVIDIA GPU whose information can be accessed by NVML API. + +Also you need to instal CUDA libraries. +For installation instructions for CUDA 10.0, see [NVIDIA CUDA Installation Guide for Linux](https://docs.nvidia.com/cuda/archive/10.0/cuda-installation-guide-linux/index.html). + +# UML diagrams + See [Class diagrams](docs/class_diagrams.md). + See [Sequence diagrams](docs/seq_diagrams.md). + diff --git a/utilities/system_monitor/cmake/FindNVML.cmake b/utilities/system_monitor/cmake/FindNVML.cmake new file mode 100644 index 00000000000..4d9df90f38b --- /dev/null +++ b/utilities/system_monitor/cmake/FindNVML.cmake @@ -0,0 +1,20 @@ +# - Find NVML +# Find the native NVML(NVIDIA Management Library) includes and libraries +# +# NVML_INCLUDE_DIRS - where to find nvml.h. +# NVML_LIBRARIES - the library needed to use NVML. +# NVML_FOUND - True if NVML found. + +if (NOT NVML_INCLUDE_DIRS) + find_path(NVML_INCLUDE_DIRS nvml.h PATHS /usr/local/cuda/include) +endif() + +if (NOT NVML_LIBRARIES) + find_library(NVML_LIBRARIES NAMES nvidia-ml) +endif() + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(NVML DEFAULT_MSG NVML_LIBRARIES NVML_INCLUDE_DIRS) + +message(STATUS "NVML include dir: ${NVML_INCLUDE_DIRS}") +message(STATUS "NVML library : ${NVML_LIBRARIES}") diff --git a/utilities/system_monitor/config/system_monitor.yaml b/utilities/system_monitor/config/system_monitor.yaml new file mode 100644 index 00000000000..5e7cfec3057 --- /dev/null +++ b/utilities/system_monitor/config/system_monitor.yaml @@ -0,0 +1,38 @@ +cpu_monitor: + temp_warn: 90.0 + temp_error: 95.0 + usage_warn: 0.90 + usage_error: 1.00 + load1_warn: 0.90 + load5_warn: 0.80 + msr_reader_port: 7634 +hdd_monitor: + hdd_reader_port: 7635 + disks: + - name: /dev/sda + temp_warn: 55.0 + temp_error: 70.0 + - name: /dev/nvme0 + temp_warn: 55.0 + temp_error: 70.0 + usage_warn: 0.95 + usage_error: 0.99 +mem_monitor: + usage_warn: 0.95 + usage_error: 0.99 +net_monitor: + devices: [ '*' ] + usage_warn: 0.95 +ntp_monitor: + server: ntp.nict.jp + offset_warn: 0.1 + offset_error: 5.0 +process_monitor: + num_of_procs: 5 +gpu_monitor: + temp_warn: 90.0 + temp_error: 95.0 + gpu_usage_warn: 0.90 + gpu_usage_error: 1.00 + memory_usage_warn: 0.95 + memory_usage_error: 0.99 diff --git a/utilities/system_monitor/docs/class_diagrams.md b/utilities/system_monitor/docs/class_diagrams.md new file mode 100644 index 00000000000..662e6a26195 --- /dev/null +++ b/utilities/system_monitor/docs/class_diagrams.md @@ -0,0 +1,29 @@ +# Class diagrams + +## CPU Monitor + +![CPU Monitor](images/class_cpu_monitor.png) + +## HDD Monitor + +![HDD Monitor](images/class_hdd_monitor.png) + +## Memory Monitor + +![Memory Monitor](images/class_mem_monitor.png) + +## Net Monitor + +![Net Monitor](images/class_net_monitor.png) + +## NTP Monitor + +![NTP Monitor](images/class_ntp_monitor.png) + +## Process Monitor + +![Process Monitor](images/class_process_monitor.png) + +## GPU Monitor + +![GPU Monitor](images/class_gpu_monitor.png) diff --git a/utilities/system_monitor/docs/hdd_reader.md b/utilities/system_monitor/docs/hdd_reader.md new file mode 100644 index 00000000000..3ce95a161e3 --- /dev/null +++ b/utilities/system_monitor/docs/hdd_reader.md @@ -0,0 +1,50 @@ +# hdd_reader + +## Name +hdd_reader - Read S.M.A.R.T. information for monitoring HDD temperature + +## Synopsis +hdd_reader [OPTION] + +## Description +Read S.M.A.R.T. information for monitoring HDD temperature.
        +This runs as a daemon process and listens to a TCP/IP port (7635 by default). + +**Options:**
        +*-h, --help*
        +    Display help
        +*-p, --port #*
        +    Port number to listen to + +**Exit status:**
        +Returns 0 if OK; non-zero otherwise. + +## Notes +The 'hdd_reader' accesses minimal data enough to get Model number, Serial number, and HDD temperature.
        +This is an approach to limit its functionality, however, the functionality can be expanded for further improvements and considerations in the future.

        +**[ATA]** + +| Purpose | Name | Length | +| --- | --- | --- | +| Model number, Serial number | IDENTIFY DEVICE data | 256 words(512 bytes) | +| HDD temperature | SMART READ DATA | 256 words(512 bytes) | + +For details please see the documents below.
        +- [ATA Command Set - 4 (ACS-4)](http://www.t13.org/Documents/UploadedDocuments/docs2016/di529r14-ATAATAPI_Command_Set_-_4.pdf) +- [ATA/ATAPI Command Set - 3 (ACS-3)](http://www.t13.org/Documents/UploadedDocuments/docs2013/d2161r5-ATAATAPI_Command_Set_-_3.pdf) +- [SMART Attribute Overview](http://www.t13.org/Documents/UploadedDocuments/docs2005/e05171r0-ACS-SMARTAttributes_Overview.pdf) +- [SMART Attribute Annex](http://www.t13.org/documents/uploadeddocuments/docs2005/e05148r0-acs-smartattributesannex.pdf) + +**[NVMe]** + +| Purpose | Name | Length | +| --- | --- | --- | +| Model number, Serial number | Identify Controller data structure | 4096 bytes | +| HDD temperature | SMART / Health Information | 1 Dword(4 bytes) | + +For details please see the documents below.
        +- [NVM Express 1.2b](https://www.nvmexpress.org/wp-content/uploads/NVM_Express_1_2b_Gold_20160603.pdf) + +## Operation confirmed drives +* SAMSUNG MZVLB1T0HALR (SSD) +* Western Digital My Passport (Portable HDD) diff --git a/utilities/system_monitor/docs/images/class_cpu_monitor.png b/utilities/system_monitor/docs/images/class_cpu_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..3fb87810b0209823626ae1fa85543f37e57db51c GIT binary patch literal 127936 zcmeFXXLu9W);~%JoKQkDEp!4n7zjqaP_2

        Y7n6U=wwXde=x`2qE+i213VRnoS9z z7;Fp)H9&x1115lRC;@DOP4D2lCpqWXFM03(xnJ&czuf1srP1u!d#|$ysT3}__F!%s_!8JGZa*=_8ZyPxF+X^mOi5>_Q^75+GvxPzhhP>d zos>>xvzX~*ItvWc^8~ZfDSuI;GTBWbtifgkx3-AM@i(WakAt`(I*wdoq9thx9pZ8T zPKak>won)Y;`vKh|Jj-th$I5GzwcUYG0Xz!Anpc$M8bdH1|(8aseB-ID`s+pOkObT zGXaACT8fKmz;Bt~heiCMzvp8A7Q2OJve>CM_FyudZX3*`P$+}h7CQs{WSYq)GL6k* z+5cXfsm09}dYHjSX=I<<&2-0U4hJ0-QuscTjE<6w;-K5Zu*rB*NrbE7B5ow=jsYPs z!U~zxVwTJJrjW%WB?&@CrGV+98ug^82=Y3VC^P9r;D}u&0#7qJvQWauQTy#Wu`xi2 zn^|tU+UF5UxEg-YU`eGw{y@N`cY0zp2NrZiy$NtDpadTxuAjn_!AV7s?;+`&VTBe_ zhP*xrMPlZmUYO1@(bV1mUqH7qVOv1YaQI+OzWYM$?w#Wn4p{YC+A^5gg zq#BeQ6A55r*kh+S$quO|hU4*AIIPtnPA*Mgl8KCb@T5n};whZ5h$^D>L>S;GAf15f zOHx!gP)VkLdik8P&m3oFfK0 z3F#erAP%ub!PV2)Ixg2IG8?pZl{U^%__<_0jgLy5vIrj`DZs;28l($2ct#8C;pp}H z2rc2mak`r!W+j9H2AXt>^a+7k=wR{$NtaT=G%y4-oFgQQZNzMX2d0zHjV9s&O90nN z>`AxWAC+(%aZJNw>q!w*s?*WUAtRqEV*6ZjvYBIL1YIGW3X@yh5{pG;^RZAJAL85N zMjfn*$z$wf*zA)SEaW&W6es~L0ugNB_$W4vOfm_$6ur+Dh%lKhz@yV_Ptq)QOiK#t zafXdyOY&HD9m5GM2oeP&DjQ}^SiEGp8%08LZh)?bn<0#&OxPO;7)dHik|e_ok^qy-; zoQ9CuEsc1+LX(yvKrjo&rN}6Lp;$|Ca3LPmu5$AnxXi}2V{C>$88k~+e5y+(3K_K$ zrOu+zhuwf)sVE}SYkhVPRU!YHB9e$6lN&rzhf2panQRJe0;1}orld@t z^zxJt*>C5m)M^9jLL}l?&_@p|6*9Y+0U>&kIViJ5EJ~**>TtXD^aR7tBvYM6rb)x$ zz_KU}?8=a9X>m1hs}M&gi93A(ppOicV^PIoT9L~m=9p{(8rcvgsTjDM1>;!Qg0T`> z@VtwG7+fK_9+Po2Y&ag07zOc=LQhRv6RI#hW`jex9k?Wmp5dh!eaSG@!bIupDAyII zi&a5tR3>9XR&|o^vgi~*pfo#<(4ux01;*8(fXJL=3rsAxFThc0lv)87(y$_4zg;50 zwMvCJs!w`^7E40yH85m;8we0kGU=2_VW&tR=LZ~K2vc#qkWLwtxN)Z49Ee0>jzpNp zGx=1Zh>b1QvW;X@FfI*IqJS{9Qb}?;QLqZ6@P@Ss3&bJJ+0PRS)EcXqDn^Vdo+}XL zM=>-)i^RE1u81cF`UlRM=JSaRE)GL2FySsKo5Oc1l)eDMNk&y1fhfV0a$**Sk|g$n zm;fnMEUi$hX2FQlrWKe14mMasE>iQzdcI!GlYn!=ECRMH$r97!F^)9u2{~W~p9(p{ zC{JjkD8&pvKf*Lim}VPE?NX^_B*bGBTKFm-S?}`Dl9-Oo(ulpV1L&W|hf!28pQO|{ z!YqZH%ZtgQe5Z%z1WIQ2TLmFa)EC3V2pte+r17Le*l0BYzF`@iqK_weR2M5Ein}Bf zI++#b;S9{F$2}BSZI%TwtrLlb19mx(84Q#MX0RcHLE+;#74%>LxIma~QB!FY9gido zVh~+LcE}~_AaJ;_#N{@6Vp1y~a4(g~ts=DrcY4UMlp*7Wy$J9;yaXkoQpC9u6X9K0 zPQEAUGCQe2ybiD2=n8RIF-lx4l{0N72-o=q9vd^^Lqaw+2=*`>@tSR3uTyPeGm(%W z5=jU|JdI4O3`a1VSnlT0L41SlL5ETuVuhGCE6vN7_{Bz)#IiC25`^Jb`fbT5FJT3b zg~fkS>|=BMWDq0l2-hwa2gyMp%*1eMND-D=f;zg37njL>Y?0ld(}%QfyH;d#`*+R8 z6a;Mu_n`@!3)b_5(U^xVRVlq1OhpdFRT?P~XlzzK+XCPWWYn=0VTQ*@k5gqypMmUT zpjN7jPPMy|WUnR8V=?T4WDsKMJz<*OV1(>p5;f*_dr8tr&=-xkWjYd@NBt|n+Gs4l zjAF-aQ8`Yw*b;ODRVJYLJgAI}8jWPNKge|k9d45h!KDI+ov=8&0hTJLJT?|2)Q0P| z81;0v*`)(!EF>WzdWg+bFyjHbnyh4ztr(XJQQH|2jRp_G;4WBG&SDxgdW0t= zIh8zlkYta7`%;6C$z0GUX_lN+E$G^Ba|6dCcfB>K#!M#DIdZ z9fJ8BH{ApU_^89@Fzfj$uFF7k0Ve^)9o`UAE%38p*lVSjXfZwFQp98cG{wnQm@UTw z5dk4Uy1^L+yTfr8l^GS#=!74Gu!Po%`8Xn*n&WZ-_y>Cs4#Q)yz$6yQ;|zzDe!p1? zS@bfI-4ie+;!dYqVDWln3Xhv)z#0y86N?TaYM=)WG z6H{O`5;+O(TRmn;%uZ*?^!7Lkurb*2Kk)bito$E192)E}h7=YS$2?f$4w^lh00;OG zzkQ~6A7#HwM3X)sD6drbnX!ww5+ex=aufFdv%^J?TFD@-yQu%H}RFWo3o z{O!Ql;e?&9$26$Rp*JTKK|BPg)`oN_@a=jyLSn)K8iH8-UJot7i(9OOC*$aZ`j{oG zN+iii)S)B?bwQohL1FkHI!mecX-xtFcuFGkXkjanp+F)h_>gmzEZ898J2i4?P^O6{ zBn}4|Pe#qK*(uY(2+Jf=vh_TkCCUwkbWD~)t)XbhJe{0ObIJ%}J!-2h$gv}Q6(gLK z@(JIh!fh71+ebBr`8umCz_&XMegzNFdl>qd3-{^VX0Sa>NIgnN32U;VTtVEKuo@i< zgdOv`qj4o7F=J#CQ|Q;(Eq12c=b_7OgsH>=w3yt=CKM)VjZyfHfY$_s1EV1`g-bJv z6(WF`c^E?nA_m4&K}_HWxH3P^K>)WfL5#zz2r@{?ILtSQqY{~jtK%AMmZS+2(v=RG zNuW(ipm3B+^M+gwl;jY}oEBm#n=TS52}i+;vICBUB+629Su~Jm0iY_5;Bo=3bW2n! z$Z0d!=+1;wW%O$y4Ko09?EHWnP8bji?tyR-pW^cg!ntwlAJImlfJmkO}9wQ zPC61b;&9TTRL~g`r_1LRX$>r{mZZ^H$RSv1)0u&Hu>c|YMNkIl zNXpo%5W^zjaKapoA;j?;Br&0o%!?{jX17GGVrnd~6pb0RGKo#h1=0iu&vp99W{`p~ zJP5-~wwRM{OcAw<9GF!b5h$%{IzXO|2%?o6B4G#D5|?RYbY@&dD4bhm6w)0EDL*a@ z*yAQ$+>$i9&?wENNy z0xM3|qYAamu8Jo-FzR%=5^AZzMe|#dKtd2ek&wl1PKta=M~sr->k<@?NPzl0@rYZl zwyUg~5EP+PH6)rMA#sI(Dy!l#5=Y7BsmMvHN@^5oK_vi^#MlZmLh%U*WDfo!cu2uD zy1ZPUU7)5=NSd(ICS)gg7Prw)a`DMxtw3w$sI?)f9SNH(2|{a~V!O#9MU6IzFdV~# zQ57v1HqrG423tpq(8CcIaiT7J#3uDqwHA&FB_e=3No0|5$bjiVh=9B@%xlqWsWz36 zhl;`&Ux3894nD~s2|0}@=Hx`hG<8_S5nKInjSUUD*@O7fN&5pPX zL|P*9@?<6zN@4kQP6pG(w9tSV2p|-I8wE$05R!0=31;wYB3c}53j1s{L~C{llPm^> z7PVMhG>hAg0GsEiID9dUaGoYDl|qWcYcURccc^OH_h z5{_`qR?O=rLtGW=k{~uU58|i=Y=0;ch$>qCZ-n|J$!jUB+$@9QAv=%B_WcGLRax( zG?EPXYkT54JcUr4u#W6?`(RY=^agdJ zgakr7Ams?e0wO8P$chG~CNwDbY6RM_T8sMSD!v?&n-J6^qXzUI3EM*QX-PO6Bqsh~ zG^urK)oh+mMHfi{vV=_n%xiGNaW4t1MlvV@5bE&AOeQ=4No6(*DT)yqBa<61S5zAtqJtaA87~hGPNolM9)c_Apr#6o?GLP>98} zX&|~G>7m)QJcCD|A?e+AvyBeB$tYJAN_u>5k%GsyYXf4N#|PO=Y(yoEuvu;rIT6zY zeI~z@OIB)_kUYW&sR7|ggiE4%y@*muwuTt|C{wRD#{(3$mhd1ECxBFVGz8EC&#JfK zY$Pd?Q8i2|KkU_m7zKgsPUaKP{bat0fy6<9NJ-2Jv0!JE&y<71f_!d-;GFH36JbYy zQ6nxXVrBVVT8QP=6Y68u@EA#JNH4S!5M51+68-@E1?;+LP)3+tlxMdxDP&&U&LD%I z_NYoILc9W88jeJRo~YB}RR=g=z>07UZ~`L4Z*s>yLNS7hv~(6ibH&vfU4o%y zK?W-m^8`?hohpdSJQPjR!c%#p37Z)#!StJ{4t6l?(dfu=3N1*KqWv}m^NVB#1r6c* zHB6OLA*DG9dy!xQEMO-PRzhzRIT(IfP{U3bDPe~~h>}BWV}NcJGMrRBlPzQs72f|R z$Tn%x`5~JdwVU`%mB25N86i+$0~Xr=*$R1}2-C1mOdwlw$jlA{;6)-sAwMLvt0*j{ z00+deBqpgKrm{w&dWTr+_tL`dpi^bV(HL2j(5lFOL>#ar5=Ifu;qYS`x>fHII+-?G z!olQI!#31R^NC=OoyOq`_^hx79Q9#~YJ#f95ucqBa!2(vr$OXGJWjnfN@q~R3UgSU z^m?4O1fQM|1|eo705MC~Uw{l2yVr(?T>E&nor7GAfNPaw?M^eS$AmaBzN@ z#w8`J6fR#v#v&k3RPcFRo|a=!MJ?(CnHKfX%`uo_@e37R7L(2l!4|f|oB#+HVLAPF zF2G?5B@rAf3MHMZlB#7&WkM^7u=Q3aPW2j@;)vcLW*QVOJ_3ieKA+V9GGMOSNpToe zQHNGRpl=s&Fm{nECh{N>IWO!NGAUYA3v+@}1p=sz3jr|DsN$$f8xhJwIL}}M4Fj>l zq4tNxdYeq^atmqJh}8t~OngIB>=npe8|DYqKptK@p2t{P~-xAjif~qGHVS=BQxUD zD(xT;!iIp&sFMT{s+5Yz{PqM7K>}RZCiTb-VT)IxOD2>a8fr8{B98$m1QP)jBtI9R zE)^%~bn=BfSj&SYLP1z(VcFwku3wHCL}8$_4jBqAg9nmI4!zS zA2z$Zs6uPvYC!T~)bfL5Pbli(qOe7diX<91OfxuDu#^-tV{%NS;o~+drV}UyGzQGY z8E$UEr7`P)Iz?Csm>yEZq%Nh_D07)ye3FVIGVv%hAKMwV8n_Z1^YKJ1s>lz@lY}E? zk@Vp(0(rG8nq6pPSwkefP(?RU>ck@?vr4F- z${hg;?j-_-Fi1RO5gH;slEz|#50x&F|!~mlZ7judD77WxyVHZk^s%YR7Y7awj^YB19`)LpbT0!OA*=@-qNs&tj9IuEk%5vxcx(=gnm7il&Xj;8ftcRJ zv9Jjy!V+tk%2M$nuo}?{eSE$ptdo0460evMC!q*L<*=DPLy`$#GwyNgtTe4!2?>c@ z+3ktyXfd_{5m@DVS=gv|`s^CLUaL{*sU`;Qr3Y+Ug@KKUK~2k&44K6oLb)U!E)bCF+Y_}{C|Ho9 z1S;XsAruD*cq}+{ z=SqCWB%KXb4msF9MMB}ET2OUV!Hdx2a*oJKg@y9JdWHT(LS$f=Lt!i8Pw1Eeiw#k8 z)lw}q2~ z1Wc0^m5YU_+GL}m5vn>6iYkmjTZp1HNP=WYN~PI7A&u6~<1mPX8ltc$WJpZGgxmy6 zLEHd;2qWZi*yRkqUg~D+ZEOJFX-u=yiWu1@yF!rkn8fUaUE`GMK#w>q#l^6Uj99~D zC}2wpRb)_o2DYRUhCOD~V`79{?hvSE`-N_%$mEh)T*jm=lu+u$6rRMZ3zMuCkJaop z!!}&%bA}Of#OUFH-#nwxl%O!fEVCBT$;|q2Oy|@|P@0l#N>EL9iBm=P_{eS%ClN84 zV{(wwCvXGHXS71xNK`B}qGpF8WCTql&`e}|eYiFfr6+Z?xIr7%5=Ck<8+Y0K;1`?W zC9@+`O90jrt{sp0coI4mB_7c*#ovJR)34Z(;DbWW{N zk_&`63ZIOM*j${dK?4+?T8YF=B8)9DxqM_Vk3n}uDP+>$>&Zbv=RwpgDESZp&j>I+cBOkG$X zmND5JM#N=d2<=g7NY2zNVkSj^htS*zh0G60VqDbd^m_e&Atf~*^uI|uM#yOP5(rNk zjRfT8Xvhl))S3|=jjT$7dbPsjGxJDPp_WO+aWC7ZVMRqm#mDY+;qd?l38^f$F32Vj zCCW1eZHO^$bP^H-6mpnmkw_CIV6o1XAlW3;nAsjSK~9u#E|$OgYXK_k5K2*rD0oX5Q@Cdj9%KMNw7?g$RY>5WEqM`CY225*7BDA>OE<_2i zg(kxR72g7S95I8>V3q>qPk>Ag7U4!V6vPOi;R34=0A7fL9uI{{Lzrw99UK^fLj<%+ zI3WhnWrtyrTnQ8I)jV=_z>5(EKPyPFi-?l8fp`r9Qc>N^xXzrg zYZ(c;T*W0pv;fs6AO&r9H|Pd{1v!8r*kD#^xf%<@1yV8xk4qA;{Gj4)vvOl0j@}oI z@hw^k$1Ox6B!h+-awf!DtylNgJS&?MmeCmm_E%~cCWcK^Yuz0pDP0HpK4+%c}!Nqfoj55wqA)i1Wt$r zCEQ@`#mEn zzuEajuSSh}HxltUYCP-Dist(?Ww(w$DttLBWoAz9ryUm#Sn%ojuk-q0q>c+tsZ+Z2 z8PM@$&gbjc>aHC+Zum)Uo&IZY>asqTu4#35Ghf8Fmqn+A{dZ&M9#)*YRaIW{W^2iF z$AfVbx5anlUhdq|_u6shT(3cyb05Ug3R<~!n@&Fnt!dW#>qd$Vkq z1kGTXl^q)H@z>DN^o+E2#T^}e{^$O^zs~61v{~xS=_18H7c0)losu%D?(vH4MbFa* zzYk0idkR1%DUE6NU*L^4+A#D=WJhjur@1a%O zYj(UE()!K0ckr~7_je3;GYd{%Dg1R*-CJ(j0w?mxGtLKsUE8*4i_{$4b-3m7y4T~9 zUw!qWJ9mcU3ZqQ2qhwplVb}9tjP124etk5YrkLJJcK$f%IVimz3DY!tB+YxuuRpn#n{(xYUd2yeCM~AK@^$hf&rRE!4T7z|!v8&#_t*%a3U3T+AcW(2_!?VJjt6#64e7GX#>bBWaM_f~lt5IzKJuXOV7a!Jw z_krwtXEmPENqn^6n<Wrh}vJKa_b) z)6(>um#&lj77v`b@>I=L*7o@wrhY(sqsFh=3%^5ezUieccw1w8qI)xb^}DiD%sqDs zHTmlMOU6%FSoWb_W%Rz@7^sK+-00262k*F)e=bX1)k89MXse`kYfs#|QhQ(+yE6Lr z&sqKpyQ8|2y4Ni4<%dgGkAI!WjJ)siD!qSUo2_+E1lh08k{*n8tQG&MCvUf@KKqB6 z-X6R5$6Vf~f;R;(&a8^~W=*}3?^qSzrk(I)a;LN17S|bh**91CbybJug|16E(+W4Q z+}i8?<0CV!>^%HPdUbliz$u@9AQLn&sqwUwTVI?h1y-~DQQz8M+Z1RE-VC1n^z69P zyYZj&-fR0r<=60e*YW!wcN~&6=HoY6+iuNeOINQ8{tVgeUmrVa zf0fOYcT_ZI=)HGsMqRowO?z?uixAghifo@osU+&tl zP^yyxy|?py{j620SVsJMsS4UC+?HhqH&iT>CDn*pxN&@$|_T_Ls3g z&(S|RsasACqRj?`hJLqKp`X|Kj}P7C_qN7OTc@s0_*S=O@0%GLT)gWzvU-E5%?tIM zTj$#3@=ot9FR<-ebTR+cfZUj1%>`|n%5jqiKFIu>I{sn#=-pM@3x=*0IAhrt*Lp!Siuzwr-`|Ct(R^LO*!$;4H_ARV@+21 zgnyq}7b&KG8Dm?2Jwv#F&vOEo180A0b#a|xGFoe?&fLt2XKuL0zSop`5<_$`PGbk;3O$(t*SO#SB$6wq3#*sZq~%}d|Et}tI$u+_bN_^5MepYWCA z%|F(xqZNBQylj4B@;_K#_+zJODXrVZu496ZgS1~#a~?uVbz?`7z8qh5q^05#d;4*F zOXKVNzs<>cSbpx{+Hsdp-ukJycv{o+9S?$I)9%inJm~(U;vz?SWZ6|=^NrpPrR}*p zKiuS~Xl+I=Z{_w(=P|r+&Zvo_Q^A8>$xT1>GT$F-JfO1}m~($%&gg@4yXOp^z)JhT zqcxgzxPx#%db6NS|1Ih%x74x9<5Q~O-#*;4_xDp859lcV7VCCshw|8Z|8G#Ik#qmy zuci!c3(c5!H}=|b}YR*0}*Z_=}9MPB(quW59XmwIxg8 z=Kt98>x|irzfB=S!LA>gV6&q-;O-Bu&iSXyB)4cQKHBVmgB)W4{x6HA0m#v} z!=?{C($^W|3CM9@^uOSj^^J0Qv(c6R-2YL>-Z|5E^xyE$#r}V0{&6zEQ~YpZR!8mm zoLNAZj%NP8_IcgWZBl5)K83PvgF|oHK9CkfZxyz9ZW=iSJn7+2vX#wE$vvuVa#z_v zZ#wJ+$6{)!8VMGY`~whVeABG0xSx=VwrbM$XB8Mm`p6q-Wbge=nx!r*DA_!?an+X@ zX$#J7J6BR~Qh9k`X)$9Eb4rF7s92tLS4dUAbNz(*V}Q<{yqI;NQ$2p1G#u#B<9;`r zG-)er3$(Ba)+~Qgz42rm02|*-6|tN3MlXZeQwB?4)i2%5V*^vReR}qfwi#=G1j9`? z-fHM~`fUV+nfJEb12vjd2Pk`}ZUEBeo56$um)2fu-FN`O)8RR%x7BNA-X<_Lxp!E6 zP6h?c>}M%ZI2!oUP`lnazdy=oG|37sgiDsJTit-FqyIIUj0G**iaR9QqxB4b)a2$M zU{hleF&Frk_Puk`hL0A*^`2*~5ODnd#K<@Fs_Q56+KgHlyPP$2@5YG4fmP1zGPZbk zF|BUdVfXr<)^C_MYH7_u+v)A(@duthe^WX+d+*kj+a6WvI*B#U7eBw8?H)6@)~(*s zw}hfFzLUJa3gBkxg=NYoaOpTn-f7>!Yj;y?i$y1?%~F*=81@hNFME?BoqFfYr`_*Z zHM3`_w<52sT3qwh$f0o8x|L5)HL1E^`?ykcrk1-WmU%oXS$e9rKXcTmWzdXS+ZSwi z^}jega=M0{wdQ?rk2=;Ft2*(@U)yGhv+&e|fg^quTygAJd8lXho_h;Y*o)g|AG{wd?^}AbOX=}B$~R$ZbuDVX zQCzxF)@5Q*&m;d5kE>m9{0@}*XHMa@=Hnk-9LW4 zyIrth#3@l>WPyCgp;vb|o>@?X3yr(9L*J)W)vVa?VDF;U*@_~^^rz*Or8UK(kA0^; z^WJ!k^Jd-O^|n2B?y>S}r_$-0HXw)Q7e#+@-Vz)a&RS|;`QpI~<&2clBiU5geVeAd z`QB9eEvDRQR<1HCcWf`Mdslhr*}GfF7N4Z5ymCX=X~GfP-^TNJTc3rnMCPV@6Eiy` zS~W|Zd7$~`ddq6m_)$mU8}w%3sJzM5;+AXP`KJwqdW^`nTsp0+{A5GtfYP^x8_u`iu(OS* z^)O$re)RnQ4|Wws%q^>yo!BsWpd)gxay-&Cse@mVA1bgK9D9*TJv^6EY;Drxyg;7i zSUvEfdvUva)*b^Mz004y*7;h9ooi8gtb+2*!d>!3T~`hoF>0X2c;-9N!pZBgzSL@} z^Sh^|Wy&o|<+d-B6&C8@#pRU?w%=btrr+Axf5W(*OS4v`Jut#W&w65K)|CFZVpp5g zEL>DwH=h>$PMvRsS%1vGy)eu;bndQQf{a{5R`yB0hPOVO`E2N;caM;wQs5%DpWIAp z;GFlj%*#&O`FL2>y)Q}~Pd21nwax3;L%gr-{oO0GTj$TKd6!o*NZ8}-(zz^IQI)uA z_M#1xVUF>YlQ^-l=aL(QY3B>adG5wbWcgZ6bs!5C9on%#T+@5b^4@30Wp+&<$IGY9 zJ=1JpQP#j!q18{%OS<^qX0JRiFM7Ogc2TTofaSuZBa5dWDJ#o!WX)gwSx)fau-c2& zqBVnm-gj2AL(=z$F?ZizWgObI^1#rsE5m6wFlyP|x1;wSS>>JSnB8I-S=Ti>_Beg` z71N0ey4u2iqo|o)FEAoc?ik zAhmcwO6E9;=J|r{`$+4@%3R$D(KZMY|5Q7v~u!hl}ey=awP! zpXYx2@xS8mUF0nOW_3lo9^$u8cU`zU0XydCvg*x_gA1z{q^lO_~Gvhx-U3l!+A#& zXZpqS1+&j>zTah&u%y@~&E7Ze=R5Acxb@`e_IcPY=2(=vY0sCTC#SHyqes?LHhyJo z#q!)gma+a&)~hDib5-fJrd|4WsJXv57v|i+UYe*iO7}MBlq5 z#XMKJ%t-6|23_~yVwV?Pn&%GJ99NlF_v$e&t(~OATq3Wo6Q6q4x_N5p+mC*KUZ1Nf zk=_ru&6(Kxy`?An3oC|tuK&1t_3y1;S5B-e-uSHm_FSI7bMH5m*W>s5YOYcH=1lLN zRr}-po?pItS=p}T`z-m`7cYLen%%eX$p~d1={e_$;6?w$pD)v`kDvTDt!a7em(K?5 z9KTw906*^NI`%t-f5)J9>;oB=6WypANB*h(qVLwvCcK!~>+QiM_`H#`TKPYLx> z&b?6Z_?1t44*vCrMZ16Rf*p=jEv?LRr=Qt8XV}lJhZ|{2stcEFY`yq-LBE80Qs?mp z-WAQJcVAc7^9+{9lV|OX32#=VKbw2??I*{|23PMrr9YAT_+Y7xDW0ZTbavzj%c*IC z0l50~_rWeL$I2&sxqjr%$omn>n>8o$mLb;J=0_z-4uY&W>3ed=k!e8;!#bd_JU zs$RVFtGv!@pEhez`)RvQ$Tj9I+4xI4dVODaN7kcxYE5;!tFNwS-a7kJm(PD1weZTC zMPyf>!tZOcC58iYizcNSQ=FL0)+m%CUDYui~rZg{YtNyqibWOsW1Hd6!7+MJZ znEUOKW}m>_Mg0Nhi^$+9^`_VM=ghCsZ~FJ!)}*`m%Qpb>p>y*9Kob^yvHozqlLA2b z;itXl4*=6IwD~xfr)2h8EU3qCzaMHmJLmT;|F1#AncuFO)#vMsj{r(+@%3>*0|X_s z0x-<;^{57!*Lh%2!`n0q3_X(i;Od!-u!c=xqQO3pZ@o+`mDLtIsOY+h8vLdJ}cMG#X8MNkF~wMWq0tKO|^A zw`5@hiKnFin){gUt^@eK5x8u;_EEe4;?R$pq!>UdvS9SIqR+q1*xe|%$+?dkY&_tL z-_dV~Ll$jq|)^;ako6tpb~r(z|qQkXZGOg9KxBTS8sHaayqf)iW9p{dWZ-^*nY2MlQaa zyr%SV$FZBA&P|Qpd?d)9xMNT>W3f2tKA+MfTY2@D;@@Idz3M%o)Mxu@%&RK%7p$Hb zJlK_9yS3O?yUsnV@Z|8?&F!z=yM-Jo9WwS@*^iv{(TX!K3V1UfJT2?IOOt=Q^^F6g z-;Bt=9v{AORs0HhWnrpd%D_$4^CuVFJGQ0GG;_~xWW$N_kz+pTwYzRfhtrNlV}Mjn zcAH<_!0FG|fO~sZ&v?^wf-=*;Pw+;4jeBOrrLyIt%CTQAR}IW8%3E@f&RH}5d9+z- z^(s6^KI$31EwebQ@0#)QH4_dhTiV-{pF8xn6F`0$mc#cx8oKL|=%bz5ioM3&c%s>W zy|f&>=9LcGr?|VXYp(o{L2L5+PkXMJWpDNP;#VseUge{k$DTavBA1T=;ymi@=4w#z z$(Tf_$k8S9dl5a3fn#5F02M!JuffZ={$Pu>cs4#*1652Yzg2Yqd4Xo@cTid|yS!!e zgjYAE_FVR>!596dqQdK!IeX@f>~{yf`SX!B$}?Rr(yVBkZLc5QZQK0<>(3wCj^{x$ z&RaGW)KwgL_J^)=i)-=B>Z?y?ww?Or`>&?79#wME}jTDdb{FL^9FjE zVg%C8UD1E+;x}KN>_2pO%$=D$Z}>dz=bGu#%IU3BuP6M=T$lD|RBSKG=wDvYF`O3E zoVc`{6`iY1U-S92Caa2`sz7DEnlcW?iMVx^dLK!U~{J{?sFA%=Z|}qKY2Vl>HHZV5vr6`SXDCY{#)%P z>^H%hy9VE@iqqB02Ms~rEt*@ZptnA|v~U0Z+kp+-+}n!It#>qQGl11JHA{YOQ&RMM z=0)uC$l0IX3qP^#pPI5Nojq*!l7~;{jP~`~Izx5GdGouE1{y+dzT?htoTx0I8lxB2 z>DF9W^*M*zdy!~OWNuBbfY+XOgPuBk@saXG^1>?9Yxv7Q_Kqmr36D&UhW55! zJa8W%{HF*1qr1?Y2vGCSDA$SyXTD$7dSsF9v&E#RxvN(!zOki8*2jJBLrWJdI_o`; zBA=FI?z&sDMRoSTn0LMsh#7M)HB1$J_4fN}M|R!GUw)aAe(2S`#Kqx{zG>SJe2WyHVeW+#01~!6zwK)fjN9h&s)skpx)9v)aX0MU>qAe^uM=JI zmS-M5laS4Ll3taY+oodOh=G50x|HL*zWd;nmEoejzir$%u(mLMXM3ltHtSB^I1_ok z?Aeh%OGX~7GwpdkB5wxKdfaig`|>X0@x?c%kWL-`W8(Win6Hz+MV@teh|letnl<4; zk5v~obHAH<{^`^9ExU_BYP?|d{w-xi*Jc2Oh_`M)ppXod{DSM(-1QqbzgwKG#%f!* zF23!sZFFH)-_^K$gV?*{#hrN4;z4QM(RCpY`8aim?E2U+c zV{4aozolHrJ=)Emz1Ds=rkZo44X~==xpLi$)1Ri^Iq-C2*OkF#XWfbA>BA3+E~j7U zJ77u42*t$r`_u2BeSTm}>AdaF3DMEnFWw>Kr7MivPFMVeuIl?=|Eba~JdP~iP+Ze% zTbm^ly2pNa_mrFBcS&cWP6 z?_ZDJv?e)z``wY0$h!3VSH|u*@DK;hnUXeI=dpDsub8H#B(f&AR}xj_Jy#YLH)zUd ze4A4BqV2Urt*|0+|6}8UueP?{mX+G1LpP@H!sgFQqK9`1j(++>@YcqfNB0YRwETNuz>3-G?gtYxd*8_#u$4#7asy0j8;|jeznt5fj zey4fh=q(4kt{yWQyj4)l@LtISt@$fkpMoOde^KkfT0c^H_rT;p0&J^oXcB2s?oK2IGIrmKxtmqiaRku>&D%iJw0$kSrJnS2v-km3j)(7Nj$2y(^~hE92d{L`exLuS>&TZ{qCXwF_r0&;U#qVEkPBLR z9GSdektMBN^Y(LhWbaE>Tvn9Sj+gHEWo+ICzwB54p&jSR&(hTecQ$>S%(=cZFaHut z@~pc1hJzz^pv9-hVTGCT^IHeBsq3F}@3$B2p6!1U%-(sMt+`SRCFx%+uN?e;pkKA= z&{pcX{c!sepQ2ATK0C7Ijdm1wT@~S9uT-uRA=fsjs(Y<39k+7x zprN~4lrj6ug=a&}H z%W8d~*0STwe#?KO`lJq>f#ZJkud|_Xz~yNlq!-J=n?~dpMP2Xv=j_{7*Y;WUDBhE? z-8Wj?Jvtp6TlM?#E4I6(rdBPcwZ7Q;+K}-hi~AO%hg+(LN*^ZMJ9by+Z<_i{wFvI- z=_KZDzkh7dtj>eB&so8k+OCVgWVq3Pu*A9xHD4d(FUYzzx9cO}5P&%rJ$3y^J2V=a zL7UiUUv@oZ7l^#GgmLD<+^O@H<R?OtB{xo?rQc3lQMdb)WSXcd3FZR{bA zZQw;!MSGX)^-<2}IX`>jbH16H!kvmJPo%#)JTwJhDB6=w&#zeGbH+d3e+HVdf5@Q? zuVq8qiSx?WcdJ=~_G#5^)#!SdEc6m#!B@F8zO?-5oHg3Iu9tEy$JdOA0Ca{u-W7g! z?|ad*GWN}m;+5b9qQ#dVT>gG=RdzgfT7UZHboGyC0--@iG&dR&g`?&-7V7xyqu3Eu)Vl-*QE?_JX&vsdJ{pEpWL z{i0QivS9}_Tkh)tI`mIZkV!dC0yDI>D#{@v{rxa#{NyU zl7U|zA6#?~xY>K_`HR${X%80V*QjHsK_uUMZGK9_Se^zB?ORvtf#4ON{X~5NZ;+?{ zCxZTe(C2!1^1$icrU%t8JBf)tamMG(JcV3?X8SOfFLhYX;Jwyl!Nh!e*Up8|fM)fv z@S`T?&dvI!zI=iI`PE90qw&9JTU)6Em4!<=V?L{YY|^Kb@VdUebiioVe&6KgyEik@ zb>ACjh8m>r(-pn1*Zn;2(GPz$qi>Jyef`i5kYZOf8D9^Hi3-J-#800m@6Bj)YjoOQ z&FLw<1IJ!neD?cyZEk8Qxx8y>4auAIP4lB~&RBkO{R9%=Mw1RS{cGz!{_xob4b!zK zxIOPJwCzhG4K}ts`sPK)T%K{1{MzvPsMV+0(Ko$b%?KbDKKiJMQuQ}=$|vj_+w0GE zp^#t!SvPu9ezV^5t&JbO&*rBsu(oM*vA%vVecq2N{0FyeQEhU)fBWk7z4h~UyDko_ zz;Df|zF43epFV${@@7e3%*gaJTZmIQ2%yH}W5-U`W0Pi{^oKX5^{U>u!dLpH_Rx;- zS+?L=^+gr<*W^M?!5c*fg!>47`s{C>KC@9{>~rEoX6FcJotV0!{ynhof833gUHHK! zdG_F{F0(i$`z!~X&?u8{_DrztDIhjN2&YE$xmMr6&WJVc`FZf^dBOdvO>4Bbj?Zb| zVgSML<`wHHfMMmo8CK5wgjxUo+WbX7E_1BjQWU-a#f4@wgqgSA%^SbE@&COdq`*JU zGA7?mM@GKtXR7Xyxqu++bN@myC@YDI<=qr zK;42h^O>Rz0HLM+t!#Z#d$#m7{;xjvW={H7tFHH^cJuu@VAINl^U+7|1rwm_{T74X zb57goFKP!tGji}R_thtrldd%xsNK4mc^&7DtJ&{>pkw!Yy(-&;=xVQ*Ji9)wc8m4o z!l6}p{}*X*9T4@_wGAU7-3SOngMdmXl0%0BNJ)rFiJ~AmbaxCW4T^Lsh!TQyGf0Ru z(p^I{bmO<@+|PYD=Xu}vukSB86TjJet+m%)ab4@g-Fw!ErT1A|$@kBB#l_a23r#N7 zc!H}_7khpXjR_shHeb{Zd5RepFB~MWkabeQ`9eHEciMx^lMLBcS!fJjFhQzy9d? zJANaHLD&8q6^XU4rFT24PgcK_ZPlOt^lkO1J>9Ia?8{QhGqG*!5}p1EUe<_`xj1^2 zyHV1~pCoFR7AZCt`dA=w&Als0n0Q}&AzI;iegd&UndLhG11%tB6tOtns33n^|DIRp z#_*bAT5@+PbnW7Ft4Hz>C^sgZ^iN_shxQgReM)Uo*5;O7C~ujfySh~v^-Ity$M zCtcH}k7fdUAAK9_e0jdxBU8QC{{Z>E`C^(}=BzkUVwLB7f7m2nCpXgY)y7!au0pI6 zs&(y9Z=sctD|VAIqxsVQkFUY;*L!6CkT7j4NM{ctyBDMmC#WSNJKysWGdUrsOuYBs9RN+C&pYC{*J2;=_r1Ax>wA~TcnghcWvTCs zKfdMA*C&b2Prh5kB;9+Rb$&2j1nSRgyPX0JLC=tjm?P?Oag2Il%dgq9EfvlntlA@e zYP}4vaa=n&sZY55B=&lHjunqRD%CaQwVLRpQ=G@a`sYd4X(N4O_m^pzEgH}bPQ=Xv zNgxR1@d|^g*uTYJKUVy2R5+`bV8ol@<}~eK6kjukKFFZ zYIicU!bixrjmgzwt|jbbZ$MMQVg^i2$qB*<1HNhvmF_!qrwu|a(aeu3AGam8%l7Vq zv3To(o>T7+COO~M@!ErpaZ#`H4({~97#Q<)X-{AW2(tZ51T#b7JcmR)8g>3?Dw_ae zTtyP~9o^U9>r2Wk`S@k$dp)2uBteWa<56v2HtY)s{CD#AkB;G zli(~bnmb2H9T051A65=a_c>9q880XGPcGW>+_oT#qN+wW6C=;-c7EPEIT*LwZ^R+b zGew3p{q7mJDypNcJr5WA`b$EaJ=f#7^?c&gyph)D#&Dq#V;ZX6{$wQ=k*)x6ut1ab zKYQw^RTp4y9WSrNSnWopHeE6k32VNy5%4`|=_Cg_Xlg5J~44T25IxD)*OxXABMO!bgNtMIPS>rMzHwg-H%`h z?m2>^hK3;`){mFlJ&8hc(TehfuFoewA12$mvY)#ngvf9q+DE>p1+K?CiwdxTVSAoC zFMq~Uz<;I7$f!AQ-+SY+zZ$GzZ=4yV5L$OIcFVBSxjZ<%2gdBKNG^Sp0p7j#iAK!J zzHP!Zwm@>D88tpC_h!8FeqW}d?S2VjZMxq3lp+lbg&V@Um5X|XU~=g_*f(4ef(z`3>nMJU8=BA}XK@WLy*euF>#~vf+^Yqm61h zhW*g12&%M`huQZd&{9$IZonTeicXIPQ*AnVB!xi}rO(R8Q)OM1rJ5T}qSSVa6LM`U zU#uZh6%afZ1F7CoztB9vAWNg9+-$r6M#@Hyo{h|3TNPawdi9IoisAyZS5NsHHPfn# zlQrbw*(>jvM*qxGE1ak#bYAo_k^?g3j!K2sEth+(e$H(sAkoB!^Oz>L3p4GEyjp0F zVatJgv)dNtu2D0oE<6&@?Ax}8+G_YC9sYEifzh@>p#F&6ODY#>`aYfa&x-J!vk7sn z?GvsTVJ-)&t(4V`KGJ&E={WMJGc*rFMG+Gd&(V`G>4_y<&5HE3d2=x;0yotdrVXF7 z?Y2(2RPrcEd+4e3xtIH%`hxk-p0CKvxuJfWOr0hG(A!?zp`5bE#Y@s5#KUqX=Jhx=tYVC z^0~DYISnqAlqW4OqNHd)QB=;eOm-ZyCvJw<%&!MuK;8iBCx7RPUkpO1Oh}XioO^Sv zsDX@0z2RHbpwN!1i73cAuY@9&YhEymOX4-9$_#fPSJK_)!q9wC-RN-#%`G&gk%=qw zxyU53#mPn$U9}Vb?_no|u!9>z=-Mhp(}3>8cH~4LOh+spJ%}}}U?!)9FTt!n%gZBj zv|ifNocw1QnYsk<6)NB)JSI?PA7GVKZOP^~)CcX>VdA$Zp%*nU(MsvU3i9EB{V*~v zhc5|864zxWYw^$>X9$CPjvq{D!ATK8CEaFqV=!Ou*4JB9g#V+MAF>-1Op;>C=ysYY z8vCQ!@(AfO$>XPFTo4ksH_-}sMc3xhO-+$767gPi=@Rm#(#0m8k<=nriSid@-C}2g z9WBNj5aeVQkf-j0p~La;-i0-fmLPJ?7dxdJC_X)M`7khSa+CP)&@7`DS6eDxFa@z& zlf4>gyl1~wP?4|qa*&Hr1 z`A|MX_8o`7b#s@93*u2J9Wx1q;2xgJ{ zP}{2d-Fdk2T7=Ba&UNr9)LJSF_5Z+p_$qB=b}1L&xoMq`w?IWmK$0fPwUJDKT^IDp9$_T(NC z;A?Kc5yPo+QQGKxQIF*bHBHdYwXXt)Q{ipn*%TAodnZ_FE^}ngLos;9(B@e=7f{}b zS|j96p(tP9E2K86b|QRvxZKB4E9Z(odAKmsr1QL1BPjQ#TLRH^V8hmyda8u*#M|8K zV(s?N<|(iE;H2yG%&zc}(Mfi-WOGV7H|x+r3KvAQo1yt5y@ke_^DWexBx}6DMu99i zo=mtO$cG!pHD`vT$F&pCROD`TH9gvk5spV6)~1Dwj|{t@Br6WOKTl2N|CS3$j{)`* z(swT{ay~{B<9;L8m$ABG8J!ctaPWK%4^~l z1RGO@G+)CTqX*;@`W8K;8=%W+WV52}X;ZU1>@{F08v>1*VB4$p64;|>QdQh)oe}NW zl=Zx*gNXtBjo3Z-$n0xM=5I5itISvCl&(rOH?jHAdH)&5Oa&8?Md+&g?M`azI$pq4^@lNX{WY0f$+0 zytrU^8=aM6`~~^S*c{2hDjD0tbWjU=E9(2gqcV^TQc7nu$f=a8Ch@E9ZnTLQo6|kie(ek6O5Mud?uy}MRY3|KtmWX%?HzL$Ii=T8GvPd zd+FoF0DNL7ra*N2p9LaKe=~9}372(xm$&H6YsRuY2CS_PZk|2M8b=it?Ycot#wJ!q6x4PlIa`?d>ZZMMJj&X_2 z%K6Br<<_IG_B*%sYt?fRvz}HD4Fn7;wSK&%8x|S2rY>*X6UmywLn2&v&{-idsRBEm z1#anE9&WCrThH#mXBwZGCQL+v=qw~vp*Ah3B7DERBrRZO(jcp|vmpF&PiG;C498Si zvvUMw%61=Q1rzI56;mEoc~Pz*DmgEj0`O)N(X%#>>TZRS+r_P!4;eJjw#JMHB#oY@ zw3dUCimD|-e#d_NZcR(b2J~-`+1kqVJnZ~$)5dkZ)RrPYLTe* zh@jV$T?Z_Rnd!dBJ&Rt}@YWGv;PQxK@6!WNH7NT2=i<}~1a)I}4d*nIquXVe1dCVa zlUWFscraB_-9Zwj)S_?Vt#|FFZtp@zTp37&gUCve!B=puE`#uAC^y}QLEaDC+QHrL z*H9;(O{ylSnLu((e6Aoh>FX*f8pudIMrUq~5+z%txCbyz@->a>g=vtIg@xH?o|P)S#j zz+^c6p3fkpj||ivh?&kYalkXE(=x^VuWt7`K%J&YM?;*;>61||`0l-3_mVmVCVcF^ zMR!Ftm&3!IP60cYDG($=HV;9XOZZY^BJ@nE#slPuD@|wMIO>d-+myL%jG@0)b=kZW z^?V14DBn9l48tsO?sH?q;LD=|wD|Owu4RcR^?LsacCSd;?m%UcE#K|4Y#9BaF)F%Nt`t(yRer8@Pi?6eb(pQ3q^ zl_$?!qw?)10j?Zrvz8vX)Rl}7I7Q8a#gaI~Pp1JgW=B5hV$|NiJzi^1nQ(ggoxbt) z`@1Q=7ssAD6WXf%y zB^#!MK`15U0G33z^i`J=h}{v9ZxQh_2O}?Lg%me24zy()#(p8Jt0AhxM5NhXh zx?xqRvqhE+{RxtOTY~#%2cw6ZNT%Da?A}L`uF9p6@c{Gz=bm6r3z%KG^`b436clwf zx=WxL_1s_qY%chdi&A^N3Lf(jqW3HZ^WdrL@`S#1UdKBgAk~rQ7QX9^MD9t+H>DcM z*lpgf$zItym6>+@b8(Kec-tDmh*+zN6#qToT>e(!T`bpwkUj>H;+n1L!`TyYNwft` z#W!#px9x|f)z6CTJIUO zMP>pa5T`GRf*BuOhhr_ACJ9?T`oKP0AR-lu+*tB^0b+fE+3@l4%w*tAUiiE^m~iYt z*PcwB?5$95R#^Vd&m_V3Ok*zr+n~51mIwcUvO4zlYza;G2UTYLIFJ_II8#%UDT?7$ zt(QSylQl!Grg-giB%f^M2p@1F7<_MQCaf3X1P`)uKGZq5_9c`FkiKB@HCtI<@gsCanW)EeFq99RJPgsD9}9C(J1 zyWW_ZjFZ{q9Vb{jlN5`O!W!?DO>|8hsyhi9uqk*yWE{2{3sBHx3xl6^kgqXy5GL2* z(E(-%M9dHl>t}Kr7Ve*Qd^ST?j`JSm1sCDDSIz3|pw$!Y<4z5DQQ@ri=Dj+i?9-jR z@n`~k*BmA+B@o}-v>N)_LGt?@^FY)d_GClb@bGA zCPH0pm%Kd}f{~YOC-Bf& zttO7^XS=2-1#+o-UQPjo+%ntD6V}a1(wCD4vF1wA%C$8M%sAGm0jpsRJAUMs>o%X1)*8G8|oj%?L-*m2S>={YBdj#SkJ)OE07@B)3zBYmIIZMk*}C@Iiv+@chJW?2IbZSU%VRX zSzOD{4c!zU0LR@t$SG6mBVsdOrss7eL>9_EpaH3^651-?-CadFO?w}bqE6g*N*DZ) zCazd?-}Z;4sCcRBmF|a&MO#f)JLl=_?XF@q4e*}{EwDCczmsHW^H(&BAWPVIEyTRo zTjzObxN$Cy??U!i@@advhh#~s4b{2hM)}?{eUa513d!~c#&Ycb79!o2Eel9P%YWdN zxBreav9O=u#R|v6Q6s6;u8+OQH~o&)>vQoGrxs3(CtqI|wKZHOIYuYLqYBZ={wWf5 z#zM`=mC33wX$aBL+QrvlS~&i1Cd-CNSMDB#(MkWqWT%FzNNFM}RiG9P1G5~(g=+rc z!)1*+m`Ka5c(eqe@fO?N^B-2%D>;@ucO=NkZaWZjNzzQG4q{3{PGlg}gx#;iS)1Kw z{`lO)HN?nQlM>xdrP;JS%X@Xx3`MId2H74zP&OZ8^Y7ddqVPUiBP%#7pW=`#Nv@w2 zZ0Ai(C5qLhcqOfP!a&5G#{&%mb}}1-zU9zGMig+ zr$tBUY`?vm-UU6(WO1}heM61FCT<_jL+Ng8P+A z&Dd1-hz~-ITQZ?V(N>^&TxgmDa~}*8YtvQ_)Nv6l2eqhV4q~jy^#vH@{2Z+CQ7sNK{~GP&%l4 zS;3VDwGf}IfOc&Lc}N678#eQx;c$Q{ZBE@=2W8~>mB_ETb#8lapvip(0oA4J-I<78 z=vUy3?T+e}{HA-M&+HN7Ols*?TNCnO+w*M*PbZ$mV0xw?v0v!#cttp~k)=4HARN5y z=5~%_Qll6~HJj9Dr7GrUZ$4~wW90W5^HEp*R?{Og3W(Z~FEnRI8C#%udH)*w;-ZUh zAIiOsOrU**_qy@-{u^n=GyAj-`4!{C92OH-)2OHkiEH-@=sxc4uIxYX0{01orjl<` z{P4J5A79Yc7h&NO0xIo~cZJqa9n*(Nyj!)q8uU_ge#q9sz}%L~-7QK5W>5*{AoDi# zapIY!=+d!+Xp7C*drDN=N6(mZIvk0^XXYqb#S3_69qTOe$4C4Fw|?tnOWtg~k|~4A zXy&*x!GGZcB<$OY^7tOIHM+5B-on96&l@BAhg(tavbNZ70BVbbuDTN)j@%=}qgA`} zkwz{E=r^CZ%}JbzmGJfY7#-BaOSjbk*po`+hA@#AsQ|^Y^VNxmyLp7ZQZzRO!}|>6K5JW5yJQrSd`*a4$x7-KjXE4E*GC{$KM>sD zT-#)<3Z^0xfp{D}E&MWUgWjJob;X*GApkf?4^w5=q;r#n0xvU8B_ILW_RNq#CVZwe zvYE)dPKUPPVJE?vj2~>V(71XRjScF$(-0g+JJFRB@%U|Jtcp}<7g;C(f~J~8&7tL^ zjYV7Jl*|rEqf)k=@bMvOo3pR651dfrOpi5jwi#VCjo`BLTF3$3tWHOBncP!HgtUVZ z)Poc+*<*uR08PK$^?AzH1Yye@F|SdEyvDK_56yx5&B${9RWC&{PA9+~xao!z%^#o{ zn8~UpuG+dze{tP{E6=XTlbO_JxYF@8QGGbo=Odrzbe@icFEuki(ca$Ik9Ls)^Xt!+xNB7TqE9hxwbCCW0lcgc58Q zW+kS!<2aXYfPb^l*KAC+*7vmZ^nR@pFZti~N!CS-PgOn+;mu-nLQJy-lDi&Fh#zXu z`6O?e9x;2*P-1UOW)-dUaiuxTtPnwhxo2Xi$e2p_+gG)kOi~%_Q zP8itOA-CV@CAp)$Lbe1!W$fE%5LivURltNGXGyaQT$i3HV6>~2)aAY;(KO4 zQr|lcp*@&A-KGsqJKgeY8Hb%H2Wd5vO%)D|M|gZuN_Mkq1I0yJ5#mLT=w7fR!bwS8 zvcL7oN{Oe<75})}>2s~0aTK%E1=0(2QwGuZ5z&A)YBxzy}D}{ z+)QO$7o@PCw}xLI1ASh-YNyweUb|f$v%z$Gptsx3Ap=rN26q zSJ>QqoZixq-2?FGD{?J{}Mb}w& zt5MjrAzJ(Wh3=Eu(MAJwwkjgNePb8YAX>FjB7Dh{#TaMiOW z?2U#$7fqv0_fsXD7g9kHP}v-a!O7Nplj(130C@fm2Gyfile~Wb1jK2x3blH&Rzz;9 z_)+zph$FmhESp4ftg#KWZISJ`2r4=gFMGH7t)7z)A~s1^$sl=Ej;K}|)rA9h1hzok zo;HEnD^Rlzz(IHc0sCr01W#1ZiO+xP@;& zE`6m=pzGy^8#wF=@1^S82UqpFR@Ai5sXD0gk-vm^@AWk`UWr1Ip1R|Pt<53*l>j1S zaYHVfJcECr4Rxx47>si2$Cw**?LU`xBiRH zp7jAplZfNSnJ|J1KvryDnb!l@3tP0saN*=DVrvOmv@!vLCnlI*zu@UdP@>adCY^KH zi;urmRC_mw|C{0TfRrRv%Uk#RWC%zgJ~>(T{Tpf@G7!ujJVB(Ogg~UDB6;4D{ZMj@ z^F(aM59i*iUmvt!WVrnpu8xsG+UX_GlBZa<1ay&@w#TfBf+?@o<7=9t8ND=3#Fjq1 zxGOdB*@XuU;1P(T2u4x{ z7MBMpFahS>pZ4u08Zh`ldA4BZFGFNfEG&Zq&yNpk9#TNqQqWL;-%`qlxdi@NGl)S|rzClK z+qhQDYjXIz`e*Hr^3O`(v(131VzWX?W4zqoLyeEUauZyGg?v5UmwW@7$3Qb-XA{L0 zo#D3^mOn$LRGL#)6~%xYuRO4mNxF?d5=AYC0{V3DodiCE_f@vAk_r5MMKA^p)V*mx zN?z8zAY>$= z7nHrFUl?D(RREwkBX~jouWMBzi0b(MEDi_=WdBdjYrg@|a@}}(4Gh3IF%;jP*w{=YoGem<7LlAN=`xaAe}<-x;{9 z7l3ch%`5X_LL|V5y+k5|nRqm;@$KC7xfmM}$FzAY{?+CIYw`-PmjI8FYKk;uU8O57kK_3NM3(M zD&;*u;Qg9M41Tm&7=v8?Br+`j-`+CCKj^=HvT0zi?o{^Jms>3X>{3ooVr^eQ+SCK9 z|94xT70f9LKmh10g|ZrWv&EXu5;FklKU@Ci6wQDB{hwXSJ_kKA&Q~>Bx4>q=Q_TNf zkt_(t!91M$uqrw5Ty5}NP8+fOh|A~J0DY}L!r+n#tkuEW1)sahF2(f*m|T|fNEL<< z9E}+vl%|++Dd^~Ru*Ht4fI)!$*2Y{3dIs-LFQw5A)Hh>_K@n47MljtO4}N;t7;Je6 zUW)ucgW2Lg|NhT*qd$NrhmGgCHJLKabl!VQo*_p&Yv#k!2BB!a~Fux zjUGtHzXfbf`Ik%PqyJG4kcmAFu#LISVNVM%Vzq5Mk{7dd9*Dp8%ltg;je7fADgTRj z9G!<9#;kh8viMtLIW5m?5CiaNr+Iv`ilt|DkKdL(h{`@YhxKylikJlrzRxrUs`x)C zSD?xJ_eh+aP_T_R_c$vqCr=gcgCkL%Cae$OyMvfpapPcd^HR@5azM`%TD(+OaQn4^ zO!<;ilP~Y~5e%!HuW!B-?6$E1XhxFsa^D0C80DrvOTo;DTfiK}?8~3^la&U`+97OR z!F=I=9q(Jk1hOy)_b~>GDp08CfmWPTaUH5nSFCk4y(2CbwB4+(DL>5ahG-7 zwjQ^sc=-G0yTSSDx6VFa?t5JPIJO+DE#0iHdt10MabveOTf;g#O6FX(!AnXL2R~xS zS#-LHimQA;)8yBq&#};;UE7VrJdf$^4}h1|2A_Hl`3E};^2QxZb7V3(g)@2eUKnWK zPFHuha$l9x9Y^~gJeC3h(0JbO8aRG)D0P+t7+6sUpDPhbq6N9azJ&uHz72rHLWR%U zDnR;peT_nO5W3Bi>a)82w8o|GzVvYlKxBQS{l#3E?t9D!SYZCGL47z*ujb>h-3zL1 z$}F~bD739#^K4J-76rkxyX}SLQ-A6M!VuZU7uqg{g)i=+fX_Ae<1K1UC?%y5b3(>N z21$U~{O5GA$^ltZeK*xEe(L+D?jc|}v&%UCm!#}^JU0LZa#P(;b8S>6|#*x^ID&EZ)k$GFxI0EID9o=Iizh=BHqyDw|lI{fIx?QD_iV zcAJL&pBltkXHmV*@0-_tSD>!3kvutTB4YBHsLCY6Q0(yRZa)Hpa__k)%DkH}^;EjA z8csj);M$kew9%(A9w@y{zTt{t9nFRe;vTE4oYh=UU{>9oKE3<`m zX1mXe(5rZXn(1jx8GqgKR|*<4SH(|upp3CqTcIYrW|(2CZWqn_#tbX89}h{obab3~;4lV=s1ZF{`;E7ij~RMvCYzot&?y|h z?9?%8`aLMuZUPK0R!_ML!?4UcV#nJcs*=zP)W>a4=Sy(yH;{ zx_p>O!olDN`+7NrRZy-JPQ;#f2AYB530-w~3T7Ov$MfZlBq;z`a#&hibzQqw{mr1} z*Ih~Md4!(K+NtKNSNu-LU9g@nOJQ_DtW9rCPK219DG9k&g*Wq#?QRd9u+RlL)Y>X7 zBD>>Zj}3iZcT%W|N!o|*v?a;tc|=hoc|iR(6o7fGz@VY3I@@)MPucJs46MYmjNA2+ zL{WSVcMb9rcNe z@E=IQX_W!U4^ZKW*4T2f1 zpetW@UvfJ|_1&29Ru{{cqDMZ5>B0P^JK|z+*tC_L?x?R_MEYLVBd?v0tz$KIsejXz8e^=L|aFWDP&gUm;79c)?=zKo z{XkWhJ2LLq&h~%kTA{63Ywd;MX&ps@n~5Cnzo8cJKmWf2PXm55YRoy`qvc6H@S7f+E2mDw z=h;rDewmpwzfHP-i;UAu@4TgXP8da!n%7xwz0xDLcKd zoI5s8F(l3ge`MKeTe|aL48GOTjKN>?y*I}8OUX$u>+SKGW%cz~t(ibuU!j@q9C)PuvFn7nv7wq>WE7F zY$Z}Waso8kxKG`Epq5b}b;y&;7U&T~Nzb3_QT8+Ge0>I#IHYxF$!Tq@_Z{E`IC!wJ_`ePPteD9&r_l4)F)N z4pdsQ4ixWLSuPNq6jjOnrXp4XM43pN+k{22+@lLB#cXPMWK;G@IU{+@vnf@HuYJCF=K0Fb=FTNsifO>eZM=MLUmUA;!sqT0)Bdx z?V63jP>e{Iy4?W8sXFN*c1udaz?CnZ&QYhgDKBkBbd} z&tax_IY|GpK0(~tAmGc586u8s9<)m8?TvM*TYd7RC1{V5th(Eo^pX-0cEn)(eeaeB zS0451?5IYfX(8LQoFFT$r%L}8{5Brg>RhL?XG8je8|yGm*e(0By2tD~W?~{+rzfG3 z7rI7u_1|@Bt{Shu8KuD?py#E;$$0wi-w(-*0ISKAs<;2_nowl;?zUzv>+#O3xG1{% z4V8gFF0M4+Z>j6&C!vt3QpH%#`tdmLJJ}O3pz*^yWeoq`m^=imN8Zb?z!Urge4Ij1 zd#+s0hV=S>4dt&N4k7|l3Hqu0R0e2`wVYB=o4p*?I41fpC5Ad;7K;k`MIr)Tk75Vg zhvB#Wy8EvWq4~j+++3}H-38hYHNbqMqP6quzs&)Sh567kieI?kLj;7l;qe4vrr$OG zHr~J1G@*f8tDy=R@6|3e5%-0%eJlUVqAIy?scvYnC8}!FestyVSZVw@w$otuXz+v^ z7JOW&XL;@4JEO-2Ct)oIH`!r4%JX&W2R`uZ8S*O?!?!rNtPB7B*&s=b6wW9N@PP~MWj3*1WVBWuY*%^pqn_F2iN!2T5A(H3@15n}_JTDSRcvz19C*CUQJhGp z9>TdiPvBVjD+5(Fe+vEU&~LH=WkAKAVs`frC$LR`vBkb;2Krz_toJc$y+2#_^M4r# zCB{JPbqh4Xmnj%A8e_~eNdEVe>=`gm+CwL9W0uJVM1byn_JQ|*eFz8hp;oa(j5W`A zV?K02pBVh_4>2pSvTM%)Xk>}QqUvawRe~32S?vJK?a!5gTrL2sbign?(}M`9ubx#H zq^FOKDW%z!_rJ(X6#wf%XLR64tRMZ`R_L)GDmEs>`-Lx0)>MFJ!}9fu_%)^W;{mBz zNjpcG?a$e6lwpI9k?llfrf-TbY!5o!lYO#<-j|9)30xOFUE?|U$^4hO&m3?7y>GNl zJiYfXy@$>dh~=~Zp58}|REhqtPlQ&63X(ZhVq2)C96jTo!TKm-2`cN1A5QW#5`YTgba=X7$F>%t$>G?5)6HO&hiw>aS zd#Wqpx(P9Ob!0QVpN|;U9v-~9f13u^ZVX&d$6e=(n;!=O)+3Lb)A=zVYk`C6j-c12}aQ)eu-6>cX_ex z{o|L%%D#|XzsuQQ-_nX>YqO*O^)cJ|>0tr@fLYduQ*o)bgGLIcgS&Vz1~=W3q7v|baK!rYG?<*K2AV)MR2Mo-6IKco%YrTJwiUK;lkfCfK~hMy3nh3 z&>VB1)*UT1PrzsK(gHwkw+9q}^r*Az4UzKDwMmuntsnfNzx94K->|9#;9-?9jp#Dh zj##ezcze~;gN=7Nb6d|k6HI(~0jn=-j4p3)eN+cf^I(7==xXb+4p`v{fH2-pttm-q z9d{)iG*gqt;-IdZ8S7ak>An|FEQbpV2n{g}y(g9MOis--$!E~++SlXd1>ww666>RY z1S!++{iiD)v0%c`%sqB+dt2`YPcS}5AUzUE7{nnn0^mBK2O_j(%0m@HLFxl z7I_ESG^&53Oq+3e9~WobX!Tx7G!K$^Xcp{XZ&l|Y2>Ofh=5P1Afchohg6koTi9zTW z_zzo3|4La^0Da|N_453NTiVg~ZK<5XcM-H`-(yI1Qyy!4&c*N>Fwi=RoNo%m|1F1z z7js^X2YnKbljHu64?cpXq{BixWfkaY1+sI&4@zHl-T;VELZO#EX;NTI0v z_(tZ!m%$?$(o`{pPs?sD&w}o6!*_Ba^X~X4=@Vrp+Z2QKkJHm$yXy38)FvunfW%EC z=Dam!WS60mc=sb1*Kk8yd#?U;lUn&28l2KxX%_G)z(iIlGOjZN;~z?FCndPJ0QxlN zgRJgg-a`d4h**Z>9o+|lYkImTwmFKry(Q*AX7ll+<0K{?CP{xcyvEEEQ%1fJ{{)I~@D!xPwcS2sweKU{(%ZMvj-+}+$;xl z@^_`?J*xiLcnhE=sVX0=uX#}XQU1P;#N zcI%ZE|A;)XyIwG$%fM0%0{j*^!5myN`mJ8FZYe4kYotGm(5vuRs@|u})(G~yLCc^2Nh3nwuusCkbpWwvsLtWN;T`HyUQ17U%Qn~;g zq#ZCU%F=)IHs&MrlH3X$SZ;g>Tro#K(J z`c9Qeeat`pak+IO6(m{IZb*x+nFsLwKWf;U<=}F*0Lc4S8&jdjf&$#?Nt|E~NgN;@ zSt?&yAdVC_qk2r~(zH8664UJFA0xm^+0Kt{yttvB#N#e+q2`9&IbExgBKFM?Ogu?- zBlvn#FMlE@p5Wfp#kvoeyubyEgh;@aaTX}eu5|kVnUrULHRTuF`ux@&>U&We(w+ec zfH#RO5jraf%00FhMt^*euz;CwaOZ$@n!t?iNH#-|oUP%*gF!-R4O5@zf54oD+RDMo z=Q@}($N-$sO^eaezi#46OvucC<@ImOU2IN)zRT+`^n*~WyHx*egSs^LZVHx8`+j4X zaB$qyxv|s$YBH6^&wSpbA@MWu%y`XUu)wECk&=sNDuj@EAmdIjYT@@N^5J3&BLavO zpP79&LUc+?N6d&j7yr#wWkPwGoyE@F^i25?5H!Gdm?(Mu2UI=~YTO7OuuYMLXwzIh zn;pB*86+p7mmoH^A?x%8Ges^gLS( zDh7v0NoL;6yCsxzbv@upKA|pKJzg+!bF!vPYWf?n`NErm1o(dOSd6*q%FM;?TXl!= zIgQNtqU$ZpCfe-LMnTIN2N))hZkc=}Y3mk1gcG|d@te^)zG>(PYpM;@V)G4)(_!y* zJ1u35jjkWyCi+RPdoNr-OrA$j-;4M~x7%Hx5hTQg;EMd4M#>35yLs)Omz^PLnzF*Z zOS~VkoBF(4Uivte%76VipZ_mYwMO!n#Hz%h0=m>R@eF{Zq?g61`xYb&5+y?d;M9cb zV}iJ%kZ}nsf)--jS~XQctQ5sICGBR{9b9cy_-bdER3vwgl5R71HRn?58J1Wt=kk0| zqK-SH0R&9JdUu>xbxGM8w-23nRAR$~BInhzWRxip@v=9gaE<`K%2Fy10-poNpdj)F z_d#T8ch7f5O5Q710u))=CU}EbXUtErq|-LOf)8*_RQky-2OLmQJmE+ zav#+pk8&xl1{6dS1bv=ygL=!VU*VOr!19Ju1;{UFd}77LBdJ^rj`N)k7&rr9|#HElh#y%$A)Cdlc^&OAhCCuw_sR6@~iux6cFQ>8Tx)k7@IN zD2Hh=Jy}b@L|C^#^c$*=v`H1lox=lZg`(Yuz|jTRdmU_XnaG=wX?7smjRIWt2dT=_ ziV3rPOF{IAeK5jgSPMUQ25at_c!?9tUAAsw;mYePa(<3WU*cI?0u8BYG?2$6u)Fy= zxT=K8lp0ICBiOwD)mO5bhr`-lE0R)D@;23^{EB1rk8=vef`J1W{^EguUgM*br=d6~ z7ebor&w!W-aLr^DD_j+6>-`6$+|bWR4I2GJ{2HsG!sGq+8ktcCWTC8Mhg@7|qrm}J ze*|PR!&~FO-N^ZoUVT-vIgW~g|CypPVGhkvMm$;+xSdb7%}(sqbsQhiq)S4(Zxst@ z>RD#!L*xCtu_8j`SMQMaq*|H%C-e>=6S`Gm(f^-$IAOtZ#0?^Q=PfqTl#Ttec~~u z7-2PJ6Zc5nYDzmbvaY+6TpHd$<15h+&NQXc|H*y%{p$CGIqAO?O)|;K6@AXZh`2Yi zmmWZb{Sqs;y?p{FhDuUX42!$7eI_gc7AAXFZq+4LLm~&4`xmF%!eR7PYKbG~j>hx66BkaXIoG0lRAK_Z_rlEd@0p zctrCm)2!uQ58Si^dfIcF=m$i)-7~fi%tiIfrDGk34sfoD>z~MxR!cZHPg${ot_-!rU~txL~MtJ5#A>| zvl6@p`JrEpMWn;yE&7X-%sO}S&dxgV5(S-O0CIBDVWE@UtQY-SE{1Bj&?Etrj5^XH z9KY+|dSn-y?`)g^#&X^o%V}Yu6X@i&s<1d8EqxU&>QM_SVz%##DwL!M>5_|1``<_F z^6Ds8L>8?Q_UWHS{T%7oT@3#D(X8VXX@|^vOl_>#s2sK&@x~z8D@FYIxP2@u4!oP- zwcj&z!gBwx!`!ibFCk(EHxW&?>S&vdCPmChLFDIlRQ8r1s2)wVHcI&8sGms@A)YA{ zD&w@1HM48ohG#`$2XO}SKv=IRpU_W*wXwB40*-?$Y;KR*ArOs2z^L&nbzIcvc#+Qe zw)lDLosSgEepEql+E|UbL5V7CE$B>d+_0Y(EdeDwGCZEOgG+>pKM;qs!*5q?>O)3t9;HYFaP*UTiq%|6}eg!=h}v z_faXCp}S*<0R{vVq&p-Aq*DZx5CchRP)bVaK}Cj?20@XOE&)MM8bMl+lJ45qjqm&4 z_1k-Y-5;Lgct&Nor|v zp6qLoYj@ZDw7L4~gY}G=0sE2Hgmy=vlUu!h?D+;ZzZ0%)O?=XQ&~ZePcI9*m%fIqk z*JM$FAqPM7%ins!-#g8;TP{B_{R`1|%k0PHPgCDv4mR`L`zyCy%=gF0YF0|{xBL%n zMBH2mAv~5*^g&wrimdX&H-_T1ZO4>_3L~GHB8;T#mS3{?_Eh#`jDUkgHyCb7`Jmo5 z%qzhPkLPO#@zkqDEAN}|nD;AZ(Vud&`wr_SQu*RpCbym4YEYuDI;SZ`G1;g$3VA(m zM%6{`d7IH91Z7C#V@(4%08uo~AFM}wT8;5d1_;CQ3Kjjz@5mf6Z< z&#qO>LSRe8BtuPoS8SS?>;B_K9tsRi+ld974X2ZK@G^zGi4!YM1Sbt&9CPNaf9S$c zvdt-k-RT0nBQ!6Zx2M|GkgoHQGfCop9x3MaLpA@{TIz-wE%ZyK{e~y2XRrLrrv=BV ze|KkSME(@}`Y@t%Ttx;wU}_bo?Nfwqche;nm&{h(Tzva=vXrbl`^T@}`%}W2D>2Sr zyDJ2~)+Qc(&3^D=XzbbNKXd(67Vb+5PYV4%`oyw~)@U5hg*p$GTIll|ISY)GPR04G zlfA;#osXlUeS729`kYT0dfT+l-XAK!K;(2FzWW{k+UmDqIP@8V4L~cht=9+QSI*dOX-`ff6sTjj0cjBm$1ZZCO z#F`GsQp~BJ`4L!-6~4#pRG$p+B+CXwCQ$JqACB^B7@sk zx`!T(T=&P52`QjA?ko~E{o&cVh?({>7tMQ}r1hnc3Abf#UqPs=UNcc6OBMcnuk)R& z%ZLr*-k$bSzu(IzOW*Yhjrmc}w-ysXFM><^+mGE{Q#*|*akuI3RSBQ;ZkkKF=O@sa z)Ww4I{|7TymBitXPdrYI(YJy(VBDt@S$Eqhs##$f*JtQbfH{JeyK$(St6%;99lm&* zLNZt0Ftpt5vrXnRKK0zIaddnp$mKL`|;9|;Pu0A&2tGwE`m2*YW7+q(c*dtCOTn@JRfel zfQ^C$%%5Ks1@ql0Hk9?LYmdZF-?G8YrUkDB2_2EQNS zK(;JmTwpB9*FFCps!g)&miQn2P(@j0#ZhrmP{dJTAlvRFrZ~F!=4t>UiD9`c&X%L} zYfU^_)dX&A*(Gou22@@3-TS(x21Q1Wzk56izQd#A7ik{@>aP1mrzj{6`rB&Jy4{q$ zS7Y0z8Z)>x7(Pkglk!3;1pjb=EJ_+6;gU$GNt&7>ob~h7c%Lm{)gzaX_6RU=mDmMt z1mRN>;c>db0=6|KuPE@HoHySK>#;V=)9bVLP&&PDGRbrKwTzW=cRI36mk$_Za|+uu z7%Q`X(F-RUDRvWpJ%8ku{OR^76E#v#`CCLop3_f?F<;uDN^KOSaoeiT1qOaw5%j3& z73*#qE3%O=N~uhyY=4ygH9@p#Gvr`@XZ_XNz-w8c8oC)`_h;f!IT*^(b*}2kI9OYe zKt^M2khPzoDdNAQP1=P>&Jjj6M>CarFy&S`XLRQ4=aiGMem4QVFd1}q+siR_^tcY! zd=O2S-Ts$-u{zFCUsgZ(dlxkDf!rzlk(SD&wacILyYpkB!QAg&x19r2f%%&GH@N=( z5Szi-7_V4y&e9`1`+;HM-$3~ruT0?fb#x|mS3Fily%cSa{ zi*qoqQ~Xe}Idh)X^S@jG$p^Pr#>yWU*6&??<0hj4x0Z34b)BdMLZ-cyjS){ZI|;kX zF^!GNX|R&+wwc^%Nq1V5sqIk$6|iy|5>Uq*qGfct{Y|q>-6^Z7W|3d-Xm{MXamge3 zc2Spc77&*7Z%!{8{oGLw(ysPgdpq0b@oE$R=4V6qdQc^bmLF}N&vsYjb3f$f#WgKB z8m7;GcJVH!kAS;lC-{fFw_l?nFUi%ZM(a|6b|IpXuOi}P*V@-PQzWj5@ieTN4jx3NMD8$`3Zeld z6{q4I1$=*}9(#Vhv+GJ@qxWW(vr0?l3=sFswz#IP2fHu&xq@-(*rrI|G8(?y&S;cTew=jOol4)`hfAX$-|ao$#3fvPZ~iH_kku++*Vto+ zH3y%}5s0>oJ_f(F+xhdupwiLYBlqKjt@*CI+wfHm4+OsdiV7vQ{<%D8Z>6MZy}FXT z2l?mT;++rMc31TTJsACK&SPacz#~Vo z+0?tzJHr4FhME|a0pL-i0rI~qPWOeloiaU^MalrUzvLWTTW=x@zWnwr{&T@8ej8tQVZ9?8@-V##o~r_u-gV0t%-V)p=Bot_5-9PWaVH{frS7N zy?~Vr)qE^@Q!=}5h2~i{e!m|ql10ibKQVFuJ`=e8Wl7@k^x)iw8NQMC7N(JuI_XO? z1cb!A2`%oD*)vI0ItQ0^B)utul@7kv`D|k_O-@*Q7QLfTl^B(mAvyt|jqn=uKf1s* zSENR0z@Mh`8}kEWj1uVr@RK3|G(?iMak7%#l5hQc*^gxHIw_1TWWme+$tHgEi8`ej zs53PaxC@6b;ko3U@8BIH$o1Y`{UVtw8^YQ!!~7Dp9d_8p(i|U_A7liGTIDfP%hU@| z>&CAdb_tf#*WDYq@y!m;R{NYf>0ulZ92-hL%`AbJvaCVx=LZG6WX%Uk;ouzt?AV9Pr@X`YI#!~3;Iz?B*^|&U&r4q#+4X32t)&BTmorgd< zdhbAIYd?ln25J=^o#v$X=!au2tXOp*t#U>RZaVE(fk#F2gSPt_-X-^|mh*03^KyVEe%iphS8X zBO^||cggiqO(0ifNX+|~R>Hf1A*9Vz#smzQH?)g+sWYP zpX0?`$B$D%D;9zT0rfI_#)wS})<(_&lPvMsKJz1{=KY0zHDLYBQGj!~|FO@phw%4r z)p0u7ipp1x*n{cfIxOGCGEy5+`>XTCx$PvnDpNL3;1M?{^zIM&T)qM_-q`X}$A5eW ziZBo=#2F!m!yst)aQbpFMPUAnSCvX5uv@dCF2QUK)2g$2QoQeb7iZkj2WLH+MO=%E zJ}m-zmt6Xz<_KLW8>Z)7AI4re16^Yhcl^}F;4Y9G+T!w(*T@9SIUg;K3q|2#r7`S) zO5{)Nf3#N%TFm?f9VSF~;gZk!=wZk}k|vH^0EbUsp^~17qY9OqZlbcmD`+W@>y_3K z@B0xp$1N?c2%2VzhR(}8G$Abyq|B!E-qB3&urtG6E8+yTuE$~!J(oxjytuT=2t+}N zb)ygvnbj3ED4r6(0$neOHsvT96s9<vB$#819rziE~@5%Z%^E0A#rBS618Fb1+A!T9LHczcYU*+3&K597$R8nz%>vyM zw7Mk)!G1P%h-lH2TqeTco?)%r)DU?cHJgHQxF=~|U4nrjQ7Ye-INeE< z4ktqeiQp2_`N;9pZnQIgd8&-B_lhD|g`@2fuM7nWN2=vP?OcyCl^(r&Q`Lr_hJenB zzBhnDaTuFV5ZR%@tx=C9*Co$&L^S1XWf2N6uMH$K?rz_{6ij50R40w-Nb`P3qHW8^ zUn5Qnj5W%L=Lm-Teu}1|dCqg>#R~Q5qUV(=ubX2Tq zzMUns=ogJk)Pf^M>5i#UpK9vVM{m><@*0Acz|G34i*7c|2f#P5Lyk%^CfrT3i>Njq zgrVxC&5%sU=Z=dH7shVPZX~ed@_utQku={^M^or1-If#a#4^kdN&Vmr#c^QZCGC=G z!y|j+tOFmUl5O36DS4n1Nrsx4$23L$o`0R_nBY7+JzK6EtY|ikQR;Vz(w^e{OhrTZ z&AQR`tt;?|YC3G!4}Tem35;vfjOFvk>!4PD^?`m+Kr*GlG$M)#h9G!}?3L;p0L`v1>{QWGJuE?Hw!I?h2Usks z)@$8l7lu#BV2j6bP4b*COwT2QC1@w}skH$vRrGge4I&uZ7wXx|oIz5vGz&PP#6%R& zq>$dPvI|~b3&jgSUMDgp!RJ_4GRkPXbNgVT3)L(m`{GuJyy)K^N(?n9jQ?N5&uKiB zB)_DOWHWbJ>tXZ97x~j|ZVA0>IFhNoYs_a@_hrNroFoD=2`QrcA^1V_j7|C~V$JJZ zp9Am=LI!T@ymn?2AT|`UU{Or%;Y#qL86r4aJ*|FrbeSeymKQ zSgy!9qupQGxVc#$fY%bX!t;^b;4<=(ZTJ9*k}4lzuP{Ful~RHPepX9O0N!ts8DMr3 z>PNwIDNS-p@AxCQ7b>`Yay?U7bdRvbZq z9Yq8Igqsq4f3FFB(1$*-)j2tDy>qzvrx8q->r!lcCDs{;pLr**$T59y^D(st zoP#h_z${VooYCW=n=u(%1Y?*I; z-4$4zds%-k|Dsrm=ZL%NO4McKW@8uI{&R8OcADl#Q9IylnI10@)arRtyj5nvQ^oPQ zgk917NG^7XgK++>OVM|>OwLgHjHetJJX$>7Z4(Q`U{u^U$JSeeWD5CZbB5#jib-^vQ-`XDAvn$s|h2iyDSt% zZctfgCAgGuASLiJscyIad3BP?9UWS!s7kSX39c*|p7iDhLR=GGatF!swWe3}o}aJZ zBQL*t34__anDmN!7qOjlde6q`0~17tq!@>J2Uv;%E~!IA1(d&M1_zF>)Po{XM6{S4 z`UiOwE`HZy4O1m-A%Y_Je=bTxM`i^Bo>Chwu2bngxQ7on9XPta!Bh1<&R$TwuBqhlqnLR9vsRG9fhJn*RM*3)1S~ z#1tfUtC^7f4=K?JYs&L+g=(DO3F?XOicT^$7st+nWwF zZ?XObeBn<4o*LbVCVY$BMT}2J)>NkV&9&B~!;Yb7V1l@-8k=cI! z&R(L(y~iFLy26FBLLi%hR=~t640pkumZ2DP;N|hatoW%)(*XD#lgy}@r5W)#=+zhj z81NdoF}Bzmx&p6@U&((_Mu+12%K7db^v!#3f0M8W1#*IjJ^I0LaWV-QI-!G=%BgYm6~2J*S3necH-gN9o zxlsfq1O9+H$E_5MuT<3+O@C(#5NQhKpn)(J5>QeEOeJ1{2`5F;^ME8V{2B0@ipB4B zzq&b|8%MGY+(JY^LRr1teqD<+hyg58=nXJ1a2NGo5FI-&mPoPO@x;Z)H)>5QE4OYV zkuJkhsU3{HNdm6{CZ*QOzdTYZ48}>4F`INo0d`T>+37LzMik8!7>UsdI`toVZFur`!u%Yn3BelTg=VeT^mk-bX2;{fZ?x(8+McVU9AKhDBJhncsb-@|xC=OMg<%=&cL?t`d!zz$zWA4nqWrxS z%)kxkrAuNMtqMXOA^b?964vlDJ^~EnuNJzh1~+o zG&ERpv_x#$VCIca1N5?0 zGxj+MfRBnOQd|CX#}LVeVCJK^6l$9h5s1lvj6|0lB=;#8;_!5YUI4h`j|_!?fJrf| z8--);veb`68u9Tlbgp0eL8W~x_Ha;7=IQyVR}Gj9R2~DEbEwM{vT@AQ;lcP8d=zv9 zL^Kp7gu8-#DtoJAb3ctUD+9p+NeKwqet=Rsd*x~hbQ1J(QHI%D6@$dm3e1c)SLE9u1IDd?~$f~i)%=`d3Mw2?{{hPjg%rcHO~@}XVgk>7`P)g5f< zr+~vPdk;6w2)gm-hPBrp^yi1@9)ht&9)@e!55Js_LG>8HuFe@vB0Z{nQt4jC@I$65 z1rzb@km1U`|Mj3s5~%XIpwX2?ct?sbJl=!iZm`ebA+&i+26tv!o*&6{+HL75qQTdz zc7+30*SP}&z}a!@*-22-aa4S$52?!D_>H_qt^32|G(|GaK2 zeusQs?L#)cD%q*sdorVgIsiQxH2C{`6T~U71rh6+`}+W45M{uw2&Gpaa|Auipg46z zS^ESB@&tK(uI+`PF9wfhDjhK43Q|nUa^0gDQ{+S{-IYVjUk@O~J+PnS|GXTvmQRs# z&vn9e28{5sJ5*Upw-8Xv4pTa{Z8XapZl}5xKAT0ZJbXAFs0||iC2FQl54XZ zr>28?viR}Uw6?3ClGCL<3VC9;!xI}rT>uNYX11#qtG(6G*ybS#cbuN`TbHXihp1=F z!dDkX)d|4dM#}s0{kkkAfCl<-s)@u=A5F1MTGAu8uu<(gmwl%>_&hoGEMeq^y?oe7 zuzQL$!`Nrfl%9=oZE(8&iE}65BNO3=Cm4na`#YHV9X`X`ss!gMQ*hIf<|MwG7=^r& zfu@^6Tz0~_Izq;byxP76HA8KA*;j!-8-FcRS@B0auP$4~8km*zITF)!xkUsj6CROf z<39`oHrNJ$mCFa7#1NL8kI76S$rj-H$XP_x>()F!sR?EP6t2-lvPeWRQucJ6esc&U~0# zo!L&mQ)Td?{? zP!bDbtd!DhK8e28%QrS6h1wQ$%spg%#wDmGtrY+Qpm;9!zEXr9y|~i#6Hw_qrLLbD zg;cMH55V>`f2DcP!p9l{ zYO?`0nbU=>BrxE?=R|t5=dq~cZau###hc3QxE*eo5$f_%!qZkaqs^l;kAq0#L=9JZ zYSTst#5x^a2~>PM)!72qJP~g~4=oF4=QW$Ux%T=eLI1dQFc3@#UzZZ2UInHjx$j6$v7o;kOY)IucX#!@k41!ym!J z|MM=?OYyq0EOoG=C3o`tIq|TY({}_rJ~C@u;-sGa3hGi9>0M%+-do?Kp}{Li$$%uP z@;>QS>F&3eP&1)firF9JW$v;M5_B!*h|Rszcx_RHbo z`xEZ5XY5~n|DL2@epS2_*Ve=PKOb=Tw|YV}@6$1&f~a2%XetT4a1R$%*M84s-Jbbn z#x5l6-4TFq|G=4^-xMSwz#3Td#*re@Gs#@UW4KSVgfz%Xf?lBCs2?Z=;%7Q_cw$(& zpAhS!KSbKwMxWA%myW)$T@n7loZSZ8s#}&9q$O!!j{O`I)x9x>*ND&*N1^U);4O-O z1eHwad&TdPd(>{h{J%|-s2uCGFnpP9R5_-lR%io7{DW4Mp0Xrhhw9Br>mZvs-&~Eo zqY)Xg@J@y72RZL1Yc}y5Da!TtS6aC)0tJ!XclVW2=VaIcA$&=~ht-|q^Y%3p`bf#q z>hTn#DvpREz4pdHSllKHudU8Z8?ilJpR31DFre{SH&>G;OP+Z{C07NhE?SX?!YT;=b)uk7 zH9`-j4=7Ef2DlR%dTN`ejQxRz-s&+jVE$hcY}-*4{vE;02?Pacu9Y0p!GiH9B!UMU z`gXK^l*(X^JWmlm;}1Askt+zK-as6ILRo@@vz0No(feCstNJ?BW1T9i8JLLs@^0@r zvhhwgZu)n4tDq73ylQM)aH=TjgK;l;H|b?zAJ)ROKfN8DM^5QeF9V?`wn^$?5WM~r z^lY9?eo|AERlZLBdEq&gHW`=jDCp~*D^O9je%8S;jWELSm;hZC_$jC?+4K=NpMuhl zVTz5aH-stQNwRP{zG*f+$GtQr7$c^GSccKi(_lTg>$&CTxPR)S5wZ5IQ3k;-Bru$_ zdvg(@WY;LtFfQ09^W`&I-g)OHO*bCnT$>&2)0CJY0!Idh5_<{gRm@U2YGwA6xev5< zz*(h;QWApkrbv%0%v|Dn;2GtNdtI661chu$E?VV_lbO~&JtI=ZJLQ@P46aMYGUlrx zxU0ouU1*71hX>WGqZF{X$k1&h5*Jw#f|o#X&Izkru#;Yv|)!X@qJvqW`S8 z_*k3{7UiI5wiv$sHkoYv&3zqCAr`G!k4Ql^aV^+oGTuVM`9nTl7fx3)4iT4Z&4`HY z7iEEZ_&VE>OUS-UywmgX(+{OPDXDCzh$v}!zgz3TH3(P?xEsJAhd}^A#f9@C^&Z|4 z_8~-|<4#mAe>mKG{YQ`jrF2^~#XAD$NLTw>il0sgCps`JIIt4%hQ(do(062bAKYm_ zpg0PO4r)O}(57F#8w`~A`YLpY7|ByF4YL94_Ek)qkbn-EBzM zLlR`B*feFsHWYd<4u(a{MI_#*8k5yQY+15MV*PA3<69CZD1&hb6R6oci7;>q63O8S zFr+gE_YyBJ;}WoL1l$HNHLt@NPn%JD z(ZAaxJJiyY1cS;h@zRJ~3g*sIbq1(x1nj4q)07L#!)NgC2|PFX0c+lHme3eKauzTo zTzYGAV^~=EV4Sr9cr5UM3_<04)sI7-h2Yp;stGy@`A)&Bgo^omu|7kvoVu57Z@!5J z$qLv9Q=3H3j>FugyAR^7C+Q(RsDi_s;l8}c6vx#+%&H`PDjO6f{U7eCAb(arZ-+D6 zkY(N9Oua}|o^!u=4iq;jPoPDrp#~mZ{>7u)r2S6;v7%k}6tsmDiy;`|?>Hk?u@i>< zd0Ew8xe=@v<=~+D6JQ5Z?k@~sF2|qsj#T%+L!z9 zSB;<5TK|^|0KOJ5A5!oxu!~T9+-o&H`@z&2X@s+9T>QH$BlJ|7UyL?yWl1E&Q;AUO zccsbIPV&r@g3gxVr?%y2IKGXWrF*N@f4}aA(!*GxXRlolSy3AJU5I%y| zkun4HY>1~|GhH^8qTmMCFP_b>w72$9&0q}y3;+r8PmUbch4QEepuk)QD()r9Pe(PbUkm%y~YhpzmVonYh(_3~i(8#~f&#ozBLv?#3UEkA$Q_-a(3XE4Lg&K!3wAHt_!meTs0r=A{vdM@W{hoC(IsNbEWTi~w4C z1x5u4{+sReP|L3qKomKk2*yQy1PZo8pn0$kB8>K7*`fdKn91rRDuxLU#q!` zdgzy+U9N`$_=-9(cRgb_m@O)8NC2WXSe5le!2T~0FtDZoNE78HKsz^C(lskvBVM_* zD)f#khDuiA(eRaKb3R~?Tc|?Cqs`aMhrHK|Em)hVc2()m(=FYFvPHF6HbJ0cOe``j z{R%W!m{IdO?~i-upl&p%aM;X~W>8gw6#v_y zuKWM% z(X;;FHB|OJZ}eea%`XTT zxU@*zrw^V7x)@WNz^(a2T{J+6jGI3KAv6-fm+rq6xkqRa92e&}R`%SI{Ima|8{;*b zP{`|76K+HeM$b;&6o2P3TJKj?xev13PT*Qvl-`#rV@k`glX6yS{)wmf=G2*r!5!TO z|HGF5iejqpGwSVNZPXVxOq%llb;GVFz^9lOz?1RP9?SVeoc=)=MGn`aod>6#`->Y= z$gC9Gme-hS|HHCE;f22RQqTB5WuRO9kT*2K5RB6CxfunIbUE0#>jSQL_Z_Q@C*K$@ zO6dtWS?>=E1Bj7!fV(6eMEqAI69bfS504wNRS~r|9{px> zVSybN$&;s7y$%{XF=;K7I==2%b#a+j@o%e7rxCho9<|h47L91YM>5KzphKJj#ulWQ z;3EZ}A2JrwAaQtC%Xgaf_e z!!($iLbi6YfxGmER63u2A88Q=s%K!{^RV_8;jVB!`}tc^#8BWh=_t6 zjMq`$YBJ6U<%u&(xEccF!&7tsLS179AyWB@MwI3xA?7mZb2Xl9y?~e_VdU&W&_Lu` zQ0xmD=IJB>h1r9CO(VLAU?rtB#S&tt@11YOiuRJZ--7x;!!1&I4oGByG&z>9>(Y#( zd<4Le_@sh-gJ-o20)_u8P@w>cmKP{3-E#wLI?`x zm0LzGATa$e;pBuoXf#y^m|1B3O9wc>mDQ3aU0kOA4S;WhSylS1`hJraS>SjG;7U{x zIy`E>_?QCX^}?^P?u!rkoYT7=-!vlgWAgtIq?*>0z-^3&e5!yNPhpA}jYuGPUHL`_ z71)xdp`USPLdfOwB@6+$Jr=zjTBIaw-Ed{%3lQRa-A@H9-l9pSmMMMI#MfryJTQME zW@_Z@WLp>LAZnqBM7}FwhTdMSVWdzGMKwpWvCr*sfjhJMRnMCKd}A9}n=8~po5Q=m z@Q<6L1#t?rnk*o}C`BV>gyVK^Mbd53DC$YTi%h;|8zvCgj*r4o0`x#~sF4v*Rq`?c z`ktHr(gIV^YF(rJu=g(yVE{|f@gDSQIVgw$)ammtc6WlIRf9|Wf?$s%02ZqT-~}4z z1oGbnG1H*TPLom2w|sTHO1H$So*%IG3~g*TXWO@cNSY{H70keb`Y2G8*8qQ)1J)=G zrKI;p#(Zz8#R}Y74-FXzfGOyx(YGMaIp;$HvK${!cqcMTIB6^o7T5zaUV@yTXGN?R zaDU_m&6Gs2dW)8EbJ_q&jst)+CdPzcBSx(JZr&=tpDC`Ii#Y&l@Oc2bz6QIZ3-AWt zztM95YJ&Oa^j2}W1Vpe%ISxY+`>)(D=ma4Gz99e`IYG+=LxVEV09NKnFlpbN`~!Z# z^Pwd+?0kD2UpD+A)nRu0-&36ndJW;l0Rtq|XX5LUO~A##K!n4z{;N(Vzk+JeakQ1=(c-R@~eDDQ~ssFv%!TuTqf%~1E7?hzM zpnH}*9v4Sm(hGsYnvmsZZe97qY!?+6zH&Gj>pU=JhzHrmSI|<)0RSb_TO1w$aIpvM z#6z>r5l$}3K+1UqBq0M&sS}jyA)cB`A|TfBFDdfD9;*~*1LgH*7zJDx&~{$P-@1lB zD+BG+ea1Vd|I9sr#5||%{meb*3+ERKL44fDldgpvxL}T+02unJFTx437>No(R1j`c z*LYy?C4*^j>Wer}%6fd};O7I;U7zq2#9c!J8xZo*_x1D$HpT!b>8W+9gxUn-{LsBv zsaNeFAh!126==1`vOX zZ`X*Bh<38MkVAJ}1cn7vg{FguA4&yoJ+%M+E$fSQP#pmFqU-U8%2)s5jtb)Y0&9{= zz3(nJAddQeChwwXP(&LQncM`OM9Mu%&1;8pWMX+I06iY=)6x zotsl!13t(UdTrfFxe*8#;E6fU7SSt78K=}4I*{8=Ys8kohTh@{lNe<>T^hwcD7@YIMh zR6kC=#gq{z}PPnaT#B zb2`@etP#pPj2Z8+q(SZuZSkN}`5(%6AnWoCas@vq7jt6Abz{ak9?*nXW<&Whe!aQw?GscLF?f4D@oGXui-ewG#s-2Ulv!1SjOc;#AN7NA3C=R&lwtE03r<~A{2O{pp>HiW-*KKbvUGNA53DLgv(|hUQIe3#p$rG^f za_)U|1G-)bkoislf0hX>;k^nD3b%{j!-^<%o~(~aAA`WHNtJ(j&18z`Jt!dq5q@H_ z3S6qhVvvBz`owlL4gZhn+|LHwjk;+*{OK>*_QHT?TlCYtZDIOs^>g^vkFR~dCl05$ zf3+55TdfiGe=@Yye6un2XhVLy+QOF<%Xi!$&-v_hx5}>XtOxWk{_HxOqr^G zHx@b$#3V;T);0X@bj1l^CKwv%4xP(7_dl_WiSVKH3%!*J%>F(A;KZ}}&X0y7yT5YK z+Wrj>3pZr@{M|RIjY{-xyWM-HJ^ZY}uyXyU@K6!vRr{y#u0!I+?srlGU0mdO7>S?5 zubCyzFdSSCow^F?uLlTCJ447P*tzoYwa`80)o4)A7ps1i)1;cR)5_?xX}e!EC=A_& zRrt@96tB`bhdn5$?f=7bLiZQ6^DV9i42O&O&fb=KGA~mj@qh|-_T(vJe^s>IH>_0) zI~k9LOP*a9#>)4}L+;&&#&O1vB($C{Kej(;^8DQBiEf_V{rzXtaBF3WRK%v|%F>{F z`QO97fc*!f@>PA)UH#|Z3KCWuvX5>*K`;0G=Jx9CDcfs>-y(h5GH`?aHFiu?E$^0} zL=0dsH2l(tl$7W2|JI?Ie$dP5r$(N^LeT$YRU*ulTnTCkHzbYND-z2_n zKU_zPeu$ObeP`E&)w#Uu^gbJI-(TL||Ll*^UE3ce_Le{psr|-acC;!l$Nre3%>LLE zav~6MvZH@YDEqd8l{<1>hnsX+URW@tjt?j>b9V`ju7u{QVgE#pzepL8Sp$jv$foEq zwE6u06%j3d?mQSlU%wWXrSBdX{@5Z@6!Nu@b<)_j2`K1!;_+nY;m0OZt<9kIyVS6A z5Gh*rdw|hxW@IXa2Z^{2oW^;K(}gqR%3e=>T8~Sh`GG{rTkSqiU}iD1F)Y;nZP#0_ zv}IEvqR-UOcz$L94aMfGwDqNaH>@piYC&#-po#hAe-C3^Fn<~+CMCL&{HN&BwwmFzFw zsrHI}ulhfm-|UJjDg)S@H9A;PwF&=I;0>cYw?SpWFDE0RPkUo-_%x^Y#c#X6JIz~5 zVQX8CNhSuhYElo38lw`ZQ!4)^osQFMfE<{6du|BQ^Y=HZ6En*D<`!F38EZz$Tc)7T z9G1Hdw;Q{&##%Ah<}ae*rpv)617q7F_Ft%yWo;v|hiAnY|J*>5zXP|@u3#mm9hAs} z6O%;MPFo;6+-&w>Vxg`4&xz|=8k~E}J-s<;iS&8L2UVTvO zRQwFyc=!1k@3|CX3wfSqDP7ot=-+=RcZY)Q!fknh#o1C;ZOtSN}L<$uq2hukoNvWB%6cU@8Yo5XT>3xpYrOYVHESMe91m!4C$KhXr)s9`4r)X-mvs$5r0G)PayYR{V(}b5yTc1})PosC(BsIkyCs3d* zIdYpij%z*_))!S)otYMh%(e5GCD2TmcN(kpDH(MBX>qU5n!_QsG(Mb7yChWgqg%A` z@}6RpU7@#`v_q&-k&(f+8K!ttoBpq~*w+V7BTGsfv-;R1cizumF*2lOXwViq*X*$_ zyLGEk-stD`QY4<=Y0+5*{!vdzE1Mfn4TygKPXQtG;g69imPFYbkF=+-W;;II=u0bmK)sh;Ae@TZcG z(Tt+2q~`mFI>u;S-`d*i&PH-CF=jR1FJGpARvcniIj&0btw=LORyMY(=1l?*ht8G9 zRK?&CoW~{gpqatRPIaV~3bK@OT;Tz~y%t^XPmHxut7}$K* zQ;^iYmugzuebQd^d%RQuL$Wjwmie0xdB>PFiGW>MBcm75hWq;qb}0nIw<$PdI}j0F z>%COQGErfMmYcdQ?mW&r@^mb#6mhp3Q&sq3G*|O9gI_tWoK_H{PR1^W8rw28HOLwi zB}mE$B&iWl!VTC5wk0AqdVZFpD20=Q7Z-l8#mg`l^>Xy;CyF<~3zirP2kYe{66;nS zeXAE>KL8g1LI7X?maJECf9{p=@8qqUPZYj2NK*i9?<@Ee;=#$R{mOL*W_u{cw$u=?<^yq9MyN7DtqM5J^s(briW6`5z9FgKMJ|ISZ=;>}HEwzpNx#c)rJaup7q)kFI6N4RWsjpk0X(atpN4{oI$Ur(Fq!f-wdycLO+(R)vRHDw@Y{ zhY~#BFNcY}=JXLka$P3zQy;TQAgMPfEfcB>&0ke;nOJw=5D}ZzmH_8P-Q=dY@Zzh@ z_4WPF$rt$!1FjO+_s>>BkWpktdgCv0kki&u#x|}=MOiAx=S8mvP*d=^>x&&5UU7f3 ze^wp@PC3>>GoFcRiw@J)WyK)Zy+z`!fsaFXBZV3j>d-_q&&(t76Rfw$3W>upuqS^; z3Lo4=BC#r(WJK#X4R0G$-|w$9 z^^vKh=Zsx0Krw&2@--1jrH&Q*y+NF^J4?6B8y>zZe|VHNSfFo3#j8Vek8DQp zOrH2-!OY=bDCMnhwNlXE`M)QQp@lbCrsc5jgMpEm3fa0jl_xbT#}8q#zZ?T!_6-QG z9=oW2glMH2xgBiq+M!^T8*T+d`L}K*ni=RF-Rrc}B$AC+N&F^L<$U5YPi<_jcOIEI zwX){L(s^izK43fg*w|UX>A6<~$|r<`s(uB}ndXr;)D4G*nu+45!ok+LH4~Y;!(Hh4;FvZsirmY{S|k zgCgIt^Ky1R|B!HpUds}=kZ$Uk=D2#Mk`4N6zUzATH06MC|1hw+xS6mtACJ&<=q6LK zJMKMAkUgwts{GL~q{YNU1-kR;&o>4)>_))KlO5A!fA>G<*`Z}O2JQ(Z@;tt*aingr z^7LSN=+V~SWA<*j{W$fd^c|mYZnVS{oA<9|TGZd7-O;zcaDDkN^*VqD}4#g~wpOw{}fhrd+mk&X4u*Ur8T7_5>*PI7!(V z6D}JFo9*A;{UQq`AE0c!i^bH{`kmm?gyn-QF?{~r}XO4thNlW)w1 zQmBAU3@QUJv)cC8t_lc>PkO|F?VlHhS0;f~qzD zQ&uIuv-dbB41zply8deM_sJ&df;C;6{nbckL7SNyn4wT3%d5{1V`R?iW3KZ6_qc13 zf4_Ou)>r?M?{dp7DM%S073X&$`r5 zyV^?TAHB89Us`^8nle$nnP+rm|4I2WeDC+nI|uZL{G8p$;-}w{b><-f-_l;pfdbK4 z!l0#<+NPDhHrsZ;3co|rVp!e2=Yx*HY8S6vPqt5g$u`Wg6P$J2ji*obZ;AWpgA5&6 zXSjU0AmZVu`vAB*HFS$9#Ha53*H`=fTq|vQcf+ZAwsGQHgDkVB4~9MCCV;D}h}RJU zNzM0Z;e8xbU3D2MpkMVY+3Bqhe?E}fts7exyQ@D@_Bb7bGB;bOmoY0#Pba zxfzkDG=id}MJ9e|yhw{Wxpsqk=IMM|D)TXGJK_L^sXcm$98K$tuW4 z3p+S#i>;aibXw<`hR?rg)xHY%u4DW!7Xa|H*RS0@U_IU|FLzW>t#mv`8^~jBe~Dhr zS~H83hf2C1Rebjzff`-zo}Y6C#Ao39574iN^>F>9OIui#RBz4x%DM4K@2S*&k!(VJ zmQg@M=-)i|-!LmVmLD9Jpmxi-KO-yRr0Ouz1b@Qdz4p_i>rGW5WE3KAbx`@}@vR$^ zYX9<0HrDm@-n7@i#)p3nmifJY-CN4{1cQ~XzJ0IH0tHzSCG^q6!QXxU8ko7>IdLPs zGgoZj_t7qMl`2|t{zll&1N({2-u_3^s)ue^kJ8nt2F0_Z6=$Rpn@)anpZy;S3*QdWRbej`(aQm!#gk6@1{1dzpS`{T3h_2Cx~>HBk*?%c zf!}G|k#f?BvoYou$yCk%oJ<|u|KXMQG_J$Vl#*;7s-O3BQEZp-IKDBP>el{Nk>2~j zlA%A^?PR%M^4C^omqjo<_9-v$aDQ!Xc&r6NT0C$X)B0I=&4~QCKTk{0<00lXu)677 zwx2@|si1Z~^zUE&u(DFBaa_V>KbfVw^Xn^ZRJY8WFB+hAITll{BCBi3Zd)m_Lxdlw zj{dWo-noa}Cg!7&eMd{G@CK9rT^sVdn_{;@{>O-=b8PO>d?sO{0Ed3@ZCeOH zfXV^QNV@1poo!X0yOP)Y_>adcZ?H1TtwvupuvrVI4%LhKS|J^}%k{>Wc`(3gGG#)z zUq1w+@$@{v?am@+fOt2xutoy6SNG&Mcf6nf8)I)B73CVfjVcTck_t!-F~EQzA>G{w z14u{-DAFY@4U&>0Al)T`qO^3k0s_*Fba$O++~4nfXRY&{wa%aH?aaLI6L($LeciVp z&xp7j7GnJVIMZ&L1IEs;1rUe#&XWQUUS4?pr#m#jb;-!rON;%_4UI3LtlSta>{&2gWrA1O*;cCvw2EP zDvjh%9zpJRe)@c|@nR4 zZAtH}gjS|&UE%>Y zMsYVs@2itd;ApA1HO=%897K%do0YY5&!Kktwt7y|pUBjWzSF9o`eFd;_y zs8}%8wilpWhnW|jfIb6Cko(6~#bxHl&=u}8xctEbHs zwb1E|FafVPP+ike&q|?~_@tu|>UVQ*Jc&CK_YCIFo~QkX;|z0sl*h$4tt`8{C$Mk;E@#KwBw-Sf6e4D>c+P50JW%Iv&Pwi zj8#`w-AdOyAsBVOELWbahg{oQs@tddKrZ~`vF9*Y4#L5r4NyR_M+ZU9!nOl)795=b zq(||pi?T*DcD0R;Kz}eo@Ri|z;Odr1{4e%A*J4vxd{GNO2TaH} z_trrV?jXG-kVILIzMY}>yS`2`Z16I2^A%T-X%n!WzVFuk_l&kNFL?LG{GiyJ;-`BK zy*KDxE9FhM51f@yWxrX%tVF1w!?pR)`a$p0ewArq3gxsYW}L zu7j%P0`a~QB@hZ+FzSCnpj^3#M+(Ve0EgPMpwMRpLhH&#Y-4ywE2}$Da-cE;z zIWX=kdBA(M|Kkdnf$m#h0aRVAMhf1?;^hNw3yra)^~+0U@yk#i!! z^I1tC3e`CPVUWtU!Hq2kw?|078)6*^05|xpRsLs`MUymyVv|>Y#*xPJ9p?6muKJ03CzC~{ z@__qZLJ#TA?{<}>7g_?^jLVJQyK$N_#!2Lx?qe3h)AkFPa48zDAIs^`lSc|wT^47} zw_US7l2Zun&D`BWw48WY7$H&YBc;2VJzx$^-4M`=mP*#1}$2k^qvJj>& zmDn_?d9;X_JhU9N_z%#Cn{tP%Ufs20{Zivkr?U+wU~EAt_n_d~){K!6kOOiZC~p*6 zh0LhWa=kFDw*I};wyA6ssI}h+UzH2a0 z)x3bBQ!D`B+Jga}XkcBunE2dYN&ZRT9epWJDT0=lSxJb+7{4p?m21EoG2A~c_iOOj zYr%@tfAtYY49zGX1UmUba5{?px${By2$_3Ac^=Dg3K6wy8TAu()id#5eZaT^7DV7L z-!Xkl7~+n;1~beU@GTb`c6}W7fj||LG{%D2lH0Hn%YD~OzaCf;8JMc>-~>j6u<*Rw zc(GkM&gnMmxfUE=_kD@H=}fLftDcD6eb&=5fT%}Kq^x!|#cVx4NqvVINf7y1+^3h< zC!ou!Fg?*ew^R>kq>k`j116?BdFR39+^z4!$3v_MB;b)fH`a(1s5P$+lA0dHQt#oP zzUTIlTUuz7%o?oYkFut!hbe}4W<^EF`%6lkzR#w zS|BrcJZ1pkUUf4ODxJ7EOeM>_YPas-)Vlq2)|N2zES}`v zD(&rdLdOSk+UHk$M=BAAoOM-tPUo;lyuq_q7xFH1S;GZm(LDRauf67I^V$W|c>hSK zzA+AXoC`rCy&F(KUR`C5sPvRL9@R>?3pyct*?abM(^eg-XWT~WIwssphWvGjaFF=Z z3}t}fW3gxAx$1PfyE9hE(6EPBMm{ras66@)Gny>b7&L!Qlb?S3a!LPQp|R?f7$T>xGP zI$HMNA)Gr=&n(;w*ogIWBwg4YI|C3ikbeCFwvs%Ov+nN`)i@j^ZdjzD_~FMPvdoLo z!id|eA-}lBnO^f4u|yB}UeMEjsy5Jse7Q!pt;!xy~FD;Fbf zm1}JcYhxhrUnkXqljGr%u_TPCq&Q8#Q&g4&E5_Pqf~28Xb;w`pS$*pH!E4dWvFgny zyhF7WdQ0YXkIH`RC6np-?xM%2=?gu0{-$Md%4DuV&tY2!(b;I{Cj7nTZ<7OSqMmKG zS?2fOH z;W3gUmnTqI=R#UfUOR{Gb(Y>XBm3x1i@W-nl7VF1hwIbn0*|Swn_H-RB|A+nUOs!n z*#T9(xKE{yu41Geaz6xhL8rV;EDvW@;8J&+E3>v{xkpraVdFvHhQvkSEVI`;?oWg6 zYBuXEjy-qSR#E1f{j^i~J&WS(SBx)m!`S9?WrWztMDE!#i^Rt$XFK^oD6GbFd9w(k zU0Kr50?|6xMeA*g%Np*{od=oI9%|Ys`83R1lj^uIZy$&(I()mmAT9;V)=2CJQQEq( zJxM67*J}p+n&{W;Ie~asbx+~n>46GWgv@Mh!iq=bgguI2z+JfDIK07t zm0=vQe8|e(1OJ67{f!!jG^b9=52xcW42p|UVj*vg-**lc0evMi8cDPj7uh!6cv87s zASLIYHP6s`Z2{&jJpPVV%T0zb1JjSy>>t+eOp4$Nh6JiI0jasS4Cq8+ZS=63!Pg>u z!A`lj3nfl1801XDa>Ual@O{w5TsT3Z4-a@G)m-|ewMlXH!!rYTrHEqqJCnL1`+3x& zV9tio5@I9F9{q~3Od>vOw`@dQ9kk4m#mx9Ap^iZ`jv%?Qm(SNfYo}~g*R6$-90j&| zZ=J}U(rz?Gop(bz@OiJ;`wY_=Xs25H?BfmPIVEoEUG2kdnD3ye?M?+DlkX%j)DdB; zLLe!|)05Fk|5ivkOKIm}SSa6^9^=ajqQ3~$aLQN7*?Mk&UXEB@n?-UYnmxom`^%Im zf-#Pxj7N23*c-q}Os#WD7=k34-=Fo~<#+%Z0??G89(k92$~Z#`dRqX645u)isDBq1 z{WB~6Y|Bz2b(9=Q2y8nr(*?;7ruk}`!`39@ng=Y>UB{I2BE{PxdjqKO$q9lb3okpF zQ*9Bp4aZ|2xM4>D!&0``!9f!b%`~z1!YQ%`xe~SMr;V=~skH(FW$}r6arc>{Sfm*h z!>gJ)el@B?HcD;G!wq6d%)@;}>!bYd><|BT@gdT+dxYyQV^ zhi&~wOr=Gu$wiBuG|Z;~oSppeOi0 zyTv@R72b%6#vzY-%?=|qH5;?T9i+_HU-CR*@P)jLY_Ty6ct8}xal84O5)}wfuOKwMF0|`V@ z{K1wzc^|hx?vDD_zw|$k8pRaDe^J$YAfQCpN0R@x##G>|Cpr0|ipd2+xkU)bDlm=v zr#*8ny_5i)dQL_&;kV~~ChEnaF2X}!J9#tcu%od4t;U}r4P|_inIaJ)YzQ;y|GF!x z-&iglVt=PVdE5u?e0-m`Q%|dw$hYyplAX~1JaOev3_lt8_*xVEe$-P)%4{_joLhWN z>bo#evLp7BhMG#6tSX1usc4h$kHPm&hDuJ2S5_sE#LU*n?00THu5vKVl?#vrpMC@7 zTIzRs5LxDGW?q9Ij0}^j{JI|=ffk??^v@v#P<t zXnI|ToeX#Ba_|K*h&p1%GlnUhtQ)Bm*ipaho{=|z2ej)d=Nxo00uQG878r_hOljpO zGu`15rN7$1(dMv#+i<5f*R~K4AE*kB6 z>3;3!=_7mGaD>=jAoLR?ChZPnLzsbxRn4^sOu9Xj*$2$o0#!itU82)6Lb<+u;B=qx zt%Wg019h1FcC%=qRmEQPrps*yzvoa`wD3le8OmoQ8oB*3oAWvKA%#1EFtpH?eDe6D zx~V}Bur(qo$Bji^l4y>DP)lzbD2=S2W;g*g)50g|z?VOB0{v8l7j?&{V!NJCt%IT- z0!hm^%BgiTZd3WguZ)0>$g;P-!;FkBt9>Al0_(S<+vX}_!demuu`#> z;r+nxa%v87izGMp$kuag!H5LSHzj8?yS_AjPI zX#mFXw_6YzN7X-q+4(i)_?QPtrn}nN8l03DVuD!jZ`U{U07+8@a1*`g^4eunXnrM0 zno|F}-)^iMN7dx;mS*GE*&!rosjyTh1# zuy}Pi^c2&PCcoX#W#9w;>%8CrQS^tN&0iFl-d>Dksto#5JSU=bCi{l4cFD74sD0AT>*p%%zwO0I|z%5Cp zWd`r?6VU%u+X1?}3=BbF+X0*u&y02*(7%ox5SSBjXaNS;Ti-i)I-D$@ENyHCNGXp7igDtC{|-RvlL6b2>++4qjP4-#SBdck zWZVc;Qg(g$eD2~I1G=*($iw2L*hBKA8vxhxxH!h?)wI?Mb=zf4pmAtOT^q7pe*_1d|Tml0UcoDhq|O zm0WE888>uMV|ez=z$)L$E|hniKvs?C(A_g!%1y{Sh9oP}WNp zSg&0W^@M$6x*)@jlKB_)+>=VbIYB5-`(AD<>1*7}U^Na(I7da-#CKLGFtyRTgPuDy z9INHE1KxKk_Itw`TE}X~ThKfd7v;x^-5u_{g~M{Kep7t^>Kqkwmtp0F zzqADtm_}u>p>We4!qA#jDHzrkYQmHsv>aLjLqVH3-6FGkNRkh@eOcxHjZ4D2vgB8r{#yx>dLhZbq`JM<6QEF~`gXiJzuUMvW8 zM`Q!)tXRp#bNf$%WKkq+SQ|Jc?}7NH;R{x=B4{kbC=2$zW%L6UER6iHdH%q?o;=7n zA#OyPt3{01iDEJ)Nb&^uCv~v`gf|VEya4-6WforcTJ1ik!^YCZ@3CQsuif^4Z^iro zO|4v4N?En^oVWo8(#e6Q_SoJID@WbWJB}ofgU5}S(5CdO{MR|(%lr{PZdyn=nRfiX z>WXA-GmVU+eEZ!bOl7>(BjW(hzC4I%hp(xumK0Q`J%A`QVE@Z%icNtau9>oPZ<$Lz&q!#^GaRBU$bW8LQ%eOK));&Icu?H%*t zIX;G3!ZQLj<{Bc}9mt=)@&x43_jL`q;|MYqEETDiByn247`V^4l44%ODd7Z1SsH^s z!kZ;EnmJK%?blz8!YC6_vXRX%z5Fttq(W0t*9;DV4xev0Kt+Zs3bU1y*8&R`VoHP>^&dd{M!r^a#U~S@xxxke$$+ok5q92 zBOlcn(QU7YNzl0Ng&^m1==-qvF!}DBhS)xNyKQ5_t}cGQY*zK>6?+vJF?qCWuZ;84 z2}A$o2b~B9;9iut{h!pV7o^6kK%@gx-<@c3kJ7{1BZ@X02Dj)Rgz)#3W&7?kT6D5v z)s3!xDyw5F<}9gjSk9gUcr9sMGfbA5M9vn^1EqG{fy(&}dE3`mE$1Yw9P6cUH6u#D z4GP1f<=uR&Os(ba2Q(+sbEUbe`5SHqxVMQ!jOI!%4!<Y+0qTQf2#!G#b z^453sKFWeh8ll1%W&-$&T$=;OCd=uAW8qv_S2r>?E&1CZXnsn|T_-w)iz*-8>P zD;uFrB{g4-A!xkgnr`~+WklF;5K@FL3rhB)AyIRZ0~4byyQCTy~Ae|OPOD1P9I7eqw4gnWWU`{u%`%&u;| zAiUJ70;(BH*T+$9nD9H=%19?N^}GheEd?VsE=X6sEfw zAZRu2M7dI~8$2=CPAWk1py4R3eEIV#HUE2o+QrwHXC{k60g_ZiMc>NK<(+*N8A9I9 z@5mkNaQfbWut#89}ucx!B z2AAtk{pz41ZUzN=0!aQ;>FodE0@&a4Tp(OR-fjQ;O7f8MK~1S)UfE&&RxXD>l^mvo z+4e!bmbwruj={G~EQ)>D@@59#_wMG^;H#R$+JAL9VG7HOp~q=)<_|6uV#!1?cyhQL4*Q_bh#j;s%*`(#C)+f)7>WF$4Osv?WpW)UX*YaE|0Kax+j`$ zK1RzijG_y#5U%fOC#DRgc2?YYN`q)kj*IQXh8AU3fOPeK&T2xAmU8nqYgM_{ag)=8 ztjBeKb9yG^WCiJuPkH(tY5h1FR_Uq!aM3a?cs3uT_3F;h_u}mSpAIg+#K?%R7W?vo ztF}SEG|uDGqlbqeZmK)m&}~Y2J8PGA6~W)70UY7Y5aS3g2xt zHF!{oiL#emVkqbFnE{rD;N`mhTKhou{VxTxzTLzZgO0CQ`*e5Pk+)BR5~a4x+qz$3 zyQDV%V1z-u+3Ou@GUL=h&uJbyNzn2~+ob1MO)`bo>Z{kYSi|d2TK%V_YR`&zgeepG zYbSTnyQ?Ran1eFuzKL`1Rfg{G98q&;+20_siQYM_xnR7S0w*qFyK0IPqf{mj`&Hr4 z1?NEKymLm2$F_oUP3Es{i_EV{j4g~RN9iw01^JdAe>RyWlr5=NBGMaTp2d+D|2!tY z6hgM~tl|=rA#01@JP6IiLIYe!fALdn9?Ng>unBx^3j##Wc(Sv@0-Ll|%a{BolD_oq z&d@q%H?*78X^nY%+J`b0{ps$rA6LhKkXH(qiA9_oNq{CZj7UE$L^b93p^M8wUV^%E z8BTX4sA>S#1||M?T~l%2FRP?il}g0Z5f&9nR7 zgt@^D<(iyWxqXM95ge=ca1FV^Ko3$xM8Mtwh17b)6P zz0BlKI^+EA`6kB><=8-F;<&^$FWA&ly+n@LolRBw6IXY7Rb*7O$GpIHZa!BD<(Yaz zFjLqRmR~~yLG=Aua;jlf>J8Z%9#DesI`HaH z?tvJduBSwz(b?PDHCKjoF4xZ#)Oox7$LTB}ax&^|h1=@CH)Bb18hAbKLkQ!g_o{i| zE&i4e%W?D#l6IofS%7?~pT6Shg{#I&%_y_L7e-UjS}1HDpN7`uLC~ZncI!6FWcM@- zpl?|9qU6fCf3vtSoz5t|7Yh9QS6&$kwYBI+$9NHxwXi{-8jxuz0HS9z1r4bsn|@n= zBHVLJ9dpiSm=%4P{i1^yWe8S;9ji9+Dt_hDT4*)V>s8H!fEIa|^Gb?_?dwn&etS&! zu38g+^8+g-oxA1xh!o@gE|sR-bkt#YB4#bO(aspYdc_kMp(8vi+;J0a#PAUggI>uYw zG)a--R~kID#00gmgIdf`!rlN_A2&^jB946CMMX?DsgtYF${4M)1Sj2f#E9!%f;h@i zYIO%VUdiMVBsm~lZ*L!FL-sTLg^_RB&8DutQS+CTik9~+nbeg=Q^g7!u_RF|)Q^Tk zGpAE-U$MaN(gnx1?pcQ6-B~Aleid%WDn|6c5V!8bpk$JnBJ?>$JTNt0h`SnLTqo)N zYtkH0evG!vUr*r+4wyei-nig81^(>GlP%|#Q>I9m9=!6C)fGUX-EG|tZH18sM5K-3yE-sow(ckVn^K6p*{KnblD80|GNTl!f zboXGWND+=LHsn5jsx3D8({o#64ZS%xNMQeyCnpHuvf zl7IJA6<=rDDQBSh4atzCB@?4L4?He2lA7LI+rd&wRYM{6kX^jBI}m&)LvxpL_TcA!VA_^QuXeRx7~7n5cu&A z9=H@7I&x$6n!SzDTpc(iBz-k0Ljxq(_DD zI?rhZFcDAfqOh_eIdiLNaurR!T4w~7cT+StNg?Bh{#}6^tx9gXwhvbLuSh=z$pzD}rY@9=A6u_0>Cf2@**h9a7L}VC&l5g;k!g5rvg_*& z$!qjmlK_HAx0k1izWl?NBAM5p(`PC3+8wdPc2IRdO*vD;1d{965-|NTk8&MfRG%(w z&*h_OSOV@CJq!}qmR5fP22rZru3|QCqh-&_DF6DUqzrNZM}yrw36%|E{0$919dC-R zY4xK}&G)w1U$P*7-*Pgh|5CzeskvVt5XV^%JRh-WjqO~xy;mfojP2-oeLP+m!|P6D z=g#x=v;W=;5BG`i(aR=6^UJ$x|t(tNh*kp4puwKC3}6Bg`5>mFiDty9LzI$;;uK`~(xk+k}=Rq(7p z^&Q!^XDR%Sk0rI&pCyKi?P?e9E^6$1FMY=dmTjL}J4~Oe$sqrHbED-aaQ8)sPfcB@ zU)E<5%nLOR*kXEnUP3MnuwFMPX9#HToK)2cQshqzV&%DB#!bzzW4Kqhi67VN2Kr}5 zJui3rKq$BIUBxI&SJ@d$=w=`!-FYfIJ7`V{uD-b_@^GB5(s-pRy5v$`!XIVozNh)L zDe>I;?qEGg9VAQB*`a!1&C<`~!xijOfSF+Zo^MR?F;(u51ZwE+ZlaHjNR3|@cDEU{z{gaxq=x{1nh-{_ac#0ADkOgp_?W$+4{qlKzO8vE znN8j5dt78h%+qpi%bz~in@DOyS{!S0JQNYH4Sdhw!E6w|Mdd*I%QsKf zQe#?G`b|8^SWyYISy3%Oni!|n;w4F7Ohm5;N5<1y>=SFPgmEehhEqnWgc8&CvH^R< z7`1Gef4%mbF&u7>KxFc32e%_j9(oPquI+DII0vV50%i75*pOhc6tNb?i0gZStu2we z9#bmmYQ7Q}G`~w_M7%MsLz{fC+lYJmB{ToRC*$;9Vq{%2I!iYdyKfC4dz6*2W9?&9 z-~-W)U#!aid`echCmqYS_gz7knH~OukcpX&WRw;M9`_B00O2%Qz*jox#fLnpia=5* zw=GRBFwQfsjLwF8BPFvqu(dht6&VT-9(Xe)jCcp@4_*x?o)A{j=v=>?UXv_Ugi|SE zoTn_+FIxf$zil~XZH&7oqGeS4b+v*| z{uPrKD(i_xZ+LyDHEC?2-=<=7W_m<**eX9!*easSJ3kwJ&m>om{ z&L4fm4l9|=cQEVylk`VK-=sZ`H`4{quC7q`uJZUsc=NZ$Bw$u({7iw4k9}ZPi`|hI z=)^&#EQzP;NkM7iwTFrKa^3RjIEhJDZMvw)J==TBgY?FRsZ$r>})De)8UUI zj-+b#v-?ps)EbE;-SQ>Wj!Dm-#gdS|a8saTW=Crn-?8Ay}}|=H=0v>5|{$F-S>i=tiZ^+=~~p zE&@62as}rZ2yuioV}hw%_Fpeq9EOmE-Fkgym{(`_Ec>1><<_TOo1c>mXJ>K=yBRl3JAFZ7F;)DDm~yqD zZp*4hQWq}k4d?sze)N;ko>bNZ3w={R%(ayzsbcZ_fX$%d+cot!^6 zN4~5oo3@RFyA8Ge>5H*Rd&8F^6abQMCmWF`t{2aNe0#l@(D@fl=hj#sIb!^20T4^3 zVialvc-@xTc0=*|XOU?ETg;L`VjJCA+sP~q9g9qj3VW(ZC~Q*PCD$iFk`K*wjE}R> z(2`e33T>u1%rx!Xb8un|vO0QqjJ&YWj)PI>r&F7ZykO8IjvR1i8_YqpX;QryQvEKu}V1htzh+K6YnhJ`-Dh0UmbtW-@9-x99|^6mGnI0brK& zQCc%KdfZyvIoENcb&ZyxPZ6Hx>gTC_PgaRk%^NW?|!80`H)`g; zX7(0`ZnCLQ)jjxarJH`-s4jM%0)@Q`d}c@mqC|8V0G-;I64(_j3SZN(!Renzs$ssP zQ!+i=hLn(li85h?&V`rnNQqLBCCMbF^Xlg4wl2$zPZ1lIIxS(u4?Mqpgk_Bzxf|h@ z*_gv9p2w09sC_A7CZa$`LGiWv_>_fh*xJ1~EQ6jh64;1Vt7<)Tb&Dy3jrsA-dZ>5| zsrNfeoz{YRv!sIZy@06lS8F42sfVWo&Odg69BUX%NGwS7P? zW=Kbk-)u-+7?2W(hl`M&cV@X=X?@)YijW9L4~UXmP!>sc#?P_A-%ur_WRHskfHQ5(v+^5vM*QLwf38zs z`?ob)Rdj+>qd+49DnVV47DG zY_CapGnZM4G{s+2yG4}g(dd+MxJ6DT zZOXMJj?t-!uynTF(i`Nfw`g3a1^O+Are3Am4f8h8Ic~`*|IgAMrKS=DD%5u*IzoeD zv&e7|W*+Reu_SG696P8A=R4w}Zs=0rJcNNzRhXV(_4OVFA%UVxnbTY4ldrVQdAMjZ8708J)IIfSm&I1RfDw?doiHRYZn4w&mo;l!II zN~GY=AX%E{n-~0jryBq*G}MmiS*m%4fAf*1Pqe(k;PmPdr2*KfJn&zij7Hx_Sz?jj zBZ_^viZf0mXUpOvWBWk`R1)07WOhGW@(x}JIW06Lj$SgO6@B@xJp^d5=qtkrC{X(@;0=v>& zRD|LNkaV)|i<1CZr=UOqC+Ie>W$srOH}N})Z-_4oefVH%&h%RoRSF;~ij*YXOqqBR zCEQ6FR8Sm0^ML599f#U{p+l5V8CMh-+q4v=66F8ZPU)9%D3ZedpA{8A1UkoD-fewn zmZiLa^>pVhS@5?3{^z*DJw*e5ii>C{jusy}W*>=#xJV$RV^weodTB79m}f|-@-f}S zpAU6E>t(_iCy>g4 z;1BSGIT~!x%UF_?Evi}G;BXJTMI)Wcsrrm>h8lKI_h>+plYRIbu(e8C2PZUC!jz=p z^konMLS^z0c132m7o4yD<=kIe@~vXcSgqkcgwI2T2tp?Eih@!>yG<|NVK-FN?goK# z4-Ls`Zl&dCM{65xdk?Z6KWF@3QIZH7A0vSOv(3!pfPX4J2t7J& z8H}gY?g|oL3WbT&>lP6diRa+c1@vSI+Ick)BFxSXId<^DamGYpH#T3a(2K1rj@_Y9 z`FyYoKiMFYjb#|{UnT22KRc24{n34XLOvPBjsj+bP_2wCB`sQloYUk#Tz+r$`7{ay zA@~Q(J03nPx34&^cDj?>3U>1~4VsLonp=YCxjJ05QV&>DsI-`7xtC=tbg-wIGd!3^MI z31*YBEa(9z|9<;~_G#5km5*o+aL-UK=l@=T`+z(8;lGpR|KCTr%fVk+_x~|Ea=Ca#IG;w_-B>EAN%e{!k-7*Vj}q0w(zgz%hEiv<|ki9SlQ?T3jBsz* zH0l7laH2++?=D2GgnRZL1I}ykF_4?p0W=l|`0T}4bpcuOa9D3(cK0&<=U0PoxkoMe zd>Y)k%jknb=6`?jS1ETsTL>-er(aZ3q-6hGnl)ZgjojSSQJC4R`~4!i+aUXMts?9q zA@j0(RcIRd^1i51WT%F407ouGM_&qw$5{h?i5_?1N|diFIbgqQm0$;O z2|`3p&#&-0usWs_sMR5;r_X(}WU;x++VU_4W$?LWv$i)UJy>8AEm2Rb#Hy$4>yam4 z)G0yDclw^ZXd7zIYsSfvvq4`8KO-;2jgDLz_Bs#cG;W(`rq78|F?U~HJHWx8D+*11 zD)X&T8h}sas**){7fT**4*A`Vokr|Tc>Si6IpuD2a<{MH{; zIsl@@XWJAZKuq%aRI?btPSS{?MSexO)JKMMXPp8hLUEg$znkjDT|c3hxeV~>f@!T! z$%gaUY|0zl{xK!q<*SaIaWiuMT8&=3Pw_2uy!LQA{IZe2;RA-ve<2e+HdT z_?9MTt>h0KB0NI{4+_6Q;F@F|NfNgKi)Xxauc^<9xKLCsPBam_uc}Vdl($3e+olRb zlZ~F4Ptb{J2*7f65}^*0reZjtxUv=#f}svg0`Jok^dUvakPqCULuVO9m!2*>D3H|@G-5X+l%ogX3_6fzvRf(O2X!DPO8_npBv#HDA4&l5d$vSq8aFyb!zVd2}_+T z6e3fAluX-dyxb{Hj~c5SGhlylT~*z{@jFIOI>m#w)t|c_?B%m6EgCXb(4cSZb=1pV zo`!FnY~*wNy8{qsevgtbVPI`v|6_UH1LO%;o}+Jwz`OMTtYhiGS^b9 zen8!rOXbfrjTx1~MsDVYt&cUKnD}*@z|&Wa&LyY|!+(cQci--g?Y!roWPQ;Hn1E!@ z?J9Nl0lBTP_ErB23;~Y;P^qypbeneSvN%dj*fRnk^svtb?l-`S`aA(Z(vfeLA73V# z-CmzQF00!pd16ea;OjT4sc;`~ou0N1{RpB7e0Q)4gzJ=o$x2PbgLzm!44y03TBx`9 zfhFf0101ri!^$(!T4qwufD(e3loiL-@p;D8kbOqK+G8G)SS5;P}z;LE^KHm7h zX@qt^;z_jcpe|GbcNL0)_7Cb4t(tc3vk+Wqoi}(9azCEM`hCd*c49_z*i1BenM zHLW3+_Q1Gf6<Ip05oy?ae7s?DUdMxz zopEscY4ZJBDQx<8^D>?B@PE z5%P!-?vE{lSqkp(2*=NE-fe{^lv z_f5(Di1Z%`#N$jhbd1^zXURxjy}P0mO9Fs_#`2fnS%JASh?JZX_@;&~09@V^UriI> zS-%qoRF&H-eL!*zM@eClE}4Vwits4YU?iUTyX=tH8flMsrQtA&lSK^HD2-lpOgtXb za9EV#0hbR2&32VA8De0RIm z6MsQTPA(?Ozmq8h;=y;(sakln5v^i|=)#u-3dgG>Zwlx2rCKSL>*D-$<&-r9x$=l5 zKO!Ydet_tGMDbza!6-D0juRVy92g_c$}Xkq5$EgA)+{7Ff`C~za-rrKFr5{>cX-tZmA*<_e8+>m zaD<|9{_axinpPqx%}V2d__8Jw13JhrsrvJ!KO7 z)FntoT7t717Kj{qx+F{dVyC6`GGT7~Ey1H8BsL<)rL5x?74Bi7+0FIyi+Ln`Zc@X`;0|VYxN!&`B!1()z$`0@ z`nSG;a@l#ZI`zbOpvY&*@aag`k78;SLk7qYQ$mAAd$A%>l^Lx?s7J%j4!hv1_{k%oad?XRS!q@RF_gnb=x(buNJGVoJUB`yDiX2%WAM|EsnX+*gbxky8Hd zP))>v3o(fLcX4F?PZ!6Onpd6T(M9tem-rzLXy$SXK~y4m4HiI~PjKA8RSsaw)$PZ2 z_Ucrtg<@PyH<;mZX;6-;pHh0}ZQ*;ctgDyxy%fxYJAU#(d-{_5t@TW!vPCoPR|yUUX}R zf80zYQZic5Zm9E7yrj{pWbK*IaIckEh=RZ=fkp6nOTO%jFV<8`>HC>MN*C$-lD>}a ztO*1S7rKr2q~vE}m$d(~jK8BcXQ*zNwm(!YCCVcTZ289ft}_D<^GDnZMI4uhjkqr% zQSCUI{V)p|W>^vQ2QTh1WCcf;SYqfS_x$`CHo+;FCw6XSD~yL=7}DJyXR*dR>^dAR zx8FB%E>;07w;Z>uH$O3Z30#zn&KnB+r3E!eKjyAxG`6s^!+xAP;^w!1NF`SR=||&? zG%#GRx&Pe-f*FfVhmkWmRCNDS92MQa*G04{u90QoE3x7591Jc7C$+GPLl`-z*wqsO zFuy}~wb3&{$$j-Z{jbXlQ+(cG#X(|1{4dU`IMz7hibLJaLob=~WI-7$%=KWC>G_@- zCTH$_oWL)pNP4R@hRx^I$SnNtCBD2Vl-bkt6ixW977$=mS`>Fz8(a1)x}CkVjbGRT zc~qW6%FyMjZrpbbq`ur(X+IhDD5mjM$6M>k;ZDHc7lZ)`%$)kzor z>Ru{i7@y17+XHWIEzkivn@20<*sMoY)6R7Rf5$4wst_x_@i>7*@kyD0A}%CmUv?Tw z(jRBoj~pr;(TS=Kr) z%>&(;*z|drW>~*kX#D9*INz09GGG#MC^B{CS?a!jDs+k2Dqp9xEz_%kMj;~48yLop zwUiVg166dAA-WI#?+U&<76i+k&>n5i;w`UfZGhm5wL1SSDQm|<*72^1@(sEmaS8Hh zGuCG9Ez-NRyp1~B{EdnN*3|NR&T=o1jBp}s>~wp;+JJcGnv9ZYQ)ZZpw(m(gQ=%`G zl~=e!;Wc>lCJ^oWm*@*Di9x5K2k6iCUS8q-fRieGME-oRn`}v?>w=zbY0U7T|M4z{ zS@T=IaTM9{^v_!&Y%RwT!`P>@ei1Ma28kM5fSqaBKoj~&cR8fxF27AFkC;RijC&tn zn-CgvuVkvRQKi^hj6mi8*R5inszW8jjg;iT?4bn|{7Z<9mBI_U;2W3ZX!yQNL9O%V zX?<@No}}YvUieFA^&otiU2&4ocW^Z^L+|86hO>F0?1u4_hSUe*Z@qD6KVugp+Le?K+gQ}B~0 zwVpW)D>4Uk;+Efcaaz+EdrgTcR1ng*&vrC~($`GAh3hH>{`HB}Es;M(#oM_5F~Hw6 z-QXgbpkz(IsOL++J-xy-YOB`ZVvK7zcRAp8odYcysaJC6RcsbTXlgW|VPS+p<&YA_ z@rc~E(Ny^=UP&{n_dS`!F+0emFMSi_rL_|lb0qY#r1jjM*MER z1hHMc!T7Ss(mV90Ac)R^^R2L*nMm%RQ|p)!;X-(z!!cW@EH00D>5AD1ti-!oaiOgx zfbRRrp5NyY&Y{?d_kK?@b*bzFYF3lYqcdXGKJ_W+O4d3<{Nk?9(J#GOVbvmq=bLWj zwVfsnq&BDVT7)mBy(&My#nmk|+Bi@@JYNmnn!C!wm|og!0_7YQy4Smo&sCaS?MkO; z^4j%cBt<1qX)-S0znuc|H1Z?yH8!ME=pT7HG}pwB@(L}Ldy)bU`b9QU>)Oe6QdsjK zltrc*4D!6Du^8!{>BZ$o?bS2Q0@-9#k*$9HW=)?!Y$+tBJ;@2 zm7r`Z>G>et?(!y36M0%_qFzf;uSOnFkygrGvk;lKmxk)lNZH-DfWe|g54y>0?Lotg zT1z+ZrWs_crMf*!G1>uzrmuU!KiC1CL&#L)XZ~O|k9Zu(tQLl5z?-*!vqOh_?5X~H zJL>;GZ^sL7x#L9g*!fMZD5x93A69nvsv}&8xedJde-%1_WKSR+J5qk<$NczMgIbk7ffa{ujVP92^l%M!Mdu zF&vyHA+-5{3(8hD@R(2Ev)@@Eg~~x!iO0l*>v8S+RBn1A30u~|AL$D+J|ws9G|YfKI|2FM}d$c9<&C|P*hDG`L!wGKoj!Z>(l=lu>_31^lpC^ z;iz5UQq0h~m9nPS;GID6d;Ku;FsF2GRdHM#DBUAx2a7VkO&=bIr{zt)ir`Hcc!2Nb z1=+VVOG=`6)nBlX=S%+E4D#w~D_V8$7lu*XbB%&E#_vjUO`x|Z9Bc5uizNjrdXfYU zixwu2N{zWb5=YkvQCdt~APnZ*v&Ofx3UBLc)$mR(XC5_IQX2_$M?_NKX+8&c@-7!2 zOcyaU>NcXPXhZ4P>HOK1azsPHc^@_NsAYN)<#{K6arXUgB}T&GJInZ(XCitWKN)76 z6IxfLTAQ;BXawl(=wU^Pps>w(Q)R7k2`w%wZAFUg3gzjxyeOv>4JRTmsq^f2oPy(4 z@XR3vdZ@)nSHd$6y;Y;6|ILcfrBP9uu%D=SidifOClnM~H%Ttq@`5EA^@k68L$Y=2@qKVPNSG5rdl4+^TyQBVS` zCk>J~oHe+LLw9zMj1kW_xl*OZ@o9+QF${ZIAGK6*U2NGmXllvCx%b97eSJwZ^M3%# z0^1h?niXPX90FwFZgLp)WUknJ!e0yy0M?U+DrgJ?rlulh>*TdoW@08iI6t90q48MURnhQ;J(Uj^e+qPCP8*c^QP{qZXd&cnBO|TIRJ8 z8Gqc_YFIokXrmFmvfGMjTujqc2Q3=@=_NWMeXP|(~Rlfj*RjVNUx=$Sc>xY&M7E41sMFhyD zB3YKV)(pC9CEtIGj%wFYDK_!wzCCKCew0QEx^ub4_ushN*gV@IeT5ZUv_HzPo~VgO zODf*c>?D(}JzHGNL$!;0P@<`hm(i=#-I(x?4iCD#>1OjrD45xnumF3BFtt#}Nf1iT z;lk%)-pfS*)D_txT;D8rq5oihazf7!Ui~S2R#m~vJAUx1i5|R)s!~RWj@{syi<%Hz zY4Dz|?U{CVk^l5K`Ge)e11Hh^l7HRj6WT)IWD8jimj?kc*GqE>s7e2TB=wSHPXvAQ zb=F5{7dfhh5!~thNYG}uOo^vJV7|mYDs60gsOI&R>$;h}O!V%Rxc5W8G{lb#&gY2? z502%m;xK1kO(7rMCgjGi8k3EL6nP`eoryA=PE%tmwUWYT?dnTqMbkyYL?aQ1-(xjG z-U{}4D@TY%7pqLo1mg;TC2{f7#?#CbbqdAgJRNN ziq<1FhN^>YQ9=qX1Rpur&!my>h1T^d+U-UlzmSN3#MN=;WO@H;4YM#J}VDny6W~shADn?7h zC-bHXB-~8WGt67IQ)qboVbx_=)o!@`?Lv7z8D!W1VO8T0|Q9ue~eN^;=!>S=X4OB;4b{P0~uxa>b-<*3TV zfR0;o(IPwN@f510+xQR#@SZ{BZybS%@>x7Z)*lpe$rAjIM9eL@1}Kc1 z`@{P&JJB?{CpfkCHds@iGnaH7@u(a#2kUzp>)mWL7sIM6A5A+OF0%56f06hB4_jxO zt)5RSuMpksX*>JWChRWhS@!D|!{d>ph)sR)nMTc*xSaC2HQl&smS;%}N5 z$Ny&hV$P2{wN;pMP;N9yUeOb;5$!#ZX0&$NVram_;o;W+Tia^(r~F|4d&y#`!NQ!0 zgDm9(=m7tE%LCJ8st(wp_ok*LG)cNwJKFb!<#Q1C@7PqR6Y`Y7xEbhgT%^0IZ3K=l~P*o9=$Y5M$Y9>6ykI9-}N` zZnmja;!`7oI%ao?Pvp1TMsT8YzDEK}QgLECe^BnzOgM{my@Q}m5~w#1+fF@si@MPR zqkWwHK?}l9#06E5Vmz?rDsCQ#Lg%yoWctoOC&w~rVbXt^X zSDavFzsPt1fmPL{^36A2oB~{T+-FhoZ50B%Z}_-4EXRrx!?tf=@x8sZy~;^`j3K}x zy57}&d=|-&>hk4hLTJj4be+iF44AW<)zuTsBGk@au^}joqmhaUDT*gxs!|7 zE}44dU3#A>A%(a{E!IEhs!C0f%td*4bVlj=vlNy++uc!Y9QdKl%rH=IekjPP8s+&n zb`Tx*dSyE?02Rs(;*~FfP@bxPl~x%KfOR{!CxX9BGeXa%(Ja;2Qq%NiVc!7!4!aseBq$H;ocF%gyEB_7w zELafUHtnY`@`6MGEJ_E(A}az3b$@nI`l>{N6haZJx}C$ahw7^Ht^*SCvL!7I^=|Hj zD-E>&?@E8F7m|>po~A*u+38ZbS)l2j)}CCOey*GZ7@Fxy!;X=p8KcZx5vfysiK9K^ zCCv4o6D0`gYj9fE0f)<6bOpG-Zb8ucMr5j&fp1 z>3{Om5zx?aVSd}N{rQEr-Zn&7-5=5=wbYTKt-3i+XJ`j0cI}%!-AJ}>tH#gyuQNv* z9rEU&t!3=$o#&f_@8?AiVVMK!_oKNAp8Sn1J>N{gL{XsV$Mj85TYf&EV@hVHtUe{=*HM`So#`N(tv^i|3%k@|V8n#2>0dkIsLlNtyBp zxq!F_Z?%W{>D}6^_@naxI6g!f3qzgKj|iu5bm_~x|DF1P?~I?Fk7zl=SOaoHlqx?= zQPI_Ixd6(`E$OK~>^V`qKl0ka9x90Uzc7dhv&q%_;OA{Je%wrkK`$lzwZM0I?W9F- zRxieIZu2c0ep_`$UnJ6+My?5-X$u=E8 zY|H;9v;llF#An4*eO9!(%#gk-5ft66VeJN=)&}{WyX>NCm=1T)xucr4y10KFtE%8# z!td_U3n(f)7rs|}C)s}ontt>=S4rn&zNvhvxC4dM_A>bm=_ejgHoRSO6DgE+W~t>L zm%Qk1A*b~O$iX|O3!*xmzU&;&&eP{F>pc{)elX&1-QI4gm1fd)PZ$8wAQLK}KLK+UTK=IcR^SUu5-QMzFRoyh#` z{zUT#&+F=!#7roX%47>-#0xqUZ_uh6#R+_vhO}(2*1^YbFo%Lq5Ay}?Yrjrpafu71}#~i51X5{<+0x9oLDfS3EJL6 zH2=jD1TSd*%SwvakFRps$2Y>Q=FZDAUg3Fq&wMZke0JuM$T#`EfS03h^LNWy`i{$ompuS3l&n`8y>D$&kTv?H z^Z+dv%3UJ-5QU5*(T1M^Jw2^rHrNWzMvUH zO?XE$y(G6&(OaXD2{T$LEss`8Lt~vkjRahN&kq}O9m8dP=R>{keqn<0O!Wg89_IWL zAqg_JpZv>xLt;}Fq0b)VneLgU9|DE9ScwofF@!ns-{rs7YyW6r{$FoKPeASG^9~r? zq=1v_yyBBUk(;ie$OqkP{B>Nu1WLYY_3H)hlzqtw?P}*50?iLI00d-|wezb**RU=7 z03i@|Y;xVl=*-+-|2L4J!Jpc9r)mWR$UQjJWgovh*3)$81d_IlS1IIo&W2pHZC;AU zEnT4jKf%0o=NFaORL>Fy+o-?k_29`&f7(9>+#FfDnMiV+hBIy)2>XQ0zl~17gvlhb z%BN6FiOCKiMDc|JMo=6?B*oU=vpKtO%nuz0M{5ohNzk~2-|Z+cVdiT%9y&>?NF-JD z>zgnd#Hk-~pg;fC7Q71nnXKP*+3?~WsHhWCu6^qQAR-NHy8)I>( zKDdzv1pskU;i)^ikX9LPTOa4d7WU0nsnxW?G%`iN|BnW?5)MbiX@R+I0mLL;3{Tkq zsO4qrOxlDO`&ScC5oh-n^Kgr!(8{L$A4G%drY7F?0o`YL1Qz+yL^R^q0d5fZ+s!9| zpIFd3fguZnuVx1EVEf)jWt<-bydUCnOGQ3pwy5j(?0Hswuk#|!i;wSFu%nd}TCM6a zqVbBr5Wt=VAi(!T&dTD0Me4i%uNJ`A32VC#U{o?C*{EjIf#^4w&*GMF*DjDujFp4o z-%WCl94gM~s*%DyWlw2;BR-jSiW}fsQwimKM=G=`W(eM+3sJuf3*L$&ht(!wTmgIp zo6;*oTt!s;S2@ebv(WWn`-r?PoUHGk!sDNL2$Ql{<-ZkG*5IpzcW9ntOGJoJL|A}7BnmRo@7dn;ZIimh&BPL$Ce}$DD6O2ySV7pRU2VW=brtCwWTzZc_4`~`q_Hm zZA+1x2vh}PBXVt0JvD#tRu3xxP5oVVbR+-KH$bp)G#LcdQaH{Fl8lna#SUW_ZY39S z40v>2SZaCmc!YImYqVOt<*(G_4TT-Fq8WCZvnp?f0T5p^_3gNqeSjd31|Vs?Lew6_ zxkQQ`v-%BmONH?ss9ZN0?(x%D4`6rg-X4eskWudLT!jz@_cn~EXM(k}n{(bSoSCzP zgpeo+?PIH1K#{vNkOb7YUa2fva6#1#Ghdfr6ih_izGb(ZU&U(>EEpn`4&MhA`<-}k(9RKENfk-VU!5fYx`%y4s^tb zQLiW5(zGa~R^3V7Jh+?~lml2B$SS=hAXQ7X8)Lgmn@nURE)q%iB|35UgP^=R)b9Xx zS(xscwr2wu(L^g&pOIo?DT?zxAS3Hzgy{C3^~2x&L(}af49S5hKHd2y6cj!O`m>P$TW>=B76_jfRsOMvsh;1 ze1Bof8rEe)B?nx&<|as7-W7cHQ-~L`9YEc)M~3bX2pL>_J8b3xS|XjOiTCGAcXq*$ zue?@uAWA<=>7_*PF;=Yq(f+_y%ry*dt3x|hK5pMS+SrxHWkeyo>HLZ4=>jBU6214? z;wXQQ(CO!11o9AY_5PGw;Sogh!o&!07_C2k79=Sl${0q&ZQnn~%&Y*F2%>ERpeb*7 z=0>D;p(ONFu zGt_wq9%#BA8U6v?UgkqzD>Oz+6U{ax4MUyGnZBl~Xx?k{?moK}FB*$`YtF>BdLiU$t_W6h zek6~qPldie*D}%*jB#nJlLC$-%GD7goH*6dkY5Mjy|7dr(kXxY8^TngF??k^83Vxkz z%9k;rA1Q7-1Xn3K#}P(LA9>KG69^pxxqP`8)2y*)j?^AQ(YXl*Fr=UAj<L@?;g}J&N0+5BO!6t4}oYmQh~KQjJhdvVhuZr z>9G}wmwV2Wkp?}MyQa-T{?k;4KBA47l_e98#KRH9n#Pwl2%nEJhwfn5$^nf>57L_J z$V#2TZ>tiv$B}0^Z@F>Dl@a-pU$95h97$INqyM-=NtO_--JC!iuz?B3ItZP)l?!<{ z%SWb0bY$`#nqzR8$KN;k=lv8bN>D)9{Ae^)_OC75{NQ&G~G4qp{ z3Ml?r_nBhs%PHlOl#@;?p0?E}@R9bg8Zvv$Nl)AHd)}5GOz~?y{qCkm^w!mDs>W8Y zV|K+;-k|D-GCjuF@Lr~=TWz&WHl<1zBm`mm~$9E}IzE6E?A}!h^*(KYZrI zddP=cG^)xrrgR=PQu|js4LyaQ1ZGxCqcPNP!* z4t_89Mn0?g2%UK1F0}|5<8qxbqOB=6EU<5zGPT>25-x>S7VJLMI1kuTsK>d9^0@u1wu`&QYXp&T}!*NHw%+dM5c%5T1n#n$WRP<7RBWOyTr;avWJ zltD9Tft}{Yx|qq9xL!w;82+nTg`e$O@=~#d1lV}TLH2B1T>^c7 zbkkodj~&`U;wX9=(&-fuN*d$B#R}u?mxbo5vGUS^tP?XgpxG$#&0KA?E`}Oi`2%|+ zbsp^y`ca?;pyM&8aExkZnEc&#ElVJySKG%=S}x}OS22?oVS@%;CH zssC@!Fn{`C1j=zIRG0@HV#{UAU|x#u3LCuwtWt#IU9ae2$(pa8x`QpcYguNK4^RJo z)noaX$A?)T*F^|FMUNxMf6I7qS;f@H=YiJti+mGQWSNOz)heJRH$R`A)ccG3yY*_b zRgXY3m1

        t0_f?E>tnV#Txg9`T~7m6xolc^`PHWVnByy*#ei@t)f-a;^Uz4N^|A z8iUiB`Kw3YfHoSIu5pzrm$3Sl=r&p+PM@7M5rO7UhRaIKsP(+3e>?Wx3Q3f^;w+e1 zDSTFcmpJ!sXz}Oy2GK}+l7c}1(^dSVabvR$Zi6cTEOOMnG=ND3MmsT(UN&j4aNp;~ z3T)i|!i$hT9((Mcj?53sPKl)TPexF{SU6yv+IM@_C75 zftGO}_O^{&1U_$j>^nd^=7mphKBW}fdsH2r6NqES{g>ZN$M!Oe9?ieiGTN_1(z>1NqP z=N4Cx5_r`ck4+33eVciqQILuypXE6K>p%H>h$gAc1p*fp z4e+zP6t)BDLCzUbT~j_Tv}O(ogmw%J3g)H?!#sgAMNiDa&3X3M^>fi z#7-lE%QH$nkASrG_1cJrK&C3?Kf3~W?Y=?LbG>jVv!~EbkCtc*c-XR{{V#eEf^9wk zJ8uQjT*Qj}sU!rqM(&XW^uHqmnw(%ctq#)Vlk^V#rgy}6!7r+`_%-R3A- z`FrRYFx_ZD2k@3^UG||$^oytg-*c$YvLv?Wej+a#mdhIO2ppf|qzOogN@Q2%`M(OZ zzVZMz3Qi?Nt;9kDNMHUBkWA%3nG@>!VL(#EjQV@P=Csj2fNig23ib^^2Qip)69^k?{Ue9~W4-TiM+!v}(JBxJZ zXmmp(Fim@XfQb*`FDCFD7|=SrZ9SL35c>D!GSLLUPjp)W`)ZY%we;dYbP9@VuIGoZ zj%{1?IUc5(tn9z~q1$Ng>>cYv@-O;@nrbIdT+c^|JhR`g!N?YNORylkxG1py*vV{) z9pF_4SqRBmd;+-fhl8ZYb%<**U{`b8eS6g*=dUW{--q3vBO6KD?PtO8)mV~Du#abj z@?g;9=oicPChfV^Hh{Ahk3|92z9B`4UDkK>Gzn8BB=E~lb&IP;wJ*`vfGrbjXC`R0 zJHMv~+Ux?sWRuIDjLIED5eeaB>6-xZntVO<4mUR$F@ZJxi^Z;t%1-E`j1@`CfTbv| z1l>NoM@383hOe;IA^DJHgB%Mowp*t`sBCA8Sv%{|`Ic3vq8iGCOoi%M^uGI zBTEyKFND#)$Y~`~|> zgWy3q(-;X6V!H**%b@5P_-X$>6LBR1^Z0&$QnQn(fAQ#73N#YTILWoi=0S{-lc162 zhEkGhVVdeX$kLWzrN;o#ZA;!A?t-6x&tgsPzbc;8^T z4!~6lgbs0Ci9FdyA3yz=q{;w?9CXc_Q1gSOWi@VKsI^_(!3Ya})^~UY>LwapIGA{_ zN`R>4%vF%MK~4wlm8LOg#p>+I{H_o66)yTN?@CEf@cLg!6-rPJ9D-o(mz%QSK|c8lwQktyjW38Sg~I<0;R2@$_kvBC*SFqm5*VRxG$LR`}bc zZ%MSL+{MMsml}5cCrpwV$qO>*&>w$ftW#p-I5{lJVu^hI0f%Ph`^->Fy<`XQkY3<^ z6s{lYPF)dgy^p9vu=5n5FAEC`HtgIQ0dKnvhy*2cV z5M_x30*tUez}ZR(oSSw*=nNKXOA%Us9iGt657}ScIh4IVlr8C3#dmtguvbOkb4-f` zPfaio>Lbn%la=7+a5jy}FHU1V>-X-zMCaZ?52tMswGs~O(A1`AN(>1v`RR2Hk~h=a zw^5mdRDaA-FN@nRWZ@KDrVn)_3V5A-AK&kb1m2b+wE1>qi1r^M6oxtQQ*0nVEQOqk zgnjpS2y)NspRfrGI}U>gj2}dE$`L`Ck}*Zuak&p*McIAb-iVK0n!y)d1Vke*dRPpx za9XEGHtbG>zQs{oY-Cp1i{0M21L_(Pe{DHb>bFsteIWqW^yamEc*18laiQe9@L3F3 zVk;tXIu&&&54U15Ih9da9y4qaWnvQU{7ur|keM}~o@x45EJ}{no8H`;R{tb9MyLpp z-N!wtLT9PjwV`uF^D8sI3%~_4`k;r}i!a-WSsJ}gj9)Nx?*^r(P@-+W6pkDx97Nv< zW!E~Ot|1{PxmjPCkZb}UAcUM3hv88jv&xcD%<>#$EJxc6Zkmr@th4_?;wIC>aeSzG zm|P{PNYBzWK=Ulk0hDpHFGu+O*LFsplGx}eT$6eIqQlNvZYBa=uL9@4*YfK3V(iDL zZ$e~!Jdj#YCFpA3JggMuz+5cWqFc5O4|F;2?(z{m5aP;M5RsyL+ehdW$)mRfHg&D5 zGei|#{F0Wtsl`J*alxw$1vVztuV00Le5P>~7!ozRFsw7ly@3sd(~zL&eReD&i!K%s zSFgVEg$+)7g`z+TDbulHled4enUXlQ3pU@hRwLdZIBK>}0wDpM}Y zik$((JSA`4msT<7UAIN4RdLnn;fW8kvvPD4*9ny{u@wNPF@|S$F@jIQS0_D1OyU+y zPay;Ma?DLU#r&a+!6DYZP5|>aY#wa(TS{2ToL*@S1sPvZ=gO{%wJ8**{`Z(+p%%$l z){nkp7}@A8f%s9CHqv;>ET3^)1;DM0;IBO#0gdC;WFXeI=nX)ny@ZOknhFmQD&6TQ@JA9W&Z%Pv z5Fg~6pja7??e#**cbUB1Kf61*EDL zDK>tKA<5H!mg~qLaJV&`@OuOcAi`gL*Vb6cX{V;yWI_XU9_Z9Qqwn3qTw#K|d)fV4 zXY46S8QWV$W7uLE&usj|St&9_qUV)7WL{&$XRm|uEaV?M($g?)gq5EDC_xE+>EkBA zo{G{99+t~aaqAPd)`W%J^3bZ?qCYiVkyOl7_@n5Z^YA-HE3f_h!Xs-}dU~%2_52JO zZ>jRMczZ6QrOEp5gtY2s{B( z@W5>-M6N7!hW;qPasfkDdNIKOmko&U^ROU3RtYV~iofn&i%yFVn=*b|v->ZwvO47J z`?*q~7{*v63VT#H-uRV~%c;}$GFVi<;?N5zQzi+M#AB$pqIKIKjn3g#{9nGSNIz63 zd2>QP(8=2m1<5SRnVgYq7IP}%c+J{39XZHNdCrX z#TVI01_}wt`!E*9k8(*sdb_qDDG~hC^}K;PzYCJ}>PHPa8Jt9)QTc0uJLop!^6i^9 z=Pm!SgMRJ7|3Defz1XrCZa!Q9Y{rqNk{Ay0iKNiC$8)G)rPIRj&FB=Iw#!EaRmK`T>7Ch<}ZgUZHo`ayH>l zeQ8yoD_JB7tl4)O(LHDD`rq#~=%j5hbpeT>_4bI(Kz2eP=T*ol%M*2p%vIGj6Uu)Y zLx0{@7YO&*T-4+Cud_VwhpJ07D%S^i=yi3{?!sixEhpSeH+`otD`~iAWPuLp^Z+dhtebSA&Q7JegDKOau~~f?p(N2 z-~Xl5`tAxP47OWAGa$HrO!!&etcyEf$nTf_#s1qs&9|qc@2^lH9)Ah?U~Q~=9d#nP zXo4o{-5~%Pn6lyw92?X$AJ!{wv*ld^KE`1+AMHqC^!|S8&?`>5^8wJ(evcXSZq(?V z$UCCrRJLZOU^eQgmezmGyLXxVkA6@IdZR7)Q!u>|b+L2sQO}_8fgAotV46tZiVQYj z%lvRzy#h6a*7KhMpo(%?m^!HZUr0bi2C69gS61x?q;6aIV2{GFeMoh)IQ$_%??ozo zq~oy|PD2eQD9)$zv@V1YjtrRtUV{}FrHG&-3;+m5n(M!A*N>b5hzBOfwmkb^yZU;3#Y_Hr}&|I28eNCPkYc*0xMwi)ll9-_ob0ajt}OBj7-2t8@(AaVxpNL{~a&vyd6d6 zGo1}etBBknCmXbH{oe*qqxWU|{sN_eCxCx&cNBI*xv&Dul7}haWbx=5n(;vPP3N>n ztVK7&y#v1+^hETXTQC2r#bz^x*luuf-0GYVvD^;31knxOO=ffxOI$l}T*O=wEc^J$Lq6irf74LN;|D z4=(%LYqTrKbjBa#y+vPS0BxfLAD7A3Vk1xV8h|v^WoJM!A_g#BILT@7vi<-5|QmC0JS#$DpC_t20!{uIis)>*ax$Ky1{r`XRtq?ax zsV!BR0^&lDd>auJz%TE6k{N!>`pUfKs&jvim9i@ewC#}YOHH#9l<8=9O zYaM0a7X`13sboi^;{4lS{CR3l3K8!{=RxVCY6`4_Lg@w2n&)|BWEs9x-ngTVL+gVZ zA^0x{J=u=VYbRbFv)vt(EI8Pb*xxUH^R-$Krc#@xGm*ID%=-?jdk)4CUJ?oSl=_v; zie;#lZK6vlzreyNT4PhW@pu_nqqALQuH_()-aTt>H?W}k*X{Z|aE-u7%S7E)kesqx zDLNrqD_A+=#L$+0JvBk2c(R=$@odB}PFSeE*OVT{I+k$6kG{y{$EY8DK{D&vp%iq> zKW87>%*m~vh~*{ApQA_f$uNLhvKw@)-vvAe?dGESU9bd85HEz`$|6;u-jEgo; z+Ix-e`~x>ejk{@ThA)U6i^?iW10xF$yhQK;*B2TFx_4j5ONqoinT^5SrY}pbg3h@0 zSX10g*a|gM6ZYguR-9pY*sY2w8Q?7)T}!@R$gIR|t!NYcpB6xoVgjrVAJ!-`oz=1c zHX$-Xy!^MXR@m^dyyX1IF#2wLeXT(k9!h(?dnOqMlmacYW!N)hRzenrnY&(FWznk~ zLTMmGRRpJD8HaqkxAnTtM_fpp>lPzMRig~eUU0;7uKorNy7XU4UBEp90&^UozqWd`6`ers=pmrzDh!crJKmZTzpj9yw*R>}S zO1aI|jL1fh6ScV~oG@M@PD~vrzl8zETsF;dCsRbHHnt?obMm7|J7Ak`odPov_ zz~_b)5)5hkR^nRp2kCRnLq#@*8%fb4%h3+n$teN7!((m{0$9lk@+IK<5>0PNx&V#D z=CKMr)uoSB>`5Iu8ISn?B;(Zm!K%R$n5x&b#RPgv%wk}O6TDn-52jP)r_2=vIF3%y zuFGOzm}0@-($`CnR7Kld7uEbhF!{X~JD&uENv_)ywdk=f-{k|5l%caJx^++!GV(sk zKrdrK^yCt!j_`DdUR%bB)p9_Dj2`BnxV3Fif=ccqgplQ0q6-4>aL+ajTy{N-c13wh zgncbuep3DBPdw~hjVngXu8d6Ecg6%aDftU+<6Q9OB(_zom$?tg@OzBUxub#9&D6l_ zmSbWP#V5h{ULYeslu(UApj7^WTm;GgYrh)Ylqq%Sh{2;*^d&koNyG~V9Z&t2MV%qI z!nAbXGL;roA{Z3wO(X$x;(7@B{BgP(Mnt8)356Gqz*6pK!6Q1)pKV`z{6UcXCy0!@ zR^t;wp57i5Ev$y5|7jNWBC!U-1p-gM_Al7ANwyCvFQKzBq-D?j<>9D0G(3bhvrr_W z9?wP(GqtUG=_YmNO^8SfUJ8AR$)=yfpuYPUGDM&dyC*Im8BK5=T@UZqJv`gUxeI~SjpDH4_bVUH zV8wF>b9V&1dCztJGZ(%e(EkL*ZFaRY2hoK3;TfU&vTBYrHQONSLc#D{NCaUHg)h+_ z)}1^`Z4AW9Tk)kx1}oZ2Ffe=~UoElYX$H5~V`T5G^3ASM{Us%QPh~Q{w;Hcr$s-rM zv%1~a;Pj!4p`^O#>qOY|plD>}N%qPbO#WA}g9+{LNQw;4L@5AXkfIZpx0i|}i=>ET z%iyF;P*@C0^RQZBrKVz6hoAEA2}ia1V-4XUru+ZNv4EJ0oCRZuw27SiQ+{j+93Ro2 zYHst*^XyG!EE&b^CIvi>HY2;O7f}>=3NJpISKEbQcF{~w?Lwr4mu58Xwa(^3SV>>- zO_@_k>EJ0wc1ZZ%4VYcog_>hYa7}-4p@+jJ-uj2*VpmXh1mP*k17KvZ04B!u>WdCr z-w5wFaD3#eiKq}ccw;0p9z~eJLXu*8XoU3lvr1Vu?JQsZdL{7*tP1)tBDg@)qp7kj zu2uRZa83U@6{sh5G||!=LT5QzrOBcwzP-KtX8$@QyEEVmcje$0{sUP)bt(x@9|ug% zI8YK(xB1iY@-e3cWe-=iMja|x*mSqORJ8!y=0*$>g7A{u}%($jtnvxYhk<63g>=R$gf zdsv*s>3YMNgl+|6D>7CPcc`b`e@cCT1FqGx^9g;ycptp7nC-1ib_j5PQ=yWe>dAhzJtOvw z9I?ky>0q{OCjga%Qpb;ml*w7D%5z)s`?4VIRgIeIfTJ*asTreX&EZe{s4; zQ&?8v_8qoKrHU~u^ta@=^@J6NOcJu(c31I@oZsETZlWT?*mHo|L`lc^Xk643gt@`3 z`*@4sM=$bZJG?AtIC?azaV^NBDA#uv|MUTP4KpR4v6Tg^DKbazA9U_F#lSWkJ&4_{5rG|(pX`AZC zy&h{aXW%SPzX^_^gxTIGgg+%hu&TkyQ^ynt9D?}$}-WcbhP=htJzYq z29t#pVJLIwV9>_n@yx_%QI_!CR%M5k$mn@Lt``csWnG(FM%}#2? z-h#>Z!NT`=huNcU5xj@)osHoNja$0YkrOPx^g|>+(2JSJNhKUx$V5uaDzvxAXSZ2! zO+q^8e-VFs>mP(mcpg+qo*V3g`JPb0sE!e*#nRdW`hLf$7f7aDhH>_vfR}jM8>+z53On4 z(hc!OQXqRK6;RNJp?d`#JYiO!e)$G2kgp_|fp==Q(`9Ym+@2ud+&kIZZ}^u}RPE5e zHtjkiTTs$|%OD2`yziLpB_1{n1p%pio^lmkL;#wcxa{Vg$3yiYSv2^n8+x68M9LLw& zwZzAwg%68IjBpuslq%i?3f>cOSpO`!+LtDoJuO2&`r-ZEMeuM!?O`A7X|+K#Z=p|J zdh}6A;Pn+tu$80|R);#Cf7|c(=@0rU<(P1iJJ@t)bKymZOod!^*I*Ad*)AB)EIuHBv`-zdE7Q9?|=u7Xh5Boxo zn_tFe`Fe)PnEoyJl_m_Ay*knu$%TaUjCP)v*&Z%;1d&t(wyb`8LIsbGz0JYdbfios zw!vh|i!8Zli9KFf2#{Px8L2+0;`sGI=%>AjfEPa4?q+ND`@nXm33a?Vl|NB+x%eqT z_!s{>(8Z6BA40Cqo_-wIo#9^jXe_m6oW$GczkW9ExLdp%)O#;`*MOCSG8dja=;A%2 zRXGz}sP+D11ea;4*&P2w{A)&3HMfVucc)U*vIZtb-@KN~on9!zSgG!PJmz?Ap;u$< zb1&D(?waq{{4J|`eRkXgY|w`?k8{&h-ZS>>4OAPyd^#b;XnyS;d*@}$fOB&at9Dcl z>G1^9c=~TBvd2`XQM#deQs3JA(To>D@871im}Ncc6(%)@`qiD6IAH(aw9v-i#Qr1s{5a$+T!CsvB%#|O5{-~2h$HEbCh21J#G}e8zR2H zI^%V`|G>KX`SyIN*&5OIBS%Bxt-z0ki1#0HnHck4@7BvFS3kI`g7Wp4m6H~9(A>MK zyIe&`){aL#uJbhx-hMY9O++`{xj!*{`jNs+6h8j$pIkd*Vq*3>HHj;)QOm3P zUw~8Sj=k1H<=Vdxtw&JH{IKlNT_l?f1bX!)lz2O4hH7KtBYk;%*!_NfwV-|%N)xw% zShiUrg~cy~u0wsOGDf;yAWL8bvmix-*~IeQMfw0BBR3FKH5NB?U71+SRbKg>?rVNA zGjsW*Ql}L*qm3SChJ*;q)>DdGN{p z)g&*riXlf!WKOmy;h7ol`e{eNd=^Ex*3`BN#IET$ctg~YSqkgySu3BmU_7_SpYS4F zH~bE44M2^y3`QcCN0rHc2i# zJ?5oT*Sgx{(?7h^wrf@LapGV0!&zFpVO-;+xsYYw^&QugOsB9p6F=zLNv3VQJ^o4vY_&`dEg~S zc_xFfjjCRDv;qnQOE?q}ev{>mV&cw$jb^Q0t zP)7Bh1$A$P8-r0Ju&N}Ynjd4PJRW{4$NrGvy@EXqjOHW4Ew@lK{ zfJEiB5UctgU3OgYA(+cdVwhXl_-U8y&4Kz~CtX&FX=;vy<(0?u+7|7(L(keQ?Qtr? z+DW_M7sX`L@+6V7QT%!ThGg=hlu35VU=__}%6A{EzcWiNo4J2I_=1TPnKXY@?Dh^Z zsP^o1d@1>1P9=LBUCez5 z`R~d3M~;or$05m(UljXM{9Z8>{nay#GuiCMFu2U4z15sBUj8j>bDaeB~dY^Fd1?W|e>NGLcgY(-G1Cnv|JIivEr4)yYCE z+VKMk{p5fC_i?3FIPlIeO9Q0tG*EBccH0`BY!XB3)WF5it zus9oFJRhM+zJe*_G^!@2pjNgHtRBRyw`wgdoP}h10yj#EA_7Rn7jD%!{9r{=Vo`_Q z(MGQ0yzbLqI^S(2jer*Q1B`40U=?1kqodfv)gEkLK~C4%HeRcrRkn){)4vGzCG(r! zIeSaPk^8aVJE!^_$ZQ<mJXOFV05EB#e@fy!X=mvm{{d;~s-oxbfOx zrV^$Gfmrdg-Cw5QrtmZpkb2{LJ@{aE41Du6CzZPvujNA5z60m=JXE!v;9aE7mYVv` zW%L?_AHfx9Z(_`Q;m+ZkP!Ag>=@u=|z;(|J}tr>cWyeIeB4UshvYKvE-X|`nJni@ zYbaT3>a}wUx6vMQ-KIcf7T;kCo`g_v7 zjURbzg*~j9n!io}WcyO<@rB8)Psks+@d)gKkB|Ao;OD>Zfa@cPkFdHD_k~|g?GwL2 zl;7)1H?W!Bzd6(!6ed@?%Y0P0xk}TwSgCe+vM0_c;~EHEE&L^2T8qEo*sC6u{BF+Q z#Xnn5F#N*Na*0S+-AiumWXHZZlds|PTKcGnYZVIL_-2Pc>g`ZlYU{rPYC+Hg)`peZ(fUYk;pGo>ip{Y1 zTUbH(B3TaoFSB(%wnb0{u}4{lvj=CZPX^P{`I7oZBcsJhl}Ot=N97r{InX$`uE+Zu z*+WeMxIvR&Q;573r4-GY;@T8%7sWS+S@{RVG$p)5G>Zlk%w$NOx0jUBnWIK-vNh9l z-RJZY0$5QPZm1ZJK9?5T%VSWgT$+QdU=tGrE>8{gpS%ustT2mijkLh+hKTlv@HQEU zpg75p5%xY!+AT0V&^l@kXN(1{3H~~~Oo3i9q>cf@qA!K+a0?W-`63c5eb9jw>nzlG zz|F74#V8p_vlMvyoY~;*OyYOX$Af znaQK)V+y3_tKIQZSB*eVr&rIj9qJI}pfI^zfgICf4S(0b7fFknM+l`+YdsxOB0=Ma z8!<19M@?}LEnXbDJBHnO{2|o&_^rd6Mag?kTs+Rx^{UUq|*Ox1!eQVsWBnkP265xYy&F z_Ve1hYVS?AH|NW1!8J^9)Yvmff+^Vutl$QlTS-kOT=zLBxnbT-{@iT@wqXX|(eBZA z7JJlhaH-iUCTWQ2>ekyo(!dhn>IZ@A zp(0&F<(5AR!1gmP{N!sR#O|^#gJahAWMBgo*;dtQi>FlLzVzMt^2QMjc0d`4yb6p0 z!#^1l#76ORKI?AFt##MxUx&xe=m}{&Sv=ahkoCppics;0Q?rUEn2xxC;FEyxz&(m1 zfeU@jByBmUUzXjp+~2kpge7fpc=Q*6BZ=5CZNdVk)$0I7aOkG#r}2V9Si9-1(q^b= z;psD%{Gy-qqXGE3laqewc4Q8;*{>tx|&`+T@B`V<+}wPsR>qbK~g34OI07nrEN> z1z<|*2%qCb<8;ADO-7bBt^^3R3s3W+u(~LfT@bfyW;X@>4u;}E9 ze*rF-i=cXxY0n%ZIRcNcE@CiuS#Fjfx6>f7OD=7h550cM0Fcwqo#JO+JOglj6S8My zAkQ~$5)bUo@Di-|ac$Z-lA9wTR2HNbn<`d$s_n$QpCV91EqvjxI%1ePLox2U+eFq) z^z9n0KhIBM<6e|6048+bq?a1$ap9e4Ai$HF!hg;rC*DbLwwbW0* z*{q?Y#uezP6G;_OCJJlXf3L3|t(c@3*QC+K{}8v8O65rzU7fM8#B?d%dy{slwsh8V zoYo8~U)OUk%CSv>%`pL*<`}Rp(F~$IpDEChsAw2_I76^N93f6C1NIb%%#$EH{S?Om zW^;316m$%Sv|Uh|YC>xaS9kX*ZV?;~=h=5gT|g3Plxg^e6xJWl(pknnWagUT;tI-p zEX-c#|Bxi2{mbE$QY#~zk}3k=Z1L6j7Yp1o1clVLPa5B@L@s zREUrNL?EF?P8ww&xBUgj=!qsXqL>zbf`GU=_=WX0D|3v(N4{p!zW1g<(iN-A6iD7> zzW7tRM%4(?Q`X$D+u$JC03QV*qWv=<6>{`#aKI9g(g1~KMft<}*lO@6xNcBdb8Z(a z`s@5|460rFF1*G+8J|E>ns`14FJOkDNx#)GaA2#(2NxaGYo?nl!pO(OskM$gNtg~W z@UxktfWx%2;G6yw5$IUO!1AFg=W+OhgrnVzXRbp1TE*32`91Wb1Fk7wKHM3FoAFl`o!&YJD(}%amBL98qM}F zL=Z2QV^~kLA__s+E@W|@E0D_>rmTAZh#*5WSeDHNzN(ahg%oKJu_D5q3{LOH$74j1 zweU?1w+`xwDUco(T1q9TU_YOcXK%J`lkBO!W{HxlyC?jT!WaRfCe$z(Oa=;Xu!T#0 zCUGXJyEGrR!xl!!LFd?1BWmolrkKZO2HOY;emV0?ah)?6HeRTni+sJsvSdePocHTrs&*e zT?>)euyLRdVvP?7Y!18kRfjI^`E+RP9ySZk!o>}rDRbpc>`7t>cGV+7g^dthqu|Cc zW9JK#te_yWlkqf7~VUDS6PUFEH!=kbZUFRO*k&opdU%+md*!}%oCJ2}H@xBi; zGA^~qb@i6$UTZwfu63@x4r-w%*X-6k`ked z4&*l>3X3e+x;XOm)~%&KAZ5`#9eZY@-d-8|RrRQyA7Rrwqk9VWdk$avULV|B9N2PY zu4SLU^cNSv#3wVayv_UPPg=Qi#oi^4O8u%Ejvex8Kl^&gp>uqO4Gi5I<=z00FBRZ_ zUN?t|&ST@EZN9Mj&1d26_NOuEh2G}X@ih?Ws=4lW@gTHfkFhZAR{(5TmVDKNMC z5`&Ij_*O*iOb+J;H7Q0Qxh)>v%F;zn&aV%>>~C~@w%PIW!-o1o{_QmqfEduOb(t3m z(dvG4di=ns!|`aT_}W&BV>qR;yOjEN?`ekhb$LJK!s#nAknmz&TD}Ih=M8Cqb8lq) z+?SIB(5o_A+}Y+Lw(c37A)uf~E_=RN8&o&oMHWpzk`oKQTWRO>X6TK5_EM?CE1`yC zHQvhktnUSq=Stai>kf9!e2%}SO!Vv5e`UDP=qPPIx`7l&mONVQld-D5XZXT1GBwR5 zX_d(({eq!=js>M0Q*68I^^Xin04U17i=QvB%gq>2S(oJ?A`t1b&yR zvdoPVlrlQ{ZpRQDf5gh1$fN;20j6@IukHaCzl;>lzP-FS%taUtH&Y;=5@CR~eRr%(8uk2Q5+>Z@s#XeM6C;sWc~u{>svL15_2 zrS}_JK74ltTs`#EsqtOn%YJ#eVEeTDvqsW6ZF>sGMd^Do@-y$NbH|M=X09j$VZe9I zPOle)Cu)hPx2MyOam~m+(uA0;NZsg+%k!tsM>HE{z<3U5qD?oYlG*~&Uwu+l6oW?AZ zyjbmd)8ZD7K)+HGHy=1**=d-h9Q7QBeew0FzOdqF^9a$rH#&PW7G}+*!m?;YUp;b* z0Jv810Z~)zXL{@m>mh<2-Dv$gHzQ!SYgyn zI|?YDE(Q|V$lOO?h**u%-u)(YjU6IA0Y862Kp$bW6@z@lA4Ddb0N z7sMUE_W@oj3(|FS2)7v%zLiuB2wSalg=X(umAaL>D+^H3&s8G~PxXEthNxz(aMz33 zY)2_2Sy|G~@QIv!*>gARjS8w#j=HrIi0COey6HKaVD%YBKk~e1XOX0ZTI2GE6_(MG z0}t3_XSzWkD#hrWw5s^I5j|%;X2y2v2uisUXVwIlRik$ajN(WRq~*Ov9$Ic7M{UBqbmxaDOIo_x{1p?8BZj+6tKN#YJ$s9|n z2@$LSc$|{7uXe4$6i{?cF?Tm-K1`lKb^9wLQh?7zp&QX62|(2pUcz98UHH+;%U30o zJ5%q8QraOd%6fDuT?8C>M@YR*#yxP}80#)gXzXi@*0{GKyX24V)Pph}%~SzCx^}2n zSBr62zhA7;!B+~{gI@+W7Q84cu#b{+0c2gm?*MhzhDX4+_S1x&QKZ56cw8l6A=n%Y z(@HQ!GfxnyR2c>DyI83r_q_@r6w;a6vn04fD#uZcU+@Eh4%i;*?>{Vmv>a5(2Ci6Q zmuDybMwfXTMIm3{xdKAX&t}6Z!98DoL3S+-T+xwhSn^@C+!wX>PdlHgW@W9%AoN9o|PvFWg|Zh!We0NrMUTHVAArd+(%$1M^3yv_87^v?9J zDm5n!pCDl~Sc<^Metrx#4Eqz-4Q#Z{V3~Du=c8!lMJvDo=?KG(JH=^bnof135UJr% zQ7HA5{vro*THOxc`-9xY;-D}UfP&?CS{ZU^SykHHzakZX`xlJbbE72}+rtaRG8;uN z?09u~h8UNQ9A67yH1XJKeXWWyD5AyI_yheEg((siE=(ATqq7j5+w#E=V3yBOj**?s z3v!Mz>)Xo}T?Dv~TkK`(bV0;%BE&x+c22vJ<(+CUU{yWi5IQ&W(W>B+KHv z6d}SyC~SF>;K6ldsC*9I5vPqTC|1N~Q5HtQ2nBA^(_pO_$F!)4_}X5-Wl^mAH4tkW~~=3dw~0`hZyF`lYs8WcI0eB zs0_-oCQ+VLUhkMSKyWH|*7Me)o;;lyF>1gAREAO=FEOsv&ntY*t-&5~6Rz*+#tXgr z>&3Iy9>27#dP^&4@uU>dlRwww!bG4cLSDGr_)68eW(U2~u!H{M?U-bdvH7HA$+r}^ z#3lzTJUbvQ`#{I}PrOGX;tWk2>KNWy|D$jcDMP z>wc2X2e^q#tIHR2jizv=kY+|p*SVzdQ>NA=0|QceVuA|=FT!!@GhlS@NC+eejBePe zs!8PFsd1{^GZg+R^;0#esnu$xGk&rdbz*a$>J~hc3ClXjVEz~tfm->JAt(DesMkRm zjp!Mtf9koBbIt-AP`M)M<1m@)YE zmF;lUc<@VUbayz>fjbN$HYg1Fqn`0_g32!o(jhyUvK~%_+Au5&9{O4gxs^ZXm7hQP z0{~?B2lK^6{>{W8{Ql~dq1U)FzL8Oaw^7tk!O*P&dqFslbp<~>jQ;<0baZ40XYX6 z%a(l4opcMe(qjx1)G?Ol#?Ag ze`)xFl2kPq52?GZmL<$HgwRL=kgZX8^tCps=)1vjg-!ALIMFxTGm;Sj@W*t7Lsq45 zVz}j?Hinl?{yn5BfRb>HEPJ%wRv*X4zk00RyjXwyb zieq>nz}G_dkOHaOlbPi!_8MV}CD4!C6N(iFv}Ng`s6V3Gz#i+R?>rxhH5P|6^j{ZKcF zrMFAzBg%uKsk4B+@R#)#`{mYd(WH${ffY-j9KByuW;yLV%=VCzQN==1Tz;Wuc0o~$zRk0)Q!#4{3o3Y@tirj^%9HY1&Jjqea}%}1L7W) z)UOVB_o~mwF&-s%N@Kd2)S7bILho%EoMGVTGm5H(8$TAHsNSFtipPH9jbqy$O{6Bm zLXgIxUggY1$&JZ)#v+Wo=RDWiS-uPz1q6-qXsi7sz%t-bUf3INksrY0*tb5H4&U*_;Z&)@+9JlH*!jpl(-DMzu&y zQJJglP`Is|O}5E@+=2^fxzrM@t(3K%Yc|EPr2yC;m)VwPOZdK0I7}Kl#n{Pd!;cfy zBnx2No`6K3_RA@_pW&{;h1U$C4HLp_u%>l_=xIh9;=^&r5X-Wp_R(&$F&e==x)IK? z>k+7}Aoo5Y4jclBX?6wNt)^jY=SQgN=Rz4u^g*Wg^DnM!{>X~4V+MOEL&Zv^j>D5{ zsrez?tvV!7m>iFo^Z^Qir{EectbiwsG+FPqz7uRWk=`^%p+tI*^nc^1?us}@7r<~} z?wd6}oQKg=GC>~1lC=}=N}82~7@=RgWG$f@6CcKGi-Jqq!Zc`R>8zEih-q$(f2h2x z7jXme?hzz2sV@T)syW)M6$1V)Whg#B#Rv)dZy3kX{-hU1im*t>JR(*T9b>1@S-3c| z4(C>HgY#U*+Gx#Rhgqd?s#z7y0eB&t7PCryD}t_=xFU1vj%;t^00@oDt-6eZt?&Z{ z8jvV{K4$|=GzX#^hp~H8*Hfn8+`?Bk1SiLX4N)QM3`jB8@k_5o?!d6w?70edgV7VS zdI+7QSGKl8yA=^cY+7ZH(1AVsso|8ELAZpGNr*n_ccwLRWc=$lH_jNccSb!kk^%mU zrUC)VzP8cKv$5eoXqW}eK=!o6KtjdS-Am8+vD6GPIz2Yj;Ld!Q|Ngi3e)63T~eV9$RD};Lzn{ zEz3i1&x$)+8|93KXOe&yp#0}xNF>t>06MCF5rA>jBo90spmr9{0ODR*)2dtGzZhYE ztiiW35;=7+ML7^l8G)!JKVvE1fI3|tSFkn|tXN%4p9{@V2A(Hg_z|r(G zXx;0q2isr27lZ#wBKV^RIbzE#Tyy*FvR9VQeY^FnezC(&zP)Y2T4UC(#LP*LkVdhd;QohwFQY{*=V<=1dvwUDE0(P} zs2Afn1W>Gw>}+8qgm=$F3-jcU?jeRw;(F@Y>F>Ye_Q6rKNUWc5Scvq~enYN%?!BdB zzU43e$HOA;4)OahIH9L9{qj^&HQadT6uyn@G#s(FTlFIGasy|V_o5(=T~g#sq%unSUPRTUvabok1sq<{;HtDD0B62+if9L zJ5MxKlRP$VRv^6ps7vzO6H_hn-NXz}G~;@>;XS&A)TsO==lEOoY%5m;B?h0ZKKb=a zy=GzYluUliz{d8dLzdGb3F97mf9d2KtDlzlD$nQ-gA0unNp}>YH^(~i3wX7j-Qnn$ zGg}Dw=FZO*mCtG+_+^+tyW$@B%j z1KJ&Z*BUMAMSsolZM3}lW*)2M_ltX_rlRjOG-Z!yI-`-R{bWms3opInP`lQ6#Q)2L zxt zR3Z_@j-cG$ z>-%%LBB2V$l}`1Dhtq3~`O{rbEEsuK-h_!wF)X~8%a71&Yxn8kEMHGD_lWeYPZ|}G zAV}r_IUP9~!nIUq2gU5{pt#&#`wktH_&*OyyLnZBn{txW(&nJ1-$Usg)WT|pNbX+o zUY@#hY`wRZ_X~5!7pl1_lRhI)zvT?r=CnPl$j|n8zxV~CzIadlv&kbm?u^XyvZH?1 z8lQ24x*vI1gnKfhxT_H5<snYGw$AZ-CBNFVR%z-Ve@Ud z#CjbDQ@y>-DT21y4*I49QdEtc5%oyrp|_uFY+BbGZR$QuZ+!6($)4M)qKcv{t>>&uyXxwYIgY|3F|PbKeg-Yy3yB!N$zRB01X$twZUM$Mw6P# zn7%@%i=>nD26=j8;Q+oNMc0$hYM(Z!rEX2tuH#}PJC>9zBwI_Uwf@1 z>d8pUeaX`uDFLmoM#7mWc4aI9GSdo28ps`QGV~NE9%cwk>PxQuK)z1C&NE1AqMD4T zwGEov{x$2J$CnEl#+2H|n(Vh#2x)rkB{&%B#R638R3j-x+B8*ImC<$X&|hRWk%GHq zfr{x!b*^Y!4S4=z-0JBZIxKuERaM)Wk45w%fJ=+yhU=&uH--_moXcsOS`e}B$U#x~ zT76&pn1d>x@|XkN;)!E{wxOI{#eIJ8&-@5z8?tL%&Oly^VHE$^d9xgW4*ry&i=O(b zBw}0Z%1t!w^XgP@YHo%gCAPZZ3%0rC8Z$EYaI12ngx}SZpy+Vo82=3bJz7|J}y&xi`f%D?(};R z+rPN%E56ujO0qHv3ZzqLH!$?`SG=MAndHyFE{w6A2-(=Ti)c&kI(L0sv?YU5b$>F# z{U$o6Grm^kY~B?Dey)uajW?W1osiY4o*gwFoZ;pBSr=HxDpI_Js!dT5PNOvoPfVTo zs$E6;fB_NQO~HNLBmAdir+Eegmro@^+BSWiOn2G1_zA7gg%t}WulesLo2t?K>S`M1 zGHsh^`0FN`r*r8~Je1qXXt*hNGC|f5h6!9%{e>=!HK7iH%}MF^=qa3}aqxDR$!g4I zEf*~}oU(IxW3nZss#SmUex1-tb$#E~OOqV!7DbH=2Ftb2+NT~z1S~8b@*F1{$(5$~ z_DwP6!z!*(a1cLQZ?y#@wEkm+U~@sAfMqs+L^%NU>_8ZVK^k(5-(5T)CkEI-;IKpj z-$C}oh1wxza5B?nApQEG()*#?`E2K)@%K`PFFM~b`-=O@TOEF?8ZPr!;6RGbpRCaLl6sWC1bAl-V<~c zBO##iOkVAVj5diB#W%aBch)Q3vCe2M=*;Rl?C9-0&+YwQ$OJ^)-)|KTxXclkjEL8q zo>qV77km3#B<3RMdIT)*=;&ik@E)+<{$3r$@4&{5-_c$s0!9-x1()bb7P6fe$8*(?m{`sahvFS$Mcfu*J zHC)Nu5HFGRr{M{#L&*FzAi7b5h+j?YxNJ@s`w3W#GgKOTdyiEk5*m4txW5ku2U<74 zxdkuXhJ((sJaT$}_KrW^ltoPe`V>h!Y#JRi+%fpzqkN@O;4v9 zc;NLtBRO91x+%!Elq#&%`@K0z9pGX_Sjdx)fnElIwmY-luj@m7{_CR!Q8>75(~(-> z9iMrD3BNVa$tm_%6JQ-Wg+VKq?kFM8gC{7pp%ixOU0o!2U@$yfcK7iS~54kEe1LGCY z!2kLTVu5Z*V5PF2O&$`O$G3m~C-fzN8d97TDX-2HCk}YJ?u>!<*GMn3sp90TCZ&kk zCpa}6+yZxv7y~f3=UxYM!LO5}SAe?=E{|y3F7-RnhKOBRRSVCbIe-`z`I@BDhzS%Y zdGO;V9du_bX8ffheo3YCPOtNYs-jvSkKv8*~io8!|9LQA6{K|$I*(|c9ATyo#z z0ypCxxMLxCU1awMC|_E`;+Rnk;Bc*_C*y-4zzJ2UQMWEmV4%Bu0wfHmZWy%<>cfPd z`mQ$<8Wrd=pMW62OVg?nyRA;n*vt5u5w9H4Ic)+@3I8Q)M(|!MB{h}FgR-5JIcdVy zfnTNP&X0mRyUk54DRoOFwSkk>E|V=*S)5u$CgsW?R^*L21&RCpAoZn?Tlyb23$MF^Cw1M!Upwy^KE7{_YiULqe)7X7^uv`&s1M20_ z*`IFpXef%w)!w;an6@x}a0 zp1-RMYQ}&&aPIX7ooh)MRQnQlhvriqORj}YPc#PwS(Wwb$`*5Kp&nz-twrX>%FFPf zZJPYCuh(J9K>$U-s8F9>%ni}pna930(&#OR~ZH~Kuw(MAhFD0prjbk9>l}-L8b_041a2u#PFS5P{8Hla>Unk z*(Gq#&qe(t#qJhdEbCU6HBieb`=h@j#n*dXeP0dG=Y?vJG54|V7NBPVG9 z>_%2R$-~=%7`F-TzPERWg&RTj6_wM2F2DQWB)`y1T=d`T52$yE7%!8A%W;*R;XE+E?fmL^%$84^@fFcU16_aIj!)h`4)_yn8F0o#(Xq1 zc<47^CIZ(hO*#xX8h3QXR;hHQl%Ome?_g;*7Is>zWnNA#;Ri^^L6T+fA)8T9&nXPf z5i|!6B(b&4?3Tcx3hb}6@7)G8qJ_fTN5qcjSsUWVt0#i|TjWv4HbOl-4|7_6-8crY zDPQGU#gx-v4(eX1|IzOX191;e3*=FJK=L+GyUMxP=uGB4sopKL0#qy)hfnr?z!fOi z#;`$m8aH>h7b{#t9VgAya0C4Gem26P9(Njcr`Yt_?_td?7_N{Q+~ z+6l`!z)|#_7xERz1i|cy03|7KJ;I$Fc?wUfEpS5c;sZBOBlNt}5p>*}Omyrr81IK5 z*4^wFa-OMZd@j?E#X`>zUNLBJ{49-rSr(6GGZ`h#y=l6Jnr^QRcqhtBoWY9eDQj>+ z>06b8;v8u^H%{ouy`?DeV0?j`BeBx6^z41;b)!7ZfhaI61VRSXf_~W2YO&e67j{fz0ybfGY2RGXm`JAf^!)a%=ZAtfqLX868v{kd6=((O;kn62A}}Abb^t*J3DKmn%J?6M#^%!*UC!4CI)f&{2XB zlgb}0SGa7lS_-E^1g-u;G$)J;O^;{6fzbnhM>ND;j^O^~T*pLDKK)!+x1CBzYerJA zjg-_YSRfd2s3g{6faM&D0`fHLoHP}bI~ZpSApW!I=V3scp9&!a;Vy%9YNcbVyVE2` z5eKHL?1rq zCHbD4PJ?N1+cMouK!1}#;RAuj@2VY(B)3a`hJ*{iVZvWQ#vyEjZ2&K%*JZ3V?y^x* zlK~DoIMI{X7U=X^>}-y)@D95+CJvAicU$@?uOtrd0t`DI1OtV^8ORPSx9Q_JkE+t1 zh{q;D5h=65aW`w~bFykEqMM!Pys3j2pFd!p3A(Y!?Hl?S}9aCYV>I-!TfDO z5(YRsJUun+AK60Rdqc}ItCK>8Lq4t6$M%p&38#xKQZ=Hlv7JKtA5{6oUcvgeEo+6t z?XPGL=XN>jxO=|Gzt@l00*)bYiHv^c4PL)PL^yGSK@v0da|6ZpldW*JJFSv4ERWCO_&rrB`o$rh#qkE}<2${uI#<`_4ON

        jbZHr2s zf*rqv;&bhVU$xYSN*x&Lla(W|wd4w6OV zMZ&6vb?oIIfqBuzPWoutHPu2wgl(2)=$2Kb?%A`_dI}>j7Tfuu&#pBaoS>)lS4ekh z_Z`I}9gdZvX_3e%Np=feAKra{x0F7F;U|yIH5~l~Mu*p}T%Z0m@r;qQA%kB@ey`_t zr{IS`hU;WStn12y1KIaQqu>3YZD2MmWu#B8YthkecDzEaSA>M=?)x8 zb1hY+$8i(OyFmKASTxqu8Oa_*!x=t!8<sLY?g%k8Tm&3&>5`MUuPJn^=8t(kmXV)MNE9wDgX+p`_c@_<;xR>$6!cz5Ek`7sO+Y)~ygt<$5cHp6^Fr<{XJl!z46{doGphOi)Dag3)QDcu3ckec z?1kU^_9QHCy7SkW3ob1FQ94~?;VPaVy4~A(R1UX?3b_UfdG{%3VEA4Ko;B)nz$J?2 zTgNpH#RP0^CGa{Py4)y66bjVzm{H*;fIPTr{&ucz+Lxjy=&^PXq|vuuCOP&Oi_hgw z@cfnk02kT6g@HYC-;l-&F6*}#5@!KnN!S4R{7Hglm@sD()dRLUyUit)G3H^gGut>hOA*b_bI!r941_ zhf!c{Q1gB3gJVBg#yf~Wf&&_JO&~>FDyI};D2iRUXG(3zYj96kpXZdJBI41xoVy6? z1qVaKX13m8?ePBLSV&RhPxqq5{Knmh;faISHBXCto5@Hs~3 z_`2P+djDJR!j9)6Ge-7IEri}4zWVm&;ZXs*(j)gu0RtTxgW_nNNx%I7$0tFgO?R)o zFDf`0gM?j!z3R*GoFqmpr1oqv>7Jl&obI|I%b}Ciujl;EdYh#Q{=$VF9E?4)L9COm z6gMv-QYt%}dpGs>U{eA(Uv@?z{GN&f9rKMvqOy;|317ldIl51BEXFjgEuGT zI_)S-SsI^MG$)-#EMe{r56kVywZXLE&z)OKlXx4RBFg*p5?>}zF9N(b+Xc1YiX{Ao zwOS>aVQ#*_8ZflV+E$4B*tI@TbLs|$c_Z8Ld#(kLFM809_+S}RAg5sMYdlI4MxAk9 zDe#)ir=9aN9%t6J&{Q?{zMsd{XL_6=W}59pFMTDnL6`zP@8 z-#FCowMx8cL_w1d4%K80&3iXlpUY)UNwXcCb>*alNxIXhKiBH;&D--;;|mT?;MktI+^v+7k$dAn z1HSw7;ONY?*TBnhME9sv9Zdnv@H~a4l9i;7$qm*NxetBpgkvduGIzqNITN=`P_R|y zrH|z%9J?)`jWYhNKkMgveYW6Z?d9^URp6R&Tgpd!Z-)BPLuy@iAI-3xpe7&5Zzg5p zOu-jHR{wsg-dY;#l8$pG&2%P6NG?^C2teXls;)HvKZe)d)@F&J2rpqF@T}(KXPpq3 zHZm*ncvW)!W7P!z*&GLrwbb*EkwJ3ctvvtxR#eMK(xyZq7bsm4FC$+lEKAZ$($@rG z*r0-L^#{WW3!;!@C4TC;r?rGZcv-P{k9d`VCHh@OQRL?f=h+1%vL+kHHz{EMYc6-*Hv(>;@b8|q!2yymF-==zU?uVb!Z?1w@vPDxm zS!5P<|L(4krFs9vasm0tNo@aKR6l+X!3wbJLV_i2(5ak{zO5TZufN?jV>C}i%3xE# zt{PJ!aN_MH7wNl40K9w&v3MZsxYi9RamTj&-T~4XP+<=;(wM>DY3@#bygrzF4FKSq zrHMbblQ?KN?~lW-C`OLHzU}uEFdt$nbtn0QiD=ruo_VbM*;4T}jZ5S$}K}aP|K5Dtyg z8pt!CnvrQ7mwCPF0(ypl!t^nEdzZ5-d4Na28Q{-gP?|t$0-_9c*#Uqp?Du%67&c-r z^-0KfhO(@p@qVDpCI28s9SY z^KECDS+wWRnFFiP0*UKDi+2mC^fc<@XEsU`IEU;40Wr&h0^v{Yf1o*b)1Gc5>j*%> z2@HwTCFlBl7;6GI`DXgxG(%s=8i_5U)l}kNZQuX#)SgRTKKpC<=HLqek`HDR1@$zQ z@{4A}&5`I1``cfyfxdkc@D7TflMshUdn`%tZWRXI$ajAG#(5IK+ zRHpu&3KKhbB<3Osf-WOe1c`4e2;AQs(vV$)gOdbN$yg(%d9tWWTpXRXBbG7h{DkpC zvL>nf&Ysr~NuSq0U#v0Af}I##p@<*i=L*z6U3uwy@&=Njw&mxGFO$|5ctz8Xl`nNF z3BcKfu_feJzr@cpl_`HqbHR{ru-&aY%=(5+m93EPdqDlQI_{cr=84&%1C6{M`CGxA zQ%@@(Bnu)uFxQ)l_UH0|a;(W*c|tTz;o>FoCuOAt>0Um{$7LIs_i3eEsc$L&g1kVx z>{J9S)nA_U@1T^KjKTQm@j#v#Ul2P0u028Vi%_VT=c5x!xSYBa;K|OT#ND@`?{%RN zvj#|Rv=dRFpl}0D)m2OzLIlkVsc*f3VPOsFBz@2)10g;T-aii0WzE?sSo|T4`bV{p z@Ju&A+mLV=uORa;fMw9k1%VXs`$C1;$^29NAd1Iw zJe<^KwaPl%LuuzSoP2fBL}FV&(xtZ zn@>C~0=6TIClK4$D=Z3dw%)v-p2@wJ>PWDyv?__c(Yis9iDQ{!{UIuv!i(Dn9h;Wj z3|^(T4pE1}zQV zCz285X~B>t634c96N=f=KjDj#YAq@a0v2hnHbqAywR+bXHXz>U5EG)?cdd$4I>_G= zq=)@~FF_b4a?mIx_~)>nO%F8>RvT+{c#kV)J!cR9_<-~%L;L}@rUf})BZ|+g8;EFP zklL8X*HX{C@OO!x^GPlhulBIBLF+56C=8=M#(U9Toy*CcIqq7B`)gsyq$%y&^^{h& z)d6j24wp^No%=Ah^3j}pV}piOz8)q!wj}>6XpGtZtC&D~ZceBl3gN&vx9!a_NyMgz zcvW80xv+9BiMN}1{+CPa2BH+$3ff5?pU^k&AYrLYldwLlBX4(Q$W%U%|Smq;&d?jp$D5HG)yhn^?vVRVWcoM-fWh22vvc z3eGs}sdt?*s^?hnGtq zW5Z$$DAD-gJ}bfm-_RW)4^?DFv``#(GEHCp15=_CDeJuA<J zj}g2apfsLmxOB;nBjzp#Im3Tbkj}fE;yB?ydf_j$Y5rG_O0A_l*jO>)(s>{s<B3==M{g`ku=4fak$FquGLK z*w)Bd`v8j}=Bi|!ntvr|evj;$bot)|CH?Pn`4#N$H3i~34}uH{jKm8F7Co|Q$WQkn z0AQ5g`G*@k?Rh3l!_vo->!-}YmkcU{dpc;xTp+@G33i-JfLXa4u#GD; z2U{u5nfSc={$K~Jg%}4J_BwDt@vHatIRx5$8Ko#d@c!C-yj>eL(RQ%r4cOT)L9^uH zvYmWLJy=jMLcV6NmmlXb4&Da$x(;}*egU=|e|`W%q(>?)d=;98Ay2AVj8RNf<=sVa66mAkF0% zo$!c^QrHFl#-G7|^}+X6|DS$}hXFI)3 ziEd%EK@sF+1&wh@&E1`jnwFdaD$QxVEzFh3PFikT(E7IToD+=P>-23uyv3(>vz&tk z?3s88c>K+~s6V7GW&atS18_TUfRFAL!4V7)R>A9UA_EglLt06E=OIW+%@Ty8ei_S5 zFxBw{RvGOILvoR_uUF*{7V`Y^DNz`blg2jD`fp*EAet}%JP>|@gnP>E+d(HNUpmQ7 zw-Q0IwNVQ>?s~n+a!I|^ccNqZIDB#5ykk+|H_X2iL9VFRF9OOy{v~XP3rgPI!5V1b z-xo!JfN^X2(L?nO!sOXB-tVY0WT2pjn|p7^7Z6)vJI+( z*GJ?blzXd4iZhpTWTc?orKuH7rB%wEFQBLQgU}tmoE0#4U$1qK;1DNmc@TFvTjllf zaoXm&dOEQErxA>lH8x=3C#jb4OtPm*4MOa{qrlditeft&3Zr00$18*#s9t>2aXCum z;2jLN9qoHdghMld;cb9`9-$3Ph{`87p1%QJGi!|Hs0Qx4P3bj zj?oA3fQCe}eb`7X#T8^P#5ITdueZLa>Gn}`gm^JVshJR$-d!OFBk&{44mtSH`u)Mx z$&XiXdDN_`9Sk(Ba9|(V7QFPnr1*9#HG~F-!ujEB@HdbTBw3fvYH%4^^3Tv_z&h}I*|(|Z_b{b-ygoyVP5o%4mS0L1OLSQu6V>h7?$ z&$tuA-EzJB^ZQ!hUg)R&IsUV#J=9S?JhKwwa#GoX`69j*$sAH@4q+z<(218ALs$u^ z&S@}KrdCEEfq(hz#pk#2hO=Ux6Ajls6gdX;oVc}AlBgaB72&%Gu2jq6Zu@Z)0M=?E zfxwtEedWR>`|r$w3oMNf9U~`rww+7q&~Ni!Y3cPR7CFO3hLC^AWw(U-?~}E?N%3cl zB*ykhU2Fv-IbLsUH3+@7QAfYs-DiaTqrit(K7SVXJNTOQZ&D+Ob1f0u0LiFR^Rq%; zO}z$+Giu!tW}*#W+d{-b$? zj<$GRa4+gB2J5f<UqxMKei(rdZ&rkauo~iR|(h%un-sIdQNBhtma{L892FD+O8vTVrC6b8A zP0gNg&Cp~Fj)rzd_qyuodyxJ7))=(Y8fn-xw=y@2p*!0E%DpNQu^`Di`McQ6qG$Wn zSjzG$M!+9*Jdch;r*x){;9`us{JUnzujVH+k}zm}XdogO5Z?>wVxnf8SKSN6P1gmu z=m@(Z6+P{W8jT=OTp)Y|laiLWkStMH2ZHM-jPPKV2lG|lSjmZDm<=kq!cnj=up4%^ zxea;`J_#Sk#D-(I2%>cI0_<0^D-kv+nZ!W z>Jj1`2XXYZ?zJPf5-6&qLCMmDG0}Moav;4~#B$WZ5+_j0Gi72Rv@&=!=cgw*aRAIM zgE|F_2`ABU9vhnubxtuHM&UzHB|z|(9*+tig^EEY>ms_E;tujsMeKk-d!)p3VEr)b z>2f?bQHmIcp4P3mUW)Tuz(Q6A_DJXEBJg=!FX*8W4#WnG9i4>e?oZ_%y{9Gj$2tDayJ>7L z?8^5nhM9PL-n^mtcql@BDNpSK$)}!BeWPJR~dV;e3z~Lbt0T9Q$TC67}=>$9$pMt1oLdF|*FwEF-;k z;Wv}rR+m%hq5c(Y23-BT=YLWjhZxz+!Wf4*0wmGa+0PBk8wx6lKwE}=m)t0 zNDM>9vS74uPatv%zObx)h$s(dN-wIH;823-*DUWc2{3farzwftlNz_xH#j3u;uM9s zZYww>GLkKu5L8;J%b69B7GW7DJ%tiXCk)5VFZ^MjR1NIPk#7|cWs61#@JCuexMCk9 zR61t_M$nkTZyT@(#{`!mI+h+b>Ax51K2(#@6L6l}b!>>pYHq*GhCcz*LnU>roXtkW z=KbF10t1c>mJE?i7rTK1|2H;a9jUwviMOv4a6D^wA$nTc>`L+4zuA?f{Nnc?{TJ8% zWavDRH7~;R#N|l5!&ZvEs4S(^XN)V57=s4^OW|8|3hn{1g*^L~3ss#SqW9?sr02Zz1BqGpjfhU!@o8Bb0P1hA)oB{3BnVkHZczEN#!77AIQ*DP4BTuaTadFjTb%cPkA^{1Iiq;cKy7Cax8o`nLQt58Fll!!iA|<><8wFl z9Ef1ajrvj=nnt?4OQXBRWhrnWMt@DBAn2}!3i@8&3zZHX`N($nLDE>!b5yA2nys)z@WOU!NQ z29SK1b3~3vKD60w#Z=jM6fzQfHeErpnr*CjHqBWEV?c@qy$!*J9Gu1^G!G(9qrS4r zp(^C1x`;>RsPK=oVK(qPEO@cK5GUC>wh3>Hjq0KT;Jq!{Gd(U4|1*$*n8@Lc5_BqJ zcYtUV*$Vlvb>LHZTklrOxxc{33KtC58>AVewH1+v9^j|gfCg{CQi6cbW3!y=oKJ^R zpTU%Xchi-J6xg31pmPsI-cp+sFeH+;3R>jhS5R*jaWsh^)bu;s83Kj3#5Vea#(6lj z6T8PYH|qj!s`3SN@CZ3hmjRMujWoUq`Fx|5bdT>kL=ESN;>Nyl{&RDNuRd#a5!=&Q zV08-LOVXQ#kv2sKk|lQj@W(yyc0vUf=TmQY8c?>$u+1^batTmJ4T;%S(8*Hs)Tz=8 z4PO>CU~o_;82_ReO@XQujmUfoMYzFhha(d_IvYFG#rU+1eEscViCUn+5zT+9_dr*Y ze^WRpCBP-gbyC5vl?#6O+$k!_W1($(^s0s*3qi4vx0^k-b6rB!rC32=G$up{zL5~0 zmgl`8FqH7V){@?$J^a>ESFQeg>#hTQbKp)2QVAS94|^SV%)CHZat zO46BZSKRcFGDTg$Q!|{HuL^%sdcWrtMTsAOORu*M9PVt29YvQJoe87~|3zO^j6f5i zUPiVak9kYns#T^WQ0ZP1|Me?w?Iza9ke^N%Dg++S{LDo~s{D~zicob!`q>z)FRZ~} zL2)R1?>TYA=+UJU4|QG`vh*WWm)5&ZrD{aJ(R%Z*Wn!`(`c&l~up&>&9$uGv{P^YH zM$aqpe~pn>Qx3eX5mlv-CxgTwfUZ#WR1y69^lT}TF$pF;F+C-P7o`@x*ZVGf;o$Q;b)n49(rk(w#i%; zBqQ{9FBZJVt!m>r``pSlwdZ}_Du3~rXS_mZE#@AU;U95ccC*)=wE4$OUimySYWvfr zno)BXkxhP-Y2ITspH|{0ga-fRefg2toX@d`S)sX&=8p<4-IH@)IpV+O(`r;IeoE>M zX#awnDl|`18t!@b#r>@p%Rc3Q9?38&A!E~sgXK1l^+HXq1Q-qiA2<6Lv{#PMb)=P? zt%>J3bZ2vu!3a0MqszY6hokd(-&q)S@fCtl2O>I>1X53LHEbE*QerJW!mBb2yO|CxK zsJYxo_;hbh;4Z_gahfn;jp@(6nlbT@pAwjBwKQ)3orQq;BS(_3m*j(-A623khBa=j zF8#P>YZ*&dlDrMa_PPjKn0D7&qu zf=S2ldazfc?ubBxbXmT;{TkBZ| zoq^>a_>Sn^eO{$4lYk2;iTLO-S37)suwm<-k^PAsE>tXl%Pxae?s1gUfU`F*gj(SW zKN&{v7r)zJRekqZeOwO(gS{ zA(gK|S!9%)ex}y7hWOg~jHTwbO>gq_N7<%pOL^N1xz(_+2N8-uG_Y7=HmSmyXedg$ zTpZPH3-(_MC*RhZPck7G{S^73C#TiT@9MO^xjv)y9n@3QfrN9)nmZCX+t6~%HS4e1 zDZH}hCK4Uai9fBHU)No|I=yGd%BMUKg3S7P*@1hDn2C(b)gcDD6mrVluP`dieIA8) z3b+j9cFbK4$!C?F#y!P`)lefNw1ENS(;`d_#X!g=2=#jCug?7LEbg>2|6bK;yig?{ zOIdcJv-@KR4V^F}HQoH3iUoKPj?$I79tk$Cf;PpxU5PF}2k($kg6qIT%7uiT70YFI z&fKr;Oj_`iqoVD~jYKNSB{8@Ivh;mEY0I#x4ZNUy3fKtM6EB9~lJZE=P1#5s>0L*5 zONA!GJB1dTdieu!d4l)Hr0(s3c7&+=ZK5qxHK8o8Eazr#{3Rha_OC)QVFtGIAG z$LhFhcSMuS331Nps`{0`u4qMVaZIX2S}HgKB+SN;t&dI{mJQ2^&|MNdhz{6z6)WbQ z)od9z>mGj5R*Y`N8RO~-d+LJ1c7C~DR7meDv!3O}?9QstCtq>56Hk>#6 z%D0b-=)wFNUpm>;AG1!=0y??T6*6ZB7}^Ut3eh6Bpo{yotr$eaNylL18;+C}=TTZLanFt{yai$jqGsAu%saR&gxB+?O zW?{8kDcwl#Z`M%=^>k`(-HLM`NBW{6$BCb?41g>PLPnq_7&fq-TT4R6_R?rv!tL0m z$8)IIn8+&i^{#j9hDqE?b>BW8@g~V-+Wl<*n8sZA>69Ze6*cI4LL3ttfP67_mZdV1v{xxEiwZHkVkrV^HO_A(^0(>45; z0lzC84Z~ISc91(034mW^SstQoM8hJ&+6Br<=8McK_`sxyUdb*eJhB@qJS6DHBEWxT ze1+q;kUx^hpfp=edCUq5|4agOm;PA@V+KVx++_{arBJyjW)x1Q@Y_6k_E@o%5971P zvktZ%;}p7iWQ`=ETu;x@b{X%m%*K}(6%CxMHJZ!eJ-))MTDahPZvM<>srYK>U!=^W zLpPQ!v4whc-S_#-@#Wk5I}BXV4%DZ`Cd@)MA3y)TC$d)3(;kk@yTKAgM@}(&=XTOu~<`G9!Y{m$dRTLxfGU1xo@W(=JEhYyP~- zK(1|dA*R<+b&+U7>UiuM%Y-{V z0s{rZ@&{No5k{VmUEW*$XD}Q@vBfAp2l3_&qkKKRu*EQqf=cNfyu|f-1)ej__ z8MO}UILZvP@vZu9F0nt%!_0Kbv)&k9q#g2fth@ix!}qc%aX`V5AJXtAU?rZR%zKgF zOhW5u9oO0XT(=I4R87H7nS4r%BDk#9bwStrI3Mg>xi!&A6yd8%uba*3E&x3ZfE&gB zst=B%lTx2qec^27h3rb_0r-snhPxLu(s@ijyzUl8-y@%;lx@9=fkO$kyG)bjFj$aGb2_tTHd8vEAMFbEWlW}Ft3cBE(L~MO;R*fxu406j6JZ-B={yNz zgnzB(V4*Z>uRa-@fRrB1F_LG>Mr!MI!5v-VF8EK^34|-d^dP~l*Rff%olb3NJ_jcJ z6zO?@5onT%ImiOWqZ!Ao8_@Fw#(X!hEDDeO745V zREa%?lH|X~b&fNdo5GcGabqo9^TpV5uzX!ho(5oq?G=&~A&sZi{#!lHS$ofbk zOp{Io&)}Nh)rB!p-PLR6%^5+isv#}gF?2{gM!wJ&-Gzc)pBfhqVxq)b-)?nCE~OJl z;$fD>%ygP^D%A;3rjSl|3v6zd(v_WF4JCEG?=2%BcC#$h`=7a^OB1k65Ox}&c@bvD z2U}+`FlP(J!cmb)5+_tRewP)t+%*j6E(u*_!6s|_Vf{-iQL12y6L>(^`EHmY*no!a zK>u7_lxkP3khmM9zMGfMu{TFtkIrPFgMZc_TVN{LZQjU3=!&Xi=aj^Kg|XuL;T$Fb zI+PH2NG|8e*@STeYIvY(f#B3(v++m5Z7+g%9uGiV(IHh??)^)>s^I}<*U?v||>tV0=ul_$3BU$>m zvJFx(D}|im#L*n3QFg?57KK2%k|aK(BEByp-JyNq2{8UG9U4OxI^KX?xaA-IJFx+Y za)fFAbi$0#bI5#>RTCh@?h~TF--g_At9AEHI&Hw{Y?<%b>GbW&k-sLLqU9qPEA}19 zkJY5&BhXuxIrp5Cx)SC;BQF6=a?w_uXJ)FqDRI7kIg-E?*43M>u@9?M6??|8;;S2 zR>6niE&iR*-e!py8V9Bw>NDelg;Wa`&74!bJBz&@Z?QJjE582sG1aT^8BIy`ZEVuAPXhV1;^jY`|(nX{;jevmSj+CoNH?tpg2^u>y zdoo_OP;?Z5cB^{`ZA3*!pL7p`8bFX(em1tf{Q5PFLM)4KQq&H7_BOT@A%2++hpv=;82KFBGeFG<1OPvpl`c{qnXn5G2-1VW#C;TxK( zYYLq~Uk$&CnC%|`HkeuHPsw#_(?!X9TfF}YS9wHcx~zHOm5<0%$b962YIFXNnSh*g zGQF~~h*Y_h%yYMyMr}GX#RrlDHN0{}qDyeu8{2-dm-L82p^$^OZe9Ax60y)%4PK94 zMRh;R_G!s^G=G%8CP#aaRoO3UzkTLk1UOB#y!WA-Ne99f1!0-%m!M$?r%^ z$q#+{=3>@+sFr0X>LqV-DdNA;ajK4bn1J!!1o%pKCd$>(r~R+|#$+UYq%#M;j$A_>mG_yzwHxRjOX973p5_B@l8m zw`IPb$^Il=zixwYTNX&%e-}YD(V~4;Od8E`|K5LLIWvF?-KJ;~Z<_KYNcqFjU8)By z?4V4ODhaWFqQ4Qqt_0sKM?Bu}V|BE?cb8YIlWRc!fkj)+TIx5-a_YxBX14m>=-wm+ zolb(<$w&ucD3?;=U#2aIv#LCjsWjorDMc*na#&T<{KqrgpB#zP3ce}!=jj1$^_0?^ z8qvSB+7Es$QzGarnY%yE{tYk1#J}x@DW&^~)MX8T(lw-@o9oPc+pB;?Gd)&y`K52c zQz?8*;1BK0rlg8PB3gIcsxnKRkJwK-GhoeeOEbm%ylh;qs2%-0hqJDEhD{;wj~S~j z!q}w}D~Vt!56)we!84Y}RTFv}R;&_PAq-uGA-|$nKZ>+A3l!!SSC$C2niHK%l;3(* z6f8XH$dXDQ>k?Ys=cIj9EEQM=G*e@Dangp&RRtqpKh>poG#k+p)En@fKmy@UHn-HP zs%hOFb+5^e9Cd|(`^VFm`Lr77BG78t9SWwzp68dJSlLsPO1gZ>>&+^8rsvU-jW6Up zS3b(TSu({ymF(laN-1B9uz-qSTA|XS#X_$In$CwuKplp&pWRWi@#*^tP>w_xDW5X=zjb^d4E`6$&-x>Fo~DXF6Wi;@buH;k~PUypJC zElJf{6bg&M6eER=5a;pqjoISC!BP!d$$m<*OLdudtrk~wtcw$+)iu4LNwaWYE0FP`wMa<34R}luDfd6;5hKY)0m`_jplh*rZ zMl_~oWLe4cG0DLL&??fmTtD$QI2cRE)X5GqaERLiz4&BPBC}cH`^_M--}*6B37!gXYMcG-0S5Oa3QFaEEUyJh>6~Mb zB^z5Ohshl^>l9uZ>iN#>N3#=7I7r^iWDb)ZR0Q6XBru$`Yc(yFQ*j-rYHNxSpVl@g zoVx?h2tGJ*D}siF${$c$eC zjSgf5G*`Sfm=j!v2v3t3ou1Qi&^log?b*=!x^KZO4Id0cxn{k!?!quw&Y5Vk%qHmK zBw{yQZ9hUDiqNFBK_#(Ovq~H5x-%hY4p3xfif}TO=-P6X($zlTPIMmYweI34Dbw=B z3gM)ye``93w(2IG=%#YM)E^lM_;0G~3=X`!g)hks07(7ZA?6Y^TvVeYEH;`UA$X&( zZVUhzd=G%-_iTuDzGNVCa58*P`%nf@+h=^v``5}z*a|Z<9O~;dMnUs2mL5Rrce9Yc z+u}*W|6uLC!>RuNKj26?_OY_#*d!y4EwWWMAuEzCD?2NDD`b;V$llo*p)#UluVkFE zNA|j3Z~A=K@4oK8?(6DuT{_NtyvFnO9FNE2X-SK;jt7MEk4wYF%YDCj`^#K@gG8`@ zzEU;O-7OE4mn?%KSal+)9rFdBS-lMbF9E8W!2Q{cq5YV32LMdmjBv+CjD1(z(l$`= zaoHrQZ07O=fn)r~f-9aZT`hKu7%KB5YT?$o-9EIg}6NB zhbquU^+WrdiG}rx?LGMhp`Yy~s+8A^lG!rc+nVUqgKC$7=r`U1bz>huMy*JH2Ee5S zeBYTDlITX<*~dQDP3Val?cCX6q;vQ2+g??2hTYs36&JaE3}}8oae}L4Rh4h4%iO}) z{RZF&E7OmxqpU5<#gXT!b9AJ(Z9ILrx?L${ef`SCNieTD%4b(t$jGi19TjG z@BKzU3KsubD*njXs#HB??;a{XIAi+8xqlJ+06NMv!>IA48*fm)7GLQ6)xp#{hD8{5 zhL${Yw0H=J{7(TB))jlugR}3uV7+GZ5Hs?5a%M4$iOQSgP+G-X~AUUJKL{p#4$J|7sf05hkQgcfDMm`5*_lW$3Pezn1?fb>;q^TD#GR0 zib#KkmkAArY{d$Pp$K8sKUau|^gi^kp5?Fvz=DlDo0@+2T) zP?#rBVWDxmFJjB7Ngm5ofq`xheP8A7Kg0{D;$IHSox2yO#%vwB5yEzA7R&gDO|!VD zG_k-V9__QK^259JMtnhVUSyFCGbIB)5fRn&?OW;OL(eyrrC}oUIjooqFQvc(C#TiQ zDzpB6Z-3#vn-VK_C9)!P163Vs{P}UxzWz9td-qV!m`8J)z5j${=@S*_pn#?sQZuSa zc9j0QR3ElFQ2~%;;^0xBq{BYN(Ux%s$XpK=h}g%9=2nkWs$cqRTXfHXtVN%HeS%!q zSeXl7_H$P6yMl8Fg9jiT@$_!>>C8d-Pybhda|8jRb8i&xU7#Ft)1_*f1wQA?O%YpX zZmj<_lf(;vbJZm8Q&&8Ed1BiZh;!u%|A`Gq2+raLYQO~ud$%`2Ha?rmKe(mwM015t zhr0SnK2F?HB!2SHbN}xh9(hc}m(Z^H$jYZvqB=csDZ*s;SeWQfG;>1F@*1uz|6$%$ z4wkqz&(V4Zh#|F{R=D^^-vx8d@u zjrE~HgeNHucRML4GYO>@Zj$^G3%O@~%dwcAfV{DGpOPcX3N?&yK}rix z-5m0Hov$Rcx;0@8?3$nj+dmX0Xw4wbjT-q(ZY6kP5t&#nO#mBqyM6`tsgvL2NWrX< zJD`e9-dVp{J308IGMf+vWM&0FZGx&!3}ysMwsjvZ8j7(r4m5l_hUi=QHwF~w>uevA zJwh0InLN5yW(fkBOn(tje{TQgv;ZkcD+4qvmbC*dZT*u znN>dG`L!zhMlM5y9;!w{@eL_`pyOO9@g1k*d!7|>PzHUeJz3%S)4p#9M4mtct9S{Wb; z(p4I}kI)Er^z6q)+UAFJ)bnF^e)M6EqsGC~wGo#Rcm>ybul4zfFL=r(qqsL=DqGEc6%Wl;*RS(otr8ZI>2PD6_RPyDlxB0E)HCRY~AVyQ1>dRRA1h z8+BcV*8jy1pw;B>vNkyul#h6^FEazf!ov4fdma}*3`!->oPq9b3%?eJ^xf(sRml?+ zc_cFpMG?$Hn#)ny{TrM!Fj?KY1+60#= z3#R!bHtWA3ZNNxPsai3D@JzbV7AWs{AK&*-hVo#8zvH?uJPAe;Udd>!>$b=T0Nq|d z-D%2eR-Tg4D<*j3O(@&XC^bc%{o@cUM-1%nFO0Y0A0s74;k>!g=A{F0-6Cu+He16N z*}+Yhuy+whI4?W)nXR8yzRn-G4i(-Y(-Vr-24eoYR^7Lo%o&Fa0{HXyxa)G?>=8*G zf1?VgtQ3$Af>9j;)@nLJ3F)3u@!cIWs`fHdLf%+dws{DhD{o)SzI-U5DaK`>R1CkZ78 z8sd&q#IH9L;s-YvJczDmFGFlEOnXrIRdFci8Ra=n>-3oOR$0 zoT;%G|+K*g?NpuIHo$vxW0>0cdebDz-1_0|gf^an9ozny(IRA3CMF zcz0I;mB97tHZX3hje4OZGjKcigkPlo{_5#T?0%I(FjjG~KvlldN0KlkzS%m*8~Z>! zqic;yq5d^?6W7LB3Kqi@<{(7ERj7~MYTF82z(g`+2;e6))#jamtaBgfr=yKFIBW3B z7>bBYKA*)%hTWTE%kb*3>|hTsbvi)vT2?W=vKv7G6Pk1gKuC{zg~A%$V6Iq9%Y7+~ zkyMfdJVaSus^XinUsS2Q%QN9`+<(J+3WkFuR^F=>iE$*r3%vF-d?T;S*1<2=97X z=QslyK(I;%%B!LF_pTUs*?=iN)@6D~rXJ80bn*fn&^bmGh&^kyqPae0(lomZw&4Vj z&BSfI3*1daVk8|8RVGD;*?X5(FYvtC9w4l|att4jRLGVWT4o2_5RF&)|BiSVinD|B zwm{&;t(CMsQCljucPEq>p_O)dwg74JAnoACrQ51iA`NYtPQIby*4dXb4nqui-siU_ zvC`s}`%_9i_fY4z8RnvR1vCUzH$*bq;+_rSDi9+>NjflTg=75vd#az0>SpI7^e|1Y z+GA&666R9qpcu41uo^MpTjRU74e@?ENS(i$X4AGD*cyq(AWpH(aM#?pj?jRU6)_pX zN(Mmo()TzGeyfoN_5#?CsVKS_Qt40^^j@eUwJDbWCx6e*+4lZXqR&Pl3h#g`rsB>p zxFJlggMxD_QBr36^D76gf-dK%Fr^Rt=C2qWUI+2bKEd;Bgh|T$*{Uq#NA?h?;$;&c za3KDOsJY29iMXar4gZH9V~FF}e&QF3VBl=Rs8=tHBL;D(A_JXqN?@`{H_3|*f9umI zZ0zfHzj@=mn?gpGWa-}(`VcWgX$r~yEPjp8yl%Lh(zfie zpV%(2oQ3K<{s$6 zO(-6fQaWc4t7{G>3>`tAOJNNHr2yj;tIRS{pydJgcLHSaJ&Ujur;3*X_s=hhjS241 z6N3Ck3#HW=s4mj(RrVL)QBxV{>*W}4{mFQYC$xwL!|Ddt~_vxZqnR26atQ zA5Xx?Kfee7FGg4j{^bXM%i7?(2Xa3E&8HS9 zY>WXuuPxB8ssVjfCIB=)%@{7APt5)plLYw$-yo6npUvNGhZ&ga4OsYB;wCLJy@7T! z5{z&Uacur)TKyfa^V|s(-C1BgZ9Xuk5wMIs0qwc2@XvTI7u$hgWf-{I;yGEr!vWzn zHlIUmxc+>UphuS?B;5x&KRdw1t^zu(r;lF)x3X&CYvP28*lK(`7DO|>4&Gp;d?evw zqQF!;g-U_e1rR5B7ch)YA3uQD@#)TeBCcmAd+2YGNOIy(BJidCq9A$3f1XZF1xNhs zczYPgksJY5pR`5Un0e~hWSw&{z!EGxdre&f>qzvIRenAq&-AZ1XJ^BLI%bLij9y%D z#sLTX1(5K^EY!?X5lK!6=D=JC0pB>#yAh>zo=St(RVUVXjotE~5J2{?(dQHaruV&V z(0weBvR_Ju)PL)qRQ9{$l63hCxG97SKUDqUEpv(j_Ce0ez1vQZ|vy{}=)CrjjT=#sUQ*gNSYkDBgG+>C16agI)t2M(Z5actH#O4oV{B^^jt&0yIwakgK z1yU4Lzw`{j(}61y{l}H4;9wD5?ye7n9s6Q#p)7Cw$7ff;ADdlzUr*)_2dj9T`dfb^gUatcx13bAyw|zOxG)@FqQM-Fl@BM#N@e`}z=Mp?C1~qNX(uu=s7CGnGf3cO z@pRyWipRw_!u-UM#Fwq$KOB(-ssS3#OxE8sv5Xa{I*C^hS0t@xB+R$6r|6J;c0$A}Yy32R} zcNES1z_?$1^ZwrdUh4mCLi`&U%YG&_?@kb9&JU#_$5!B!{J$lZza9Fm7#QgE-oQ+# znd;gV_H;1n6>+Q}L3%VDr(6K7=`ou3t*?7&pDG*h1Jl~Ahq>OuJ83PLo>I9Taf>f3 z<=<88G-yZg-zx|Ma}1Ui3DTSdc_@6by5`BjoHssvs{8xCbLOfj;3rmS(k?SJ@! zxvHXpEK}6^M;DYBB?$*p}^AoBE6K z|2yCF)EE$<&S2tuO3cLu{kuXuF0RyH)A;TpXab5t2UC|zo9a-}`6KThVJ6hRH&dYV zd9%~-K7FXzIsfQ@Zcp4a(T&Cw4?S(yb=}#ai1i3q&M^X}PW}E8JKKm}p-Sg*BfIbB zJ+&=9?#O3pqDFdvSB8OQUd@X6%&}Xuo$(VI z{XgRkHBLj;Ha-vAzkO{woAq7YtmFAG6XW~n_2wC3#I*`2y^NkV?LBqvEFcJ%K=G>c zAI!3?f{I4%u!T_dU42`l{28s58@reO1Xq#90#u69(L0Thi-F%{Wl$&0+&TD>)4#IY zkT>QXM_-BbEvhaT+N*K3OR2+PJu)ml({jsxr&Eh(`|G31mC{1(BZCRIOo^3rop-10 zn$GAzh1FnU(v?(u-?Db1sTtNupD68#!uNoGKQmn3#p|^(TUXPyCN?2*Gex&$xpTZR z`LS&tT@C-?JhiGsWw(*hpBg&jGsRS=b%MV3ilTJx7D>j38UsmoerLd!J@e6m$mdix(LAq$NwdIbxA_*@rkiIFrkNpztzjkwmbY&5Y{M7p|& zm`bO_4NqxUPc=z=RzH3HgH7zo$)0CJ)%K%_=au2Zi<5DyTM_+LDMzcTB>+5d!hKte z(^r8JEQ+|624nv7l&&~*W}F0d$vEzOxI9fhT<- znOEcpDn$-@xOY1mDOMX6R3~I&ZfnDRYE}gkRwWfO?a&!x9o)@7p2?62*cnW`li;1C z`b}ZvT5R}jiA-!Yw|=;KPkHx%!gzu|CdPR#-(x>nMJXi#EK|zl<%=gRbC7tRO396YjN#PcisLKCb+mbt>W-QV&mq}dYf$T zC%V!~ueD68uhYpu{Heu&!FuD(@$pytnxWVFAHLPJFK5`dobEPwZyYiW*BeSQ<>Df$ zrfL$>(F^q^ZWJU)SmcDlu4CuPQ>02oUt;>>TEcach7s}4oc7gkN%^W;g`(YzG7>57 zm!XZHfA=JyTxe9v%hZ^O7XEW-!hO!SZe-_|SHzTnr|F%2y^Z@(^!+i$;x_s^(}PLN zOZGkvm|eB9AdY9Z^lEbWM+XI2SeJj&~QnVhk(%{&Mu}xekZ1?j{m9i z`a;pY2Eu@qmtpP2>H#@v*oy;tsx)C3Nfah#v`eZi*3@Z}(_yia%^n=j{7K|`-Db|n zL?!#CdELZ~t7NQK(c)S?^y&c$@1%p2)BRpxD^WZ@+A6e9&oiIgSD0LeJEf0juKJ`e zf%n!s5W9Hqsgsnt^Y`We@9oZYoOgE8hLeOtY9V5OIb`8z#}?gI*XC2}I#utRR)D}N ze6Z@g(%nv2mADwg^Xy&lHk*un^T@TH<|*o7v9_RigaGf){-$5nskiJhyjy-+G2QPC ziNDg`|0;}H`r8JI;p(*EAK#3WJ2LAPHcu%nA~Ndw(@SSn9+9+v&Czq&T4FUFBCdcFBdz4jaTQNTA&HmQ@=~C?x1|u{8FYt z|0};r*_uuam#`+kH|TfU=%VVj8{$EtQL9=#wHoBHN45b}oM7+Fwq* zar=z_u;%w_-%Wy+66Y*gjGH{a>?$+dr*FG^r`$8x*pK5GB~MKIO~Pi|?D6S^4e2$? z-3Is7{9{@`cmxU4wdcL((hFNj;KY4Sk;%(LIKpPL#?_;cN&a55efGGWsMspt(CBrQ zO0SC8Q;VB@4PS2S?bfBccrv*?I-9KVE>_BUywbWEP;3~ojL+BVLFywo{|;w&h189D zy}b|;FN!4a-}1GJ9{J!YoTC7`m+y`a;V^X!MwD`u?<@l(mmL{$yowf_3bd*t>C^!j@{Vdz_NT6;D?5L0*hlYV;UJ(Xh4j zvgS|w6Yj_Q-$|E7M_)D>Cg}kRq4$b!hu(1Z*rw~A-HFB)k$&p_TK+LrGW6o7E3Um4 zvDQZrN)E_xU^O2eic!c1E0~UU9~lhaB0O6+&Pibild5BcoD@H6qxpI%yTD?%T~wHTX%VX;ggpzzu zmW^xLcPB=12%>A24~-XZB@OghdAVfun0=xX(fgKf5m)rGdUd4q+O^uR8ZiZ<6eyZ6 z1m_oas?zdr-yoVM2KJYspHQ?DObk{`YBl&J$gGkEo< zf`wN(&)wSC>)>^N&+2A)ZDyPI<>ah%$X8EkbxQJn9e1HLqvNr&%26=T?!K|5k3%c@ zk1hc4&-6#8g~sBooTGd*$E!*Te`}PRUODpI*&BXuXzaBxU5!3U+&IB}Y$>v@7*P_8h7m zUSuz>x=GeNj<&ZcewbnD7PY36ktp+6_44^p3D`2ZAkJSwEdz?A@`k?j=*ETNS7d2V zS7)p?jg;)}e$~Xq2`zV%u!W8tp{Z}cdD3k?p_vW1WbJhz)!;U0yC){jD{(Ys>U&(? zCwP4Pu=NLNX)RDqF041!Wb<45uwdPgeWZpaf7rCb;pP4LsN^Gikff@md;AWaz_8EB zj+@uQZ!f&gKdTmaD;xD_P*&|1zujl3bF&33n*ZYxghXWUE|_HpC$4BNKhr5RKN#%7 z4NIBvF@9__TvWYUQ*7H(deB}o{g2%nqc`92*N^3#VN3TJ!cV%tjQ2*0vO!;Bgb#rHn$;A@XQg-w1kE%L3z`yCq z4Otu|k~}qqBpM+X^yv76t!Sx4Z1iK6+t|&=tP`q|XV&_*&B=ySbBxOq+l)f*3SxSk zGm>4FPpc?0sqL#{L>2Kk!OCP+&x!HB*oGOvf_$#L62opSjPmuUMGT|A)VQ`I>2SlS z`%0c4|Hjp?-#3{kYqdptQ&WVd7`_)Or*j+aoA&&D$L;N0ior@FdqG?OBDedPig->O z!7uMH!wIwog%6-gARDx&25@Mpvn)r5TDr{pJ*Jxv%`#kmBipWL+@87ZVG~T}d>mA> zm!ZA7aD}w$&AF}0QT_X1&Cr9@lAocU2aNUaPFWD4{XHIiAzh2aH8C^0gLnN)DTq3b z)-7(>f&FE7e3?JJOgQ%eftT4&hvo5QR{Q%z(A!dYblsa0g%$suT7Z4Kcn=lx5QM{94<=cmD-4q%Xu@D^2UKGIy z%KWSuho;9+KGz1>iUH@&X|c!8NFe&WPiOH&#nQbB9A%YXW##e0Q<7sOEfQUtT7#bN zth8KCUc2xuNf_9xR;xnk*MjocQCERph(-y0G zK+y0+m&j(iK18gxaw&(+@E!7S{~&S3Hq*MHE*HZhZT!u*B;ljVGh&N6TU+|Z+r3Xr zHNP64+u4JLBc$_rl2#M^?oq!%l_HpBdZWd_kRdolaDAn%bE7CfOiB-oF`y(AHoaTE z2=F@s!5iJb#;6cHP=}5Z^qkac@HV5TsBt}gd$QVN9<}1%aCM;@9~rd;G9B{S@5EO$ zfx^Oh4krqj>_M2OVIBSxC{9}J^Bp6f$n|4I+A3}rv0^@fGEUj=igr^Xx<)H$^m)oP?htf!Qs<^8y9Dh6UaR%t8nG80!sx4 zf5@bsLlpR5%X#FP90SqC5!Na=LU!@B7vLsU^#6Y)C^Bz*)fMY+H%UPwC)EefFFSDE zT|cZv_dLIQi@0%v=B9V{LU4+5-s|}j&%e0~So{r4?&JG29t+mJ0=gi}hr)Vh9G54b zNqliSi8H<7ITP1+P}afP^7C7>0aI7ji8ReMwqRg>{M-TUsxMC z_%HWqe?jv>ub<42@fMMJBeQ&Yr6z2B@%(Ah3pj9)O@EUylO*3rdz~7dQGWo>4Fi_~ zM|%jE1Sk>L5Bv31vj3XFcXEGmhBrqkvdY(Oot6L2u%eXl={OO%JjmkgA^$TeBSnn$ zXQA{aNHfRUKyQ@)xmu$5;9^Pr&0Ee>ou4n_6I&@I=Tqg^d|VCX07140deOR?JS6@3 zi~f_*+X8tM;Ou1Bd4S=7o({S_lxO@uxBn+=_}eC z?z6;M=o@{%fF6HKY=M%TQYFOSyp{hmQKfb@BLzq|4I6pyXdjKVoIU|kf#r1WKm3OQ zCKpIKCo~+|ls1{8)10HBA_2?87=T_KeQ^bE(hKyIuy-Sv0l96l2~Z4R+VcW3#G^pn z)CQ<2yAAH8c`g;W4#-iAQCXzD{Idt-P!g3d+1T2Kc!GVu!zS?xA!z)tx~pVPa*hauv`~ z30EN*;Hul+hogWqr}qmPdQ(=>3avyB)CH>{q|9)su|3jexC+!RKG=XReVsV+C5Av{ zjilGup2Yt-1AL+R^)l_FvVlRihfnjzo>`alYj6KkWQf>WXz9Owl>4UwOD;;`5D5H@ zbL6F&0$6Va^cH}3H~=)k+)_oH-|>$xkCd)AvZmTrg!QHh^@{>2fzzpGZ!a3q>AGqE zXG9HXYD8Y71!QwVL3^Un)8lQ`2{3gl{@B;cpbl3+9gN=wsLw$X!hH?SpIH)x`AEo+ z#?Lo{hJd~}t4f+BP!&xZ%2#g(!m73**F7x<_xNidJvX2IS!}VT{G7@CjU@(w2PFnp zLeuV#TgC00b{=>EMYB~fm=2g%O!k2EpRnq^_a1E_oBTCEtF6y-XX#04(|4lRent3Co{l6kDx|lK{Z}2X#&hn2+gI6+vgK zRiI#58zng24WVDy1p7pnxhytjockr@Ka5q67%g{v@jW{-mg(NVMur41k*00yMxYS~ zs$596z+cxZj)hK+}mWCOtN20d+6eEZznnT-n>}Z^K6@uBZK8tNc#DRdSJjQdRK*PObbO z9i)sm*_Ysk5+^jHnR`x<9nyIOo45PcP^(Q zZC*=&N@E`rKj;MrC?YQ*?G2A`pz~)A(A)PsAF%BE7?J)#!8tn*67#cz)f&n?7%P(a zf8v$9fosqh@ro-m8-eIHLY$1oSz48u%O4LP(V36%3QIa zebW`;1mrHSZ9Pi!SWMv;}HbePRQ(_Qq%lC6{+s*RhSL zWpRzD`xfB1!3y(0YqT1V`@=^#9qllBL(;?$FeIe!+(jc~f`tJ;wypoV*Gl<|jmomU zxdbZFXZcN_Q|212ilZEXDYtC~>`rI5@P>IHjcYE+bb}f* zVg`}>>ua8BXF%M_N!ku#n`)g!PYOKsbS{VHJLYsYBWe-~h80*ZKxSspxsIA}GZzDU zq0%^uWPD7M!DR&S(u^Cbf7f}?zt;KpL`fwqOUmWYtBvHKU7T|(#=(7Vf{{)pxhU#J z(PZ1V$!zGrjmbcAqTcxrKr%m`0@Ja+^hrdrIC6}!borv(Y8E7w)_g1?2Drw)kUj!B zi$S)yXncQj&QN#)Rghe)tuyFBBCn9121>G&pD|Iu4FG!0-@R|@+c2xg-Q23b@Fk=k z05$uspjq`&otln0Fy2*=nC9Cc?!sW~Ah^J-Y{y{$5zpOTnXIe47o)r@43+L3&L7Ao z9b_8hj7Bbw|8891WLaEk;09rQ>>bSd(%<)$uhu5kU%(MUnZT!Aj@klHr-nf|AnA`+W?i#m%!HgG~LTI7?gi#F?cP`e~MQ< zVvPZs)Li%zpUqDc58mD-hqQDf>u+30^Jb27x|^toERgAcaL9s=M?oN>Vl$W<=4A*d z2ezO^;}wnsRngzfIx@kYLb-gmH$Gk_0BuWXQ;Zv2i@~3KIZ3J)0Q)2aU}C?3?kby? zc5Erzf3yY|GWxyA3yw5JReOLNPa&QUiU7B0{cbXCKvMw%g0g@IPpDeo+PWQPI?s112mH;_WeKBw{u9kx`p4<%%>9G7eYHDVcpx?ulPdv%AWBrT$ znf8#N#|eN{>;f3Z1TcsXET@55M@41-?TIkf@jx6>TQCwOek_dnzGtT@WCOkcptyS8 z!bAdiaVx;dDThF3I0Y6N9-ZW8xs+_BnsiB3wmdG3n0n_&T7rMVtQ?E=7kCZ#xt=y- ztTzxNJPi#1V2V17)2**OHA4^d>wF>dqAPGS$f$))3}EEGrz{Eipbcj9y|Md{(~yof zJJ?!KiG+K~=cn4E@~uEaX#YnzIn}^#7%$SREQ0pqpDNq2!7$Lqhs7I%Mhi9z zZmt9J-0GxJaYldVh3WjH&_S($lTgrgMHf1dNU4~yb?cm-+*OB|G8ApEDShOHsit28 zTp$;KUC>0rt7Hg8I>N~NzHRXLq5iB+jChzrlG}i<)kvxjyUt_X?b?Z?;L`np1;@-Y zYVssOid3{9qmG%+?Y!Clwe#}(dO&lo^|Y|GdHe~2DPRno*0z94RRh?R2$W{~0af2f zY`Mnusxn@$&!RDCq;0__`=HdwPXB4$+ao@!tj~ZOXbBXY-O&Cj!n1+W zWBrPR-vE!+3!H$H?lgk7zbY!Gz|kY8tPhFmgo2U@b$UVA?_pHgc_@W-OOAot`1GQ8 zNpRH{0S(DHb&>VP?ORCi9gr%H4Z!;8Wc-!&p$Evr8joDqKXzwK$HOf)EQ09*=J$GVsmIFk8^^LlF1_Zk=+< z(6S7dVNltt{uwEjUYY=!E-6DzmjL<#?uB`{6>~yjwH2lJovo^YewnV>i{O^i!>{Sy*1*vUd(Av_^u2nT%xQthBx;4NWd=|!<~95@ zMQr$wa7|x{iV_kGl)J7z)LGdE;^l60pn11b zc?cx)o@jmuq;wp_6(y#!o+(998^QP6wvxl zKaN$|fd2ATe20QuD+OA|z#FvTidik7nbIJ@wGkBph#D!wSxl2JMnxglUdNe>d_2ZH zcP{RHinOVtpPv&k;Vhwir<5Fw-wBI27gvp!5d#x3$76%p~h2tgvoY*YCg2R*L?fXq9##Wv{X1&R6Z>?`z>+P!*qa(xhBX6D3o#!Ka zbq;?3UF40LHi%j_tN}7?P2F0!a=6eUX6N)zo@7+Buy<6BZ$CH-vP%h9!kd85WtQ&m z2~Ej<4|Mtnx}M(iSJsngeea#2Lf^AJ-%@T6Q&EzLaGu!<5HNKk5o9>#_(!oIq-98Hbp9PX`>Y6MwY4&tIKW_X_i;dxV{ z9wPtaMBjr%wTF?)y#a^>oYpjP4=46pC2<6Tqi;OH1HXsl^+Z8SGgISmk-SaZ-4gwi zSon(RF6mfczvyxiDZS?NKjIbiQ6;JM8ryU9XCLZUD!#t29)5UZ*9y#D0SdppsU+cO zocI1?S=E=h=CZT>acr1jQjD=Md?CzY@#EB&)Jts?%^N{WK$)-PfuYNg<-^Z);vg=~ zp6LOM1-j^>#Z+us2dSOGdpvUaLx8M$;Gm^vSWr;v3)+ATf$*3HD@VAlcGBq{J2S*p z+Y$2J78(K$6n!{G$jcnBg#?|edLm!}a%LI!b%~@4JDLVQ@ZKpjE-nEEnE?rl@pX21 znGTroA}B`ZRDKH;;jwQ20|XVgQ~wQuJ0c6wd@-K;R4z*UlOSfIoqe|0ntZmE*fNP0 zjviR~z89D-QexCx?~@_F9DMKOgJ{@qWoznU3xLxf0B#HDUC z-@8$D2>iTs*N3rRnWBXmcYgsNdF`N?wLmeUp9paNpR^H}Jmmoq|4f%~HxHwgeX%#_ z#!vvqUYZ829Vi~ZZkFGrrjl!hL;VFlptq#siL*eyg6Vc8;Rwl=x)8G!2=(tgO6Frv zY@Yd5&#|xG4FC8kf6xFpGZ0F>-9IxeRIy0>Wf_Pm z&9SH@j+@joZhL$7EQ0V4udS_7PC+9aXF(67L)yw^xrEbtChYFwW6F3u(t3Av7$mjHd8fP%5D)uH@WKc2py4+Za=*^H2Bcqv5 z7^68dU=wTdJ%Qge+YhFBnh!j6GAwKkE7vKq`ZAY(A&rVqrb6N4OJUiw5 z%FleUxSx?ji~9&qa*mP_nWh@O%;U2eu>|rRC9Z%<$H4PRctP4RFtS?Ox^ZgpzUPFI zV$=qghv2l2rgb2L<0;4WwzMU}x$qk$lnD9m7qz?6FDcpTk26zDSGHI)vYEyE%G*-< zK*lR6po|+A-}GB3s;J@%C!e5`X080(pJq52?T=?rr-)hnk^b+NQ)&AT5>n*1;kaE& z6jw)6FUE<<0RLrzS2NZYFlO4poN0}0h_!02cMjA}m1Pwc6_ zGRKTeZ@E(AWW0RLCBKVbfC4R|J$Au5Qv}P+ME*@eh_7$%yZZ-VqeKhM$HP51+S1|S z)2wF2k{ay@@^EHx#a}uIWIWa9?ddmoJEDMxH>WJd_=3yvGqRDw3t4E|&xrnIg$#5E7t zZbS`FrJ~e4gnLh){n&k$T4k^8x z(`P|$8O$50pC*}J8jkod>NSt^8?w1ff$(AJlW;Jpv=QB$5AU?fykPh0ElHKOW=}&U zgRB9ciqa;Z%Bz&VnfZrxr7k|#n7o3SkxUW384~9MBKs(b*m7ZZCKBb)7Ie*nl;^WS zcRxrrxA~I}=Gt;wP>sc!DSz6m(RWX9;9ZiJ0QjO;^aw`-?x2pN`nVh7_fCVbe9W*h z;3R?f5!kef_6s7li`q`s)Gw)>-`@IM%I7N^?%dD``1z-bNOu?5KZ>r@q=q`#?)Uv1hDock!Bkzf z-0Hj5v3x zeuexrpHUt-KE+Z2_{lW_v2t+$h}<@-FE4wDooY+hs;yw2Xr=sb^Vf@v@}Uf|d|Ip;7Zk^*D7JTrVD)*>li# zTb~@kWKP73Us2=6ELn7uAg`)R)8>12BVI%}tOCN`oibuE&WLP0Ev5r$GKsD~+9yRt zml26V=A{Ogi^g0uOMQYJTBmn@j8n8JO59!M!jx$$b#ZlV=l6V-GTSQB{|a_)&Azd~ zBHxBcYP1O#q}kd3Cg)@in>EDr7*UpCr>u^o)+S1z>6TqcW+2mQniZJOCZm5thG>s3 zKef$Q);yw-^u1jHzJE0S=;eJ4e%<*kuk+KN88e5(zx>Yzg*1ynFa1z?V=_hd>tRVu zEru*>t%TO3!BMhTvjVtTlT04mT6ew>4@E8w_OOd>Im`=vE>xoNy11kpn^NzimtWUe zF05|kU98T*c4NyFIDMU{6Xm>4{MMHoC+A?tL8qX=>CZA&4}Q8+=AqUL0;4%*BD-O& zaXKut#gcJix%WSCdRjdu^)G*BOtV7BQb5J!bkOwIOsR)S-9A=Ws9DG*^_P8vgXv-X z^)~VV@9*f8r6FR8&K7Ljo$JCrI{8UWkGw*0VJCWU^IdG|H_;yzC62X!YTQjy((nbX zXc${to^mQ2d{@!DFI5utO+Y*UkEpuH{RDpU{;M`SJNV}KSMx8Yr+zWUy<`dF?6_B8^)?pUrgu@llv;3flcpCqLT8|$bA9lbrngXU z7K8jSKJ^-BqM$e|66I~@{$ONW4;=i+w5|NV@5T2*>ITsnNar`Fh`Lx$Jc!g~2Mfd= zfpjuCbUs{4D0yDGcb2NGh7@4Q)9%vnp)Po-8!f=jQCu5F@+F{rdYP(+5)vAA0m?73 zl4S1^!)|qbxyD55tyj6-CeMNH_g-_B7;3%BUkcKEvMhC=3*gn(_`+O{Uyq7f4&G~7 z6h{qDd=W|Q-2+aYM|??!kiF3j8G>Jw3w6ZbL55|ObmpE0KLh)Olf#X@>YB9t2y7*d z@1IiRH1A#bDwdMx9wc%`fXTi9$v&@GD8937d{#gH?7MOfW5QjtZoDC>nb$yvfWx!N zaymaG99QdbK!6EJD@WL3o}vho);eo>)zQ3uQzAsy!$iXDPwRmDrv2HjeNG4ti|mUJ zw{LO2CI5b4=-df8YN15vbjDUtOlz<-w<09Nl>izQXaPZsmOW2_rWKnh&T=bRJ+jLQ z4cv9}uRh8mxxJsli@nzB*ba|=jRZKTEA=QNu&`u&6MT=md?R!BMWa2(bPK=O`}lmj zgB_%iqj29C4GLM_Ib9LuCbxW!_kZ!r486(cjZ)&!eV?6NE1%i@fS+dNIl3>Mh8$Hh z>GU=xYm&@b zwBfAW0tBW8=oN?i^y{`H1@^}KjIEvIR$A5y7hJ~O- z5Hiigz8KkplE~mMLcC>-oYq|q`We+2%T9<}gi-gcOwq*ea$5)#PzEB^T0~}-t)yQG zcZY`V43B^VM{ybm@Z_{nn*K0QB#>^clb2;j4tJPbdxfS2(uB>RH`z}M6ss)m?}AJn zN;-vc#~Z~}8gQlDMak1SN$QNm$G)J>qXo6uc}`&jW$k-{9OuFD)otm@DXMe3bcDf&X@kt}F0e1IkKCJD*#QST#e6IxFvS%Yv0ZC3wvJWZUme6e z)ZTAkvrB+Do?7>z=%CC{vOa8jHts3~E!Fg*d)Rk1zQ3i3`+oOgss6&pjJkd*{j4#; zA|5|5=<~LeM!3gO@q{RL^esP!GSIP#C7u%Nod76UIG*N{G%59h!rNvTFGn;B8lEhL z1$m8>4X3{IL6=v=S=d4zmmG;Ln1C!}jL^d3MxpTurxr!DC)4-MjJfyNxDB8r{FrOj zr0<4oaeSDOO>s428jj!-iQZuX8qSDU-&cUMizA1FD2k)b{YvBW{raER!=-aorF3FkO6Yrbu77LabA zj(TR@ycM_dL_PcP;brn@Q+X3EtnY5Ia_^&TULqE{nFif~co3F}(VRsa6CCI*LM2@n=V=?fnDXHGm5ibb0Mqx+tG>1#HrYGG2sjRL^Fo7+{6X z!R;5K7Q`0);jIA)XQkzx)Dp`FBfcji!OPd)$!2k&6L~aGjoFZ)mz}E3KEKMaI;`8^ z(p60rEUpJGuw)h-fm}3Jv;YBy=sNI*HLV);XrEpo72Zj6R;hCk%UwO1IrAx^8_Tg( zV@er&w5ZR9Oi$s_zFVm>BF$gvI{T`vC*KbxFe3a@gN$~DB89DJ1K^BT5J;_??+t$M z&3VdRk3-?l+$;s5@n|t~zbyiG`1A@M-uAVI z+MNfKhj@}UvaCIY>_}8hHq7Iz&$v~dHYlQhzQx>Tz+CS&7p+Ua-Fbp7xqrt6G{6hg zK;+4UQfzll>5?TsP$Xy@w48DwdAuT@D=$o%tH zr>YGj7LTRoM35J=BSHQdFDT|kH{5$49Inl&24I`aruKHHae(Oae_vFH2{}Fe_0BBU z-9d_<)sI?Vzy^q=7kZm(QLpwzg0*NruSu5+_oTID#iqQ{bY3dRlfNYxq96Kt$%HKB zkj58&15+x9HwI#2Z#@-GYYP=FT3m~26xtpRkb1ruVO#|2>qWu2@_N4xJ*kWJ2^E;G zNViF9%ko{CwV<6P@sa1-SO=X(yR=_aC6UU#^D(;HE2R|WAk7>@N{Bb>8ONqd7zz5O z=BN!f?^c(}Jq;C6FAvx7f7Y5zqF&qDS4*zJAAgXNv%!CbxhP9rC2EfS=I(WqJM+WF zz9(v<@CVjuGdLZpvzH`G(Wq{^O34x?EEiB;yc7BgECFRGTXL}ka?Q;g`YT!gx;Ai3 z8Sni<_uvlq?mO@8a72qb1FNG>4j04rJ#~ z2bx68z%+;FEDd`Pv}h-HqUemE;3hXUn+wP4JlXJF1w^_uzJ zsAB?L(l%_KZIWQtJU~TkSO55fUFdgW%kdL-zMXBx#LFzmP?lRT8N!C=jOfY`7|5+V z$4N4;%d3Pr+?Xdns0Y1_3n5dRTXf6`pS_K9%*1N*(H{6jrGd@ijfO@ZvB zvU>hLVJ6POf;Yjm6FH&t4E{)T=xC$w20> zmG}yqZ*O^$AG{;QEKf<>Heyw{cQjjuS128O$ZrA~mI?2+TLq+-s@+0_!Jd6~qw4cO z*98;#HKf<6_?g41` z@*2B}6lMOEmKPav6W2R>QX7ivC_ibOLL5(IE>chrDOSq(b$asFTL+Ews<}+{jto;3 z_DbIwf2G(%uy=El>fInfhR~Vz1?|1SEx*qX*Y%?;c_nnWE|=&(&xF?kdS9T0LSX7q z@P%xpd2~DH_rTeH*zx28-W2g0*ZC5EKjoLR`$N?~a)e_8Nx-j}*Gd8_q8$ymYVgXq zjoqviIzp7(q^py;k95Jkh?65-ZF*SfSbk-=A?Ik{76+$OHk6#OK(^_QXprN&4#vez z;lT_=z&+us<os-lx~}db=uJEy}Q1#6uxuX zOiLnJdlMYLO-r)8QNBRvJ?#@UPOso{jF7T!+shJA?u?~U-7~fZ)4W-JhS8}+N%!@= z0ug7LO$1G|)6amtE#rEAxf_v66yL+44Y-=t^5IRcrE^(JM@Z3}9J;993=cN_`?RQI zCF$L(04OR2_$`ci5ivSs{)5I^#@ZuKO-6^VVjcb07Pb6e=3+%!Yx;H-Pg zS*vE!^v-~Z9UuD`)aTAFp=VJ4L$~kWlZJ=Yt^V@Rc9pf<1tcx{6&M^kQuer#ZPt53 zQ4w&oE$OPjR2C+@yIJ2{ano|_35NA+f5`sYWM1tTRD3^9yP|Ow2*!#&Wq_wWmlZ^- zAe23<3jEth4PXnq4i`vJY?1bwYK1vWcb=O7WFg1oB?OfLBIq}0*Mybil7v%x&KLp9 z6w0mxg5WT^Ys9hnC=*K6%Z<0avOZ0KeI-^f2X4Kx_w5bmU0I`rVf&(u$~BR^02XWYla)oKlKPF3U80YN)oKc6}P-&|2}g6 zKYU*QRidDutD>9`wEXIK=o87s;}5XU>jHsl1zA0pNoYPUZt5z^pP8Kq{EJC@4E`7Pd}&kyJ`+A^q)*G3EJ+fTHoFt)088fuv?2@3MfmfPV(b0fa2)iEjh1yZm&NS72dj+rK;ACU=d z&?B`hu^V?HmgxC{{siY70B%2!JX&Xty%{RH$YaCX;30YIWJ%j95Ns)NBR|5^# zHu`5{Qh6Ds$1|xK`>7LHe1o$ zgNx$PA$%_0xJ}@Vf^BG=5C098VTD`Z8BN&0TuVe!(G)oXS6;bePa6GOjQw{qbyHoM zqAGeryV>8uV}n;s7`R7wHV!XN9fGCtMJ8r5q!Akk_Iv5O0sgqHLRaySr zUubJ(<{Bt?vs(ed&GdX`8%-aRY#@?H`yDKqxuwAoTb&a5*U)F+9BtG%vvj^$wNgub z{~a^cbD)UC?iGN40X^TQVkKxzNhdK$6)8sUvN@jOD8_gH*Hfn3=q6oVps9w;K!O8t8grze?U4dRK z^<&~lz(%dMLVW53-b%-hN0Ru*(yzkNvsMo)qcFaD`5&E!fS`{f7*mT7?+aE=sbF;S z5syeg>X@*GBTzhd9p_WzH5=$j9zBG`F+r#$oTR<`Y1R@X1b}zMnI8P}dKeK&%NQ#7 zNHfPs$RHsu_`<&MgA395hz+NfAGoEiFwAM>8G05m*i6tF00r|Y!_%_Y#>sDj-4C?A*T*XHWTWj8(7_Mwd| zH@%}vI1XLHF)SCv?BS{Y;x1F>>xO6l;x5|-fI34KSmt2hj}BZpya)roD@lr(NAGw7 zpCpzpghs4+?}tan&U!6o)ck4rHPI-&y0N+%&Rc-T)(n>wc({~rTNZYsaitw2a9u%P zA!DdJzGbl7jJA&_l4CXc8!^+1)}az5^M~)eVfv36x`46kAW4Ghtz^7Z6>*8%hV}ai zy7QjtBD(QUc)iLNsl`jM5vKC!H+6InBmJ zh7n6)P>l>l`WBF%IfE{l!0g`Yxvs}yv@Nvi{vt3oSJ7oFdAGZnj>RY|y3x35Fjh>5 z(Rem(BSplaL>1VxkZFAtxkfL0$2V$Lg!Bwv4)(4rLQ4YsQWU_c{~2^y*m~?McI{+2 zUvKzUoT;75#?+Abs6TkKcJRA5P(rCvr;0P(W311LdKl!KZy;cyt~#xnSGe1KubMYNS z48u{w=OGcjyB`c^uURaJ6^~Joc=_YmWjVi}<1AH!fxA%2>R_Qsv=fS$AIW98_su9I zMlR_0%ZZAn->;UnUH-i_=f;TLt z`jYw8@C8PDj$SDdtZw|&G02Xx0ZIY2jo4{SViiYkZzgYy)RQZ!p_1}_M=gXB@LTWi z1Dd9)#3R1H9&n0_K;N#obos_phn-R9_mppehW;3s2g1rgvuP1F`FHU%o`LS5iW@>p zL-&B@_^o}W?%#JE2JyI#h1w_dXYYck)w9m7BIWvF7Y&e#%WRju-_u6`k2_N7^HTom zc7KQphxe$>)(6#tHPy)EUW@sZ{xm7Rs6k-P)Nr}IH5q9~T^PP*Xfb4E9HvWqu7+>- zdS8}es`NWHG?o95ZcQa|3uGa#TY;jR5lAvswh9J9wHc$3A+>r~O3+&71a*tO!5n^y zg`~ttAHVG!5shFnCH;1RMV89+DYc76=T9J~A+Hk|=C``dniz7yT=6%i%DdE)L;S?? zIQ-6sk8V|0vcWArqP78n`kEKwJs~?r2O=tKqd8?7@hmWc|4fpOdj5s$(6*ZMOJLHflj3RQE9h_l8V6bJ zqp3WXD(W|JUOaNEw|096Lx5pYY@#Ze&292~$f9vB6&aag-Z36pL}vY$0I@z$!dDLI z#k6Fhlp~f;Y}FDIwbw-Qoj5`woPoT3S4D=5kF+w8ZC*>b{9XT@WT0)|mJ)?B9IR9b z-t|M>-9);q8=?o&_+00%snVYVy;8N?zsyx9hV>_upO|IC4ERic8L zU>pJqbD16qc8jQZw3LraDzQ^Soh`PE{}A_S>*j>;8Nt{_mX`N_E{8^y1)hb2-#juS zd?kfN!Pr??uCw%&9fFnT7R(d~?y8IWALL{1djZL4y7}k3UP>TX$NNeGg>{3o4;cCm zUzXEHD^G+H5*IUtY{=o|LB!%k{nY(!Jth@DteTc8d|5ncj4y-C2^g9<JkM@&@re zx1t<^ZC;XYF`kz+<+Odd^$-0mR`2>Q!A#j6!aeR#!Fg@D1_r&h|!76v3|anx5#bYS>B3kpJ~A2WN->CyDKx8osP( z5_^tT3OzKY!i1d>D`4&w@dSi zbqquhXweGF=^8=O-tENGsr^~ZS6PG!`DrjbV_)%5rl;(IHnLQ9H2T+T@b>u8Ou6it zoSH2rXcNV#?%VB@1z!@^)Eu$KxZ>!f$KHZC0+*&KJy|QN=$_CakrWE~$|EZRU;esYC!9K|K{jcGX$GR9rrSTxt;RQzMa&s=}agdEfN# zyyhkPDhY|=iWj{v;Wls7_MY9#fy|w;?O9+%!?os)x#Q6nssPrg$;k{?@B`+nYZBya4W&PXkCAbL7|@pREQ>UPE!q zQ!x*BXeaa>!axEs)8Uy?e^Y{SP%rnSTlY2Q@%4uvKzCfhj+Ib3eP6c(H%KX3gf=kd z&8OW^vn~ATb|XD7le}xu=>~~(`6k>iPhi0QMeMK z_anm%RetbstZCH8dN!0k7o4AKcgE*c#xz2AGSjGRp?NT}Lsp= zKl0~Jyr&^{SRCh*Wq62YjOTwo^hze)d}law{^*N{AUmS!GWeNr4_<#Ou5rHm4>Uec zWcJvTYa0i)fAx*$07(`+ibq{$!;I?1OKljd*_!-R*Mw6T@XK{@$h%wJ$A)=AnV}Kj z?BZZz=o;B{Vk;x&SN)o+zKeeGhZ0|_n}b?X3B?5{$)$Yn zh5X1%Av?pl1^PAZc^S9LPHjTWoCoU~#LQ(l@6QOS684uu_Nwxo7e)&D6R7N9RG~%n zbVqh0x2{G%uZD zKkz~pf9`HL(g~*H$3b$$As zwl_{K{eTh4H{B`gNtY?H1p86gY0s}4)*^jpSMyy8t9vo2RlrMI69BSXc*>H9MA)%V zQ#w@*rS+@%ME!K>A^_H2@s7tUo=U2I2%0v3m-6aTw0HsuO3PG=sV8d*+_Hq~QUP6} zS<`Cj7Sxhmxj5;RanH4K8%SmBtpX(6TM`RA^CsUEtDt-7CG|6M| z>+V>AR&3~3qyUWSn)#}?Z2-tAcibj(n!uN)Hk_LS*If!qPBn#Y}zhbK-_N~kOFJpbkVT$D0u-`4Z_(&Tz40?k%DY3>9h_B}YiePQmbZLe# ztJ*QO@y}r*!?rc=MIVTmSg6lO6D(uyuag;3Qi%(RrH zsOLG%l&_W>G%M2$@z3bPI13z`)MsKsH8vQygvTqs#+hJl!jjd`RHK(Qr>-SU0TLh|F1 zbeGIrXNtyeeY&xt7#d1MN5WH-q5&%#Xw;e7z!JVCQWfG{}1;?SBs^pxSDr2ZuD~aLVtwR!FANnH>aHV^(dd+ylHn@pi(O0sL|tsyHMZM;q$h ztO4N|Zl92R^p%Pp!mk>YDRrrBVu=b9?G6-|-Ii5pQN|YC z^F@U|9$(o+8{;ldR{)Iv^*uP_ z6-{FR5M;P_pi1)YPf!K?WwZa!XD$a5%tC&f75dh2`b0xGTu zJKVP<(s5*`VIhO4IK*|VA>^_n#~s2o>V?p*up=Q>Ta|=wXnIx)W6 z{CTuI>dkQq4m4CGp0tYeYkAknqsBxo^p$;RK&l0x7r6BqFt434oy`XRHU*s`48Aqd-zu$ zmlfw4@_hmYLShCAe!wZ@K#Os=V3O5r&3%)hT`(u@GuIXP-R+L;*% z&pyFT@0fMG%Ho4KyuSaH!|P%9kLOgJ+$ls-1+<|x5)nA{{^Z=f?@lA2%^IQiTmJJ+ zFgn-F6BY=owqdC(X0&<+Gq=A=o<9&E8fMPQLz{(Gf+XrCLG~)y( zbtbI{2K=(Yw>BS;Q@OM+tUdq}D(eER7LP%Owt1(^D3~GjJsfE|u)o56P@Qqk&;34D z!@$d3`5tJ!ZZoGVD4@#NaLIGI0-=kZesg^vgCM8%5BWXjb}r|4K-Rm}S{WGB2Io82 zk|Y-~pAmdp;90PvOAl5~09_tq_(%8UjB$w)fAU_dUm-|w|Jem+Z|$mV5Zh|rnUil$ zM;Uy%uLM+|-%k^=p2w1dO;{^4$@mDEFP#4ye#wABCK$sl5PnIJ6i=v=U(e88Ty9C) z2SD|*i}kl3yB8&1Ar`|D#rqT(gS8DV97}}T7t#|Z2YmKHm}@^qqX{@A!x<~L`6+A! zq)1WD!vJz|k!lU=+D!m2p_fXZYUD>Ng{3}UCUWqTm#h%v|9G&u7=k+vn{@qymW zEIgLO?KcGF5U`FvYp+kx;iiVo40|EFtY&df@0JP7=VRbn?_)63TBNTTgaj0rSEpHg zW^B(%m|g{BBmv4=!0zvCP2Uf@AZcfQuA`9&`xc{<29ouWTPhE5CKwyY614d6vU~LQ z*_JN9#X@pcjkv!wnmnQ5&(D{4x|OQ{sY|aE(ZeIHb+txiNu3Qh@qxK;88E*zsoz1m z55}&QD1vJT z`Z+iOM1Rs9JHrc6a| zi>Kg5Z|J#}l0CBW*7N;zqn-@25KH`CKM|bYf|U22-UVY&sRU(j0Ok~9e-|T6#j5Vf z;dVv$p6A(o(YhrtFY>@ zJ2D#l^aSqxUy*~{6jE5-dk4TY90r^G!#F_V2*SL`WE2BH-F#p=X?dUSMv_R z)c@dP1;FnF_I%&@wH_q7$#E*uj%W3hZHpHPYW%{~DaSN5N==u6g+2~m%_`&A`UGO{ z6Dbb-R8re_q;at^-T)M6mS)D-#7R%T^v0$=rOGTzW+S~wCg-oAuXdu)U_W{~ycr`F zz`jAzAY521ktNLiDwSEBYZz4+DW$5$$MVmLF}ylYA8*&P=1=lofM6jXPnPJ{`11mqSXHLT7+(E&zSB3U@8t<@ zWnxgJbe%>XSiWj5DK%8wTg5qB_5(2eD8^H!47Y}+Kz(r5I#x;w`ampZh7k-JKfYei zeC!23F`G*t3yhe@bw5Jp(X00AC8cOxnh_Aexxi!JGEu7Do~%npL4}dYDiui)pD$FW zNg*PcC2JE@fy#22&uciJ!p37a2TXK9XS^-GYFS{S^3s0Qf)UAWPVwHZ9FKLwR(i%* zHbVK#`72} zy|us$>VpISNlf+GgJ*`@+TDD{Qi*KcF+Qa@LDGv%lHnv^S&h5m`G!nwlnaO+$CKH% z)nH^pp|)RRDNi{hRj%~BJUMg{w}*Y(@=WzL!fCKV#aJARzfvc6A-KZUykq|y&Axb*{h}!e~pu^^*-4(hKg4MWw34fyPqdL&L?*(`)kpd0sfwShe5! zX87nIX{>xC+rK>c(t@Z3b}#y%^KYsTDP8rB#ifaGpCLsP97PR8s>c_yR-JHn(=!L^ z>NIW3k$>%RvzC3n|47Fuh;$?s1w(Kc?qS0Ia&;N8azYtL%N`ft>L$22d{V&2UjY9B zSi|BwmF-!2M-ci65KZYq6gfm~M99i_tE9Vqjn7>CW^4M=#Kf5G`IpY&>azIloW(0) zazzoTm`j%LbHUVNP2Z>BAir$uI+vuqy}tuNL3ij^)>kLt)#} z(z%JURuPIbMxEob%%*MSjKyV^Hh+F(l?@V_9zKN0YCvq==Q=Tqz4FXkeDnWeHeS$T z4LqV7BY(l5p>#ouNXY*7Jf5^VqzZz5^J&0OzpjsYVXNH!021WXS3X;P+_wLY~ZLww$h9Teo z6LPSO@xMrMN7H`TKt5hYPKVRi1b)h6B4o2RSIa@%w88zwx8hRjTfn8R!>6NsO<}DK z#5=iZWH&G(9zW$aX3(k|MB_nr*0fj ziIt<}c;)64fKzO-zIpG)28fYeisTNyy>2^brc=cRB?SkL&HLH6A(IhW@-)C zdaxJQUI72{l9NV|A{ab(La1wZ6q=%~T{{5z?E~7utmKnYA$G#DdFwTRber~RJBHwr zln8RA5(n38^Ay;sHf3Mc(UR(QIqrpijmbjt_0G-To>zA^#SY&z0k(_`|KO#|6EWmj zqm`<(yr%WxCz;8=X{yA&fke|mSi#XmMJv*cH@a^R+D+4}Yw)?&aXn_OP z!f2nqH)lX>5<5MPhzD$wv@U66Ms2)4xWVc}3ajd`OZ8CFnI(yez0%OL=xh@0=?o8m zz+?W-6mv5Rjx-4Xo%pFW@EFw(og+`G7F$Dz zWRm#e8cc{c+8MG}R{OCPj{;`7@})bR`ITq+6&U-2$Cm7Ew5+$3-!m=_&vYf<*}N=Q z?^fAR`~v*^V*qc+KWM}NPyK>fV8i+65H6q)1eTGBNh_P9n=1{I4cG!EObHW;O(64< zUA_9{3!g}v!hY5l?t`t4d@d-=vcea0LLlO;WlK8*NzuM=9B?VeNujvHf36cLNF$iA z_=%GbFuMAW3(4PnMX*O=4B)h_1*`-$S=?R9Zw1c)`^!FA*bnHjEdOpgU-cY4uPs2b zuTkCd{EBM^1^}@^uw{7A70UDdOi!8f(uB%)}0@0oW)TB^n;?`W9XeQT0()GWa>9G~m7i zOEFM{GLfPCg>Ml)h`plY%fMxV#x9>t4#8T-Qe0jU0h14^M$lbV;Gy@cp!+T_R z@=(1D&-G`#Peh+kAbgoR`R;+Pwb4(V(~T?4`=&y2@L5e`dW9!2TDf+AAVOco=#sgm z5@Ao3R$3YPC~(-f^g2`sQfF<~bI&ejXLgj7MRnN4?7P6C(1UD#pF7Vb<|5>Yr91slSZR) z7Zw;hverP=$9LTvW~zvU6kh#6V{>D~xdO z4iBNM7(Bdg`2iT${aKrRftEg&k(kABbn4!zk4`ycLf!F8B5(VZLTp%mI6*?f$FcVl zyUE1$Nc8?+7q=!jXF%LAD`8Uq;@wAo?rL_D(PwD2!L{4yXY+i1h9fav!i+7o`=AHG zBnp;nf8Y7~vk#6dx0(`3K_11m^w@*3*N^?uN*!P2*=gS ziVZSPO>mZB`O^1*St0JJQi-RW7AdZh$4vKlxcWC&g)XuDfX;XH?tmq(ACO>b8N*gYY58GelZ97HR_hsZrg~7Q-UjVgoUN3%q7V=6AzR*a z@%gB@ne3HYHAO`?h@Q?HV%M;@I$5-ne*TPRMbiXPd_DrNtaaNYCrrN77w#_weN>K?7f$GxWS=l+Nmo(cM>`1Xv^?99StQ-iQv7cC(RSV} z!=ubzP*v~@{leM55bjfDSC-M=)%!vueP?9I{IOGK1zJ%mQGpDKeBRe~Wb&;+KvsqD1oDbHtAotU(!hlqazS0 z=?zhgGf(ej272N%nr zx`(iq$}f+Lejh7K+S~u#Y*Q??aKW&EIicHat~cezr2-4GvyMNzPrIG|aGk3n$2gb8 z?s42`=i=>6m10i4J(M?Oj8fhU+5eWiFA}igZ0{Nv6b^BV)Xf2kKX2vAcd&nklD!p~ z=y!`wpX=BaA00ic34GwqwbA~ zRtl(BT_0C$Mpw}RuZYl~$toBWo8UdTYM&yn?HE`Irg?91AMkabme14?TT;(!0&EdE zZ(k_ITTQF`pHimf+r@7h4aPK+PE@!|SAm%Tu74q=Xb6u4o9O;`C)HT(gq?Ed zEW)E+V2a}ERRo8%v@CzoUeGpx5J+Mcw=#z&1FnSFElGs2V5m$^4mab5D<-0+7d^J< zX=$IUC`EF3>zeQwzqzRKPJ0@wl>?MvXSQt+?I2YfitT8IntB$&CVF%I#o&T5T?Vj) ztbbiRH+s6OS%vPEj|sKi0U#3TmmZZLfSp8Z*pR>T`NYBg?>jr&3v0E&udH()j1W25 z;aBbpIR6Cgl#JBT71_~={T~zBZE~u)fPhS~`QrWV44%gYbIDelX5Ng3@}C#r6F67c zWw&d$Ljbw$nC<0&mW4JvrYz=qlWNe;I`T3#3?n7 zm@|gn{kkRZv=J%C(-K7Z=hN^N4FdCfz@rztoL1%C8sA=| zlI7LTnxDwR{SDHYAA?w}e3Qq13LDNo_RKR_O@yTR#aCX=Hj~D>uR$*iCy!evdFU}6 z8hKL{V^<5^Prw?7?zGreI310moTL`@MSPF96c6*L`$W=xkXcfe zB(Rf&5qU0CTYC;H5GN|>Ni9I7A&he$p8f-S0&S|}wshICy}4unDx zJ${Y7%^+hstu0>eylVfj!bDvJyN7dc8s-&#K^P+vf?gy{qT|qXA+5xvs zt8)NER2qt=!RMX#y+n|4-8g%%PVi3j&t$^%G)}=qvX^^L-UCz~2MC9cKzJ4@5{Gx^ z0uFkO-Gf#}BWj0O60M{QH{V0#%?xSv2k?E|Y3YI&DCOvqoK6(KBqT@VoVkxFXxiVX zqIiS93!o&YpVcmPG~SSh22`m9e*Xai2^gs9ORaF`!gfwStHV34Qw}9nHoWm#74&*q z-SD#$YE7kQe?4AKQWl#bp66I*6LzTXeI%L+7_z!Y%l%kFm-_K{zdbHgsvPn)v+yIp z>7}2<#(!7lhru5Z#p1LNt-W&n+fY${3KZ-$NX-CCfJ)1#@CjPW_n$yP zuZ;autS41kdca6YCeb7}3T>@7Qg@YyN>i?x{=zd*x}1J>2RK@rk#@jZ_?F#F^`bk# zXQP;lMgQ}awPpPm2)@f<>Q9e2*4K!xE=VLAeY|Y3z!|KqMn9#=^Yxd{L&Y_YamTqW zz`VYC0oEvu@JZ^E$*bDUJz?E%6-$Wcp{CD{isUrM!a19R4I2$k23NB z7gpdIm`g4c^l*IzB(cMfjFlPnQy6=6MCx3^PFK7dkT9%Rv{Y|9b=n-Buc=;2m5lah4O z=YqMyTSPL@id0p6sMUE+$9nUPR}4Py)uj>8{ot|~ZpB$fUSeep?@|(11sfjTb zFFaW-vS{=HrgcnVbxw39_9Ko+Sv~#y(Jz^$4Ug1GmLXoDC|=_Z%R>u4RMT(wKe#QPX6K$XGSZ;e2;A6xHw2Yid#? zVHIBYFHPR@t|@<16ZXp>LskTad63aa5Fl*N$R!pEhDaO%v4>)S;M6t-7Q}GlsuyW7 z_N&O5VNYAr<$@TrjKVU<9l`Nv#_vA@w;O+E?W9v#!QPOwUmq|oid!>sncU*lfYF+& zJG0Ann?6@-dq^S>bEX?Ciq=nyvNe5g2`Xr+ZGqe6T5mRQ8FgYR~GmagRA2zh|gN+ z+JsFv4Z`KaIpG>^mCN|0E{@65br{q0=BdFt??xot#h;1%btc|U{*TT?O^S@zxQ%V}_iC;^QeFQ)Y&B zqdZ0fYdOUdBQ?E}g~G;#Nsy|jqT2nqGJ%`r7PGbc?VY(oBtQOw%#Z%cv*t&e0{$2T zG7khX7gO#&tRE6dp674Xzk1>-j*3E|3SQ+X7@`eJ+hxvoft*TziO$cSoO2xiyl_w` zhK}#Oe;I&wET{h3AI-(<&L0t(7k)!J`Ogorhs$__M_v%3~ff4CuE>7U5I>aMBLLjA>){Pj{<`v3@>hqiHJ7^diMm+(0H$ zNj~T{6qV1JODoIlGE2hQRFRy0zb5>tJkYyV^4U()x{A>^KbaJUZqyyIZ{^+T3|~?5 zpOzWgi+M8+>OW;nmYCE@zt^xh)W2zH?j^mbqPa2pWAD}_RX2$oMa!cb{Ro1q2cXf{ zrr2Tz{iv|6W~d)UT8mFm5=F84d<9h9ED~{ehNLWtjzqc6#C9^ej4T#90uJH+&^yqx z`qM?$rE;gJ(`V45h_g`J2uKwl1b14IGLU;w4idlD;sywsbB!n-x^^HXsggeIrJ`N` z@@U5&LHFbmB$Iyx8Px)#q^H?nkixw)B=5c-K+_OFX{X1NxAMEzGP{5o<@`y{{RA*c zQARay8FjJ4SMU049YOA&>Y&L?H5_L=-q}bt78yQ$@$&$S@qPLrE%>P!EeWPQE0Yl{ z=HfETtLyHdwthj`8xVM!e7)D8*#U{H{2ddBI3V=O2Bc&Gk$e&%6NHt0QJA*iF*UyP z(F%~3gFdrh0(Q*e)r6Ifeu3ttiYb;L2RLPd+!THSwO#o%t-f#@sD!N(z-BQ&ayh&P zM@$KpN5I_15DZ@Um{Q@0LL_3YxTU5?k!d!f=9Aj~?$AM=zw zEx`_7`CXjfQw+WYbUQcAgaKBD?Uu;=zX0M{Xj25`5p1%-lP7ITg=sRbd0W3?n$Pn9 znV-qV#oJYS#qv`STiUpCusg5HO)L2lK(DtVv!$-QU6d8<*th9(3VbA4u6>QmOS({5 zS%gfFmk!t|5|qIS|Lx$0OrH{OYm$x$jvZ=+QzKCr$T0WrmYdV`ERQtSPaQB%2|%8Y z;{+RD^(h(!#eT`WanD~#cR>R^GAn?Jd1DeB<4-b>aFe$ACz3L~O;n-Lrhjne*?V4H z?v}jj(&^X@CY5kfXZvW-T&pI@j9UU}Ttd_CtVBmv{YTfw=CLZ$PcF18`~jSWnJj;{ zl$|!*ps=J#VzlG`fxqscO%%xwacy63^gd|@RCXEApe33f^UQ-v*|J6Ui?cE`5!@E_M6Oo1C3bfB|RXin8L>^WDWYzd8O!Jur!X?IL#g z*{AL(IwCkqvG-U^L|XsAgy$(?sL`wXhd9^Rlvx2=&r z8{(v)Ky}!KbuHH!4%QQTS2=vwfY{GDbpZLuZKH7*emLhQ7zjeDsCHfW5&(ugWy>cY z+-1oIb-OFClnD7hQ~XsyRBYssstrZJHRm87`Z78O*ULjA=@So8!}%|Gun>0;SXFA9 za%R!8Hb)-hVXl=Y#Q@xOy~%EZ0Kw;?SFb>bl*D+=v+)(f&yF7E1_P{d@ME2W2|d>u z^y`J@7$35u9p?nJ5`~0-CKFVlc7dwUd-hcz=AY{%5o&l3(l~FsCV-{_#Q1J0_4kb{ zzt3{htEmUfgBBg1sc;WUZoB2CKklXCKrS%?+GXqR_Szi|Z_(pIxs)&208GQRVkk;U z+Hg9QC&W-RB^*hgfL}BW?Uj)vR0hXtxJc8jiMCHZiVX84vKw2z6nq3DDdBjgi}uj) z?4bcziUFPF-NB1OP@vvI?XfoXXSXj1bm(+u+LaqcT~@B^ZNw#iI7j-9EwTPfVMLjU z?)7XU+8M!V+p^ewAaVno-(e=A{G{oCpOz(Mt*+&MlGmChqyYy}^+ni31TE1E*@iwUpBPwXW8@#&*sw;=p9>KPHncO z&r{!dYokk3^1+E(Pdb--_bbJ_>$Fpo20`gUp>MubiplBHkmBU~40p2lm%IyiOF_xb+i_*>}rsQ6h zSHIV&P%KYSyJXv8$s>ngZjA@N0`3>$xDuXdtDQ zV-z)qC9O>AoGC;x?Iv1iKL3h~$~1bAG3Ya~=u!N?XirF5rG6i6#o|>(2y?qeBno*< zy&@|)?|Gh}V8U?KmBVU+zOOC+;ir7byN&GI91MMm9r3#H1JZpWk-4b1`E$QA8Kpt5 z5D-0lW^#~1y0QK#jkNxXbG`R;5V*@2_eB)AHD9QC`66}9tw1A^h`$Pv#7*rPfm1brCD&CD*9`wSLn ztyti**piFukan<>*X-#;bfUyU7c#U8aeLeT%7I2IDI3^Z@FoxvBjZ6~W%4fTm~oE- zk>D}&KtvbtmH%Il&mmQ;GS$L5zwmfVAVjSa)?w^UJrYLs=9~D)b79UbGmjC)p;gtH z0MEH_V@_aTR}+Uvf&!)nhXxLgn^Y%+Qs1KVr0y#bs`+$JIDJq=$Y0=}IU&OP)j-(+ zC;DbZ8yy#YlLw}ceVHh(8P0@-iX2Ul1{|)G%OLDO&BM;{Bk4HqBJBe?9{o0v5(Ncr z{Y#*kBrUS0^GS+LVduSuOqoNRepNI?tCOpUx(OloXX^YDc+;f`W_#bfLUK&e3!XDD z^3b`!N=hv@TsGxP#&)6Q2$W8ehUn~X0%R8S1*R`JUfzgN zDx3r$9?W@Xh| zlNMC@yvwC05j@axwzTAxL_o+J)r+po-E}`&C4@Brd5!lR_U;D1aR70MyuqR82oKIu z1K=*<#Gdocfb`*szqnoTd5=%@(VzE)V0l%pKH+Q;Dy`c}putMSA+>d&(uhdrE+ESHetW`<7IqSs^dIn$6Rk#b$60(FT40#zp4G2 z4(R56`L2md!?@id!9b{dz4zOd7z>sA-b9TnWUPe7-j9IU`SRJ?tU4(3G4P zJ+jHfLBjrD4Bj=3e$=;Z>TTg-6G0T-u*xzP2$l;oaWpqdzP3?jsgeEGwzYKY*CV&(*1GfKY90xRtLi5>=x+P z0O6{6_1K=xf0y~x^gS79F8S>E6XpJ>J=vW%9moW#V69<9TS1?A#=Dq_B^LEsG z7kdn9wOUc3FWPeh9(u0J<=wQx_X7s;%VL^c0>Ok)tQb)(w^(1>cIvVw-vF4ilm7x( z{0k0Zw!g*WJ*cij)^LY}b71g@`sV?wWFDQ_gZR10=a8FZco=NN&-%9)H?X;MyQNA| z5uwM~98MK!uN(_@rB(%=V}cj&nw$b|;0?3@&l z&Qo~vH%l}N;Iw}8{|2YUT6`b)-aj}2(Zec? zFX~pi#mvB&i?Zf5>paq@KykL#v6o7E9e`fgPI;mscyj+HE+#Nkyj)PBwoYNaELij$Vm-o1lvkk|is;md3|h zL{AX4Eh5+}RvKOl0A1i~8ocn>f*4t)pTGqBGyQ%<8rx;d37~mcfwo3m|2Gl*Osy|p zyr)hl&?9}LPGC!9>l&CH48jb1)sqwpE56u~S8L&bK|KC0OdODKdqSdF7Vqj@h6_Z5 zWg_-gg8sNKThaA>`{;EAfn6(-2ol+}TbXJbdG0k`_FvWNH|nD?@@SxSVCqYc8!G7a z9y|W-?LS+(JX8bu<)#s61v*t?9OO0r>az~$R+qAby45E)BC_~;6h1*skTc!4-x-dm zQGwi1p;jkC$HIIB^bD{~Vt`)nb~8lB8qPfZQ2GtW1~{iGsuL7iOpp;)B4VdIWGAOO_}+7WqWtZ^%3mPVNS#+~f-ukoB{>|DU?fJD$q_{o^HZ?4xXwQC6}KP6)>q z;#fr}LfI>27LHLFhis?paqLL4XI566NW&;Al ztB0*lpkZxNwv&Dz*7Ofao%&2*EuCq#$9)V8v{ju_IS^~8llAUDp7Ms2HDOuIrl+ho zQ`{7o1yqsn0agC-ckZq8A?kXZb5-01%+Bk6(=*NQFvhNJ(Z~s7Kfh6*P+B(P#%g#K z(0LT8G1ErQ)Z!d${89aw>`$Gl;^@J9>~$^GEa!$(2pxuJ4xLOZ@4$ZJr)_M?@?(K; zY(rTBGzG>iaEdjb`n?m&uOGOe13Gu=?7+x$u@5pbxz~k*{c!Up21j;Unb1A#&v-iY zhiwVJVKAZbWrotlyOHTXveDw(f7E^_yMimo^JRf)yGC}7=|i5GxZ^e`m`EIGkU^f9WxW_I75`&cy~gnSQjO!*=(#VOQc+TjTC+Yqc5lV ziaLg4w|MgNDuSk+gXN-ec75@-?>YVHpuc*JnxEbR^rLJ7FyM30N%F*AfAp$?+)#;V z>ia^~%q!Z+(9g*S3hEJ7py9CCk)6@n_zb0l9|4oF0!VA?LdWc*ts;;W5)&pJzn8tq z1ehXfPRyB>{g9E%l2a-1ZcH-glLU)@SeSmtOfrBOI(dj0%7QRMe9^Z^r+n)Wx%brf zbACLc5Z0m+RV3N&!rxc6)6}8LHCe94^7cxQ8ogs~hm=M|5b^s_i!=4;vU~W{M_nH* ztm-@+gZm5CmJ!Ctkir{5wJG4%^BGRBv5Iq2?oG}kCvaml`I3>{FJ+`~j(02#SSGyG z8M-l=aX;z!MaF=A2hl+jOirt0$I{a$d;3;%AImwlIR2UFui{K-B{C(piwmZyZk#T|^D_{XB4jr$G&wH{CjP{H$JQ~z_EI!Y} zO~wGzo3;I&5Rj?V@95RoKozLj%-oPG&_B=jPSze5MpptGb&aS=@vCXZ7M|`jg;1kwUyxzN0l`>Nj1?@Jr0WjSzjPY;x<-hd$}1(Mcbl1`xOD zm$A+KgWF*aAfw2{g2(x6ICeYP_)nqQSp5F5bztv4zN>sM{uXDX)Qrg{9nq6_dQJw` znH+jKY?+Tv&ZNfZMP}j};akxU1C%TX7CgpJ~k@#i$S_m=KSI-*r4l* z`daDi(9O`e@0=t@yPkZ(G!(KD{6eU<}Zr?s)BsCT%%0dDM@PBR-4)H{L zCiMVMv@xDbo-9_E@BK@;BqkpHF=hf0zY9Tutb>vStlcDbZ_y(R`&ZF=OAFPNsl6&i(|297O^p}Y3WyGlZ_u*=?sY3rD?V4!!f4(Yd z$QrYTN`j!|)6D?@A6a!Lr|&6S1Q1^HX|i*Rb`f!3T$YZ#J-vB}sz{G=2HUShG2lXk}j1d>j;RVvw&m)sT>UT5F4F@x&TL2RY%-e`)1r6Fstj_buT=0@w|>S`v0U0c_b{n0y_m<@on)S zVCud>*A);Z8(6EWyZUehc-6V^W-A(X4hC&83&rx?WW2c2?r+5aj5w>3p$C}4u|Yg_ z)-Im^XaT_RdM;A*t0Ksd$y|N%Q9(ar7eXrDTkpt|?|70EHIy%E`ztDglUH!n_T$)T zy}{vWu;fR`LpSvBkHcPZcCX}oJS!k>(|L9)E*9^xS*y%+YyP-}vFUWcPLXvML*86e02aw-M`hBd!TVWQTD~v=TSb`(qSSr>^oVuK&)&l_?p_!}qi6rp{ zRIZ<{=M)q2ur~F{_5uQFvK8hiJYh1zj_;5H)wP*9QKMm}+9EW?c3ky*2{{H7%_iuU z0w))ej((0jcNLV-WTbKWms-h0)0%5R?&c?pgY9A6Thec!VkI9jbb}kW4pMRR`X0pn zEzbbolSB<&V9wT*u0}*iM8r^f`Xo4y7ErTQQ5Akd=PJF@sp~HnhQUCI!~R;l;8UG- zbymwIpur_cmjQ#$AQ&Fz2~g{X5W&~Bp4nfWc*Y!-XoF)xlbb3r%}?0U(P-;L^F@g6 zv7IdEjhH5F0W3N`)FS5HeQ&Q3>jV|?LCc2C_rhEr*Odl=&r6hj~K= znjkVDxC8WO#fRS0WLWh zC7VH5jU{p7`A*){@X|6+cFWQrC$ZAh%sYUe#d0^cIq;3>mNshq*)n0)I5at^gTtSY z2i7$qb+Rdy#I#h=XVhHtwZVi<)3Fq{BIGo1(*tkI2A-1>%r^g@@^AXG9J=N8bfb66 z0oc`rHb1GQTj3c^@jCa50<2#bm7Ky?0NFoV_k>%3h-=!#H;}egF=z6AAy^&cltBA~ zo;D^J#=#y-?Ow!6n)1UPvdQ;(mjrD;DTJ2vGqbdXV7qi>pTUmjTR|SV0ka)7n%f~V zA5G54VGeOd`!5BAnNi_<{8(M}2oz28faXV7 zyKW6&Jos(II2~4iPRY)^(=nRbyt+N2$G@g(hGP|KnY2zrk+2~BoC@+Ccm`G zru4m^t!z}Qte%>>e$9Ooy2_0p6I2E0QIp~oJ=lShRX5_W6)^|pMom*JZDnve3qcA}~kic>A852xO>0O~Ij8(-F2s|l$F{y|anu#x&65lsN0N(zYfV@u7f3FL8_ zfpH6sc5ssuNbguQw;0I3XcTI)Fz=yxyxF3Ox_Z`Ad9OdUEyb7YmjSyD!VQeD#Ne^2 z!9;UuZh80%&E>Vf9{T^p7aCEDM&~WwGI$EcPRKLE{31O=0VfVsF$IDB94fd6^fiTM zODB|7oSrUW21F= z&vhp_LWA$6h$yixQ)*1_*v{xiMn`~O*7|0l-dcI!Wy=g=2?s-OtFZ7rp-+92mYrt# z#_~$kFHL9JDK`MbqQeyJ!Uf=uhbc8w>$Trk>wrf0KV*-fL`zo;kBvpaP<235ttSUW z=-Q+z9@s|ofY&|od;7nex=X_Ogu^lp@i#AVmXR-EZ;qW#Z!HXvw~t5C54pjiniiw5 z)k{Cyjn8ZvdSuqZ5NC&my7{DHFH{NE5A(Aw>~`l$j2Uzmz6v7XtES&U?yEzMsHge$ ze;^}`d0xl)1Ip0hYZTY;xdSoT;oE(w0?BCKOQ}Jmq6xJ_p=-!N z{s-}Y$nkuT72f!JzQnEFnueX4xv0mxR;x~WQw53nmfP)oA8J9RAHkVl6BiK6RQ`2u%S5g=Els=QG1GdZ+4oj9~Ox$9^K`tyU# z_lPZ5Bg6*-vv8$If&|O;7wUC)d9J@=d%CfmdCPOeT29VN;+x>l{Xsx9UoA=JN-Xe_ zskBLDbCEM#y}9HUA<-Ve%D56uaQ0I-ehiE{vi>_?$Bcl^)ua2mFgq0jv3|ErnM9%l zlf*7{u)lb~E-wSQoAd?ZtC9*-U#X|bXG?fk%v6km3;5;D_=pcu~ z*(KX-50*sj52ami(huMn%LjX#GU&wh2iO0OXWn3>wH+P^h%0MpxI zkhXW$FMQl+`@8Og|-uJ>l*U^n&Pg=UYNcLPY{k{n70z>@zI zZ>@lkA0*4Qxho~O*QH{;Sx(Dr*Lw5%FHr9RQUY9g0;qoNF(_AM=Im)8PYk!>m(+yW z1H{G!USoAe(0!2wxn`()SRNhW_U}kMDlE_n&Kz0RM~jGSGPsl}am%gq;wOk)OC>~G z1}Pzsi21u$Ye3;8KqU)8CVO~TCze3R4iBZyWR6@A3q0YnjAs&gv_4{+*~B|g3Cy;0 z;BKjem2X8=NVI}_k%p4%t~u#B4_!F2*SFj+?FYx@*yPdq!q8MbS&3^Z8JJTh;zTyi ztUWZ6P{Q~4Q#L!HXYk@T1DbNf%(&pj%fNc;4REVUJps<&!|$XXm59Y>IUQh28x040 zpVf#76+x4E-EV=)M)~|XX=LtR6_|owqLMRobO)J(BgeH@ zpi@2u(VCxt&+Swas3U}76f3Ii8vN5mvT8;*t#my3ZNqW8meT3j$SFXwVa$)j;zz+q zN2Coz=bCzzLzE@~T-_F!0bF;wGnpfOy7cLRZ-2OG*{ge{tEwoeJhIfGerx)Z2JcHc`JID`hn4B^aZ{{~m32%=Y;xTB3_Y?B zinwG-ME+}nM3I4@TI)8vH&iP^P~6^E_!NatW%$l+q12GFK80N6sbeD;!$mrv; zV)(Vxo?cy@d3fMO?GtI6T0V{Q>mBh)ohM=L8?l$4_bLXVaewU1HYik1h2S2JL3N>z z{cv&7YtomMsetjbJ&b%w=&&%UbTWHM(FEDYE)_cT@4`O=Gf!@$Qrqq6hja{C5qbkG z{^fgkJ$E>BYZObi8Z{c__1gKWRWX^*Ol<^Va|7%%URB$i`{@nC-%OIK#3qAJ~Rc6GCfMkm-FWTP5p!(2Wm^*IA=X7YJ!CYe+R~do~6!qo&RP^nxYN7;^#*zF$1luYKwf)qL^k&@+lT!Bzl2)EXKMI4K(qFtUw7zHW&*8TO5QT}gw z`3s-AUG&w;OU9N!&LeuB;qGt2{jP-=O3aLI=${e0^KQdl2mS zy}F_jr&2m4ZS zn(aR*Ty70SlFY-3{gWbfQDQ>U5=4!S<2ATpW2amLLRW3A1LK-Eo>)By#Na9|T1 z1-8M;oQ^a7?my*iHzstAEZRP@`Y#_Q&^tI*<4b~RCVA3d8RW&@r?Ie>vrat3aDUWi zzB2{JB|^C1)SkCAFw&{ny~W1|&xgR5(NVxGA%B`>+|F-ZpPeE+PxW#MNm8tm(o@!0 z{Xrp3$b02arIjS-(z7{o3nSWm(kOzE=c%faxtvHE=nmxkA%w#I9W!<9=02m@>{M&g z0B{``2@z5FZMxs4Wpo}uZW;su9iH+2^GV;QGf=?q)F*%ePW`2kW!oH_$6#=_!8uDc z5*C`8*|)9HleSbXfI$6>Wl>d~EaNzhvm#p(k7luZvX-aH<5kaW$)#tpEMthu!(ox+ z-42g9PJnRfl3Vn5n`Ncv1w5N{mrl6Hm|DtCJPfx~(a6AbUPdbiWN?N~DV^Weo%-JG zX`VF;q>77vphHniZs(Iv;CK==%_|j_d?8jRF|o7?LQe;;oMybGo1Zct@a5;jp!`&X z1MLf_5DzZWbf%1U{r+ao)~$L{Xl(N{T$E0pQFXeY7!B| z(6a4Y^@sjjJ%6?FJguaXnFpJB zemWpqfn%eB4{^=)$|1)H3Ze$$G@9mjI! zsSqxn1Zz=^Vc!|sKSf(Pnl^h#_2*A*+o*}EN`eWKCD5G=Iz3E8UYmWj6U#mrJv~Je zMCtol2~1O`4{c=5v&4O5k?gv|487Aux@+dxZ>jIgwz_G4#rzeH)rq_&2ot0~JeJ_6 ziujeIPuCd6fek$fb5PEqB@S%thj;j0&a%13s82#pbojoP6gX%OmOkfpi-A}F1DmX8 zKo9QObw(e5C|a1{aEnE~rhP0--LT)_7kb}VUt{V~oGQb1HhEINz^95tjJIK-}XL`8QS25W;-&pUR>Zlzmy{zPwTa8$sF18nAR4ZyTc_aac@SJEpx2;A1mH} zi$~vhyfPqHH$FMbm)T?BKPVH%FEsv5pyzT(j}eo?S;J3r3}wad6W!Zzg2eIj^^%%= zIol(Azg4HtfHMb&5j~FtxBdpP8e8Ch>7UM^EJJs)IEd95NfgEUxB>tO{aAo9U|ZR{fr=~hhtb-cP&g0HS0q=Bu;mW(s6&*t>=>} z+I-^nal2ZYG}D072iV6)oP5$gW_uyf6bZmJUhMt--YsvS7dAd%+xf#H4Q9!9#oAi~ zsj3Yutt-H_%U_nyWfGhGEsWu8fY3(8d)WiN@N;N!@)|7i_#%zr?4O#DXT{TQU!>Ej zeDsX`L9lxfMXiAOA+)o+6^JWK3=-SfeF`_gt+57YV)yjV;^?S*KjbT89{%3kmy8~y zzVaiC8!~`~g8m4%ckAZ$_repVI2WdSvte1TpGk|TmL|rz;bAY?rEq%?NcL0S;5+qm z1A`)^?01#;ZRbC7ln1Bk$zi2hpKZH?vYY|`v2;+D8Z_VXlXDhUNw5A5;L<8OA0CpU ze%cbF1&N7kCU(H(RsRsMni#7H9m|F#-iE)e8#qO}MCYFZuXttc)aC5e&EfiH5+n85 z$a69|>QDlN8GwdTsFc

        @6}jxfWpvf+MM$&t&zW%jVSC|8dz+dT)+_%uR@lk{20Q z0HSW3_oHKNpv=byl`}U|fz?i5vk`>3==F*b4JK=Hoi{j_uk1d1F0`A;RyS|R1FgiI zb_UWpXXofDglO2kbsjT!SEj=S>Gu_WP4=ig|3*@07m%WFPNj`3`ft>5oe%2)yjzwR+zO6JH4=L%8)6U)1= z0B{QZ5YBR%8Oy2qpp1R)qrRT+Ouv4PI&wOimk!XNy>muRmY@ zOW-u=tyu!d6s=%=12q2D(I?VP!~vNyXlhwEMj|aMM&jo!ZW?u?@;lh%_{U;{Uw~+m zVJ|D^<<})>^Ac={w7G&;M6tY{H?|{*W|^b=p<-wWp!vT*3;-TB8X+}$11Ynv%&q68 zW*~Z@uqoMO$@WSAV4|ZpEoV*$bnv*7?jFz7U*~LX`^*Ue`hX$%XHVs_vIT zZJLQ(ndlM7vUzmFChMp=WjaM%ExT(A5@cPyIOMlFuM50+CguXLS%x>xIqR#!R}{UR$b*&L=pLo#tM(Q z0{)2TS?@=HFC6a%&K;!_wUz99=-io`=i);N9)bL%$E!gWM`?ekd>rP*Vo_bGNV;}& zJtovO1UWd`{h>gQN(;t#R$vWml4HgFL4um0Ftb1u{PJYj*>FKlz990`tBWV;12kV- ze~3qu;Km*;U*C3Q(u`Q6Hc6>HOa5%mvbiJ=t$xaltcVwazW=& zLdA#SEfCLUGO48VJn$r{)mQab%s9l{V-(ffd}0}RgX3{WXWE=Cm5jW?f=lsWHRV=j|cXX$-wqA8c};G2L@8pY#mFg6YYXWM!n9aGy^^ilm}NG2^Ez0~LDkV6 zpuoQ0(x5y!2%}0V+L{*W)f645oCfGO{wa07AD_(FWUSc;3 z3OsY}Ji?vosHowDY96=(?hY*7y}7A=t;qRuFPV4UDC8&>fTF2K&N}h3ISTEJ^!Xcc zx)iak+-jd$;Sg~;tbfFvh8?C^kID-QWl$cSCQ2*;l{4g72j!8t8>2N3-O@9UFkdo9NIxdZynI)oX_&!}V?vWO^pyu0sb624;7J*9NJ z>W}@0${&oW$WMK$_oc)Vj?a+?^ov7I9#v1xc*E^2=f^vy5&V@(LLE}|OA(_0UT=O8 zw}w~roqWCkkcdh$8)!<2mmnf`dqEb=JnD>Vf6ya>vo9dFTfYH($|p4&EPwW1u&{5s zrtC(_E7bb6B!@bWY5TVR@@cTf{K9|EF^;lHTL7TMyt08_KVV|)-Jm-Kf(G3pcR|JE z@kq_B5&UGLahq^n5ca7oB5rVWWrSZPGGpH_M~uBeY17vQ%oOI=uKhfJ@NPRUuOr)D zZaG8vxoYf{ulf|L!XK|q8#inluElJ9ZofLT103!(thbX@yg&Gl2av`q3DNF@4w3WA zmMv;v+0|@S;{yAN1A~g!QneFQb)bb&@(|1$2wQ7{9-N@Qpui9WA$|#Af~2%dszZV8%K<7qSl(chHFL<4=CL% zwL7rp3Lwf5IS=u~?NDFBQv4O5Q9^#DP6Jx}UaIPWFhcy>S>oz%!|QizU1cS+Y}g)N zcBel2)p>Cr6>%SLEo(b_>n}nwfRIQ6eeVJg<3r>DdXFdw7ms;jDSU?GfM#gmD-WUKO|NNqE$Oi*UyW za;zapR2V=!hk(Rch{p0^M2#JO(q3(7A9#-#Pby_dFGLV-0Vj{4;{x!J2omL_-;>8L zy{uvoIdOu_T|-&Xz^4~kwgjLAZ#q(t-1i}gq5ZiwH71E(%&C~a)x&kgVJTkds}gO> z%2+-sA$|wY!o5xVJm(omh-m?oGNaFsr7L&}n%O4mUBmr6xA;hH&s@B3|F5_-*RyFG zwjKi->G3Dc#HtV-fwmU>@7yjER{dbfob)-cwKPlQtly)OE;>bv{uq%&x)9y!Umj1z zDrumkZ$ml1>emV*X=Z#mh#=WfwHuecmpZ*i8Y>)mfe0*~+{h(P9k6(Y-L}a)UOfGX zN#u6X^e&Hs8uM~ zq^XlcdsqLac~bYTK_UdhKqls8&(Rd0-q%tGzp3QfZ$y%`GcJjc_R84SesJw*E;g&t zylJT(zNL2q%hG#L{a}7hoLXubL=)}i(DBYuudHm%q{@Q|T*l2Fdy+iLrPLp7^&7XB zP`{d;ohE(${b|><&$0m6h4=%otfOD6+->>cT6sf2uWNLHm|2VzO8AM(C(dQ?Zddt5qAcX;p?6`2dAqTFqf*?p;7A>+ezAJWnWYCNH31uHv6nLZ<61G zt1FW;OR5}MJRmu3hrD+o2-;mL-j1T31>J#5yWu~>2riz;u2{O>4X7HP%w{g*@YVcm zz>SDdfaS6n&^3OJrHFKgT84&?;-$86PUN)WlI`)_mlk>waW}JaKDfeKXRdBkq0RU> z=q}8W%&_6p8{c@nO{JyKR7^Q_aSCX7{Xr#pThHLaIW0;Hi(F&KWMI!-rH9Z zDr{k6Lf^d{c88ma#n}n8)UM9=c_~g7o{XNQnHMWwq)EUv<&63g*unZh)B)Nu8#;Lq$`jQ6V69E6{`Go1iWfr- zG8i@W^j#JLMARmnA_yG)LF@OU4qTRlqgB&B_&H`VieNfb@XSPE%v?u{T^s3fHEMb} z_ZzDhl9521u1kph1riveSyJ^}FaoaKJ3T4B&OeYn%aQ=+(s2^4bQqFf(vT0mA}$Xk)(H} z%@2{~yaxfirn)#94JvHRfQZuYMUe1C60(ebUAsv^Gcfc(u&K1Y(u-!nr%O|R$z9rd z-lJ8+(GRRm);QOzJXtolhr;e)?S~3-IqnCnauM=7n5a}km z3X>7KuC->2IRG-OgAD}pzoMAGb&j^93;Gi93+Sx$5;NY}~Y~W8#Y2`QHns zDt{!>#8&Qw#Z^(E?eerc0(R-WgqC&lE`z3<{m*`V7Cr@DoD0g2F+ew5VW0Zq`$W2U zA{@gVHDxcrLk1B=g%CYT&mjIahXL5?N3rh2ucK0%XW|d~b#mHyul($0HPvFr! zwb3k0R9|xC_FFm`Rav0jeYANaoCmDq#Bg!t<8_+`>Ngg^L*D74`B;|)B%McZRSBZ} z_|6~p8*TCgcwXbkw0|_Z`3JLhBGZ>aUTv&fe)PqyE8%ApJEQGU6XSx{2#cCV)$Hwf zMzM>rUA1&l@PStTjYX{q+b{;T(Q2^&9y8%agb3U*+tZAw;IM5|{l-VF9^!i*c?A~n zfXg4Z0eaa#KIW(Dy~g-(`gfeQ%&ES0iLU=J=7$%6=atIfXJ%BGrj_h4ANXya2mQ^6!BXF3H1gIp6A{IWK{;H z5>E(`*f5r7eRKWi3S&x=r{eAOjS8U|rZp>+ovL4`Si|w{S^#wUXy|*RS;K>(JoMh? zi9L7hP`O0O*`Oi)8F)R!X6{ELyCUH4ZoqHw9Tmx_l5}7B1HTLk@8oJa5du)kSSO4a8U)JP7s zQL)MNE=jgek2;S1QJ|u(Vh1miC~^3zNpI}0%#$7c#E{@saN+gx|@%-p3!En)ubbjpWhdmoy}~&E~0 z@br=M7!EloLVC^n)~7BKLkBu~^6|zU>lbjz8SJfHk;j5t5&U=|JyR8|MVaK^MCx?-~RTW6q$Ga_P77-KZ8HwKm6}t%lyy( z=fC{zZ~s@l3E?(eWz!db`#Z}0_37^jR8Q;nca;A-f(U()ZOb%*k6`;Ss$%@_C(@^<>HFmGh=~6a0;l>vLKyx#%7RZ? zGwv7oe^JDLC9wY!d}4mTz6gr+(`;{hl>8@3yoY>bPuKpAaNu*_bOrb)6?}k0Ye0x{ewb^>>os) zBL9HU68;B_qXkKn1q5Dyotyl^X@{?vcwq3dPSnNtiYm7&*}*fDCeaBsUvbZvfflj@e^E?o3UM_8Ryd&lubAsU1R5 z3Zl31HM$BXSv0?!w&e$Z;p$gdTIO>oEgbD{_=WS(NBP_7%=`{Vut~_poJR<@kjdwE z@rKMGebqrPMX-(1(+%fEqRAKdF0GK2vD}V|sMB1~AWsL}mSiN=H+efi^FuErFrnBl zd_DDN$8Sd5Ne=el2Xp!^OY3J*(1PZr=$fc3iEv z-!uDR==sgv2dx}u*yT>i^&woty=)DnL(tQOK{rJqTisY2@d(;V4h|iaYz<>9QcBCK zCey2FJka1eWeIA*i}T#9Y@J(nkJ(w(Q>hxpNk(aeYcOG*I` zv1s4cE->9KS?uoGu-%)q_m)}1qz~S3*KU8lKjI@v@s~oYN`{7cbFqFsa+W1ieuG4Q zr@>Mb`P=R!&v5Q{2q)Jy?lf~-b*R)7l^itlYIQKcE~k`_ddC;FihF^qbMx)z>CTOL z;i4mx%Y8FCSlBF>RP0=Q$&`^xxn}zLEX|0T+15OE9lKmQ6KpFkpl7NuyiA-g0&7f+ zv0bfbDfx(f7&*rBEUfM4VlOVx?0k#qSFbw4!fd#4dL=9B_d1hpvK!-_yXF3)WAb*e z&a3n83RF~OTwzgef0Cwz52s^rREfeo^?1EE8*o^N*TVC%l&;WcSiCg{wiz$|+HiJ#S2Q@#w zIHEY%h5!@DQajZ7vC<-_u5{^sew$WYXo>AhuycVJOE3K!4v&L2eh$rA$rl)G(Y-N* zn7LE*h&6OX>&ZwfMRH~14PQZ3(r|)|Wjti9z#00#9l%elkRMF}h^qc7~K zz?IlO=@&Rq5QD-^Y_%+*;d0K#lXSXjaGlE%wbyfa(=VFG2knzX3bgT}D#_PsdSVIM zU0z=yfOCybTb};+?skK>^uTk%2h%YN6~98)dgrkd$no2s9E#6edTnp|4V>pPHQnf#qIs%Y&3GFP zFp{j+^rt|{i`Qm0k_V0_UhbvdLW)xnte~8MIvEf3m6q>%Vkn8WoQVaeZPfLA*rgqo zq8MH)?b=tC#lK!J%3#7axFCI0^I$7i>*Tf!`Y`ho$zZp3?q9R`%fx*U_2OhJ59dQ*y#x)+mX}u;2hPRfatFlNX(DykeCKNwObcK8l#*x}K znBGoPyESxGT%mS>C3Zq1U-hTG<%HYd@5`m+x@v*d5`#L-@H2#LS^R>tg`s`nnyl_o zk|{G+Mhr&;Usg;kg@#GoO5Psb=V8^o9s9p{<5zu%(-qG+Cyo?yRUSFcjMqVnfsY0g zR>NVQ5W`C2ky%i`P+q!KGG!IA`@F?1VZW=}5yAm-wFnoK1M2r3dJ0Lpcn_GtE!|hq zE(qr$VnvSh`C2nlVr>#uu_fxFd*xYHBRwbo6{14BNPSf8OzcmSt@S+=ydyhx-e$Wx z+iHl`L%tLl(_0Ko4wRV53etNhoTZBOByk6Yyq_=2(ae#t} zp&`MO9pt>0(;l~K$-ueCO6YMSC;6J*yR=0k}$JW3TPo}$mO4@`rEXDAK9VweO)c&X!_l0y2thOb>h$o z02=amCzMl?rE)Jp++3gPgnyo|13)DT%)KbkF7U>9*^W26sLG>MD`p9w^|38Hx?r!3 z9BxZn?pNERee%`m+iou3Y5rPyrHH`$gYsQj5GT~rZuJgXS4|zbf7$)MSVg7z+uec? z!R_)JU2>w@nwpVkG{1L9#&F`tP1@B)JAV1??b9)`tJd(u`t_O;HCuIIJKBrWEUZq@ z)zL?dfx1#omeP1_amM_V^+Z9;(}RPD#wjiZdP3U|$U$d&HNzj<6weZA(LYNG?G$LA zA1rY?D4vq>6T5v$#J%4J&X?)n_8X;Q8#@zN4^ZYTlF!+^(I4~Or=Dt{$EPQtVC48c zNg8k2Gz=pOcySlw6l{b;0zD1r6XO`^W}|__m(Q=S$T5IETkeKw@-vR%^3qc62TYOC z21!1KRHHlT>oJB+*7kb>d=*GDchea<5mk0^{K3V@I%&iv+I6GTprAU@0^{d5L3#65 z!h7DnO*qyp$O1Nh4@E4llC-h|tnA~u1v}K!-22$(Xci1)s3VV6dzr1Y+4|@p?C-g> z>q|IVg6iost5pke<03O(B>x0l5!s*e(KAI~lV0VSWK^e#6hcZjT(PqqZ}NU2pBy{Jl0)r4V#q^HWpaPx|%^rD3?H~iYA&%;gCfGur$)2QwV63$h750LRxa%8^x=&{Y{_W^P(8=!r2L+ z5>bQ6;Z2U~9z@@57&$eca6$IAt%~;YY~}Nl zLd*D8RC(j@2FBg`70bdNjwC~kULx3RWnqd$F-}NpqL9c^rj0Y_WM*u$5`5-EzWK(7 z@M#z(0$T!S^I|mR8plW{WNp)NYb#f;gx=rm@FF07a*``1%2Da%7ikRMdE#maDJ`L z&3laqY${Y71%y2!;>Xo@i!q+plt25=&lQ3yD z3pa>R7$t!d_A4zM!iy!TX%7nF;yVEgjOp|E3WOv@>Ee*+uJuH}1u39x0enx~- zb-{3mie%O&h#R&PsruoBAULTh=W>C?1M^BWau@g6T=MC%9uWf~t=bE1jk zuJ3j9+oJJ~65wFdmX)ePM1DBxTHSNl`b*=p@whfb`yxRMUu>< z!9#vK3(XBo|H5QZj$2WKb)`gHh8b6VZH5O1QMD9S27{_8hFT#%IfbD#gGRd!PQ&@UeK6lCODw;D zj96Qu5yQ>Wp)bg3g@5nKc+yOcvjmI?`1UWP$iHDo{$COVy1V9Q69kbXxIEsF@%{Wo zll&`(BK=zq1r-1zvSs-GhY=a~_c3#f?s8TYsSv#5PeLZCl^-SQpMHWQ9*0%xj=fe7 z`)EAp7Fuy-g|$92=3rHYJx@oZm(muRK^^ZrTj4@uH&P&(MWfB>gDNNEOYzv1sI0}? z-Vnu%L=J`-I|3zWeV4lox!X+S!vdUmr^(E4o)UTuGtMfMU$ zqDvueRkGzZk1t3Cufsa2cj7=7=T*Srii*(nS(d)fo9)s9Tnl{o^DJ>W#^U_C4H>(9 zbL0Xu6L@piJUq)Yr0hFP2=OGyEexs)E-^kxqei>=)fDgi+&A|LS!1{ecwQj2>n3XM z)QtCXhamuH5XDiJh)dQ=g1D=Ka8o`pv~P&6$kq%$o`r9FEPtNaA29x_a^y1Jj+H9w zy-$RoO1?nJ+m-|$eATH~9}G@MKUPksZWfrY_dPRt+rROq_Maa5R0bJmul)oz_8wWs z(k7kC;rDQ*Wu)Sf;@Vs<@s5!bvYq9Fj@`C!EmiJHbLNvgu$+S8hyq*s4AY2~HmAW2o+|tKXm$0j za}Z*%Rg;Gt!HGBoMIs~wl~xY~!CAr3z&6Vr8KzW72^ynIV!g8#=9%xge$-+@+%-~{ z+iBpccHTMeQ}(B~UVb4>Hk785qpScB*Q@SZJHFLwx5Xw5zPZbna+#%KrD{ z$Md?qlB5ZeY74IT5UW~xTU;M;Qw;DuPaiRx7v$$HMxkrs7*d&2vu&}|fwa0$k3PVT zv3c@ZM?A#Ad+UD%A>XMnVf+eJr8b*NYd8HQ>-kMQD4SyY<@1PDO_p2RG7F13bJ0HOjeCuf)u zEHx2sZiLRdjti;nN$|9H*q(lwC&zfU8P)o*)acylfe9sx(X~ z$Bnqklzts zKwkF3gwcv9t+LPt0{i$&II(NKy4o^w0xv}oSf9mRqil8SA5LjM7_XnDqqo>J7Toy9 zWUmJqW;&L*%m^*p2cSx7XzNDlc8T9UQkqu+5v0kg>=^(=?<5z+UF@KQKcD)0CZx!V z_T>F~591eeVBtQ&(dx0gZdMj%a?qIjHsGWxfvd8wOy%_TFvcj$+3b#uu&sbr!r;T+ z`tN>uGxpxS*GO9yzKgp`VN+HVn?+Tau4)AK{j8@y-L#K1ay_IJcXMSzi%}9Fne>M|MLTvcVK17wm z0nALg-RVwz+qM_}xpuqr2MW*FR*1N)6R3Z;-R|0W|8zvVF*B>W_(` zQk-v8vHSK&W`*ip>>ctnwZ%eCes^2RUvl6tKVLw9I zdll;EyK%J(g$q-F8bX95oBMnf4(HumoKBR8f+cCJYdK1;@Rj!&%*j?I&ac=7>~Leh zk3QKI??uSF-`wxM)+k3gAP1)N^R2D92mzPDyfdVxMJ1RuTGx;cZ{te&D92M)!)7`} zL_^BbN0oR~$P?$^kHbsWyw6{3GK&boq`@X$l-^(7eWX;amXuWnz^Xy&&rksV5DfyvJ~Uw-4S`PY zl@?2W>7mYx%Yu=V%fKz7P3eBrj&zGP2cdmf3sS;WzhBEwH`KJ}Mf&ogA|e?`T}U&q zejngx$WbgCLhB-*zfRl^+Yw;4E1e192iyxg{CTg^P<}X3<1#ZK`XO_)l|B1qx?sT)AV~C=pnTMROI4{y`DhBm&BHS)5JC&+JpQJ?%k*!w0Pis zDHki2AeHg!ww6&d@@O~~WN>WUuRiKFHg|)1^Hj(mU>Q3s5jyADvT1s)d4ec>@bFCu zkw+qZJXylrsI1>-G2u+Q^Bmid?Q= z>HsoUL-HIdMr_CUfS~CGm@Cw(FuuFSS zuAcL=`oXojH5nktL!8sMpuekAd~L_qaO}*VDu6>_e_<`i_$Pd%)9`H9?|94@%GdK_ zb?IqM%OWZkdBD|6q8WY-W_}%8oKLIMHu>Eyp>8<<`Hw??V%{*GgAE9tHr7Gtbk5_9 z=*h31zeb&c+>IZ@!2(DAt>W39%poLD2P3GTmGTSC7P^jy=t{?sk7{g{yNCeUl>ji4 z&u;l7$c%h8kBbju>(Z=Uy@+AvNZ2w92g_6@^G?d;NOjdEyF+%Ve)xqvR1wADZC_B^ zq4H+SFO$S^U}3M4OcRYOjP8-qZen;qunAC-POKx-{>zg8@P$NTFSR*OGf>lBU4V-4BA{#g?{%!zQp1{ z88>~ipT1nDQ16B&6F2F{sZZW)AC-a2xNS`NL#<65i@5&Gj)Oe>D{%-?ruR|_)zF0O zVcPSiXr_w}T$jZXdfv4{>#W`{IpWuq+K0-frc#0d$ufmujGKul4b8R-ZL7$(tN|DtPvvKXO3J|!bJ4Tdsc=LikE1iU~C=kz?D8>fhJi8$EBAlo?H^^MB zJ8bV@1z$^lhkN!8i+{&+;Q)em5R5o2u-xptlvJ}`OL_l20pLyP$gVX)Z^#X)#Vif9 zb9@%Aw`xsBw$obaWmQ)}D3^ujAL4zkBZv3s{&1)tQXt{Q)#*vhV`(7Fr-pyI0EO$e0JGRnFD+&{Fv3PQ_@<{To}V zyz~X(Q7lbF-xU44Dm1`BViB%0mokG7FIx5h56j`AdFGB@{mM@z#7?!ANHAyGWW%+9 z6`rsELH&FqD~qYb1q$ulZ$idtLo*WrXOwPugn1jaN>lKzkiu6|BjUr_2N?|Xe)dQ1 z8I%PwmZ0%`WESKCH}jf2h(GuxmC6bYpP+1|95g6KE82( zGLblnmx0MI`0tIhi~jR`0DZ$Q4ZssO-dKfnjFJ%2wYP2?q}xRB^d$cU$x-_km7F{( zV02hbpw~g4ib&Gf_dHVejv06{=POouU$3G2pD;H6%E!n&|3A~Tu#eXi({mZm{vGZv z&oTzw^sA2{zgL>Q8WszK$Ne?t7hr6R7kVddY`ifBdm~=_dx0yiI<}U?k!iD|et-?& zRr^&Gx)&ee>hT$KZ&>q7m2I#mbj_zJYq`A(D~9@nCuo(C%wlDfaa_(HQ!t5Ffj$Eb z%w7Qb!#3>Ss_R^Keq4WK-bpzf_~_pR$Cw#c`;R><>!@tpNZA+N8f^Xh2$r&Zuf}!* z9BH|4Bzzy@^EKaP62*XT$Ze=K12MZU^EY3=2Z_RXs==QMHI;S;ti`qujEyYk_BlOx zRE7ci!D^|)dajaR9xL6;A$fKNr#NhXrda-^nrAGz-{O2_8vB;?++23NQ%!KlKb4aP zwqL(&3q;%=_=iju4>IYVdwpcdAF(|D*@r*j_6AafXhZ~-MG=S+0DRKQihpSlI+#p9 zn!2tYj&gz6s!uH&}w|IaYD(&`sOQ9mRu6AUiD_Q@+fYywK7 zUZD24_1nuHny@=6HCTpP2My5X6AzOA;8{8{_T+Sru1>kyc?RcujhbZAs5VehI+rAT z0cb-RO0KMOf#)f-hYS$N$lS_h1CoeiRb;W%{EQ}x+!Z^g#4IgCpGj^xC6kX^vlK6S zfw0hMg5Qc8b=DYzKla7cYi1YL>lu6$Kk0=ZHWMO<9Te-2l#zu#?P*!)p%Q6ILNX*|+d_S~Kx~CaW zp^RXrCndXJD6-U$+UenqXdZT~X+e;IOL6ozXX~Pc49re@tIaeumAEklM>t3(0!~A$ z&XWdGvLx3C3_JzTlc0?JE_)NcyQ}830OfreZpR z&pB$c-6)14jmoGnU%^SVy;8c#;7Ox$q~%5uwuzX!${?Aku@nNl2hcYF36EN|GeleJ z0#Ob)-SH>S;gtr6^fj!(J`lj9(@KKXDn?jwFBNL!02;YV!opL+knrp6cn0Pk2pgFc z2*e)U3FubXS^fmjNu&iL5}NpjU@Y*e)Rxr``8XG*?d{$x2N3Gm7g+mJs@ciI`2q`DAF!9&@C8Heklew z%^l>*A4xCTtj6|68VrX+I1|FtD`3@qm1$KA>YF{G(rBc~Hq48`;9~Itzho#Xw@C5u=rL#JxdxVtO)=eMo8*g!A4bv$L`MF6m*z{PuBmBh7oAh+r~7yBp_q z6tF$|Q~<+vb%~`O?~7D|G-`NitEQRM3$aQx*FAQ>f7B!RR{j{tvG3>Xom3c_mLbA$GunnW z!Z*rk`^x8T$dnipMMGQJ!MVkB?Q8IRrrY|<{(#(mTx3IqE8!T-Vhef#II77fbl%`+ z00~7)-ig;$8|G4sZ%VB71c;_?Aj-A)F+HSXlBSucv8v-<8+kjwzm7$igl@U_$?L`n=@IhIj+3B8QOm0<6h`JpPse)|rncR^zx)+x4Fhzb_vEZ=7c5Mlr{ zvw%rmhZae+;#3Uhmjj=a(dq3ozccw*r}7KlVE*otih71oJ=h;TPRQadx(fU^J*C3J z!kN*K0DH3Rc1du-lzMvHX~aOcuHCJ+H*S+C7Jm*WS)!iKrH6}#&YqHaF0*`Ay-KP$-U2OFQv5#t{=~T0{Hh# z%8=`ay3?mpcdZ0S;?GnVjT`0wLYJ=g z^sx~SoH{^qE$MtFxD z>2eZCr12^^+0EDNmR$o#PF^Ii%o|{3w$YgmEySRC{(}^X^Ih>^H$(leqj$X+rUm$; ze_xc2AyI*b>d0Wh^bf-O)blGs{0qQu{|3Or0KhZH8G#ij$~(y?Ai0E)2#S7gj!!+t zyO|I9F7eV|Y>9=M2+BKXYms4eZ0A(Rg3i=;%~f#;1WDK&HrE;m?ZkYK3afwu1&D|Q z&B9AN?|t#TQ4WwS)&#Q-BjhognXLHbQ}Mo*d2=EJfPseYg49DwGD2H?Sp%CiqxuB0r!>OKE-Ah%QN`8hC#DF2^E({svT2C!KM2HRRQ6U0{8rUv7hU+pB30k!akrnP?Eb^ z`)|?8UaWk|_3mTU6*PAK0ik&LF(!!5{O9Zeqt4gph@VZ+F6;|LqQaNsa0IO0Oo_@h zlnUm_LIL^8YpY#nX;@~zPwg>!gwTN{whEAy@BUPDluqmftzI&GlRiEJM6D(?PTmd+ z{$AcnXKx>nN|_T=kc{ZM1e6XRTW0k`QHZx^qsWNTHk%DVQNHm z#ZtK60jyksTH9h+G(6`J)Q$w6IyLt3!+427-TqXF*Fr^_5k%@wLhDo)tCF{`O1&x@ z$lU*oa7zSjZi61uBnDGGJd0ItAyH=27Sk55Dj8uEu=T<)+shon;TtI03&W+cp zGSK`98%c4QrlkfYZF{xwlBv(bk@`4sp+~V~_;5-H82)SOmggu?ivakWYyo&jtKNxt zmhWs5F!)g{$!zs-w{`7uYNbgF9t`uz%CTg!=*<1(9Fa?;K66B^f5KK}f+!a{5Se7} zoM$IL?Q>5W0!=?aUJ|TGwxsE5lc6HuPg`PAQj)!n1?n=^_cg4*{ z(l*uMz{ZJ^rknJ8j{=asgYU(;gD(}&6Dq5}DIz3D_y$BmY?Z)Gw0d@>Obbox>mIY7 zCY(VOPAxnxK=Jgv=G9iUbDHZMIQmaD74)=Y6CzEw3e+a!n*9=Cnx3VI_+6Kaaetk>h znKD->*WUbBSmdkng7*c`9actXND@P<-@e-YjJp<7I>i`M?4F+>BEnpa8Q=(w%8|6y z@9Wy>iz5^$9&Lrr5oNB0w{D6Zf10Fbuj8G$;_G$R(WWJLQYg*C_PZI|IG40!JFJNw zpo3(FlQd5jP|7jZAUNxa1%m5z|HNbUyIViP(bS@_fGrbj>i{^**P6b-d92zB@gET4 z?A7n(j(FeWk&0$=Fdx}|1v>RirjFbPySm!JhM(AL<$?#&6Zk2SxiQgtTdqa{XwJQl z*7Y=_Z_1o_*%^@@CJx2Jcy&&UsGOgXZ?Uo~rPGw|amSLM#YFObOlx1LgAQr&Fn6(J z&=A0&TP?&>o-z!ijn$kvki*QnPm|g;L{G8HE4>0IDk_*;W672dUA17=vy^_N8Q2r{ zL^NLOUX)M+gafpdy~eG?AQ``$03koe;W&nO%LXbnman%)4hR~D*@b2!tx~6#U#Bem zc@I#mzCVRL+N3OR*A*sGa78v!rz_y&psTbl!x<6WijgC>`LHIxvP5IngnU88#ALX= zT%uKiPh7*=hSL=ZGrZJ?Glc$jcjxzIqQspWPm8dBj67{x00bcKMhd?u-ZTVZxbesm z;XnB3fKx;&L+)FfSy5B6@tsj`iw;l|;0L348M2pc5rm5ICzm~nJ%>$v$Ws@l0 zY2k?4XH?&RQ>_E&>?u)-ZFC8V^2paQ0r#)J~Yhku_460@8FX^~i1 zjcfWDjc}dbqlk{BA6cwh^_usodmqPT6X%zyogY1v8xX?6psovjhAlA(2f)Wk&a~rj zn-z3V_BA@-j}Qq4nm%G#+n*BYz`UCMAH??&sX2T?ok-I6#0zoL%okw#>nDfY9)Wrt zCMQpOwYyKFPq>d@X4{3f+(n~1Iont@Z)p)r^xBkogN09zckE z;>zi}8!O~`x>%4YFf~B+6v(YfT3XzZD#D;>1tvO{5I~73h-yA#$1Heejn9V)#%s_M zz(MJ@_41r`%_yAKaTd5i5NTSX8we|>>FezVW10xB@p4LK>TguO^9#TwbJV1dKnI^z zY!ZJ0%Y!}pMKX{9m1b)RfMNG4lu4uD_i{SW)f_+8hfxXPQEa%wvkosb0BJQL4|4Tp zGc5kC0T*J~Y3{oICG$VA$<6`9u)sv9UB}zG&_jztIZ0|oV;ln>Qd~$JLs2o6HN7(< zPycB*MJkf`4!Wp|s75;rGt<-?*-?*MYldF7fN&8PF$ckuH18sG5Fi{9)z)A-F+s0p z@YHVP+{OhG0Xt`tRd{*1>*nF`DI2}{UrU7W$ud&n+QUJ+tspY>VrTlM1MuE)&)grio^NC7pSSU z&j*S5lgmJLO4a-(bW_RKO>T~SfT^zf%I(z{#J!iW4|-?(p?ab~gF&6b<&6qEWzMx^ z&AkWx&#_V1@z>fHP{FUQkuTN_SzUuQP6t!;ceG@e+P>T!btBLW4i#myG$iq|zTi~` zs=<&dEyU_EgHz`bW|eBzUKOcOKut+>GORq2%ZLcOgWP=vfcP>X#M@7mn+3Lx54h)2eCkf>OTFmfL65b^z=_AZ%D4uc1qQY_HL+GL zuRSP&EWZcs&c5%I5vm|sKwIz;vQ!fw2=Qtj@1Q~XP;`QCXanLAkY55f04BY4^h1pS zh4+cEzi7~e6)34bWm$R_kYn7qAq*m^(lK^FTkl#N`zwK}POH`=&Sl#Eil``o3J6C@ z)t3|VMBZ*i*#NREXV{t`uo3Fxa$f*QLU z6%duas(^Tv(QF=#jBW$arC?>7F;&K0Jsu%y4<%cy{Y zW#DXCxvmF+Nq|%lfW~l7^sbZ}+gsS#O5;@f=83RUdPD~;91QCR1_UQ0?9iu`Oa#ZI z`P5Ro<)`w+KlZeumnnIj?+N67EM(36YfC`^DR>|G_q~%%@aWm@6H2fG zekPz8$0$`3ul(I=Pyj}37;2LKq(8%;zQu<|M~l*Zlp#=sTxO7Y0X4L0yDcjJFof_B zFgTf`AmfHS$sRlO>xI4+@Z+LlkcPbwAP|oSB$^acq1*9|@e)Uy#DW%|uC_fw*T;=l z>{#EVG1W1a&bZQy2JNkWy2`;d~eA^5c+U^u6mNlO!E;cOc3DJ+?;l za)g`CPxHGJt4T*3>RjRB%dh1Y96tnP4k+V#$xCn_>Stg$)u?Dm{jGe|(x9po6hA$x zMg~tNp7{!~LHx521OE#hf@5xg5BV1#qEWUiCJ&c0C@p$-5OVvCiJLY!xaX5?dns%d z;6z4~!G5t@Za$j_Ef}(oX7`FeX8k7gp%#nj#RoCXRr{=jk+OBjWq#wI5vH932*X)1 zd@z^|4x(|Eon`;2!TEo3uc-ai%rwGI<)k^Ha2m9NyiWgJ2-Fcq;zYOoR4;DjD?j&uJPTu4X9Nj4fD(Hugu(P>4^EdT-5rcmpfn4FgVTSmy5(_7XJRw}#EIUyIfRa%t}?*#Vp zEkzi~GRn^oj1YA%#didL34x|_KR&`|O*kMSyjX~tG=Ig~#026YzQaX`5v3TKg)kNr zFiY92WQ{Z&ht_apiv*FC7=Wq$TJ1ChZwC)br~iLR01OYHoPQrH-rw8{&e7g93b1;f zaQs&fc#8jT2JuJrNDNB8Jk1Qr-jLa?ACyLya4!8VFvT*n`4?I=kSOm#!8(I;__Kw# zYhZi0U`AHPRBdXU1F9a(3N5_N;nrqy0NdtyZm+7s?)zcUFhQl&bx&_AN7R z6CX`UyENY1kqy;Fo)_h=K+qWDU3iWmR67cBcWdh(C<=JQxt#AU{&|w7&c7fAphXmO zHI}F!T1y1$$T_ynCkL2B`J#c9wmu-2O7=6=E6)&3WLT)6Y_$SB4XciW?%$6p04gES zrr&P`k^@jb?|v47mU}MA42m^b$^ym6utwC>?IH0)-j@SvpJMd^zcaxWe~>ilB)zc5wt~U(NErs6+w~Z>Qz&4lvKX8atGJ8!Bxy;>Ch*Gv+wFr|bFT+k(0f%VB zfI|ehQ4%nE0~}(@Hn{z@lo#4AsUCe#;8sOJ25;ciO)rlqcv5uaK#Uf8tRw6V0|{Qo zs?CRHm{Yh59+cn3d___KMEA`jM_Z0v+&Unhx@e#I?Y`%yQR8s^>^63WE(0p0Ckgi{yoHBBP}H>p$|#VXJ|? z!7um#pIO0&UV{uXqiX<*%Z`v-Bud70blpX)DA2j%XbWi3@2-MF42@cn*dJO=Thdo& zH5b(kO4g81i_1e+?THXIgg#K3zOBwp2*{6fw%A^&)O*0M&&YG)gJpZ>aTB?LmCm9Y zVc-{VTyX`W@33aK_4BxYF^EE?z6|0clMrAKiNgg_B+z}QTU|6niswAI2W#WjX{!_@ z%QEY11xLr;L1E`ZWw@#94v4A1Z*k%zcCMStGOg4ge`yOMZVQ&qOTrTesZC znSfX&wpktkAMkt6lh&s+aWWNLBGq}|mjM93N7(5C4<_(|(jbvYPKxcggE{1P{MABpZ?^>PR^k#-`JN z>kqiHhluMT5m;kjERnlALqxTbq6A#F6D&mHC~#zhNe!;>T!kQjFq+k049+XD(wNMQ+>Bo_)^5`y-y=6J9a(FvQ44@4=r zLz+KNFxq$_ZMiDW0Q5!@c5kVLjet-i8WfAC) zQ3NIoNwA-oX@#Xotbs?F8(YZ31OufYl)!ZgwUjHa<_GHEOSrkE zl|9Yh18(L{hRVQ}PbWi=Y>WVW1r!)sIiQ4SDw2c@B726K`@(n(1{^}S2Kyx{m;;PT zJg62sTFEtlgShu5$Klx8yjNG0|oZ3TywUW2b)jk$=yYs z*8jnV<^gn2(CZKa2LUSGnr#mxPe3ur1$CSL76BF{ZU9{o`&ckIGANNPGQ(4aF#BK& zfRPo)8-?#Dm9U-soDrZjk1BDIijjdhmtYc%>}f_}0%?FB*!VzEw2Twt6aWg?z(Ea? z2T}|iOF=N1EX=m6?274aT zlFsJ2g7?@MCyA#k*@J_04+3%=2*nvAGl%&@q^^M|S%@nWAV0JVkthlb5|Sw9fePg3 z;Ep9)1q(4j?jnlVMGm?f;g5Ht&_Kt5!e20XL;>OuMa*@Eq zGG`|Y1_=e6tQk*k;bdjbV+929fLWK=6A|hFAU%T1azw!aw;5u^a$-VV+<|`1lTBrj z7_2}~H=&=aKi|#5i45WkKp8QF)Br`TCIW{HB!VmzG?Ye`GTlM3E+K?UkV6AFpjekL zz+yasw-Y!d6(@+b2Zzn!`;kOuGzU;C4|B$VGQ|LAH$IB}FX-aQ5|c;*sfXBEk@`hD ziyftk#SBI9%_TsKMGN8pL8%3m!m|JxCW!|eMHTRwB1a5MB4t_ASu#skkhMix1^Nf! z0)yoK^dPtyg3sZju=ZS$C65x|E0c>u99(@Zok3XT%s`>BY;iC=nB;7Y3$-TT&O{^>=*00-GB5zK#siJ9ROn2G0ILY79~lGSEk-~k zFpv_Krvn#BCV}LLhZz=z_C;b{gG0%l!Bhw?gdinJ5K{L*P|krcmwF&6OnY}<4iAVF zs8o?+f8^niB2eImx2FIzFvT_+5W+DBv)t7ZNtF{hY)O#7$yY|VG(!Veh@i@WDTu^R z@e<7xfJumk0cRvXd!#(j8A{h2}jEGkFn%e2B_2?#)oaZrvFDBnS`3n_jQ zoY7PlRH%p|y9eDPNXlj5*>EXXO$eCKAL-;2=s@Sn8~`~%B8zBjzN6ST#M#${Ph|p&E>El? zFbniY$owtMJmro+G|z$g0oeyN*q#d|D}D`5vdMF%Is^C*Vv#P6 zZqOi<6i=fDajga5CU?MDt|?hDw2MR_+g@IFM*$q?wZ^-pv;RNE(p+ z!LhBG0=y@S8HzWKmf<3{_apkt^snXd;Qt z4C11L{}5aPx^tk^96(z!Nh%=($UOW={;mNcN{|%6pqrybuI6G-JgDe(_6>A)1_gPX zP`0I*A-6Z9QCSQc8Yd?r*yd)=_Gk!kTO5S07Va$I=K@muM6kNqzK(%(P$(rpOIR|jgS7_@>tKO5gVE_yca{r9 zu_;R3g=V1CiS{QaVDAykH0Oz-_+SS!fsjmLlCT~e0*%5#5j+t>TmTD+B!~C~0ap}; zi^BH}!K8uO0Em#`;3;-=Vg%W9h%6{tgmj{D*<=OO4`wie;Y0;R8YK+uy|Bms;-HiHH7&8-96xp=I(54UK|+cRenQR!g;`9r zWw5!x!p~LFS0Z5PK!iAu1Fi8yoD~Zl5=bQlo3nvs4Y;C(tJuw->dzJc%{tfD-Z#{p zZVe335T2G!5+`TCwzk@4^I* zhxTwb3@#IM#O@pyfr9o#)9ghYI1ZFTz{$d37*I^10xgL!G9*;Q2;`chty!RUg-4e{ zco>XWjAluL=~x#$&e~5wb)te@oT*mk=2lWB+X)zHI{4E)9ZqiM-Q@Ju)j-y%mM{+7C1|H zGpw1Jv&^3BhvK;MIQ}$BusIqkb@3N_SWsM~f?yI~abRNoEY0nGnPf)-@MI*&Jz4g6 z5{KaKU}oh8&}|4@p@~LNXbco6y@T_}7C|7mp<58-KqZV45JRkhgp(k)#9HtvG;phtq z3Lrv&i_t{qd@Pd;CrWXCd@{kz-i_!> zcXAW(frBcnMe0O_+ACZILa1|#_5XS5e7eZuF%=st*%mR;*Sct)4 z!yvobJ3B}MppKsS5E{&t=H>{eQLTXO6xGdw?}U(na?e0A*_y#en$!4bxIjv3_T zph%u`2+NJ_$A{R17!hD8q$4#54Jww+tQd0ON9wG&p6HK2BiIvk0D|-9Szt-DfbrSD zMHUtc5!2{G3!pBPxzfcnyhRX}L_>KZsZusQz!SJENL^ing#n-y2rHqpGsBYuObpzi zF8-EGxdPonkYbJn*n!ag1S||V;R1DRC@3ssiGs|Kj$Dp!fXG_r0Vbp`P?-1 z#giOwj>Q0zLK*;;A=!U8nYJdiBoI|P6k;_9rm`@g zwglmf2gRCDE}Rr%!KS*2oC9FMUIfXpkXqscJj^YvLxGj0y^vuB1Hx$`8{~AYJX~Qe zIFi&_@w-w-09z3RknP|G(%?Z-inWEinL8*4wgzD+aN_`Pl7s#)<0|m(zfILG9A0^i z0W)@kIXINPi_B->?EK@)YMURe)fT_%Tw-|V{z7T=!sz?=?-Te^sdSV3P|UulPVR#Z z+qfNfO=sWn+-dT6CqH~Y>GiqW=-u}s`B*{z$$O*i1xtqe-drY+RDPW7ykk>-7wKbb zy=iT`y!H392(K8sD`xuIhMrpvpSpHMR`ZObRlwe;nmp$}kI1dsD!xl~rDSqiW)g|; zW5VOndQYnAn#a{T)BUf*xF}ydpGh*VNdzAxv|M@z&PGqR+m4?W= ziHY8<8Up2US;p&*$@=WM{w(yWLHuCQy zK~qH#FiOs*e(v|{_G$OGS7MH9WHw&R@MsX8a{SL-fZN%}P+F!-)894kwliyGWR2H9 zFQP|^L{xWSpSv2y#@&5<@a;c(_rB)22L5o$CGa#iVEpfwsxByRhC1#rON1OnR8x#R zH2%>=c6KUGEajMt`GXf5u63S!MgQA6{#Wg@Dh52Dj>|I-Ck^TChZsWO;qny;q5V(q?= zq`#fxh_Bin`}lg==kD6THQf(~o3srNz|)pI{~QoDF+`y!8e#&x=c6A)TjRO_UViA^p8h`Ehj=#w>W4U@9kZ<@VtcMs;Qfk+mn2`^e6Us zoqpWb%ME4;N32r+XKKz-g(pXPsi_ane1-O{cTnq1zGqp#L-VSC!TARMHu78aKZd8% zTgg`KSf7YSI3FXpK!0V^IyErApV4yS?#RGivN6S|^x269LXl79`lhdv%zT|A^@Wo` zJ)dgHuP=M~vz?|fVZEonSogH{scY}{+4gJpPDf_))q+jf$3Ki`2DH9=nT4Gb_wTg- z-X38zZ@*>QVCu%?pC8aqk9kQM1J@F%qnD|kwFPdx3xq*IiM*Ptx&oGPljrK}X*r22 zCY~<$e6i=wM&E~EObJ$m#?2}8o@n3Hjjj;uh~azPTfE6xZEf4P?_84hZqZxZ1i#D3 zuZCa3d+&%#-JIoks=^yh_BJZ+C`&)mqxNJdDj51q?d98`w`5OfQGPI4@15(GOw)m& z?1t=%qBwlg@1;G1H{32zKBz&2{GG+qVL=P6X6{W(+0ByUHu4#leAg`|OD~&d)>?(+ zVLtU<-T(ULw|&-<-c%#JCMJOVeXDULc_wzv4;EZH_j<_Rxo0ppTXkYHbW78~w!YT~ zHqDd6(j=$D-#mw-lpY=p8JOHNUj^32E^$kzAX{;xajwdt8nN}zw8|yh)0aJ2Iv>xX zzf7fFN*Xl2|5HB&eRTo;QAw=JzCxc$uc^gZTgFXz&Fwe8LcO`|_qGyx7pE-L$i}`B zZl_~AGN`xwC_1`l_a95o`y|Ka`GsC^t?km@;(|T7JFJR{m^XGjzY$%1g`=UvF5ey-ms9qLcO@%=1d5>eAlTyJOLB9rGApTl9tf zFLoKb-^)8=U4ls6aM(2bmZ<+{7%r{+$hNaPT^@ZnrGEcn;MpSG9kF`HIJ+A&mLJQ{ z=fArdT)9{e=DcL^6d~t9I_V#Cai5yf?>Lh0QlAocF8lq==a-9bkE^wq(6>5y1QMoBO{`%TS9=^#!9(UzIP~AgR9~ zA8hm}pf^pO9qGUKWDE56jNI<6$*POZw5#to8((_3u}W;{qp0z$MV12 z7)qemdm(+=KA2_}wH;3g4bNEUCS8fIkHb_~?Cuk}rh!2s3_rYEQyc;&*XGLEP*0l4 z$|6`xJn8JN2-p0kZzgW!;>=`2$g^3JFKtnTxg+d|F^ANOx50;6bNC% zDyyh*ncrRW;E}E^<2`40*=^_cim*+?)Z@pS zHJ0F8uK6|=uDL&(9Pll!?qXVyD~t0%;PiHzeqQrXK}4nDo1Qw}=r0}JFQXG$XPeR@ zN4|g9uVZ8Nl1sbpzvw;$;#C%(z?jWR{L%jkRe!v0Q}`_ldLu_YMYpxMX$8W6^yj?S zWgna-f8R%CpS&h`$#wsK%XELQ`>6iUt(;`g2?RM0l?Bk! zxrZCW7LwEVHj`{Y_4mbh3!Yxm`E-Gmqo;eS@y?jR*hW;+a*t7~ugzOF zZ9hF@gv2~g>GJ>lbnX4m;MWhV-gQK7s&6abax`E`Dkdo#*H!WyYFLhLN}a2%TUR@D zU>LtKabR7xZCEO!AUwSSd8z(8@s0Ag#=thO^A5)fL)Y7?ZmWF!$TaEk>-6_w!Joez zzCpbrb|#X@r>AzFv=PPL{05vWs}9apc9dW2UMNxeq-4v7(GL^^~K%S)Cu2!PV>cWT8*0DYXM+|2wtYrPNJB`;EMt_nEoT{n~r2NmZ3hx7h}=eH_04rx}R{f{j^Y7PJqDh6f+A4oaAx3qH0|IWNlU4U4; z{q@4W&5w;cs$q5?^LHEAxWO*R_jQ!uxW_Wx#C1>Pe{oKvvJxT^vEJb3HkoN`-28>d zHm3c(kwpM}g<}qqpFo;Y8hmZM&+QzD-W4^@+tpKlcrx{T-L`1Mzwk!eAj)8a=EvSw zUD-D4YL8#J{$?S&n)7T@Ijeo=hOAlJWMz-S@pY)rZ+sX1y=gn87e<;NCx7{8f6qR- z{YgoqC}3yd&Xp?O*1%2gBHKXU++rcJpOgBxSFu%RRbwW806=~J^5rMBR^vuKM?t5P~IcPvA-at&HG*wj8|9);ibF z8S~Ex2wwByb4!=%YM5R%e19)Ia(v zQn@WL^1Z5h9O>={J!br0R2iup9i@09YlqI_8wtdJV!AtP=BlZet`>%z_^%6{Ay<8i zS%AEJW_MnT(%*>;I{D7ohR)=)s%Gt>1AOnS_BKP)>@#T^yj_*Ib!}HTDkEZtlT}_( zag8w!kJbnD?kjmHIo&gL?PrTH%zgh1YnSSY^f|F{9+ zP=*U4e%LHM4Ei`iX|O|n|;i2FihtrDkW;KSFAeHafF7}0t5xv)5(%09; zC}nKu3_%>saei^KU}wlcvP&Kn7p<&%=8c`%+ature@~YOtof%yjG}g~fZ^({T{nj5 z%}MXCo~ucu&2Nr>vLL26IWkt!D*hwq%eOi2)}6FqX21m>518xxy4U-wS7WU$_KH(Z zMc|H1)4e|Tq=P1Rg*_u8T<=>Fs)8c(N{nFg(D@x`D-fN>GnIo9HwvM)T&?Mz;U^P~+o7eN%n)XV7ki(D2jGp3>jRhMo|u#x}3er?QK|M|t)w4}AW@zX!QT_m1{K{zdD zeeX+)Ym(OPMJKE@d~`%7En~Y^eOGmS&uLyo%G;}6gc||RyPu?OqLy;^+?9{zi@!A3 z2fi)L8#_NC*$$8Y^7gvcM=k41sAFes;m`NICm9U=Xg4078ILlmd;L!J)_qL6_u8VJ zFBDI=2Ue*nZ%|Ben#NiA&w-PUr(wiPjwjd6S6h~BvgaPQ^(I^LVnPz!1c0zo$YA^S zVxRKV#j7B7_32xis?GSFb~^K)q;5!)^uNU=>F?_9d~on%SC^q{zDo)sRxR&bq*>_H zkGyB6ED1$>?r+RE+hl;V8Ek^SBs9NDDm;A%S1I(XxUd=W z^vU+S+_68c`tPRMt2VC+Zn{E2?pp3&oA_(p+K0tKWBtu;g1K6eBZHN*_?kmnuGcti zcPO{HAMzu34deXU6zVf&(o%l8x*7il!>k_XGXrug568G~4Z&5C$-K4anS>*7A@7`#d}hld6u zQWiMgulw+P=h?{4Yo<##k&YwdmpnP|aP-GZ#?uVf!38mM)gBi5)h2F__&s@9Z(;vW?+bnJ6`#Fig26PVKO<=GwsOg^pI^v#4oujDGMD%=erhM`dCLB+E%7JbY`(G z6l;*0;4L!1BV7gS87gTE-beHnKC*U93mzU2ajL(1U_ELYTQ#HHMq;_|6013@WyOM@ zXMaZ}tTcDw8)Sl>)m*6}d04)=l=~r7MQdH%$45t9-3_GkE>d#QTXb7*1&u!%h+R1E zr4^^esdxi9%e(i*+3DDZst&CThG{e>{egv2lwh!Z*I0l{vCjuWGMLhLGPJFz4;*Y+ ztv%pw&fK+Cs(m>?7KNP%i(#!*J&~>0JKc6l0zv=lw#Hl-g0f#9fPES${`G6Tf zCWARW)>x2(jQ<*ev@1I>Nv$q1IHDOBTf=LN_f8_6-GO^`-eLERv4^pXDts2bVALFQ zsrphGF>9a7EHqfeTyp%t-Pw-!%ddGxf9G;9DAk_oU(cU;_8Zz9{|YbYn zRhj2ref%nDg>T4rEB29}S|(h_|GG@LNplCo6j~Kjmuv{(wc9+e#ip!_eU`P$YiY$M za#o?=I{fj?Uz@6oU4~c&Gpe(3Em0?;HnW@Z)AitdyVwN}uRl&$mAlEw@%98IggwS#c;N{U3!|51X;)l)M@+jZSsZ|2=_ zO*y>&J~k!Vy3EOnx7#Jv=*Xr$@0-(^vvPbRn42}{ZYvO5@&2D{Y)t0kVHsD0HewI2 zyF1U)aqHWGriqTAAGYy1G`}LQMamZ+&-Q-Ux0L4vkEh`q+hZS}6uDi%-t8@szfyT}cKt!aoRn?9l12!# zZ|}WY+fs0sGdXrnPBhtb*LY8B6D8-m@EfV`tu%U|4esFg_|Qhn)jv~Z0{?t?R0H;O zZoZi7g&EAQq^BjEy5__^^X|vVhPo5Bv5Qw*kO3Lg+w;oq^eWNpwu0qLGS`kU(o;UI zs5{@|)!kCzpuI!9S;x5VjZr2p_dY&ac74NviEE^@r$KwGS1(fx@JL^kVt^O#vi&o_ z!$kkep(+V9ON{&$-J(h{7-jri5Zq&0De2w0AdZ$aagDw7HBZEF! zw%3SPlrS|g(>L#ed(Le8gO39bZ>@ztv@ZuExIKHxW-x-0+Mj-b5o`xhk$utvw^$;7 z$^g#&##?s5bl@~Zbdl3~doQeLVpf{iqLEC_asJtSqqlg&ul=y}k`1H#f8FK2sYu-w z>!|GWbGd|X|0bLcV-#P8p&_gL2mBdYC1il!`u8^mzLq# zgpc^iadLD7n<3^T;(u?3PAu6{-Cxt=nc=^t`s%tmZkKwD4$f{Ey*F=RnT=-c?~l)W zKjc>~q2>ra7B8Znqp!a!mmdVtc>RiOgWsy^vYncU*aPZbQJcTKxqAJ$N!GYUPSicQ z#;NmJN9XQ3jr*;AtSkmSJhJ_waB|((KD)cJ$+!zoJ&3z>GmG0H+n{ktXH6rr%L{S6 zn~~@j8O}_TC#mm{KV}6&+Ic90K3w=9bvHRcO?@aMYbEp1P5|i-Y_!V(gVFqWR>dGjt#;_+2ZP&Zj-3NL^{Sb=>lQvA=Nx`p$2b8i zx}3G-R_OHHclSP>i*ugb1mz1|rn$M2(X^52nv#8e0Xj=pBo@vaKE?O)g35iQm@j z3_bkpOeu||=f17uz|vEQYQF;WYlwMSL{4dX*A1ytah6rr$0n6@@ zbT8e+_`7MFnCMlzZkFpem2sLv9-t#SZlCn2`Tikd8}4;_y4$$M*N$sTdbhW4mYN2? z*}<7_O*GwGk%8R#S^3D%^q^7&O+%fCAMn($iTM;Sed~Rx*!aufbFXnD0CKlfi5O(l zG>kM2e!cS7sjqq?i~k*A^Me3yzf6}~KBplxTRCpKvCXyB#_RbhixcSsyG~#3{|28Q z*l@_Bg#L&YIy96Am{RoPCH+@6p+Gkd*=XO`@5J4HHe3Gel@Ci+ z`rL=r*?PyAKyT~bFw*;Nr?K0X$^_llK9BHrF$*5%10Ra3p=-kKTfWlFJG=jPa^kMq z`rXpC_}<0FV~u%q+{Xgz+e-_QJG7R?uFk8XEO|Cnb*7GTt!VL=CdWY6ts6Af?sDxq zeC-~f_+3~(`rBRVGbinRD#N$Vi+kRXn`&s1pmuD-*3$YP!{yzzujk*)Jt2A*e&wo? z?KMR8PHS23zSG~7Z$+lw8Z;#Z2EFB8DGQq>Eq|`NtRY`7WOs9XwNuGDZNAsPx@PC( zE5Vr^^EJ@5iE9piYcwv^kKFg&#)=xXIx!q@KZ8fESchj#ycmFb**O&b& zhaXF1yM@aN*Uz@U1Kx@=({0W+d&@?49GG+dcX!@V&rBlAyK*w==75=F`0VISHBFVT z(UUjwal5U)kuPPbm4*4UL8I`&a(%N+qi&n6^jdD60OG?-tcat-+QZ-9R6X)3UK zeQ_M_QSMtBvuHKCwKP93l)72=^Xu6AEk;8f%`Z8}{d&A)s$1I*u3fvY_}fC2ZeCY8 zRA#d0)F5=mjC*F~$H|Wu^}o!SPMK8}&@LjhbeL=QC#Dd+#{2t%s~6lH*7inY&h}St zHf{%;O6O`2AA<UAKJM87PpV}p=^2+ z^qL_?rM-h$T$j=GNqx~Vqr;!-FZ6Bg{!$V9b;E<5feOa!)8%chIm2Dmm?xg+GF*zi zy_164_jjIf$$#fT((^7{r-JzOWmr_g@3qs>V&vaU|G7N~f3S6T_(tfyhza-5?zUI1 zKKkl>{H@z3FdR=peN7K9?e`iJC!W0N9y0KIkH^EUKPH}7;L^67R4|2E zw);(PY#L90Kiif$^Jw*x>%Wd3c=l@~csV~znHx6525eOY2Kjl;ZpXXJ4*WX*fw~== z_P|=(o)8HDP}#h7&;hS#zRK$LrENP(JwDbR?I~!mdx5ya_uW9R)1(@Zmyf|ZSl>nZ zI=a?3F1~s5&dF1%Ym&0g!R5ie!B;~jP(J4drfo(j9z>{zqN1GKZ-rl;xyLQB-5K!& zZ9UY_DXyqKc+d%#bg0YK0Fbc`ux)E|+t*G<&uou@>d*F<4Ya~tGYZ=_ewcDhwj`kO z83}nmXgAkdw`*)Uk-CX+CE{Rnu4j*5_F3%bjxVCH3Cy8purbf92S6t_E<#juwK(D% zy8dd8$CXilNV(UPZrJ)oxOu~_>h-7Z?*5=Xs5mLDIPbRpihq&3d)#DbYP6|eYBa5J ztEcPM*(ocdgGiRa4^`9bXMjqL)7@}r#Zv-nUmACm+p;D4au=XnAtFDXjxM&I`+kO5 z-gdV+Vw0m`+f&n=DDPyMF}}Wk;X=#1tLNvqY3|4*75)0?;XU5Iw>#IRsL7#dww!{@ z<~PhMTcL6~dQ)#>M`qc>%H$vI5nseQmH@h6X+N!;hu^QN;nl(aVM)ri@VsN2koqwU z;D8FiUjYW|>(D_vI~Wxn8}O_KR9ezk9NUdig0-LdR!6N2jp%z{em$$KdR?|)fk-dy z=+Ywz%efa4Qb#5$A`3MJEnNy<;jA7HEtznc(biSTd1&4+ZZiATvb`?ziv=rx<~s8? z6OrrR?>QCyL<-_zo>xHK+K8;5+PVuPW(j;FsLfV*pW4NMY9B@FvhTw!3ZV95T0(mU zchj)1Yla(hHO)!3)`ES9vwp`x{J-mZ+zY%v&}Q~1xuMEpmC!BodZqaI1>DE}JpSb+ zrcG};_?v4091hQD7+j$i@ERM^c&yzU9`vy4$yw z{wjDe()`U@1Ei=@Hy*xh`Wtj>3IxAp2vMD}xcx%7gZgJ{(f1=2XZ5?BRQetmvv*CC zGnQNp`f55HuBy)IPVu7TyZiLLxplqQ4h*A5;Ec=bt&UTXEZ6|6uGVXUs3Q9-Y;P zAGmbJ<__w8#MCqAUdQhR`dVeVo1Eh!&-OkZ)4DVE;4)YeCvtN{k!vq`t5s;3O&$IA zY11tJ!E54=FwNWUyj+*z_JnowMc5Czj9+0jhZ-W87qRbpg=0VD5&fczt2Mtz)Atzt z*4^$sjmFLQVYQ?_xSZJkeeCgM+GP{$Wgmabt{t>zEb4vvs=oH?Sw)7GF$)SG5RAMe zdPResLqmrQB;h8xrdc)9?oI=-aphw_5%VH2bvoL`DWj1M`ILk2`{XFqLk(3sgIcAl zH-POYV|Rp?0k6HHNgDH?Y|3_Q~N(>$7|bqyN4yA6|tAoVDHpAg35W? z*|@%)68^FuFJ1BVZ4RqlScRUYgt%iTw@xfRveLZFan+kW9hA|Lrl7vp`^z{jWp34_ z$w3e%ey@B+$*N}(s+w#!M}e<%w5p6h`IN5K(e(=7wfS`Ex8`fcgR7U7NtOK0JABI5 z{T{j3YSX&1e5yJ7o#4bXpKGLt@rwW+j(a1T_*8SGtN;3OfKzYAu1Nh*KJH{i)Oor* zb$I=bg7}MjN-0x|f-1aE(px98bZd{*yk4+0n!?yLoQE)(M%lL96F2ehidt zfmQ2yd5NbPKi*SZX^ICyw)~X3Hs{xtmMgBCot=8OwHeH|?cb~jlPV5gW@~>hXy#pT z`yBUrBmxueR~_@oZun?$B8P2>wiRAD6u2<4w}z69UGmuU;e?K!A+_Bqdct*;>DC{8 zSHIf6!{va9!V!ll7wOop@dn&(^iiAl8|F3xb%cFR*Nz+SRCk%*OVQme$@~4aCC8Px zHWuBg=Q=jw*v)yiw*_1VOWGrBo*P1RDFE1s=9_ib;5oB(pi zMS?HJH(aP%P6oW?V}Zwu+R&e>f)W0|f6R?0R)j_UdM{l=GgY7Jbi1+=_WMbyQ8LKN zAD}IKxPz2^xA5ClA1LB|{Pv+!Kfbl2*2QRimQ;@0O21murXyEe3>{~Q2dyX_hLO^x zD~;Q*t8!2|T5$Z^FhJ$q^T#~JRc!-#s?E@6kQGFBJS8WphEV2M;GGBLA?h(dZ0_Fm zDlV5z;%z>5uXuTX`iFY;Pk?HU_BCHWzIQ$J)a^CvK-#Z4d7IY*LM6ztZ}@gE@%8xP z#cNw=aS5lkgK*KU3#g^M+{noZeX|6ESTj48b9bHo*S;$Ab3bdPQ_#rv*s2>5yXK!C z_r_rPEcO!7zd=j97YDSM@}CV)I>>h{hasCu8Gm0cn2PcV%^cNo4g@||gU zeT6$8IeK`tG4jNL@+bdaBV;L@Q3|{6UNGCUx`lTw#i}c_p{jUF=4D2zun&(0Q&U$< zH$v~1SN_}YTL4ORS$7cgEW=Csot=7RJo?6DEy?FRZzEd8HHkFlIx}(e0XgG0X4kES zIYiCHl%>lSUu&?ltsC#yaQyq4{-D*^NC%Y_F>zN7o~*d6)fN0~;{LepxSpBED6W_E zZ9KN&%KMwe&?|dIn;t1aSi( z8tQ%{H_^L0Lt2jkgnuS%aPnjN#zUWOp6vY=KPBJB_y}b%n$CAkB_`hZTwH(Hc}4f< zEgNi+@t=bIH*Vk3OyV`99Vq%RfdTkGSATKY&Bd4B$SP#UhqY^7HCzNL2wAA#z}AwE z&h@iK2MTS3vS#lm$89fe3|JonjxjrkjdqQo^;p>O_g9-;F6C96Tv;3Waee?iRXjPf z*9i0Wrd<9a!mt0Jf*F%b*qe2p>QHlD-D6w!wN_+hL1Xle0ksXbYi$WwTj86VP#Mqk zw*j>Y6nYk%voVJOA8=yZG$2PA@riM1k!(PLgRE-+k zZ3(l3qO(BOVVA(mtxpc$-sENG+X_)S3ChU`iNfXy~)@ z?HwP7J_}iX8~g?(=|#*hcyq_}tCIHE1*v7PNlz%I{Nq_TGD2jttYmw9j9oyjHx4d&oW#q5V zsXm~8s@ux~PN~mu{I<`z;>!0YZz3!cjLjHd3tb`HdhM$VF)uQX&1#jk5|06A)u%EZs?fXV6Vc4DTb|Uc9Qo=OSJpQMXqJNh`&vA+rPKsd9SdR8p(*Aji7?9R8T2yZni8$GYrJJaExz z#+XGhZy0rc{MP^7zsk~3xhTHufRJQcHYWCdRA`J<`R~lRYRz5SGjl9e3c9CM z5G|Y|%58@ffI4n9Q5w>;TS@NC&SU)k@VMWoGXp?^Het&<5M)N#{b{30&5y3!B6Q?x zW4G0mpS3CA1A4eL2~bnqnfE77m!9}MkZZ5>?{xagveTt0k^8ker})Lg0X%?6mB@-y zb^XwdLze#(3?xTd{h>X)m;G0oy_5gvf0tyt6gJ#bUa9N%;d*Y*i%nHy|IWNu-TK#x zdYcfyQ*wxWQWW*DHh#~UInD9^R%HD51@5Gjd~bOr{Ja$0kFEc0AY=WzHf~r&t*dHC zw(I&-Z9* z+w>%3`)P6C$Jq(^ZANY5+w%^K`dV)lIG)|%`t|MAt$EaoLdQq;?u(i+nh!&UFMS6y z&2;VAj4#7Cj$m$H(B6>{e{}rB2a(nPmAzk~q-ciJOJiVgR^`qVIdrXTASt z;RRe8T0Z`L`$a-#2J>YW4y3?0$bWnRS#_1enugIXh3=F%jkPAe)p6;)&rcITB9Pu$ z73CvhyenZqq~E>4pQFFGi+Z1F?+!ok?v5b0d6y!G?0(%3S3tW;|I&~Xb&9!v{Chgc z>SK>AGwz-o{Y<@x*8%ys_ioLq`+4nUdB3KA^rdyzrxP}U{8upiUfW#}24rWpEL@_O z95(&)2}otqd!L<5ZJ{kGixpEt&17Z0G6!OG5mn%;8AZdKbN9i=?Q)x$d+LARp z>W;0pGQuS4eRYTo-rOQH-E+?cjIUwD?5|R2U?UctsF&9q{(F)+w&VCV530lC5BH^G z;WD4cNo!4;i}z+K#0emYZgN*iOMFKaq325{!h^BK7cpfzGi30aiEC6 zO$>E0fcSArPfdBXd-(LX(y3WZ{dYH*nLvZ!6*zhK>(sSI1NXKTuUhn>e=FaQj>q(- z*;T37luPk8vtb6RCE`mBb9OvFw~(VW%xyO4%wL^1`uXJ|RMpWHrU&#k4B=z4b2B6XVw#5CvC?O-pRrA-BH<0C8}8nDl;--ZOYLPJNo534QNs^hk2Elqb`!F#zc z6N$^nTOxuK+9u!JU8S6SL(o%m07s!O2U|Ki^0UTTzLrway_D99u=~GTBZfaZ0HH4s zXZ(=g;dhBe?UfM`zjQjTG}yJzZMFaXIC0I+#{H4kjASkb&>;=j?487s;ZGRc3A3Cy z_nzmc-C`FAZ6S>M3(Z}|k<9b5;g8{J$AC;B?^@M@-SoQTscoo*S%dFxT((_gA33wk zE2<%~^kH>1a=y}tv*wE*AEX_jALh-SmlCJ9^iY;<*cA57C1MXy3~bq)oaWb$>8?w; z#RIaJ=E|m`JzhY$uo1NP6?1l~-?Uhs;uUR+eCD2a2TX?7E8RcPaz%Ate_i-x)VXx- z`=p7*XU}5}Zml7zuKcBa^Hib?)j(^N34cQ$P zA0OuARMqngjaXz00G@bOJ2c=I7>!&;^TEo_o@)sZ?ii zjl7^VTdhU*snKXgDd`h`c+qa*Y6DwN<;V9nx^?Mx+R!2^ZrcP%20EYT?@lf3GOhy3 zw1qKxVWZEj;sBPvWk}b281qSFC~L4yy=kasU{jy5y&z=WvU-= zt6j!Dn0HWfi&+f+;EH*w-LjJgBQ`_aB}QkFVuL5;xU`L1Dhy~&YC2ntuqw4X?F(JJ z1!0|7e_65F-p)PMvUOz|k1hwn9n?i@&##VF$~kc2WiBR(##__77SWTe5fjnrP}BCn zyJiIC)%_o|*npaPFY38`^U5`#k_Iq@M{o)Ncj$IFd1JrZ=_9fa?_VZ7S z!XK#jYbx|_&liiHf6;>+ym~WAS&#Uq^InOLjCmwPzB08hP*Xpu9{=>j(e(m>?()Pt zk0L&;2%0v7-VlpF+>^-jGkA~E-!81NtkJh|fv-_tXCB;ovsF@A)KvpLG^hJrXY6s6 zQe>94&0@{-n)5YZ>{B(=7}Q;&S7prAJfXQvbK_9BA$g(CU9gCr0&Flp-uwa~lT?0S z2uR#IKR`8i1DW63+}tk4jUF?@akbrgRm)X0XXd>$IEb;++{rin`ng5E8 z-nRLbFE`xxgOIEcAqK9q=n6dv7o3kfYS^cT8w%J`XBzc+!D+hD^-ql^gNhq}__p(U zl}z?Beh4VVMh#31l$?J58sGc;Wz;_Vi8V_s?ASorCNJxpkFu}OSmGS{|HymKsHmc4 zYm_Euo1CG^Ndc9N#Btj`x1=$NTsFb2ysayZ2hFYSx^yYV#>naBP*$>L_;xz@6s|Svp)hJ?k3mLyC8u zrl`m7<|*APq4qd=Qod(?#KIlkI7aT!n&}f4%KlF|<^GfT#t{$iKkje=$5Ck;?G#Q{ z`D4cJJcSZYwna`sxK&T`?=M%~pN<^Vx6xDP;rO0+`6WtE*Ivthns}Osko-3`MYPd7 z7q<-c`^>FOXna1xMx`j0tq6B)hORpI)^i^INy6cr73^|9!twKZ%rJ-KcJ(ZvUbY>>jHD_6S>*T3VEkIcp*j=hID6)&wmmlBn^|Ev!q_wp2bV*`xIPX&vH4g z`J=LElk@mm?5&`GI@dZ=MSa#j3y0w!C)A(zqp+za&7&ZU0~lK=fir)DitFB0lA#j! zu0gf0NmN;O>0IdV|EM4XC`W>3x#5x3+YPR4jgPq>GsX^*Tz`03qvJa+x<pl zSF-T+&oYNVwB>MZ8*!O+~350$*0%*^x=?53~RYcFrIFzk}j@p zuF@JVWZZE4m2STqP%o7KqL;KLEiY!DW8$q*yr>dQsoKUU8BWYf7A8M8gO)*`M{`SF z{m~JOBOr=S5VLzjFB{xn)w68xqHwSW0 zNz*dGo=Eb+Lyeq5Myv$YpFUKnPh2w$OK;OL$hS7WjAb&?dFJusiN*7K>cl5WvJ*PrWgTLC z@4iSm+wQgTKI3XTOY&8}#J+;*Gt4(VS6nXHeCZQ1ESWta2?b_PD@A3q#QFC#)J@^Q zXf?!ihx7x==d+00<&|h9znuAv?Ghw>3Zcs+orE5-#!`wLaBCD=52MN^Ur=_)Fl?wf zz5LZ3YAr0{a_UxqJN7R%tm!PkPIueVMw)-ey)6t%`Y9xez2%}mmCdKaFxl){#-&Ry zQIRG3Il-XttY7EdNuQ0UZyt<{yHBaPkqQ+WlxwolNO(IR?j>;A(;=ml{kyXt+&r+= z+Hv_sFUlo}3U}bn4tHp3`10orhR(H7)+S=z@XjXqZ*v(&xTpNO7x|sQ+Xp#gDSXz< z{Fg-&Ef2i+*8dpXcJ?cctBoztF+2OcLc7;r9=!;2xhku8u1t?zX77-Ff9wFXkCn%h zslTK8~ zf|JaNla(rHrQm#&#T22fn`!*ctbq>7S)& zT>Ka><0Kdp5b#ylGSg}Inf4g5s_lov#{ijmzky3hwBo3E`Zp*~j#G|LAI`LzQgTOe zA~L&;CS`^Ce9KpD21%DPm(S1iSTFb&U4ULd?$``BgK4OT)0c-i2cWfa5hz}pk)1^# z#|-c6t+jzc(&XT_TaoMG=YmM%e-VUuPYF@{J{xxJ*Y^Hp$C-wR>Gk{}g_91#@+MdC zh<)jeE(~~=x7hAqRXx70QEY;H0%e{%z56Kv7cY6Nv9&9b>3a9 z_8HQVRSNFayDGrc{5|!@D$h5u(O~=wTJ$bi>#)Q%TpuJ^I5O2W$@0NSI z3$uA^YUCOg6*M7e^tdMG0%3f+uGOgi5v#7#$`I@$YVx30?)A^Bk$8pY+*nyhta^>?DodE=u(`Y4<$* zrx#$=r@wBMNBjK~WzjwCBKCW&W|mVMV8_4--0$NTUXP&YJ-#FAK~u}CcXRD$mB5wY zkA}a$j*OID_Kv1*4q~1bGYw~o0dM5ByT@O|XfEMx+g?hH@+mZExb942O17Fdeix(v zHm|*^3s(upGNm&hZqbu|(_z9d=s4h5sfhbD*Q=jr(wf(&wI{27EW8b`K^koz_mne} zMOD1F7h09919|S%)bpW@YQ6iW;)OSC;{2aQ0@XL~{FOZ4lj0vy)54}>G9HU!KWjHQ z^O$`G2k+!b+gMiMiSXO0OH#l;DOoAe^XfA5Ted#Udl3$y^OxA!D_;Am-31XpolBd4 zaf{YJQn`;vYX{Dv_hspcFj7t4)P7@+ZRFt;y2Z<*rWM3K@Iuy2ry||IRtL=)U}ihqaZt!niDlGW7c<8O zdcQt}E1{g-@=?3s@q;6f?NPF!5${HZnl4D42N!2oYRAXtLqYl^Gy-WVaT_yCYX)ei zvFFa5G>jYHn_Q0@3x#Y4t+WsJTm)>jm-e2u|CbB(@uXh`!%d~>fzSL$3vQM)YXblUK@%Xarn9k{el zice>WY0Uq8G#8guP%zHphnUB2Z&8xDDiP9j-E+ydn+a2cZfdUUIsP7BIw&=N1zdLx z{O=~#n9NDNeA!H5d7shSk2Dj}GIfVXuZRafDLk5yym2FuIc0JC-q{NV_21;dNJ1CN zf8Mm}6}}W(-|)uT@ISj}!9{px?)p+jEboWAlh=hsmxL#|v`t)6bp&5kjh6>B4^s+R z(Eq@}9i6ck_IrH!p+AYN(i8K=FIE#Q`h~$m67?%XRb{4EmvJue6W-Yp62&YR@d}*& znpl%kJ-+6^`eye$Qvfw%UpMslhB3a4NRhH4qwz*FZrtn;G;044_)GBKZnRSO?2hQO zzLw;3glWw!)S#ebGV0#$?L@eI($Su(ZS89l&zvB8tB0z52_yPKD1M->my@nkn(ef8 z6Wn317ajEjY|FDrKN~!kBRv@Vr)}J|HHk$yNgze$%QBI?lQ5AwDCH{JX*% zf(PJr!DYXUm|e(j#aD6TF&$@(X;sqUv=`lIl)LH6JGJlQa#b7p_8$f|&PZ}zmhzm= zYH%8M=eLy1rw+~#EO{6vr0Q|ln7^;{OyO!&u-nEaZTfjV!LvD=o-9q ze&Q=L;?{V!!z%2vE}J4+nbKckaP^YpzKQ#R(W3d)h1vDMZ?QzxmxOo($Jcf!8Kp?Z z(gkQ@`j&nWGzC_?`-!cbQy*^iOE2eH!5v1z_`BOnxx{2#WfHD3W^Z$z3tT>5p0e2Feq5y5ASm2^vp^h!izg@_P0= zi;e5-q-Yq?tk-^j-VRsb>zaT6?6MeG{iy5Aic=G&vbZ@PTh1J)6k2cK#9C3~D{hK6 zbAcX}(fwAJ3I1V?PGg#;%~>DbXZ*asEA5kfa4;aA;2UssP;=7@EQi&sXhAw)Bp-fe z%O0wyvorZ|Dz)>6S^_IsweF3NEcDo5Sd3uJ_x6T$ua)b1yPiKRwcw(?5$jVlYP)dw zXpFHe%&Lh(ZTsgB83y^H#>VWu=6hjwor1GQ!9JZowcGW^`9;Ae>LP(u47i^bZgekU z{?zZEndemnLoz@W9@@Iy^8pHjf@PV6QWgo@=!i?~Z`*B#KaaGl8r2SdTB5fK`HKMu6D*Z40(mH@!ferMF-K?Oqlw7$c>jHYj>Gu5BkWbWg3 zP}}wcKz{aW*NEVQ!LE_-QiB-&eDMA)%aJn7A8et-Nk|Z`^B@8)=@`+~5CNae_<AHDIg`eX{Q1YxSqNuHEnW-JIv~ z55_$sY(LCY?U}F0}R_%rg(J}rwhM2{qQLEm2em%dHHE4D^l=)-@}rKOD= zu1W64x^C!cnWJ}bpC%LEU2++ghOqqbyouf8(e2J#ErE7VxCRX0J>(e?qI4(z=a`_E zoOaNp^xU6yFgV+d$fU=d=ANg;g0cSLkGv!ASaF1BtGD zDRHi97V(NC;O>Y|%O=0@+%*dBnEhhwYb;b${J)GrT5_Sk)_dilDwY&Oo?dPL z{3mtpuI6v8D)`~OC%wsqMjx_(QTkiRbu_hN$TbC{70)!B?nvO~T_Nzi9!^Nbg zCo3dT`T9DRzSOYf?)zjLn*WFEn$2=If=Ac#t)uZ%1h~NHyIy7^jr$#X|4^nmZfe1W zBv^cJe?mjfRKD*^h4f{^)|VjgT}cZJ^PQq0a_3x(Dejk(ih&1MtkJ+qNyv&#noG>O zHhra3J(QKq^Nor*#R9Un9t$o*N^nD`Ma@Lhas4qJHtwDmNsv|ipFRTvl4J-FY4DN7Y!KOdO?kNV(zXdw2(fOR@IXT_BnL~vP%+_i4dZ9fevrmNRylt@ zcBQa-iy8TV0}T9YXM7D>SRu3)9=5%6k?=p*(FC519U9Qmp{X-_@WMxBY!pY(`uXB; z;mz|}{b%=(pde|-^N4l;7|i<5Ntb(Pq2sqd@)TQ%!*EfGh_%wd#E+X1)2(-mZhxO( zFH{Oou^Y^4xw1EDMaR*xetw&r2Vr3D*z=z86hPe*k)f&kWJ0dj+Y?Jy3L@*xfet5@ z{PXq+{wGI!J1%CfvkrB1sC)Sje9j>e0SQOv$|+|F8jUuexh{grkj^OPG?Z#x$bj{( z7jC&U@Z^}bA*(E<V>?o!X|jgx z>T?78Q11NttkJ)Jm+c~=!QTGy@%6@B_tc+1%M`k5^W|mq|KZQ589%VxCMH`=U^zoK zhujeAKW_*!{gie2P(5NzASOHi?oX^b|4#4Yk_zlR-LTcNOGXZ6KC}Fy4`psQ1-n?1qBh%v1ziZU(|9jGx*q<}s@?MV*H<bkZ^#`fNavVfw9^k|?%^y46IYQ_>q+dRu!x2+Mu!=J$~l|SirJ;w*US+x~!XkhZ3! z+}x%&mALzz-;G;uUT!fc++27~1wS+fTJL|HKZRW|1?C3Wt>uRsy-ux%>!1M&T=@9J zRq)$LX)0*v{l`bYFQFBTU&hc3#7bOX1WTF_IkTkxdYw^u!i$zxc)}}-^}@buaB4!D zvy1cK0@eHVG*M&|U#5z09UtCdxZqoF^Dgh|+gusmclq+B2C4i;Ji&Zju^Y22oq_Xi zSD)Wb*DqAk1Vz6DcJ+bD+NElf*U&M4X=3)5h;>)R9v7(l9^Xc|LHmnZc=Nyr5&6g2 zhcbk%gg}-V@pE5?PI+U6T)6;qjAaM0Yv+x5tHPm;M08#D1FZIUZ)BwZ`Xo@vSc&-J z6ZdF*sb^dGOlxy)&ia89VIbp-(YiW_vbNCeWOZRJb*Mv)g=rg6h>KLBcP7EVpatTv zyx;Nu=Dff;^jqM*1!+()l_V2pHfTkVGKjVgl!qL+PA9rdHdGR3owJRJq4ssfRM@@E zsZ50PZmj$ioF^Q%{b|F2Xdzm#wm6PfBpcV5U&13i5VwEJTrc6p z*i9zsEa?g3VO&IY4Ii7Fe-a4D)z_d?+~HApNT)NU%xxE%v&iUxQ@C5o`sl9k&y+iK zc~nseu=iod-96RqAgD9`4Nq*0JKcto-OMs!xuHQm9BWNbH49 zdqhiZxYmh1^-}qQg8OV{AXoG!I$zO)-PNx*)(G;H$zOvPV0UJ&D}4JdwGz%WZ4~7d zgc3oFJJ8EtGR+jG+UXqp(r1EP5vMTtnCIeseYQ_6p5+fOH>!0|T*r%ELCc~U34 zoWh=yLo-cx-`$9n@5%<*b766KgM1sTDWEOq_1H0K&Vc=6ybAnT)$H2xM?3HBFL5pq zGVNQo-F2*>y+8tPp^aw*A%tL3{XPl3p>*t`_1_}P@vmdIFssJWri1&%af14|{Yvvq zbG8fgeVg?}WLz2ZX=id=@ao845_xEDoNPGY8aqtH?e6T1iir3|Bqe_N|8&$OK}|OW z4JlM9L{xmfPa7;Al+DSjL1=*}9G8!C2K4gxS|jkRyH6Dc>2t5&p^{s4z(_GNIp(O) zaBEQqXX50MaAk5vqUJ84i6qx(%XNETV2QZf^g~PZLBoSS5Z1Pmv!yg^!s zx?*788G>gE;oY3>fKU%-OQ3%8Re**~WK>8qJ}ViNJK^f={LJ3U1*gG)w5k-+N|A_v z5UsL_3}}L77ar09g)1x$B&rTWn>&57!hrRPFDI(HEe-98mp_9 zrBF#yis%!tfktnz!Uz`iZ7KcP z&Y))e?7$oiyiF__c&NhQc)8RW9QY{=Kd&=D@)Gf!$wm@Jg_zwKeM2n_{{nZ#`wzSm zv0o3R1tvaF{2zY}F_~#FZecK0&7q9yz?-8|$ll9C;wMN-kyq;UL4Yjhz8%{Yaue*s zYvd+}LX%Hrz}%rR+0HfOgaeZ%k-=0y|HPtSf6(9bq~<`5RuJ18-JaEqbR&nulTUp$ z;wV1RhvL_pVB#g?Kkx(N`E(QM9Ka9V$k zp6>(1){gRV)hD-w%l@V;9TYxC;I}x9I

        yA9dtrCUKmw+V8_J#k?I=YPZE&^jNc!VY#$F3(>Z{@BH7LtEXEjp#p^2{n@csZs_MhiK{qKk7a!U`;M`r$5jxVlI%-$7ScmMabZSaT% zS8V-0)`)*IN5`(y^jz7$r8V0{S}@*PZ=$?Hei5SlfB&oj2KochS)96D`R0~w8MrXIDsV$uwK7#`yt2bc-=|S^@Yt6t#mE$n(;u>=*X&R ztwr+L8@+vDL{u+6CUI+L^i8+?j%9( zmno7S_|OUWT3Gzod!3s=fw`yLYh_e3flYp`c!-ciy6Hl|fiYl;qVX$_ow&hI^C3`w z8{FHC5R1wSKLmxnnQDO{QbE04CiE$Wt7WdD6%nB2Ve=V5dN5ypcBRU3lkB77_5 zIU5bc)>opNYhG*FCgAz?Z93w@1(G;i(BB)+B$l)MiY;)|>Vxa6r36MXEo6ul zWZP5-l>>lLzAX;#?~YrQ0zlXT0kYDhChKC3qya``c6b6jzAn?PlY%ZQ0M}ClO@*d9 zOaVO!m^|bYa~j=$(*Zegpx(OMI1G_95X9^|FLi-&L-I|&ycHZ>0YTH+G??47+*ncP z_`b|zWt3ktjW4-?{B!IVqX4w@&qAZe&f^*I%S^z9Sp9CFOVr;PXF6Hhdqo3~x-Gbf zVeC{P2eEen+qEaxdx&2rv4_rDiYU#@4Z;|YVlc<5Gm1JC{OF2J;Z!I8wOZGH$Rmtii2!S>wgK01N~)xIAgVBMx4;Olm>jHR(k_;zw}`-HsK^n?L#oCQH~onm_vH$|vs z2|PtkVP#8*0iQA79r_v9CE`)CdLPw2S7D>FxbY=cvB^l?c>1$Sfi00fD7<%{zB*u< zQM<-f#+r3El*u;1MTpi759}T=s5UuML+7e!*5vx>=lNoG(OH(u&u`ZpvwR`Q_U0;6 z*6+~962|Ll)W<}<&5_~+oRpfl3x-4}c1pk|z6G1oKSL0TmpN0WzHfbq30p7?LTH67 z+L{k7*XFlpVi0_LZdj43myYXWz)EOTJo^Y*)n`=|qNvxlH628qKV0llhS74OImB}pH|}2JjE|R8 zikZbz2;RdPhs7=b((%Ig-EhZJn^pTgkA*&p&S>Kea)hYJmkkxE$HpVxH)9h&TxLtD z1+t)yHSOYqb9ZFdufjl6eB6jOU&*^W6*2r*?h)WpD-EDOET#@AOwfF%7r7Sn;Yr#XKC-y&7o9eAVU=0UQKLm%! z2I^U)y-%%>)mNkbf%*i^y-9UG%2qPMOG;bkk7*I1(Y&eRt~};i95I3eWyBvw~#`lFc@8mM?%{NgW|X@-WSR80jKeT!!@IL zW*nE1%+c#Yq?8lm_kNuqLaY6F1*LDnh%7mUYsU02+72oX7=SWZ@yW> zZoxM#3rC6q)U*=!iBl9|XpyKm?Mxxfo#kP%eC~jQ9l02u6ZK)SH6%?+8vYxg_(z)D z2*jf3wV^^^ZnPV#XW`;hc9gPlrtXtHhgt5sPfz`#eHwA1ejlw= zg_aAuasAOPbwwfdcX_g6QjF`v3Qy5%inRo|M0vq{ozKPVTV4^FNWGM z$^*l|Mvd~J31)g1MKNa-;Ilq`^nJ7vaa`vDZ}pyz?7(X!&CM0+157@S>zruq{j)cm ztZre`5__m6-G2cL%n8Au>N@gUI{yA!2&YjhQPjGYUHG4-V)djLe_nLIPB$%x{pf2I z-ZcLkqEFfLZF{K@L^<{T8bmpL3D88JHat2=zO3~K7jACMDU(fweC@q70Ca+wBikJX zNpkvEtbTON$T1E0`!Vg54-&R)O#)61zn#6)B{-0k%=9a6VY1Lw>CMxWPwW5b1%L|Z zSI~UYT<0U?a-A16j~wz4p0~9zHA5;LOa6XtOlJBOr2nUfAZh72Dax7?Xj)_L}9mNXe*K&NJvCjw)v2KgM48o_y`dj%&7W zck}RbypO-cfiHx59o5$9m&IR%=X0_qaVDn)4=o*N?s38xE9AM zYd*toP-8Ck;Oq^xq{(*?8XcDiMbx`La%v(E{s+Uw)%L6)PH{u4DM>aiR4NtWn}d2H z(kN0w(pKmsSsCS7KRd{Y@}#WKm4+NvA)M0TN=snZmen|3dxHkK*VQ+6Ke-fumtw|P zv`!8Z`VSrybhtNacCFzvzz`A6K7E;1c4UG6tJ}${F}XqQodY)!Zk~d|2lWvD^I|H* zC$pv3C2yy)#&sm3oH3|kTTcz@;%a0OKBCUJ`v9tIpi{K4~Pz z0>l@@T~%a`<@4J=QVxG@uYUEN2fCqW(GJpUtRq9RB6MVDiMA89x56?I$|+320J%6NSKLV4&@P{Q(5Xwxc`MM z&cQ5FhMNKvh~DV2`sKHDs_S@0xk#~S?&SMiZh~46Nn`P#`l72^2iu8z-S9Qy^g;Y0 zUyj*`Ao*i0ESyj*xU$+cJ4U~=o>`2h zsD|iu_k%~P_f>*OJTDf#d!eJ=0W0Arda?Q3E(tB}!;SH4on1}0k{ps8?u+wQ>cPOf zE@n)@WIQKD{fPX&ox8d&O5g_u_u-By0of;tsucL3o)a_dvpF(CZzVuryqQIs1S7QgctL(4>ODzuD7={sM>@- z5ua8u7Qv?|2sFbvh6K+A12!9Oydu}k68)yE6iLQZCd_}hkgC_!?hHJc*V<>8vh((P zGvzz^lU4ww!wnKm-fiWv9Gr|uj|b91w>I4-cndZoT`HjC zUk9soyRPfO4jssTY_J`mjfQ3?%rnudQwP-sOTG#Wlw_1-p7y+AjWn?MPr9_{$kl_6 zt>aMv+>9_dH5qCRZRj#H4n8G+sBc)V`=?imS<0jDMZj+^NHeVIBw|G<1xRXVAho8$ z2KRf(J0Voip5<)t*Gp48M!kZmk(HXz2$l@(bp3G*=W(I@}VZIf`DHpXrQM2!>z zmZs1VcqAlnr*^aw_D;3M&K;ni6Di_BD$s(f;+BxicN`&uXe&exzr+fAorVNx^d>Lh z=j8`do@FUDeO~Ig1UI_c3O_8@Et%)2gsOCZp41$4QH5hzvtjtO8@8H?YX?-JhDgzZ zaL4eoSM8XX=0Q+!Qo+vt0t&$ZM2vLIQ^RtFa|qQ6b9hsLfORl8hH9-l8h_;+RIRkr zzrIg4B3hGq*wLWG3}5A~$1sg}wfAT-(<(zx{>WJK)JQ~w{kvL~Vqn>|2n(o2Vvv3y zZZVDa5IKw%hF18+e$j`d5*YibbqB+Ea{Rjv>D$x9_u5U9#yi67Jzsx8H5!l5n#JS} z$<~BdLF3>>h$}9QB!w-Ypny9-sBg6@nW#yqnaXBD-NVd_VexPMb@AtNQP7$o1T|jE z;nslg768t^0>#jUula$0N-n&o<+^kHa>QMM2j9xwyJjtmgDVIKJAr}TwM0iFEriR% z#kN4-nimHH;Vf~cAK$UUqNU-3cLDj!wqS>Ao~I~7K^%}n^a3@Rf>)qCAftW{u0q>| z*j7lChVd5dX)_ENllUkhVXgAEiYU5Jk-7+^jFCorJkI6B{=;JCKU zUMAS|xfu@R&Dsnvu5BW2GRvhi_*Tv zJn@IHk#!s%!QqXjJKTHpij{;e+Bvxw*B@QjDVb~-L0tva+NyW5brd0K%mf9QRti^i zkV=6htD|M|H*$`UkRAKHJ4?Y)N!?RJ&b#00ER|_CNRUX6E%$ArkO7I1-Q=TP7a>|D zf5PL}(vZMzQ7|8ZQr)&A2&E;uF?tMZat?xDWE8&mAPk&NlRw^9hBkmL^l%5kTBT9N zAoN1*Qemi|Kpz_A$ypw)vy#`bQZlC%Us~gpQ`EIlnTK+Jd{9RG1S7jPn0i5lSO2R) zl`%hy3 z;1|YT^w~i@NBT*L%qqkVs#|Dz{~CIencQJdWI1_(a4>aPG{pE#9>W-=R)7!v#bjC2 zVNJZII=CDx8d6=opD)Q6Ja)QN^T?gWE!LR#b1ZdrnNGG7`wjp_QS+ct_E8s%02X$L zDA%ZP>+iMa2dw1G;Uu}1cfXZtMB{Vt06H+D6mcBkil@ZH6CYg5h$}BnEYIgsU>F@Fb%-jBG!nb0ZXYsHV4=yV zt>(|WtRED78M5%h8Yq40F$pu4$JG#DIICr&|5ygty3&6`IyA?)ExS|IYj)*=+Q}OOZ&A>L~o4jj`^Ggsa%oJG_ z$B;_)L9#Ha_1TO5Vx2f@omsrl-x6DZizr8%fuA}~`^-iPO zY1T1)-p~q)k%o|(U&miP zAPd_%KpPligf0tmOUmUuV+~9wHwi;7#@kmywscfFv`#uIRY0;GexETBg+;MJ793S+ z^pvUm7JDwSu=&eR(=|J$Gfnejd1wTKZHTJx2PAQHgiC3V4Om|e38Fbhg`D+T)<3h- z}_=d(QUW!u&lsd;j zk72;jOR5sCt6t;8R_XA;RSfbl4w{SXB4MhI_*kK+$3SeoMggI>!xWk}+;cnX#9*=J(| zZTQ42jY>B5etvS(jwENH?-c3FFy`K;01$p>#rWD+oIkkQp4sm_K7y<7hs4lF1qmOY zy=JEb5GMXbXA8{YM$!(;FbuOth~@^ry_=Jdoii8SQpg^J;TVH)ddgN^1< zEA%XR936O1g5-_kp}#@g;;^>$>sO#86~ULGt+os2Jl@zO3KE@?*d$C|r2DhVa+Q2T z421g)$zP~2_7iF5=8nnRh|EWS z<7qqG!_8BBjAUi{lP;JTUhJFjgz9ibME>j_T)VPIbn}4jU2-%lk`xJ5Udd}nlAhzb zL_~yJG+)P#(kCTPK~@RBob7pnCS3Cs*TMHsUQi;OdZFI!1vcPoiXFs(WVEL*G7%ul z;pmxifJ+Du3Wc3DB}s`AJPLKg_gSDW7$H~c&ZTZdQO)W1&s-)q7XP6IrO2sQz9r`H?P@44b|1Z$YNN^XTSO^dm9-#o?Cr zx6s2C2E`HmS>mo) zLH_=`W2S}$3aDSlzt5Wx>p^8! zdhY9BHZSP9!+z@VjNAzNEcl82?NY78b9L@_>C%tw-?8#ry=X;V%+O#rD3Giw3N;yf zuC({ay|X4sT+5NSH)a)oYy&+^Z4r6)=}1Eo&)73>XC2;wH2zeWH=y`iQ3Z!gh2$j( zMZW&c9aGO5JqQ`rYu`)kokve!ME{jZVh}- zANZb1xJ)bFhPfogJs*+6#+(>UR&u2k668XiDmqH@hK(Lor)ucY!T~_?=$UI z0I!SEBBKVuIko^rA+?IF#Sa4&oUm0u%|;hI7W+#xIq*nTNVo>Z&}~>!*mDXCIA)6P z^6wpJ!eo`|%$9M7*%<`BAVo2N#{da4^c0fy@BcOHcl+U7_l#>Q03lx!8RS5GYkNtD z8|Ax|kcKh!sz@`6yYR^$ZiJ4);0b3@1?Kuk>MGcd zmm&4OFF%gDsKUj#)-wwg{Ae8k8Dk0mC5&RNsDOXMGA^Nx@m3OLglIifV*=JuF%ED| zHCq%Fv_?lz*TM=qHhqEO4HO(EDWA2RvYdDp8Ixiq`YQmW*`5k>3@h~06e$i#q%lE| zSp9pDfb*P%8r8ejn5g3kGKRNj+%on^Y(0A*^)TPnXHEA`VQ=yk1v?Oqq-=<`1DWmd z`=@KoR~YaSQl=7o0W(IpOA*D$rJG~+zEq}^i-W40Bb==HeqfB@TRb}4ey3Fc zX^;~d@X>vWv8Rhr9HCz4&`hFeA{7UP+N7>@S-;!yx=(GceFl@3(MZ_YFJAmjQ7Xlt zh2E8~CtXy7#W?u;V#we?)da1NS|#6PD_H2^buX+2Bt^l4(i((@Y4r?h#@OC;k{PsO zj2cpiZA*cA3$f6)_X|x?E`=%!u zO|(l|F|5Eyx1!9EC%woz++oMo^G(p?;gEDHC`b;$QsVmtuW>4ssISAEB6Ir?X%gxJ zb(7-YWjsPkLI%S(`uhnQq($d}L>W7)M9#s&ckh+sm8c!#T8qo?8_|oBceYBtMEG45 zW5m#R;8UdjAHoboKkxZ$4prhiAPjlq1RU<)(xFmnDg>|3vzB{59*-{o$-vmt5y3z~ zoJ3T@YF$ivE`+Mu0@Q%bpAeLrj=Oe6*~F+Z;utXyBMc0K&53f9%2WLaUEs}?G>{ISy-DS{IJlQlc* zrob!_oBA-R4EIaNPYkwX23-lxg1`h5A&)MDa@*Tt#-p*%3UJSo-2yor2kGxR(y0&li_S%mA!Q3%vtwWH#eB1YXTVYU?# zV7i9ex|?V+xH?eb_#68n%X3cb!f-6&Ws0eo3G@%8;KQ&r22D}YTuS61MCj^N*-Btf z-z?e3?YpV1{~{Xl(8VTVZ(>zk`eFAcV+cmckqxbEn;`@zw}e;gSzI)5weFb^VS8H{7dzq)a1WNaJm2HxyDd76Kd6Qq z734a38a$$qt)`KFT_#UJ2*yLRIl2Eepu5<^<|BkJJg{m9sBK{i3x zn%rhAArRYE-lJASfIncxmJd9z3*6Vfmo5z}VWgQV9lYOUM+f1cHvn^rFkdsPqEADh zsUlHWa3}||Vcg9POBFCsR-pMBPnC20H&l;orknQI~G#)R! z+$t01HQ}9H3-u3!V@7uIug9!Nd=^X`3m}hdL8iXo#V)=f<++pwnNI_<{qAoBqbKh6 zWRD!Vp0|6G1bo5(NREdzn;ijG0lVqQ>@0vo^N(A>{4{XIt*!J1iOLnQlOwF-NU1g* z;;ps;>qD7tu0W|)`qpzlW@C|n1FvW%iQ1WS7oR5|J7uXJTe1D6^bR@(3L8o=A=nc% z=!7UT6`bq|;Nk~hOVnBcWo_}|_nM4mxY=mJfP1m+3L{EkSH@2~kN*;D zofCPn+bid`7R!jWjTxBeG%n4Qil;zbYXIxMfZ%*cq<7wjzj9VE2RWP_ zK?2S&jjn>L#%ZkTU_I&vKL1^a=UumUCptNWmf?kNfHzbjtIxmtp*F1?C^mAsiu$iO ztUkdZi20v*U+IzNtL*oQ%u*bX?;cyUc&O%2_&Ei0Fbc^cBiZ6DXI0~Bq0()?tR)I_ ziny4>UG%%c@i~lYEu<=~+K)M-BY5Lle;orOeUQ@k<5RPrXA5U-AZ5t6 zc@IoHTVEeSp^pG~q@*&ZbTou|Cj-(Hk@%}91$a%C*oC4^c)gZ3$Y=|7?Z+cK74W?J z!ArOM+7H09SP_hZBTEO}k$>vp4IC>_OzuD*Kq*)(=gu!dZSYaTuvA}u7>KZ6P*8X0 zuW^0}GJXh_$^n>4CkR0MgI}@<9*dC0(}GG>43EZCj8>kY_X=?GhD{CzzrHuVD*pOpBv+OA&en z4_?7R!xJNPYu$`MG$ljiEekk$vb$+1r08Uz9{7pwe9iSKxz-t?C5jm8vyVVvTIr>$ z)WM)@NBLboD>7r=jk(K;4+xR3E}KVv&fQYRQN?cfCaPi zDy^{P!*5PWi7(#eNEIJ}kpf&lCPeBYP5L{gl5Q-j^l5<-ChZ7k zn8amGQF0@US#N`aVIN9JFRH{P%i^;RLzsYr#AR&rmyGcsz6hcar`^3%l!z35hI|GL ze8+SK0MKsU%3sHO)@-oKPRDG|i>t0mN zaIOTO4Jjy`ORENr%t>I9M7S00T7F^u6K z9y^Ckhnc_~AUJdB^|u4HWf~fkKYBAap(1mYU|>7s;Z)t$UdBDPvqr?{cw7#_|pv%7btXmR{SG2|3d%{`=ZuwqQHNl0!^rTqR_7ccA{NJ2}VME z4m>{H-ZHjt#*#IB9K#)DyZ=JtfJWE9lmSeQ<&KV6o<1K}ULwgA1E%67bDua?tg$};0c$dckBN`w8%xrhtj#tdIqTs?x{HASvt~MBPZZFHOTREP4C;eYJS~OdxfLWg{lW2o^ZRNPenm zUHad4F05G300yrjR6&a(rkTQ9VM-NBpmbbJe=wPBf>i*}M~`W-ys@9s^$dU(Gko3t zg00V(1LpD9bW=-%$qHKqtx?cy7E3cNQ(QkiK@14qRB<}q@XpYZTl2jksmVz&FI0gB?}7bW8K1RfgW4$cQ(f5xU1@GvVidD> zT$)7AemJ#QN#xv21%D^SGfXswMc2`{l5^y{g{=0_L_A*aG>WV%CXwQXG&jq5;3jVCl*T4e(o{x)KNTqO_Z?_fsAC94isoFZk)JB* zhi~N9j<~PfmVIv!Vy=}2&Pp1z9x=Xp(LjOXm}SC#IJ`k7{Js{cMMPY64fCwd~ZC-{p0UZgt#QwwMOOcNeVAH+{fu_5P!_T-~BOB z34u=u@ip)X@h$r@z`3FRMWHl0h=_1QmXXJ-Q=UZwe#&9CRO`Sdp^81{;(n(mmP!W> z_VGRe5q>!hMHB>BaPCKs02QVwB&zPK$6c3cmbrvcf6JSX-5iw6n_?v<}4c2fg2rf!hn2almbR@XJt$qUff&B z+4ZTu{NjTmw;R*{lqz1ujv_!MANngbwK7gu=4XQUy4I>)2&$j}1zliwc4z*oRs3IB z2;JgBj26%heFanobZaQ-qhxRti2dDB;M;_Ps^ByZK4}twV%e<_pXod5;4I>(Yu$>u z2S_vk?D6I$<9_FL$l2shyS43RK!-?o_JFMAHlTG)==WRzIKx^;_JIU2E(QzD!7FsC5kedv4C**C`hyk0` zUaKG)-!g`tA$hCfVW`l38K2sRSDJO9W}3s)u+<14+Q;7_W#IxFpUFCuO-LGh9}WEt zMS9QXUq%<3FoTDLlttQ@lIJ4d|HIy!$5Xk!|KcnQ3&~oDEMi&6kS10cGAvr=GFK8J z6p{=PGH1*@r2!c;m7&lib3&zv(qt$lWJqM@T(`YH-?P7;{n_W7*ZJeTet-P-U;DK; z%d?*6e(w9a-qQtgojcASs<-=z1c2oFU~1#Bj-Nwoy%n}nYy|e2uL6m<8op0GNNY2M z3A`_UVzdMKCqa^*0Dci&K!1@*+kNcKcC|e0S#uC(*DZtOLB@SZyWx@Ut0~RjASgh2 z)uJXh5BM6y2`J1wY8?VFyyy0@BY=&IK^x0UqX=qHs9xYMAZ<6VOn^8=$2EjC+^a!J z+JJ0|0?=ss<5j}M*G9(8q_7Q%0t3@P+P4AMfHX6{<42DB=X)b2VC`|him&6_(hSmL z7T?bo@ORJm`yW9n=9SyfIU^PdWGuYx4pO-^6dX;t%0T zb&4-E(ZkZeez*HA83?XpSkWg~F$~;L5|(T0fdpvYOSZG|?znZ`xBKuwk=)+bU?6#n zOx(W~-`+Z!3w`r2IGIK~0ZLDXVtM2ncyK!(X16f$+<5fX!#Z~rC@&}B-^dOFCC%Wk zVd&bDH z^ao@T&iV<^bd7ye0pS{`)12GYT&Ubxa_1iSE!-JJK&06ILXn2^^^CUO+&hd2?B6ZQ zt<{c#gWyE43U%I)mm#OZf642rqGvG@+Er+p0yCwV7zcy4y-EJ;-sh#=0^MfTzs4^`k{$+gW%YS~VgE#Tu{(%# zKl8_Ks&5>xm2QE(0wsO!I9zI?iEqTcD z609qI(UH(h?V*GWI7tLW`~W?nLo;)K@PMe^Va>hdCNZfT zdUg87y^vL$>I2eydN)SWN76)kD4_m@RFX&9sik*cXG)cwZw_!7=i}-w2X5XgD zpZMqysr~{8#@!z7Y#M={mmZ@-EnVhFQNa@=-rQ_>iA@Tt-lkgqZVmQ?Jx;+m%-$-9 z`g~16o+o7Mq1cN<{m!(hUs$=V=VMe0WS}$JVLO>A3B0WhEdmCMFzq|*$)NTj^%;f{ z18}{*Du9UsCt_QmeI5duC%NQEnNwvRm)m2kM$ zjW}jp%sptI81oK*EpaW|XLD)|0J%~+>UP*Yc#?80o}CtG$RAt*swmVq04-Ed>+0N~l?Qd(1>>xCC=#dbGEE z&(-~H$1_ffAb6+X#nI8zNK3IDlXN14GuUvNLn%y)l{532$Z?@PyxLKiPAUcCs8pC1 zDWqDfqVRMp-yUM&cq=%(Z%$Z?uze2BwW&zdfW|OmN`)Q2k;3h8&-tBkbPk-9XJa$7 zs%-#CyXF--Bi_9iZiZGFnVhiqjQPPt_xP>%wJ2F!IjrA>up^-Mn+D~PUZ#>yWtNhR zk2c>!@1Hq0UDWn=B>)D&Wgn~AEaJ6$V~iVsh`KrD*;;l(fIeMf({9RjrB76+F<%Ms zrkAC~!HQOOQnO~uJFliib1@te+|(KAe5*9~bT)5}XraB^rduMnSsCZz$&UISqv#!f z7yh5#@swo-gIAVVm?BS(WqQ&;BFbOI?V;~oE`YRVxekc{uPtkry2YKXjO6IugJR`! z1WM-|koH5aJ5qpT9(=k&Qj?p`KWBpex=VUosBZ%7_TP*2!IjtZLQWeustT%K=ryt8 z-3bHS+wx5JxO_DGnys<*+sQ0`9%IM6Sprfjx)O5|GJTPsR&x(2Y>f(d{9S z$U7_y&;JB;RbmH8zmTC}&nt#Kn>stGGydX~|rj-LLu|M2ud;;`qWhT2{y9+*Pl97}~D&3SSYm4m_2oMZ`tQI5%n z(B}Il@wVoVuzQNi|9tjXyWjE@lIn?~>iR#aq#bDpUgJtsfAB=KbN<&$)mio*g-vS3 z+{C`lVAI`at*&f-?X~|l+ocsF)ouVl{Kd6tAjpb!+@{f|`X8H*@{XXwBG<>J9g0OA zN!%th292+U4GmEyy?Kx13VIo743peyw^_dtSbq|t+z^xFu@a1)@!!O}@*jgtRUPoI z;>1!l4bi{#Fw*gFe`3bg^-kq3dySHE@z7)#eapE+uL&Y9hn||+m}}KL>)%)GBje3+ zS-pZ9GX#Ft$)EZuET3eP95yS8p-uAtx`}ZxsYzg;^jVif$zjcM2l=gTTCP)D@6+>C z=+*1nV@-ohPs-6q);P04A<||5t9tJ3&ULMV+MWLOjV%Po^se_DPxFMKMOASlb0!IR=VIYQ#*?ker2t?Uy;Z|kngR|wv6i$F*T2>rGC=Yk| z_^j8GiJd44a|RONeMR2GJt1zuE-QGBrg))oFFH3=9Hkc(eGV;^3M513j67 zX%s=1&jj+bo$HE!KVzdTS$Ghx;TeVY&q+WF&D=<&qQ+$>r(U{zg@B5mSt{h1_kTrd z)V09h?@l%KH$H!v#wFCjthYk;Z|A>b^MW%znlUO|D^j{H2rY+c9gW})YJFNP_i@*u z4cCqJ#_&@;s#_0U6Wt%aA#nqrjKkpE>9WTsGh|X|*hnfcRikC0vaUFUT47zPE5ucyaUzd z2#gTA?Q0@Wz+o|mm$XRdP72XTrUWE#^!W=zP{MO^y^(H5B=q+xu&`E-9vq~R@Hn%t zLcy<6{qezuU{Lt)+;HSX>jiN+B;m?e;daw1*vK02h$E|)kQ#P4$XES*M`a#sdR@V>1YVaEIO&h%c1&FtP8u~>9bCV1PnjRT4S`L3YXgZHx z(UEuF!yd*T1O}fby4fNO0Vjzb+O_Ndb8oA^6m~VV=`fd(_Xe_cSYUJ3;*V?p;ci-g zZTvwNfGnm2h#vV+EEmQVOhvc}R{i*IHLN-xJ#6T2{-V7ux3$r%@P=ycOwaYkC@KkG z-lU4jmRllWvLlg`2XGi~9SX{N0yZKJ1l+9_r;TOF0}QZ={pq69!UZrh@d>gD%s;Hr z6%*rWO$?oM4fT@y(3=LbuQt$AJ+IojM+BpS)-iLrw_~d?bq%MG>`}i_6V^=WPi+cW zn7AW^K8Zf0v)2DYTk5v72bc3s((1LKe_6t9-pK)XLrB=(W#b#rYe7>^iqgd9sD;=} z*yW#mgQQ&MN|M{}17e3wQ&zY(u>Pt3aMfBAnG|A~r15-{Uh9;MjOMQA8TY%T7jal8 z8wU_oWac|Mn>cTc`Ro3!Z&&A4Te`} zBA1ZrlW*7lqL4G_8^F)L2#w=BkTWRZVRV!{AhG_l5{4U$F4LN#O$tEydG)qwlQ9-k zwJX`d%xUjaR*_EETO)egMH%}E z8J4j(Ex8}Fj~`6lT2-QRCr?MoYHX6RRORxm_oT8KGmA{$&uYsniF!GM98NV6I6VDX zJi1o7hf~*>3Fy4aG6e3Ro!oK9Ipda z6J;KxD_*c_;h5O*q`y$Sr{DYN>gsT@fReAVit}Nu7X1wIqq6yFBI5ebddm&+0zPC; z`*kiSN%|A{WEYN!G1vWAIcOzun0mSFo%D*Ti`cuncC7bSFKmC*c7@(D-*5bI*ZimA zJKkS?7b-p29-RAn_UbO%>^%QbmZNj8H!gTtT!~rrMZp!v;xd#(zA&9nR=oXCujn)5 z*Z8KV`G&RW)A~Jchwi=wam3kz_`rMgMh9|c#S|y2JI8b{{#vs5_POF&mofIw3ksO@6b(@>n zLnjCXiXM6?cIF{_(zn_Eq&d|^)591(Qf ztfs|p^;_6Sw+hYj?Rc%}FXdev&%Q9__B!=Pb1c^p*4o8VQ||@F2j?d?9)#7zHi-jGA6~cZgt16%PXXc6Hkoq{Ip2) zn|6P3QrG2M;62UhZ_l>|TGmLX9>1XDxmM`2MT|z;e79DB^y1M>T9L?7_?Tst8uQf! z`#_zPUBNZxC1DhwvTJ}q=@Gk&rC%t{C3B2+C+z*yIFy>E8#nxcO*m zR=~^Uo}DR^h+DyZT@dQB{qr&SEpKRBaX#!bo6kA8w}EN?d(`WYnJqK|aGKlCKJM44 zy}lR1Up-njrkKBY*xsD2JkxJd`&}enOh-C(>|UDNMU})jf35GQB8im_h9;cN@jDqb z1GeWbdS1SF-78V2$+tbN|9KBiyM*bi-dbXEp5_zx>EVUCp_RG5l!v!3v<~~Lc46lSx$HS|hm)W*s6}IN)Of|v%$x`TSaN6HE!6Lk6g1d+TZP5Mzs2Ap+NSG0;7-M(ry$(|5OjnUk0%^3(u;nUQnS2^Xfmv+(T>xT#6XO2eze^F6SEMIvbqo#_7bX9dBoQ!q(osHZnnE%hAgug2p3s zUYS6`tiop7FB>?^_H_vrkLo_F5i`9ERl6?irzBKUDvv}kJMDfL5!=cB>tlY2nAOMo zNh;$eGM*DMSCwk+bvu5tj8gv~c+tL1uF1Z$efG|Y@%SW)&WVG1jhX>(%L2cL*O-I% zp&?Irk+RyZdL-ZGwp7S>#tDzA)Ukjh2Ilzou;?^T+2aytH-5?k_{){FGWz@mZ=QFy z(zIPM_Z{b1O)+95r_xoa2RC)H`&R=m)vI~ROv%5!SbsDiOdA89H2Sc4&LN>uiFwgN5vFmJea+5jZzq9}_=jwCc$`X;q(Xb?m;_yN5j(uBU)lQPZo_?)s@A0w4 zK{eTLzP9%t+2hGpbmTijl|)rZ-3}d?XQWx3{CA^Y7dwdKyKg7LJY&M>eryOc+MgIXP6YF_KnbcjaFYLm3~MlT`|}2UiXj`E zbb7Jpn$PX?{GC3-zgy>Z(}B~_(H#w41TsyHWLS5q;iB1qCTiRW_usW-#;C)w=~2$b zo*Uy-E+a~0;*TgM&_{@%g%HuiEi#H|wC2`k+k)Nk)GVHpoUvE#Rk09(nzUvdrD8+Y zcS}Zb-`{cT{Xrj}=19vQM|M-MB;N1|7!FzG_K9GG!_fPz&T1OXq=%$oou)aP3xwCt z_9jQ!CPApSel(;SN6``REZviQ6~DKvD<*=pmPNwD zTU?^3uY{42Jx`P!tFA5EURcXibm%EgtpR`P;@kgb^Uw@DJJ;y9(mkgu zW1J=+8Gowm6otn$4o9QayR4Bu!;Wbd0p+%$^zF;E96}>a1Q>@qHcd=z=?cFXegT3^ zgFpf+pKn)B-O4=n@$7B4o=N+#oaF9m&CwJDkA*2k)EKurOYcqa~%gW7jTu+-mz zFhq#OD(#E}oWC6+S%yGRGd&m~)DG<`BlZN0ctt~6(YR9-eFngt2$*{l0BnX?5Ro(y z8NU0%(2=3pd7zDpcB%haDTK`jI-&R(gyepGJlALP?mo}Tm%Ciz`r6~~tL$47gs+8Q zbAr$1p){~p+57X)jdXDUH=y#d4*XZhhHnpK&2%H%&d_JS4|B|Xs&q7gyq@?VXEl9b zW++J}_gpL&7KU$#foH1=L@#RH!(fz7M!@j%wu(&BhA~VQ)Ir zGSJz1sbQtnp%Wn_?2QygcOm$FFi6?P!sh|1d#I!8@hyfk8jL;dkYMX68*7@!d)&{6 zg=uf=yx`jlmmFwf3`5!A0h00hVYUFbh{8AqzHd{R;8q&22SY%uZ4hTbs``NQKsEV{ z(=Vg->v z6EbwAc3&(dv5~Y8b@Ij<=_x%QfRLY*l(_G_%fX$GKtBnAi^3ln!LDTageSDA=tW%E zLRa6Q`>)20I>)~87c{Cr1}B|$L?GTAB*Z_!bmhcRdRSX*{c9Ke0>bd^!N;dx#}-WY zrijC#Ciew#4U<#NwLoYh>Z1(&#NUkC=%C4yG%L?)2j_V0GUOS&@BbH=4_RJ?8!R6A zEx1b>W(8R-fr_II<$J=k(uWV2>51xuZ6DW?xVtci3JcKIkriQR$5Kg!GG{GJPI8^n1 z%y7t3!O|RnmAlq8B*pY}7|cn=T}hyy+alZb5P0ONgdeRlbZU-Z+x2dE@NAEo3<_(2 zM1jM8$k;-NJ9WeV@M$f>WFyFyay6KM;i#P4G>!E4x2&$bJToFH`O9CzjVs?vO0@er zE>r~IpFbYket2v`)t#vaatK)37a)?1K@WHP86*aT-4q-&6?L8gnvgs%c>Q}MdzFCv zSC+RA<-jy(Ad|D7k|o~tfV%f%6w|qeZ-RFDknuf8WB3AtjIZ&;i0CFM`MBSRV!~~1 zZCG7d5}DnSrz3oazUwzqR)fk?3`R4CBo|oR25(1Kp^?Zz6Az~^jXzAE8BJ12(A8tx ze_X_wf&H(CC@`L&jxJ9`TKd2k$h8Lkl1)Xm=o-qz7w}`Rj7(zqEM^Z0n{J5@)qn^ps4wL zDdi^DH?jR15prt#@{V6SDP~hTE5qzoOgs&uQ%IGtA7h#57f)Ne{x0BMUo*WMY=6ZZ zq-557X%^)+%k^FWO6{6U=n1#H&8Z-(&|x;d=BmrJ_k(t<`p>E{#&d)yO;Z^^F(L%= zrJ@iGx%om5Dv`^)Ig&|*A54vYfMX64VnH?Qq{x-C7k;GnP2Parw&TVH35}kRogJ%B zC)b@ow=Ll^NLfdV4ohIPL>-=A*=-D_Q)OYc0)y-cM)o3$dV=Q`eHVa`Ci@?6EjZkh z;2m#&nUY`YF0-LK1Mp1Ojd)ZJWI#E<@yQ$d?T{dcN+5CA3XE>Wd>#iRZ=}vBhP}&L zH(FcwK<6`l<*B`{v_R@Ely9x^eWJk7M?~b+TL|P*>pv0ao2pgyUHbXGvgNI5f&4oS zHVJWmx2aGi5Mo9&Fs3vx9^Z$$HZ8>ZiD8 zbL&54xXwS^)h}PCv15WYd8W+o^z^GDenL5x{`g8$lD=dpH2QV0K`b&Jqq>mMR!B&= z+NduO7PJqh%m^mBrhn|Exu=c}xmhg9h3nj0o;-a}b97iW?dgp(13v|=sMz#4I=LPC z_eirGVh9E^zfRjvGv8CTGxz4W>|0&696l@GdtT$_@wpX?it$^RMi?cMw6^Oshvx*= zX!xto#aMC0ikl2y#!CLu=_*)T%MVjy<&V(7a?`t5$P*%iJl1zF08ljlaIT)k-imV= zD&F<%tfjXI!Ig~pcwfHLsaxT{kXxb17N`Kw^zm=z$=3+MYr@uAu}lr10|YYPdA?u#>ySCxG3)ZPt=#a)RB8tX=$LnTw}MAvn;yKOvqF1usF z*L!n&{c2Ru9Q^jZ&I+>Nvt#`sVzVI_P?i^>VgnkBjFtVfj^W&RHk9dyFs1CxNRtd@9@18}fH?ZqZ zu?~Ul#|pkcs7QiIl0PFNB7)Vgt;iFA>EpVsnX!KpdSxz)cTR;k+<(s8h{X0Dw{>1b z25|tb|C?Ugis%mFLG_Lyf%1#%h`$miyHI5KgOdn)J&&N*IKD~T7Jy!}ZBNH_FRb5f z;r~e6t!oCg*GuY;e?hkYm)TJ4uWo@FWKlmAh3-H?;ZCrUP^jBZn*#H~9+$$I4i^{l zx>VqhD}v15mZHx^(KO%t3vL7uRZLKh;?AAv;0jDv^wb4`n>fE82inks%d*4t@ zpVPrNX4)Jqg{R*Mx5bymbb|$glCrP+Ip;wbF}DgM9F|g$Bhx9q0L4ry3N3{E&3v_s zOqcad5@O(}0v)ejifh(YbqZ3zzy^L9ikl)U_`a!7Sn5Hn$o40so1tztagsyt%Aht0 zlyA`OPQ)#vCg9^$*g7G71$4~lh*fYM2+|~Hg0mM*2|zXBo3i6Op=M4770>q%9d(PN z+mLT104B(6*8zDv2zrsTbqH$VG~f+KR^pxDknOrx&<_HIKEGcFAMb=Ds%g-nN%E<+ z8=?3lEzFTyW=6SOAd5(aJcBlSq zsyjg*BYmv;0Q3|2YvDgYOs)gcm*=w%LKLVh7|d!YLvVjW)7uoRnb*_DyhVv>nv~+h zw~J}?j)uKH#>;KdH9ogw;PDGs9;Yny#7P0 z3gyVkeFD+RW$_z+#(ftim37i~WLS%EyZJ!r;MoLf1^4kWTj7`2EG!fpnRiBs_cT)jg*#H$(C(WX^~kd~gj6&q6SG*f$;}#=+g$~IM$H65Eco~xW-!-X5}2J|RTwd6_ue~u zj+(O>-t2s%l*;WNp8F&*9_!iU4MrJArEfj-MV@A(7bFPSk)$ZQ6D@An@mB4M|9s z4f=kcn6u;Vsh4jqT+DW}*~qlbeS;UUM&)cr+r=<%U>Q^inv{qpIbiv~H^9G#L)#v9 zkQ+Byf_G(o!w@b(lyKrcO=}vdqxu1Zgw0ws^c$ zE-+Z_M6t8bzP{29y)gFa(Y+)l-gWErO%>s5bet)WxOnj1L-((jDji>IJ`J5j?BEx* zei9MF8Ss^0-`+;=p2$Me4`MdX$dV)y3_|<6M*#zRob2G|4W*OR)6P~u zhq-<_Z?~{Nt0?&dgQQv|gTZVk-k;h$0FBb%EX%|kBB&nvF#D+O*X8P}pvq7=L5T&~ zd6j{AB;kXSC&1edE3QWZV<)nSjRwUobk9e~LE&SBjGw6vr1!zv%w$0by*UzG6Vy#& z<=XAZT4Y}s?AGITW$aC#V@ue(ed*qZ9LP}RAAID|-2n%ZQ|Tw*sAC*Rx(RAmOD{@F$${Sr)(T04Qv8xK~MvU(O% zc_I(v+rkpM5xOGSK&U(Ru0&c7_$II=@GY+ajFek+AR+!CD|{ilFIee3KjC&vQt@;&QpZj*1y>4^O6UfrD+~hYufz~H=TG^eM9Xvwz~~2 z*-q6WLB8A4zRZ7y4jz>=D*u5-Nn! zGlf?l;LM`n9Mz@VPSrpsY18`=HOB@poPD#d z-tm-Y6J~Th_)!f;Fwl`itQn@&GgZnO_W*bf4672E{t5ajT%toHZ5SOU7@23T=JU zTP4*K*#ix~DAVdKu=5vAmYxBo3(x+CtKm4HAdFh%J0J$4f@^!1S)whZ2fZyaf#cn$ z5cg3mesz%J4$zp*8!$6(uQYtRZl!~$c2EQ9i=ZZ1?#eWgJb;5zZ(rj9)2^-9d6>iz zly64HGvKD?q?xF5cl0=8akPurre{~1o(aT5nf~;80z)~fF=GdeDTH#=mputGmxx1r zxrk@fZW$1#OmRzU?vhTo=e8F`z6ALpVH(NULXqb!ipEy+19%VL9HRX6>D% z@+kgnKqlySujSf4jq56U9XMRbL8NFyGRQoz>(>@ut-YS$6t^Oe^j2q{b2>6v=jOi} z8_K@+tuDN z5n_|wuD5~#a0r2epm@^(^ah25qS;Q2yl3CF2oY7j3^zB7{IVJT{C?Uw>J9uKb)9sH z!N6b3Ee9V2tbAMhwh(y3RwVVojA%z-DT8p;L`HA#0oK&9(VtIKX-y)unjl;+s6xWW z@k^iRqcp+61^FZpNxvU$h9NVO%P=gZ|7?(t2w@k>_q=Hy?t2xzxY%um%;bSBu>ViG zUWzIKU4(+C6KG(~%hVbPT(6V-nJ}ozr(X4!hvGiMWV_bm{qQJC9vp@$e@ZYmGBg(| zxb=>YUI-LS|4=-SY&(e+uNP<;A4QLEvNeR~`sJdw-M#EI3(&6s< z5rLx#!Tvn6yHXE>nm+hCBD9R$zF1T4=xv<oQrn#Is#0ns?`AD6EJ@Wn8I{diTHj%VHj5 z&}P5@hd5+qXIu;X(YsrW5sDgQwmmI0KZl|pUXdpZI8gPipvfL@C&8snmv zhUq{nvwkasVHbShh2)auc3vu%9J0zEL6T?J9eceIaN8j3Da1b2kcrSkciWzU45{M9 zU~3rWw%_S(>6xfnZuOi71u9mXBF`L2b%n@3o6;?4Gm*ZU0o4?Mhe;eN^HgN()c6QY zQVJM9d^9Mo$DvipgMPC3IFJ{!dBq46;PjUaUH^LPm}u|-6%<$&`_O~ftgvrx{DZiB zDy!DV&ufrqAVu2Y{6-jn7e#5wHXmHpx3Tei{Tt)2X$sJsrTV5ZYY5=)lP%Xer!5I+bxbI!o~bIzp3122xuGxt=^#ggNmpjsh+kk62JeC>zth*kAcHR z>%gtr4%-Mg&!8+Kk&&zrmXUI(2FOP85#^PAL6eicgPS~nhllih4@6ps{7csO2l&IT z8ASL~_9X;0#dD5Vm~(81_zt>Be6*V#oqj-WV_E6nIAB>Fe?xA~MR@x#7w@V*Mq=D~ z*|XjTc$6B0i)j^}5Bm!!$*H|I#b(||!=8ZJ;&e>?#GwKN5m_DNw&M0f^^?kVcUqrF z{hY?+`IUcZ0UW&JHeY7EA3IurpHhhiaav<@slML!kM_;0#>vprSS7Wda` zoIiM)Ax@c*ZBrs**I_@m8{YZhD^TvnmDIyN&d0>P~%oAOAnK zvVWEc3vl9qrs-ee`qlL21}- z5y{$aVxauBKGDRUJm9=ubFcgb=P!;CKFOUjq8`34zZm8_@^sXV}AeO&8`iA*wFmSYJLQ~%vQ}r#B8&vu`)nzPO2&_(2l1aGx$xMJV>_~v zw)y@ne8~35R8u)(TYIpI*-IPVt`z>_^~d)NZGQi4zlm4FT6pqGi~@~adEArNt7y{d zCCun}=-SobyYUge;G-cGJty<4|Nfl3H;{rJ;*L0_q{45pi=9wrHZIAM<0p_XwZib4 z{t0!1**yL1k7pz(Liz1B6n~b(fK;1x=cwkVu(585eWN>;4|g@i77n{+n13xErV|b91Zwek4{xI5MgKGP+qj0nDq>S0EFTmNqEx@J7AePBTQ$}Am*QHMm zN4jwt((lK^>Jkq34uwtdzqI9lY{HMJbns-px7-->hX>RF{x070zc|lh0k{-cHKx|w zV9*$v|FWbYZ=g=Uey{BR?OyR$HWuh_DzdT^bvv;ZvAJRbqt*58S=!6MVEUS00PQA% zsSeeFL%?J52ox;=J^t*%cLi^|du*#$^E6oV2B)ikM{1qMQG8T;;WUWU4*4JIQ<$E(~QRd6+(06lz) z>(q+C;SOB83?sU2C!!)||2-Q|ZJS@qhQvgXH4%P?s?%Ef@`mRJbz>W=O7D3-%AEN? zZwwt_zRRbFG7xhWD`kCA*?Yq z65^I&;Das*EAnAn36w!RMMugqNixCOSiAj~OR_m;0E(u83&-D^#?ToLn}Ad&9YO5_ z8u`7?>p-!H^i17h2x{sBbbyt%=Y3o5LNX|-tqQ~Kq3D`SO*bd}8%_aDMsC3N5=0ZWW*pE0OC}Q(z z3`U`?L~Ul{0toN2^#NO`iqN5#^f{?e>Stx%6R?;fqqp$Px=8IWC;Ju=zaFW?gV$-l zCwU=)b7;{sF>r0xa^=38hLx|*P*DNXGq}P$h;c<4mwrZ#UmItlzEgn&7=k{z>%N=q z0 zEBsA)E^|i(%VbwD(ns2oqwPARlT_=pN4kJex?Z#g?MPQ;lg;1#fi&=cYFM0I%cm;; z48@VT8CfG?CP&h)>{C?-AyCYLq!^6D?wuylMe^J?2gZlu9y|t2Nl6tUaQSBh(pYo> zStD^;(@-y%QUX&&ri2slooEJgJ7Xtxh9RsUx#nRo#pmqg%7pfAnAa_)QCcbWvh|n; zqX_ZMfVSi}65grql(yx{*v`bJ2#xA9Tt_R^u~*Y>n@3&oau7n7tFVo64~qmQyLuNh zw?)&wrrHaQ*hFAHcCrrY{i@QmMRU4g7|J*qzlYfSUE~Z)*xS;`7Whw%Y)!zq6%$yx z9q+#fV@p0%)W$&76u~Qy=Q>bXh$e}E>$vK2Q;%V^@guJ@NTI_RHZf74{{o!#Q5&81 zC4_u+fr?akw8>=RaChp!BJIGAigNoNNc|-cu4gb2XSYa!Vd+ z7f4<&t7Z9%bf_>PM!@iX?8t@-tEHA2EwR5Q+j#Xe9-cSI)88U%kl_waLn1q#t=mCB z$=mRC3Y8lci?GBSmseTA@0k)A^Hd)H>e!d~#({JVF|oJv;jT`WxMnDZncfDWp6ays zG1?&*=GB#FA!&ikq+i@_!1$66-=txQbzwIR)^=t%eK(Z7g@{s{mIHY_^jd&O)(gk~+<4Dr6W`tg zSXJ6qN-f_<#ch8Kd(!Ci6jF#Jq^7G;snjHT(D5_UcJpOYeegTZ%~eu%L)wH;7K+Ocr3%6@{_RhJj{Oa) zQR+T&nr%ts+sC5)e#OF&L9*HXdj9ax?&g$2lE>2M|9JgC9CX?m$g-oIgq=O=6n zC8TM?KC)mzEZZF!kqOLP5UE4N^q&70y9(kSnt3Jufveh3tQ>8xGycIj9aveA3`di( z!$S&&-8-4YtFjlJHy;oM#amQhc>htn~i{6yiY zsfm16-zKW~=~+1A9;GewFXgLP<-8(}HL@InCfAskJ;Y)_b%0O|s!J|s_ir(U*`|_& z=3(olEx4zV1j5U+{X7ly^ngnwku?hQY#z`^URe1X8ZE;wRW*nd{L#nnS2NK-E1STb zdDv=ncX@ixlyIj_*{IEbiLZ{rn?8vg-c@}#L;1p+FJD{XcryH|xbPJqUda=|Yp#u( z;`$jI>WhwK>ywD{WY#jqq@Qxt2e+v1=qh=;CR%TFP5yUpE5Fk_GZjMQCA#6et&szn z?7d$vZ~r~F3DqY{7lg&i8R<7Zuda7FmfwMy?@Msh=f-^yIKiNQ!8 zW%uVD1CObV{=6h!H~)T(12njV$osKIx#X-`AK4RX7uiV3;%@~5_EJsY3n~}hZwwRB zzj0?DdZfLdn2**SghyJ<;>};;+1_j`hINS?jx4#)7U&uuQuE9c+vo zaQ*nKk%s-D9`uVZDtxV(EsLj?^RH7+kclMT zDTf2;o83lDN4v?N9!BNq4I7L+*Tde@SpSGB<#s#AAKqJoPgIxFf_@VMoX+p-+(j83 z^4_@b%Z|pfr+1$WhR_Yma2T1xS;I?4WUxG8??V}TtSO4u2k{pz9HwiE4yWHSt51JUBihHCDto*R{`}_AN z8yhDYaw3DOajq&No#pwz?)>+^cz`puw_zr3`2L0Ahul)jNo2v!PcLnnEthLnm~|3% zJs6gGe82X8{~_$ZtOJw_N|!w+H5L}$=H`4>VC6}I)Xg^3f4=QFPX4@O`c$g;mo*9d z(HFAEcX@C^Q>L)~m82(4PqNxQmA%OMD|8#CGJfi{QdGE4#)S`0OZ(%Vy{r>V(_8CH zc`B$Q753}YWsHw(N#pOcf}#($NmKq$K1b`6(3-_Vsd&}PWMjbUzU{WxC*!4HwI(`* z7N31$zT@AXy=dnyj;-TON{658V1H-^{npK~(G#+JdY94ba4`#}lH(w^efAajoQ6FA zD^D*epvvPFkVDQR7k_wH*LUddQ49K=9hD=^olI*|x>CvU%WStep`4%o{Wi3$6aMz- zt}x5um*(e=C$es$9lnM4`5YDbFr0(;LE!Pc{mhAuuW5&Gb4KwRXfWG#r96D2BT?xHBC=PL@rRuXq4@he8r z{&Pi*jj+Tn!zHtO`gW^+i6gHyHg35zWf!DWua_v9tbLJ*(CE@9Fxa+vk5q_rrIVQP z&6w8Q`0%XV(n+}c0_gK!l*`-Kpu@-YZbrqK3fLYMmLEo#Y!%#+z|pNT5bM1%i@QU= z^U3XFlXUw-4=ETtI`M~*E z){&q>G5+(@aR)h06~$=<79l4Wyu=#{@TK?m%s1Dp$2``N}I)54L){z z`3LhNxa?zUyN>$o`W<}6h=D0m^nk>jbB?qyez{8rGNonQPJ|v|Xz0gbU#1_mdvhyN z9(;!)Ay3|x@$&6%%*%R?f~T>zWiDYaCBG=6Lh#s`nDOagI_7UvV`TI=sVbY7>Z=Rg zzmh|0j#bVdKTW{JjhjwckgUGEHV~;c2sZUwx~;uDPc~5DtMHUMefYobhHY7gL-6ds z?nZg-`Mb33_<{OcVb`QLbxCr?=f|=d*)+U=dhBe}1|qEyPo6CYdXpvCdb}srRq@X! zl?9ORj2if?g7rAnnzdg~QiSkI2-d=(waZUGV%FE1DAA=_wt71c zR(@B+@i|xYr=}}8wp7yiqNrF*x5QoVR*eHaWpTdJwCeApxF0;a!xhvwoE}=2>8X1V#d3wG!YPWU!vGGZjV(l28H+#HdX|U5`XBZ|sp@nyQQM`L;9?ny63f-nm_k+{cc-uamPsjSCI4!vD#?|wQ5XQVoX(2eis(l{!y6^^l8 zjzZrmrc=2D*%LxRH^8PuZ{}CG^7{h{=xhTiAj*-u14+oUPlTfVrCSntqg|wjDqNqQ zSOz0Z3R2r41)Ro4m6aKj*#JO)@?n)tgN{%S&=1>9PkB4#&wWoo$rgmGD4z@x+cLKo z7~D9V84koy;X^d>rs_#suVR?@C4d7YG05wqAq^>V*>*aYrLPLeyHcybmVcpLFIYYX zF6bGI@X3SKJpI~0wWy|*fqXI#MROo^4UXC5`5$Lp1&5c?G3!(L*GSZ*S2QD@OFB6= zf(PD5_}udQIJ|_p>y#x5SfE~?Q0SA#qReTh!>4wTc%FoP(felP^ z1^qH*(f9%Nc8zw*JMMx5N?V^)?cpD9Qk;Jr#Z=8Lyo(sxq>ZM+!@!u5%^UITlTTEt zH!Fj$LdLp2NE>5QViba98On|joK`9`uPXL~MEA>t*j%l6UFh<@LPv^*l2mCFLzrPF zXDm>Etzg_ronsWme#nX0>wAInY85PDdSJaGx3L&|0L=Dv6AC6&syhR++Qb-GYi0#_ z-pjNL{)R<=ZdexbL*+Ur(MHQ8cK+-7Mq6CTF;+QrkOByOjuN5w68BCkr9*A|CTnuz zTp4vDbtxz%wsz`EN$q*5W7W6b`(h`9R9T_}yg5+jpp_m3x&wsR!Ie9B&>f%r6Qrkw zS2i{W4jfO%gbj^%*8eVr2tEmSdSfs>$Y{iD$VmiUC(P<9E9NTDQFHM=o}*`UPhVIQ zYsD%1Q+#z`pt`2=2&$$j|Gf41a>YU}tTx0-e}!C{G`Lr6ky=2BenkT_o!{M2rc&@9 zf|n7q4f}%S_CA7L>~`(QGxcxC*rOs$7`IK4MUmTuJ20Lio452ufo`}B++|8MhVubI z2R8SG0eP%fX7xBFEgM4PM`sF^e5PB$e%;Npt=WN8iw$KK#KS)<2@Dru&Y$1>V1!f_ ze;ustUtQ%k`+EYM)6^|+?KCMcUlljqzs`VV=;Lqp-}NMhZhiY(`ls!${fPeAoZy;B zgZkgX&AWpr1KpC+-xG6uDN`Hla$qlXy09q{qkp}zPJWi)JSUKzzem2^ukogVcvAAtHM_65VKtq&#r`>q6z%iP*n&y zuC?Ac*6)Z8h|T|aK)AH=ZE1@dtG0>Wr2hru*sykf{QV(nT%&@pWR`{H|(xFVT`N{bs=1!ut>eGERs_elg_{n2oOY zNq@!I6}Ds=bH=_e1eMaCD{YCX760C*K!?$#^4#|8<#c^vB5=JXA1Y!3KZTqnjYG7Y zjupg;9J*qCU7)%~LrehHVJvm=$g9cnFO2NMY_7YZZs*-57k(4G#BUY;Ebi6Ag5)}P zjYh_~qCcwM!)&|#-+Mba_?chd@~?F2qqcN>I$dl1O%$?lc4F~fN+^2J8S2m#T zv;A2Xi8>E0xV_s+1Cs!6Kk~gAK}mWs78hgR-0~*-zQY-yy{dr_lnd0+&;{V z1Gd!W&)OzFQd*iNQk{xYaJuzwbhOw9Lo zX#_EN%uDvIS6#2yuVe!=);nI)+T82U4>#lZcI-X+@ZVB1kLaPsT;};0&g&qwH>g7@ ziW&qbz(^;qd<;8B+-K!F|MSdw5$clby@1@)TTt8f8lKUUbnxb4*XxiOwSPJ(t|a4n zW7prS%POsLr`UenGUbAT>zYKn`feS{^NTu5yW%%NoA`+E$LY%aPp9h%eX_M2=8vt1 z^iNyQ|FdQ;8P$ofOuR&>=q<_T_*=jI=R*E}dz0LKI{?9b24#&HY$*D?snd*+=;n*m zmvVhP{lmLq@aerz@Hm=2Eyk95LVN3}5BEQ{M*&JMsr3-vuC_A2e`x_AkT)p@j%5kN z`@;75I%)crH1^CE7(x{zsBDfBqd^;(40;>$qZ(!@8tZo=_wGNu()OPE`1MhGC@V?t zQe4#fB+`yd<7=RSg_C?T~7=70|sTFpoT2_%)mlDi|29QrBE0 z;8GZ~4g;v3{HOBwN;;&1B?H!hjLxV;gZaUB3XqGR0uIM;7zGIZLR#J0>M?Lo=2r6v z2jeMc-kUhh6M4Z`EU1jU9^;+)v91okvoi9gmTch2#z&81|sQc7KZHk}zP#YCi zz@aP!V7<3)KUSRrK5SjE-io1lD#(Sr{TtYIwxhYM@hXej&>&21O5*9|Tr_g-f3Wx7@mTk7A8_`G%#7^Q%E(H}=p=iVnH3?UB(st&Gh}ZS%E~NM zq)0|~C8C66req6+c#hAh>%Onw@A+N#egFCV@%+_zot)qK`5edlcn{ly-C*rdsGABh z1(ajX57PWY^sz`CUZ9iC-~nY%439!2%P(-r<Q`ba7eIRQK#cQ0H3U>5g|Kt^-wgV@?2a#gg!g;<@isv|eCh4jQgrIE@ z=BmRMNu!p=eiLqD-wN_u^T#UO@n4P-NZ{b4qAf;k%jaWPX9eNW0M++Yx-b*5MPZ3) z`FtV?@fT>tj8_lc)WE};zea4&>R!cBHrg9JPzhQalS|!jrj5F;2PxdIR2Z)4I(xA~ zr^G{M5Ov*4;wSVveM|+QBfw`mfvCr+aUsj(fn{+W$)Qx!d`&uVM|fmeg9?flx^)zhb3Y3 z3MwakfI8v5XHHk)${(Fwrr!3WB%L*riz6=7=p9yjYtMNCQ1I$9cce1_B?b zYxCqiDF{A+s6Gk0;Ucycy2FIMbg9HQxmmG#SR+SXTZxKQO7cQ|C2CrZd}KS|OY7D& z$%WrWcYI^io_<^sAxvtip$B04U_a}{Jb28$4^wP5gkP2k$586L#7Km55gOP@(Q}u2aQnKZWBmg_TYc&aT@QX`| zW#)f8>Q;D{^D(8zme`+;>QsbLRR#a6pC4@LnsRFtXZzz0Cp^8vr(T-l&C_z6v zy3(dVe{O-dW*?!@y-)2wAI5I7AV9x@GdOKwGV##F`3(`7%&UK4o{JYUUXAJ!Z<%X` zcQIqVoHnlAzl5-^H`{|`t|jvz)snl3A@@48pIoB`_79_ob4KdO?T+>ZXft1%*_m!t znYJAPOF7wHgbt&$elAfC&c&Qe)cjx`9MMG!##_CFRq?1{1>;c%sMIeljL5HYMX5Vp zd1=^86pWamNbsjS-4tcnL()a&RPL(&_74DgdoIQ$8h@=n$Y&z(%)eqSc#}y{=G>c1 zA=q~e1Sk&yK*5hB0*0 z1^REo9{%W3Q=rOJZ5B{XJCCLNCGO1ui+qD9P(=gxLMCa+rc`09p7uE3R4cKdpb0 zOQx;g4i|d5KQQ92_%2-8>aK)65OVhM9aNh{i~idr=>+|M*O}N93`iUr-g-iXA5SXJ z8oX*#Um%Z~jdJA|Y@;brZElS&-oa~UiN2O4fo5fo8!1hh#a}Ra8QF^H9Nnn0wjblh zr#;YY1X8*-Q$D6)Q+!g>3BZmPn9J~k0XkAB zO8~W)z-rnugs;)9pY}zIs&zS(5H4C%5GIxgX-cPo3vZ|8lOqgBxOozv7ClB6?+;!YYa&6V6%H_hhc=Cb9RMiDJoEy#RH`+woQz2$$p#}I{%^%p zq5u)#KHE4hZw<=Ly>^}2p|pkpZc$lhwCL| zQPMxOYokV%MRuYzsuNHb7^2Ed5();s`f6Pzg_P*I6On8mE6#>4OJYxgwT7^92_N_* zB?AXXxQXx*fw^|Nm?-cY4K40w`_0SV1XJ0%AH6z3G0L^!PGF&Rbe+*Bas&XLk~k1 zEUVctin^2UP8Yv}LN$Djjh-BU{1|&6tp7H75g33plFN}VO-2BdLSUCEC+(!lvYHfa z9)Y+jNVt)R87yO#$p(FwC$$jFJv;o=sQ&kw#ni_P@RHcLmJhexLfE8C5ELKL25U$z ztGxWl>vP9GJzUO6=rn0I5_AxUxz*Ia{1v0xoL1lc4}Em%aoI|28{u!zcKVK16&+$l z;5DRkl$8GluzTHqRoZH{zck&l-e30p@@ON<%l3zRAiPcR4ZhWBDgK&KzUEjWkx!)y zIb}fI3Ye_7qw|NYRktO8HFs!cnDDSXhrCp*Ti(t zdMfzDT?KD`F{`?wkY|asF>&6JfSqXr;Gfzy4rMumbCq(1Oh{wp6oo2*2Ww}ziV$lsf!x?09%Nxf4tw%-*C0pB z+N&qeNd1J-PN|D|q`OT*Cuw4n-fMhhdC;z3rDidV;SkBYR)o!9w+`ZRI^ig7Qsl zzMGyP=e!9s9`caMeGn}JoJEtDBvx$D2AiEN|8nsiZy_x5Rs(I6n?EY{YhREhWX}+d z=vyLzk+ug;Uui^YZ^$9%0g0-0PU}ZYEgZqEC+5}mSd_b;5ZCQc-hdapKd}b5paz^b z2I%Wp5S0-P?S!|9h8|~ZsRXTj4E6p~k}Y=Mx;b^FC#BH<^g^)9tNoDy-uw0v z%h?^H(mm2Nb(xR#sPJLxl2(uB1M^paPs`Yq2s%rY-+7AmS$Wu;`2ZmVM&h1Au;vXG zR2oAC`-1gH7rrzORaH6u{cprA{FL?XFFUSp(RxeX5__R+NK{oJ12Etd-C~>7WmB^v zzsn~(7EoCYBkWTV4hPn`ftC~?x7yDGTYmlIm8OO50gb$o!oD+@8X|5dFUoG^~oBoF?YT_GT)S@p{J+1BVm3EA2ZNP-O}_!so_reshYj7 zHXOwzv;gFr_!1xRHt#H_DF9~MJQ6O0Ql9HKJc`d=S=h8IACtWE*9H6V<>qI8bitx{ zemkOy{J3hh=tb;W<9@24zLpzjVj7Td2AF!BYNPW47q`<*bdk@W?U(GA`fGIjN9-PX)_OXxT>yBj_K9S~ zK`8h-@vj)3WRU&mu(|hyAR7x$ic~LsnYq=*Y&2DaCx&;pRj7I$R2pcc-}t94LNNDU zW@1~O{py?e!fk-?pHMk~XO*M&Ec9UZo`Gxk!|`n%-9N+7oK3DB1Or-T8lPgRjKrUQQ^oADiZUrh?l&@nrO9o#JK%!Ig61p{k1lBoqt@>mz>M z^h%IKD~RwcWQLiRGOfoQDO3Yx(3S7+U$2}7kz791r;=xzh%W%h0EQb~cX)0}Qy{WI zZP*{O0kzq`kqrh)3t-uAhip?U)RR@J2?LSpFz@O&c!~0B`90M{CqYA#h&CncxqKum zgiPS62(G{cqzDBjE|@S1aTg!6q$t2ol|TF=kfEk4y^m^`UVQF?7>qhim-eCLCLl2DD@q}1Kj3)A7TKsmM*DjN zr>~~*6ORe?#aE*AMGjaz0o(~2nF!0@zD)4N%E=v9P#wx#Y$tg+uc3OVl6RJe{<3LHhLHrxKTf=)NSiV7H zKDZVp7YA@TATB8=rW;aS%9mkq|L%r;P~_+XvV;Uw&~;pN&VoCf4BX)+A~yR?n0zvf z*--371Tl3Rd4cvP!^2B(2aGplHN$>Bo5!%58JlTJUHM=;+@S}{!A0qAt}g}{7u`%k z67iRy0p+{4y_G0T)YFiD&092~!dt^iFu6|#f=5aD_Q0*ltlU<|hKs>cpxwAI__!E`)Orz#P%#UDvs8Q~E+HCpFi?V; zPC_g2(CxDVXp()P)J>R!2|DT!Q)w(}z!c_Q9b>wu;S@}e6>_B z;t~3V^}485Xm?V*NQqlDQPek|9n^q1B*QHQ@9^Zk5!ZPzN2+Q*w_jd?Feu-71Z<#?@~z18iZQLw0p&w# zgs^(^rniM#JgF@&EqgtnkBr^HbDA;=Ou-)xrIO_ai)s&ygl&M{yRcdsUO~~;{Z!uK zw9XKnZ21earV60TSq3vIZGbupV2Ez`^pXQ(4YeK_;nT|B#W2}G=CwXR{7*?I3d6L0 z89&3TPPD`-^Pb6~EJ0C1@tnSxkqv&bK=@r&sebB9oCX+)OuKh{=VKK!uxCF4$_#>+^S#;XFEn&BH2j58qU6OJR6L?jd++$fb& zCaG>p(*-lq9>?DNs8bO9NXN*Rz|_9}>Tq`$r+fPQ-C5nm+NTo;J1$^16^gn(acbN# z7+}xRwi~~QqV@f!T1~GW;IY95DPHwem6Nb_)v;K< zyWOZIm3d*nLzFQ}-IDi#R{(wsJ(LkniD`w2e&09ENVbL#mu9=p^AM5}4p<$50vWaZ zgIB{vZB7L9(#AX|wJLq|`3l;P$1deAosKO*hk2rzva7&ZMievRKpdGwG&Q-U_Xk)b%U`KS~y) z-zc!AE_qNSzVPvy>N#;M(a>j4mdxiXqAnMBd~#ZDZ>CFE3g=<*EZg!;P7yLVl^rN4 zxgFf6l}m?l8rzIRn5GnMdsEA8n^7w=%e@i2h8|mRxu{RaA7kl}rge7RV)Hsu`{*9j zqgk3;<;Hjz%kqSj>!*6rs#{kQ9S&bF&i=5L%)RXTTD#Y-UDX`tkgx%_nlt(E^iGP9 zib7&8M z=fw;sZKmDGrlxp)O_fqv$eo$PP5D-?cgcA{F`4~YV8NNrXUkSIEqU=yRXbp zeK0`olyJHzx3$~w0m=hElFOxClILpII$LyhIxmVdB~53)=AQH0n<{-UCB@WQgfF!1 zby7^>&uMu&e*QH@V)8)d?tHyUG zz`Rl~GNX}_0E&A#!InGWIve9gIL^JHHv3)pdfqAxr5Jb-Z&iL6W@MTfu{2r+LW4k$ z`=Oqn-_qrK3qCvgjQ#ST8D50b*12Eez|i=0a3jFH#{W5PO_SoLj9=93<~C*Vh83Cl zq02RU*^e2~MHpMVnNTh$cTc4q{Y0j-Lh9B*#Wlr9rE!Sf=aW%D9ww%LWaSUlJ8go%D(FZ4=n% z3fo&L!nb(vI5)YqtWHl1};jX5{y4`?AWwP1tBAb2dn7q1XCL%(uD3 z&DeFh_7L*l{N}xUhSgUoFKp=^dFnBdR%cp!L+bmm-mSh;ZkJ~?Ns{FZEA1%?uit6E zUpqO|IpY>c>wOvg>h5ZGZF&4Y#X+eEZZVCR#~rC|;PA zw?47q?~5b4FR0}beGgEa&)o|c9(An5KDtO9Vs{}d;g~g3uX_t;Ic?5M<)v3P*g88M7yuNck%fis{8QVyx^45PupI_ z;!kCzC)n1CH~iMVcJsBUbQEZZu1Wg1OaCfb7hK(I70R^GpTZZluPf-#VcJFtp1-&N z_RcTf7?xgOzNt_baU!G2%t!I`b5os-_?u!!gj3UwZ*N&Bcu$`!{=8wt^078=`LX}+ zUovX6>bh3gYde><=;-{%A~cAGZeYnGX>ep_k9R6uO!IN^$2TG$&m7h4IP5TD=rdla zVZWB!KeO;MYF|fb|Lt~*RBfGkcJq|!sez71N&I%F`}?8EbK?&A3FP-kPsnMJXex2><{i7tx$(&l5W zryXAaf%PiEwMc}lpMCWtGKhs3(r*s{QuTwKjQ!KG?E#?vv-I8XQpp{&%?)ENad*k7vCg|+I!W-XvR3++3pXEmSG{8I(V3~*R;3HCzC)du`bfQf*^|v-&g*z* zGY!A#P*O$0j_2pIRoL>i?TCk0HuP7IY%iylE(gw)5H666fOq!7wIm{qxGrmE@!}T$ z#yZ)49*%s{FruOIH@}zC8ALNQvbBHJlx?4T#KXEsk4s%XRCSVKl~dm1^!4=(eHWkQ zH_1FclJU5c$5xYFUD$*dNN^-KdkYPA0^b+kyuu};o858CAnAY>4_8&u0{5wv^arUh zyXL)MC|_J1+4y}A4Y6T&PBJm`(KFBd)o#5n=l-pJa-X-z{77vfj(eg1fyhGDoDc-^ z=vSf`iQ^4Nt8zL^374;%rFZRE8CyK5Sf%j9G8MS4E-&jpv|s+X*m1+TVJK|QnzUNo zA}GEb@IXrLZQWctGcJt%SkwO4hKes1s@S8%3O`4QJi964SX&L+TYvM8ED+n4yJ~zA z;&i5`V%|rU6^mJ7U2LseGvwBg$~%|*rgLcGG5j*ASQ!gWSOnjw3n@RdVG<)9`wI3d z8#awbg;(CnI9!n=1m29PhrWy$t39vq7|{K*hUabUFaIG+oj6YYu{M(A+lQ)xjp_H2UyN{L{zak0q|I^_DJ==CR*+gu~h&d^URJP$bYxLTpn-Owt4<%q7^gn23j6p zp_IcpBEK&s>Jfnr*54rriFpVXj67EMNq-+qvqW$4vyMG>KNQb-nLhX}k7E3FH~+t; zar5_IjhO+tp1qV+gW?OEY~rXY-3pu8BRK9U{il|-_ zYxKYg{IN>=Se9F59LC9gR78t{D48i0?den-c<`XX65@14Kf86UrRM1bM+SZOafyr} zPt40`flE8}nh#pniJWfVp5w(THjVN_v95h@SCFG9NH+>^V$OGfCOD~1!e2d))lV@I zKe)4LCFVSb{iZFRq)Kz1yvW>AlZ5#8dvRHZ@g4%z!H7pyS727+si6gPh)hwz0!mhb zk-ePz!~V?S2){S_cU>hGn`hxkUyC=j=hf;A3G8YPPx+j1VJ8HYMM3!iW~BwtXLLdH z>j0CaGzJ_{8IYiM3bK?JOY2blL52HkP{ms>kR=U0qPI=7UdC zFvGMD8F49;^A8~m0JOSkuWn20!49(j)XirvP5?1D^v_XU;j(Tzz1>AtsM#w(sgsmK zveg<)^yps?iJvwUk#`UmT!-Rs^r}VgVeqx(^!>_hYz>lwe7Dc_pebkN*MRX^XxhZz z)CR`pGOkBVA6PCUuEdMHYL@)3;A)f(DsHKwXUw9f`9Oc13~XF20A`Taks*+9?{@b6 zcEERp0U7^*KpZ?QJ8{Et|3l|b&x{p`fwIG>g@Y~_NKy{Kr%DnsI$+#}$WFiyN`t&i zRUN5UqxJ{7K?KhSz>G2R1Q2LY50BW>uj*z7ad;M>ob)ctbemRYJ%C6n`^yoZA2-)e zY5|{#B)L=)IH0BiXijBt+4drR{k(O(zd5v+0+20`2Gfv(dW1M?7^Nq*ar&KDbl65L zoN_x0B>bF&8Kt2`wBiZQz@KMVEl!}B8<@WyKv*(o^h|$gsh2G;Yk~_P9>^nD3osCr z&M^Z(^h}YcR>CUG0hWQ?)Co;_d7Obf^4%3ZeG1VYBGqz~!|lN*H%ZRZ$@46GU}z?Y z+>NXlXlb3Zme`2m_>LE*G0V`*v;*se4=6_{ z?4upbj^ryQ+)|QZde)G7@7Hbo)p;iI*VU={HGNff<+a7K>d4x%_sCU+g1Z4f!`eLo zhkR9v*SjoaBGWIx7)nTvR@0rOJ5%rPqsFeVwWw0nP_Ca7^4O_g8|)PBYPP|JL;hiC zJcSe$Q+e?UhA*i0ODN)5U&td3`br;6sCcdcM3D27%>>LM5FArbtE|%HrEvYC0*w%yb!!g89;rT4ZXx1FqeIEaiZelUR_5NmJ z9GN0|%p8+O6oV0Zk(TMffFEh&WgBmzT8>7NFx8KctJ(obhp0TO`=i(4Yk+)a!H_cm zWcXJQ|NVOng*3y zR!;!zSsaOp)0?@uF(~p85hc2SaL6vzv*%_oGg&c^_c}x0m0KTI8pXB0fm1IHB=SM5 z$H7}9%*ybWn(;$6%Dx-n6u;KK|R2C=j! zCi?#PnuDRO4i3MViw8H?cfn0L;^5N4_wA{9l>Dzt59g*vu8q;EwdCwaGE20ocOE-` zQ_|s7rYbPmzt?%kCv!;~G(O2O?(6vpwkv&U4?ud*5z8jsXCk!~ODs-< zQ;c*wL?6-()3%}7rXxLgh-hjdk`AC$1DNmMHOMTNlBX?Yp9X3=f;&Q`-L+MO>(#~RE{VO!k7p<$D z61aEY$eYW945ZB|!2UHtL`lZdAfuaziPogxKh@Uc4=lI3O&`abC_Ec?=lox6T$sTekR?_>>eQ#1Y!dMVsdHD|!UHnOV`ZZn zc4!+iD0;)pnE8fD2p7oflp_NO#u^5Oo?bq$_7&`73gSkorgz_-o!z&`Q-bh(eV~pZ z(^p}wJ0g6bXFTu}X1~SHn`(mBLCTZO%gHgkRlyvq+U(DaX;pajp(#^!REc<$ztKd5 zca*KrJr(F5S#L=e$j6T^N>|?)vu5|aI4n#5z`OTfo}`$Df>5KW?)x14E;rRKEq~BT zs`VDQ(>wner+LXVQf8zFAeKzOnx8Oy&k?JabZuKT#~vQI4#t2!UuCZ$_3?eRQK%Yb zh>HO(Ej20!0;336U);Q5eTcr*DpS*8>*9UljZ}5~+VEkQiS8*wXc{M)X0bDyczkET z?UrM{xI)WBqXg!94{(Me4i4);n8C`kaR5I5Gmrh+Y@We_(ah{sVp;W*7~PkgXAeyC z>KDBYfL+-84RZ=TNV{nn2r--*LC?$WJr%51!)Mn2i|RHqq_S}M(HEA?<+DN~0qoyK zdndbqPb^fa&9yEK$wK=+#6RIwh_Xcy~j>4I&ud4%g@oGbR zp_bfb%+V&g+t$d@NTqx_O-#s=!IF3OKK1xBDX8c@KFur6P`*?kERI+J557^hV8Dz^ zC&E0QF>Oa{%OH6|y`KT*QpH60o>NTUSc!p+80!853_f7vY%?m9`o;(k5+h>_JV@cP zkk2L&-2hAfsj^Yn#^u9^yi&1fVR*I1tFux$VNM}Hd6@;EKo|$UEj0p=_Cq@3+S&S} zc*%$eA(mZcgZW7g8)w|%SXTCy(YEf9@*;(dt_)Zt1kg>`a-Os=ics89X5*R0)_GnL#@9-%lD9FS&KaMn*;v!;DOPAcCG ztJQ)}99v-QCHG^M+~0bn^{=qExw3XYaT)poM-dl0Eo0drcpQjf@Lgv=ddG#5#%!TE z#k6ePrd0LKQ%vk|(EYWyi~~Om-G2BO;z>H z2CB;HdSfUVuYC8-!-X4c(IP}#TU57Io6Z~^={}pRsS&4|#&t9*td^y2h3&~1E_q+6 z-pd1g^l_(Gb%8-;axGiNgU2v%fUg%si@fp?Cwaz}Wfy$mCxHVM_k;at)D>`S&_utg zrg-RBPSp;n0B);hckF#d7>C52qIRbL2GfbyAHy}$L|lG#-@{MxoO$kh1RZ2A z6lJ{qlyEYi*hhpwT`wS1cncW zOmdj)WebiVdh+Il#gV)pTsSLEUAms^3_}^0RDqtzs)J@Lc^|`1$#~)}CO8PWDmIh_ z)LG@+%J+U2=>&|^=kk;#@Ob)>{s!MW?`&S1?u@-45B=`54NZo(4M=zIO#6V;O}@L5 zvCFK&81c;CK)i;0H}I8beH0wuV!KyB)9RBAN|b?>I^gtWPeUEGglnU!Rd4!mC~pMh z3O?C(^oO%yV);FL8isP~IC0QI7WxlQUYrz%xP<9nMFx4eZt#Ad^HBg}weA&|Z}?=# zvm9<+VJ~djPyS>N+Z5!4l)_^uG~m76d9d6&8-m+LR_b6bc4?yZfL2;r7|hZdSB7P7 zbICz&L(=pwsN!aC4uBY9)@OS>THLqu4wNX0Kp`P70ZnWlaBq85ph`3Yr<8 zI7L0)YfxU{WL{;;zFVmSFRkopXhD{7;-`udre)XM*`^?%EEVC;|j#EI@# zhc<1+FB@)~-uRuZ6LhiDR{ldP{@afOlLWj>R=w((ol38{S#9d1J=kb8(uH7?6x>f5 zX&l?sgsj*T)eSf@9(ifq%NCCv4f3bWGPy;q>STH^i+o8)6EUa%Cd+iKh?$F^?t6Y`fp2bRcn& zu3=NQT>yWuWaetSU;Lzq+5R*9w?sBf^bYr4rX|9)!BKCKlA}MS!Qt0vbsYa4KKb%~ zYemyvy+m)-iIzX#D0!7Rp!1u_h@xU-r3Z)D6 zsa^(dZw77un#g0CA!9{?NX5sPhIa%Z1TS)=%p)_Q zAT;MXW6lrL7au;)2P6ctcAPx1Y38f}#+LbF-1`COp z$9)5lq;YdC9z(5Jv_(X15`Lef_BlS+^)Cmfvk<%5C9b$nq&*VzM?7-tJh=BE?VH%f zM&TIdf z$t+vuUh4@Z3!{NI)b&#UfEY*H58Hww#uWvb`v2(B2pJj%YHmrk9YOr<5v4s96>YEI z!1ik*Z2^=*B`Nn6oNGbbxB~3!mGo31O-inc3>EDfXMlWA>?;kmfZ+p6S;lGoYG?CC zmt{wl_4!XEPxMSnPH6#zGM((Gcy3rGp6z8Y$>43^db2=QAP?(LKQQ1xB;v+ufh|&; ztCQy`?gcV0B*H z!xKatzqgLE9>C$GfbUy(T63aHKI9<{ha4Y7 zY#0zs9ZHQ5RhIE2PhZcOeShCV2MB<+u|1J9J!Ta)!8fic>L01L;?`%gqECVBEE6?W z><4g_?OWp$S*-M=P^GA3i&T2*|Lfrf6~QMgYh=8l2nM%*V1$Ha?5R?MpR+3Oy=qpC z{w6yjadKPpQBNgh4yXoA!idO+%4mbQI4&G6RPvhK1#Oc5iILWn%TXwo1sPeQ^&Tbr zss&n9r7B#=1!Trbak}13X~Hj0U^zhqwOpr{MVQkV9)zVZ+q(TpE_~TzgCV2@ar!h# z3A^a@V>2+$CzWyJn)}AZfYov@k~DJPxMBj?r3T)RcX=@b4Bo2P%JnYqHEp#-j#L{*#9Hagzc(61nwZ zY{6|`E}qvFz>ad{osGZ^+#~5d0+v6T{SyqL#1Xs$oJzAYA4~Ofl&?m9&5*laVcI6u z%A*8|rnXv|YdJdmj%DjGcAYZ^2bgB$m$*y2C9&fIY0q^kBZA(aPJzHc?*RH2_3L{v zR+s@TDU{a=HoA{rf!U@@?6NL~PXpI}S1Gjb{UPGk2tSHet4}ww@MJ@}k1u=@CLdJ1 zy&n)e$3xhIYz4ODb_HrQFBR&@Nvo+@JjlUbh7IT#+VMPjXH<#!a={s4=4CP9)audf z8%))AS$3Q-r2nhyz)~jPRIUS(VG6&0WmIgQC^7Q<&Km0D`-aYazgJ3<>_Kx zs>+mAm}a?4@Rt5L?8CoPeJmrvfRb6bUnBWngkEZY*R;v}pEYg&JpuHfA^fia;ONmG zAXFFL)V`zeoT2lkep=wu_QK#~(7LoQ??ndKX=%Aa?Bm-yT4ML~Mq^)D`fn*+5eWSFGj6{G)h2LIC_(0O5p7d^_)@I$nO zUB9mVVsMEhV%G5Vyh@V)yukaEfr~^KJ;6vG-Tr6rEPm^`tHE2r`Rd7I@K6<+GydvD z1V`~xw1!Ijt%CEOEMxj$N7~WXqrsk(e;%~|SqcXkRZv8a{<)#Vj_>_XdI5?2`vaw& zDe&l+crod*LpsMhf9QOyDpnt_3khD!x;tXmMoFPiKYIy;L}I4yQm=VoGc(OLwQW<}nFU|D}VMG>SPi5(U;g?A#K-#f0i6La+P!?#me~ zBS~d4AqBMjOSjaO#p8_*WWRkP^^?_+tI@8VJ~Lhs&Due9^TS@o+L)7k?4wzYdyb-) zoWB_g?|Iu^Cs>jS%2NmaTfQl3&_n6reIX0$F~|nuIt|wYH=?Ff%OIxeg4#n%YWDqc z0gBoq4I5eDJk;DVNFM79P^3oze!#t|7Nn}8_bJg)M%67-kUbZ3V@wk{)t%DO3`gQ4 zar}!~EDpQ?-?Pp>i#R(AGz{@o)B;K2DMQVjN#kN-h*|nJrovT(RJtLX)gN~mm%Q1Qkg{oSegum z6YUUK!RXGiU9XutCT`2!*&W5B+VIfK6nxFx!&!ej5yO?L*_HAJ&|&y{%<8-=Py5>) zdI3au)L)30RVZ=-{;;3mu!>Z+_c-}e-_;VN`%waB{*AazLC|c{SJ3Z(u?fEp5CVwA znm;pZNo}c#sQ!{Q2*a2$eWyTbL;XDKSS;K-=D+TphmzFZE38MI1;OV7KZ%9`uK=2P zA8%Z-*`ms=gcMLUK4c*V!ck*so6ri?X}pPpFS8Xj?JZD6YQjYz=8OdZqaAiEd+3!2 zFZDigv)0OztI{x+b{$TDUs?JL5~c2oi4B9G65;Eq;0CY#ZJ;vG{#Ay-rXUgFP8XU2ZK)+IOaCp_wQo<>*tceT{5|_*;f3 zZ(!t40e`*oB9OwF%^_F^$mYgqV%~|QP<$XbUk2wgRm1lv1`2?|Q=GBKw|}aj001?H z-a@ek|^{!TZwL@#Ad^ z05LwOzqAAMd6P<(9=ce_o+`yf?tnFR;rUH^9IH2VZU~${&s5@9C{n@YBA?Kr4ynwS z8~hAFOaPB@EDt;U>K`fV0427Axp1l_X-~spZ>bo$vHpgu!n`IeomR@ZXZdd_rL;ux zU>1Lte5V7&q*V);O6AxNYS4}@8N1NJ6Dz?qVCIa%a6!^21n)%rV`B&QT!YWVAUXrmnk_4=A4_U7k5xV_h zNsjv)M-6%!d7guJPxk&;P!O2=9IFr|w@9gzC;Le?lmeDEbfP_rV&H0F1QUc~QwBdF zMrsR;1y2Wg?;m0C=2Miapt=YnMx++5IzmZ4k_0*d;iq--te?SyeEK&$2$*rj?7)o+ zUB@s$lu95q!3x}HaG$Uk3*Ixwi~BMANgGxqxxzmyY6Erd5*W@E2e~+(SFR%+=T#Kj zn;YD6tPX=2=7c14&?OMkWoZz#4X1(g4QL_nRm*V?u#X@&n43JTs8w3!Nh7+%{oW2V z?853qs^l+;ES@L^VVTDjXu&(i7=wv`Tc{}BunD6&Q-Vp1ZQE6`R!1~rx84_Z=8`Uh zYrn{l0|~5z2le|(_rlR_14vY)(Bd3BLd#0VGMC+H?29HU%t+ zB!8{sv=q5H;;e^ssB;NIAg4Vu0ft%Rr)lZ_r*$2rdp?Vv<59ZIZ+1IcwfQuTNGx`r zTEp9=770Z#>L%5W>s9^x&4IYFOxP}7jWL`NbIl5w4z(yGTu|~ivOp?16Hfw4UD$%; z{$&f2|Nr2AMlft(0PzZ_`Kyn`9PZG|l*yTA3!b;tfy$L-?;D#%iNgj*KR_O7@#1&N zzsv3_FevNgOhSate8vw&8vr#x_)YBtb08=cOj!PhQbFAY(65;TvoO@?c{FBY+>{)A zyKNr?pa2tMMW`5x8@#Q-NAsJFSx}!$={}zs)&4->GZ;aAIyc6Idrx;OFkO&-*@Us< zl88DMt+%~8;=g{_@9zhUxGd=FjR{pcGVCJ?7g&EBOP>XiAoDtRqVYwwK@Ikh*CmmP z2_OgIB1Zlp$oH1`!ifJFQ&dHlJZ+e|3Lo~S9G^cqs4;x@^{q(73cPkCWKM5`?A^%NiK3tci%}zy&x=54&YB!SExuD<8f~U)af%Si|M-Cor1Jf!7Fs6Y&(x5HZ1~r(cqa*~r4)V|zJ$D+i+4tAaOZ1$% z*%FI{uX!eRZpnyam;jwV;_+bAq3~sBY|oajr9N2@qpIkK+`s48=JE*sH08st7oDvk z4j1~*2V;1rk>8c^bJt7^iFtv^cf$rz&ms;Of_n_>AEy7ad!H(gy!^w^G~3V4_6rML zbaS~W3^aNOd>*YO%IT0lWn18e=)v2kAod=)()QOOe^{VJkXRI-1M^uRZ<%&~2a{hE zO#@t@PSDyRUD6Diiix1Q0}x?kR-6yor5PU}3g&~Tb!KPD4XoyVX3A6?SFMabt+uW; zKc3}JE&6vtJ4lEA$cSf^g)>Rd1w3ZX$VY|oVLL7)bCJH-m&kSPIUl$i806;wc36^h z`23r8fGnqAq`wTJK5YO+`&OVNz&qi==MaeoC}UB+fye?!JR4cpjB*j4n`Pv`{>~q) z)U#E2U&&=(yVo`Bst%ssx2xC!hVY$j-SM@=sy-2xV^_;I#9@O)$&8GJjjF_vio@8^ z_~*TObkcH%oKWgg%Y&abS%l*wh1lvmCch zf?rM=23&SdA03Q%``1I@XziR#4sYA-Jsl3_=)m`s8n0DC`N~*m0HyU`KL#E?+8v5pz^^vLY`)X+m3j$=8^+FyMY3`rS~HBBM1p_IewZN62~ z0jKx`faJ*j^v&*>;B;M+Kykd~82&lhU0hIPrfReL!BN$-yg$nZmry@Z&eKJL{P%_a zU=7HBzw^FP_5aI7k|kZ$?#=M8hnME(|WKtn`kTw$Fd;2#jTEeC!*wv9@ zJGDfSPz+FJ@Hr21T>qv&1}ngxrx(4zX(6t!Z0R0uR*m6 zP%GWldl76{p&00Uls%W`#@KPZ2gBCF5vIDvxbp;&B287OKrS8J&&I^8Ix+WbLA&;- zDF694=bLD3PFnacj&idcaw-$akk)y}q(AGvYXm2HwBg@o5)&bgb&JcT4}DwGhs7Ln zMwHJmR2vwVE#KSv(Y&7X;KtOx-~>oLiBaX{8OZ)37YwrY^bq6U1DCS~wmB|FECekj7` zk#N^;GKNo~q!E~TvZQ1PSi;5_6l ztj@Pl?v<`*0|Zpc1liA;J?wM{{v5d z^S|78TVUfe7F%1}k18gPw}^^as*c}qe0=ePE&@ehijf53%?{Y33SjM(bRCvKQEi!Y zRDER1m$$ckplhUxy1shm20uN)9sKoM{HUdz7|bEgQ1tM`6V(4kANcJ?7FRPjEX!lk z?9{DpNf!%+uXdh#EMgyW?$L!HW3X~O^|E;=uM#jF)Q?R9gfa6AjPa3HdgeJ|$~J{l z_LCs~c?kqNY9NLha!~{iqE2A69zs*hy6 z(q-tVS|oh$0r=h|XgRe{ERT-Yp}iNlwhu;vz3w>(5;@fkD#u^nx%yHXB3<#Xx-akF zAJih+DDv*sj6*ycagiwpnJcp(2O%*gTxzjwMMjz^r5klWtzlj3*6}K-|IZJUeSPiUHWGDlCGvk z4VSRUJ&>6fE_cfp28NQ6a9+=_mB^*1N}%_)M7R|W*~uDA z0S_t6R|HPuGBr{%U8XZpZDRu!GlztD53uR=qp_J-fU%mcpvz~ z7NQ!eKCG0jn(x%T?{+)h?G_ODV%oghtGsGW&V96jZU=Z#Y>BzIM;=_6e>#0@sNlzn zup#)ap4%=5H!WoC{;elZBZ@`#v|~{+MQX88VJDymhjq^F-JPIg5aeV-8&>l|E2okJ&MD~CydM=DG` zXv%Z;o=}~B#k*nwIHGL6&PNiLxut$|hAKRH3k2Cmf*)Fbf=?8x(7xQbzWvHY+3{47 zz7ngns|Zl0QsL1tJL)`O!@2#wl--F9mM`<4fDwKB;)7XT7_2J&RkzIn>}15od%Oez z4jev_TVEfu2dJSg`5{19Ea3d;(Juq$5iSp6*biodXKV*}y}f$G>l?E%8&&-d^wJHb zd;ay9!{1^^#Ik(#f}%cdGRXPtc}mObJBnOYeHu>R377F+y!+JfZj<7j+P9_b{J&>X ztjGqYvv5Sb8HHY^e_?%IIWcPXTNAW6342Ax58#H2?TGNX9ooa zH5_FUNkatr@jqmkrhASnZ&7lhtuXIo&=TF;)^*P-2K1~?eII$7J=LCP&KXl?ip+To zDMs8<+7`!H0^*vwFkD=5G6by}FZZ$cj&VyV6W%%d1QWZLV0lTO++9J%G0ZTC!Afx8 zTi-sy7#cnLDf0{iI@av7-7=P8>aCaySXFpOX<2hpxWbt!uF9>3?U`s!R`p>zpxpc@ zjDs4!^885Tvkd%mBWM@gL`iZi%U3yQX-q2@N4YO&%)E(~HSj=8k?8KP*-K6#&Mq=%n!CxT)$uCu%9d0X_+689fi4!|Mj<+f~0?Y z9FKX;aTD!))N}gqW<_NA=k?lvP3oJAeX2JPe}AzQ-jL{b66|r6c~c1QEh;za7G~4h z_RwKt)J&lSqDc=$@O5`wy=9owaVos%~rL)G^ zzSrvadwu=2m)-l^_vgN^&*yqy_x--!7xFeBm82er5;u;(cFa#h_la#P;*FNuRK&E` zj}G3rM|Q`w)oF_Q{g7iSy1+D?FF6$%Gbak_Bp-a9Sx9gjI z$GpmzF(NU0BA8w6pyCxn(aXa)FG0mD^rpF0`?q3#P}I>0#I3O81C?WqAiy<#mpPnpc9k)dg=#5&8L?<9*pW(Q(UA+6D`3_I7;hb27iALxE zhCE3ttEs^Cm*OU)NBLSf20|8#psT8m#`qiWgSt&ncXj(kYL{W)QfbS{RX1Yop{2!@ zl}*Q4h$^c2)m6webFkDX8RuMGw+D9}M(W4Zc+C|FM-`yRD2ptvz*Cs;Ma@=VA%8?RD)6qb~)0yOZs$VDi-P!;>3G>80E*W-0i~ULMY_-5(*;O3}>{gC7@RwbH};9%|)n&cQgCg?`7TUA|2&;l|i_~MBGG2 z_1Dgg*KXirP?&6(VQ))YTO2tlxhr?Q+l?em+p|5yz=y6W6lOT|YHm+Gr-IKyubj&$ zICd&CLL$a_Mvq0c7(X3L1gpB7+-)%zVz+JESC_#Wj7n&11NV!CCb#`MDZwud#NN%9^fgk(iGf%` z?qyw+c9rb7iP3wOVcjg1*lK@g@P}Hs--IKRe9mn_HV)R=M6nC=V*3YzMog2=&$=MV z$}!35KI+!(Z|_!6?s%wI&mU*{KN*Vt@~BW23nRm0a?B_f5hSfECnx^HA!GBty4DRG z`0i{s&RSm@=!;jVMAF?A3ylxPN+!(m4(Yi&Tyhr1p_CbR!d(usY;(491 zAfCe0!05c=XMW|t=i=6LA9qbcyCe@er+Wih+?HG`R^@Ul zoB2)aI9<>(pgU_tffKxo`9sHjd$qXHk)}nc3~e?W=>ynNTI47Qgp7tF`u@=g2k8{! z_<(hB+6y#mpr;3mx162{`CbL5lcfwvkGjOt zBFPef#;ZiY?A;)-n10wS_*j8Uv5ss2f5oe(jgdOzM4zfOMNn-0u36}#PbL)-5UJlU z26CVA3~asZUjU(>mjWqcnbp8~b`+R*ta!)==n{jxz5i@g$iTCH;PUzpgjP?i@QH^l z#1b>rlhJQ7ObsNOp|!ojI#8?G-C#OIJ3DZw+&gh%1c+Wf@gGa73{D%z_GKgoiZ7l7 znVskTKRb4F>Of?NR}V_0`rR=8ZozPv;t>P_b#^;tn>%dmy#CfO^ZH1JlzF&2SL%I5 z0HQ1A0gwj!#J|rwVQ?B)F&VLS_40(O$loInMZFOFWqbP1N7QP6uLh;hj0NC#+?y-e zS#*9t0>rls5+}pzmj0^Hkz=#(C)D7Ws&z?c17uS2>LK;E^We@yX?i#i&o1{X3lna+ z4eP}bsCz~*zm9+m;)~G8*hLqT0TQ=@RI~#zU$E%0> z(w%XQa_TEZuswfx0F*+#e~VxG*?g}3p1uINjGQ^E_qpL+VkkOoAOX~`DKedV-CwxX zTqLM?B8Eul$Sm*}+xr_t(-xg^ta@cfO1(sUx;PJNvG)nqn9;bL{4kz|zXW27Ne-)=nP$wql{dw3h&CRmJGWK zJw0+i@=gq|ufaZhOoTwiR(%V|gxzbuo{IMTF?lQPy6KQQ}42Y#Mh#*c8lJVf>Gy_}yPIuOacbJcL) z#Rb*0*TtnZ9h{H2J*J+^@uH6fd#jF=R`WPzdnq--6fzLm zTXr=y!8cw_vBnb&n&oMmcua5eg@s*=$(NvJ*$KS&<31iL7X@WFds8*5_8Eq54H)@` zN2$7eclULo;>l;9fQ)=!0Fjtcl-kjD@xF^S_k;R)96aTEY6Dz2qvm$9^8-A^AE@D( z{h|{M&byDA>(-Qh=y_0WX<3;$D`;!I)po`sb#}hab8&U?RGb!}QoQTO2a>Zb?YKzq zLS*09iy0DQAzAt#zQ4C>UKkSr0=M};%(4I)CU#nt4Y*k62BEKn(V5)iyC7wo*{ zY$TQ@Lkb|F*+dLFcV&M0kd^TD^I%n(U;Mkv0qG0%qUj0&Y#kClO@8-jkCC2}y|DqU zvraLTebtcW^^9;_Ag4jN6l2!I`KWgA=d1k=7YF0VQ}F2$;HDXf0Hmicz`<*!0EC*h zeEJJAFgWVVm#>tpB`58f0V5p}0(J2@N18|>T&ii(#ev=3*TSW1tcN(6tG09qGglfl zaip5WJaG?s>E5W4$fNH^$Rdn}I-;;O}9UoOc2-SaxOE?J%Y0#q6;3bB*z! zm#lS$+z`2|k?o=1k43A2_jhgAZdH*5FN1auQbjhRy=vu~w`i8&2-Gj%ADmjlImn0b zVa_>ecx%FFo845eT|dB@=5EBoBWD1;$D@*!ktQ;{;zw%q9)~fjRadNIv2Jqbh8LGC zjn!GbC&KhTMV|f!yxA=hmKFkt`_3Yy7&@uBs?V@XC2296Ky1=!{MDYJfApE#MqA+G zE?uZh;WDq77Smst>Ug+=>34sznYVgqrkCJaKTw;Didq+cjs|SlqCbKu8Ts8}Dfn7i z)z%b)9dJ+d@ta{!!2?>lV8>bkjlSSVXaPEy-i>FbIMikm0;4JMvkd;OU#s!2fjKjT2WfA#T6!d zc9?sih*&bRTy>SkxA8a9pRaIZQa37OuZ4R^Ld=@U9(PFC$O=b^%skf;hT0an61j>n zo76%&7O=FCMlfQ?(U+mVJWkN`Q?Xz-rZi4addNHf_~f* zZ8|zv+O5eJS$P?hnIkre)ZA+cZF8|)Qb!5_&A0)<`gxtCd)OUFnfg6ZHw*w2zoqM9 zM`htjz&|6R&x0A60bD;rRD{XnW^j`8dPXT@c4I1X|35M`Di!debXqkn*xSZ#dSIi; z(&_#^^bxpOj;01V@F7#7AR$2&tTWGH(Ka(jF#SJ~1&u`%Fy!${0Y{iz43?{Aqi}(U z>Xvp3!NFMs1R-b(_E_L*h(f4nueB4DRj4Lccns`S$$QYcbndXSi{p#=_(mOHBq}3I zmG}!yOF?+dALx)Te`p82?6XT&K(^{|)fXLeS0FWKSfc+o@&qCaMYGj%!WxIjvzcp& k)=U1+RQ^o+{3WhL<|$8ytS@so9|3>cZK;$}lGmC40$&_6Y5)KL literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/seq_gpu_monitor.png b/utilities/system_monitor/docs/images/seq_gpu_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..f0b145a40cb997bd7ae2dbabb78f60c8111c4f7e GIT binary patch literal 111248 zcmb5WS<3v*wk3AJU`#;`pp0J+*bnERKBY(XeJ`aNFcuQ~sqqOD{_1zuxdytXl(`=TBq(ms`IV@Aq8%bu=%2O$MIh zJvxIH+5S5Gd5@qxX!g8Gsx=wF=`jHh{HH3`^1*j~8k>Du|GKvM&&>{_1q=~X_74&% zvVRbHiu?mYOZXo!jus!HEFiG`Rrlu$ryYJ^{11cI4KxnZ(wognO*Rx~_f3EC%xQ|7 z;T}5~TZeER6W_6!f_4C9S@xpePfQFi`LozApU@ITC3&zw{F7-EUe-De-b(O4A62O4 zW-Q3_CdXk&mc0XA&A8-Vbh zTcHqg*ErH7V8LJ%%0x0C>}aUOf-yoG@v0%sOh@@FQo!kBe@dNVcV!$N@MP~xg`H*i zg+^ewJxDfweou^ra+r#Ob?|p;$}jsWVW_H6H9dLJF_Ihymyz8->`->b$LFEQa>_Z2 z6r6HCp|ek%2VMIb8q^My-2DNmzGnF|Zg~LhA=K1cf$w*2&GqpF+AizAPW-8i9nI3{ zeMPXj{=1`a8ydh4E>d>YD7T_=f}7s1&5$Bn+lWdU~lq=kxDn zYiHgV!$|S!g0GaUHv*U*j5r^`$Dv1yug-lsO*P&KwlS?knJSyoA>WTh(pD;xC>r5Q z2$C^P>{yGOi@K$FjA|NirWhB|R|-~VffT3-mfMb`oG)zr3F%2dIbjk-jSba@nvl;> z3Q5HjX4ifTET@$~X1{L#zO#^oVb*;|fvH61R9m`ozM{YmC(YV&#@@&bdDHz1N7~wo z(KN~)&-_z_RH}sVdbNc!aj;n*XD#LjU07a_ zE?}*M&uf;7AoExbY)DPSAeAr7h!Hluy{gU=edNk6`c$1N54~QJU2E+oEKj zyk{bDrbKh{y;n`X682&)t9yi!swDbhyf$y;M%^!-IrEt)j)XLVlHx3e? zVG^>Qd#O6b^Ba|qz|p_>00 z{pH+6C@Cn}q_y_*2%{f^CTF;S#NjU(XnYQap|I~W;ca2AI`90PpD~ECDx#u-s@d8V z)hvi=G0ZH5Q`@g464tNF?B%VfCExz#C?dStNSz8c!fjnv-Oil$Yc0U`?E+Nv1)P6t{pLN~>4kf_>A3N6Q{BNuKj7th8PvfHkTe+hRfo>6g4yrn z_DmB2r_`|8`ixSYGn^N(5xATE!XD0}Dhgs{>=_7dvFOZz6EZ>>uJ_c3S*p`Q8p-AO z7T!Q$CAComI-0ufQouoe#V*<9Vf($`vv z!C@@&b56^sR@_y!5#4ekbS$pFYxMM64zSXpF4psdIzF`4uNr~fhHtLYOiZ3t8s35*XbN)J_{Lgx@x2%2MXJ& zCbrdM=bEnVlk3jTP728_i})vJ@32pIZYuZN@jKX^XoBx%-ga}zbzbim!`xjRZYUyd z+56ytbTgrb^B;RU032r0Z;-+BqA`E}C;r(4Ick`Ds!-Ufk`JAEe2w|B&8IOG6wY z-TXL?-kZIbj@~0;XAb=cG;Ra9>04Oosc6eruQR{|BPnkMx)2Y%IASp%R8VPpEXO6DEwIMdnec! z7&7K`5+?gfeXED5~p)O`ex1J2820;_7v-gR^5)aHN zWqANr&~elyEQp$zdp}~KZ|~hA1X|v43;Oh^2Ty@h_Mel_$!QHg=_pYB$z2yI>e8xM zP{@bWBivvunEF1L7SK(7e10Il>@X`WSAgxn^Rr@Y|tkF_+wn20NLB9dG9w&9Pdz% z-J2nF@xL~?zefNwRq`0_ZLDSRx#XMAc~*WM8Q4@TcR64Fr5&Z5Bio;a)RCgJTit}J zqUCXkjKY?CIZ!b=(-*a~h9)MiLS~m6Q2dHHD4{%_F51`lfGy~Z#N>L(CUW80N?nda zOc`_RM|Qv0M_9BlD@A0O#qTk@lrUr(Yo0HD)^wsHbsl`8gKFmbXVmkA)q5BZMBM`D zEEBi^fQArZoZZ*%tcP+x%Qr^Ss9LV((mPPK$x>L$?}%C;OkwffFTW^&nZJZ!5SL50 zV^W2)H*T`xBRpYzab-~s_Ao7lIe1rzr_0PEj}fEfMe`l6AH?DZC)2XJy0p z84*s^xx~?nJO~|s0NyiGeAh;QhS4Xf;pT1ta0MMA>|guxl|mA(eyb1@6zqpN`>3q= zd^I~&KEFY(^YLVI!XD8e4JV!}qM0m+_gw=tTc8VdU5j!0aFB{i3k4W5amS{rjWFLf z?_jC-3o>*f0`laW^K>(S) zr!s_wD-nhm4_+IC>PXuJ+4A|wGe^s*C1%uO?-uvM?KWP&BM7p0{GH(H z5MBmKY8p5g_HxM}Og$<0Zl`p#GKTS`MqfLxd{%2=Rxt#9M1cV98#3YK#^CXsB9t|w z{dM@w1v!meUXcTDj!UyIKBd{5-VOh%CQmA3_62LSUc@{%$ppGb*eIJxz7n|!B)L$k zc$c(S{t~kE%5ZjOoC9T6CS@do^yYxy!B?V_K@8Rt1o*=609I;oV%OYjLAc_x_Ws9N z+WkP)_9yIAQ66s#74r)fc5{4hT7Hmo?n{22j~H1&uLzgCd<;z&AjKo#fMyKZp&8`w9n>3KXw3fMKlG|m=A@$X z3EXTvb|orl@qRQ!u^^FyVa9<#30mLfAwllG5czOsdJVNGnzb?MBi@KwCuPb>YO<$9 z)dvZa{RP8uhFp+EL;Lr>sCTYPZ4EGJEcIvvct9Z%0lH)+UQfjqxpqS{cUH&(Ed}Sg z;b1>dc`82+FfIEE3Wf`ZmTf;5)Y}-pj^m^ce!Arzx1h6ML*Qy98iG$`T~q$E&so>P zY^5O+urf?d1}$ldELz|p82`P|bC{)! z)^Ay`wf$KZ+5NgQmqgsEWXfw90eE{){;ZRXz$bLEUiE@jneX~6OW*!xy0ifI0y}^D z5|?5u&ac~$u*)|`HZU`uGY`$fvphq}zQgzsPlDXSpt@iaLq!@TI?S&IFur=>5Pn>Y0L-Fhzd>jRyqzr|boTdHfDOT&8k2qx&Bc5MRUUmeYDSeu51WQ}e z;0C?QsH#?1?>v9aCNOCsORxeCL6HFQL8Sp}Ot4lkG_cLEzYLQrqy&Z0HL>1N3v=}M z+*GBQ5O<4|^>!M#s-1U?`=qV**5!NvxwxYgwM}j9i%I``*x?|n7PN)7%Ll}DPC~iz zCWzyKHmBr&Pi{P~+bcg5@gduSEmUGtN^g(rU)&S}d@sNUXUmGr-f9%OCX6AOIW^N3 zYaNK2`}F7ofDe-=0M7|{2+X9=`dt@bB7x#lDK~2=J@i1U)SR!=MNZAum@|6=-V`R>*k?Cek{xZ zF*g#H78c_ej+U=Zh)%J{3Q^I^qP*C>O4^7IKBq#v)PLZx9 zk7WG5+=Xc1B4)S7ppVd4JU?uLyo24!Al&e5| zEFHbYrm2_Nv)=|(st~v$`SMgwUk{^=vRusW zw-dG%P;wZk%&pJ2_V&kpc(0MREc_4-g~A>FS(#w_^9?g65^;@-+Li#5MC>}DTo^Jklm zCO$TN`WT{0X3ZA+xZUYaT-&x6u3m@T`2&e(Ov^`X*0QAGw>-Xb?fS3`oHxkX`N6jJ zW7$5RXX<|wO{O^4C_?w`k<1F0$LYNVUfUz}ss38PMv|05lvpDDG!gQhp$X+Ckb*;aWEqwXygC*Ik z#F>kO$9`_?_mP@i@lk}F`_29CYmHKrONla_>bJI*BAn)%en&`6339M#l&&Ei-o}-z z%D<#3!A63GyLY_GPstzYw%dvd1$t)rSlLn2(KzCN!F&g+>5>2wu@Yc7N z*{8|Gi42IaD-xo0uOkH^h%CR^@4APsJ^~Ql;yBI~k(YbXDw-4X^ud`R$o(KjS`JeW zQ&vU?K=!fuaD0!_C2?Il4ze3czQlUS17kqXrUeC+X$y^7N|Y+q+fU`S zkri46xm+JafTdgw$vb^DMDx$3oZlG|?fXl=5|!qqE%!Ymk-i|Cty<-90w`8GDyz?dC-^y+r(;SvZ)c(kJi4T#6J|S+hH2)@sHt9d_xQRKW`UP|oEc-#q35bY2s-XY)bwX^Zi;_JW=sbsX(0ak+pz_| z)5Qz3NL6=}_}wNda4&VUfG0YvPolfpcj+7bMP>s#(N|0Q7G+7OKRXiXbj_eG6WH>39DHiddOG?}oAGpjs#v#SaXmvP&el1gq(91FPqERF-RMG2@pNNGTO z0tOvTK0Qo%-V`lV(SiFiSVAp_R%o3CI3AXmyHZohY-%bw7?3QJY1+8yh}6(*ztFad zY|9$3@*Tjg)}miv(t()~0xlc3{;B{we7a*qT0d`D@n@rwFcx^?ITP8~0i0)6q+a%I$#d1I*xS?eFl&-e&RdcqtrDF$Ug}NSouVSU)(E}% z>_{zSX`r3sv$B9;)+A&jqA={N3w3Ydm(pBw=(gWPpfj(i}8F}bd)O>enC^ix)ts47gWllKWNmLcP=TC zsw8F4_Y{#d8OCaw&iW`iQnd`SHo3(UCU6Cy;M}Ihs$o1MNNFKq9-LM=TiZiR;=4N) zqp|dFY^iYK7lcQ#I1znQ^vfnw00#+0xGii-4?etV*#kT*iwowNJ9;&jYQ@J+wUtP) zWZGoIHIEgZum3^)TqDV=DaQp09qc?I;{+rECLkvS@rFm3vr(%wdG88IeEVob{IiY$ zmukQVw!inIJO3vz**c}*U~{kSz1%L)yjpv}~M_!`{Sp)D+Z!kTs9hkL{S zcX0fCd}q@MT!f=|8JOIP&u^q%^y;I&l;7F_JaOZVRfxY)qQ<=Sh}qj_V59%PFgE|HnvpobLH+xx8RqetVtOv)IljZ) zOXJ* zY_(rSp?h%=uKd(7_l7OM6v+l>Lf3qnvX?{Z>4HwY3OqB@ zlSkoV{XQJus_R^4d0c;_-$6P3@X@~smNqlC_8)tZw^82Nk+d(WHJExS7D*s-0PsmG$^NB9=wQp{Sn^E)g^?z4pl~J#0$b zuII@kZvFPMhbHWPl>&r7wGIlPjT#T4|KM3V()Q$ZkFHF)(s@9y$`xLw&>k|A%#o#)%7$LVu`06IYG$L!B6q{iDKSgS(3cOpo*-Ktw`M6^ z)Cyst(FF5`8+FzggFp7g)N5uJ*4r7VvY+()j4gx!Vh0&hKXcWhE7I8ZryCqkZ}_V@ zRyx2mrZDn~7EvZLHdYw!HYN56l4*vk5)udRm@(1MTS=?C-)R{FG$iD2E519elOAct zktofZ=}Ag1Xo@T~#CCc(BU*+7Yg!Ow;9?xT#hJQjAp^71-fA;VNkw){!4(dY34qfO zs`I3PSS`tc;tKSF=ZR1TG+)cpE{^`?Cf)V|)s2_eDjawvEj)*H)`xnkMFM~l)KpBr zKs`rIvK!fu#ZeyRH`|tIM>I4ByI&B{?TS20wxYr6basZ9oHDTZ>p+E5J?Km1{9|#-i zl=&o&?gUiJ9}IT_=p;})5%EntBNzj`Dmi9Ym8g?#0nqTtm}=(%Q!bv^6Us(H(XlAF zNXnnC^fBO%{DzHi$G3o_VjkO}M4KzC{PyH~y7E(^uV-w{(0N-zK#_K>=Xf_j&Q~_r zY3U$WQboOJvl?jN#KAxbB_>rD-q{<}H(5zdSuGb7v1a<3+0uFq!+vkLVA6BOFg-ng zo%2%dkU&$!xzW>*v?~3kD=C@f0QpR+;K2lVre0wABa=5aviaZZEO@pR0+ET5NBQE} zbW*w-XS*%7KwY5ujM?B{Aoc+T8=Q{ap;~Gdif>?!NdHTmi}~3=cust)FWpWc7qm__ z1trp_qm$3?h-j^>BlZot6VsEp`x2EZ2$!Qr7H4O;L)62Do{tgeXf*Fd%e+Yk?O~kP zuYm2*Cj%I^tDoSdGbKHB$_1~Pf9`>;s1wLqj*eZpC-n_@UFsW!kI$R43;->FN3{$r zkzmzwVO$M>C`uaLAQdN!I)w_|uQ^bsz!dc7{V-52%wA{VIH`QX3T_>$z~&E zujf{~z(xA;yAo6R)36biC=Q56RJ8tP@B>1q8B8a~t#V=Qfi^3G@MVm0g3$(r)!t!o z=Gic9F-SECYttlL|xAGDK*0LEF$q zxJEv0UsmttlM-VhYiKJuIJ=szeGPt3cYA-?>J#8Vq&8Hz9FD;vyeUS&QB6Lfa|ZW{ zxdcl(h}Tsc<_ZLU;6Ur~5JlekT=?nmAxWxGmrBD27s;UpP49Q0fE2}`z2;&{BxOlF zU|EEH?Wk~gaN6_lGRs#Qjt=fVa_F%Y9p=uCP|x*K$kW;N+kKa%2K>+hPE+Eh0Y&=aJ^pOLB9sOj}vb)W`Xz>Ne zg3)DrdJ_jccEW-6da@;Lff@xzjQmsY2+A7!fM9@?A=j~$kdLUAz~~r+o>hXt0-X}j znXUae83#OmLDG9jpD*y3!c)HU9>VepBpjQ?fa3C$KD@Z3#Oywm2^Y20{W1yPnGFJP zQE(=p5WH;<*CCp!9Lp%Zgjz@9O0aj%%&0;#-@c;_FpdNt)=8#Vi3%2^EI$?q5Mlr{ zGk{6mh89V*;*jw{3rI7b(mQ8zUVB{yasE=g^hZbz5lKkY zQEEiB@#M1XwdZz3QZ(~#NIw_pfmqC+$8zDp7Y20)hfGh3Pyb2d zB0x~lO*>u%C$syS-7;GMNy&=@)@28*%nlR~KP|+dW%+{?iu0ZE;51GCzvWy16}{`l zFs;BJ{rdnOL!tr=m667R=^uor)(Zy)?_U6Z|2F_01^}M^oqwd=((&OEkX%AO2#TsV z%cUOe-L(37r+DeFw#YzD1mzvHx5zL$wsR_DL1oH2=c>4TumoGe=Gp?jo#^kc!YU!- zXz}JX3oq@w_l5UGSwON_6U;zJtsT=3yuB>TD~d1Mq$s1W2ZfIBf~!;!&}ss#{sN>qrECNwtz_0!F3l+n1V(dsK?lidF&m#&l?kDo=MWIM%5!(C+v_L z-hV*AX{LROEew`t@O2G?W~m7omqx1nri_G3ckZA$98%z(pD#AMKBI2HUJ~{XsslN> ztF8YQt>neBT5fkAD=x1w%PhvuNqhnM@@uPIXKfhzxKHgddW6t{CAJEXmGAzn87Z9@2&(mx=9={JY1?2;Xq>zQ z=KZ6*<<8z!kV=?rv@t+k$I16Fk^(Tnn9KNDAELl$g{%rA>HP150{Tuo7On5pYM2^9 z*{~Gu4*)AS=AbQ_LBn$i!RnO2Q>MoL%@`-rsN0`1@mi=zGlEE&MYK+Jp(;81s+6m; zLEeL2S;>V0nx;VpnwYV%#*C-l^t6hMcB>%Ku$)1RX|eWp6|4#HJ~CLD&|KXBvVns1 zI#n84)UXj{mu^~ekkhtT3NM-ZJRC{Yi3>f7MZ1VVn%WPrG6mU2WYk^0OLAW!4>Dg&zaLYIGc z_KtaG^3y)|#39i1AIM9B8Of9sRqYZ~1l(zhbc(#?t|mtLT*rO~cDLh?zY=%*P?&ec z&HkZmvcrLm6GTlnsrMaup#^?gC|&_7Q*j)jF#4M!LV|>AKqLe-UvLv`o?Xe)N>TcD z#Ehr$XAp%`3y-Tz#?NbBZACk$rOtt)SF5R@rURQ0ak>@5QO7Nt6MmYWwZA&NiTl1G ziykae=o4TWMRB6i{>DGz7jc8l`Idn$wqa8H2&X|DeT7o(Eq{eYz9Ox7U+^EZGCD&PX-fI_)!}FCwVL87#F%XN+yoI3kS@~$9HCJ; zer)CYx_0Vf2^oq@i5+;6C)~THu61|54m)j(*51B=w~sJd>^o2WF>!8NC`jl z5K0;i0Svm8LO7)|^RGqX-@QoDwzDRw!zm*GS~d2??p$#=FNH$)33My zd%~QE#%bM)5^8{O%AD;rb|VJSm~#Sz{49&(7~ZYB2bjIDw?z&J8i&P&79*`vrVfxpjdsYg*4h9N!qU~OvK=dY@|*%z{f#XXoUnFN5JU`rc zWC`#eeDs4;L@eXin_Oy_C&f^u?)(#xAui_(1)9|oWLSjw1!jROd_q$YCYM*e!ySMU zxIY^Mt5^N#olu~aEgbGO8a3T-*8K*$H;rpO7ub5ZN9$(9p#JjIz4mU0{?j#s`>fZ~+CD7Bn)p0^U%C^mrr9w?QM>9C8Zee2Y+< z$21ZfSo`gA!b~bb&m%1XuJqZqY%hnboyqXEinQSd$U7+jTgCj&r`SN_Kr{;hnH>W% zV>rk-fcWyVM`IaJy1}_=4Bce7Vh}gCj zmj1+P=6*GuPrvh)prjHVkt#m?o&4Cfo$FoN3m2@V2}$iokO5tbV?y%6!@WI%#0)D# zS|k)!@Nhn|E#t${wno|uFK;Nv7^ z+VAH!8+bg)*QkK|g-9?^)GwB_<0+92jH|_;A+85Y6dW!gPbBI4KPx@b%;#b1>nA^{ z{RPVPGg)amfIR(a^a=M7%miwATk4|Got%BF8WcqI4255VXzgM`9wm|&`}cJm2!Mv* zUEVSJ-xcEhD=;()aLK=q3R_bX1+IoT4hCz#Y7)o;Kp^uMD*OQ<-iC-4wU$OsEi~CN zR^5(9nxi>j{D~{4?ryA*>*-=%BEisDaT4U#L@h1uND*MYxM8AW2p%kA1yPMUcJzv8 z*7&GoFkXY601isGt(WJlYg%Ttj<9?2rXx^+UW;hAz+T1P zYx*458?+> z=;{DA2s>^94W9o^NNWiDcY^qTbbgr;R>qW|{!l$ppuroI zUEU}&Q|4T2*4#(X&yJ14j=$ADkMe$Pja;$q$mSZ1aXOf+zpW*Kb+cdgj=B+O28W8Y z8442L1zLEO;c~T(X(u_2H))6VBDlE9uJ%AuRxH-l~ zsKAap+Y|$Sm0bm-_d1)`;36tXF2X?aZZ4Rpo=mW?!G7tq!XNPcXuoihpI@WLguRcx zssF>u1{qkvB)O|MUz^;#gUDa5CZtyo;I1F#VqFKEkVW&da1La`Mb>2sUTGBR0tH?#rq2*@vi z7XX9a`t?JNO@Q3Qm^m6WegjG>wJb}pfXMc5+~5b{qfjw+KYQ<5EHjrtRi{;366X?S ze+96j?u120PL-Dv^90Ur!Fp66%W{Uj2?84-RWENfi;-tnD2 zzGDCDS_}s)BabN5RRv%{40yae8fo1Ipi9QeHlwW`3qFfS81P~f7QVJe+0k=LRkUPk zTgP4x>F6^5FzQES?=BJnuhud&Qw|pl_;v7b9PGw>M((u$)|$AZo!!T1AB~@S_`w#Y zD>EN|yVp_9(|7$mSg=_SJe>fkA^?ryk?371HMX}hi_cAwFtk?tKpgs)?e-{&~eidv`Sb-pK%`!Nt$4EEYmB!5lK$i4qN z$$V+}P7Os^20uhljAN84iC50I5)^EPM)Y#{o61k~yB3>Cfn}l275;qbwcNbphk(q16aOVI!Fwp`K(mTbQKB+$ zT+~v0Oa+koDB34@GU3cOhza7^LJa&bbO^4w0Y2nje27Nbx|$qZE+GjVEOQf5`;Cd4 zGFZ6hl6`+EYzE*&T9d$ep<8b*TLvu{GF7vC*&nlh=lf8Lh4kWrm}0AAk;6#dJLEFI z@oa=?=K#WRkqzHLVtSv+HLN!N^E2FG#1Y6bhAS+4=EaHe(}EvOh#9b$^)HmTnNhJf($Qd{ zV(H)KfM~vj!|E%PvX@VdVNdh`NZKv@qOd8p$4@B$0oJBa>zkOAmVN$CN^|l+5inDk zoyrNRxUJHvbod~!mv1S;NRm))fnbEFdojMF4ALno_v2sqYzYe_gck$Rljd(&o0vd6 z#C5m;(SjI53m?Y33`QxFm5h;w zOnEsFS<&aKL4CJ_wE1R+*3x?)5EgFFJK0q5BU-oBciGF*2EG=SQ%EGD#F78N& zR1=VWMb4sRJq1XaO391LpRO1&)J=U`57Y&@KW1fa{Jg@q8+NI|6wN7qfdhQ z#Uvja>>V0)ogBC$*ncMkP>@+AOx_1~jc(Z~ra$5dyf6T{2q3uymW}-Q^uaJNmzdPM zFT>P-{fieZ39QNy#KG%7;VhJ|=^bh|0Xz!ybWOINU3ZK3V6h&T<$%d zJyBDZIfwyh5rkX;za257wMa0IlwqPrs18{0!0b2@55({R;3j z4ETW%-M=4&2UJ3!P4m0~$w36muDTMG)U!!ukc`QYR+T%jM%3i(A@TFMFGrvGSb4~W zVTwOU8g&xio;QUjj?%*Bs{>2)z#_BMiPP7tVR&E&Oqtgwuvh|#B(4zamiE9;R?H&Jn1Rtv8_zOr z6B`_CaaH-_~xs{${9e_-pTmq+A1G5X~| zj23!~!ygR|@m|L$jY`q<$=?OHnN!SF9}<9EBcvl8EaC@?oWPF^urvhLV_u`d4go*_ zu~PnV03RW>fCfT3tBoG#fO^F1h`~;n4X&kG6L~4`whxxi_GRb z0HkQG`K?Z#iCE~jZrPnR0kKN#i!=Z}V1DaK>r~w_(6Zk-J z5K4(R1pqr{OFniPw;ZXbCw#d~Q@p_SBJov9+VEL2^0q+wxyq@%NYMo3{P>F$1c?$_ zeGLa<0D)WlqD4!2y~Si1(omaIil_`y$YVsGU_&dC_s>@*%EIP!ZhQdh}|ML{mGA=tidNH z$pfVpg9^p}P1&1(L;1dM!uSz4qd3Y9dQ854<_F=HEJ?54sj#%yLW#w=(PvL`J{ zmeMYfHWey_7E~%JYf7{sYbftMec#{j^Z6a`dmR7we;kwMFw65i_jBLZeO>2yUMD{% zYdkTMMsnl*jyL5C{PHndlbn#O2iMvc}5}N zVZit$kV)kE12-ZWKn}t85cm`-ngx^E2)%hMB$6i~gh$fCto`7QUf}|!#0!su`Fca) zzOFn^02^WfwgDAs+}#?V|nBm_W=yGJ?(qR@^2LX04@L}4C2 zWLHTPJ`l|dWGSl?HrthhQ(}jH5t0AG4kN9hkVuw4SkQPJkpM%Am>7V*!95k;ek?~e zDIAE}U?Pba7D^C;hGra`LnkN;lTb-GEiw${OqQU53z|PWLO=)yNHV%j!P5?U=#=<)Gr_qDi0+x#AtVCWydCK!YL52^WF)!g^r2B#InL zMG8VgZD0&Eh?lr<9!&zGF5DA|f<%fuS!hQoRE&Z%c%rB%Cd>;51`v;dv7j)trTc<&@)0n4;6!9`M>9e1Sm)3 z=*x$)A%ScmNdOFQDCqyn4WUfNUlTPOP@pohY;3&XaGuQ%O@EV)oDWUk10(sZ~E|BBE$le4Q6iJ6keK|N;ly4Zw{O~?R zqL{;t@E}7u%FNFxz?p~&k05XZ#Nr0MinKLlT+d2=G=X1(rf# zf@pz3Mn#H!B*;jaw8LL37C2u8>g;+!4%Vrv1JNtG!gqnv!H*5073@(u-tZtO_l_u=7< zc9EmqTorgAoa56x{;D)U+maVWfxrvkj%b9~-+BmYCsD$^U@lQ^QV$768o&YV92lrH z5K9ho450D^K&0U1C052qfeTg)8vI-x$uM!4GK?~#cu+9QeXX%x3L=j!;fg$|GKMt- z57I)6mx3ukOK8fc_%IQegurl$;zD!8DmdO)H!6t$r3BE!xOA2mFM=9|a&dOU09cHN zb0;H&PRb~xJS5noy?k(TF*!mAexuAbJ>1y}EHIa&L71-ocmnV|1aCu0NWf#oJ;2@F zQAoqO`$pm1JskbSa#=tiBakcQvs~FWQm~pZ$Ot;t)05-G;LDr}=Yk<=(} zs*lhsjDnU@oRx(chmMiatsxYJI}pwDkTf9s@CtY2BS^}l*$`1ozAON|4Sb6`L7|Ks zKoP+ZLp>2ZAqtdN0HKEn;nvhp6lk5}gEs>H8r(??%@-inWIBz_;sfzAkI6v*p{|TX zV1yFIL}#pzyFY@9le+qOae2;cPY*W*pF$2NMY+hR;aERvC`T>@x>*GsNp|w^BVi$) z6jy&L41hF%{c&NV!$htWR+!us;vC4uJGuB0Bauiy7Z}A0CU6e*iFBk9=`sb;6U~(f zX+jCs9Rj*PaB!;JH&A9xhvU6mtt0b!wRG!{c(M{$LoBq}CMfK={VfiN_I!i)m? zXTFpa0r&J|;n5K&5rTyPcp3@n2rd#M$3}W6A@y(=TfwyPmS93*G70e20xu!L9YaYH zx(5)~1h65#0oIX$WP(VJpi-Pci!#E=1LDiZvBU_m7usJev=K-IM1jPW&4=;=kYb*I z04LCCbT1|%iUc%FB6n-7ID(3$vjb2fCxDjXqxUaU|*yo-W}VM8I_j(8YSU=5l}`FJ5o7{O)$t2`_wR9QiX zx&UAt*r|emL}CUq=?I1lT!c7^;DfdSb%?b)2f`zeDgOR)Hia8Nq_G6b*b5#`0!Ma) zTw;ylIt!p^8(?2Y^!0Wj(EU6RP&pCr4$RHMh(0)9CXWwcOQ|d`F~uoD5>5zrXAy+X zQigYUCC)A0sys71go1(b>}cZqm&3QVac4G(7;yF3GNC( zG8obTmXFf?44527KtQXL-(OC^F)%y~Du_h5hC4w-5hQY$hjSp$%@6p0xKS_>E=(2{ zO9JjX45lp9CrUZkb=tvvT2;(J(SR+v^l$(d2mp_asl=_nSk$~tEIC;1@ zks{dE6r4N7#+uCxlmmd?gXJMYx{)AAju47w2Jl^->Hbl!kN|<7i0tR@OaOK^G(U*1 zzq5ZN&zETJ1o_*66ewkRkYQwS+5ob_E0c03ya(P@!J|NApa}*pgiFGJiykpTfpl>T zWrGGls*vkX#nRZ`Y?iBQq_>RiNMZnj7f*wEVH9E;Bv|MqcNgbK5$Fz!gn9GnY#bjD zQfzPtMHpzz3d386Lq%|!uX3!!z|w&Tb0Trjz;6@9!bfquJi?)D0!ld@;J%UmbT2xv zR|SeTsv}h%z(6~40x%S7PYI3e?8v5gM$jTaIjvlJ;R=$sh#+wfrvU>XPoOS##DsbK zg-MZN{;ob@R2t}VW+QE6k-W$No{vZgd*b~Z#XK7q&yn#T1TXO+=Dla&ah! z55=Qdpm#;UkivkqW@IFuB@Jgd`?$KGX-cRQ7w!Z6&7e?}G>q-(Nhh2xRRCtjO9I?*=#E~IY(Fei>VXpCU8qREP=*4 zIfaJfi`_wIlZyx~0=B?_+4l1m5d%S%0tX!iRGiGl(LGAJs=(L*7YHW!=^jX;h0}eQ zGB^%!7B1ES5N8O)Tjt28;ds6RU;{@EhvE@ZA9`dUoa`eNg?k8<8>TbO8tO<5Be}bw zrEE6^h2`k#!E+06f}s3Cb{l1*)I?**exW$fdS@db!MUKgVZhxKKqZV55u;E*!s!-i z?F<)^{cNIqI6#L2kC2dr0wUBeG!hzW&7s5HU||e$1j88)d>LI}Hhdmb!SM9}5R{lg zcV+l11W1CroTh|1$OtAbQjElN!ntgsL?Drgy@*tjL_lKU6aa1&LwO20N-7l!cnUNh zrT``o?o=3;NrZ{yp^o7Kx+}mM(4aF(MurvxPqAB=*iFCyOd?1Z@htF<<`Nc#=iH-!CVGI-%2Bj!P4_-j2<`Y2; z5Ku)NMt~3AnoI@=91#o|lEW7h1kPxp+{+6p1(t~-8j*+L@s&FbmjL;Tg%DX}s1PSY z!d(dxcqG_tLP@@k-cAxG!kyw8<%jh3^LMxL^Fj&mBrkus&=VsA?VcPG2^}iLLj8nz z8@)Ux@Rx0r@8A)+X8j zkthhd08A(N;N3ubH5BXaPa+WgmFK6tG;1huB?QVD2%1H97Z8*w!{2g^g$z_WE<$}t zBo_eYBE?(;R^T1Q@@Lb8Fh@`$f?Nvg?#0D}j%5fc6xeE#{~GX#{|Yq1DPRCFyuUw1 z)Oz?>Bht?m&UN=uTNA;Ykwd?*>D^>|-p4G;bo zcrnqS+g478L7~=iYb+618j)el08d~vOOpU_9K45*;{pq)FbT}bpXBSWyk1tM5>%7| z6#)2;qx_+8g*p?+p4Q5Y4dLMdkt30yF9AW~gVsZ;v$9DE2oZp*jdJF4`EoRkr3?!g zydW?fY%v%)=xue4@J37FKHv>uP!35ZbYg-T6iAGUf}@ZDFrQE+O2T0JLH)6Te|av*CPtf_VO2d12biaFO~q1I?Q9rR2@ghG%&I32+ToGvQR z7wO~TA^mIfCv^vDE5;459ej?T4OdD=!vi1zpdAf7JSD3;N)?$7G!)hfZZ_>{oNlO#NtqCOkHHOpa(W zc3J1SC;6K&t~?nu%J9RpVtV?~!w-2L5Ils-B- z&~jli_>OqYn4kN8|2D^}Hd9MT;2K8`t6dxuB6`AlC$XUTs( zhOAXHSDEy_%)C?{{aZu#{IfV4%}$3`{i2xS68o-vg7#o{QzN`wMBPrie{AXFGUUiF z`=U4#W7YqDyfF>Isn4s+ntwdggf9OYXpvHl>;8}=Ik?L7(gA#S|A5&)M_ZyI)xh12 z{q&$^6CrHvt{>_@UKK`fcJ3bChju=EE)#RXQrT~)hI9DekC+ny^_Z8zF9M^PaO#bXwJ=8EXtl~HEuUGbiLs{BbzjoaUG^q*ox$F7Q zac~c?YBPR}nEPMn99~a6kUG%PJ)V2-BIUv+WN}{q+AE!x`f_2!=Xb()`B=_geY(h* zQJ(6$Jo%rI)Q}zA+m)QUcg7>Xa_`}#lYc3nqR4 zn=sXr)|XRJUC!~_n}ach$L0!WY6Ewc%jUW0n%5H6=+}&DRvxm$8fY0lUq(0ITzzNc zIJt-tn7Z<%3b_#fuv_Q4aJ)ICZ|kv3*ZpX{$2tOTvKXb?x+T1nD9fn`)3UI}z3ZWv&3bona6B>&+ z{tjKu_OTBa%VBo+LVR-mHH#b?)Pj~6O#Im9a4hCEM9!05S1Ad&Zdz8EYZRxrT|2qK ztu(4;G4Icpg`b(zzjfz9q5{I~WJ60HJwZB6q%V429^`Zzhd&-fhmNG!TTm>_FTeiE zRC`uS-j!)fF!Q&_14wg)Y>H7f~ejg=S(|j)r!}R2UBm4 z_+yVpjk$L|s(ADj!l_oBkwF|nI^;|F3D`3$bEf;~5N zujb|4hD_77{x9B5mSaStUtX@bZ)BVH^YuIG%l;pD#+50B?UYvD{y~%n;n@nP=Xo#g zXn*_j)W8QOnL0mBo-h3$OKJTQTKTITcQzRcaMw)kq$T#mZ44Jp4P7ra;om}CJrz>1 z&@wkV{m~`(=d=qCSCi@z1X0wn59IS6Z^YkjgKdRg@N3qpvaV;iw|>R88>UZU+TZc2 zH`oNQf}2ck4h^2mwUJM)T5#lI#*WYTt@B@GW%iF9mI=eP&k!>DMi~|E46W7HhKY;w zAG}0k8!Jh9c8*`3eY(c`@!7%)k~n~JQl01L9G{oE_jlm%YouvZl;A{s_q)?+OE2H7 zf23!aWn zLE%Mcu0TFIw5q-iS=!K#4mtezeK!2unuN3yDTVbU`j1zC>IxpikI_eNRa$*wly8K& z`t#y9E_FLOqjRi_^gHRwJkAP|`nHW%lT+7B%qDXr_j)o4xx{T)d{cE#q4_o0n!9f|79xaLz@X6*YDe0$3s zzZNMLok|VoUg#d&^P?c*dy`pP+tFHqzf;}ePdP874f?!b)Y6jmsfk;O(WZ_w<=M!p z3y&WQeHlX7eHC~)?8q017 zp-DZz&rI~|ybPVzz)s!57v5b%ou1f!I^w$({sGiHE_RJgj5@OTo45+$AcOH5iHPKWb=kI$t zxD=5S&X?V98=qUg;m;L1Hf*<=-ov6-1IZoRXK1?RTpxMYI!?3~qx3?r*_OI;mz3e| zo;{PL?Y4c9n-mm`DJ+2WwW;P>Es+Ro}viqlQR^d;@JN<0v zHB_f_4#vdP$IW4R%D=a_lMbalURrt^eahAzYn)!i_F7-_ds>_L@@K1IRefi;7<032 z{6^2^W^2`-jPg1c|D=C^INhPtB#zY7!m!HdT6_gDcqk-qPDX0%d^OlFo0W_5U)DTkwTe@w*s~5+P1U`q`LDUN@3Y2%?8$AReGBvs*X~TbH}Rv8 zcL~$qRcJt~J!oW>x%N+wn}dmIjJ(MDU!PJj#$~Q`9yc@2qz(>ejs3HDLI|q522rbS zdcL*H)L9U4*XQ3UfhkB!?DoI7d(@c`0NTS&{Il6iZd6Iq3SQkdJLYCmQ$IhTL+_vX zvQYO>Luq$`?B%*7Ez(P$UH=@+SoP|XLk+_C!)Ya%4W+}~k0bv%#nKJ?obQLTM-jW4 z6bDysODEnlz8+^X)ZerEls!V*z^zGt-9K*zK}-Xsn%VSy%^!qEd+ot|#Ex?7%L&zq z4~m~AiazHTIUl{}Hi@|C_fJX$lF~U2XW#oTwyTVYT=w!4-`Ln5|G!gLoe%4pKGC;% zOaJ}$EAGZGTP~3DgSNt!l8koZlT$wx^NM&2=j}@|f3r3s^{n%;n}HTTUY`5+^_g_r ztAM$=D88=aE8!3%)Tq{FC?NvT9%lH%8Zy84pJd!u)wG@9u;|}u(V@NGjG;Y0c5XYk zziTYj1H_RKM}2eZ|5ZUu*8gRPMU> zCh@jr(Qcig?W)a5T6_BcTw7#)=uW%Wp8m^I{f??XN99YHYQF19`4bPgv9gSC+3PD~ zIzeY&r)x}VgBv+(z#T)RsvWtmj~6bhBBI^$3|AFvH($HqN~EmuGtg{Xt2%DhEj8(V z_xO|Zk*dp;1mc@SLzRTR{i8R9HLI^K8W^>n5OHJ6o1b5{X2k|b7>wf@Zxi=+C237- zrCHuo-8V8H?=YBot=d`Esa{E_i#<An zH)NaHlXAf={B5bqorq7EGREVeY|g{jWs@K3GuD{89qMG3cBoLh91s8sK4Q*xOLt{V7AuJ=frn7xyD(iq8DaQD)+sZ5@zJT9(*%ZI;HX0 zUZ)fZ2AP{dI`n2+%;b`kT+W*2PW)ia4$nN0JPfzJX-4FZne~o-LT?l2=9k+TeWa zv&>1)Ph;ob2!Fq+8XukAUJA{B5?n-rAeZ5&c%ag2Y=tXnG}(6?M-6z%$41@-z2^!IFBdo zy{S2w+fW)^{;F%wY}zI73$&jfA6tM-?QYcf7$7Oyks{cS-#IOL&i z(NUJcRqe86>Wf#g)Ew_d4h+5a4?Yd{%(s=%s1LPCahH9I&ft=C@$Q~S+V4sh!o!+s z+pdRYqQ%TpTO|uNc%5~4b0rW;uhZ&%TrgQ4_5GxdJ&ND%&{-kBrWoUVY{;y6EC2Qu zs45HjNLO8T(#_fR~6JRSp3=cMpA@!`Tu!UHyXON z3yL0DZRs!aEjl*rle*e=Jbosz+n)Qj^t8@0{W+GiGb7qT@=r@m{oY*Nm6B$NI(Z+( zd8Hw!99wo*@|F2#Psd%!3UtI-9kmRjZPj~beqlewlt#R*N&@aZXSZkb+7!6xH57wdcw%q+4z^GE^#8pv8TW>1<&>R6jXLGdXQMp3Ju%+>(g>xXN7@N%CcAw#!!&L>drrmRKCx`OC86xKJiI^P_9e!BbB5j>FQQ1=02DcnI%ZS*u0`NWg5J z>WW9YOoG~N%A8Yz`cug_?*CMzE{6MGW#(~XIj87r*M z#_9N`M{l>d?(h|`*=o24 zt3g77)HhI>AM^E1vDv94&F;W5hMaGuHuJ4Dc#pMF+-lpX6@zLc>ntq$b2ThrATGqI z%vH}Gy67JqyR_vz5&pPs(MkklKNCD}$TH8kbNq3KzHR8!W7ZdTELy$w)eP!UO~*Yc z(PEjCHnt@DW8+lz`xke_VMjLlenIabowCvS81} zaTBwqkW$0u;f{;ZR^Ki#&!;jvrZ`Jaf*l7nC*R!K|O%33h=~FVzFT__#Ex zclA655W%%y(a%=A7U(iiq z3F#-(u!*FQfm5f?uWrhJb>b<#t-YC;uHjUduvG65JQ_bDzqQ{wm2hS>dS2X8gXrBe zj}9g;ydMr(E48#X9Cx^7Iq>4To2giEx7C{}%sz znK4+&+jR_1j#EvSfa{oQoHB{M`>MaAIH{$(YxnHj&`md?oqLbRyUqI+c)^J7jwv^d zOv-NzDy=&ZvN?Zy`_3n|g5=a~+l}f#QBXSeKGsa1^Jb>x)Zg0I?2cWCuFX8pkvd<` z3w87H4Bk$(3c75Yp24rq;>6wC?45qWoWKR792ZniK6Wb&`^vk}R;lh$eeP*%8Zq6o zsK5?QHGEVs_|ojjwlh7I_U+gGq>0D&z9F!Z1{5GIPD*tUI|QHobI+px+$F!_lbW9t zftrKFSEu5G>2I^|n2k0JS64qjn5sm*&KE}$cPA7^4%(^!n8DiIbDq9|7D-Wp5wG(& zGH1vAywuLP6`kYHvY?EQmaFU)x+!6cpcBuhkD9s3El;9X4C*(1Dr=Y&&6ZsByKVT# z=I)zU*QXPMJ&S`-r?yvhw%vc17QNQHt~IUna6@S;MQd=3x_;~Y-S+7joJg?IZ>ltU zvz+|Vn;t|uoMRMx=xV2ut zl3Sh5Yn9N2U4G6d?4W&H0y7+I!tQ>2Y_q3lLD|QmPq4)E}(%9!UbA`E8n?hyM70tiCvBpMBhg?mw?P`rdvnJ!U)G`RLsu zTk`cU*ALZ&cYUw9H8?@_94w8WdJ(i>=&XzG$w8Goqxy<-c**t!MM?ZF^UNM3#@ASN zH_^caYf@9Pe2#7N@wq?GUOk?)NQxq_eJEL{tj!Ic9I<3reXgtE4vOARHX6-{rx!;s z_bi;NK%(v}SsU**{D-(>B3rM>BX4Wskqx?qq>1wvcU7Kh(I=GaJK-PbKF@l1U+{aJ z5cviD<|FsxlRw8aFVSeIl%gK5id&M;J>B=V+FSZ-T{jz3ndhD|juj0Z?|OF0yHNc$ z;qixG#7clnHLl>s{%D#CS+NE+ZD+SPaW#a&@2eC(Y-mi9iI`^GTY@e!C{=09-8Z_*5ulJQaOz)Tvjs7_@ zI5$F4YXO^Dl*>s!#zaq!2xJ%B^;W&T^SnZAW|EA<<2?OyOuB7Box2Ve6NbFkmUTQS zZNxU`!BJ^(dD{(shOz29+@1OM2$S9q!TwNMdyL+#`Z%@2VHPPz7ZPkTwk+nkIAr!r zrdHE_ClB|53jScKQ!u}FAGUt@{l2Ajh7tY8_4;RjA!6>)w_D}5GXUAL(CPP+lG{0P z`de>YO?#8?ha!69-qfupopKuOC#MmhyDR*!#r%OV9v@k(MYo&`n%i!7d-ce&5-dRM zKmmYV=e}Zj&HP(6=Dtt&_M{Y=Th;!auT37P3ER^6F^OGq8=z3Ewi_qe(H|Q4eXnlq zHHrKF+0ttvefuC|1$h*HXN?yEC8k5f6)Gl1AB3Jiz4I#l^-9fRnJ)nK#i5DGtIJcUDV>HOz$8}~WYC70aV zmzT6Xqqye#d+9D+gZ3G38_36lon`#kI>Y9Wj`Nkn064`np0`B(m|1U`w@uBzqyu+J zdk4+A%kQG!r6W29yA)}Uj)=B-{`g(Z>R^{^HlIX=KMCM(zs0bs?Yq9gY-eSn#87(X^In(9&}QA*l*bKaY+Jc|tL)i9?F5gXkMd$Zd%Up}oN+4= z)r~h#-xkTA-?ZO}Key1y0ZgnQ`}w0zmv1_%jxvTW?y8!u$t+w;N)R+JDvq6~Lm^B| zL)`3;zglj^2?5-UdI;YVN16#VOYP_UTx9{vp0B?pXqBGTqZ*ZR$EM@9DNoS`75Sa} zxA=!Ye6~fAQ+P}&IFTmX&}EG_c(x@uYi9Mg+1)Cz`(p|0{4KY4USn>m`o%e{V*su) z{&foBM6*RCo*1yVV+S+d0tP_pm23Phe#G>wpQo`+PakDY%EzWx=XZZOvDu?pwdNcL zF{vduOWc>JJzMk0&A;)*t7l}*Y-zQ$m)Ch~`I!CpxcRN)-R<#DL#&>(Z}?3f>pk2w zcd7lFZS@rv;yrS)O@;X1&F+7)ik!aI_D=Agug&Iwy;)FDeb+wwc-98e()P-VuXh$9#1WIU$5S^q+8xi*dF$G@`4N$fKxDZaL3SqR&l_h{9KBa2ucV)6&Jnd`%wobCQqjt@3~vJXHBgkoHekzT}(Xk^kNX`ope$c!(bn;9B_=KoNS**5CM2s zkw;lJ^a_zTe#BU!*}iqQ7@hfKEvzaCS*LNVxa&9Tr{Sb}bYeq+dGAq%lZe$yt2ny0 z7)qZyyMi_g&g1pGyI{jVpbTv$NBewrAdSSOf}g z|F!EfA4dCKZDV>wP4DiFJo|K9XIay#1DIdeZMFAm#9-cBF1g*Ch2JLnG>XcGgl=dG zu1I}Mw_iA7%#A%@kjn?0^&I2OwV6Gw3mdysO_%Jah3# ze|e+PSdU-5XxF>jo4Q{Qja%pT_%BV@rMK(sKC&tu-% z$6~e|u?k#*;?L02PldNs;1A|$Q95ot)#xR5*V!_k_2Zo(7pjNP+7~nkD_TA@7jlP3 zH=HtwLmQ0hz0r;QFD(EC0#)>+I)+&2cCD__Ym;sCW#QDf8Eu=|v#)Z;=j?SqLO0zm z7(BG$Z597=AXjp79KU~31PzaAUS47Rjnr)|8F{n)V$0dv!%wt+v@E!GSicTn$cNzX zcdW2w>ujA^#kDiIKcmo{oe|f6Jf&nr4aC04!E?VpkKZ>NjI&E#_Jm!5+?fwxXz{iw-VGPTk}$pnWg9)^N0UGyNEr0jbI%dA`4Ok&Pr< zrby4C>}S=uJIQ^I(xZDMZmW;H8ol(xBfZY(CHr z0GS*jas)k@r&)hKx5sOgp=KE~KfWf*G4o;Rx;HhZ5d(`pzGHQj9lNt0VG=iXr1(|c z#~q{J|7aY*TWceRfg0# zjI>qFB@DaN7@4W(4)!$oo?RA1%BeoJzXrH|?aYQeJ^pEUgV@<5&XACo3I~7R{b}=N zFd+@kJU^&4L3!Ds)G*gthL3cp{7&?MZ<(_SU0$hUkovoCgZ-Yo`;5-gXNA_k zZe){O@7*d{ex{+@n{uo1`NpE<%0sWU1rUy+ze~!Eot&5~nlS0M`WuR*pAV6`1c^kS zag23i;H0KrtwaH<+uhk#;c$hT^2eq^x?#nS+EZEyZr6qwYw|ufuY0Mw{)^$hVUM1j zc*a@9*SV)`s}{$*Sy#V^4L-wfu{V<+z0m6U?7+vz<$GpNqZxqPfIrQrhk}+y_7j*K5XGDv`_L5i{_8=(xp!jA{WNcYK=6?IO@WefJ&C$ zr%sJFYHWEccD4$@^Y`n6E0?QCfh+__CTtU9rgnpS{7z~Z@3sDCA*M|VDEpbYmCF_$ z<2xk!-2`#Q-1Xd((S35%oXVxo-iLq_n*3S%(cnooYF(IneqCthwcpeErLtdUVxJ4I zQ;_5zX@^z=By-#7;JusnGto1zqjiMG_u>+83HQVe7Y1+Fm~mblHxzY07iIbDyv=$z z`&s_W?$|Mx_lrsDvrQ9op9NPKwKnmct^`2AsqCANEHy85&9#zQH*IQqdf9*X8t?is zhx?~n4sCSO-BEFflw&b*tmOaWh{;BYc8|VvCx(l2X=~4@$NyR(?*yaOyI*^!wV2OS`POOhK77-Qi;gO8nDXs`h^o>axDKM|{0Kox(Ynf|^?9iPziSwy=PhZL!9krmws5FE-GpjL=kMMfSfCdwnt+=D?4R_tWQp`scDBG5*=m_)wzHR!tv-Q7ZU0?v` z{3n(#`Je0@`R{Lyay>6U>r~TUOjDAfod5>v*;REJsIDH|{yTV+Z&LjP?Is1aez%9@ z-}>gxU))`oVPBo3XTHQXikI=)FlcEbU~ZtaS_go8zbGVVyXPP`SDYN@fLRdqsOSku z{9{u8o>&HvEva9vT2+>$n3;sur5eP|Tez$nDE@$SWxoCNH@K2WQYT&Ac}Mu=)dnC8 zS`BnfPCeD}P{k;#;?LAqfB?e|uXjrTT*+F%M|qq&0S~J?g%*1jIH*MSKUWcdZhCai z?YR5u^lIW5fHkj$H5*A2RHQ%J9|Ague4R=3ZZ4(P9NOS*<^$Ha``F7)131$dfO^I` zkpnNOfI6}8x#*ewW#PbifK<}~aU}bGv(@u%B-<3$@aD%O|2K&p^^W6!3x6B;_mZ|T zFJIAGu3DwL*z5l8SW~OIj5XTHart}x80@&kb8ODrmTOWNe1A8yW%ul#SgjS1Ikr*X zAhSSev205a57|6wQ#v!&8r+bB+5#AW-dmt#e>?W&H9SaVe3NCoNnCt&O6b(+K*;Qt zo#ji8ec4|b)?1eraEoWaY&;oy74S;)s-}O~!k0yDsVcMoX1};B7~D6bzsuzt)I0QC zz2?xRD@Bhyw)6w`Y0Z;kn^OQywHmN&G3@07f3b1l%%o^&V0!!POmA63_svlo%Ux67 zKE>1P)2(R<611Jco|)nKO15mx?#YJ-Gr$cwEgSyOH$}4lr55_+$V0&Nq|TvDZ}Pud zyQ!pNf7kBmMc}5^f+^AXyS=nNdFj&_{MsW3wpZl$cdvJ@fivBE1KAySZ(fpqd38z2 zwHevRu>RyAwT$d0(V3#JZ#H|^e}8{F&728{wDXHPk6VL35$3R-l-E95!tc0Sx4UfJ z^~=8bt3@-9mIsHlmy0F=o%g)Jaqj5%_pLLPK$3HQi|=J0=qyR6es=cL@!*}g{A1-! z{;i4YyQfa;NUs{z7K?WXC;CKoyJhv-niro|xf{EV+8oR^*86b5D&8hZjJ~%~nVvr# z35s2quvhappiXi4`l!XXU+;KuXZZK{d%-o%>&wQ|%RCuEcvHo`;61-zADArv@;GEt z8})8_Vz9obq>6*dcy}wDoA=h60kPZwz(uosd^(HnmiY zeTlb^om#PP$@bkb-dh%KGiWUdt{>{D5sd>x*5M>9G?~2}+?|Vnxx1ElCaKkXPVCrg ze?S$kuKb}oPbwcvaIcJ*0+jL!t*jI8@ zyJ%?4+}3LKiR62&8OGEnb_cV%7b&-r{JSMpQ!4xZPf;zr@|ZGQ#toEMRi*AN;h!mg zSScGm1K)W86ThI(#crYAW$z0f;SsQMm(S|xh>s0`EX^K<4GmNknV5nbS03?cLFex2 zaQzKlYG4u(CVq4@s^^%*%?fK853RfP5Oey_<{e1ATTYn|XVS;Nzt3rYcY{r@UGNCw zK*EP)4u5>CSDU0)uc4o?|C;AIh~+?zpbBadm(+SM>U+fEd!~s8eos$y?QtZjR~qY^ zt2_lum0h7XU)!kmR`~nWgVcPBjjGA&$(jpJDygXVVNIu!z*;zAmjOsi!_4K+Q*bJE zOE#9>b{l>@MqU1=ie~=bg5ltS!&7TjAL^FNXsb=?ojC_U-hoRvmXfbK^qTkzd_GMY z0%)A(G|QSj<3BpM6&m{h-4N8UFVEyj+rcle@xN*0fqy$KcQ7gbO7e| zm`iflYQ}2)66k~l+WpV>O+Ll0zg%CAKoOa=A7fk16UH@khNH)H!&r@9{<_ZnMv^ZQp*F*mub$Q&WR z4r>aNZCv)1^R{$t|Koy1TK7IM^W&4+-Hus8tDh_dmHCQyk32WN`PF1QxPto79)|cb z(!70-l|0uxob3L>7NgxbJ$OIEjCisDpSFBN(U1P{Ti-JMXJ3wBWlwEZ#W$}QN$lJB z`&-`1|2)vBP0Cp@oW&f8|8Y^|=AADv5yeE}5{ozZ55{lE0D9@MJZ z6GwRJaT4)ZV_EXNKKJJ-j>8X1HzX&40Fq<>Jm}BFgMD*}5w`Od&E{ZII}I0X?Yjt> zN$m+9JzQF1`SHOLXo7d!rOBUDr7bpZ+urEyFf;`kqbCnbM~t70Lv%vY>jtnRN&vVT zu_rQ1d&$rzqCVE{>i;yOs|w>ZyYx-%;*$sUsi(WC zHYH9J$5ZHC?1@~k<8x?6oaT_Yzqc}t0QQQF*^-~By>A!Fx0d|CDLoPE(2 zlWyY&7HdB-EOxqXswQccPtCn3#B9$srhY?W>t&ahWqp@_v#P1+PwMHq;*)*P8<2vZ zf4Zu^`@H3AocU#PU_7K7mBMY>}5Q-wpl?~n%vDU?U`uh+o$&QtBY%f z`_s;37c5WBLns!Wc#0*h&T#0P4w!5P8B5xdg4XobpR>?6@MF8ty}#^7xBfho02rPV-mS8WDqRLOrl$s0f0RM*CykY@wxO)1Lg{j=p;e`+v~b=%Y5uA27%L~YSv=eDfRwX0SumSyK) z9Upkw8m)XVaSk$j(ER%FqqOy|MXV!Y%FIo!I|q7%#7v4gZFZvLLg`gCUv$KvU$dXO@b(Gqu{V?u#TxBjDuU zT=Jax#ncfi75_bRb|8upa})C`-L1+GTaZmg)V!S3uDI_VIWoAiM{`Gefx6Y`gO5*- zYr~^2jH5FjdOz%E7u4?!N(HI#)_ZH(!?fbh`0uBghERWQ*VgFX5N2sdP7PXAKOJiE zP8Og_^6Ay&Y2Ep-Av^}XUK{?lLVjINas#z|^uP(>Dye(P3exsMNQ8c;n?QY=S)BSJ z*oDh?eg?{#-Td#{Wac>_|F__xgIJQaNT{Rg$3zg2w7k35?1 z)fa#A!5#7EXXj6#4caY7l5DXt7FM!~Eh*ctXdB&mCNwkK3n#1((VT26x&Mb_r>@M~ zuVkA$QXL0z4w=`OjVnPm|KI=tdOH*(AZF-$j&bVv=R=hn?Lt#0V0Ut87kF)DeUU|{ zv56;V&&$fAC$2s=Jl)?@4tbn22EAPfN|nBCmMRM?y&PkgeRdH9WwuugGt0B>_0FV-t+#`2H1-I z*34%s#4nF@Bo~Pr_`eTVnshJtTk`w&C0!jRt6u#x$CWYJuQt@nA7AwSZf(Ip~t-xwE+QPV`FmzRz{A9Bh{ zH_ZrUUMLbbw&%`VfKB0i&QP;jQ!Eq(@%j=qnD{6)#K83 z)VSogh1+{{7rj!OF4&~GEM+hJYwUf*`7BSe;Ya@^M?YeHC*d|;^jN$?K#lG=K({}) zS*IqG2fxbwIopq|asE%JjIYB=t?MfU_gBi!yCw3^EU}xPx`h{9DTj#ESKY2`jwA%W zkO>6$53_0NvMA0=ig)NeUwlv%wHHa$94jwH$m5-cXzdi!@Lb~XE?vMFeNX#cazHamg4}_(W5!=vugPd`+leNKmUG$S>`U?sdMIXNiD={ z1B9(YAU<4ePa0Ji$U9a%@L3i~8$71xBzz~f{jGZYgxUT0W>AJXZ^kSv^jC=*2N-|z zZM)6%b|E4w)aSFsuVSB|wp@`;6`AW6-<4d=>|5CLwS;Fe(+b#On zUO_LxJ!T~O1M2&E?X{58Au1o5Mr8yUO|Ih(Z+~40$W{*N(*cvxV+rSrnUda7(%;f^ zb-%@bc;mV9O(h+y^*0ZR^vDE!6b>PYmIXPK1%I|#Af?QR{hLpuGJKlzj-5HLw*R0qq ziY(cjgVDA2_w_<$hNLq&m``;f1!?;$-vR>7%^35B3Wf%XJ_&tDJEpa6jfpfgk91JP zq!JGC_D0f@Do=vGsxzHY^H^wobZsbypNio)@2TcB`)9Ewo3zMcx#hRhg?+)6!%jK8 z`Jd{xNNd35@oO*ZW$tq+@Li5g6Zk(4x`#FlUI?wVD{oc#N_#swj8r)jZNCy z9wJOW;m0vq6{y={%MEj-bwXL?C&!`h5yg{wFNRhb`|!N|Iz{j=<$|F?-1CTvu8-AP zbo!~ZVk~qG&a? zM<<$-NKSPGfgct1UQ&UI0r9mxXa6~ndsp8^C33xItvi#u2zwf>kS=IJVoF&pFI%C+2B*IXxkL~|^#EM8RD#mX=o{?P#V`0z| zM@x;~@f6?WyCgvSTwSKZtGs1E}! z?kDjH@3vHW?@SeN8c7FKzCYtqc?~=r&*%4I>&v~rnhQzJHNKIWi`;>DSh}VQ#KU^# zcK?cpF&1=;lv(4t-t4nKk}+vy1ji$u8f{;^c;`gp(aI^zZxiRoea}9a2GQPrJDpz2 zlLJ90p3lL->^Gvgdheikg)6-$s#nTBy_o7kkzBE*@h!!m@oDGss^|Nig!W%+ zc+54;$?m`FIiDN*{l=7@?cUcFyV&g0<|6THp(r{A#Fy4obhkF@8EaIsO?}4s+)$2? z@x(?y)9wkE)?{@5@85kt0}??WW*#X&L2-OPlw|13%yeWdmWsQg{QC_F1{xiexJ==h z8rLbJ3%`PtlwJI$Yh1C+hHVQsJ|j$WsQa%4X*SHCLphv+>}?h0EnsPLl;=FfP~7L3 zF>r=A2HhTAbEDo9d2O*osYD?5kjyEHNi5Erq^DqNyY!cG4E=!SPT#{9Vj2s53A(Q| zI^sDG_{wxTx9>=8EUodo&Ub{;Fmzv9%Em!FfO9`1CTIIztgU>zPcQ9}xt0c24Qc6> z2?FqFn(b(}$^tOxbS zmISVflV^naK7!XU*wDJ&HLYj0X#86meWF~vRyAE#<=|7vl|i}V%pRSb<;%TGOJYmW zzTV@aqJ$>}XOup;rCxZ?R$^9 z`cf`|D1~aenU`b^n){#Ti<^>Y)5|xPI(zTdZ*DvJ9$ex5bWUucJejVsRL0+7UBn3Y zPTKoIyWWn9_gU4F&XrR#J_oOp8)q51V++D1SU+?UEqC&*`*Vso=@3IIFYs|B=@cx- zjJGHn2Jjsg}s@TS2Te;Sw+`G;YM7Y9b)>)R6k>l;(Iho66_9YqmlwJk9BannXkkM?w)OFw3gS%@Ort*=}QNQRryJo;-^ z@2v%6jCDBjd{cAVZZ{UpliHEtHkXaR=pSjC$YCjDoyUB<3*mJU##dfYdmn*K3{^QWyA zVRJSgPsE0kQ_|OW0msRm$B>iE>g?pxJxYxTJy>)v(kmc^q}v!a=9eGuWN-cUhqd<` z(`U@qG!y)iI$Wl@HD##I$$sSaSBHJoIl`R9GYD=LX~MlLWhmGbf&_>ki+t#-Ol7;| zBWkS}e@FCDvfa7%sakalakHobt=QB`O7Njy)Lu`0elS1qhQ~CjvzZ2W%ta-dj<48T@x;c0g$$pV#?MS1808In`>(k?U)~jmfgX~ckc)Wj>W{}Sq~B;;<<(5; zcTBr{k1Y&rThj$AbLj_Rff5AiZ-2>s9-q0pxbAM-xk2zJr5v73qU{a8Pr&1NHQIa8 zGWPU}4TPGt5_Pi`{jMEWat%9=-`H#4V;1C{y<+TJ6|k^MoSf3=@|=+3=mJN`m4%)! zXtyiD#1$oie(>vn9%!loA=! z5ILdIb?kBYs>S({E;XHH(}SnVl{fm*#<8zz-e+d8DkYx3-^keFw@G{8JL^gPR@BB? z&~CiDS1O`G=+b!iS{`qq+)s+wj_d`@*RP&O_(~j7Qch`~h2R@aJ-p>EYV+>an(9?& zoxg5R&k%lz3*{-xA5>YKpm4b<6rJ==fICEJwdbH;(#!5VGj(-Io|`F+_lsoP=Fwrq z&E);f@Riv4=3eBa@%R<5V2h%;;qf!xRrpBE6=H%JO%-2R{z6NY3fH&4JcO&6sq|j* zsJ;|Y<8(gjUO}fRYdwpRgM9K1S9;C`3bvz&HO?xp>RrkuJ8`;N96^DN)8d({^~-LN zF_de{Blw8(0WG>a=+g2RNx?bYu0|Isg9D6_-LKnct1d+}3-7txr9C^?jvZ@ z02eGI=C^4|`Hu@;K6k5!5iVGK{-np-Cb;0dbe9L3DC*Az4I=(OUU2%a03BJSYv`7|3NKW@9mO@8*Q>AQ`OtaEA{zS2mUrm*wGIJWfj9JJv1Q zX=j;D^sjPIuA%OjNyl71HhtJJsk3m!sYP4$I^_`xVpRciw+5u)3dfgcxFYTyhf~|EZx_=KVv>`pT`jqqP+HB*E{0^h> zg1x7`SXrHaRk#1RarlnZWYhTqSiCpC(!zZ$(fN3>gfhGTUmBk1#Dxp=--~@o^xqPe zLqueB2>aP(Kz+T3K1G*?s0sd1E>@34 zt6EPHfeC~(@42*BGNRN;ndwLnx+o=!$Weo>=iCzx!{$G9}T}6@WLxM(Mf(FY8&wWnOB<si>JZTsH&qu~^wZUkELJICxKys-NdH$Kng87vOC8E0Rc*8QAoc!$16w zSK#2x1AMf+Z2EJe#u8;GdAJA<9<;u}5aFsF#O)Na!vsdJz0#pmB*JmZ+4z9EJQ zlTP*kn$bj(b@%=uOuDtS80O627JH|Z-g+knFSs9{ReTC3OkL@K8PWQ&JJHy%4+-`QAE~V~IsrZcEH^ZZ1 z*kW;oU~XK-8AGjb{rNwej{f|!<#l1WkAiqx%|Cz|xx9e9?(+3>iB>}re`eayd;aPg z4d_PG9e7yg0~a`1r5NtluJuUW*2w)NGLMYh?{u9L1nY^H%}wD^uDpO0fQb>h^GPBZw$r zP{FdR#4!V%kFWPsjh3U9oJlkrrL#VOK%Vo`LA068H=WY@52f9c8E#gitS}wau-hDuJ&B9-d+Db^4ftK0*}~{avQ?V zc--%x?X^KXZBsAtJcwmy%xgw=MDoHtwWMk(i3HGwHDgP8NU;!u(Pc^H~`NkWvz+O!fPq?XO3 zKi{>k2O)}SV4%e8vTaWqthUuRzHGZ#C1 z@z$Wwcx+(U_94iOlP2BQ`xXZBVpm;gNXWlXjU=yqb*{I9+(Ji+AX^-pOdPl}nBevNe3!qA%~<6JWJ2HN9fp|xRR;DnK0FF)&ZOa3$jOwb?a4S0}6 z9vAobMLuzHvZy0lHk&sjeQAu;xGuH0m{R=5#)ud~rLTUv$9J^C=<$qAaSR z8}Aauf!y ze(jP_Oeb2c+)9%FJ=70*@6lnQ3o9q1cw@$Uq!{Cd2 zKK~@@`|wMXHj}dZ+jmx9fomhr`}drnmj$0NVoz|q;SGkT@%t-MoCbWhd`8Tm$3EiH zOdBM6OhS8_z7OxWoDu!oR#U326jo}IIH#{~84?@&&k5V)Snkee1;o4y4a-c0y))fo zX9Xr8C)i2an5J(fcDOuzQ1XfcS&w(Go%pvM_;!PSV!7vvc?^USy||5b1~b^No$=kv zWLF@Vk(dmZw&bG`8=#>iqi`KcMyygXOkyX0&-aNjd65uCkxQ@H$$K@(Yb)3LADX8v zHSRyYPys^r@0G{rZ7w-K?Z{3E3vSU>OF0({F05&YuwOK13YQ-+Y2@qgHx9&>@#l~+)W>s^V^6!zbLir{o@uMIjq^Vf{g~41M*ckEl z6xOKwhqHN}Duz#-HO%@^=HFK=@#NnRioh2fA>I^ZYdQTy%w5gAhhz??b#p^MC8OzQ z!Q}K4+)TA&_7@tf!7BBvXm4{VUFa#~s$~o>Hpf(YuME9NA@0jnVYg|E>AlSt&c_Nb z`%Xh}kN_@ae;<23uE*87Mc4R?P2Tl}s;wQvR(9t{-h8kG%gMw>F4xRwt<=Q}Jvl;F zzle^rGGl;!i6{q~+4&rc4WjeMT=~#eiHhCt&W%4O&%!@!l_gPR!Kq@-nQQc`gSbdD#DSF1Jp6vf7! zew#)`*SRx7`BAt*Dqq&`6+YmX@q;WCO7&E^Vfj3 z)h0@k29e`${3XHZ2~-UJ?@axQnvrAGMeW~@RX7Jin>8;thj__T{U)U6XyrYCIU>5u zT%f*IC|!GELsDET)cTK!@WbNOxFv6GodWgqPa<;+!TKfUe!SXDp^Op=N^}3s!lKbN z_iRj;o=%Cq<$x&M_&jsu=X~{)U+>GGdS!pkcA0A82?z#lmb4=^mMId{3PcMA)3Hd{AqyqOZR^8<&z@=Xh@)#lt>R* zA;%gtJ%tW=5*Kbf{7k%{KDvZGED3_UYk{Mf*qHo6{?gg*uEU2NW$OzaZxe_Xw$E_M zqkqGBt*G4cLGlgb6rdR9DTPTlf}K|#mPXeaPM!GT1l_^^FXtvO@W+qtR+HB$hJRDm z*iy4K3it~|1U%}JF9mbxDv3dT$)JT&xF8t-4Z)b)<1IPBPt5oKea!Q!tK$4t4RN?JHX=6BEh?-Ph1N0e{wlBZ7Ya+bP^luoM0Ru_Xd@+2}s{ zTK>s*(IT9T0dZYkP7_R5l9gbf`wKDAWuysre?<_J=19QOyh$;`C9sU~dyAZrBwuJ8 zsklLkaGP^I=_Vt3sXVxi)CgR(!~XrSvk;SwZ-Z0IYI_ zN`Acul%=n};6n!zCAgptpb&4NVo~u5-a*vHeY#t=Q?4P%Ew9uNxo9l~aQE%_Vj%xv& za+z$vsoDGSV(vGLiOq+{=N}7M$v-B)UgLGX4&*G2Oi76k?x>nI=yIX}AoK3#5B>PT z`A9XdGI{9tA>{N$MEjcE*GsR>UrOBj=ie)N*$e!dO5i=b3z#Sc1X$g?X*fo)rvx*1 zYuuNHcP2w9KFFN$Ws<;Gfphe{+nfesBT~czJ4h5X9I*z3z;3?Og)bKw^KRUS^pv2v zNW17neE?f&&3aT}2^^&Kl3ry3`ql2_6VCF9YkNzj)%x)n&ciT(3&?2vYd!GS0In`i zhAG>Eu@nzB*>;fcL5Z;)tMR5ryvFcH$gY?9;Bb3lVZ8P}mLNQ(!-ammnL;KTETNP8 zDowA7jmmK+{I*%Z3Cxz+V_bChrJ*``#3%Z{uhff{Hc-K{Q;frwciv@Ewip^0g;M%$ z45-XSR?XOtffp3%c!OoQz=HsXgN;wxTH0-56TTtfpP7O43SB)Q~45=hi3z-%HEJeJ~LLSRTZhhT~ z$~sQ{0(zz9QX+T8=oKPPDm@Xu8xv^FvP_ujxBES%BU9?K*I9=0m5pgh?{$>l-iBPB za;!%6M&@i^7F+$nx_U>*T%I8^)h+*ds)tH?0W7$fK8_sS(NM3(CUUAwL+wD2RRZ2& zVj60w8AQGD078p#%z*dlW?sE*Clx0VeQyi-YfjTB?O8S{pU^m#%a>v&H#?JgRRA?> zFyVAV=@Dk|(wIT6aqMJWYYo^m0QHLM>^u-K>1!{x z3+2inmTW64_a#_4c|4yYZGEnR*K*+XVH=b4V@bNpbvwedsdVeK#-;2RqObygC=u)N zLQPUiSfcm@ay&)|?Z2eZY>K)Q`aaU`F?Ci2xLwBIm)mLLG(QDB$trW?(~E|teY`na zp_HJ_YbB)b^sLWnc(-W)U~6! z)QYOb+t3o?iVm}0fCA&WdF`J1k{dP#ei$9nEXg0Lk9k)G-21}8w?ibDk%m1@Q8%E9 zY-1%6qKnFemB1v|=&{&oHS#!52Q!d7z2KH3A65npd_EBdoG~sPW_JIdrax=^Jr)uB zgf#=2bEYGq3SeXG3q4-#ysRCOTfkA)k-Z&grCams1_y$tm7&m^ir@*2V%OO4aG~ze z6mQ1vY-EL*Q}|2Y858Fu!+q2MZl22RrOy=5QU*^uGuIFUL`C1X=KfOa)~MRo(s#B- zWq6D%-n+JXX}QjQSger&6GaJmRCHhy(tAf)RbpL&FOy!YO$QnTkcAr$#3AiewqQY< z&FHITN&9u+&4>J%w$NMpzaOiA?a(l7$u3VTr=@%P;8m{Kox^Fx6RU+5EV7U#u%Kih zBfoTi>&#ql#=agXM0~>veMDmGWN)Ua{leJ>x*JxxcrN{R2Kc2=sP{DHbI5e7exh6- zPIEp?<1KlWkfQi>zi=B}NifKDgxdTZDd$v8M4K`Ng(=u8DFgA|4^1PQAAj!=n-H-M zWo7@rjJ-Mh;vVI!Db){zlgT?sB?9Tgd}yg<^YyJ0mQ|{%^8!RV-GnQ1ZffC(EqqXa zEaH$vynlDrwyZAWvS->@G{gp|!Ne`(O|>D^Zz5kx>_%DHX=g+8S z&0&Rz{ThSu*(uWE&2u(y^#ncq8#*$;6XgMhwLGM~j4!jSrRPn3O3HUzlx41L*4qxYF-$T&rSU}Izq(2S`rXMG%f-ypmKk6f0w zjO2QX3KJn66LJy1|KTDsUdKoKg3$8oAy$kl_$*Op^3>83KH-X+JyDlEe?8u9;EZ2< zPs}I!+MLrXiD01SAMXqW6Gf)RHa{+oQh1(CP;1+6hGxQh`_Gj7e$bfC_S`#>mZf_^ zc7H5zUN?CP>As>NBj=&O6VjX*_+lx~J$i4)da88FJ~fRB=a{nr50@1fBKdZ2Tfqr4 z;a8rwBFRX#NRb~vs->Pv!-_KfrnuOt?G+RLrHm0ryCfdYi}X_+Yc$-nXv&~|bOJBu zy_({CZ;92C=%2R~QNEFZ zu0RZ?A;4xUqqbt~END4G<3pRj6rmVOW_Ycw3u5|*WL(*431@q!e? zRNNRRIZ|hN*>V(8?W2jhdAj^-AGC5%isI&6XDf{A6|&Mjh!7;38Aw|<4UMh-MHN&= zNz~&rw5Vsr&iwX1a;h|my4_3pi4-+k3eQh^CCb_lx6i9vTfKh^!neL!vNJT27G;U`xMEkbB;&7?@T6Y@1FvS$-5*Ip(c*) zh>hxxj$&SkV-;R}akiPBeb4UCxqwNgM0;=GA~z&ni%4&Na{ zk|EQo#8?qijFNw4zImU{pev^yk+L{9UMYL-pn!zlZxJe@Hs_#xw22ntRj|5h&PcB> zfGfxj|8P2C{15j(b$I<5-I*&ef{&QN2!h7_RZI~{9!-|}VU-E~Zde~ggTsO>E^MGf z0nbZWc%cD3{-~usZl)2Nk9N4eilN6Y%#UJ23mfaOqdx_^6>C>G5hh#kJ5gW>kCQ?} z@{)q{!P}m)Zk=?h)mfi6{J83AXAyR(Gm<~AMjI|UZdXjVj3~f$HoV=3psu{Q*lzka zvf7AzP#dGiuPhy{W ze`G*cKAai4<&D%I2b7%+L|h>bu&kAT-5$N2S(U==c2w?92JB{%l zfce9uuB~D$BP}qO@-<%CHuAXt=>=FbfBqUkT&3ImNj_1dO5GA@$K*|YsT*Og!K)kG z`5Qp13M6w(g=2CpA=(B(zzFrv5%+X;IA#Ensy;fyzzQIaPd8WmMduTV3v(Y*ZN{fr zS;NSnabz4@zyTUS;mLTOvqRy-FP?@sJH-6+SoV>b!vP6J4gzwaLu4O)f8kYLVBl!X zs_r$KIM;^3SE7X~hIBwYfSLjI@tGzQ^jXG*2A3xj<4eu5VQ)tN4}0^$q-Lh%Xeeif zgd4&2S2tUyTcaCerMmwesbiVM?m#?A@CP+tx%60zJV5`*$*yk%)j|; ze!=~s(-#_u&?z1r?8ZjS?5xf7F?dWh;UkSKVV6||QR6&daA?rhH6rXdA_Qqma#)4u ztrR&`;zYK`>jNgRDNsAH8x$MORmDs1b@E5kt%HT=GH?rVVny;Nepnm*5LcD^jyg#4(m$2PyqQj3PANo zE~0gS7s;R}9hYfex>z3(qsp$#Rvn&N(e!Rr2ZNFhS9EX^7on04B^eQJRA3NBj!P|x zkAe6cm12V|6%Lx1LzfbD<@EK0>?Ce}RUO&j2G2W(b?=U?Mn{SF$2ICxzs|cn%J43& z-ZRj5o-ouugehK*bN#j|+vK0b(K%CY3(O zGTeauANEP_YjmXuuIPItR9N`$D%BH?V&5tUT)aBN#lXdI)0pR}D>Kfyt~iAcIHoZt z4x44Zvq<|IA*J7FmHP|d{h#lUyS)qN^^L9N(Jw)ERWzC7c{}?NZ2nko(#(qtSdTz5 z$B8<#75vDB!NO!9bG4ubExpKK4{4T+J(74rLNnB@pYE)LZteh}N?mpygZ|tm2 zF@6tZ2FRD}ySu*V2{gl@+5jtxT&nQ?eG|E9{uOs;lp`Y}2NrNdCops) zuV?sWa&a-@n6r0H#?oRyw6YK2R(~`|bM|1v5z=ibP&;yuWYOLL-Ll}BZ%z(|B_Ce~ zI1RS1+$Bmss8;1{34SXwGJJdnZC{^%_HL$3JVjH?NdnH+OE^KY?2>xbHJvA^f~SA) zLk{klYC^P`5N2Sp6sM84BKnH3Dm-7$k-6gxs**4LDTSI19qtCj%ATw-m0pbOnFNvz zAjUg^jeKZ3>2TN>LI^8_|6Kx^<6}rco~=LJN}ugX-=<3nqLBRbR3|!!T9?nyG}5(BAun_067| z2k2=NNvh?8drq~p$;hC&CUIQ^c$k;vtKn0i=v~akYYKc&A?oyHVFlwhZre`ZuMT}7 zANnep~km1DF+@+nR!F?lkx1-&xv{qu{ypYiCQL z2ZbW;gpF^$M@}FUdD#5(h{w`?RY`n`ry<_RuUaZ^B~DVGcoV-^Cne}!>E&OQ%>v=# z;dF^qih|S6g1nPiTmwxpU+^6BUJh9F42oYNxDuZF=t?28N?>%w45izNQ=GELt0j{8 z-(hz(&<>K{qY~Zq;zg+vFluSaSJCL@uG+HH&veSD5|F%HV-Vd^<(6lp{`mY%5^_|; znqriQm^Oe*aB#vUNk@k@Y-6n_ZHs^{cesY)H-0{I!dnhU{0Cc&lCZ3>tf?#w-5H~7 zVGenmrXX@Z`NQi4>W4riF-A5VCa@LiiLVjo<0|4ReHEV~PNYhRg@X^N(%m!Z*$SL; z##@-ePn|REw4UsfelxTG&qmk@t+YtC9dNiNCi*$utZ?dZwe zW$_l~hE}3}nWj9+8bZ94mJ>md!{PSix%AJ)~Dh=9sc+Si?k~Q~2 z;$XrTf{I9N;=A2X|KpGmWvwUZg%un=@58o*-xFYNjs8^D542PPzdZ=1pH-E7$=%Om z>DXxnJ~FB*2jSv#!L&Etkg;qCH0dBX9MX81Y@1;F*dg^n*IigQmrtH2bUBZ^5x>e$ zu_&L3|7j|jOOkU&)jVG^Cy@0G(}<~!O>D56Gx?&SVTtKLT7v3r41?-R1vx3kkG~R1 z=B|h?l-|6R!4<;QtkIo+EsnE6Y4k2uA}|`g`dNl2e(}uv?k$fs4gO1LAts!fXjDEa zuamcE0(p&BIVhESd_Pa=mB|}sQIFP&Dw7zbFaEw{Zb^ZQY|C3lRQK<);2uGYnXg*w z4b2Dv>R>azy+~4kUzo1KO3_0Og_ZRsnyfvYF6#8LX}6MmlQ&*!>v4=1C+C&$pg9HP zeq>+Q%h$n7uJA;0angL5q<_Y4Sr9O}kpp01u~5xXF^~uqE<1LQe=PRuy9D{L6u#-R zzdZJCTYg;o5lV^a#B^pyDDvZ)KFGVa_T;Sv(a01V<`k!LOh2x9jiL3y&YFL0Pc-%f zdPfE&c}3aO)ynKfL_L+;J{oyz*+kJuo&Y6G29k@q9YX90^v7i#_(TL9_*$e*_bEo; zeMHPS31m-B!+BLW(xEhFPBl{+q~3D*Kq(LzPz#eOcXarPQ{RcM@)g(!;5P0Mc80w? zZE2^7p~I;mLObY=8w(w&d1a{ldAYa143RPijKAs|9X`7MeC86z*DlPFBGqKwm%7Q};KQ zc!5?M8m)o-SJ?f>wb44iYJ?8edu^|KSOdFz1qkGaWX>MvEb40f%}Y!r-b3R20O)M7 z&5&t>jp(^i8JT0Y-j*Qo*WORdVsx{p@ zp?2k`9ES4PlB=2Z!zd}5h%QL>;9)>tu#&{;KJs$hcZ}m`G<@4QqKmFnC)p`u0=$N8 zg`B$BTgyy1C@El!1cL6d;vn1U{L2_l`bgMLIfvwP$mB5RkK`(>uvGlYgO~*RfLO+a zCLvvTU5wCUmIx6XIRAOOdn;q__P~%B{1$wxj z%mn=s`L`*{KFRE~Ie&hh5nM%sbNO)SDJ4C>D6-8ZhF{5ff^2iY>D^G<9J0qQS-)U> z&VU){0oRqJN^LK-Cw!=d(#YVx@^s`BW4>_C!%-BbSyt)Njg9Y z=K>n--3b}+Ye*SyzkD|ybyxxz^W#esF<@4;`=fk-n7aXp_HFG|F7P1)r@W;-XDV)= z>NWF{2pk?pz+dqI@)V=Xv|l&0c}N*=i7c->6^326IN>v$P|0RW%*bbA7~p~_uk8A| zoZfx&h&~4k^z3|J)~N(?5l3-I&%apNk-hAHP+7Ax9Uc6-3~-n_6tIUCgbBf*=Nkh` zoBO<3cWzx-7=&_O&?c(Mm_#+keSi0i+<{t$69Dn^uGPV-+PgobXD5yUPPuM>^X!K1 zb?1N0u9i+!V$u#SGVc&v=7Bq_ zT=uqk-xN8aQv?#GFGtC8?X(lJ`DQPw5}ssE0H;_7$o(j$`>&nrc9k#PTfhVyZl(;D zT37(6=Y&T%46738<&_meLx8$FAHeFv58-lWM=m_={zUm?;3|GDK^2l5!Rn(5?LuCl zn{Y=c@#)3f_4 z5^rteJ_|MAZntqo-~ zIGq+Zkt#u?1d5wNjXufWF((9L-hk0VGf@p|d%|!s=zZXW|Ez`XQINg3R>)C*wD$tU zJGCgfv!}ECwo)H}h9NMANd_$_+MlAr$~qbqa1s5vrArac%tRxm>BDnMuzji1s+21P z%W~}!iVk~SijNf#?Rc)a^B+}E)KjDi3jW6`sP$PTKx|>q1sG)fYldyJtvF+G9UXtc zXJ3CgBl|7FuK6Y-lPx8^h$3A$1zSnFYe%`$SJBQC!7Tp>atV%e*if!PHmm|LAR_BQ zOZ~FKl(CI%Z0Qb^3>({^BdUYQdCh>5B!QSR2qyWWA2qMm1L!$)`yO{mu{az^vUTt% z168o6xicTM)Whc2PWRfTIUb9btAb&`SQ|)@wlPTgync3f%55^v9=C40fCq1YP*Hww z>!$#;hN*28oBqMtLg*9Bk{u))JSJk_-ykpt{<8iKst!)o)X1|*2SbX!ArB+rnC3M4 zI^}l`+3ve(Ro7UQFjNP4+9SHfu|4eA7T9}d!HsrmkOOm;WFVrF3$MK)w+=U5O>$BB zHy4BIlH5I1y8UZ-_C+Ubr`$X|%6Wt%Ex|^XzoQGjdsUqb4(V|lqkG4Lmx#Mz2#?y} z#@|^S-P>L%W!eqhdzE_zD~sWnxgxCd_^63g&_0bmmmFipckot~z*cz!1MEh5GlvrC z?|1Do)hID00?Q8C^SADFwq5dt~gkKNKdYycG>YkvY8|BaUGjW$6 zRLYqroIOC@EoYp=4stKhqPaT=aYL|VdawFx7Flhw`&nmfGBK1G5!EZd!zEOSK6VQk z_7OeGJ4tUjpEy~HqcuvKf&k6RCLR9#LpZSCvR&PxmmsSACX?_el!lX%G=I<+`r@RW zLnQ?jj6)Nc!Qgoq9wzO45~R&f5){BDssz%j8Y%K;2}CzWVnS303$LntO4Zp8q+!oL z!+t5S=jA-{m4$YuPFY19S4#!brkPRS%?KZ~BJ1gE&$HcBW}BmIEnl5vF5_?ibPQS& zpE6yi*K{PW2ssIw+9I@rsq@5e0t*V2k58V6m;dagQ8|ZsQqXOTHd2_`vj4EMqS%Gw zgHgTGUY&X~RZdpQLVSQbyuh$(}X^0J`Bx$?g1DL3)IG7SBPX z{QWlz&6dHFsR(9SF5}#qk_W6^t>Zu=VT%j_(mCqenH8j}OBj*lbSL1#(enDO6=I>*|iiS4OzSy$3Am9x>6HuJVUg3UMpvrS+$nZi(m^T6Lbx4Wv0M0^>VN=wMLU`}=7`0)t=BHCY}Sr9Cxd+6$WP@+AbLd(5o%vh| z zubO{ts!-y`g%PTV6GQ}MiX@Dxfyv}yQ{wXU1ztH|j?lh3pCBFnr=~oEb%mOenf#3e z#xj8^k%^|2Q@`)k0DJ($|Mmgjyy#fJqV5m6hYa#Chol1q%uTO4;94=oX9X4JD%%?- z@u*Yyt9%c(hcTR5J@T5W;*6>UAGdTiPNpjupE8eHKq}0s{+N~X2vYVnAuh$L!dgJiq@3tvCoJJC*no2HGAww=MP7ZUy|QO;_8syfjfz@k!u5?BX8{ zm$g1<<~W6+$D9%ur4f|1LEbHn+R2QWbRpd~Lw?58Te&zk9u(E9NRs3Z=0`-KWI>h( zA+sE|Kc-|ACwWl8YliX*l7GtYUK0itAu6bfl#9aT8G>aoM~SbRP@2(AGBpqB=eIAo zT46c(m9JqavGwajU;9&0$TVIkj^$(sgK3;MC}%~c0F@m5p7*Wm?_HlBfB^lm)Iw(Q z>$}okXaOanm#av;3;+0iskHu4L8gzIO#9s@U_nR$Xxj-kj;GLQZO2sBu?#*47p16j%Rl^^yWQ8~8)|f8-An%ho|r z(6m z6lw(MdCKas7b|Y0Xsk&F__^nDGDYg)=J2b=5ex{kuLwoufk&hR% z+UlrX))hE+LVh*BW?C$L<}e$uj;y|ar<_6`ey;X(mIyei33P06!Z3_9fKX;|r~0Sp zVHJEwcnBI52v4t$q(O7>hL3_ygp$H{rxiOvy3oFj!{4y4TnBEZtj~LHL1Ia34R{nC z(7guryYk**68KcLs_)OlisgfuYrS8A0^VeIz|b^*5pxC#sz;!#F1=Z)`5i~~8aga4 zuH2m`livU@dfW65w?MCR^pGn6cG!>+9`E$wr}DT$z(u{YTnsv-7QNQb?&_VkLpZ)O zb<5wr0mrw@$$%lS@LdbjNE5koxs`y$Sy9GiGSC-lS=V1<5`KCsFT$d1ja(0)R%3kA zpicL4t6Q*sL`~RrzV|G6zH}?X2&k??gv0@?Z#7)ar<9L;1EyPu{cvVMGCF)eM*F$n zqURblC#>MVi50RUd+lHW+I0HvrLc>Xcc3>U0m=NFE|GBvq7$i5YFgUFbTrp)k25iK z?m(}#d~l4dgPqtxZ4lh#v(N%`uLbGd$k_S(YC+tVJ3Rd1+jE=W=I`#9dH;GpKMQ>v zPr@>_45BzwKBY`Ua zHuqrG!*lMSpYfYjy(VK6QOyiE^8VS!)cM?~JogWy1buQc1m~h?xWMpL0r%Q1AC7Z9 z=+PKE>P)cwkeHcH!eo?(rXR_AfiLv&&Dw)d*@F!(GW;{FKz#I|? z-iuFDHqNd?YqF281;=DOf0@>9Lp6##CFnXl2rdqQn(@$QDE0DPaRbKelpdKb7oGMI z*?YlsPZ>&|DT2#SV@_g#Lc`G+z0rc9j6Ev%+xL*`X}r)U$%!Zi56)cIi)=9S{Pq-p zfh|a)YO?0OYfAj)HI+#*AObEZA43uQSyS+1sw`{qJ$}b8a*X|1LoQOHAE5B=C$F|! z8Y$0{rOPMa)=azRf3!Pq^zlT+8q`$kz}`Rb zfC^V0*a(v@-X2c3T~ijO43nG1x3OG?*wvEqI0plT^iKA(kRWle>*x{VVB2ltrJfyv zjn=FaU$0A+4}>dfrp|_%z?bh-l}(d^>`}KwWUo`>Ba?0w)l6?a6&nMV>MTF#l!x$HZP1-KnIrwFY-8LOLGafhPzu>W-FKg>?OTDFX`5^1wDo z>32?tZz&7I{VhO|kSE4KYfbyt2-~gpL{>7>Ynu3wb>QR&^eh>9!FAA9)jzefde0^* zCX;ml$H0ii%w6(Ywe&vR{LBp+E)?eL_ll{8j9XLDgdA(FjApX;^#mSOUy3PL1T z`00rfB8whVx%_35NHH%UTNJmoC*Wwe;7%a=JU!I8%1o;d*p&J)DEmwF3!H7;? zD>nn5?Re$gygPx3@?rOQ6)%?!D5G%Eq>@4JMCYt*D=d?8mJ{H3lE>&7py}BMFlFinE z?|Q>3q%Was2nsrG{m58bO#b>Q+yC?ePz7O8j2r^?7(a|PmK6u$;xX}9qzB#xV}5JU zvWWBe*k)Z6u_AJ-@BZVhUSLyw)d>=<^mk>v_p+fU!a7D)Im1W_sNe^Vlz|OM2T^AQ zJHZ$mz7@hp^n=)EYq@Yy9!d&hf^ zE|fRtNVZ65E0mb}K{n!oc$-9~Nb9jYlC#NekGX*5nIyWdh{Z5*2+@^bS=on*uO##M z_>D=lYo-9z2qC%r0ggc{+pY&!;u+tz$=0j32iGMk(-NO$JRBnT;Y5I0NQRy=A;QF; zc)l!bO^H=Lmdz0+!ui3Ppd2diq{yUWx3>JM?=+6=J-l>p=JGw*sBiz0`GM;qNb(Sv zgyOIsuc|vkwwR0puo{06yLBpo0BTo@PUyyrs1He?zb_HcGyMR{@(LW7C|(SEE73&; zNO^uDca!JBd&9-&+eYoHNJ4pD?j8=)9^6!`i+W8$the|Rs62puD`feK?rb17ey()A z(j}+Y4I*}G_6hR%uJ}nOYJx7#MHy3c#9F&jQaz~)do45;KPT9Ujf_l`IoeV9)H!_{ za|$CpJn;UG=a~J5q1ZwUq8^ZYs4=j}0xf};UD1t|!!RD&z$*Co=C+|Gn>_k_+-;>y z(AIA8tj;o}+bD8@Hk#*7G<;u}QchOwM&|rsZRf4@nVr>i+UybrTA}%sCfyiJ2MxRV+8e^(D+T>v3wZ^KK5yYJ4_}SU*Q~1iDux`qjQF*r99~XjXM=?lf0bS5Tw(S0N{k>%^BsO}VHylQJb5 z+ttcRmyB%~UbuJ#S?vF&;w|g5=F*FkoDxj8abv|%)SzUSPh(>I*x~Y#Mr%v{7Sp)r zv{Uo1ntMU9fqPVgBr+=HIFIzjj`62ZgHBIJ~ry)1>3`O*Id={I%T6W-Gfg>?dn!f|0T91|AW|; z9Z+fHO(T^{xyr>b+#;JK+1Zx(rst_;Sc&v}?R}>hn&Pc`&qrkv@h1?0;Mm2Rjd-Y~^@=GJKt-9z$I8CSSIv=a zn9!ujItZ0#Vr~{eEwDXv2whhcz>Tr3Gz3nIi{aNBbG1x9RArjP7hAsZ zTd{d&qloB5hBIu73QxIW_(zGfjeo!$N;L95k|bw@If^J0g>(4;Zx$XRjoy=g4bHf3 zu;D0hTqb14O$>$mNpq4MYqILp^XX(jEY}B(R8r&z@xN7-kdFbSj1sSR$~5f13L&pi zWAJ#IT?`;mM`_3hu5=1rVLIxTN6z~CH>+J(dCYluz$|WXGCS@X2E?QU)BXooSuaYW zHj8FXhkLPV@Jh59UEgRMlv$~5vZxwPN^HPvv5?%S+*Jx^?zY{-7}NeLtn32lZ5H04 zP752z#nG2;&!{T11CZcz*P(Alw778pOk;x*Q+@zx)yO^%RO5?RjV2`kmx`RPA1xMS zt0jp+QNAmI3D?{b>m@xeiWI5pvP|J=hS z;kgigX+w18qXlXX6Tv^q<52cU>U~NgTk2L`nO_3}+;0d$M+-?LyDwxXsE9EFk zWUC?%e#3lr%ZPeqMjoCI5y*@}UCt-7f^Eu`UUojAM6N;Wc#^5!EYE}FhaPHq!!SkO zGJgb_RPc^4S5{c&y*3}vW6|K!sjd3Wy$eZ{SwH|ur}a-;{2$`pJRHjY?;p04tr`1n zjD6SGm#l-4ElY(YLL_C$R@R}ihe1-2>?$Qmi#@WZLbjB>BCxebeWl73Y?ZH z>(K!ITY&>#4m!?viw}-B$ia^G<3gQ|SS9$k&re+9bb}3i+wt4?>xgIwFhz{GW$xGkQYXBZ*UGIHcVc_|MNb@Ia8M6BRdP;LC|dwlo)dFVAV-A2#7-hZE@sqHfR;N+du z|F}&I8Q_-kn?Orz3L}djHv@^#0Sp#~8|Rh^Sam1#1q*!#^v!WgFARJ{I!h|#o;&y4 zRA2cJJk|kH++!kvzw>*c7ZF0V)=P`BEuDKV8&>p{aM8phoQi zTmz|fR^V*yf`0LY>I9HxZ&oF0>-a2x?}bx5T!=(`k|j(*RLwmq3k=->nWeq!E#`v= zN>BuRLM7N~&m*cS;5z+(uDI)6r1Ci^h;xfWV*GKSv}~#&yjd!Se?%UG>Olx1Mh8L# zLdMCrdX7fs&RPR)k^vM{7t|dMoLnFbyP7x6o!?gt$G)>=sWxfKpm1A1ZHwcY{N>6Uej zJEE@9TI;vb_y}b|5i~Y9=tE4h|f$+`_Y8tW1d|ABG5#u&7AVN90~j zfuo{`#OQs~G(+O{Ap927pl_pPyo+E9pFPQQ<4D*y`v#)w1b5TK@xGJ*C_=gRrL} zcpT;&RJHD48cU#VB^x&2XC$;jbBhGHA|$Z%KpYK-FZ;hb>KR4RS`WPW7`YSvQt+*a z68@TQ98{{4UV>M|A_LR&kxgjS?Lo#nBiLNt(}~q2s8Qv=)q%?s3poLe#nCd`G7>bk z#;TR@Wqq&TXq`qJ=Mo5eQ!;tDzxk0ErRDHL`|4i5gEqwEC+vIlY$?U}@BiMd`1~jJ zZF2RB+%HFssI!r_g7<R#*i3l;2J>$DQu!yn<&+Rd=l1M-kEU||1XI>U0!=$r z`v~wFk6%N(b?R0lqX?xMrjrOmy)`r4L4n3&81Hj`7i9sGQy~^q7?!yao2NvRuc`9n zTOydliBF$6lDFq*!gtqClZ9jfC9(mL*#>d%L)MRT!45p!(^V8{l-{0QP~?@FAQU+~ zey{5m&Vz`RDiO>XN4wG$*%2N?}0i3bRm-s!TyQYaCj#8vr>IW_2KP@Wm8aB+Ir zybij`jd5+~l-0`Vj`Xi}h`h(>p-letVcOlraOFQPh7O(72qiFznJd3w4fQ@?6-iDa znoD@0VcxYrLx=7NTfG6lQJ4s&8}&tUaWh!yCSN%~uuy^~!>elloMugi*k-ME+BoKR zn)bv7pi-y`O%^`Z{o>#?D{TNxhJ>Czo=SNyMvIurhz~!=Kzs%e?^^Lgw2eqk2GuOZ(y-IqW^30u`+^JkCr+uae7ABXDoMb%3Z*`e*^Gln zGRJz(JJl+k=x`-;vF=D;U`0IjY~%8Sp_Y6x%31S}<23CwJP8lqSDh-Legis-Cr0K6 zyAT_pxw3vIs~2~w%B878=sln^xlwF*-UzKF%$>UDEmhK9{{XO*{)DZx2wdI{TF`YD z?#a;(cj$ZkM%6k6P_a~JbE8q$fPH(r{Q&DbkXMmyj7Plxha7deCYz~6=+pR|>3gZW zQTr%5$hJ$jqU2J0skzY)_4GpZMVj9`mQS4$;>;H=J@zo6FYUmk$;}PA>+ktAklXMa z5!?Ky+mL=PQENQTzOW|`#U(;1j=D`l#=C<6dBxn9dIr!B2*EE}*#lXi@eUAv?ouaS z00q_aY@-%3D|*L7rhU2Fu4et}&dtd-sRwr+2FzOTubTxs(DP*)a=p4(Re(e&EWGqz z(OKNp=Q#vjT$PTJ&(`@|Ici)?*4D!CBV+e9@niJiF>ZPTpb_^J(geAv8j4+)iHZ<+ ziD6C#5LVfj)P;Kj1)tLR=Y67hD{z;CIt|sHvblGhh9#C@xqIP6A)b5{f}p{zIP2Rk zd~9_EsiO3VU{4T7eaLo)yh#kCeW zlxZLDoRM#3mWN(_NjK8T5dL!~VoVNtv&X-2e!e!#{4L{- z?ss0jJw1l%5i0|!(>F|;=#Pc>xc>{S^Yoe zFDWi3siMdmP!;KJ;~Uns-b{;r&VP_Kb`XN$BzDXkxlyG3)>p|u3rL4jaI&EKjc;To zk^6%)oG!czmtYI>s)f&AYLnMBn+Tgx%zaPf=YPA@<;;i`$WJQBWP(VxZj`x5s(UvwV6_|!03`DsP4?C)5TF4 z;0SV_>Uhj<1wWCd^xQ}kUadH}#FUC*k{kY-zB<1vbP0X_vPXQlRlKi(BiRzXA!0CS zs=xguNC2my=F=#FedfRwKK0d|-#69X2+Xe~8hjlwEpiACzb~j&+9ZyzcG4xGCqxRY zb2zMPmnglI#CJ4=r!EI%S!@}#j|-d;{hAXz>Sp#;Wm|+(Zd;nYD>Iez=#Nw}`GE|$ zkOLV_XNDgd_Z)vJk)mzeds=7F^19^uOo!xa+w&q;t}pA(w|%R_1@@eXpIy8BI>IDcuK$D_EDgwNkcoaHN8?Vg4u+m_oM{?_TQxZSjBN3aRV)$DuyVEV&ioumc<7dRzUm>|2rMVV--dHw~|7Zf7b>b8ZHBlNfKIhA)tt z7*VAsbsf1+sN?uBbJxH_r)gR-e>NVKSM?wpQ#2jgMe}0Pqk07r$*}^XgNMFo$m2_5~ko@%@R|t zvx7~^kQ6)qz){}dLUrcv^XJ-lW~I+u=%6(SZMTtsl6g}89f`W@aM$|}4qe&jBD-3+ zkDFB2RJI4}c&80dxw?&tKN5l3(Em%jANS5#`BQJIpV&$qb&Pl)X?H-&PS@$)S|Q^F zpI-AprHFzDPLIA1ZdpIK6Do5miYAqYexF9ACbh14wWm!*cHSzn=xQ2EF@3=N%I)3e ztIF?L;UvY-!wWT^dCh0CX?)rn@0U+s;yGmd<1ue_MYHd8=O)R18&>q>ZR*SU96U9NkxNG?;_ncdlE z)8FHYvp7%hXV+}auxFUL+tFNP(~w4zJHw;y|9kK3`?5>5$^rA{=T2>&Fu&DfL7HI2 zI_XkH>%-$EW`%+Q$R0FAa?mIBV;9A5h2cv5&a-}S;z&pF58wGT37KfT2572FGJ z6@wB;mkqlH=Zb4=-$t((J#gv0v&^tEa>J)9!CtWars3G!r{`zVFIYbeI%mH%6H>Pq zow!nz*gA3|*@)lmcZJi+rzk62`273mlAl9KDLgybEIHF1B-3SaCz4l+PQE3%Vxgt@ zFJ^(XiEz#KyZoCS`DKe8g5s8@gHOiNYZg2GyOiahd=oYGNJ_gEv?X0n(uYWn?%S69Q1)72wib);o$n67d#&9(E^ohY0um^tCznY|#F`Pelv z%Y8W^Fj~R_4*86VZZ1{3Hm=RXn%t`&@yV#IT8~>S>g~zDFj=1+bz8%fNsPzomP4^9 zK8mKZ4g{6x<{QCiBG4%J8pKYTef-M%$8%UTzb16)Tf>pukSfP}qR!t#m)2dQGx+g) z<&M>3mm>_1huPD=lH#lRt`6Ee=()g=K97k2e zX;oV(A)9>@jlm6pN`#NrD*7Q(secQiLla#yk z%t)Ym;rF2q;=4Nor^{Ei&TZ!_c@G|?pRO_fY*id0RQ98j7nf&hn*G@KS@DUjhW39N5fAXkz%RSD%sL#p3~n1|bQi)yuU3UG8`ueo6kox(R*sJ?Sr zz4B96wd)*5c`92+y6F|~;EpQwM35tH_vRh*5#6)!t5%vphhOx2R{7PUyY*R&v%OwY zEGo-73!CPuQ;%;1Ts@y2`_*RS+|JD`v9;6m`5aGQdv(?S()%&LU!ug~*1P1ecd*}s@9BPW+Ka9AL*$pZr1>%XzMEPPOm3-| z-_v>!%rE2f*yoNF1D)d8wGXMRRnwM zt};6?!$~2QmIONS4p8$JK}c~#M^9p0R0o}J--*f~310M5ZgPOFIQ0H1=o(N8M7JnM zNF~&-_8!isz7Im^@1{Xccq%ias2d#Vj|~93HMz{|z3VkV$b~u#%7UclulEQFBv@AV zH8+nI3L)@Y!C&y(3IowMm662IVB4GsvT0RWxg(gDDN-PPKY8cIU+`3f5b6Nwq5sSQ z@Rg;3=ExMRqRO&!fcpB+5ADljHx4-2b=7?5_3QYU_X`s*a>-XbUukP^`9dAo#M`h7 zC<}sOWujU8cA5#!(G1tEBzb_{i;7;U0o|WUl@peb_$B2nWLsC)12ym6@V zyuGub?iWWD8d4p`GOPK;;8wlipQj6-G3HH!#}$SaayIZ1WRVz0 z7eTFTnOOT3lFaP(h3KFaSU^Y9+#Y{W0*j)iL&$pEe*t8eeTle^%Tsd`WG+TvLO`E< ztFDEP)7ZTWH~+W`Nhiv-M^p&+k7>&WXYziNpbwJi6yd#cCoU%z4RE+{(&RZ$Eb7qi zC#(MP$=olkkL@hx^BsRjIP2ITH7p%2Wn%O36CF>GTqnmcAyX<7e5NnZ=Z7WHbfOeN zo5m6|pX~4$o?W>};9qi)j*jFHGd(y1euEeBhTNABr&_St$sjW-{Yz1-+i0m_b!K#& z3i4CE{`{$hwyHwD%NtTAH_A!nrGQkiTLf{q0G)v~yM5CFFN`dJy1y1cg5h`rgYop6 z-z)y1O@~R(LiWB-oyhm*&6t;-E>d4P>P_@>-BIHKu$OQr}Ig z6Ii|VViPN66)Mx|;4jg)6K1NgEXdmRLW)@gay?WFLvd>l_I|$a!k__$24Y$cUIHvl zbcbY0*wc1zn)F|fBMh55q`@TDsV(%0+6ug$!U>tL%W9aB&yzy1@ZHagru$tNSzK)C zE~{g7HZt%0K~Fy`W_p#6Y@%?T`S`atPvUoR=H$Pwb0xm9DE-Ft##}2&JJ|f$qi)o# z!L~X8wHs3}OYN^YECPW!Y?U{Vpc|80+I9W+>}^0aE&>A*(<vp{E!Xc2vh=N6VE#Vaeo?;Qa2woxr)}>8&ah@!`DBEtDYTAg$&Jh z1XBgeM+RVxCIBm7VAfL{yAK?&l|c&*+&U4z&9Rh^5b#H*3h_kOC$QmGt(VV()|Ui6_Md>O&j8Sz1+IAMw73T@1>4<_*EffB^`=-%P{*J;G82&4vAwvpGuMLkCU3qoF(v4w$~v;LMi- zi}h0^?V}P}z9_=wOWBr`{%@(5ClLP$GLRLqyMD~ZKaYG$2xrTr+W`IN9BY1sqb}0a zaWqfm^P^f{Yt#ODLbi{f>VhB;|(ei1f-jpmBanQJg^S9-73 zQk3?qw$_zrpL5fXIGs2AHP>5|I10$rb4lYWN|6GP^l9Ap5Saqh<$^4h5*#sC0f#&Q z2*%@-+VkJqLJAfk*sN zxp-5YuO48pnYKa;QmF)h^@NYthxOKl2Iura7{CmiBFiV3C;RT%EB=HPtNiXX*vIeq z^k=b29MlCLEB9TU)FQ+TxVUfMz69lbg+^Mt2*9K7n2xK11N(6n%#rNm4;~eQ*r$PI zAyYu2-N4x44=e&6!bhq>Bt>1NyW{ci6^dBG#zB;8;b=cH4GEj(m<#-YsAIdE?>W)9~tciXg|Jw zb58mv2qdfWxNi}?SLcUqDu`{Dmmp)Pf5$RM<50ogkP|wQ+hHFR3O2ZJ3>KQCcS2ZT zspS%g7GwyDo3NlWZEKfXd7o#W0nTXqO0uNN?V*dVwO|-M-HC3e$5ML2BF=zTzY`vC zfZ~;Bx)FHFR4KP2(;S^hCzDQi`uA=GquBBEZxmXgyUK4Vg5P;z?{7iTccrx5NwqWnt_4(lfS6Y1>?0%e@tpL}tPa%K;_;1_* z;68ws3UDzCq! zeE!VE`j#@4>5I5_H!yLfQ!%#V7nGbSd#?d9Z;z*<*vM;gf-K1V?+b$uZn5Yp_2=ga zqWIZfxNcwlC~J?lr?96KYEu5fStwb5*$+je6iR$BJR#_K1)=zvC{_pGjPrewKo&l6 zgz-Tznxdq7HN9coBFj6)JWa{IYfR)Ba^q=KqA}D%<2nPH^{ce0gn9vgI%D;i=IuaaWTSETXv;& zUZkT}X~FD)dipA)x_`jqQZHO8`And0KFM~G0_xW-N(LrQ{J;LSjxPV}SfNma@ zA-T9*jEh$d3wuZFd^WBVb7$)O%>{@vEenZp1B+?M38H$m?L^7D3YWHh&oJ0rSs{{3 znuO0a;bVKgH><@-<=Kl+Qc>fgWNr&Nz}utO7H2DzKQpYgKyj-9_?`mgSY=8{h2~EP{U>*4_r=i*+_Lonya5 zO*?iB(f3Za<4nFOEgnNwU+XZ#*-ZAR4@yi3a7PxgrX*sY_th@O`!P{ zZ7bxM*e?l8!(Jd(OL@-~8VD)V&024h7*YFtHk_xDm^6B0YL!zZ@t&zpRJh9$G)sEZ zKv5I7fj1M!;2I$x%~gt46qH7RZ@n0Pc$cCU6j1Vz>;|WJRAecGi_Kr z7o`<#6^bD6W>W8KCDe6CGx9KU+NVD+hX*5zZN4woYGXR=F{87UMRQA$&=^{>3-nF3$Ol z!_PCGJdbn!W&TAQrGgJn<@sDrOwE_zGiE>Pru^;k+i!vvUoMA3V}ovtp~MsF_N(PJ z&?Me_w2lysYNuW1KiE;_pSOZYiry^W18i8dm{LDY-Zu(#7U9%wG47BK0jx*qV(G!# z(MP!aR`<=}Q}sWU8$OD}Cv5o%q!Gz_ozoKH*-ZJAqJ{5Ik(i+PeZFgp_(Ma1|C*m< za}#K;7tUJTibc1zsmkm&I3;B>L@1T{)eIR#UcG-<1$scf+x9*xDSH<^*HQ=%_xA|< zqsTgR%h`KH(Cmf_>=rz$BD_F`tnI?_|0e5lyr-2QU_}=~Vmy7q@81+t96Jme;UBvh zD2$MnSJ=5=f+>v{)o`P{(-|7(Iu~m#4LSQFIq!DQpR6;QVE%Y29^(#>gi7UlEG+p`p zhRVwHixxI$a6L`}8sxt>geth{9vEP9(CLp`*@!3H8 zYJ`FI_N}dTPoXub+;`{JPwiCg5Go^&j690Hb>SCpXDr3-p<}CEX)Vro0oOwOo_vD;D54M@Q1y>4Yib z;nNa&ZpZ8P?*c0`|Mh9)H5~5s%kTXT`9&#UoUIE>H{D+VGn-)p#uz+F8Kfw1AT3@!NubyQcrU zAEB6LEqlD)u^JjFNV3QT`+{ht>PHKzNn;EcLXe(C62j+g%N;Tm3{eOimWor)j59`l zWx^l7vKvoO4%_fWs&m`YgL(;&aU7Q$B8^^3ZiH6W4f+p~(kbiN(Pxhqc|$HiWJmE! zcCY+YyzXxCPWQ)MKbdN6k4^$_1=TR6k1$1(kOD}KBoE!mfFLo^r_3Q)5Tem{B11!h z5luiLy*v$~1OzQ9jU*He&C_Yd0xnd-gx?`Ym+0)!$>7ze8r!p|L_>boA<2rGT8Kg$ zzHRfOgbe3yz`@I+zfAS246lII=`c#Iwu;{1n90FeXeC;-#Yd3XyUuieMx^~d8< zB$OeIAUC8Yrv`sl!KSKFL9UVnxbm$gH6}h7VH(X7(O!8de4{)-IuT85D~X7LLjP=l z1v7y(A@Y3wJtshE^(g<>>!VdqjgMqxAjL@4Zk&dqEPOlx7fp5L$#66vfwBrbZ}+Im z8kG|D5hfIVJGD)_JVIjAJ$tLJjxo8M{-x6AH~^s=`tAG2&ho_VFYGd~0>1CtiHCit9EFy&lzXeQ1F>&4e1_kS%lC=<{@x2)9LkSADn; z(3=cG>tV0W6GHTp_Ltdav$lY z9G;w&wbcGu*nj`nuj1iXw{(sJR3e7-oRHgV54xJ!qgV6*oCu~KEQc_$#g~DQ(U1m_ z3yOM$AnXwaiB4v|Vd90lv(WAKf|Lb8a_S|wV6aH0cy5TkmX4)oDhR|ofL)Y==!YZT zI!&cMVE#w4CUW`^eGPOyBuI0n?mIN}O{fDBjH>r`n z5K|e5*%gjmS`Z*5Rp|NrY8EYrAb@oS6pNXV9xPcFGFMho2x`O40e`&on~04GT6^%3 z8SR6lJhW0r$fs-%B!Q~Z>zx!oXG2V_9Xb(I{(+eN=?Y<&EbCOq5CJg^?EcBGY%JRtB(Kif#np4G|ZSeU)b#pH_&%RkNrl8ONsw zRoCDnK{wh**9P7QTe0z^Qp)MIOgUwUEQh<3T>JCW4bnj!fSRl)qY0NY<=#Py4IZ+G z+jkuv-|3`J(mP;rOIsGOz_j3x=Zz6X+f(67GG_}VGE@$b&MeDmj@+Of#vuJ>1CXNo%?uivJeQ6 z38TD{hU&0`L<}Q2RGr?Ojs8}PF)qpy7Q50b8K60(RI&U>p1e`aQl#`Hh}a89u$^q> z(}#y-(*DQiGYr`R*wb28#@AUB?n7NX#|TTd1kJ=2E382*S=ne{?`SmAfzSn;tI+01 z08Y!MZ5m@L zCmw^8AhU-&_pGrBc95Z?y>nY`LsUxwHC7<*3fbu@5L1kkq^!g9*dRbCE9+}R=@6By^3*hu6rqHG1cE0_BPEhoz_UuR-diLt|2zpXugZmToh z4Y6Go@Pk(O%}6`|z!x*!oSBhSE&}gxl0Ux0-+VWsF|Y}uVt_^wiv0Q{6GsDhveNb+#drm zl&qO?I6e%FKE`>ep^%+P(g>WhJ0sSQtqkFv%&hE2V?hU@he%+C`;AK4F zF=v8X67u4{?^GwnuMzO(^dyP#Ye)UNCOChUCMSlqK!RRmESe#A>4cXv9ZAviO`aWT z8FtvOixQs3Je-iw0eFWS<)v9a%Pfem$@vYtC`mhf)6Ng@q4E;5^IvJ(K1XZiDe!;4 zvKSzVk65Zt16*s2B=9nz43l&D$;(7In3bSJ7eF|Zxr9IH9Y*UrzN93K;iog`i)5#9 zSmSJ{Qm)9Ur?>A`DOdiiQvTmR4k7i7FdlM477pPdiUM>F6et&YB&g6!3{apPSGe>W z3xz{cDsN6YCCN=KUhdbAOK`HwUmX3uUsd+oTXs=VIFl65>{5PaU5wUJa23Ri#7aL`D!I*a>JeczNZT0vl_R^nr*h0B3oeZZuMtD53sQ_8?AW*tFAN zNznXRo<(JeUzM=ZA2aLu6akCLuYp-T=F9F^-v6hnFx*vHm?xer?a5{`8I}tPS#s+j znE+z8RiDCnJsFY*b=ayWwd_`(L~1y5@F&3 z0ZyJm_zc(^*12*EwyA71$-2{?_CE-<8GxnicuKtIg@6+#sY)2X}fv=F~`4 zS@uYwEgnM#l4@Eq4*6v05(KSE{4Itc!Vt(z0h7yu5P5-ka-s{Y5FzwbTZ*d9jf@03 zswi;XkTp&gS;YdGHfP(jrw00fyV;$>9fT-1I}oc;PUpk9ZC&B42kxq}INd0aCo_W} zP5|gko%{nIZrG=_@TOx$|vnm2cqpar@gVf$fs_Kb}V7I zbEoqGvqH?lMsnR%M-RADA~9xUX~*y~!1~10c+ z2b0(SY#VplUPGGd%DG7t`p19yXo^3ab}e*%oUQ#}iW-k0K`$Ums_J-#*FfF`WiwI} z;a`0Zkni?zMdHFgS~P7h+%*;V;tA_JEs%z&zRXn_+m0}o&z{e8WA`GLp#hiiJwTGg zq{wv5nmPsU;P}I-oU|0UgDZjE+(yjEcLkb|kQ};y4QkxWDV>sU%#ZxVA<#n6c2wB5 zsYcv5)si8lhCIGl-o*rFczkbfd-ULNyWN2?DTxezwG{G*|NFlI{NUdMNdI?>>K{$) z|DP-S|LjMwrNOWpQy}LMek%isvV*A1q|A58(SBAz1p^Z2N+Db1BK@f=22?EYT$Go& zG~VvM`>a8kU$j#oQV+BhnTWmu1e4%BmBhKcxQJixV&2{h9;GT8>^ML9CT)2P-BViR zi9bjBB86TY6n_6ms0%AH&AN(Eh;VQxWeg_k{}10R8-xtN>i~ld;&_VQ5d<1!PZQ+Y zBIULQO~eiyRz)zB@&X+6p@UZ0L+4L%QLiS(p zhi0i{D60O0cCR=)fZT~k#HaGN6g{pm3TitJJUA|o(1T#8?EtRI^_K&53t`JIIg$K_ zqtou|+q*0XI8RDE9CIqVR9H%AcNN!m<VF0q{n^t6+g~taNFnX&@LO6zrD~puwo%LpI+aRhe0^05IN}8 z^aH3rH;8hMNMjs5^5~>_8Tha}j{rfuKWz?3z$b=IL4ZcUZ`%ENC~hbSu9X=h$EUC? zC|Yu&`$~M1WVgp)EG_~Sgb!RJEI8_btXO5#yIFqUF$H0aC|D~So;ZA8AXC|g30 z)T;?LCRqj!nKztHmBTS$AQa$3B1Wl!sydj*x3P=<5sxx0DhQBUl3e!iW_k13zjvfR z{AKQ(+@G2P7}>{AD;#wpABy^RAWf^P={CuQpw!7jLI{0Y7S;S9MeLv7!0=}?Kze4{ z<-y-u*z8gC=(*Pr695-!Bpl)W1A%1rt5tGhQS?w>+}2fJ+DE|Q3(wqb#RYBlG`^kU zcS1LIAwkD8tU@&pzN};#LAcpW)Sbi>Jvi=+ z#t%1ZCK*SiF+Q@TVj+u;;-SC$6Uz+@S{l4Zvoi=rg82KO4Vr;{g2Epe&N);Mnm8%M zpHyE#dL;n$*F#$4ANo}KMA%E&Bxtp15QO{BPgdqWSte00oEx6T=p%nu%Wv|c?E|M{ zDn1|iG&|s?Ni|)A#5H@?;D<^8N+CAqf59k4=@I#S;ZTe0MzzML{F@SSl+V?*Nof#* ziR3jRIWE6CuPfh`Ia=NQV7pdOu;?l)}AT^u1#TH74M})H#T`E$CUf8QiWnHSf(e5 z5Ht$8lfySnY8+Y4Iym0fO%VJi)z&}quiKbWf*p-rqRS_LAun(hgq)fngk}SQ=G$HS zN5v2TV9-|T_^dLQ5C}5$*t6DXZI&(J7wp}$hHS{;|L$L%>Q|U5&V9CMnzd1D<=AOs z;M8*%`VCJ_d*|U~CcZI%YGb|Ij0xdx{#H^vETGi-HU9{jUoLJa(CY;YAjaj&6;6|! zqspcLF&v8i^pkYpbna>jp;zrQ%Pdk=^(*{Q0{`PuG&LIGU0gl$ZNSo)HnF1T{HDW2 z$&9}E3%g&*`X@H`U&dHx35u|kq}vI%L5@a%zmXw~^VKIK$BhfC>v}PEd@+Bt`j9KP zW_U?ipKp<4P{ZuUv2DjaR}J(_AjA@qbi+&+k)&E^f!kX?J}X3A?#5&P6(Frk6&H1m zZsXT_()Qd<=E<+w2!>e2(e^e;56a4Yck(boMp0==h*vx=s+n$SF}sdYSWP@$T?rJA9mr3kY$Qakwh8orSmxj)>FtnU$Vn$d|faqBf~ zP&>#S;(N)w2MXEL#%{g1C|S7YXNYfqz!3$9o2pdM7iK8)Y78tha9U76zlhN^7NuxH zURWCC&x^a(sgIp%(MZypinT0TCkkr8%M#HiP~`L_KtA|OYvkEpq2UqpamJJ8j|<&|0TNrf7izRpA~!mJDvlhy`y&SN3GlQ{afab zM*dt@liAh**zt(nCC!f@Hh+7Ib`#Wdw;wKij;Wk2iShrjXzCx@+Hd`QXuoxB`+g0G zso<2(&NpVH_#Jw(Sjq&qVf^A>!qV-u7u?kYw_Ju-`y!r!%d;pX-r71(mmJKrDc!XyDcX` zM}?@M5b9;S3r0(i^$M!_>h7W4o`I7P>fwTm!T>x*tT!=$^NLOYK8`^^Q+yFAhJ1VL zhn_Sc3)D`X?Uf%DH0{ML&?pvCpc4UK7rQVDGGK;HnhCPEWD~k$NJ_g}EZI)3dhD4K z7m)s$khHbr#EC@Bzw9jdq9;@V&Tvuojgml)mx-njB`pd*bG@~!H|CI@M1sND5)*GW zlY5KSVCVShEtts9Li99_ihSK&MfOL*^0zfegBiE?AosghY8V#CVG*CW$t3-pxX-R( zf~|L6)nRuRQ2sX)9L9{!E|5cF90@8ri2OIOT&Dq1WA~zIlc@yd(eO43etveD`@emi zkP%rR>aa#e4*V~3;j>#by=53xUc|j31XVb3g8j~2q*&H>Kh4*s0Pj6-F)D$TjRIn~ z6J^JZaxMjGWUvNu=`z`l-qbQQ&v4@=yBaZ&%4I2TlQy3`M2Lrj&XkRONIh97-#x(n@PA|SBOy;E|c+~z83c1a^{wZ zWOFhHYm*}fe#snc3>PAUfu7?;7XzfgET+=po7mub?%ZT`5PO{{i29AADPZmuxH4z0rov4FAqsJ zto<=^dZk@Bg^sQnb}V6J&|g$4o1`@!;6O3ZA(KF%+|fv+ECMYk!obDO$<9%* zETpgTUV*#K^xrKezZT|$MG5WC&h6aDeLPs*-dbc@5;!GrUn3Dn1%_=Q2j8hyrhl+6 zz~dYgMnPrWACUi`e)9m#3cWoT4(SyuUkXyZMh4)yms&v=h=XaZp-3NdeSi&$N@PR; zz=@;z?*YL#=r9EB@!Dq?Gb8~mtPP3yh4_T#1u>uup5d@S$CAp)ur*$cJ!GpHw~WY$ za}4h;VF1bg`B*%{SP}ND{dpj^CODB#N6vpazdf0kmyJaq6{hHGOZ@ef z@2_Y0xnpuz$V<@IG%D)Z?!9^USpn&{nm;OrJ9%tU+uc9ga7@HfAT8g}P$1N-@SxE5 z!d(>gwUne40W{upd%9bhD=)0=^yXH&q4nJI?e?YJR5!FP`5{}`0UQk@UKDk{QB2@Q zB!17m0SLfKwi|yAp)aRoTVTwp7^2RuIz1@Y#Dng)z&ySK{qU2hiv%O!?W&H$f8Kv^ z`U7B%NCKsg`aXtPQ^*rPqVHB@{nO}Ut~6Ii1#~tmJ3}?h5|RnBo9%jd>JIfi5(FB< zgCq4#nO*d%&?l4FXxH+e$lpU~hJL85! zI!Xtsk06ZBjBk9-SOA-n!37xjfD{SvTHqOIgD!yqvrxvaLbv>b0{uWPqPaiWeND)& z|66@cKaBD%A}|m5JC9^qF$-u(sJ+xI-VS@1s5;z!8kZz{7W_;L3)b5?bVCB<^{?@t zdf0#dK9{B!gFld28QX!>m-7?x{V)8fHV#(v`5z64TaI{g7Mm{qYyBldjp>I5`IV0_ z{oq(cV z0m{!-Ts5XH7Y+m4oGz=+#UX<^L z@-5v&@-@Y$0Dts4B7L)jc&zjwhpag>iMxYPSUnH zmUhewsl=Mr^}SGRaL1VG=k*o>eg&nWh4D))l?D^>W1sAs=2;uMuCfEVV(G{*f#lXS_b&X&9>$?Fl`hzEc31*hLOiM#R32&7o)hfPqv&^g z?Ea>qr{QS0!}ZmBGETxa*LyD;LTQL|O*ex+SkhYFP$_p%5NPjfdi8eX`r)KN4zHt-9wM+H%)>&5g_=78>W6VotfKExjJfp%?dyJ=$bp z8~S73DwZzVZd`DQ&K80UFx12JY*WEznHqljg+60D>q$A@6<@Cj@k-zkwFh!eY+c@$GY5W>`}0Ns z1E2U%eT-KPMyz1jH)3<{RlJmIrw)2T9}s`VZGMFPp@r+}7dobIqwzy>te@|TnDcm+ z4{4+0c#v=PYf|Tl>ykYh{dM2Jf9KG(f#_q#H=UB!c;D{}HpYXfuXGz^)Sa_W#9B2N z+++{>=2FL9diU8LZ;bQRA}oxckGf&cJ@j>H(f9R^@7AY^zCbPVK?;VMwsRKANlNO8}PAv-1CBSz5qgTIojRKZgM@Wu^p+xeyB-wYaciL znjuQ@3EQ~NZF2dUK+#*C91BX3gp0BiNhwQ;;SwaqU}=prTbJK`m3i@c>U`ToG<>TF z_tjq-IX(XE!?$Bl&S7fpc4B2bb0W=A9X(%Fqo4J>5K%p$h;Iyn_t=Q!^30}pRwni) zzXlz7YivxCJL%4ZK5lfPviT=3QS0>!kwItp+qZxIEoI-o{w;(H-PXLYT6$X3@n!?@ ziYQGel#171(!}dN72ds`nSHt?kNEt9zF?@h z1etMHP3~OQ?C_06$3)Isxc~Ucn>J|g94wK_%>k-SirC!?BYwZ{=}_Ef&#bN)fTBp+ zOUvCQa>xWHK;3KCK>ot-$Gm+*&zSFVk2E0zn!)Nvhi`hgkWN={W5+$=?G^5*7$wdI zTs7!n=D$cb)vVWwGdV;`x<(8*-r%=0cGSAi)5K6CUn8>F&f}r$uaohdI%Qw;wC=us zq|l)}#EAA)q6oW{=4SV;F+ihB$Rn0nKWcdb&CiIX%4kzeCl8 z8#m~5zNWie`^WDK`a!?__3v+o8|Rwk+9hzbOHqG!Ka|Wrs${ov*r{|(K@?g= z1%6n~1e{s0ln+zyY^_jBL#!gQIv#18T&{mrkdPvM#HZcHQtZ3uMG*r*n*%H`CJ?#( zMtNbMKI%%7BG z5x+uMp2YHN#EB3vxX|i$k|=hsKwP1jEPr0oKw%A+u`K4~AN4+o|aAAD*Lw9qXRAd)$h5te3%^b)#VMkPbRA!Um?KN(Lp%63D9LMTDkdrFzjiGJt!-c_%bdynLG;?$B5}jrvci6L)Os2nB0Xj|Td(N9gcae+YWXtI| zz5HUAZ$s$Onq95pecHqv;)itNUUwa)sqrqj1V8$)lP$Ex`iJhYJN(UAc{w%Y=c@p z%|WQ**Z?HFBl+r;Pzav~ucGfVBBqvwu9cVMz_8>jli_@Uo1AsRJr7N@a#M!8p#>w<_ zXvH6^t=Zv$hmQkrSe{LIAwhISvuT@gW{jA?dp*;sR;*gaUWO-%?(`#PsOqL*ASBWQ z>U&kpGjy~=nmm@#UO~Rcbav$NT?G1G0d`Ef15hV=0#J;zwa0jVM5dgny^M_t3i*gs zMHf$at8eGRj5Z(rqaUMSVOLX$(HE(C#@7`o=(c9u0!9~^D~9B#`-AQh>9mpYchTe< zAUY}pU)Y^Ti1^N{zf=h3o@PPvB#5PcVp%W2wQle_sfa=T@Xkq`2c#1ue-S$Irnv zdupt{&Jj}05XmZ{n1tx|yJoH6gv@kmOA*Wh;;7^I&+qK}BtWd?B@MU(X`ibRGT84$ z9`u!!K4aQ}J5S|;zm4A6yZQ_SnI`en8d!>6E3hsj=Fr*?4nsRR%bTSPLlfr_C=C5$ zuec@!D1wadsvQ^CtPQvsjir_SWJjOPh`IDw z6r!5jzVTL!Kui#0%UIZVb0p;(Nm)n7fX1WjD@=Bhfkuo3O`4rk^Qp`G*nC8$fNn)H z6%9|!4L*1<0u6LEM8_Msb0IT6H#fnZ(_ba#`kZaR5=7yL(z1Z^m9*Zs68Sz_)P#gb z0;9hz0&Om(Netvf#E}5ebRv>novqdMULG9A#VA|N53$!8rZHW;hIXzcx!DN_TLfs# z%e}lbcC{v9K|`dYBF98uUx>sQuBfrRbvrV6z~p&4qnoI%6rwZndwA(;9G0&ggG4E& zA!FRTJcini;C*Fj#<}`yI8*m9uJF2AT#qvY6Q`^UF!`P!O@#pq7)V{PIRnmpeKZr} z3Zh2C$s<0l&7%Q*ML?MrRZ7ExJA9GuWscjpQ!2GyYxC0`SY(JQz}AR{I|t;f&%e1q z3S_0{TWnw?6l(RGQLq(tyD6kk+#R$2NC8<5GGywEHON~d3HepmTqT1^#8Y@XDyB-8 z3}o^t)I9yynNk_oiQ2{N`yt5^hl)*p%5El)2 zVWpKqFj_lcYXNfoZKzzq%lnB-_~KEQT5T^!I3Z1Nd^(BhQj!_jWRtRK7$HG3tfIRIdNWH+MYcH9|hM@NRV9-`eTV zIKZOSTm!iA?uuMd1E>eDNLg=X5go5hNM4?;SUCl&ToPm#-Y6 zx#P`;Z%~WOH^T`@J_58yD+oeW7!=w=EK1SY1!ltfIM0Y8<@=%`lALXKXG%`25{Bs} z+QX$Y`hDrtFiRtK{8jP`LY)`MOe}iKzUg{38XL{ZdgO@Q$C&Q!dEDWjUI>ZA*k3*? zXff?ucce(~ez=u=|jqcsEOqKY{2*3en=N&d4)aDQ}rRb!??s z3fWZbd>);8WJ5SLv|QchA9G%_%qh*>;@8z;HjJOui9*Bjs$+iN$j>!g%w3=Vq+fPn z=X~CKOTJls`6Kebo@zE^$e7Ayt%kggWH8aWe^M+V>__aT*=C}C%fXH~+x&;Rdouc) z(RbDc3a+qW$OnHIV|FOn6LJXeClyU=3LZ+5)g;1gzpT6CdD4CF?9cDzo!2JTy=Ff) zRQfd9=P&Fp-e^yii+0$VtY%kB+8pf2&ph8YRGwl|>oQoan)hzs3}dgx?Kb&3&a78R zZO5W{YQsdcvo?Cj?q%@areR!3=`k|{yc?p&UkY> z3T_`#YQkR%P0%dK_fT~39)6mNUw5i~3wXAVbhA%?0{m^ZD?7;F;{}8_Kel~C0h`ww zZXSHclN^mVS8WO*ID`4Qt)gTetMw85JQ{07$vzn?R>D5r*M=2kc)qsdCm$aQBBo3R zT274`(ff6rIPu4%C{+iB@CmaZP#u@(N0+`VOIwX6bjRM2Y z!OlU=K?K@#x1S$w@8#0FOfI7~2vBc@Vfj2YYgUp$W#kh(*DU3YKZSRWrR2L+1k>;8 zT4F*uzx!OmYWI8JPgVPjUfHgG8{%*8^XB%HSt!OuUUg<}e^vguBcVN^{q=z6R1>A8 z+D0g={m-}5n9EH@-ROWWr|yq(lgV3VjQ+3r0St3 zg12s<5U4KIcM;2!yLC@=K4scHFey=OO5`j#k7M1mq|f*^SNXl&0}ACF05lym=+yA8 zC%rnmuoPTqa_;Q2fUH0ExQu0L6T7H1^B*Fr`T zP{P2O3oyVU%9+qBmK+uW9LG(6?SiF-=_T>7AFprnLi6gGIpZPCW80JXb8X@1z;thl z=5z6uvCY@B?ty}*+StC-c%L1)I(V)j?Ub24MMLT_wYg)pE*MH+q0^=ux*SS@&X z6+3wSoSfjjvb}UqzfoI^Y2ylilJ&V~Gwx?7RJ1KPQpzqE@eo-4h-+^$MZd0P_N?SG^c_beZv;fpnK@Dp$`IU?reZg0SpGMWEg zz54BJZ~cSeTz;L-8Nq{wU#&mvHQzbR_~`UvvPR?liL2_n$7OlXzAu@RyF=$=EYvt; zEcdgZ#;4LIGyRU|_7`>`ZhS5RuH+*IL|&y9ES|FAgUPJkz3T$&agqkoHP;qvJLsq1 zrmNel+#*lo5Tg?laNo8~H1ee!?fJhyb#VI|F`%W zS=I?X#{*5u%~LLJjK=Tf<{!Y&ZL-VgGR1~^TBL+7ZmYd_O6x%mVP@JAlFq3edH&C> zoja=Z};~DQyhbH%uWH3P8u-PI^AuWek0_FZ>26Vt6A>M}ZF2w_Oq0vDRM-B>#6@+1Zo;l(1%Q?R7Pt z(oj)p66Ki$cV!3C2zGV>%eJ=v*!q?2RKk7@@-epxiZn*UP{fppeXX z*UQ)5bs~0YC)YEQ2y=DGZ#Ps>9hf<1NvtY&A*_|XhR^TU7BWPt(oDPhg6%g7G-I%@ zLst!L-uZrM*MsNtrDZnyzzbE0U07p|8#S{H)i0B#9`HWjdUAschak0mWt4K^H$<>9 z8suf)gyunvPpyY55C$Ou1WW^wGqOrdxMlFl+CM$r*7D027%S)>3CIR3uJ*%boX_ab z(=3>rb3Z%EAMnZ-5Mq8|#reyr$qhZRKTRihV%FKawa-p{rqIZls^Qhicn*2d0^KK7 z&Y_kEkDmC5P9^OInJ2+bozUC#=oEOGLwTCzZ%i2JsE%cazjmvOkkQtqdHzb#aIB)r zu@kU{e!6>Ywxzdh+?-S}TNNC5#+*%xiAHKe`Rwo&3qdMx)5ZV1 zRt=N0hKqfv8fMGqF()3w@n^A9C+9RiJuN5DIz^F#M^x&}QVk`3^_a4L)ap2`rrudZ zOO2-v78ujyB6;vc(}3!^pHE!I(8}G1VvTBSAGVVPov%r&DOh%Y)1O zZo28)g9q2{Xu?Y^m5MC#1$kzItC>R_x7jU4u2?cNP(=X~;HJfc@=!H1iyUsq5OU{|8v0T5Fh` zaU$SsD*me)06J6t2A$2qn|`u0w;6n>j(=TvXQx+qvRSPEurD_?J2HK2v;% zm9KtkeCY~Lr(w&t`%LU|N?*4QqC;u>&xaC8{oKtVg8PRk$}CRzUxe_Z z@!9#z*iI9)hf%V3Kr09~p~^bCDbm~F*t1tniKv#c>YIHc>0|0;EDb@bAE_#Wr? z@I69Q@!%ek0H#&YH4WNpe8=XU2^ndKTD-Wd;eGLVpf{_8O)#((Rba+786p&D={|&5kkR z;3?%|3SB~kf{u&~IbUh2XEe_Dz}+bsu?f*E9#+R|kXcs<63T@yHQoBM86!-;Z=K&j z{Zm}LZw=li_eH;)KP0!R6*VX>=VT=kX#~X>aR&MdC*FLBLkuD!j|VZ4Ix?#P7b6J& zbHm2qu}T}ll#l~4lOO}4XjWN(10SaR2|$`v2gr-inL{|>kh%9#_agu|#1J0<;Hx6X z94@9dr(fUX_Yqp50kinTyWrKwK=lAR2TPO=;Q@r)w701eN>#XNFtF%E$>tyA_g^@i z0&+nSo3G+Bz##2_N%bTaxPV?0=D&~fG?)mP4zC~BHC?AdD94P~od|soX_}XI2Je-} z#_{8%0IbPe9oI@|RdEEUV;$YYEh^Wbjrde#B#crcu$bZ1VQDWA)AlIH!QO@vrhWp+ z!4Bk|4px4^Ebv+x3qUDwh(v%d-QX?&d3B1q6a zc_`q?{AhCi!Hr~P!8Q3D`N`%uzUZV+aL=wt$gNl2iME62EV{y`2ZQzgcHrH2ntV+! zw*4lYL@x&`{w|`CI1%SDW}^@?io;S5FsvV|h~rlQojXYM3uf;L@YK}SMrE|)#Hj=A zBE2;c&=TIT1>)^@Nx~^%SMQy0G2VcAlHN5AS>TO%95GYn!{;dikZ*1|Q`$2goZ8Hh z7g*H~{O(5%eI>J>2&bkYXVYl6a)z@Bp1!W{v^0-qJop0J^A1Ne^#)B&PrSE?&;G@w zo?ce+Mpj(z@Rd)dg4*%flIk56}`}(8w0&1@&}ip ze`LF>3{3kA^Cyvh14w)(1~s}|0E?-J*OR6tLK#vl$p|Hn`$o`P5;dB~$3$*n=Pm0p zEy{w@nGsfx1>bPF?rt$$+wAc3s&!?LCwpV|@oi)}IE;tf*u=t7n1>$2*%65RTLTRLbrgYLDruQc`adMgVQ zgvuZ7F^BlH3NU1h;kMeZVQt}t_1Acw$Hrl~g~5_`;cIZv&#vph9lvnCMWt$m!+kc)=Q@(!Q8rfh#6a7+%k;SxX~)B#p_v;*R#Z7p!Yc|qJ; z8F0L$%pO6KODq3rZin_e8}0~Pd7^%xXd2kz;=3$xg_K@^d2E|_hLqcB-`#zP^z1n% zB$Cr=7M42bK5Fg&B6Ek%L2%Y+hd2PX=_P&B7sEB~m(Df#)JO{+c2ri7;-cYTjmMoJ z;0p16oqkYj^YqKB23`0(#M40gFJdndv;L@xeW;d?@Tq^A)xwK^7tDiqvE>ci1idD5 z^gG-N@!2liPbQQaRW(9|@Zvt(DL0%IF@AH`5VGsen|@hp7&0uFu=(mM0rR)F>-?qF zGahE*dIDP1;m$r|j@)@C;g?l)o^7+a4FKl4Gwsk;*K$OB_FexI@hGDctRi0w3O$3g z9S7@EkA+3Hf8SX3Ej;Sdnd%CU(_)pIMz?Tkwjkqm3KCQ2R!V?;^}PBjnfim%GkNfl z(X%c-Gn)$Su8K_%3{TN7d$7AHDr-D2`rKwa+!o@UDNl#8yRRsnc`2^k^m$8xnSJO4 z^VBPUn0cOjuLNf&Y&ogaXs>Yym&@un9x95T_;xsYdq|g4>2X9+ukgxge6|!b^$rM$ z{g{M6c<@qWZVeyY?~A1M5;%3EwX!j%Cl&^&Tw~mLzO}vr^>x0ClSafR$dg|raqHMn zZrFsyXt=T22!~P~X&}pa)iQg!r{~2Hc`Eqmi+i!!&V}KNhmp8GW(0_Yk0_qmRLVou zHrvnsh=klXg0ewA!^UWCR+*r}_z|rB5@iMmWIcziB3Cd6xG&DXCMNTw0Ph=_#7bY= zEID6V#J?T)C~WHIrz#yBe?$|$L#ljl@3kt&y45{!5u&~f(otA@br+jL%%A0$(SAVB zkBrXDpP{sZ(*!<$Z=e%`(qV0H8h&)x<_7E|N-cbH>)zQsz;l%*8S~gg@(~!p(0&a6 z-H%B7*%gsxzBiN_Fb(IlQt?4XKgj=KtNqWfZ>Iu3m5MqH(mklc?>eEGt;er7hD_3# zg|3e)sbGDlwjt_$&Kgff9=pf?>UR~@gsbGqwZo=uDbeBq4nKxxk3}I;NhmQz(uFkQ}dZY&1=*3y-WH}b8j@3n*Z{jI?{V? zn;amkdd)ba* z-(-(6y|vr=R{x@76%J$iCe5}FK78g@iASucl@GyzEgTOpH8odH70-qTlpm+`NxK4f z6HVi;QvaVB;r@#hlap+?6geCd&x2Zc z+)>oKr0JWU2k`%eFK=a^4xwd|0##_bw8vNzZu@=NI$&JtfKNja(G~|C62bzrrX3i; zbhh3cOqA?$iNF*U4vgc~q+dO5PP(0Ku4Vm78hB)zE%B5tIE9q7EBwfYzrp*(1r(68+?(D|8Y9)!!btsjkZC-?FemVzHQrZ6 zc17SRb!G&Nb1!>B?faRI31#5%g7$V!+RiDK^CS?IMj6ApLw@sjmj9^^_!als>Tu9^ z@K&CU>*OwP7l1+zNqK#zKcq_J&O0``StB1{sAeRp!``;Qtacjqf8%*p-7?F@GNQdL zApT-f*kW4@dCAt?w88br9_Et{gN8t?O#A|>r=Iri*q4Sy(7Ut)ozdtk;laK}C{s}j zM?hc$Euw>iiAQZvFx-Qx)h?rD*OO1bv{{EDr(o~g3xE|s2fxJ2r`a{DMU?n1gcf){ zv6%e6cWAKxFc>u(Ke;0WQ8KoE(6!CX%r0XOp2@1u76$k?$X;|mRG<7<`s_z+Qd8|+ zcz6U)`@bb7^@DqA@XQ4SalxcQgMJ&+0sT`?Vm@&23nb}N^Fpq3)Hw}cm>}StiwTX{ z(?ia%R zUJUiqAO}2Y2BSSH#2O~B+FqX(I^|zzkZL?#Dob@>J+XvUn(5eRS=C`d|69Nzl>$MjSp*TB|qp+BNMoHP!IqZPJ5lwdz|fEff0bJ<(aB; zo$3PH=z+Q$zQ?M+v;IY@yyU~;fHE*odO$zLw-N7V46Jt!}LFT9Z& z8d9j=UrPEAFBmtnx-ypr!^^<}K59s2O{zn#x(~zyIuSD$Ft;u-tI{~4Lag_yhM9xu zgv*Fw7>Nb26SP}iNmJNi6N3+yjw!X!fXR@jwC(AGiY%-+}23mbbDS_u+Ox>2*2IG_ zEfoUPN$6kmtHmnZp+8cjcJQ&J$Ov|ve{=It0xz^n_#IzQlLqv+zJW}j(uS|(Oc-Tt zRx2o*pz}L^#~F$Y<#yfEINhZcbYj<=Pa_NI-s)#yG@_RlkxKfQ5xLAF=daSurXCS` zSpu|M+`4a*L!0?tS$x2-jdRS!$N$1QWHKTF7X%v^bQ2)B{n}RW1ZXj5&i9T&85Zj@Y@J!o}Kle2~_PpPv{(#|7VxZ8RlQU8o+9(AX@R{ zV0EPO%M9Cv183vM$uso0IOmJDOk}(qc0j z2Dolz<3UF=sCrY|D_Z#$cx9-OK={@h#{6v65WLBxG_uazpueh{EgE(y^3NPBt$1e^ z^bmFC)Xe*46CCLX zrp0mmlji5Pds8e%+sBWMJZVj4OHJOi9dH7qJW z17+g}Euy1LdtPGY*JR)@PL2f2jUrZ;oG|OdgN*Eocydj{BaOE$A<~}Xz#$$I*RxI| zA_O-lo-=m?*)n8MQ~&xG$;ZRgc!2eHDb9u=-I6EHIMgJB*Pe$# zvs>6`?O+H1%oNnq$N)vNHHwKB$o*wnDiMcx?EsTP?uopVf3w`)`X4J9#4^AB8D@DK z`x+#LBlQlY%AlT^hCRgSAuf+Ch%+&e9RPa4Qp7(aUy}!j3CfQsvvPz8YJv!L3etn) zp$|b4wj?dX#hQdDz)>_Iq0|o21?K2;fILqN{wKx+Gf)TUgMY^CXk%mgT(BH)2KkJN z456mEi|W}VCt&%}y~H{2GL3?R1MFywwwb#hLD&cvL{)pdBpwEoJ*SN*(gh2L_f*k)v`f$h)QZNTfxQ!74pY;vKg>e#|+fC=Of>RcI&tw za0aMs6g7{l!jZrmP-x8ssj)^FO8lVapxu;Y`h&g;#M>kSrj3vQWM^3!a%`dO5*FxM z|EB`iM%WAdJy9mg_F&Ac+7jlYE^=1^Ox>V6I(A%K1OBr6wYB=On%G7H!X#?^ zc57vPU|@AviUYYQCfhOA0@$T`h*#s`l(=&-m|6&Fx-AY$qQ>kOq^_@h(iCe){we_D z3ke5`MC^Dj@k~O-wU99WnoT0=NvNYxGzk5tin{yQaZvZa>k6QrP{1H0xs>O9S(CzT zCs3%?2$Gz3iE;CAGTI>V`1eMB?`?nR*_n@9r|9$tB8s}-Bq zorc48kK`PxqZ|h>yFht0`W3;2Z({*`uN<3~>l3rmZiVLcA@nH@+Mzr2)k|q)B_U0x zSD-^H+F(fy3_fC0*(P241FRj7956`lvIKv}-o!ivTh{U6pF1cbl6C4v8DgIzw;|}w z;$iBb4#zePS+XXPJ#phrInG*M5O5xESZu6~aH_{F97_Gn44;`DF)-CW|JlZjje$1x9ubiXt`Sc`kP%9HziE;DzaKA}cn zCvH!gMr9jKk|$;TO>jMI_AKfX%}(I4BG*R@Yg?d|InnjIugXk_+PC0WdIYC+=ivkY z3Wdf?_q|$)rvyl`#b2^2-d|9GIJex2O^eAXA4xkXDBpqzqAd!Fz3BMya2)zl?xR7T zyj${l7p&{f(~n|{(yb-Q$`^q;44ODzUTWM__W-SAl=FE$I869GYjuP2d*r!=XjC=$ z+Cbe>uZ#IY-IQ1aGo+5TIPP9UVXYmTRaWc;TehI-6rS;@B#2E3JBGLSI_y+Uli#}3 zThgIZHuEa+WIJ^S;bWqIMNsbc!APEqs_7{0!OrNc*Ddncli2gp5h=^*Zo!kWU|vJ@ z7?Y;9o4qL6HESHGy$_o}^YAQ5Y&GuL+UY+t{aNht^4~QZ4X;%v&z>zdxPeH@svOOy z)kH3$D{c2Q`9lg%YYJ#oMN|%cZGDzLhpA?AG_zeQ57rJz9VKwrjW5 zfs`1$>stl1-#B%04}6^H=hTFriYg1g#x?G`|bY-b(-RTTqkUR8_4-kCFhs1g)^{lMYcK8$uqB^^lPR#TUF zlPyZl|~>tJttG$IlNyIJPwyaT+(GKq9uqNdntMu>8H*W>R9R zx7z^pcFLcCkQHphUgy;VJBLNDOMk`7T(*4H+%W?C&7D`T3=_e-^=0lJOgW4D@D+yuuTYut94G+}s0(c=*1C~~|+T^`FA0j;0Z?NHmQiJkGAC0ANtc^w6 zG~O3A`{J|I!JNxT_PCm>OQXQZIv3((#%x1lS#T>uU{N&2AYbqL^2nkd78Hu<&K;gU zNGtGQ4%YX1J%kY%HM(Tw?@4(v6NWX`Jo~=z^b2N}vUBcJZP|11JKc!c1`>JkHux@j_dwjZQE!%%+pFA>{?j{< z9zVCNG72+P{YJp-2bJVN(^15hf32<)DhP{RKPUlXwqeUH92L9pd`vG3Y>_s0*l+(D z*NZWDrH6)kF@6TH5YK^uoEYU#KtPK|;fhUhW`VW3(e3FDI!Z6wjxN}mW#^*Hci?EA zsqO+!ROa_4jB|6RWyxQl|Mcg2Ij}IA+XPyfSI^|J>xn?>F33_*hmvf&yz)SJz-^F` z80`WlL1s`w$LPdy8i}b&Z%)$pme)S>16nh8!N2c$mETWqSlS{Mk*xRk;o|m0vJr}zZQddy z)BTjEJ+BuNKtO6SwY0`~^8xra!EGXTh?b1@%d|v=VmpXIRCl3cGm<6Zf>%go+jSF6I`Ma9dFS^Uk2~>_l)H8}XeD=VHntPvaAA z*wyPz5i`)*-f$}1i`kwYbxJ({`Gfk#v-3Bf;@gDd;e8$10~cGP#`5|f>G1LVq$Ky@ zJD0A)*6{S|INsWp>zG9hC942(Usv6Q z>MBu2PV0H+S!jmZPh9S5%7tQbwTO*f>dQ1>)b73SiP?R|^kSO7>#pFonEL_IL8IYH zcOKhDu1d82+LpqkXbk=q2h6eEV{U03JpIy);D(pa%P=1}1(`XdqnLs_b5T$J=8Bck zXr4Ap%r+>43aFKI)IRt6 zfl;39+|K%J?iBa|&gqSULmqETLf7!n?7)-!qJ3ylreWTj2newH64?#ASrf~m?Nkk^ z=uI`u3oj*+{jyWxr2P4jyboW<1cQ<_I95W^r3D5e+D1X5ty?6u2MTbg!|8E-bn%$* zD~Wzu^G)g%0J-g(hoDZ%gsq4c^%#fHFESTk!5QdY@{wxM?>U-5rC`iFH36C;!>Jq? z69g7o{qN(Q2h`zOq6*?s8$2`jpkAfE%<# zA#r{`rx`py$F$MnM!Zvc;_1a`Kx6 z8o*b4@&2d#twwX=se6W6^h?P+3TvEbn)iy#u9#y)n^FUZ^9|laGMuHp3k8qb%RoXx z{^oBm0?VY0ZX`b}rEBBxfrAMWa#Fym;dxu&iTD7T?ex<{6Dod1f$EVgkwV+6em;{B^-erY)(x$#I^bgwW)@>jI}_bqr+EBT)$bqhAD_Rac*e^?hE`qk z777>?d5Llpidvg|`zx%Wu%bW1_hWff446{Jw|Ah>M&l<`qnuI8airwIzpXk1+@c?* zzYZJl;otJ_c`)@M%W^iL>JVc|kP`=YAO=D@k;fPs;_u!i{EVuIe62<>@vr1#;=r_x zJV0)x_E(X7)0BrY=Lr~=Zk(V>5i%+w$+P7g!o`GEaj4ApmEP+h32+K=w8r-9JOA`( ze}S73l#qIN7(p4eWDq7^4<(A6kb4){kema>=yr}vA`JBePQ&~R*eeOJ>2<;dG&;@& zH(uGi=Vv?ECbeb*wD8o39^(=z23mmQyslldKx#)XEd5no($#5Xn+>t`icA>0@Qww1L+YtM`=&OY$^=FSK9K;%K~jn9N&XBL{wg`i)cN0m00F_b9{izhn{C4>L95G?AP2;oAbf018+(w7(^lAgU*y|DF?Qke z7XPP(?}j>AS)~HALE6fh2B@$cx}vYhebi2QwPAXx3tIOYpkT}Fu6H{)<6XDBQz*OH zytU%V9t3bl$~_fKR~H~8ba72r4NS%F4nGoiK0ru75?NJQM@zJu`gr5(J(r@OO@%U7 zw$|eEhNAETu3fxL{YMUl5u(u(I2n{-_}c6qxY%+^^*Q43YcVtrQmnJS55a;r`+tKs zM(Ya5MEC2_ z@Z4@`X}Hee-mt4E_9xu^`zL(OC$|#F0$qJNOH_hq%;A$0gRLJGse&_$03qUw(T0iB zX?3m@0lc=mR@+IH&spl6la8D>UVI%=a-i?Z*bObp=Ce+h95VzDmEFW(oeKV5H^$ET z!0x=~hR{-D(ctf~H>0sGT6WlJ-;qJ7iDDM%R3xM#{DI4?G zy$WxNmX|I4aq&%HYa8J~Y6wrnm#MLIr)!x&75+|XfP)2} zh%6R(hpsmS6PymsTtr?3>$2&+eohn3BCP!saANzaW1vxXa2^BBhPfU7rML&!MLve^ zuU#5QP2luH%ydB+m}iUj|3zn_#u;e((I7SbrOhd0_>19M^4vmIgll?@%^xbxO>zy= zU_QLspaO}YA@$Z*`+6KGU>P2Z{JlnxS$zg^KqA)*Vrckn+}wbad10f!b67x1;`8M< zQrQf*!RYN?u^%L>+B^+fbR+)>op$XU?2QXWmazO5%NgWpm2CrV(rOeV`!)JH)L4t3 z_?1G*%C?~ie?AAm;&PE?-SyI9HvUcK#jzf1r4MN9oO9E!&;!K5!9-SPPI3;q$>|~l zBwW~#YX5wB9}LV~H|_zzZn6t2k@-gd*H5wgz{xRRw9*LBYrN9U2b%T7DCVkjnaWN* zlU-s;>=~j?J+^24a@o9BST_3ajSBRidt0y%n<%{7th)fUSa1vs@Na5Om*w3iUYFg< z$bh#P;3}aqz3i6L?3JG7!KzN9EDl9HlU-nTU)Tk!zEPunsFk13RT`v!d=DcD^Th}I zH}mC0^VA6fsxi0bVp5e~4jf!s zYZdH+>FDHE(RcbIh0P&C;?A1Q$W&!CGfePoq2~`8Xwm@Ua#^Rxq5PKYHi_J z`Q0AL)FN;}zBLBA;m;q8Vp_aZcH!cGExJ7!ed0nB5CTVy;5~d`J9^lM3dMVjt`inDZ%fGOp_KszP zPT1I^H-=H-l@ZGItQ~xFpgz^&M{HLo9^+G%VXdEq`Ss4_*)^z5qL!Z) zR^}T3M|$>tNSEw1vV5pUZ6f>CiDi*i$gr(<5Bv`!K z;aS@Dn|m#_W!pcyw>#avo)nLMZ`4)Yec}FH>|E`&C&ih-D;D-$q2xcovY5+8Y?6aq z_SrUC%bbz#fT}FfMF9v6_)+jifx;f-{A?SHTiKRAIIhbK_-A^=z)>4;56zxQe1CvO zas;+;psf!OCY8f^{@M0HWFRHZ(gq`A?ijwmw=B`8nN0u-HwxY~v24H#MQ{IHv+t$A zzSJrP`%(@(>?cr8`2YTsd4@rGw4UuX!AAe1_IfsDBJ@6snD0jb1!#i54-m5B00L6- z=TEZVe}3s&hRL7ooZ`A}3>?53xL%knVhs zv9_kQ29=7JI38$XUd?7Nkahknf5iIf+n%G#Vp0^Py}(sD9=jWZC3SdY_2js0pf00Znj}3-NhSz4iamNS z-Bla%H>>oTQ-Z5*J~?p-nH441zwJr}V$YdB0wrS(|10{bMGjDyk=c@y0(TPGc3_9# z#xgAZVdThtEmY+|g$97=1Y7jlj`vrsnG>DDNnSGtz+zo2siyMv6$gV#Gi>ltrl-=% z$-8EK&P1)jxPFp5qlDEB+WGC{m;TJzFB4RpR0eRkrJq;$+HLd}g`F|(#lI`6KbBm7 zjl*(ys7Zcvr8|9N|0*5+t;|Jy)QaCG97{p})L8sah1Y-P0XY4h((Hgk)qnF7`@0?g zqjy8?<{v@Yzj$l?WhV9MCkdeD$gmA14&2y#7d*oXAw@bsI245Cq^DL1W({6CL?7C_ zt{Ibtupz#~eeL?;I4C$qJf3!rGO=H;B-kK1hDXDv6}z*!tO-jCq}hoCEZtq)iD-fi z!5(1xLt+*(S4Ljcd^Y||;W$@7OQKC66;7&M*Xm({rMv#&_Sy#FU>G3>Bo0P*EqP29 zj+}T>M|oh?w>ZlDhkIel$h^>@11w&9en->XNH~_hFIN`4t$kjzDOFqDCID(0Hy9^d z6E*8-kthAd1=!2Gb|pNj6~>)})lYVQQ$C18=#3<4fYSR`xtqxucuYePSmJPIqylhu z?I0%TeSLsTeVvEt zcm<2)q2uCsMit-(M>&+vXLScYTd5OE-+q4v6q;$(V0soXycJ&&KwS{%Ol{@U-**hx z04AC2Fb@Ppo`)ziiEGM&O4B519x2)8p7s0bO(ZyYu+Ll zs#~3C;Bm4dD6%>aW6^3!?Iv27hleHqIUN|c9d%ZXx5lqq<+aA=)+HQ*0c1t#6}&t~ z;DWATan6oyGcnef_+4k6H;~N(hNqj(eGgM&0 zpcpr7LV5;A?bs`_Y^R70g6pgof0xB6F~%MppmKrNz)!iK_9EDz*uph z@pdC5X&r6ddmyay(Ql*IWcRoYQklWjARdw-8i!WEr=HA``k=pz~3)L==YwARQw%|Nbo@vnCHU7369JE5O=onzOId z?ZyCMIU(UOquUsL6Gj4$G@&irz1sZwpgP9qj0nyeNIY>2k27HqFSs>v@Wko(Y;rod zNQQ|X;&{ffWcc?HmlBj}A}E3rG5V2$YcDt|X!Vp@E5Pt{5mG>FeF!6qOegZkhm81; z#AwdU?u5d{BBNqH1Qc^5RDwGZl9MeA*O@42$?Ys0MKp^}vu7@&$`bqS4_eC z3u;e0xSxwkp-0z%R5>03Bnurgsk3}MOc!%zFP%TE{PVzJv4aQU9&`=Qjq4-Kj z!gouRc`tJ zwRV5wvLeL#kPrrW*^!DPhKGSfd=%i~olrv27HsW9!d{PARDoJ6l%q*xecn^=GlwMY z52TUx1U-D<19>|_G#>$3xvWk^LYU_XF2HK-9F8da1!V6ov;+P1-p`8bGf&;<0O47p z1yQ>KD~3rWtL>r{X;S6!7A-N(c5xbQ`JoBTS7*m=o-^fuQUAfCM-#^L(;$oy?@j07 z5CsnPP>JWQ3a7wt8wn5vbszY@Sr_o9^8&Lcbw<0fu52YCZk$h4kn8xAk1D0g@iS?k z3WuX^-F0W)<%X40wIO4`Xb>5Z^ICgIOpV-BIG!L7P15&Z?Stp@_OVeY(FtbiY@CVo~D9-|A90Q^2 zQJ!r!hb9JyDvwgU`D|gbRW@I4*(hqd3299Z-K@c2v8d+j5-WCKRAQ2DJP3ASA1CK8 zf-up4_t$z#5M=iY>R<=A<9XuNzC?XW{-%sP`1m*MC@a*wAyXJ!h}x74)5x6ccLp8H z)qw%kv(6_XqDnsnd?Yg-TNoJ^S(Xg@TbK?>c&*u0ffn(=L;UV41-}OjeO^}1#Ce9+ zt0&emYD6z^KF2`N?h*Pofu369&{cnHRgFsj&P$yWI_;bm2rDlwBWo`S99#{Sy$Fjv z930LOJ6v(X1IiOHEivrA2fD!g>u#?+1nqEvCYw#KYg=)*Wmpf)AI^l5v+$wzL^=i^ z-%n(uFH_VLibha>3B1vn;;0c=fGzmK-sD^ zx8^Am;q%`?0Dt-kmn91Cr6^@nRFg*92HlWc(Di^{I_3O!7!ltG3r7uImAR!ls zBVEUX=f?$p2((gvec6ZDul72s{*?Cl=eus~f(hcP`TW?0ms=zhOAARPTkwDaJC(gL zqF2(R*7W6@NTtKDj)b#F-5L6edH0ve!ao+B@9xBavPNU%h1bTZJfxbFvHhho z8f#9`{Yc8Zqm}b?FJ1&tMFW&S-*+AYI?Gu*wqBv?RW}f`Gl^UIBda-JJvJXXooRD( zZdQ%JhNb-Oiz{LpLw~eXcPd-FKPkY8kjI|ZdJWx2zQUY~&ljL=#vT0S*qs;cG2f@H zpQkmOIFxr^xhalh3w^*j?MHtsI=ehf?u0Od7Aq|MO#NsKs&%WLh6T&7N;vcgoDnTD zE-h+114YWB+tHptl3*!dCOL*Has8=IgKuT5?&T=@Q%>IJdJ;&22>||c9O*cyG;zOvIQS1jH}Wg-Hl-eNBi3tfbv^(4ejDCWyI1=3 zOU(CFl+OjMGcKT{=|7W#qLc}|46L@%jOP)EZHo3XZ;Zqt0W5NaN8Sd^k`4viDHgZX z!Mo`QcGjz|q=5=OpIjXi>?#oYcDh$dY6Xo$C!9zHMltqL5NpPUBh5}ZNk_`0Dk z1S4B_zT;CO1Rn4dtm|G+CiMM`+OwmXThHCTC%^dFck1y*N-=UlIl~A*e!lcc?;j;l zS}7s<79tG+Z9%aYAUAB?0u6Y=bGJzi7$_O;BC*xko=PeZjI!WKuil|=p7p(mXu~S0 zCo^5FHD`5I;A-lEE63(V?8tbNSMG7jJzgXW-Up%A5fq6%k3slt1re~RfH&{x6lj4C zy5#%uA9liUF{_hKis*&H0bjg53A7TXJ5J!$b~Y{=YOVPj8c2Zo>vYrT&5h!tVHfOv zQ}sTn28X!PU%Lhj8C;QVreo z{6g+1;PmJHp~d<RwgdXAQhesd= zH?0~IJF;)#f%ZY~Co)V#a!nt(5JA+tWsPG$?2q#D5Xw`D;!wu5Jfw(|X)a9!#lEeU zeLC#%+q&5P;&)g3S@j5FaU%gG!OlR_UQjSx6Cjv}4!Hm;$JVg3u6n5?1a!a6 z(JtH8ZC#~zrX0A{BIu0W{Q~D zmr~cJ!ePwS##1_=^?*7R1nvM$M>0h#;J^EUABr`+#&s{7VgC0qd?^P?twv##;z8E& z?@BHcF-3#n9I4Zr(*zmee;mM%{9DKFK-hk{uOuxBfIFV(fhZ#q#QX-n{bi#Y3t=Rw zcd&2ElTOsJ^^j&w6rd@C?c~*mHL$|>*|N4;zQ@B|u|-tm2_+t9=k-zr?9~ze^){FC zFNpq+^K+G*dK_c}OteZCz7$C3Y$rKf9pIG4!yP;GcoCGYSm$Zqg}5L8Hk=LX5S=FVf z{J>703HY4@!OXM2J;@uMrShofA3dOUoF*Q1W}iwVMtTD9xyyY>@3 zwuj4*(^-ul{o9rNhr~sUh-xaUG!r~bnNG6%p3D7u1m_3(ioe}vkubkP*A9zNC~|_i zzR=HkV|gSAcK^GLIDG)N zV1aYp&%9qAuQsm@f9fQ-wp7<(KCe9}6#o&q%|LvnVS(<;N1uQv$BC9ADBueg z1$_l#7dxVycSwP~ufF*SAc$g}P@s0ze|lLD=?Hm1a%SPZD2bF3(*VsUL&2|!Xj6se zbw9YD-3ECA7(0f6)JU(LF^z0p62f;(r5qs0k*Gh->HY@Vc$DLM4u&pV zx@{d}>mI_SN12Qtyp_X4mi#F6l=lJ5(KOEuqI)^ zKoHkUfgL%rz*fd-=IggLPMjuxy8&f`qFx+D00AVR3}coWoSXia5_p(!!%|rZsIboo z-i(Fb3GIJfZH#e@T5ML>{ip`&Os1yPD? z)g8~ani_;p*V zf{C5It9*bc{31jYDlGc5hbLMC^fG~pX^DyK>k!>JOt`aDvPP0=W z8HnQ5Oa?Bv>O&;J296srMXo&ECIg;JT&j?i{fAViZPUs#g#5;2RX= zm^tFcOI({$YX=oiZ5iy%4!*C2%U|SZW4@@9d%SvDh6R&+k>L?oOB)?*(*rZ90t^$3 zt!`RH^KtzzKQ+2efp#430Rd9nQtfM#x$bQpg~ZB3oG^jD4%5$(CIxyAWBjj3rAVqOudRMA>=I>32W(d)&|Q z9`8TTa~zK5kG?bCYdNp;I+xG+IYkpoZIsJ&k&dW$d%w;TD?(~d9u1)&&xC@6{)Kg* z?|tdX-N$5+2<$5bzRj6y>MWok`MUociTLNtZ4?WS{^vEOQ2=)!NjrdP2Cq98`4bsk zO>rbG<3uXpk(hk1q~?3s_?fLriNtG&0L>&!BD z2Q6XF8UX3}oFhYqH7!;ZRrrD`kmU-WPr*wWTN`cPde{LkPO@sfq`Z$Sw zAcCW3a^XYfr}is8y1)G$ewqJgot;L(BP_J!fT-&k=E?x_zY;G-d;GuslyiPO4W))_ zWI;Ff85ti3HT}O@Pu%|xt*@X1b(xfGQFt0h_9#o4#~BkxFj0|9!x_A+>Iw3|3gE}u z_$TOgsEQ`o1MV!MVno%(Q-G>LTdhBql zb))NJz3Y2vy?I7<-+XJ9S3IpZeGg}AS2pXl16LejCZ~?4c;xaqhRG76!U^RrSWyfv zCZ$y$r;>^(#CJ$ZQ9kRCBI!s+j-j`;;yhCgp}~d+?G>4K!^7skKMdR2+77WcUaJ?3 zfAr{KOA9)DWh*|Ai+XiG8c#DYCoYuw16rQMz_sl%EyjT-QoDmzrUhoS%7npXSx<1K zgstBxLp||NS31u6Tf{FS-*0qu={hR9d)?rJ7&?bSmqV^$x+)hW0-Atbp*0%U_U51 ze($D}=(K#>{-;e>+YVeLd1%`FvwiXtDfGbQj8okamSHvYEQxAs-7N3!F+6|7`4frk z?J6&Nb5WG&r}C}x$|C#TZ=_2Wzj=gFMfhV@PhL&*T>E)my;VOIy?Zk7>El2xn1Wcj zoly#jslHUxfr-K64aCW z%2N@8tK7T#T?vEpya>HvJt3}69Zy0XuRcx%Ly_sCI1y-)6{wd;);^r{R2b!#(WXes zr=Eb2dU8#!1v7FJTcl2Q4N>ibFfS#$G4ip{Sxldde_Vj{UHZOSNo!Ql&(WYQA4y({ z40((;-HS5aDRN;{bont4U5U;h!OlM^X!XhW^LO{{?;u#p9Y~L}kn!>kJ!p>VcPrtf z9!@0r-uwEV>y-8jYc-oDvKKBEi}kt*w)M1Dw@6{Y%X677T;MILf$#R7Phwg!;uirw z|N3gs?1$gnlH&ZNN(`$4*M2I0OCFI}j2&xbRoVH{{&`{bh9t^ab~${t;n1K|(QV;O zZtPOr{IE|nYaf$0Q;iJ6djsozj>ES;)Nv|SM?WZ@P#<+T(KkQxJizVS+Rsx~Ti-Ft z2fYPvT;_g`L{!Ta@h=QTt`-(Ao_?^KzHeUQcebs?qpR%emN#?8{`nYVo(JE=x^^rZ z2iiNQCF!=!JsHJQ@C}kbFJQMc#icx}g(-1-SKI_iZ%^_qMW7RFR>Pw{eY&ad+Q4Q0 zrU&mQFG}AR5h%B|5E7U1bfrn&^B8p7{?ea+_GX~_%=Sua>A$Fnk7Zm_hk7~zrab%@u_ujr4lh)n%o`( zO&uMtY)%DSh@13{5l<=SOSJ9pg4HrR_nG>NY;V<_b@R$ay?T4X#NKN~C7hBwKjeO; zvoOL`wul^!t%xm%<7*FSk`#K-n(@A!ZeWVZuWI||(!m6Y-Z%dwXJ4B)UiqVC9JtM& z(SpBkij2y+j)sn$S4F?1_vZDja`9QK(b@3fJNY|3fTn|^%J#7Ts3^Qjf?oTLHu%&xMF6(&9Im$*@DsCbI3-o`+0Z2kZQ2ZZO2e&BnCPi>yDn zVV+oLa;vt`^mVwav|WFVCxgfQzTl96!TVpPi-WVZH%En)hw@cq>yln9=(bJvQ=ZN% zFF16k<&TchSg~a&xzU*%-!R+d;HTMqUBJUVWLkY|;DgEBODeFcj&85dv<7LNqm#>~ z{IU_=T5y!XZLg(xes>nlc-nFchm!P+XnHR2cx`26^Lp#TZz9J(J^Nvims;BW(#Q0& zEB<>T2PPSuhWqy^dItlnM!vnhdtLyCw&FMB4(-`LcYR`d;)j=<3qwrKz&WJRvXxJ* z6HCSIeySvi{a9IpbgjGqzP?g>JC7)~U_v{$;hUG(wam_;G%oAr1QJXsJ`48DVFk!pLTUIQDJvn@eWOYEt@m0=CPL zxLZ)D-@?`?JwiNh&YPPu9Zzt$FYlEsqoN~Zl3slDw_n?sqRkt4@?j<8{W;!qUi`kR zqbmu@{l@Pdj%V_9 zZ#ql(8&q7}h3qRGtO2GLKR9(db`MWQv2iFA5+P>_Nxt>JlnZ%K+ce6DO) z*X37QH)1)3P3nZ1C9GraG2k+17K0OY<`3HBi&E4`xnF+`Je%$xv3KwG#d8T*hC>j- zmmhqxs_It{QsjSM-YTDyd~s`lBEBf})4K9aweJsAc4;T3iyc2{zw1;x$d#Q(-axw$ z5(@3wjWX{iHe~5!D3#o=?5c7kAz`G}MQdF8sx5%xS2E5v*6=)|x1;jRoqQ_n&xQ6B z)YA^{D`_6S*M2II1=qg0XmPxQE+kRx^?_Q^ZK0Ovw8-7gr`pR_HGO&K3q7POr}xk5 z7}Q5kdNY}|H}jA3;3@B2pK{<47eC?Hlh$7Niruaydn8`JHL>DMBB|3rh3XfNI7|&H z=hIadgrTHYe3p}&Xfm?dV7V$q#an~x^P?%Vk6~jf_kM&rCde6`qTxt?5rV_wrwK`6 zuN=jig$l!ve5W;=d{tPZer>PMB|Lc&0*SVxy?3hg$pq~$r9YG*!pIB2XlUQGYPxx%BREK>#z!=>q+zvllKW6kFh)FnER z5|dL?2o{zwa2JrgyiK)1rH=GeBthyelnp|BB(XLO{5FB=Jd=a!a$=JLq>(g|L2Tj@ z-fG%3J_h#kMF9aj+bq$~&Ya_-9{8C-DCyw~GJm2nsY#9tj{@9cCZGd`PDH9aRu7~i zN2-!xk0tYx(i0%LX4)&FnUIlZZDq#<_Q2~ujwZR)B|W#7MmUL8zY5G{Ec862z$a0d zb~gyAWz_U$i2m1?w~>ZBb<^xI8D<8JC1=-rp&w z7}@Ucw4OCHfk`@BGtU5|$_}_J7M3v(Lze;|KucR&fd=7_SX>n_yVB9LygpIM{Gff> zX}yfbczewM?E`*?r@>fK`o5Gv$rZ=vv>k|96Rdo5%pWdt81B1udlLu2_lgfn9q&>D zTzJ-!@J%O>Tp18L_j`^;(x~iDvKNA-c(+n53e}4946y5+C2m%CX?#7HXvWxi6-qHC zw)GIV5Uoz(V|XJiV)kUeFv zsk2;un9Q!8ppjs^-CcM8_pvhj<0f9&X`^9%WHaJ#I!;jBG4TpcQqZ=hmQwW-Xur>I zqY8uF?vB~eA$|#)_RMT{ekWI_ewFXoWscZ70i?m==NK+G6R)h#3JzI-N6^+S<)k(@ z3S4upr*(B8#ZX{yUNY-T2cZj8rfcnU<5iPqE6aODDBvrRLJF}qP5e>3GKq4?WaG8+}M53pg z#w>MAfrcfn$n;#k>)T!3;-#x^T)7|;81(7WrR?l%AJe2z-A3V{k`k#994=EYQ8YYy zT3Rh@%tNBxAgbqE#x4GMJW+VrG+>SybKP}41?9W56D@yO8SlSPTh8Bj&YL_nIe7h z@Pbfc^JRO;{>#jHLK~NJ<7|Yudp3f$x`U)SE+& zRm?AOebI(G{bAda#;_v8wrSsNrnV0y+JCGFT~*RFU0UO~#;xQfhD0KtHI?Le|GZTp zl+~YS#O+JlGBb1$TkS`7XR8WwgM$NC|5+*hBW9^zl{gw);xrCQ=1jz{>*cZoW21W9 zDHWQEW+XqI4-x;>2s!s7-=(gci6M~_&&_Z+$3HFyGx<&x{E-B9Q`=bZsYOg~&b7wD z(+zz5-WmEtCg4I=;5)T&DB-3jpkFxlruhIRj81DCd9_n%>H3Y@MdAteP#_9Jn#=%Y z;emWPrP}R&k+t#skf%v>bufoNhsZ^SaQss}Y(7}csej3kh zJy4yd8Uyyug1ll8lrU-|1s`CENth5)H`|ON!Qia7D)PGxqL^J@Aoy*7(tMCkaNxKJ zY}PZ?AKmlDLJ7Rz6%T;mH4`G1^PsPGRvWe^j}wtF;SmuUkj;<=f~%0wQ2S;X&|d(y zB?Dk^kc$;14Qn7|AF!eWzC0ZbZII9$sEjz&nXUP;vP&q5A%BQAlZq00?V5 z_gfZW_3nl8+Ls_N(oAwne54H^F#F9c6`jPr(MYy3lPyXn_{`!RFELNSyDxL>E@IjM z`zj4UXnsLKBv7C&{D!D4`RU8ATOjyvin|W^Sx5j;!4-&umhBf46Vd_ZOpQ44Eu6+l zQdRX-6tlRV_hYIUASTIiM4|6w=j2R4%D`m59-_#4R2XgTNr;shylGm$&Gs2^XQr~+ zWgOE(}qpE&Rn_YU9D*U6>I_TC`MXxKc0TnuEn zlHB)cDp4I`6?B)()#Va+Io1FWlmVq(qQP_sM1sg;-sJ84d|^)yQDtQ--lUiUXo_8& zM$ZP+VJ$#P9|aJ;g0e>n(6_m!Gl0-G#*yImOG?0+*4z|?;%z*%Ur?zmW`U%!J z*D$pJ9gMZ)zw$9dE9^>SbbLJB8P_pZ&{ldWgtZdLbYwx?+6R&diQ_tYdKZc-Z;diT zWK$hva&01v`#R{ag|5Zy*bNc84Xh^`8;Zjf@Yy3HvE9GQhmq&%0cMfA0Frwp`K4Y$ zM$BnH*^p%B^!`#L^)rY?IV-wraS^A>`drxSbapaS9Co(NH-n7>V=LdGiNKh(G!s35i41lXuXUYyU>SiTf)9$yPP{bL1y>Y{w5_tqWu zpd30MNc21Dh~?;9NuacfKOw~LK^7PX1P!EsnM3iTvQvC7}!A+|w78v_c`R1ni<0ik?PY!R?17rYCXs_8`{b&|r6 zS}aCeu9R}(@5=2A=%tcDKe$Y`?PS4qASHXz#Z2#V0x#aZeekCHonv3J}^H*(LXM%~+{zBnnk~i9C#o`p1=n2G|UJmIj$?Aa43=C5fH#oKaDQ_kfw5lIuD2*@?B#0#4MgbeI^pP@wcF$ zybp-A1yIx9!m%3DH3#1n^-Uvbxa!8!PmEP;wZ~QJHtItym5dX|N)$2}`F_i#)I>KG zgB#^^EGZ2h>vhQU2aFe-lZmht7wm!ev0kO<<;ZOwppiG+B4Jr9oxdUfclVEQMDssp(5 z6>IsMHPL<0I`Ksr6Rp}_340WlJNwo>s7kiCFURtseZuE`fJtQVrudbrOPi;sC%u6b z_>-H|1W)($CL>z_1!W-zve6)lS6>WGW(hWt^8}6~`UMD0-(80tr^IEX)G4J}^rSrL>;jWosMC*f;=M5PIyiJl z5NGQnUp{wlO>`($e|jJ%J5|+xXB-f%W`8_mWFbdl;g);(Sp>C5bJ9!> z4Q7zmGxKor3LdaPnolsY$=!YbKsHvRRWaiJ{cy8ww7O8j!~ltT#}K)X(EFj~i*5gT zDG?h)f-SZ&04{Hf# zZ;%j>J*;Umh}!ojAgaTN#0{Du?1PPAe+ME+&P7=bgeM^0D>Kmfu^ z($DhJY%b=wTpty^6dF_+)#D$b!eBD!r+YYf2y-7l{av6bjJ$|P3JP!_1J)P$dc-l1 z>dpW?PrM6`Tpt$cENL0-RidT0C3S0~82Nnw6nxO?>Ye?VoX}V#k9BM{)TRCY%I&vw z9@chuC-&*vIO5#W|2;QR1qC)GuO)S`O7~qN26Y>i$bN+egGr%*#b$dmSy-MX8>_f6 zbCO+)?13&EjX83nX$oRR(O6JjEe{uIPl`^Lgbcye z-2X-8Oe{GHY9AI9c!`q(dx*4555*4LDrjeC(F+$YkbM$O<_+qG=vgxzJ9{S$E?AI4 zPW+_1VA!M&s1cQ``u~{N*`^vojTnXb@R6Vxa5Y?(l%Fpv{(Zpkf8haJV=O@GPU-6E z5_@-~rDdBEW8e~<*U0SLE(5xuy7Mb%(FbaxP0EAOW=3kYVEp`)ryoZG>tUK<@!KbNi8|2JC^4IJ|V%j{B!IPT35qgDWMuAc8!y_Gyf4vNp$8aiT9rNZ(>jgNiM|k_ zH=C3}0Lk66Xg^iS(}=Mk%B}(I#TieU56GZo&^!wY;=-tdNkfV_gC7b`PNp_gcT7&w zoU59I8-dnwCo#)i5Pm5wAcr8e`r`s4$9=;GTx9`*$N0|2gMG>jBQWlW89{j8*ZvmyI1U?W7c!`xYuaOo4{(fBb;bH7slE zwNk^({!FoRWU)LvQDyyMYqn1qyA(nJqA8L#EkCACym*qh#8Ixey?-Tq(!RYgTbgTVWGms&i*#YqINl zsvAfSp^tz5#CSlTl5Q;4dZZG@tuu?#Ju3d|zudf$x6eMxpHYwmUxtWRSlEn%&Zj?=3?Izs;VDbc|vY7x(l?$f& zxhCa^V9*tYacgGeU^YH%wyEO%* literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/seq_hdd_monitor.png b/utilities/system_monitor/docs/images/seq_hdd_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..73538f8cf237092a46115ec98b5607903ac6f608 GIT binary patch literal 63852 zcmb5WSRWz!db`#Z}1wfA=fs;6!LJIehXLHNGN_H`P;E;v3+c~dq; z{?|DKLZE*@*gqh`L(spYG(v!XF#b=B#NxloCsi^2r;7CHY5G3-J0jr!gg{mQO9;b% zM;WlEHRExC&x<7fg~0w-ut(2xUj#*}Hv3y1{rnRp-b+-;)3v`NEZFaxt^glmk#*C1 zNxmlMKbr{@hmn6$|3twdwqBt1FW&FD`0Hq1{F)3r z$9r@JEwcS}`12k?dC=^6lT>RmfYW0F9{5jHtmT96`ZPBCwElH%^Pid>Mhh4ssO%pk zQe^)i@)Y?8gqH9>U>q$zL|H&!`>XEH7fw6;!1x~quN!C_rlmKVm6~iQ&hDH3;+fMF zH^V)4GPVxkIwrnjGX?Dc%ChW5zn_>GUh-$LT|S{Dic0cef%qrWD7>t79K4m_e?F>E z&COVl=S_~okSu!#x|(sxy~u~q7Jj8boDE8t-+NLda0%!jMi!a{%FXa8{oP9B>d?S%-U(4WtDO%2xH#FjXnn{dj~r4r~X1U|VjDXxMmgIyf8iOz!d zx3@weDJmAURmkK+} z@C%K=aC?w!{QRC63*|5s1?%AN)RbTLRl-nJqiTBcqGKdE4lX0Rf!Lw!jE~Plk>!+g z7AZL8d_rfRI1jq^H8iLlD7pIsQhm+xXWa4t+C!+Rw*ueq+?wm-3AA0-f1UVK89SP# z(ff*EbNzQm;WjjY9bBaBs!?u5`ck>I4YFo*fU99}W+Je5HKTs5lU;HM(v z>+oY2%oe?U;Oxm_cU6NQcZ-ySYN^JDGj3EkZf7S_f{wotT-(;Ys5Og0(~yIU%umkk zr_eOm`zXxQo@Qp$V7K|mX`|>e*kxOGsOGd2!Eq*Q9q_+1eo-k%y-65Mll1gbfzIdO z%ht}kF@}-i)dgQES#Ja|Js5F5f{#Ow7GItFbed|s5o}{xhcZ<*r9-|Si=?eoBvCZN zmk=aln%J=xITv+H@fg)K;7lcj5 zp%jveDa@|@7FbRzfy{p0{(Wa53B#=WjsjDO%&E3?<$Ohf9Zs6H<&3?N8SG z6{BgCJ)Zfe2&q&F;q__@XUH9Nl*kBI-FW$diA6vgqy<%5)~63e@Zw;zKF(Uq54y0t zAYH&(37^+26+z~?WLtgGL2% zT9U5dU^aVh8aK^qp%B!?Mp7m+Q^s~zLYl-Ft@qAqYLTdsinv|og$0}1jmAZ`ZvGyF zsn19?PFSTMeQr6-eI~{_d+jB+QVQqd?LBU=yJ+bN#slAB=bJwiHA~^3H>s7aac>+X zKEotrJ@-;|isv^fAAzYc-cF|36o!#)nb@g3a7STOC+pcm)Xl(QA@u4%TYvlwUIg%Y=q(7EFWPA=7YfM2aZq(@^IKp zvL69$qa|ZXhJY}XHu`VpU%tP&pmI?7ry8ztwz(hDq!O`c+KQvD3ovO)+kS1XKdg-b zXWtJ6MXpRKF$JIfL4-zuu^ux}uBV+D-<<5ng6A(Pi1lu#5iw^aA<^kkbCSL~HMeH7 zY25C_Okr`}zwc~NELlF`20?^)x#;VV!A20oJEOs-d&qGAmZex=@GV2gkAcyBxlcZ0 zGd>@{*pstP3d;oLRIY&v^jCeRv-Vq?gu0zM?blj>?b`*Y=nFXi*80tRxYG;wa?^ob zxu+Tt`s`h;Y8A075NeZly~MNcSlzR{*t&axi$pI|kPM-34{7!@*TjQ;2Ud;S;SAUz2f%%{48i+;e%^)je~86ase@T(4;Uj?(@ z$?cgY0#2!6we=aLI%ha9Vk2-j`-MH6M^zNW%Gfgy++xw00ViaHGFbxGFjq9|8K zXtYYJ!^3KJdC&E(@I}u9l;>#@O{zhI<1d&zjDp3pZBAe&4h15jnqe&*=(D-Hf2FUr z5`)87#(T~s!2FlA zKJYO$L}j^fL$;nZIOBR_Hn@4)Bj2Odo!W;6D2WjQ%;CpaSX#1%QCXlFd75w1XWzi% z9%Vk-E=0=@L*}*`WSKto5$AzdiX8&uPy0z;p$%heM}R53DwgDsU-vZGQ|$8U0HDEmN?MLK zlwVf+1@B8<9}&2`d}4@?&`Yw)ZL=uOS&<0KpJ zU^9_eX1BB)1x^Rlwm|0v42)X0nzVB^mR&UGoS;2@s`JyNc)YmVDL+V)S^puuo0f(+ zM7sHL9KAPtFCD!{#LgW05op{7aMQQ2(o@lvuU=<<_icB^ki$BYufnY_(Z$6-kT?9EW6%&Eat-0uGQcIId08+BN*gPW@Y%r~a6C-#?w zn$(?Ge#iJPgJ5$8&!A1rkqaM5mC6BHEHX@xxy>mr05<3o0Q@m7Pk`)g)V%i_CXRQg z$L`G#y7*t4+}|UBnJRe<_cqot_+0YM=R7OFjtp!nmb;uU|I&_9&XMiULh49S+O2Lv zRnhXeL`GrDy&R|*o#~6(Swj;OS0S^@4Jdxa9F$NVPZ#ZLe83iTMq+ZkWD~h?ZKW>9 zA*PHu_9MIB>mw{$n3WpXD1PX;dv&bLkzZ+GHuL<#$9a5T>wr@0VW`z|3DlFo?^g z+cBxa*&8=m@e!UdzPPd|2YZ;7!W_J-#M5Qwk;jNp@}l{U*YRx9Mih$^^AuhX)3dVS z`-}*u>RjUJMIMBXKLGEUDZXo?Kf~yg)Npe*0Jwq<5%#Zr`AQ)PSHD$=2@3YZoPAVQ ze7>5UDxcpV*ZFudIbn}zkcJb_712x<#QUxRnk~?Ux~|1IeK<(PrG)|vnYd$9)kc_a zn|H9(`vn;~5rKMLW5yDUg=W8sdq%E$MT3Vn7GS^>=0IsHvUd< zbqFs5B{dBk412j`5T>4#d$&_MS{cLmQlqb(S3aw?Fsm4XKB7Q?_6?bEa%1p#P7%tQ z(f&I8=7O9?F0aUeH^-&f7oXB>PVa_)Rg))`G5dlwS}$Urn`8prBW#q-BwvZ#1d?1R zRlG~uD}M=DdSy5}GtPlBE0Z!3L3(q*@8B!Z$sh*n2?Bg!cmON4II(N)wIE#aS$qHE zEbV@vYWov*swj`Qg^Kxw3cESJH!VNNIrk+$&qs``pjU)TUOtAV3y|Uwa6mH#ZSoZ} zG;vflvc&T#vDRVShFmh>31WX(qMS0SH&V=H0l<5;)QiYqIu?O8Aft19eyIwHN~w$Kdn_YUd}E;MHU@E>~BD05O# z`2=n@9=j5iw0J)nqF9i~!7$@MpaiY&@{k~RUx<7-Grfjd6wTV0^bv1Ft&=k4BsJMn zqUwW$$^L@jI72STqM`kJU(`ESrM3nbG?sca0z9A)i2z+P6R)RYi(I>*nL8_FftG@E z-EgoUs63S)2bh+91qH)}L(8_G3+io*U&nFM2S43%k6X~$uOV=?5)Hv8vaTur+2^cl zVYbqc30N7Xw=7H>ZH=Ie7N=MBm5*_AO0~lYuZ&nQ% zW4H)-Ss|tCCUWVNjPr7bCf>*y1nnYmNm@w|cU2H>$|Z*O4bctRn_=b{__oJ#_RRhV z<8zfGm+?MWsW9H#BLrD;1^T&dk$=&mPR9CRusW(*IhDFuV7@-+%%uJJ#=Fw1J)~B~ zC(eLfV1UuSN5-+VNhfpoysJ`XYj z<%{yi)BuRYn7~B-_scA*q&*|fyHWmHwGt9PEiW)qmSkR@0FhoDG+_@L5&H6~aq7#i4S*k6Xp6;gu2=$csXsD(ND zdv2;yOo+Qh%6dBuT-DAy#(mOOd+TyOfLz>BirS{O_QjJT8!g@NxReKzdiaU-@e#ks?c6iHk^adUk6!LRG_k@E)(DAW3!fOA-`-d#6a( zl1DOrU+zLQa1paxW6(!vES?`WLEgb`Wf1OtzkT*(BPrhBJs`v~BJ};RHBZ_&}?6Mp-Uq z_uC2E3Me@YROZ&_TYLNCKD^gRTNZu@heF{F|Ex@~{rWK@y08I6PFPt9G?*Rv)zx!$ zU=cqwTQs4mTUh~;tx=;7Ei=UsW&C%BOMT~r&$*!0e)j;;U2$*anZ=r48+Nk~wfVD6 zM-v|#K79;PC9`IWecbMJC$4SV3sBF^O-Dj&zt0ht1frI6s= zZDAdVq%}&^tm3s-^zdur#7x~nm7}Ju_UH)NR%|+N`|4)c5>8iV6x0iENWHJEyeob$ zPxMAmW(Fc^05KJ)U+%`$F2LBDJk$^ZB-*U{m06r~b74AB0%R|e#=6#D$rir+_Q8_u zRpQLW!DBx+_WMZ9uJ|ZI&i&?o_q9eT%B4h^PW4+`OA$`N*OfLMX#wT~*{S0PWFe^rMQt>sw0*kl$Ff=Po$W1u@L?HCPwE{P^tXn5<} z%k0x+;zR~S*cA!Uy4R6{5JZ;W?04NmS04cgZ*d&wipa~oXcf(gdHUc?5afOkBQ1xi zhbb$g10eg@d^o;G>5{mv9S2z%!TsJ0GY(8B(*y5SWT%7J0FX9~K#5B{?6JRpK&(ei zK5DH8QDZHOZmQed+C9QnclLc2_sqwJ%sB;oJ7 z^jdfO@|kQ19zv1_ka{1$d|h+a#3$0vL1QyN_C)0I zdNPHUin+x}?8^)el0hr8gwYhLaie_x2-7sb4)iCs0aWC|hP|FZ!`H+X=V@XZ5A8Fz z#l0KVgBB0GFX>{%8l)0_-PSs4Mjj2n6&V~G_bXM|M-VZh-ZB-E3M^xXC4A>Rdp1q4 zHBS(k3m&d1q0cW7RZr4#o!?w4t5t|`gKOWlJYQlxEhS2o>g}iU z+Qfl| zm6|MH&yUrmr!_5uC|KkHS1$@?_%-O|b!>4yZBEVCbG>|xI!!~zkKtg2BOl}xvm;qTh$nwEuc#Xd(xo=vbsR)hI)VsD~E5sg&Ao)d@ot$zteX+j?4-C&!7K)(nuUG4>oI30;L z&nGs1{Zdh3>ZKqgse63g3A4bA~U9glQa;2{q5L- z-|6CoS){7FN&IdT6}XqWS-=w=)+f8HmWnL& zyXW&Y76#I|shd&za+^ZE8=6em#hF!}yxCQShRe8ZOi3lTCXNMMe-_69*`fqg9;7s& zJpqG`CZ8UrJa38?s_4Ld87!feLo2k-0vr!Z%w4IeWHvRG91KX7$uw=;bVO=swqIyl zMYd%PSoscMS8LHPFzLX|2mzOkTYpu69X{PLBCVgdtoXB0Nf-+}@tlcl>;TR)D^jog zi7HEjEai5<_5o(_wf1*-WN)+hcf1sirx*io#3{(Cnw^(^l&sfMz^;J;+fGrDU2BBi ze0HQ3vNX`n@mX2GFl!RBpVmgLo3inIxvm`d5O2SZfWbnKhXv^tGS4NpPETSPO9P?R z8lH2@oyK)%uOnHv+`W)Hrdyf#%%@ek>cx1zEIP`S3%{VLVcm*$_zNoK(H}Hw%sZD9 zNmY`v=X;7snhaw#O=o=+9jRIdS)1JA2@|*iP;hQjW7RO85u~(`Fb__voUQGlCGp*z ziqTm5H?~wb@e9JESe%HyDf(rTDS(57BHR`>r3W8gwd?^Nmc<40%pJX&OSR%-r`k#+ zSTb$0;hM(^&)5H;ey)+^)s*7`g${O}kZ}SM0TYlDf_TFt%-N__n!I;~B))w#BK}#& z0P=*?arVF5Ge`^lBgI*MnFYDP&AcWL;(pwkie-g{Pta!SK70*s>(CaKK4Hx|@WZ{~ z|2sH-KEAW*1TMl+ybMfk#pgHDE_(G*U&?Q70G_z<#wx_$DDojyd)vN4x=jR6|KYyw zI@xnnveGDn)?qZB+6H|pB2i=Bdc^E)GqBPBUl^NzRn15o;Gq6})eQ4^O)))}@f_db z?(!_7!ArjioX_`4Gkn7Y>t$?SV}1d~#(1H3;>N}sV=y=3#q$eXamBHgUn0v#PUy5XdGofofO<7CrU05;HCmca3v}hI^Esx`R&U8U1UIm_+ z>B*yTv3?(pZ`E}!vplXp((j<0e)#C$1WTJ4Tl`2-d)f!AatGp$z->b3R z07qK(8}Z+VP`~CoO`;g^4Y>`qW*}tOWzNerKS&hD6QIZ@pogfmJ76rPePC>4SRi$v z29L}zKtEV5`Lmv@A9CGiT;S?`E39E3Agv|kWeA*YIE9R~{P>Ke%5nHDZU~-aycwuC5UX7goR1*%}Zy#2$$e zR9)qLn%g#j`aq!3QHgCZ)w-_mcj=qiDzUhZ^Hh~OEUmct#Zc7G2bTyMmtOnil^!;w zZP)YU5x0JO*+Ua{ze)i@pjrn7&_<01(SPtP9cg=Vx<^;0T*~ZQ)myFN#@AXN@YVY;#d_~Y&EmdWRbgJ=aiVGW$4R?T~Cm$j$5-7 zE^39a&}f2r!;Ly?jKLrKV(K-s3+wF+RM}5@e#RC;0I`FNsh_!O(G_WI`_m1Mr#Jl7 z94j4Q8dDf~MT;mC85=7McbgLX1j#hRRSAiMcg&dR=dGmG-S4yv0U8qWw-w)=)=7^v z<4Ba|&GaNC7c@nd8e%&=oDnUX>YZerlcY}rr-(($ppY@ z2-SH~K&+PJKyd|n!Sh5Y1DdbpX%|QTa+7X*f$GM~YZVT>k`|uBI_pC{)gl2v32G{) zU!b0&CfSW_$l@rE@|$f-w4;){$>2Ul<%sKzBp_=}*Hs2dbd9AD;61pobH0UAv!Q$vk!!g zbjo~^M|T3Mg(tV-0$wg71OWK6a5fGHPG>J1RepQ&Jze=J(bqG!X6U>vA)rXR)^ofYAm=L^ z?6h={E2*Mhv{?-_aN=N~gc6gg3-9a=>YJ>jrmU6=idZv!&1`AChGD-qTrlZ5W0;FA)2Hf(=f`?ocf?3&l4uN2LEH&c*y}AUr3&)t7E3kPBL; znt~GP)6vQ2cSN*S))D&#-HGW*+$+#%{=L(j(ubTpdxqGjHsgZ41a z>sP?`=#v2q+tp9-(wUN;I^}}b%s=`nSye{>P!pG;$Sq6X>z@u6Q zmPoK_xiGE1?$;csQ(y}E^L`j87iO=sa2(X*=OVKOTr+0E$z-#U zve$E~UEm`9_+5#q{At(-OB4shBPv>dGxz}^)C{JR<5sz__CT8zLHII8Il*Xy!fNlZ zIP+|nwiu)ugth6GjMxl1Xhy|d-F7K@aYO8|0wT3sQJWClkoLS#U0g4+0itA9T{IL_ zS4`Y^hPk(%N~;Lwbp76h7rJif5GPF<|yFI!D#RJxz`u4b~f1P>BegU{{96kbMn-XAJWzz+}d; zTv{S9=3)1R`HNIMkayy#t(ay~uf!%&YzNZ0hpPO7Z{?4X6#IV8+)0I@X&E9kyP$1o zBU~e&wlAx9^GS&@ku|iH9GqQE*S-e7r@OtsZ1o9nAW|DDTn@)z5#AId;HV~_&^d#9 z#ax0V9mMOZ4RZwoKX9P+c!(nJd@lTS_>d%3s7s~cgNx))gQoX8P(X@e&|Y&fC6clv z9a>hY1!RoU$poF zWWngNJ-vwo9y{T{dOg{awm^-7BS!wIcLZgPeLyh4%8={WO2|i4OJH;iLeDBeV1Z5v z=*-rBoQwk=zaZ&7q|X<4OyMctc@JTE1rmVBDo@5}}P zxF|RiPzc_(hwBhcRgPtpUP7%SaV6M0XJ%9(nQ!0G1{g>hlnI3 z>L@j$+IVtV_S$nhA}N~rH>977^gt};&ttiINC=X=077m+KGhblRFe_6D!672h#}zl znLfW35Q@iVPbdRe19St>xr3JU)4}ma?Os3V?df{wU_8KK4JecIv!VMhUe?@GcBX#v zb`n(^@j%r9l52SfQvLd{HEK9oS7D-*xf1vY6A28BK-|znZ{VZfwF`r~gF~h##i#$I zaS=%yX7f|J>O&2E`3fTZL_0_(B^R%QnZh@Tc>(6anN3dQ-(cyO8~|KIYh|BBxA zVwhIokN$lCk0DWkhRR4|!SoNpQ|pBTgZD20zyBKm4+8*C|IR9|T3! zo8?lE_HJ7Jyi>gNS6gJDCW7(~+FN889ospTv7j>LopV)OK3IY+VRLN(-%j-RS7DWq zakO~znuV8k-uuG)qAVa;tO;fyq}Gn<2i{(mAw`{A{$1OTV@2&fq zLGq2Nj#^udhz@}Q6qJwr!QWtq1S0tPi<`eQRk1J&A@{Lc0|3nAb9Ra2dZX%*tP^&~ z4evi7;55@d#TEw3Gx)lOL9^6^j7uZcep5!mr8{@f91baP&(9Z|U7t}mU@r;#2i1X` z+||~9i&pYtSuMA_j}@2Km}M5@Z>bs+#AW_-_JC36YIMZUCTLgY1tL-5OK~^?R&OB% z`5H>Xy9*fp@YBfxa zplnzQ_XmKL8*|VW&7k4AgkW__;3-pM|7MI6Y1HjcnRqQ!q!~e^%pzK+x=@vzeO1a; z*&y#hudL)k0Zr2&15M1>SYyUhZ+coqM!QvzXjsl5#cpn+8OlYod0NFr6 zdYvi_Eo#_^vP(BDIml_-D}|R#eIAaa>coW}#iHTEDZyj-+|(_{l9^a#s_he6C}^1H0St$6txNeJISk z;%5I)Hre68#tEXPo7DS`ywCzaEflW+m8m$6P#FD95g|dsH6RiKnlHGCHqWl)X{9KA zJ7UJu_%n#YsfEW?CgbNduePF{(^BWa(W})|P}6};h&bJf;i%)5%?UqE&)Q!d-o$<1 zkVOv`Df9`jjG{PEX@BD%@r$^@=6uUQ7uztYeS}reoNiM|&7W@AK~C3(P;jqFugt3V z>suVpl)gf#_LjfGB43eKyf65VSs9%niZrEs`|9vB_F7Hx6k<%adv1b=2uPRd0glk9 z96z@5eO)_sv4jl8qb*Z8A}=-niNVov)}+TB=#;H)cF2(HsZjmK)fTR*~4Ao<4vrc5xf@TXq$t)?zek5yYC zK8qA`RP)OnalXeP6-B?YdZynba>^v~m;2yUS3B4+3%ypZcpyH3pAwlH6Ro%BN)&+N z?Ax_K#cuRXnG-KNBT&P{qIei@&WRC~GaLCH%ZFS#P3ivbSoE`)NWKqPFtUL#d zGTdG&(JH|wwqb0;>57CNUh2acLVv%z^ZPPU!oiNGMc6YfO}iEV0myrh#4nOF4W1uv zJhBA%4?grF1T%adZLQg{A|$Pkxvh62rM2{J4~`~tJU6+WRU2$RdJ-r){F z3EZEJfz_*i^iC+y$`%gy8jYInH|u@_-J8a>9t^tx#sBb#5~2ePQ=xI@mbuB@1EI}j ze^9*15r}LL9BAm`07h9|@GdY)7~=!XHn@NSOA8tqTLEvVLVCQB=G&l=Yz{dEa=t~V z&0`vg4XpikIbkN1py!d609X2KTeg=&*3M-3T1DD$1LU0)fURPF=TmH;aUhz7fXt2o znK2w>96)?|*&~qC@iq-ELv->W8?b8WSim)qs|YJtN~bn*fP71lM1z-%+7VHk5kzd; z3QK?DG;_b2&ZpmbOHfjYjz|?B{!V`E+RpVZ?S%{0(uAb;BglZR#W5jy;o;sML1KoL zAuSRLt8q;~qY$>!dlb>JRF#CfRj%cjy0<$nn>fF8?ab6r?n6()pVmO1VNXoL0q}8> zGVS+sn+-gk>CP_z zm&{QURh|meR%jA`0@H&z`&BfM0TmZ(4S-?yDwIy6V179r=xTm5kV2GRjoRU0s~_YD(+aaTQ4T?jUf@5vZv_kMV^lIH0 zC@LJ*AHG0MrKu_sb0=8)766UuJfXYtdEMmhNIx*t6<@x+8iUyP7WR)iXn&}lDA3>y z$}Vq|nJIIwHEZr8=x4`9VaMNUpGSGWwnnblc4Tu6#yA~J*5B5Wz`EHldq>>}G=oD$ z+6)DW?*c8n%J8^BsjBo|>Ic{dkKR8J;Y*kHeOTHz1)ezadW$2Y~o8AjCUPgH3aNq)%}Jv``d>oHLAcvl(Q zfLdT+i&GP8mGU|QutqY!2kp+j?~viEAX-6LunSp=2@r&EHIMhBel-)F;2YY2cm(8^ zzzcvuZ~gkA#wI{+V$2*38ovQ0m0Ff1SU_a^H*WBQ@KLB3yPv&xEtZ)}psLfVEs1l9 zvcCdYQFp?kBd5yCiFpENw_rUgkYzc;-UNY-kgAurDnG78X1uG(L$6j=JzJxIy?1=4 zkFVJOx)#F$%g7@NbyWda5Ca}Bk49Rz0qBykvdw6#$AZt|5eB^2goUr|QFip)QWY(k z+SakxLpr+5KaBbj*}IEGz^kXlM5^+DGH39)7Te z>B`K<-|lsk^YmRm4;F0J15YPFst7=1cqDpPN{#KU%wnZ+s(tf>-$*^8f)=RKHx&j1 zC&V9++KMKEW8!jZsoiHZX{37x5aH_>56i}24N>gwei?vqT0gCgP;J4FSS3jC2GEAvjMdLsgP zXNG*GRqZif?#BLJe?>p90S2g-F6-}TR*4BNgrBH?Er7Z|b_Ttr5K({-*NN{I11jQeauAbA>-&dM!8a_#q&3;KYB)OYk0wI?$|QRFtU9 z8yB?{A5#IOK8p4Uo=iCN4Pt_Lwh#mV3mt-MZh#ND7ayWgwyq`zmrF$h_;7O;f`QcHskm1& z4ax_ib394-juZ(XM5Y2lhNN&clG}qS1v#bzNoYVRfm8LQD%j^!`MC$=SzrabGlB#i zK#4sW!eIC^QWmpU2>7{3=@xVkyV3ErSpBV8x_*Vv-nT@)H$cl|Ao+EI9Mp#tF^A5h z-+8?_5h!wBoQMFN_-k>16R9EqIB^7WjNuB)o_TR%{IuXl6JiD|X8j8#Ze~>MjdV0v zs95^RycRD1&s0%Ki8kK3l>93E{;+^rZP4)+Qzp z4{;qXK(rvn(87l?FN0CaWF=#y;W)I0BUv91SqT9c+OO44L-6m%wdMam34q}Nl=JUn z#rvCk!8zKy239m<9{>9n4|t0IHiI~mJrb{F>S<>9=?#h5`$2AW5ognRg-M29%)ij0 zfkb&fLmiE?__K$%YhXvXVn$ZRWNm7!12GDUMW;=+v~cs1C6sOmtfedR1{iV52goy6 zDN|k!L{{|qYEa+pAZ@;xp|$kh2ZV*&^G-GuJPCS7$d~;YTB6^cA4`jvm$IoGf4xrHcYq+EPI-_0un8FF!*xeZoQsZNCCM z4Fi54MECDU;Q^HpXwy7zKynblva7BHCG~8Q86;yeq*dh(tPwSNdr16z?#t0j3jYZx9F0#oL-%^JSF8KLBCJ5hNcqkDpB zWepAMk$KA8e(b`4!?OkB#as=?v`0YR-*jU<4=k2IB8e-+x}`nvlNGZ_GiG3P)5fz* z+r$P3TU=HCI5`jLsE#i5PmF#! z5Tk`2|LR0DH^-v|Oevx0wm4KmEMt^q7AIec<`&`(@P*ImT244ns#wtyD> z9tya`(8x83{h`&gHGOqfOHnP*Xd`NiOG8#22_H3tK9HKeZ{TNbcw}asJ+?P8^`1Fg zz^`ujVA`H}+(d3*rHkN3V7=(=3L6l8hc&Zr>f`>!Ao7*+GKi1#fdGR@{9GVK0*~)> zn~R1>@ti;Q!P>ZW+A0OfvdlVL-qEqQQJCeY(CpN8KM4G;38v?!fs8=>%zlIN*&?&~ z4ge`yYksSfXCfB*ty^|yO+c&?`yvg1518M2()tu9Rw9E7{0@!>t0&<12s>Tj!2~`~ z9E4KhO##4;*^-Z4#w|zc=?Pyh(-bdoy-0kOk~VynjJz$7ey(zAFH$rCIY0g)1wo>O zR$s$`7(n0_zi81?UT-m3hBVY^s1mA?&S1^@cfuNjNWTS6j&Vw8KUguF<7VGr#aIu^ zN^GU*DeAJka04+DiF~&f13##vP@ta#qx-q&YV0AP?S~&xLqAd=10oWO_(q;_9B+HmF!qi)6G@ zNz$Thl@L+c+K5sqEm}y@LJLJyDy7JCjXt0I_r34q{{8Vhe>}%wJIs5z-sk(g&gFH! z&J#n3V~6`X2vH71j0z8R#>7JD41_F_E(cMczY{?yat_c61k8f)Cq+ll0G&L*$(2v@ z_eCqEkuEWgPKww#G&(#2L@p){7A5Bk{b14{3Bc}MNVIrq3hzwvu6u>q>2FU~T3#l+t0Wh`rSY!kPq}JYS98r!1g>ifwGROsi1Q22@g(u|_ z=@gti9utHR1@W}m37?M>ptaZ`GdAu&u){cKs6!kt0BmRsnt*kLOQXC2`UWGbX-poH zPl^VlHb<#k=E%WHKtnScCWydl6BCX+njOb=@ukQSU0F2MupG^=F*sy2; z$tPSI09utAUHDA+!Jjxw^C z>KCo>SK@gt@hY@}92@QjcVvZ6yc;Rg83ueXM$Pesx*)v&-^GRGSaAeL2E_8e$A(y_ zK#F9+SQNa+PmGKNNi2N{g z0zoDa#u6z|fj08<3G^knM8{%tJuqk*lBf{!9HYSKvOpDD3{!%WKsz`Xn?s=n0=4u;!wFHcSa7J18pUEo z0c+t6kB^hlPskN+<@yCgND$DjyKid<bXjg!3#=G#y zTqk-U;Lox6R34GT6R-ke*^CHD0E|om`2~QCII+|yZLg-cA4)&~RVpVHlceAVf@WR+ zc&fkJDM|#IbtO_?EXzqY(Rv8hga{JxMG`hq=D_q(J1F5aEND}Vq6J9M{J)_Kix)>E zN)Tp1qAlPh?LNS@M} z0jjnr7eR#3PasrBL<(IUyd@$D+7}rka~4yg!jwr9drq1#PcnDNd-+ngfw5 z4eQ5YsBtlL2cbG3P9b$diJY(;e~Oj?1inNx8Uf`5c;Yw(i5?V-zyXf2B9=yS6wr`P zY!ViPw^%9FpM#R~SUxc*5)l+ff*gF|m~fOYBU(jbMN=L9;{6pwxwj%v0NOdcp^6|B zg^LUf7l{E$fl8HW?W5QaB?Aq9I3&eU#?_k9sCW?+XgR|fMO70-e7R6c4p&AxJ77Rq z=uK5ei4k(P_D>8~3X~8GoMQR0ktnr*hVl<5VWF(R2(B=KM-|0}b6xy={k;J!CPL#W zP7)uj71G`k_-HB}t&&klCPJpPZBw-^t z1R22>MaKs?3DF81lPVPX^2tPhbqtFVO^WwZhDW2A;T(ZV0eG|O2sp)u$Rwd0$Shny zxFY~*K=sFukKjsiEFM>dbMOrkVto7F3CzI*NTc^f)A&5TR5P$Oxfa!j{NU zcn8q^frf>v7(q(s2pEQnbB5!ofm{wBf%3-k`zp_%TpXAY3LAV`10` zb_6xbDV_v4Oj5ivN){WAir@#jNTJ?_le%zKPz8gDVmQcs1E~bG zABI5WbA>UO=m~&J8c7o7LaG;}?7A~OC zKtrBL#dnV5sF4m#Dv!g&_^Aore5eBriE)IBok4SH3`Rnd#PTD-s63Q6N1H)&`~WZx z#;F2>M2ZTEig1clf`^dBW9bN2kcT+q1r8!Cg%uE>;dpD-I2aYnTagi%%>A7RVEd0zqk?0CqP&9509jjZ#vKoTv2lL4dJ}J}{gEJTg)d z$fIkgpMfEVu@0csi8)adKn6u~q2f3vT(pmaG?ql+5`BY2{!B3c!=L3H>lejCp-5o5 zPGpplLyy;LK9>o40~}*HKCC!AnIlAs2s|f@3`J(f@JZTGKbpgdb|q-xMSqlvsRXm~ zqJ1L;1QnTy1S5EOT)tc!0e1zBFjSR;Gu(ye;!k8!0~`qw1%nb32MT>+AEKWRDVFcd zLgQJk&itq#6#(doJfaltPjY|@Bv3?DU<}STA|M{;5GZC!Da-(0EEs3QW;!qed;{V{ z41%+d!$b#Ckb*~~I8wl}0c3;G2IW2&A_k`xu^g132?i#C$+=*P9wAl@_w(oQK?7j8 zL>Lf`V)JQy9u5~rQ}U6dNKoL#upO!1YMCn>Y;+Rd&o@pAy2IieX)zIebPOm+@xd+B zT+o=s#W+Vpr7$)_D=Qfo=|FJwAqfy*-lhu=6EC0=qoI7Pi&hGH^#iRCuB6y#IABbn1BJ`s^DA9T1tjZ{n6T%SNb z7{lejV?`?i&|pX>EJC3Ml^LoWOv8ylQsekc6jVWUkzoA7;Y?1X+J)~F9tBge*ytD; z9&|SONfA;o78q2vnKUUO2t+9`&|wgcR=Ohb@!DMlWCx}|M1i09AQC$|f*z%Wp+U{U z&pFV+*TI3NM8>euB8C`@fulr2F-{74L|hPzLRUzmi4v{D^kq9kk>Okt-XEdh`>R{V;ysMTI?M-2F(4h6sRZM~jL2?rb^H&3wFj`88cL5Ym|2St~n1sS~ zji(C$4+R!0CrQKvD3cQhVE&HWNJ?y^FAU6O^mBBL5kb|F3?hJ_WUL5WWPn-> z$Kq9NEzCi2ibBW9;21%)kWY|{Q$K}L%sZ~$vSfX*Z(HqM0<2>RMo5;&SC(xQDhf03HQMc~kpaU7OECQufQ zWP$Wk=FgS+iz7iL5rm5v9{6VaapU14tW@i*!50zZ&n3x_G8Y$#FPG#>Q24PWB!35F z03ke*93T~|NlXmhDUbqp6+|-~fERJn?jbTF4seFOp)On~OG|p70;U>0Hat)qE)_%u z(lO2y3P9ipKxA-1j0`LGMG#a}DpUbRCQ8`^k+&#D>uH2ohY2i%z@tDVXek_q!^&ZC zz}av}3?$7*9_55*;o_Na1~UNf%A~r8F(hgLOhWcnf_6^<0@77BY56y zI2!FOr-H6mW&{BfArfLS4k%%u+HZm$9uVOw2loVDE-?}`*%ic_pj(^Z3P_^B=mIbu zOUL+w_G%~!A3(wq0<`PXKAJNWOeF-&83zQ9f)``8A;Uzv#)AiGCoV!6B$6KhbKx?f z6G}{r=LPWD5=SJ+5kV}4!c&D9(6Q{`!U1D7DH8+uWD^99XciEFw`k(0)R_Q-OZeVw z3S8wF$Bc}H0d}F15gEtC!Gyj` zgUMKGZFK91iW9+r1;Rx5`@)%yP{58=fyP3fOz42Z$B4qCWC&#tP{?q=FbOBnNdlQ% z$bxEh!&@C2CuDJXEQKQs^g`eiV45}&M20vij;QqJDPo`$5Y}TD+8iGI7E_}Tpxagz z;RuB~tDI2;Fw%(P7!^ncgJ#)s0FHxWV$eb`0*Whl^a&s_0<_P|i_?ON3cvyYzXaMJ zY8=!TOCdXJBQ_@@(Ln`=gT4eOQVeK44ENPGDFGq^m};ZdTw#m~!RBerf;UDS6b)RA zw+i&O;$mqC1&j_3;6eo?rNk!+XiyL#J|5-*4|Jq+qFm&WQA}t6DrjQPCY6T;y(Qi> z9B9@A196G*Fg`UvMgzl?9T+GPOyP`+3W7Q#R1u(OB9`L-2gK=EKB(!s1To-rKcZq{ z%%1`e!d7p8Q0<5jFkOWT3IZ1B5D40V5g-i((>TC~Bw^J5!k5uL&%^+C(8<`4eRvZD zvKZorM$(mGA9M7T^rrTk>sJQmU(nz2dhlc>dlic({qcH`9O5te0lE6ZA{8ZFHOO3u zqlH}Q#b3FXWZ)OS|M}&FPlIkP`={KxpM&^%KkKsR{cJavYel3ykM8kZuTIQXZc1;DIQx{-;=kTvN&Uh4g31Nt*&;stFZ8x{ecA7DTrCVE?r}In3Ozqj^$C?fzIJ0^kLSsIj64KswQGCEZ23UJ8pq7+cbiYVNiY8A5naI} z_QILtnHPOsdV?Br<&3UT4{_w`%jkBGr>_5AOhMB?-o1tqHL+g|dOrU>x53VER(|%9 z%Wu{$^Fk1X!)X19{|}yk=rrHxJpzuOeYczP_ZexXi@gv&@lA4^CN}%Y#}uuAy!4-A zb#ya#wK#+0Z4Nh{_$#;~TQ5y)>c_PHOvpRevX0q*mvCXPuAZ%Vo)8>Qa@c|Wdn+OZ ztje^*qTNoXS<0%k(TWpdCRwCEmAu-cU3>h78GHZUD*L#Gp!ro8x%4M~aM#^=kDoe8 z?iOrQjtn_(>VNig*QF^la&CS)(Ys+F;~~6Lir$v;_z?T?ld-2~H)b!r^tfPe`nT!j zlXNqeKdLnTdzXCOJi86E^D{Pu&OaJJ^t%6Xo(R{@{cQSkr0&|`S8j`$q{Y zi64V`l@?g~h4?qCW1iRUFnQG*@Pbj+KK)JInvJaRDjuyfZ`avC`+aYB0FQO}k&m_w?6G#D&&ms(l`w=)C$ z^#nf~;tzWyEW4k3Ikj;5rkl5{ELyp1*4JS=SHBFrES*VRPTKr7EF~Q-AJR;1EjIWH zRln9n@9I0Y#2rh@uAG;ANjb8-&!vCY^6x9cpB5uNf7_jgp#6UHU|;22kEqqheZDq0 zzUscUZ$QXt987F_c&eB8{E}>u{!rA7w@`Q8#l_4wVYZ<|3q(&VW_BtpnR#bITy>!l z=q9JU15azmAk0+@Q)*we-S|Q?Pq&tCv?d*#i;e&Nx@VyN;ibotg=^K!J<+WX(rkxA z!`g~M62^K$YZHGH$Hsate)pZ_NlX_6-+bKHE)W=fz5O`J0l>!eGoxEd7EwKGzP+d% zcU}8!?zSdU?g`&xA&23AT&@r8{*qm)dIz!yVtqcd(y#Mjs=8)lU*O0tK9+}6?4Pt)LV}1Q7;J?-ffuAJUucg zCt=Ukn(F=O*H##)ryt&#ld$)hJ~_yUj%vBT=fOF-#kU2HW=02NFzv(NAJj_C+6px{ zG7ycXPVYtw=P>X7xcS3pi2e4bD)4OF?6gmznp^vpA|ZWGQ;ZIK%F;KV7-Dpm!WXoc z{+#D^+v|jl{cfWsrtQyPpSzb1%_-Y;gs}+?u4|P~y+{nmUU!z9xcWhB!h^_f17BA3 zwXNLYy8ebCQ=wx!Z*SG(GF0Nv)z2V0cY=H2Pe0mNCw_XKxHII{lWXOB9`9S_zcy~b zea5~eKG#1@dS;UEec3QD?_VL=nw=FIi65sL+&a+cImJHV*nIo>Ur}E+?>tat`)4#F z?U(K$cHIr@v((`x@x#I(`S+|k1X*{X{w|k>uWpxH<-f<*ZJR$m;r0D(d-`6P5HdFD zWo+MbWY2!?YP-W3Ltoxt3vPv2`uF}x6C1swLl_S0;c>ioiwLt9rC2CCmXMWGUxy7Oj>aiIDr}rr*5_*jDMfVL?{JVXo=IO@kWXerce?Ik} zNIDaBE6>Krr0BQtnMD>}t;Lq>A@qZzZFFl~%>!>E@;02)^~z4SHo5LR&-T9EoxNi^ zI4^un+5ORrdiOeK`qW-H2R)s16k?V-`c!Y#5jyh4{CB2aX3cpP1Hn(IdH$K0=ABmu zP8ntmx+UnH`OnH97q|d2-X4z^M+K9~MfXEy)GX?_HqGyq)zXcv2m3Oi z?x^g@9Lf~= zD-F%>CZF4H9^Ui3&GllE)p2ynLVHbyhuitGUG@iXU2mF5w?YeQHhcONn&+30%eFkT z^gp!xVid%zt#Rq~O+bQa;kM+{S5jTgMwXlBdL-!7kB60PRrGsn48I@g(x*@OY%hJ0 z{j5lnk-qPj>9G~7G?x-SSX@b{sw@=~dD+zxYE%pRKQk;&?Tm^@i6D&)o*>tu*e(y60DZLsq#>YfO1; zzR$@|clZ29I?HyMkq20wSGoS(={29<^1YH9x_%k>t^c5Ce;M(9s55Y#dKB-j?^>1A zuUSRg6{=?&47=X)Z+x;fOy_8@@|ZXyV6GowlbZoz@8}v`+i~qZ0<9fn9}LIZZe7O;r@>uh6?ZKpYXWvD^SS?W+qd|K7^g zCwZ#*d6z$#@PI`0@aMQxosV=+{g?IM8>{zUxkZjWxGCo>=U-Sf$s40qjgWs54 z&%PjhGfzU-&F*<}c|{HBZ+t;-C^Oyp`NQKP(vKEmW0T9w^pz;p`T4agW)8nRIeq6` zXJ|&GaIm@Y?bE*zk;c%~M@OIhsM4$Tjt$qiWyP9xZwkYSnY6;C8*^~?_rI#_SE_%^ zWnXW>C=K(nYmfYEYtI_$K{8uEC&cNth{a8JxaOa`%NB89S-ShytutO4v;4XrCABkt z?OluZ9W#!vJ?mFKb4u#H@?y;b+t2g7E?!kiH_@hpknOs~_GYM{7_zi#e(HyU!nw!f z8J|BMG`vu(eQh~`GyL834=*jwIf&t>AU0#N44xtN@0Myhbz0x7xU+9@BIE1*xvLb# zx)sq)MRW`Mi;ZjF&`M_PKVm`AIYe(5fHW`T?%VQ+knGlk)$|s8Sbm1Kpa;Px9>~j~ z={#Nm6lTmc7NWM7@UgQ$7i@Ajix2Bucj}euStZxL%h2$Gg_qQbwCMbcD~WE7oaU`> zZ}0DaoV=gKm}z19p{L+wN7+lm&!PL&EA9@T()8PR#Y5hulDeaxRT*5A^A$+^(5|nN2QISnZ4=9?=u&9T;I18OD+#Vpm)ydu2fqk&RM?2 z>C#Tf$$jaQqqjpi4^oZ=(Hr!DwgCVbne}scAb2IKYU&Bh9`EK%yYBw}UCJ-7Pn94O z=eWd#d>iOA|JvKKLqq*NJn-O&chTqLb(0uasPFs3zI-NfVHpQ(&YZfujgzd>j$n4#~ zc{9agF=v3d zBN(g1C&iSd`UG7UYFMo@`7kuXepYb(CU>~_<>^hYE=VIH?;bXOaaj>C{_<@2Buv`E zQyY56e*aMZ7_>N!-CORlUtP&~yYkkCeF(-66F?;8hDKptuH|zJco7vOJ4{dcU?J8aza+R_dx~ol_(ky75n!T3p z-r)60e|_VNUR*NsNi`jrmj9NOV(XK(FsS-V&%Fh$#enUTck))X$+isN_O7d2tUhyF zxM{hobu&+xDMU$nwoQHaUKVRs*a6+=46j-z^+?fM6;y$Kw|tpzx>s`MTl;O_vNZce z7yUx*6ob!^yXQjBO1i!E@fi!2o#a0*G~B*6?)~R&dH&b^%EgZgQhu#W{PpcHjCEvn)R)jPll+AzUcX>Kn^%zYVI09Jz}v^Zea^rk-BF{q(ZVzQkJPr%NzlR7@_e7Phmy8j=Nf zRx?ir9`;DQg!>lr^z5lj_Obj-&C^%V3U{jwB~QhXCGj2S;C}UiqZJ#!;>&=@JCO2$Ixu+L@ zC_Qt9O0iYhla`PxrrRVLUNr7`xMB#X>A=gW|Hap&u8R^L_BjfEHh1i&#D%* zwGOk%+aPA@lY8?nX;Pinc0Wovu+!L`^?re*%S_MquhrhAz0f&>cM|WShBNhlO47*b zwW~%9rcu)-7eDtAoJeZvDW?DVtx2x>=sL~db<@@Sm#ew z`j@IocdXxJZ%JPN?1Fk=1_+3Do8I1^|7*?32W6;9=(LYX%^RC6Pe2vj>gV+p`j(dC zoy=7uH2>O-BlD*y?#{^BnJoA{_QRy#WdL=r#IuC7eQ(w-{5)zByig*~@4lgDJN-r^ zjoxt2RN|(2Jtz05>Vie%fi3RuQf}sZH5Ws^kKSKx_M)Tilk5EIzP&F)j~-XOX%*8X9TFcWr)*coC)ltQmNP&IILn>obba@{=?UlW zqF-oPj*$k(wx*+}v2koc66wHq2B-#)!sKNk9@Dm(YytKWG`24}3jbu2fwc1w1_%M(4q zP@TS(rCf4#m?Hb>d5FR6>(gg@-JX5$;q1g+kEfU~ebatwv*^tZTp78VYG-!RM1#w* zw_8qFzda(Mcj-ayw2ib1<7d^UQ@+sVtkC?Ayz(4(TuLv0Y-TfaCA!4a&&)d8$Oi|6(mBz*J&|2y5`-v-$xSQ^^^hBM?V}a?HlUtIq2zT@IUE`t2T*!I-n zbu`3J;sOo8Rc4yx_rV9YRPk#aKA)dsn4gibY%{vBB8s>JF}Zf`5_Gg+*vKm<&hfYzsj+>OtteHFC;X<)qq# zam&jt_ZqrSa3?|f8jd|KX4bn6hCJOl)p&_5qTlI5S#Dwf<2rsZq$K1(yda^R@*;KC z(_L8wQ;CD?3u+deynDFPa94onMw*;9l{~z5bw7X#yW)U}*Rw5hI|iFB8Agx~S`T$k z>YSVfS^Z2;z8hr6)}l`@71O2%4`cIU2#h$tRJqATQIT^rY^q(YNyM?1S>G=%(_IE} z29VZ5H>ssj)byKap*z3=$9~T&u}IEMD-)tLCEnFDTrY7gAD#5G1UaPbA?wqmg&l;P z&1>GMM&Bal++DcahBS^$FWv~(~Z~t%e zlA?Pb6Ajl;t|<*MkBSb+^81d*-Z0UjEscJDVdQ-Ci6PvmyPtAnXBfXT0+udO_vA>#%)Ve zabf4*Ql&;MFPL+i{6X*z(Mg4H!am70@6?krCv9(7?M>Do$Z<14W^}DY`=J^0m2_7> z@SE=U^laO6*Qcc!zCWe?;ABx!)|F`8%nwBl*L6Vtm9Po1);_-oL_@lnxqmpnY7EGQ zdEUC2LXs60tDjw{J?EWMFAUYBXA8SaeHtC9XaDip7o2_9APA_Zk_WF$_D&;(|qw)rNVwg)Px?uexDhvnf-q~Y4oH8A^mTD*b0)iPaFO-KirZKr2xj|!sdx5 zTJiH-OvDA*M!j_rHt6i@9rFGy)7`Miy)*AOe7dpJy5(^jV)EGlAT@m1#Bv2wo^&ef zu{NJSXU}}p!!K3@h+bVa3~}?Al2YNcoqO&1jKQoIT7@;7c=+(U-fA;8P zaBR;AJw?x@hR-io=@_3_j>!<+0~mF}ab0@DNdSZ!=Z7>O`#yj7|Hu-zSnM zJC7PjshO{9a^6I8N%RH|cmd!(Pc9_t8|e&;swQGF5KmAWRC*^v#KQw|D|<=mt=`kH&EC_-EFCW!)2c^zI<2 zRM50&KFEQmYEgP!x^i?!`=!IW&#%d}Q4aY31A>mOsSeJim)+Py)A+sZISOOp!AfKk z50?E#^|37-2yz-?)pnOuZo#}wsk{xYrc(!}A;4+&3uA8hhZ1yRx-UN4-REhU`{+#l z&5u_v8tVO+GYNd&d@=X-%bY?@Lq^>;?1HDInF(!g5|+FWUO})Lez_k33o>ordenY# zr`&+HNhtfaH)f#s!&^8bw%)KJ`p4fF{C?Ax-kmR4$-<`I#gv0LwX%Dzwz}}O3&fK9 zV&KbM>syXOIJ9LyN+rENrz-!!8D4cE*yovDBU@mf6Ta+(EDLK`GxdC!QH+~XH?xyi zw|r84)d_<~Jtcc@S>_(8YQhw2f=tu1i-k6c2EfWyURXKM$^u}@lhjKA3B$kkCY-wV z@X{__6J_@t%cbPO*Pj-07wdl<(~aDEuzYr=?(nafZ6`o%4$uO7OA-u5l1t9g;fMy~?jeb<~i4%joiTXNkg#pGif&LsW(Y?ZbUu{ri# zvz7POsd;TiA1WQ@6?FT66>kr%u(RJVcVe?Px-OkAt<@dgq;td||K*j$T|T?!goB*N zH_LI^#>7P9HDT+P#gOxE>{(!*_=Jz6@gBGQl1)Yv$Ql)DZ&_UpT}`{L@dFMUe@edfx6cd< z3!4jN>uvhkJ*6t<#r&i{BQ_u&-dq#ic^s@lIs9?nd?%i!zx~V!S`o3BR+J_P!1?AO zUPgF)dKfk?t;zYAXZZfugjw9N{v2VytyW0$AbojBf38;XA3JcGO-)y^OkZ4*qd@B1 zhTrGO}zFU~#_R_6`mb9UoMteG*mP5R~>a0(k_SMS?O&1Wohg^)-jdKt^? z#xC=KeCvkqqa(7rN1TmZVxD{T+|81H?_*f|ADq@v!D+mk1!L&p8v4GxX)^4~^+-(J zI5HIey|3+77Obe^E0Ead;bCUY)WF-MY*(phQ_o68WqVRKXVLGIx@vo^XZrAAy{NOx z@ab=T-egTl=;fMJhdmZJImJBTOM^0Gwa3A zFF+lm?(Q6Xak(@}{Pe8OQfwOi?AJeI3AG77W;{HB4aoDW0|3PdN%yrpolMPPbd%wn zmBoGXfoF`Xhta1_-vJ3a!@3UuWr3ICPQA!OJbUr+`yy=TjX%Yjr4xI6VK?_3O(knZ??yzYu}R2 zL;$7{A zb@izkrKXR#y2Ofi%jG9QUO5HIzTR+cn-K^cV=^-f2}kYc_B}Y(Xb!VCwz+u4Z~yYX z%5NVYN8HawtcPTdhSf|d>%RZ!FuFo7+j5;U|2WB6_+%QSEZsv^n9$MhdB193B2A}m zLOS1uR@De~wOiTA$ScVI%73QaBKYb5Khy5Y(7XTl9ih|w(k{KINBv{4EVq1r_EME0 zDRzIPQOo@Ng1Td<9qhs97wuo!f$jVG%NI(@>-{z)X8O0bfc2+rGuIukF}Cg4zTZ>- zwcaDWnrBt~Eda(@p~;B83XQl~Y%_E>@ZXM^ZmaJ!Ycy-;M+4F_^`AeEsX?hj$ z-K9@+18W3sn^p$-j=iuwDX5E?`{{+*?TqF0<)N3Q<}NWWQ7NCky1lsWv8AY?<&)XX z(U*4U;6G0j^^!g!HeXF-@nd8?8yQegoXlJ~?AgWdkj|wR;kOT3EZBOf{u9o{=TQ82 z@~P1uR$*=%?}kJ+r$39TBQKbBS6>@_F|S;Y#}{kr)@$@^XA{dOFZbVC2CxOeE@(0P z%=p%unGF!LBSH&?3+Ld_)61OY)RVq_#j6Jfo5D0hS?A{@%*<~1XqV@yBT!(i=y7wr z+Qd%+kilD?nN`i*eh;pVua6S18J3s+y+ix=Bi0%=^>`=K&m z2`AOsmR5517q9a^>ivU6)7*85Y4Z;xZ55@s*L~lSx^~&vB`5fqY)y6tYy+rvr`tAu zs9#;$vT^y3#`D`oTL8@2>jBCqJB<#-bPd++@Xd6vv_H5ab>3`sDSS?g<@T^i%U_@Q z+Ww&GYRg>2_3>~`z?ql%!Fkfai!nCGeZG4&!Q~GoDvPbrtrec2lCj(AR7UvFdrRKa zM3Eep;M+6A8sJg@jNL}=wbovjVbgRYc*`SQj_TRsH^o#MVL8^6zwzO0NGxasbj zwax%!k>1Z*Z!`4z*4H1J>$GwC6YB&|1Qp zzrS$JjSF_Wz6`!da5_!X8B@b)iLHX?MxKY(Z14Em-u-FHUTI&$lE9W@nx_wE_dYyV zJwE$H4Fq@7X8!Hjr3-34q8?crv_AdX`=y0ZyXmXtk(zm1Y24M_M|BaBufwnAwq8D& zx-zA3Y&)LTUauaTTz46c?2l@Dc+BY{?ieBWfXBcYkL2bnyf1MSW7OG|nXo^ zd(4RO^?)FrdUi=L^-a<0o4*JN=j8XSzh_lhwc{;1jsAO?ecS&559mnDe?SLqQO8C* z9#+Z#JWTbxA8>A#J0(2CwPwj;UC#7%j=3WJ(iOa4?}}chmsMQTmn~6$D-NGrymF*8 zy!F8hUPnPm#R=ue9M?n%)Ukkc>fc)a;mue7tCFu*9yL;Ku=CbiJ1RE$O^aEo-7K@G zRp@;5k1MD`c1zE^opYS+apR9BgPJlmeFa4R_9;Riq5qYO+Wr3F2KOBiHfyez$S@;|MP+Q}@urbzb31+wExlf<%0{t{S_MHIXnJxyT?_0+m z!JVq-dtbdCYU{l9HPqs{M?F$U*3mpbuI$^Z^JY39|9W;uWkFNH!xv^#cQ|=oB`nlt zbHCi|&q(HJ9fh^m#k-k1REv?xtvQK=eHVS-kN3tzU*9Rc;u`mD<-wM(%=#I%+P8DC zKX={Ol;H87vnx1Xd%hseZr?gwRPk%`nqSeD`jg+4R5ez^gp(kGiAw*{Ex#1Q-p&pH z1Ix5$LUR4;8_&6a-G_*n|GlF%XvJCfzzk6^Y#yk0GcFQzQDL`D^bcE@co`fXRlUV~ zIW=2ejrPemJiyz@J+GMTbl?ony|t7vV}R9)K3(ARrFW6cG#zIkFd{kCDMz+%zQOhx zDw)dMpt1kzAFRKJ&=)`*n5xXFSBB~wf@Gqrw|}c%v%WcZYNq`9;EnomtC-Z+u2&Qu zFRvu*HEdhk_44FBPzX9+v8;HZZE|B}Z+VF-?Ba&4M}7bU`RMTVGb7TKkNX3e_!{BB7vLWz3rmv>6{J|qiNwI^=J0} zsXJmtx{vogcnt5gfZZ^hv*Y3MMsf(Edj5FbM*UCcuGl|g)D6x2ndlV^$SKBbJzV~Z znC!rk^15YJkY!zm*D@Td+YYy7SdmODpF`ccSVGOO-ffGX$t{w1?9Dwj(D^~eEKwbN&)J|c(`zH`<9P@jfB+Ae0wo5XZ5yc%mW#heWUeDb;%}sGHh8V zF8vt^x7w2e;p|8lGP*WnU*L^sv#wu~&Qs?Tx{%5Hmt{Q<8#j2KWxcq_H&;*Bp^2D_ z{SteR@kspS?gs}|k7Ly*_|UF}wj=nO`;nJ%u^X*F72Xj?OoHI9tP6&hrRFuy8DopC z>d;3X`OvHUjsuu$#&*&4gT)WL6CbvhGbigh$_1GWicN}o>ek&~2ajtCWu2Fbsi(I7 z%5k3Mn;{z%_iwnND;^Czo{oz@X#F8Q8@hqmkKF0;3WEDPqAGEmEcWxCC% z-_?|qA-5k386!+t;cx(geB;h~|U%CP&1iu>{W&^t%oKPZ8}tRK&>xj1Ka=kD=82`9b0VxvrKQj0YC z5ql}Vg9qkf6)m(8?CRbJn{{pHoqs#^RM9iF6KdCTM(g9f8FyFN4BeU2eK#eM9=XC+ zW0;LzZSdzZ{Flu>|9Q^g9?S8e$Mc=AHQx-^eSJ5a)J%j3hDWP+TC7-3%&9wFL*)`b zTBLJpK6UxsdQu*;;;W5u!*=;5DrA}0vS)w#e=O3|Ec0%!@tLkq&e-tBe_*v>P>XRs zn;wJLvvrFx8{K>sWzCcZ>tFDA9^W@G{{rlOa>bpqUI(n7eJ0$-*qd1G9jf0n#!O5; z(^-Y}Iej-|^RsKPugaAW&h+dkie?q^;}3)FQpg2& zLoChro}qVgOp?N*>h69<>LMW^ma>3}=TTsKq7-K)hk z%N36tUznZ!VU!Lz`I~;YVp76bQ|6Wv59tltwFsH1dCCGU5VKgPc~6e@)?=Ohp7gzj z7mokMDt|dQMNZ@=Cix#tTkn;CWHDyB(T@J*6If%+>%N6iWNpUkt2sWtwJE9C(oEtr z0l@@(6Q}@j+xqsCY#{a6HNCyO@ge}@yv*OGt4mpvm+iCeOzr30N4Fy= ztews9X(u)R4PQ0PEpV8U8m!zNOP~M7704~^@w2vsjDgzT^XK2Zt2Fxg`AJLLjyqp2 z{wEQ~FxNmfWp}Rjew8O1x>+EBe`sE;QJInZ&wn)eI-@~u$(_;8uE@e{6oJXJYz2npFm*^kM@4H|1U}nfU#XE6E7)c zu&F!;z^)rARv^suK;aE5*IhkR)mGjITG+N~KkF_?}z5m0T)ny8vjJPi+ zhpIy`-C%NYx#RXyV=b;4GUNKLd!U5STr0!g(Oz}LLko!@UK#O|{~>J0iLs z+M8gtN}?rf6y3T{Jf&G~C@~_kt`Lb4jCmg(vhKd`^~i{9W0F4Zz3L;kOi@Avlq_V{2)zqN1R-NrQq`v0)eJM7FJ zpaEFTUlMU)z7^1fYwx^jpVk6-+;vk_J+CuOuNF*HdFvQKYqBTA)E#FP7Q+N@DJln% z`0>xT53{xSX))zQ-(#KN>6N-6rQrvO?M7PAIMibIo&^CqFEgu;9-TC0M%Ry5NlnkH zh4s8|fEINt({6U!BG0tIbL>+sXF@M;2gu5XYg-M%;cP$4BeKQ>*;4 zB-PYzGj^{f|55IoJ?l1&&aG2_zXtHDYTo^-Xi3?8S)W$q5$fe-k3zNg+ph#fm-mlO z8WFQyjjg=^t!18;EEKRl@uY|Nap82png3Kjk2NveKHA`@B#Jkmkmo zdq>X++U$?Y2Tsje=*0n)o*#oRwrIKlBx?+d!ncKJ!Q9AOvl5QX2*_EKG)mE-_qCpC zY)i{p)5CJ^`DhGu`Q|q~>*QtKT05bQln3bp3?y6T>AA$*btyZIm%aw@*!K^tv=A(?`8E8b2h9LYB^f}L5u-o9u;9XynhVT52tcjW z1$@^1%n#)dakG{G=%@N|_Je$6VEv}LXHQB3&mB+QicU543w0H=+G@#QK%}S?lVy@` z?;ippJ;0hD979dfa=@Ggtqp(!Wz}VETue9$4}WuWk4~pT@#&?{G4E}rhv}uv>Gh*S zMuPV8u`H>FhsRuxjTbhTK04_SSSa%jyC>A7diia=)!uF{eSQ7v(7QYPmif<-msPdb zs$_s`HQA0_P4e$nA-`+Vi6JTK8K$XsgH%`{y zqDA;O3tQAiq?_)t9{hm_vt_u<#X9x{9tCB9zIL43lKcMYxuw6p_wUd*nv*YVFE{MF z9`jHEsCtI^k)yf=fSE+U$ksyg4VhM`$!&@wPJH^yz^zk_S}={QUjojOSMTB2X*olj-Ou zJF0#WYQDcErQq7if&;2oBpNtWi(mbLZPCxSK2ojzF8H31yf%53AJ3eeQJjW85P6iG zs(A?{Lk2H(ac3o@wLJ9l=f;_yU4TTG_l~Wf=C!SL$6LIX&ZcM zbb)Ub&SQ~FO!j8WeiPRzxcmZ;Q@h5#o%+_mJ*8*k*!T9l(50RGKnZ4gg}ctYd3n}C z&y7FHKD9tTW|BmZWS*L-V8yS03|Dl-2~W)jPX}V<8`T% z3rTrlKjh)pXMhKBU9sEiR1l)RWx=|QcMs3Nm42gXT;8QuA1HH3*3+4t@_K5k?_io{ z-^ODuqNlS!9pIO4e&pr8n|l@sr=`gy`Ej&-N%O1kqP+Ne7!l=JFs1-A^ z4;-@IXO$A`SLGkONpC}BDe0H7?S9|GqhZGxpmawyp4T5S4bV6MOOJ*K&e*xC%Vzva z+=q+`n+wC`VReQb_WO$uqhDEX21YBm`he{+i5}QEpv55rzk1l{`E6!F!(%{#oCPX& z2i6>PPZ(YtPX6J;P6xuD?r5BRS6dz3{UNIgr_fi@W(2W2h?N=&c#O8;eb!JTuiGgv zD)g7F9|n7kmcN8l69hIz_Hn%Yw9@z|T7nqPMf2@`kBXHy~XK7u}vB z)7zqL*|ndUsfWWo`a3SWqPKsxjpz)oeWjXbpXytKakQzo(7(ozbMyEvNhB&F$nWo{ zXz3pt`H8^XB8V3>6!n+nMWr@(sx>eQ_D*-I`MeXLzF}5rh4__rbo@kiLGV`=5 z&X|*AT;2+9uZjG*xh^?YFWg=Kps8i}BB3c#zgBPk-9x&1HL=(Q2#zL?6)pITtSh>g zUyKDI!1C{ze`Vu%mVo_e)P^Recd{p?Tu9B~WS_VygMj9n;>w0z#(a9BTL}+&R?Y*7 z=oN~-N0sY_t#dQfvRNmh>QZr;M^S+(#(Q*W$~BEPJ~ut2B~s;RBSR#4XJN>ZW_ zJUh5}*D7$*HqXN8D%5r?;iS-PLC@m6v8c{&Ng94#c26?e3QxuoXk|ODX!=l0MA5SJ zIeixc02ZYm-X=#3zuZx8QE~O=h5Aoh7J}Nx1{RO8Y&1Q3mTf2D>YO{ozhGo7H=i60 z{+eo$w$l0blI)vReDI_>pCUhwYT=@=WEy?_EU~j6dU5ky!oK>F$ja&W6!(vt@f@V6 zpE09V&uOoevAuCBC0;QEC?yx_Q4vb{@}5qC&B%b^H0EAe(qI5 zb88_){qh9A^&c&FyZgfBS)b*z-toVFGjO10CY&KVzB=OV7M?q+Kqq=T9le51eUmEA zR0dY@GV>&%KF%; zwA-9;DZ6&rI8c$gbJbUy&e|9y{;J#^Kk>#8fl%Gcgq6<+v31QNivm8Sdi)A!DY13d z6<$0U_s?r0*!StsU~&!XnBI`ZqKbPN!5ara@TJT@fS_MS=58V|i7~5wRrP0_2*N$+ zkC%4c4#7bBv7%hNwp>>iWbB#vRJ~RGKk}!-XPh^ZqBcb~FW02o$49QX`4Xv*FW7NB|@?*8dA|QA0Bp%o?E0pckWygK)QJbG@-Xht0rXq zEMjxNyi(_-x}BxP|BG##L#5TNQ%ftzC3o~6m)v-U1qI$`@=3tv54qO0xe7^+k1tCZ ze*E~s!y~B1LxwLJyc>3R4M6nI_^d~g<+0%Sr zB`62yvyG755+ETpD0WCz4D=}iY|4WcWa1o3xX69D)$PN8T^NE;iDUwb?aFP)^`B6G z+Y-D3sbPTYCrQfT$gntmeGhdgoU{n{dVBktKUb&hckz@H_o~~m3P>XNGY@YVxfvs`-FI-q8!`#3 z)=JvkJ_r%Fxb1Omw9xz+KpA4-pKsB%Y?whH2L zjptyK^O;0!1cr^?dkO05W2Q>q8H-nbvu4!IT ztv=#*3j8OoU>&(=p`|1OIZ8e^=0j`nbx27I)H_Vj8B)3nzfjy&^i7lfm?J*9r<~Ac_=+? zn<0Ic5P^cd6RDMYL!BQ6YYNMETcX`r3cI08)E*7*#iizZK{JkLwl3?sdKzi$9 z5vA*V`!uPoE2yqqARPY(Tc8%N@kr}v$RJ$yFsQV=Np<(<<{h+fZ0(!I)0Dn5-5Y2! zh6=n%=be1~B+Y)Z6Y0Cp&K{jEK0WaWC-xuLDIMx;-nw-`J&pUEjtz62 z3#T@Pc7eu%z##0We(7wFyOur)0{aDz*`c}8-xR^9uW{||+D8SJnSo9-JMeIsqL;sa zoiIJ4(NHZQq+KA3HmlvecU1*yC5&b?JCdm#je$o;VufS9>s?a!CL(;aI zqtg(>Jf2c!JXYB;=CMNolOv!l^!oO(agY(>SpEd$$P%$Z5s12yxX>{-w3N?uGDRwD z;BDQ8dFO0>KE8!hv4b=Ot=@(o`ee0+Th8u!4J%?4{nsrIu$@lv6b(;I7e7{R&7+l) z{yzDf#0#Ooh*M9Jc=1_+!{<|E1nr?}Cgl{XH3lY(tjpsH-my;gSTSI;*Q5IKrbL=y zuw^tU){-k-E4hlhgxUm>1Zc+=1aedxF-1WuA7cS`mz~!BxnNQ->5nZP5Bs@MTHvw3 zTIj)m6V}FP+nc;*=sr7CkSeZ>vho*2Zimx<-VT5+Hw!4`X0*D`G0XZ6@EJOYRZ+-w{8?5p&;Bw#Vz#86GPZ`<)VIF3+Tm!u8vaEq`M<^?1m=DuG^`3}^RE&= zTR77Z6P%Jtsfw*zf=oRx?UD5+sAWdrQ)2cSDi7^B^N_E}&WBX4x=(Q2j?{S@IsUKy zas2%v*@JV2oolo(k;3LqqOgcW?V;f>Vx4u%@dC%t|-- z?NAA)FntM{%AAn*G?nJq7+5&?;7CM*;dq35i|C1tp|K)txGG zIjHWf4NIZTGa1=EkMZ`XvbHhjnj@F$=LVUYG)^H{COAM|V>KE*-XuaN8^1@%s^zTe z$jsiE@6}-1Wt7G;3uuzJ8>jiU3cO=&1UPv98K14omJ2skDYRW)qKshS)rk?>aR#%! zV-|R{QFz>t@kli&O5i^%y0FbAujH zY#+Bg;kCn-7BA|Nbn|41M=YU3p?9*y^=Y7wxZRj*TqVKv6`r4%kgfBtu^~^H&Ltd? zdbK3wQDY<8!LmX^B9`~O2C`GynNCJcAdF*(qi9k@F)(8n9TXX_2{Y!^mnW)un8MmH zksF!cn4rYHI$s$~edQ9C@e|m7%pY54QE{7d_B=S&X^39$SGa10$y0h)gpyyDmXShn zu1#jkH+wg%_QIdP>G>e%SPa7984TWjI~IYW2LFJfw{@OwFGD2jN;kg3>G&;ProhH| zFa`w8Y^OX|LAEigLnRFVxI{ik?1Sx`CEQkD9vhb>bA(jOLf+i?W+!&6K{vPh=@Bd> zPe)R19N6Wk{D~l0W!}^!)uM=K{e@SnhK1@^0shUUv5A?qu_2J2?Rc`2H}%%gx-ez- z6rE^&v;kTlvC@JMHD2yg-9=m!@`3kxI3%y4^^s4cEf{_w2pf&Sl=E?(!|XIIfc&$u zCntH{5KsWk^!I}o8HEo_zT#G)A6jl+wLMS?%dh|FjFnY!JfhSV@*lejPD^-zTkQ_+ z`4r1PDVEpYxehk@3VDsT#&2${7uwwo)qVkmyN;kB$cC&Pgv!@wE;*mF(Jsze|Br)L zLvMxs3}uzDw%BO3zZZe9gzh}0bxQ?Gs%^xd>5gxe!@g7<@bhloUircK;R6w0&k?!q zFN;*8^Ipb#&B*B6;BfENd+mKlm*j}~E9G&jb2?YS>a#6EZ+u&6iM*49)1p0@`Z^VL zhCs|c&p3;k5Kh5VEt|=Dd}1Mg48SGwuu0FnGks(RKX>Y3s4PUYBU3p`hY`-B{8LA` zNr_}LtShpflm+s`4^?k88P}-z3WLZXHyvwcgv{F-E*a?db3Wb15|2KOrqP<4nf#!|E2&yg2vsHW!IroQ2-r#-&`9c z%OT6nwWun3jRGKL$X1obUpg*?@*xzGp}1kH=iJwfB!aYkOC2MpiSS^)PgyF9VC;{U zwsI$bC>6)4O$aRTz=x6z7m-Ae@Uz^D^jSw?w>;Yi*Y6fj+{)4Xjq(0}c;X9fJUoyt z_dmp>Uy{cE$p@k(n^u^;A8Ao2(a*g|MbE(l)zjze`{T}kE%A6{S@`U888T%jauF0> zbYkR=KLZp;--mr#14Q#_uEGu|r#)CydHm2t8JC;gT%XR$Y#pcxWWjiqZvMgTJ_5Ak z26J*uk=A97UfTm453_4`orssdQ;1A(jvq4dEIm2Wo*YQd0x}avHbWPu^{@(H3@2q| zWXv7iYzbUEKKb;DaetHdI9gFrQR>u)A|w{5k!tSe0>y9~1{+WFzk8fmwJAOz$?2Zhp|r|`!b z#1KQSW-{NsfdTWO%Xm{f)*+qm)8XJ1-Eh`R(m>d+$0vA1xb1U?rt|YJw#iq9?vu2K|- z8WV4ZY|#X)&HI6>{Jkr+a0o(Ry3`;=yYB=d8}&Xo5DAtEnp1scOjftN;vMdvzc)P0 z8Npauv?))dvoRM*L$!ZKB9%2 zZa6-?2n7}qwN=n{V6LMDR3cYLNzhYXP$P9BJcM1oCCEWL8Z-@56dR~*kgz}L?zfLa zENEx36;U2Jr~V3ah70eottm1t>-Elh_%U7Bi@DcA=R{^5^>ul`4iPGF$_jpSOIS_V{dJawN+vw6TS0Btud9ot4Nzwc-0M_7PFftL zcg>_QY48{to0%y+_+x%N^0j(BmB>gcz3l0Ou{g|C)$WEu1I(g4-ygy~&m?{B1j7V{K`!?Zp(no8=)`8c_Qx#?9u`;XmRm^4c%& zI7qF(=T=>3w$I@5RGLX!G6XhxBhU49N6bYg;q{j2Lwdy&J>mQN&%Cg}GhT;Ow39sb zpYj9<$^Ui%pi`&yA5uNL3W0n&Q^-ndYl12N_hSP-!pYAj9?!Ypta>B_7NnUVfM6@3 z{~Id98NT!2BMA%#uu^;XyNw`e^Wy(_IsH=^|G)KtFs&kogFnYKo>sj3{@d@Sb^gJF zC;)dVNIQ~}6Mvwo^z4O>n=;-@ee{Z9UpY=YY8-9Nxt1(?Y>u=^OT2A>1)#+XH8lH6 zBLDuQ3bgqR>w68R_fIdk3L(m$b<-jr+!vtRp!M@)&qMP7e!K3vCmEvRBX5^oFxmq{ z_7f&N&d8ozV*G2{9W);szaJwTv?RQpTlxBHXv!f25hNOP^3WFpQ22x>J6Pi{qly~i z1un@z#{{%fHGS_4^1x$2sU<)KSPk{N#m~;-=b@ViRu3|`_khW>9qcfGq~%8sRAcDI z?Ff<8uL}!DHh-+L>8d5}dHY$~A{i0XMcZgh2J2rgBC@`=!B59weWNkxyn@TZ&<_pZ3DZ=bq*cbs#2E+4px`3afABP20hO;I$??vrhH4M~i^5KPQ ztPAYoS<_~%p&J~aoS91%FBC6K86SpdKhP{Gt%-eOg9KBhzoEw+RvJCq%Qp1qucl1u zSQZ%h1csxrnUZW&y8~(2X!Ma^4vG9LcG$C3Pae|R|Gg#nTYKt2QAYEtRU^>P=tv^d zIIvL$JK3K-$8t)*-J7{bE zb$iY@Rfq-ZEwJXYYEdzKZr*#d!?`0PB}YUgou4V7HFfBC%8I-ZJO+P%!(B;aV4c`Pg2zjXd6(YTH?BV-DsXm#4daV>mCzw4sHpr7U*jp~Qy$uv-tM_UoZ$+s&Ge zz@NUne@>(&)#c7{;6*M^hxmWNKZ)aMOx^DLvx^k%Iz0}k2QNcBE6%7Lch7(+#N|_e zowH|y_0qy*aCZgjrEJTS_OvQz*T#a*%V2j0zb0S4 zqa0xl$c4owYL+QZlQSTo!Qc$lfKNZkEwsaZu;ak-r){AAe1#;{vUVo4@*x9czp!&3 zpYplyBf(8BbyiXkZ| zmtyf2iEiPH27Kfj1@{*|X4KA*hzAYT0s7M5aROsf z;C=nE*mD?Z_!GLZY<>>%9E>|Tl+Vcmm#KJ^0_y#lFC)8Q=GCADij?bf9;9gxFdPD$ zaN^z25H_upC&_iav;dY@c27lgm?WAJqPF(75qFNLgI{!}{aTIKcX1)t|lJ1$U8Myu5*#VYhry!O>d1 zK&Z@w1{lVk^?|{`6<^Q3e?CsPJY4Ty+I9_q&Rowm; zudv5Hp;2VTo6sb3A6AD4AwsEOu;jq?yd{wrIp6?!2MHwC-XdCQ&(}pf1{X89y+s<^U*#ZF0xQ-rr}`GzHbKe=&*0B z(dl(T%rSBO@$ihFVE#2gka#}+j`0PTe6X8Of#r?=CRRj zzYisRdPb)PZrI?Mp+im_v!FKFbGU(b+F9#HipMvtP4h86rm_@4o$|9_A+Zvqoq(h` zB)M5y18Rv4eOc0;<@PhB4gc5Wr^IVA;!kD^s+%Fd#q5Chq63h zQ*?)tufUo2=~HSG*+>;N*KesaYn}Wgl0w;k^MpZ~n5V(^KBVCC`@BPc9Y44d?48$j znHwOV8P6$0C6Fp}YQ$O%`r>sOK|bv{WCK`*i4G z-X};nH(PcI%w9e8dFXh?dV1vPRu*$nIX5_6^<>~=2*~hfzd0{K*9uf;3Z-D1fE*F- zY{Ov}G~rl-N4P+s&XV3m)d*+08=!dJn6mDj!Ccp_p<4{^M|Nk*^aLh@gBR85`VFV| zF}ds#1!?kb)by-mVLqh`J&`Zf!`u>(WSL=wS!LhEj|CIxTXmn6qT@7mZTwz?@rPhm z8!VkKQtEKeQVx+{`8ZVgI;n75kwL5g)_;2+P`mz@VLrC0ij_iYWYfGSEZ#3~L)N>J z%_Ugf94wwo+q9q|<+6I>+3s!3z;?R7D&__+FE2-XNOmON1QYv!{_1?5s%^9E^9J#1 zCu;9+62uz5=Z!UYLxyirzAUBuGD=CyOwkgAx@PQtLg5%xhl6R7tvMnMkGg+ePN)V+ zK;gc;mY!T*IFmK`LsLJA2{#(OW6kpUf=6kJU^w2CWL8OvVL&y_ettu%7`DBy9Q%C@ zEn-BmU_YI8sO?SD)ms_n#I4F!Y}NJ2BOO=T#gEMuht7XO#+&d>o_a}G>p_Y~<&>yu z-TvXVKA%9-ivsx{0^OR-&MFk_hMQUOkVv3O?QRj@T_Z0aV##|AsP-RU;s(mv_G7gz znSYb#(An!hzl^qGaXYBaenKlM?cV3OqJs4R)Q7VzJQ_oi^CgKGdweMKqlcB!cF*6h z8k};6KSs5)a7A4rd^B6Aij>UK{(zM~-3;=AbKu$D8-x1CiU9>x-ZKH(`T|9haR?3Fg?R z@U0pFB7o?#gE1{-;CiE5Q|Lxen@%`r;SJWT_%0-|(sD*KReeh@L ze2M@nbe(>F0jKxjx(;>;b_|f@f%_4zx%xBS9rQ1+R#2qYlaF_0^eR+!NOh|pEhBZ~ z=I_K&6yLlQGNhQ>J)Xi@a?~6ne5p~rJHyA>_Oe4x{COfOmu<{{7fSoY4t|21wLPW( z`%VfM@jFc28NCb5dnxa*>J_5(w;a(vjf*d4xg?q##wox)R1DADeGkf9q&GtCFeQz;V1#4tNdF#)KStR7E7oID zL^)hUuE@Azu^2sbsKfY7ukIAwDPk{v%qVoxU2N(O536Gx#$2j)klQ z?uY9#J%)|0mN7X4&O50Kcum>}TN5?q?O*g#&f4ex8BG!{5HDcoHe5d57&Q9wupQpt z*10oPt7UU~GS+D`P*3h9pWThR0RMp4lH< zTuOeFJ$B9NIfE~fBu}_acBadd!yy+!OKg~OrpJ@B(LW^k3A5AI_YUcn`Zi9UpG~50 z3C5$V5>NDOFv=v%?AXCf_HgguFd-OVzuTyjdSBj+@W}qP@Vuzb6_cnFA-;VO~eU$YJ$ zc*ybj1|i^8xq|Cs|M6KVnDX7KhqNwZgojz!Mxe{FfVaubk}x|qQS{OC6bAX|%X?Rk zn#AoS-0~v58S6|%;mxUDRek%}(l+p6fKcz&;ORn-AM3_N`B&b)eHJ6U`*@~)X=K^n zlPU021?_i~8@#aW;^^Z&R1!7|iHfwWS|%cM)FIIkj^t43zr&784)P{P!0`T0b(f%QtOYa|ZZ}4gtXrCIP`1BgJTb|-X z_jipeMd!Yc-L(;7^!r+H*n77;#<_dj(r0=Bo#Vr1@PVJN69NXxE8I0my$MXP_SB?GU1*mZNFvMk!e1*^-UxE9w=Gu!%qC6x>tEh$>-l(Ah9u2;*X7@uLEm<>o zcsyUVKOWDTyWx-{J>DJzy3El$Ed1D3`@i`yEphv|qw=};1!Z(&V0RkdTXs0c538vT znUXY$DeuF7A7D6pe}3+N{KH_kW+2aC$$q%HIJ3{89b@7fev2Qvt)PIjv_lIJ=sqSE z>|A|EAArR3mSBI~TzNKnj)TOF>Zt1!19(*DxO>zehtNA@@YRz%4&Yq(!HAB?)vD?I zLpEd@LWf1(;jn}%kLKkjxBl{-heH)phQ1oz2N$bI+Z*sd^}0jfhDO2h`k#XAjUim#tLOH?=+bSKo&8@xPe)!^9GbD@B^N-sB=wrQvkbQd8L3> z3J=^n-|wz;W8Rd^ZA_dxE-0vlzn1hlF-ntGElRbxAnxab9*b$YUE1fZkCq4|2MVk4 z8a^mieZu8(QB})D^U=>mo6s5M0lyy06NACI^*yUMX1+de`C{q*sb{_QL|E{^YxgS4 zo9g>qUtPcA@w!gS=CCrjYIqM(J+iL051)Jx9HNSefJzIag{7AUA0)(Yg!Nb#llJFP zY?GgOQn@P$t^EZz9g}A$#a>2G`4Pt{qfcxKFAMnGG*e_;s$UEJYOa}9q173TNv~_1 zVqjC6($*ndu@wwwVn{#Dw5z)g951U;UVG19-#2}%{eEciTz`eAgV`-F8^O%;8(+kq zgS?RTY4}#f2ZgZB=5oA4zA@|lCuBId!ng$WMlh6&KC}2oUnBmG#4&{ZJzOz#qkrE&dM(? zzx5v#{OJYENn245dNb|pJMDhon*L)DPI!k=q{Zq@9jq&g`Y#)sI27Z58dyxld4rV&`Wz$i;JjaQjnl@I3`yczvbc=)C zDsW*>S?W9b;5>wxuIM_1v28vwKJ6+ZO0+mGW_}}wS&uOo>`2ea zTlr`yV%yxc?hun$W{>ViMmtxw zJH*mu->i8|vz}gkLWFo1(p z|JUFp8>FMb=vbM)R!xmtzr{02tcj?OAVj?XN-KP!7W{c-@nhdZAj4J!)~dO+8jqL| z^Y<*!mD$m4+vt!HqkdU~gB@FT82YIxPIzMV9{E7Rn=F(FdFh6I==)t*r(`3-y*=w; z)p5}wM;MO=;24fz#r?3j!;zYEZ<=meO-E9+zx4mkX>iX$j}U5aOG` z=KAPQZD5uCk32l|HNsj;=XvINUe9BAFg+lD3HVMwEmu%HN&O=F=Xr|uu)?`0mj{pt zt0+&% zJS>N$ICB{i{Mt%_73*nKVh`Lix~m-1q>XYpD7v&MNXp2~htu;n; z*EY2D1g?6V_+-)`NS_krcA)-j&G9y;ZPxR`rx+y&%bFSRmDa#{0Ch5|a-Uk$l3hn%{w=5S)P4?zzA&FeZ%} zH4X^yGnjie(OPq*BD{rwnmUrY|GhP7E?EM0Sb`($uon>+UB)pvVzOZg>0+E+R{k`7 zJGN}k)-Z(O&OnAi1)I|hjvMbkXH=DrxjLM}Hx1nxz_tH<9RIE31eh<;-}A*uBeiu# z|KA_|Upx`EwUEJz$Wacl+JB<^WARDf8!C+UH;f2aroG)+Qtxx7W{XFJ$x9>1PH8$> z<31n}IDO@WGdLI%wk<*s)r2TLb!#-#x9G5t!o7M3cP8p_J9#0|oeo{dwV?NQ4i{g^ zx+8q#E(UL^+|!e^S)p)oe!+e# z7=P{hXE2s?`8pE(r328#6!hv&!JC#p0YvExxeOzC)4(ppfNG>sGc*9?Lz?F4Si3UH zL+iiGfG0XCZ;jyJQ}zoS4BIHSZg+o94oA!!i0fSWaysdVS~(!j{b8HuIVop|BhCCTz8AO?Dnx-VNJ>7|QVIzvP^s&h5$_Xn-JuV)|ov<;vsEnQuct}}Ey zBvPRWp=?UQ?&uV~lVhky(AK>Yk}B(QkLCk&n^xeHQ<9Q+Z0?**gJezzSQJv<58gVJpL00ORy$ox1j;2-p`KK@CcL=n zRO_lbdU=M02p}p0eDLP!l6DdR`Ibb13bpX0A2E$5+ zEP^EN4Kf=2Pfw->mf}?V2z$*T9x|j~DlywQ@I)wSXkq4I+z0x;p($Q0`0CWNY;(l1 zh&S0>izGq9=nCN}l8y1{62B$DaOE}{n+z3iXY1?CpbEkzrkw4OxJC7tpzpCJpW?Mu zFr%dH#@IkM?6OQ-AsQPV(4+LNY!qy2hM{Y-LaXl!6Z>pM#l`_Ki3UnA9{;)86V?~- zKaCoj{uYWUZm1f#q0)RhT%yl z2GxGfDr)w$iX;!kZ_F0Ja~hrFAZw!u7+P{@EMY_2KzY@9Ve^_~>-Qt@iiwK!9WRXN zgiY$ICu49HV9V~$E9E%kCXg6;ksZTZ?*2aw5lKmzEMvP)-@^%;MDs{MrSsV#R`ha= z;1RAJB<)v_0CNGZ7K&xf>%7kr2(&T{HW_u!u`)DL>*A)x$cGDVu0DY?c(-Z=FWW#c z(Zchi407SJ)9Xmw*~Q@VZ$X0gQpaVX3MEyff;jPuljVn4p**6F^(LMO+}J3M_rkW1 zD)P{|53&qLKk4B5MkyH-c>?C>W84b9WY`9YtTvMBq>~HfqXZw&vg|F>n`HDVvnmcf zBDE70T>}{)KBP+7v=%n4CX9Rv$}iK4iUb6U&e6A@1f1vdQcvc88Xet*T^C{?Str7a zF$^#LG%tJiFep z#E(H?NII;LYOZ~Pk|m?@wTCuRXj}m!AJf1EC4Gws)%(VQnba6AU|5g)WCwd5vU8yT zW|?>=zaz6ncB^FW`EU^sgH-7PWfgqLhVjS!8NN2oYy4EraUACt&{RJ57tA-t0+3HYd6SLQxaP8{v`q0+P=?|84R+$U#Lq000Wx zpE1ysA}O`vEI7u;l=Px+UK)ItLDDCLZ_C^NpttDDm+!@FYiTjr6;~4{pBWGdO=B`t zxqlO*tJBo_DUbL+%d#>Fxvg{TiI&+2V%+Elq~aJuC~M+SFyHegjYz;g77-Aove9gG z?97B2=q4@{T1QGwLVz$VHCT6t%yKfI;1AR#2>Q~*SoMpF@jq^^+IZSfq>@7X^loucErLB&x~O|RC~=}Gf*?=^~%A(Ua-JNk)_ z=WCU)sdOVw&zmUv`E7u_?q<^p{T{`--SYtxRluqkC;X}_X5Qr8%^u~75WamW*7Tn0 zBXuP($*2C9Q2GmFm|vSe z<`;ef zvj0>S5QKOzye_J5vuJM$vEk-fyy7Fmr6-1zt(|JB?+(4^iWlgTN3Io+L@TkqHhtin|VT|!%pW|KdSD|>$B0bJKw{BIKNLP1F=xL-H)}=5HL>)W7kw#Q3hnqyLO;fYI$Kk;9z&Ro3~R zoC&^DdJBmCmp^(U$_^q$6_N#D{N_=kK|ZEc0$z`ELr1}l2`#)-idHL->*(=bIBX<)CLJM7zcQrwBdBcG(S##M6!LI)t<`Z$i zX+6s8x*!+r(KtUZLKa{Wh;<6lvH9W=s=8w(-uLi%UK9RQ_DOQvK zTc@Gp2?XU8X);}bSK4IByoSteUp<%dISc4HBH}+1SPE6EN8#mDlm4G=Zl5vS0Jr7K zat0c_HUF9;o$jwS(%AWrH7e8;>&`!1g*l2`JK(`IKZ5Bp1@LBaqzGJ~+V4M(-nA1y z;raHq>F36Y?SQ7^kQ}WD0WcYy(Fw@pUVB)} zvEm|bbKAr;`uRxcy5}|9mfLU6Ej}|sgtrGgSyCB@j&T+|_37`xyn%x%{P=w5OZtNcs;0R|mQTO}83B}9z5^PeCYTjWu%g5;fZ{cXR8#JV zRXCVSYTqMl5}$W&L2I_ZBEvdxDlNli0j?5fkeh2Ed%6nS)l|?8#ND}3R{&f&iYtRo zM&OFM>l+3tPugSefjnw|C4z_PnvO<0{lj=*DvV z$OSk&8Q8|&b%IgqyDp$X7cfJ)i9pAlvz=bQRXCT(sTPC;Ah$pM_~4Jt7aH6hrsg(+ zj2fcmH%z+XH>bCU`wiIm1NwLGV+n8_90Zjf8n_*^|D_7awg21RcMNx_JCPq^Mw^go z(00`z3|$V&oOUX~WU@PVJ!RZ)<7!q^hzalpQ%7nx(Stu)TwfG88=n2~{dB!YjLVU@ zDR%_*ba{h=(J(lx`pkt;d-xyLyQJ(%%tVmI4RsP2L26%2taIzv-jGpEzuV-rjYfP4 zrE>nf;4^RmRk$3L#+7M0lGw`r^Nt`rZ>#MGo0Ftc&{7iA(RPA632Br9&~Sz85cox6 zvk^E}zCC@hy07#D10U_g)r(7yxx>nyjkyj!NZ3#ZVLApZm6^>h)OyV>3t+^ z`+D1;FqtnF1p|I>NN6JT3?tX>h6bwm1nV_yxje#Xz{par%_x1@>2C5}94m%3&n=Q> zZSt}~-(F9Xbe<9(GoU%axG!+Ko3RO;+oKa{(R$xFgi)9A=paRc&?s>{B5CebWww}I ztF?EQ+#_x|pCWt8bCASvfp>+uIVq^}bjL@K+U=#@_`W(9Y`l)8j;+q)}vbFcFKgMCdI5Cy} zQ^@JKhxyD3IQ`@FItE{+$egm>Aa9|#D}+ZZqArt}-|F*+(+_G2lj}0M4m7?)cW)-X zU`OP*ND1|~HxN+#&_?NwjZL5K ztr#7C-ShB6OB|c9r)!iKV<$b|9@F6Wsx6DOuzFSP9f^qjUWq76VA2V+Xup3sKvpUx z9;4Z|8+met12s3zAxQmbC;LKgfZL$uDd1Cnv|T#RTjb5oxaY)UOAQYJ0{S!K1p)K7 zSCVa7i~!j&{DJKBCm%zru)dC=Yj&mu+_~)V%K_B9-S>mu#R{R@z4^?Yu1F)`^S=VT zMlE~TE&HMGmS3ju%FZgFrkfMK#Y&j;*om2a{a zS+s{YhXm_#`at#m(i(2_K((R0rRtU7ANf0Z&lx69TeM`XnZhvY4jWKF-&kInS|R_xy((5M8X9S zM?l$>(zAz_ByNXIpeDILv`X;!BOZ(b-oL)f9+Nk9fW1@41KkFXENOu>Gx0X&O8QF+bviTPt+ z@)7ltpA@GUgVbx>Q~*GWflPRTeMD$}W%yJV^uj6v|7Z&M;=kAt<81GN^LPr-YwFUh z?e?c`6cn7|TB<50FLglEIC@(fSC-_BJ@J%N)jP-W1wxTcwOp=l%W~ zGHIdYr!ZM;p7RtVyDYD^F>K$+6Uf@N4`YPM&9jGb!gN0#aYkYFFZ8m)Wis}^{FUBE z3F9V<0CY8>eIP5>xq(R#(X8rRc|jP$(Rcu|t_4#RBow<`&VurF88Y!5P|#UqkgvQy zWbMq|5NMO40fj?+P}06lcF*+1mn{H+xElB?Os*mI6v>dukAACB#$80hrDf8sG^;fJ z#gey}X!I@GMv*O)E{NwbLexe`k0v4F4alxPj?k$SK*;p-0ie?~o#oEQPLz$_JtG3| z{E+p~fJCs#GeLmo4&RvOs71&}1g9gE{te2yj(ei_Vp0={(5P?f;SRf0_o^1N5n$L? z{5#DLX(%9qMnqpTo9RTR3h7J=)7 z_%jK%*4on(>f!I9$xHs5fQk5y?dxz3ir@vTZr6dG`H`WKq7Jr7Tg47K+oUG!R_Fw= zxLkj86W$Ix2~8M%z;%m|wPt8q<7Nx#QoE4lwC2Tb1)sS-5hT$GE%)S_m}i`ehy*#U z15aB6B57Exx1EcFEwB1}8?_aYAn+yEc?=oVx^%G<2`zvS%JES6 zLmq=tf(c-l5EjzUA)4L*#MTLYDV(7*;{Ko|*M0+N5GV-c9=%ZHuEPb3xPKKOf+-eW zd~$Rym&8c8^~UEC@)}&E$;33;;oIi=7tt5gDCh#GDHpg$SFbqx|Y|#Nhm1W+L)}5$QoYQ>dexbUA23p7*7Zs$)?8PB2XhT6#ZjPEZkZxCWFl zypyWG1ZZLhWWdvstbjWBgpG!L%iYGUZ2hcDh&+G5gnZ7a02l3|G-@j)#2=0B)XH*L zfdHL3<~ZgA@`KQRM1Fvc;)N5=_aY!^G^VO0aLT4IIjo!e^ zF{+-V6&9;kNfozkwy54g+n)#Gx9ECm_LB`yyn$tSySjICnN0DMprscYShgAjZwabB z#fncgpF_JrsY@;N>FH9<;$%94nxg7wT%V-pQ?=jctPeNe-rsXHRzh0v7iS%3DEm1%DK!p`(gBeS4+1+ff0D1y*KrPY1`dCU?~f$;<|+-$cbTkmT+)sdtf9@ zuI2S}5wO*?es47%4)h!}Q8MRjskwfBgE$z5c`?aCWE3o0v%mk1tP`b&d~FjDOKE+fPl{b*GZ&DO?mR2?Ae3HwbL5B9eNI(8p3x3L{_)a8fKwk z(2BnY4NyJjCwlk%E^CHvD?@@@*MaLJaI)!+>7Kg))2;sZ1%a3S2~yc(k@|i%>vonQ zfU?Zx&$cD<9Ci^zD8n&``&+w}l{m7*ElOnn9xp>fm%~^r0#ez%1HZTO)(^3%*w6|3 zcC?V{NgV9+`7NC=Ae#c4Dg$K6C4BTh4s%KmzTa|8W`sw~`$%dD0aZ-hg9vaCs>kAr z<^AT$c6_c4jHIxYiCnB5yJLTBOMIqs|CF;^CYeqqSz(9%%91Lac!PM2?*AcEtEF%&k7K@K#-q$71q1}%Q*Y_hPcVEP{Ylh|W7P0` z-W-2WDer~IcCDT?uoN5&_x9_1#@xn!Wtv9dYx=J35n& za4w^1wThtVEsm$vB7PF0*2#Tx$J;V!7hT#Du$T3A8xm$)m@bkWvD!VC;py0cPlB64 zT+(_(63dEBZE`&z%M54otgKz9$Tz}i5rdvg_%#eN39+YJdZ{z!t>;<)m?+JK$RpZ4 z8Sp!-K#%*c!9+3q+eA&NhC&U8(g~|1LJ=nCNx$Zd{UX9$=ePgsbA*K!BZZPb1ip;G zv>vB}f7zbF^6MG`^$h?@+{d?f z2D02|R3(_{Bssh2@YW@MlZNTK-R0v;gBj9*9Rwg~xLS}C+|v-EAr(X>Y+`SdSy z!IQ}v7cOEHHAs+q5uQ-_ot}ToN(B9`MDhDrl=!nFN})+B4(dQm zB_5acWu2j&w^c_?oijNZ^jq&oe1qUk=+cvUJNZ2aK|yXsM{&aZnQ|BCFaeT<5QeU! z{X2e9v#)ig;8iUKDw@y}i|#yKq%L1X+8=QxvXQVgBRkrGz{r{;ZiDvT27dZ1(&rT3 z3X^m8x|IMCIFKWEaS>Pn{EtMuUg9qv=nYN-gxCy$k8r{l@_1a=l7TkH*-!IGFm6p; zbhRTEK9hm|`vVq(C*b%HYdkGKq)S@{8UHR&!JWZZw*aab;xn7NR+^WB$dWetkbrlF z%FGl|a|t0y$!D$J0q@~0_x-iPnL*%(41D39bAX0OfT`}mAX9Bd-w3c&1jN^;c}mBi zdCcd*H@dXKT!XPLnmKaOr8pp9m7DQ5;~<;wsY`g4BWK(SZ_NM!{DLCLl&r)AHD(3A z@G%->e%Y*xWL+W1FqUZC$vPa?T0RKxh3u)(P8EUl6Zl6KI)o$xnLfiy>L#szO)JkGHR#~tz>BMdbM-b6eTP~XP~q$3&HA6~k-*qt>@J#}uhd^{U%VXrvK{_;itkNTaty z)7M9w_vM8;Q%Rr|r|V`*>jAHjL=rADH)3+0Jn*=o#Us zrLCO;c?t~>dHBI{%jR(d-u>99xcKydHc1JjK3FUkQ=4)qe6(VQ-X{K8p-~iCB4p^& zu@~GpX>h&JL@_-Qwrg!h(g>k5i(m!rfNydEVcutL>E!C&pX-Nbhi_Fa#0b^7#Oc0wI)>Img-^XPh?zpX-LN2dxUd>Fya|ly3`yOE?YD5~BN?Knsp@y@9K2tb zsbbmgjgT2SV>oHwm?9&^FW8*&UgB_=EY#?9XykoI;7gY!Tz%LdViUgQf&>^0KlsJ8 z2v6_ZCz(N-fluLN&~_rsfE_UvvEC0m9~X#GXLkC@i7Ia$mx z3(GswGg&)Po(fqFcV0GtieAEblAELaJ*2jdyy^_wz^2PvFea>Xx2<{o!dj$5?iu_)u{VnEnxJS z@d{BZbZg44=(s9x#osVLHqg+}7x3nkw~m2S30iFG3b5c4L$a+6saX5Tth>E3CsYzJ zN-{Prw@7eb7i1Ju%#OL;())Sw8641=TL*c|B?ve!zaPWFOj&mvT+Lo?_QCFx1NE+& zx3Ic;6?lr@J4>(*j2MoMPuKa!DleNU687IZe14HOWz{&B<1-)Z&AMG~8b0%6J+^`Q zi~f#S-Pl`z$9%i-5**}CWA(qpIxE1VE;-S-?(D-&JZW#Ddm4UQ6O!r=mcL@!fVy?v z4%u9;IWP>o-FJSK!aT?Q0pt)!Ixi}5IBvv_na?Mu`SzJXP%qsi%x)-8fS^Im3xx9I zr7wq7sqhs_Fm!6QUEBS(;&~XrIo|x;rO_rBhyidIL2Wly`}}(k1Q`l*8k_v{rd8`Y z<|DMjU;(CcEShrE59_v04d$W#S=vj1@vBPhbTjxOepRzZxsZvr(<61gUv0SNlh1ZI zu?>p7-PR}qLOaL>Q%_0pkoQ|R1~`?^_sjP_&_`-FsyI0un{vL9KHt#r4&nE`)DGh9 zR^sJ34|`Ku5AFy*w4y{guQ3j6aOY_a68vv7?ljY8_B{s|1s-NyFg2h&b5&usV-PB^ zr~u+dSy)ecZP#srYBvrF=Oi*VHWZ;GZYh&|MX=y$#|m*gY3Zkj3L?qy@YNY+(UC_?K{{fiHL2xSp!puQXLq?}Y3)LqlY zNluuG@Y8VvV`7kb>OlTvfWDd?olZ|N4i6c7l^69k_5GwZM__HyDz9H%v{HiUDs|5m zKRn{QhB$BVc!XAfgrOez0mwb`mVgDZ2U>>Qu6 zI2^2=yKK1faKKVZSJ-HXqBWfM2d4cFaP3x#58M^MMzIGQEZ5J#(;7#^ zy?4~Eloy5^6*6v=$S_@G8F;5z*PfNrbf&y??UKiA+O503Em7n+iggtKom!nbSVxab zJohByxGjIq%glc&K=aY^;^v_uSnJBh6p_RPV)iNhUt-IgL3dkh^_V(hqqN3|^ z|23-9NTQ*6-dMIKM$Vb`r#Vy_xlhaErmumY`ACOq@^%l){*V{@GTWY~phbk}tkRs? zXM#%cts-BI`J{tp2~l3UBo$JzSM!#Z%iALu4Qcy$m2FpA)oB&cfeUY+xc((}5YHM- zOW!o?S~GYd;BQ#yRS@`OCDZA|Xvm>$3 z%3UQgC&V>{!8I;8H}P?QP8f=fv6@bg>Q)epL%%C8*dFiP4XK+pP6c*aDcjtG!jQMj z#))k+MYf3&V|+Rt6MDg?u5N1K?X(zbxh+iP+LACw{HM+4=ZiG@Nbd>S++mkP6;t>1=DH~&4d zh8Pj_05ReV{UQW0VuH&5{6)|sR&Za-N7;z0WWlk_?a`vq|Ni_Taq}XWNmn_I@nqZt z!SZ_PYga~sZ7kB7gw7F_W0eU-0aLwnb93{Anj4vBh}_6dEkwfo%ZQJ_9*o z%7*S4_xxkI8qzi+&re%(JOG=>#KrU&@pP=k+DUt}Dm_cOw>|T{zNCp}L{6bPy}kIOgE1MUy#;3#!)>?o|q!11tH`S5)(sQ8sk^5h%&Y$fEXjG2wc=Gvc-s)wLryG48!-ppgdT| z{12>=76%mHh%o*2r@br)uVS~+T!mcMMqY6t8HAX@90|ZWNVXCRjg>_DEVt;CkFcLo za38!sZPbqztA+@$RwFdCOWX!n+rHpw%UfIx?rOfw+3biv@DPi;>qF5I zwx*+xq<#d!5b6ae+-vd_K9huE4RN&2PnCrCXXz;38r~dp#7{X_<1?tG zOxhcbM_`8SGBE}5IL+OL;>%;B1L2)P^@2pD>Whv=2W|YK^x}~vh47nOD|iJ zSfIdhxqP1b^agtL70u)$g*%iub3uFZ3m;2_m_O7 ziwoHX_}kz-T;TH}iT^-g|2x>D=eaL}B2}CHEsuWwi4yN6s^sa~-w_t<_f1!T53$I)>AfUh zlk=a=1d7ARKdFDB;1FA{(*OzyB=k?{pD0Cs{t4qGIPov)On<;1qP?lvc`u)Vj@RC1^?eYmNQB;x#3&cN}M&V_xE|oxEA@IqKNpTfi8SLVyO>`Etzr7U- zA$N@$fzEs#*hF@p| zhTDT=6X}uM&o;8dcMi7ab$Xac~*g4a5#*XMB7fiY%v`vq-@y z=My^n#Cg!Quc1NhK*`-7km_reKjW4M&>lify%qR==hj>wPoV9x{_Dh_%Gl8?jow!T zo9n+j3b&yF?BF70SB-KjDkn(favwwij|3;Jg*nU*=J1Mn=cx<|;Hps#2R{`VUxy#N zV7BP(17}YbyQ>=fxLc$oR7*8JoN=SVaXUMa5_J5H;M%tCMXgy3nuZ))WPWmPKZT~j z-bZ1c_B1o22D{BiP8&s+!7kgfLp7(J2#zyZ>wy2A@rz19>P^C6nxvA{He5qunawD{`Wr_)s9jbIzoI+UrhDIN0tSR`$wB8j3AzJwqd z)5MOo$hoLnipQv?0cVPF5q+g#brwj0nqax@NXq%b#-EU$1e6mdQPkK_eW(ff45g4% zOksBIx4?2*31s%`_U}6jNf>6`cNCaPWKOlEE9WZ;>~PYoEobbF%#b(Tzi_0jtr$(C z?D5P$MM$Me2(MRLI79BBqeMoy>c-0tOe_N0AT6lcvOaw%f)@vy^>Nl>e$a*G1?d9T zO8C5HsR%O9CEMzg4uTs$^5X>U7hKvhu0{ETEesYhC-VpfuP{Kb862faeZMVA_Q`uD z5@$*@r*0&Ue4I)1`7#D%eU;S!^(suwcP+5BjQ0coKGcBmA_93~p-J&|pm5Q3(voxq z2ea98)3|9?3x%LAHj*-tnKHJ!64E5bXuWq$#VzQ#`*>`3Ovn@pdxJrZ_CdRBr86d`gIL163h$ESQ~sz^R|i2rO2rG90S;pV42= zU4)W?l1*A`KaVi_F=%pz3rHOPf`P{8U>FMfJ`>&+=Bo3~&-odHD61kWDyW*RT~W<~ zs20P_QaH8!S|VZny3AhQidypRUydTetBusDU?U9oX88z1Fdqa~KX8OXkcY!&lKlv1 z8!Z`AG6aO7w9$V%|MLCK1(k!sKh=i7EK(4jfgob35iaRnv?X^skt?qP2+Ya zW(te*{(WbIV#)FeHwYrc%SB&@3^sxw-Wd%x-9v`^w=Bg1gKrr^ehiH6%YE`0oALPo z#-5yYQdlM^r*aKcpug%foweWEB-HK9X}{J2Y~Lm{Cj$LgNt#n#;mTqJs#f@BD-Z5x;E^oNgixL>Fs41*0Hdag{D z;YTU9RcuQrt=l4+oDA9hx19y)cxc$+*A8>FBJMaHg0};D5=p$Y?;}IE0lUWZi)jp& z1rDOa2r={4-XO{?TtpG|m9A_6Oc>M;lkWib1m9R&%p!i;2EIt3_3NR994PumAB{{p zR-mwWOrDXJy;CTXF-zx=E;=(eP}kEq!z;1-L{3^*Ypl;L_$eVC;>Eu@iLj*pQC zgKRM;gV;R|XADgF8Vluf7qiWBpg;;7g`nRF20mOusl9qbyGUO2u1m6J7e%=`LZek$ z9UfM*%X_YOg)e#@pgd2LXi^Ot9Dl*&VH7N$ZF2%MaVQWG)eLLlK%dRk{VRQ~l^7hx zB0uM}jB3SQRU6SQCql>K`nyI?zvTcc9qM8|Kd9p)yDDm;GTV@1Hr{hC0p`D?^?{G6 zAu7v-8?yDR!5P;Zv%$^V9{C=v?$kasKuL@cU=BaV!qSp8jLHJd$kTk2KKlk9_bBtx zb|G4R7&5ojAj|Zrk2nv!QtS{IhZ<-?lBD*!hO!#xmUo@bVdk@tA*ZWGDsrH(t!iRh zJ$A0?+CI7N?ChkF+_H#&a`q1UbmyjWza77W-H9gnZsu(_mt5!delg75)!~LB;+DM+ z4oEi>YB>L~rvt!YCjABpACsv+3vC!%I|5AMRk0+8{JN*fo?@3*2LKJmQ_^y@q5QJi zFL+<_`iQ{gH3J^5xQL2qA_b@>#s2ePFtnS%YU~KyPYBA1B#(2b+n+ zGP|YaC~!KUwgoybU|`g`)uf%XvFxHb=LGHPQ=OkC#pA`@PWeHa%=!=M-Ly2sA=1r{ zWeDyl>yKlQQ9{;@sm{6zejKWXaAy0(|81OA5 z`{Fe5)!0ChSSNA=#TkJ1`_nmg_u<8^_l)1I2-C>c695>P-+k~!8&`NI4tqNoKltt zUiMjV97W($yEkdB>9k-xQk9zPFIA#Ai`J9~A@RN=L)t}sTk)kfGidBvi zcnZP$TzVB(rO*K+RDuJQa!!UWIvOii9bs{8hu8Aci9o$?MV7@VhJ+Z$e)THjj z@;k-i_qvpNeFmb#?J$7$~ z(8d4SuvE1c+`ImN-a*k|&7E(uw(r$GVs*0A! zB{B+I?&Uzm=uBVK&KjDSxC)tFZb0!X=AeY~c)Dm`;{&#!GZK^QC7Z~FYb$j*4l!lS zu^-v}ULRr6!mJdLVHUr~>{7yzX{>p^_*v75j?{VZi4Lln>z`526ISnGJP>sYptDTi z1^^mDgmHFXyR#n3{Vd-YNuz4HnoI9M)h0_}Ex#jbfiQ)|d%ygm0A~IYfh_HX{%U23XxcaR^Oi-{N=Io=g;`7z) zRQdb{xz5Lv$q9QzgEX9Yu83x`Al`Qk&}@M&)O9V!>BB)PE-e&b$iy9+sy4!W+q{FN z-Y>||i3rr|8Z(w)B(L5vb&ytEC0>SC=cGZWQ)))3n`ZFUSmc36gREabK?MP1`ku-V z8m>ebVmx?l45}k-6J*QhBhMTyrN{f;2ye%}T%?9dCFM*T4I(Vz7| z+~BbOSJ(fp|!NgrQWQVY7wDEU>t3!Ah zD5+`SVA#tggD~}^+`FC9(aIRcml}QTyz*JCg;~WA^brLDv~S3SlN*D_bBa*bjP}>z zHy7kIa(P7#yg4q-zW9`8b9y)YtC~EijM*2g(RvZ{+$0m|9$}+wCizO_CXnPpsp4JI zUinMN(ksK+nQ;!3S(%iP2-2Gaeg|KPP6jbpPY~b>!vk2U#fe>WuLa?X&)WMRXKD8X zRokDiQ$=~aEmX`eRM^e&y=nPD&bcr7c|Kxf1-&9%^71h>U4RsifCHK_Xp^s)p^2la zktLo_iM0;nHsq24PZ0aV66KUpy^&(p`I0N|_TsbuO1u0k4(9)%S)jXXW*Z>g9KogW zhKw(Wc9H*%r4j!%OM~)&bJ;U600h9fjK}LBSz32ltBMo|KJX{`B&n7EO4L971W7y= ztCRx+VV8iZ8ppbYR$N(OZO?)^SXE)q(-G+p$bYMqoRC#lJv5>+20 zO!gPx?lR$BftX+kqFQwGx2&Vw#c;`nz^$=7HBCr*9`~z zfyz_)ae!&rS5PoqIJ9j0xuD+0_;nm7eelyQ_qYX}{Tc#SE71^qBI}y+pMB1{7G^6A znShmHddtGJ(bfpcXmN@)vl0cML7R9-ieHQuZCjhjhaaRT5rd(oZ-w@r9y%}bXfp2>(XV2_^Fg{l~ zavAS~l?vm%JwlKrSD>HU7Wo$~>SU}B2CJj0l~bvk1?KC6&P>{mZ@eqL+Cyq(eBun) z1qK-Hdt@9-n{+aV-^=Be7K=xWYjeAVJ4Q~(c2*S~yM1L_vOMJKTu6LM8xF7{nIN2jb5HK+Cky${s>G9Cuk_+o=rTJO@5Zl=%RuhJtm zxROG8)PCZG8y$*g-{9jY@FZm@%;YTXM^CX@=X}H|s~GY8dh)U(@J#8`bR$^Wk_I>E zRYp~{x_amNYc_#N3t55{a0rS7hz}|aSYv{s*x7~p#WJ~&%eWcF60&^2KU$;_#lwpi;x z+}x)}9{_xqJOOx4z(Zgrh1UNX(9t>{_xS!y;Csnwd~gYSBM9Q4;_V$+p?_XBY770y zNJ8e!%EK77F7eI~NBB25)dA8n_7EH~)uCb?Bp9moJi-eQPLXXA5UU~w+y}GVrPLZ$ zCcH^w`JARlFx3R$(-A7`IyNNtC&AO+VS4KIfR6F(3##>DsZqJp0~7iwPWv;7enCX9 zgH<581PKVsusrZhAI$-!vIXG>zetGaN10p$B7-VwZ{5RmYy__HC-r+OtL&2Us157uIg)gsZk^q?!`uV}gRRuYPD!z9c~bxOa+lEqNs4 z_vJ1`0~ay7H3ofz#^U*56XYH2RtDkT_uFSrHj?7~-2*}_BSPN~Tl1uiL%y1dD9f#B zdw!erD*6EHzmUR&(TXT75FQK!ruu6*F1XNa zEjEn>JN_}*+wT)*I+nQf2(7#NnM`tM>qhPlk=s=<%`2V&!PO=onZg(EAQyx~=%9o< zpZa?yAAu9>$(wr*<5qKE;6B08>an|SkymolKxJ-yzO}bM?!$YHv}NIka3~b+@XyKw+pixpq6-^9{ERt9?9LxZJY!luVzZVd4Zr2_m220BW#GI)&dv|Etsl$w z`8-qqn`kn{xkeGXZ;xbFxI9j8zI->>uwsOsykKKKBH~=Wq4IGI9gr!&SPBW=-4@n? zNLr&r%_?4dMGwC=PR!ITR5@zeYLAYPZN;YZwy$o6E#Y)^MnS#shSdAo%DdwC@Agm2Bb5ZyzklUM0?4 z96a`OW518o?23;fF_qLWL5q> zWi{-k1Bew!Ui+vLeiib>`B!x~(OQn>i%n(`A(%91GzPk}(vH!<=aOiWg@(7jz05vM zCQf8Pgk6ykt$Q6Q2tj1|&3@NCboCK{@D|5$u86$ci&oK`n5PfU1VQcxG179FdYG~@ zIsmed&4=TAlrD+u+HsJT5!~<1Fyp|4GClBKMRq!f4FGA=2$Z0Me2$ ze+_|7@10gl0<;>{d2w0LqI?;+MYJi^kJ>NYW6eP*AJ&4DaFy@Z^3xqP?PV3eTqp}j z7DkS^0PCj$Kl2%dvLUoC^1188?XVpIX1mgb;Ah}onBmX=Dh;KF6*M;UV^2gLuP0Mz zshC@w#Jp*{E8$d-aY}o4wG<;2Lah@io@z6eVTim-* zJ!tX3`;snJtU)T_*KMt%X5`WETam%BalcZPeFPCB>Mc_tslYOJSi*PCvuD%vTJr>v zx!~cN68iiSQS~G(*ZIw*vRZ{0H@Nm)%kw4HLmn6ddNwU6s7zaE)Ka2Usos7nuZ^tG zD#+#fAObAqYDnJct09_yF6I2rkZ9ju`jx0OFKxN+8Hx1m=!D294Cb{|^m1%(ffTP+ zEZe5NtC#$&X1G@NCNtO|#96K0c4!PMiH#pfJe6j;Tgya!@X!J0(Eg*{JQ7O|F%y%o z<*J&a%QP?OMzSjeNCR@Z!+{EnUi>UQUFFg$H}nwGFTkNjw0RpNHxg{EY>dpnP^roC z_54^}dRo&mh=N5PaP^{KhF^nTUdI;a)8@2Iez$9=TMj_}ei+ZeK3cnt_2M&~ z%eWwVGS|!3sM9ob{1^^aIPyVGF*}kagn05t^NPBWAYE$nUB^LGrDKSy7<=We0zh^p z0L-7~u>8-&5bEx+@z2=1G;236qUj~#_sqh^X6W-};wulqTds-VL@X2=t2p)8$^Uh|`g1^L%3C z*Dn7p`I7tKX*WZpU_?<3Z zm_@3(o5b%nQGt7@n*}`4VSN(a)xJyL=r1xG*onSc(zhr}LjBp1NT+KCZK=pYzk5Dk zV__hTo4OgbFSjYwyP?U1U7T6v$(vnOXt<2q#*|cYYvNeI^=EM$kS$6;+~d+u{01`t>HPh z+-Y2Q_BxVv%iRmPW4e`z&wN^yt6q%f%c7%Px$p~`8rH37hrggw9{oY1#=LV$kyIrq zd%mZLq{%Q=({$EH(UGcUkhRGzo-lzc00rkZHC7Gd89_=53G?8z%Guf;S`y#gsThr= ze`8C96Tculip7cOo1$MfnF2USD8g-FQ+n{>Rm&dWVOd--&)m_gxl}7YcB-vJf+f=? z8?Je*@O=Fb>gO6sUQIbJQ0QRi2^l9K5ikKcA&56T!kmp-rOA6&NaEW^BjTTR3?NTP z9cTZ`J%hB+KT@3KmsyYt+{|n8AnwPlsaRHM_yldH?!(vMwhnD!=@Zth13%mw{=b9c z=i@t@PT(RO#mm6tR(yUV?V?v7^`-pQ2H=SsZ>&Q6jUpdXwYTj%q}xRB^dIi)u9H1S zB`b|GXdOo5scq1wA`&&`tw+q>HUk^||An#n7uAf!0S@ZlR?RSv*A&xp8PD+@?k>+V z8oczY!1;WyG{ZMcuwKUIHRcy!Y>XFrCvI%KF$QxZUOd0R6;~WvOXA41nNk0N17NHD zDhl0;i*V(qj=48%`K3rUI1{?&)0DN;-h~xIeZmoxLW^dx(egO1=S&xL;#J_8nVvif z7wh-o_*Px#GRx!oBmEA_>4%U0O|Z0?v9^P^I;1FbMoiwoh z`ej=n;`YD?GFcpno1S~AlIV|Ep3nBrpKyEc9tn+zz_LgJkpqBFT1oaVEkXyA?nhJC zm7gPDAhzmL%f>h`b`Adpe&w+N@q_#IQX_Ww?F|I|>FOGRaAEa3ovi_ZL+p_lLDf~> zr@3tds1F1h9hKMyQ?2U?f0w?QtrCmtI8Rln!_tbIUkpY4d~k`Nap|>BUg=>|+IBrp z9&zipmpwFL_p1~j1gdpV0BzKG5d8l1v|T86%S*!2Y2>bNya;i6Uu z3ymh2H{7VR#u)suFQ#5IyRhEQK$ZQZ=Vxpo1Q0vOnEIKk7G06Xwm;qAczVNM&9Tw} zrZI()SG0&Sk+HGDaJMP3PmoMAT$PYGc*l&1e%?x2-Th9>5TGF;e_Qe0X`S>)Gmb=Q z-b_zYazRsMsUf!0!x_;s99YwWAOjcU=q=9FMGG02o%U9nX-X=xV+yWtkW2uahESa+ z1;lDe4is0Q7d%gdGNAcdo_2BcFE{D77pQK$yjJ1BD{0|5tg}AUQ!Nqzl%S?!`UUDa zYLeZ^hAfWqD8JdZL^~?En+)z_RF1gbNCL9vbX{eTMAujf0p5cPJLg*{MY}+hrK}L? zfa-qFORjmP0U~`315zglVA5&(fY}NXEycZ7sF4F`n!>UA`Yzu&fPsUU`514ZC#GX(#5{iyR!9`O3 zbfu30f8;l8ggd?kBo*`64kg-LS>?AU-_wa@y7124puWjUYRYQ4polfo*UXmIYZ&%>!v&L`GluEu`RkmQ zYKH`xBF>GThNM;LH(g1|EC<-mZvrv2kb42=I;#|zn2EudVTYc$v0=b}dswpUu zJ{_HWen&)WWgW3^(4Cl`#NC&uR6)2LJ+e4E!yTd?HuQXqKu4o_FIwhJI%p5$ynY32 zk3Jc|uwDHGFP$mrsZ%a^&HQr@Y(P!0S@qD13b0oMixL0X(W@V2K2) zmJ8!*07OyJ=mx1cVbm#9=zh(CIt8YnKktWua$)v53&%k{el9Xwz%^qgoJ=+wDSJJ) z+66AskKdJ;%Abafutae{JffoYH-jG#Ld{@0Ic}8;YY((p5ri*eloO0LD6IAli!;xL zX^TOsL0Fq^$%xIMgJx9R)oque7dONXD;s72u5TE) z%M%*E^(j6ftG;b&6$54;qjOX}+|%Uv(O|uC1(k@<33g?84B6KZc*Zcl0!(Hc%cUg( zV;**2n7>HH19>N&+KOo=^-63a#daW_d#K7U_*VWHNwM$e%$-yinwB9#vkTgWHo`UX zY5THzH=mRk6InxB$-&vxbnR>Kd%D~E%T}KN2O_nh!sT!b7U4}X0*-3(37s>zSIi|? z(m}kg+Avoj@B;^0kB2Do&ga5UhYv|og}PK4KDbB@HE4Rj0|lfg2JJN$Qz9u#;sMJd z>}yAb!-LbFf0tRl(r|Qe_mM-7t>`d!c7%GapBi5t=}RDsh)+BK6T;Ur;kdyyKvY$Gt2<+%5o0i>e_C<>?Ko*QH z+tZsk;IR`9tk;t*X$#aSIAY|VdPh*!*arjytPHu1t%Q6;wFE}TAoQ#f1QzI&fX-~~ z$H_S0@e7jPL;8Gy#}uCOo%axyS0LfoECv*pr}W{)B_(F}sZ6-2rS6wW_|9w)fQy1N z0fpdgd$rlKJ)>ZGdqk_^?hg#Y$ALAZ7WnK!6YfpqT+o z>Nd1Uq7|oXICBnsQbwh>PtRwfTBke*Z!mxNNku+D@AG43YMhYOTXhBaZ)!^Um4P#( z`2g(6F#9FK1zqat?@l9@lv!+&l~kG{c3(i6@s!>3n1hM^4#oo<)_^iOKO4IL;$_V}WoPOqZzoZ; z5f4-yAi0)zAl0uATcd`fbrmK`nJa;hFpI5;oTs@a;r@e-%~<8AppZ zuUU9$=e;kyFUkUv#hPFSLTc@pe&Fq8Szb|m*(OC9eLX02d>34$ihx!VVD-n%=Hc9P ze7n>)kOFx>v*BN{rW7s~EJoVtefQZrBVi0BX~KtcJ)AN&n=NFairzqt83Qxyxd5ON>8H2}a&K4+IWt~aV4$vR<&-0=Pb z0!}mSQ*2?dJcF-m7&J>w$hb68?Kfp4T)J}y&Eb#&_xyaZ+4UK91NM@ze^4FB$z5&z zw`e6Vmeq2*`&e;#jagN-xohmjP33C3K;*ZL3zMk{1h7)j@U9~97c;<0Fbr&hz%2+D?~ zaDM<;xiJTA(F_`%O9)n{1fDWA_HV{Gkw)GAl!@0uMVb*r$}FOFstZ-g*;l1pl@0P9 z^vX&u6wovcGSI|~jWuRG^`@s)WVBlaiH7A2VoZy*x2s@HfcKHX%7o_X29OODq}Qp^ z(4vNoD7$pil7pPKy;69|)aT(ys!m+!Q7jrhoDw{S&rRKOEQvWi;BT@O;2o`c2jW@2 zqlw4hN47+>)x*QqwacmHCM`J7%qI}?izWlaMYEJ6Qi;@OjsSTYzgHPhwHLblyR&!9 zGn1e8xhD>RrvE@*63j@Zq^N3_pd#Q-TclIuEq66B%I7-vJFvSQfBcoW+lRuuD{l4= zWs@BaY@8r!x=Fq7$O|p-(?anIP??J32!+w#6cG|6TmvE@p!tHEX!Gn!o>q#|w+t_*_`mx^sN2W;Z5B44O#SH zkwTvU%P5KymG(FO5xPS+DBLg&FMCk)com&9prRv2nF|=^vbMyzrMxs zOzA6>YH#@~Eb z-`BNM7fZ-cJlZmqBl1%7pBNk+XH8VH*YPfF@%1|E*QOW6P5$AgxQc?6Pt7rO6BBx9uf4L7%b+v;Hv(RhhiU;Bo_$iUOG0}Q^u0#PS&c0m> zRP09IlsWOTGXgbCEQ*Km=A0N&IkS=Pv3$s-)0FP-jzvFeFl{&rjI%WRP z{{Y46TP>u~{z%e(U11^yS7ak~x&b~8x=QOZoDspT82QCE7uKJzBvP0)Az$UOCd2Ke z60H(^VjIRboUTad;iW#DA@ujVJHIazB^>N{T7*5*(zI&<5P-Y~N&F%?)8P5x#v@CB z|KOt^oFZZwzux3hyF4j|Ds|_dhzxN#XDHCDmLS6-#4j)lT;UU%f-t$f>K*O?l)(Mj z7+AgPNAH9Jt!&|NuhFRKezWd3(7kC~>%p)KQ2Y;%C?Pt)FclhSZke0hJrLSl_6NnA z9D&I8z=4J?4q%kk1@8i*gfTwAY=a9Zu(Y6&u@&%!Dx}97X}%2_$>xw#Am>|z+B~L_ z*udIvmlI}E33?uB32>#)wq<)cWbI6buT`WCH$dJ=0oW?$cRs}i8V90T2*~UhkQu{4 z#sS2ampuYG9dFa%GDIg2vH`1>js;u;xr(rYrF3c|2gtV+Ni=xLs2vft89~Iht+4bb zPBZtb>3sT~w*)1X=!jJD;qT^W7VJ_qGu@l8boUs6Y?mLyx705<3Ip31n=^W z(f^?k?_YqSQGiSSZB*ErnkaBJ#BnfK`&E-b9smNFzfj>12=O*Vw5YW-a%!Q;j*+ow;POU!oSALDdnlZQR&Vv0GG^B z6IGrH)K+K`e*)8kIr~*KkO37JYYl*5_bQZ5qhNkH9q4L)GvmXkh;S%2+~HY=7aD-H z8lMNbax)oNTCoLeh-IgF==%4Q|A|cw79fTdCPMA{y$=_9Xi>=LhuqK@$AE_v)(?)M zsE|sU-kFi7&)Q9XWKnn>4_ivj~<4=V0hvRf}E@Qoo6-lindneo8N($!#-D>g#;VMkm8DRZ>fNhNf3 z02_oIH-QGv|0bk0g#9}~{69Ls%m}Ml)E`M=zu2$~ASAe5EsLf;2(&`*H}q=V7$_U8y&8kq_ZIe#I%t2Wo+!}Z4azQW zl$j}Wt~G1!Bj{(xMq$U_YM)1WzqUrM*mh)d4aPVfOxEAllEAvzFMCJb2sDF3McNDn ziSGg}yvp#nL8`P6s>cjYokQqNtQmWg#X|NtCpu|Hnm+4@6jBuy-02=bkRIF|VfK(BH#_&k=u9O2u_GU zAhi`u1joeX)Ka_8Xwpdc4j{tUG05+89BDIqA}oU+A}Gc&N|nSb=UWL1z=#b){h`!!HVpDxs1!O{r0%0Mfy$qC0ht${wUl;W z748A+s~!Rdl{qppg4I&V5j)iDg}xT>;nl9%8;6m_6k#i%GznKv$K zDL$qGNPQIT6Fix4<{QKW@oXUm{uep~*W3UfaxXqaqikJG4lb9F1P+$D390?Y#7!A2 z+;hpkzZ5nDa3ZZq;JnbSHgV#OiIf>e^!eARgj6 zT!3gnjG=`OV_pWMl*vlQNW*bx4M(y*AhHqyFtlH*ord7wk88{Se-Z%011RU;#)|hh z_kwe@cMYs)#ytM_A3WeG{>KdBO!i2;mZ_(i;ioqwX72~N(M6n1=M^RydNKb(iv|+q z{S0+9&f?D=-mZZi;ffhq8I!fCu@1y2C>EVI+0w$zOO{Z&A+VON$Qxk9DIXxuV5LlX zIS^UV=c_?|w}Z6#W`@?%dmj)MZqGZ}RPZF|9U))#XK0Cjdwwh}VqVI^ss}FaNQYDt zkbOnYqGUYi^`v_7%|jMeOnLI1-Up$Tvl&|R>YBm8p3iNbMww_&gj6I|L_R*eyrB*9e%JF3nNe81t zLQ2;DSNoP3y9upPzR@WPvW7op(_}fNhg=d<}|8F=%GFiMPh+O(^NklH&uTq4` zl$T+rD}X~ZV!$B++$i!GwF3^ZWg6W6TJj5R*Hn+bCvd9*FM)qx>!z1S-8LOQFB9_N61#OsK_1NbpT1$p+twZOm3^3X=I2fv9Bg~1L8&)4X0Me;&8 zutqjLUjLC_4pR-x4SpjC_{<9a={3kO)4B$*xa9E3^+7*z9bI=3%QAExINAbQ^m{1a z5q+ZVoLGqrF7P`z9;}{#-y`gFg$EP(KyeUC zi8loRJ7!Bhb{V%Esi!A=xlB{M!1W^WRZ80MSu*mrK>E4Lsl7r=d!yMmmEv>)#1$3?ls&I61~Cq5WXRY>u0KgB4>vEGw~< zqNk|K^1=ZW45>c743=^`A*%-4hgF%{oH=8kw6s@$$){3;t zR#DotX+@5Y!bZgNBmfa%QLkM16rSIDybLOluI(3nCCNVuS!Wd6PHA0~)_X zuyMjL(2Yn1m_zVAs8}iu&UI3{OG1QP7)+=@iQ?!SSBkSQNhD?~NJxYeIRxrV#tI35 zHuMMF20)NpAit0bm`cE@#mjsdWB{%G=-6Nd3M9sZ;(R0A;J$!Dlo7d7PH-p@tB6NN zz=aW9Ejr=xuzZA;JEX|s{)0P=bA>|UxM5&HBM~^16HLnX1MHhKK@&pZ`ttB1AZl}x zD&$TqlmrwsBb@mRlopt<6e4;Y#|=$Xz(E(ZFrG||5&@;4OJFQP?W)m!8(qzc)v)C_ zU$`4mqejuWa5Xs37fu8H2@qs|Hxvo9Q=kyg@iYXegeT+C{-BKo4CC$>=nDi@?%Ewi zE#ZsV+TFmJ=jtbyg;N970=imA$AVCbk8_ftk@9#Vf*TKI2J;m{InH0>3I-C%QTdDM z+yIt>?2ZuNq+%y3#Dzr(kASLKIHnvP1k=J=u681F;eg}w3#8)&IJ&clj}M?p!$7Gr z)hRZ@7vbs-b#?QlFe2O`;dmDn*z%cpCx0GF3Qhq9hHe1}8It55>@UDm)leEt%woAa zG2vjpM2LiR1=w|+2{1QEoRq+Y`zoPwH)p0$8XwPgA|ZeQk$z5Gs1ux^WCWqy*kU?G zgmQt%IqF~yUCN7%=S%rQ7vQ!S;ToJvAfAZzgQ0{0ZnO{?PDu~IILQfO5=Nv9R0VO} z;?)QxK}N&CoT#+Pv5`_-oq-QVYFKEf8{F^zE-oa<#0-`knB{*T8=|0msV_Me%7aAk zBzQ4scteH%S8NDnGbfvHrYZ`^9pD5bl86jCbP_I4+^#KtD(2 zk+{JuE}t4EqmvnuFlPcD;0r(*v1BB+wpP;*(0FL9uRNJSkA)!WM#J zU5ONpqPoZ@OAo<4!6Sq`p@beRhfo4E5EU#01oF)_l zkphV%*Y1yEjK3Td_+fpCPI8WR8)e4}p>xb7RMYSA|D0SvWZk?H?Kx z<|05Su@sU(h~^Q312wT!q6i<4QPD*H6dH@KRs!9uh5;i61XJ+-5CRn&Msorr4aojr zcyNvsOXYIZSO_{ofDFKpad9vh1>-~|If>D%&^TW@j-k@v2ylTyLYFA~gCL;#1K~_l zlOt5F3}++>>k11Zg>zUuxW6BY7cYaNwZKO%B3~9>!3YN8ns6S39PSzy zK}1Q_E;K3{lqkCd1VhL?1Xu1NC&9zy5_hpej1w!cyjZ9(93~fvQO+m^ok3!|#N&a6 zNgCwpFPG8$8N6^eDbx>$N)T#dkUJ6VN+6aFk-BlzP$ik-PlhPa;UpXagTw{%ID%ND zXp-QPGDG-EC?57^IYRt z8ea&7#AQ*C7!A&k2Ze6|Qaqv=|C^2kq-{ z#C%&IKz9fJkL{A}1IfAq=E|{vUxz=ZK?Ih-SBT@fAm#o9N-Phr4fRDVmdG8ar56MJ)f5%zl_x?o`8YL!;tN{v za5+4Mm;rMKg)k&F#1-bobqfrpkiwjB5+#`!8wV17;(%aG0A9v(r6Pi;?yfv`gc=a^ z!Q5aeED#TY@g-0=J3JPPW`xCKA>m?*lt>9fqd+?wIt4-wLx;r)$vD>l$YcdlgpwOf zbRvS=29ym_8GWnXMzMTlI}$E)5zUnV4>rKFz7fbs1A#B3W;U#5V0U3#RHena6n-e2k9z;N}cIs zt*zvsr320>0MCbmew%JwWIUe~EQ0b-ZrbVKOpXgSA9%P6&mggmJ>Kp&S|=R5|lt?y5Lp zT(~e)s--=V6koZ}9Ro@s-0?CI3@D}$d{-O{@1&Nq__0tVoC|7K#7w0VXssC+hvX_n zOmrv~1E*`LPJ}2F^f!Y--IN?2ffOtYU@)lx2pV7GtC7$-0pUE*h6}=_id10;(4^Cu zq11rP3`qgH;V^tjaXgAYR2l3hL1Jhy3X7?6HWviSKAZLMb4Tqp1kPww`EFB>v zi$NPWq6ms~QHC<&BAkh#N~tJVqIH;Px+~O|#=!>#!j-&04VCMQ4HgE52SD7yKy(}L zuGK{Q5h*MLD7|wRKHPxcK7P_SKssMvT4 zj7$j&a;K2o#7I0T%vnP4Q-N|%J{}KeN&KM{3DRAv41{z2=r9DrPeB4zuM`Fj$q))q zNQl26T!WdEhlerT72ulS8h#L#E)g(?f;FC`ZG(=Qj06*d6PpK=;87ATR(TOm%QyhgUa|Y@{6`2`F z!8!}j!4w45pQPk5*;LSFK}iOkL)qXd{M=+AAuOs8G%*Nw2?d?8G}`Fa$v;l$40a$S zBM=RvI6;9rRt*XZxpD!-KPXm6W6R;H2rwaOKw(0|h2r^gg@6jx&J90}EKWe>aH&cs zXHW})Rf2BX!5}ikO0mHzKdv$sN(5m&lB~t>;J28>hJ$KbHNy!Cbyd6i<3LLzq7yru z02;tCx>aDmm8-g6_r2*0DkecKQve<8bu_yY9lt6;9!Uv z1_N~oF8EkbdPqZSiI6?$mjGr3Rwqj)=aHVr7IDiA? z<5iLXHkd&XxcGQyH(0n+D2wf;V6rLDF#m|jKAR*i3e=YPgxe zGi3lQ(Vg<^u0lWqQ#K_G1P3k2DYSU$yF zpd`Yb!y)0I92gE@DCoukKEw;y{~NuG_IV~7xPwZ@eBG7SQ>HANfZ#_3 zHSJisDmz??X(DC?&$63yD|K8EO=P_xWt*5Qz{n7(F-aq?M zK;&>RNxJAH-95|Zwl{uGQhxlNY3W-gM81BscBXaz*CBmR^+wZkawY5ng%U9Nojy9f z_+>T6n#^w1?k`^>&wDQ^wz2Jec~Sj1RCva0XkWDDaEV3 zVuxhsgnybN+2=|X7bO2aN56~Cd^@+LU=)tdf!sj-y=f!x-oXuSr6hwaX>o+H{{AWY z`;$86=KEY52@lDCzcH!7>+k6YweRWPkYNm7ra6Iy$)R0ju5-6#no`%G00d)LtV$t^mp z#^bbm|2}(Cl2L(IhqI;VNSj@B<+3x+sHx>0rOh91D8qlgVl(ST7ae%AWX~r5Gqmb~ z)sNFx8&g&4SR% zBlq?{u>I$c=Y*-j{F1btZ{z77TV`?JDy-L6s!|cDEmj+RB3~Di42;jNzE_}c`2F{T zz>O24dAc*XCo9I<8b_aw9cN`07WV2}T|XgvaN_t-;AlB>XztIi-c!#$i}GvLe4^dY zkN54^NlDAOAnNEV6#ZK2={JbAfzleCJg<(HQ}Y@I{W?W^r!9-n&my6PtgrfbdFy5Pl$fCtb2lw|u@z~dJLcFYX; z`Sk^%AkKK0iQReFIH9%ShiShlMqFqzhf9^}paP64DK^9FMCSitA&1(b8T z(*}9x?mww@KpxV`wms{3X3w|eE;sQ>NdwzGvEP=7K4?Izw<<1gE81cs-;p1B(J}i_ z&AWFM{f+U9l2H@CcSmH7wmkf#>{nDjwD<0O_U&B%>T;L&$#)I^PG9iT&$j>Wg1i~8 z&xpn@XuhKr_4%L6C12`l!y$~M(HrQOU~xhC=;<>pTu~(_o*esgaK zVv@$2IPm!eq)#KQHwLz6yVNX~W&bFm4)?uTA9Xcu7Tn;?{SUQG_kzAu3=+3JzvbOv z5c=rx-5z2Ycj`8B9hkBGW5+YY*LnMxux@X+b=dShWYbp0nCZ$jve&$q)9W1$-Z}g6 zHYr~<{qI)4Z0cV9ZFYpCSNg)5;$$gIbB|4H&>5OJIeSoPe;y3ai+*0*vqAX&x@om{ zu+i({(3P3?BSy*g`yI_1D+^ru*eu`MNeSINaXpk_0~*sPtJRj~N5l4oMedZ{ z4fw+LGstXn>2Tc}0`Oh|0|y&cM5R_q{0Mek7V^yifyHbf0GE^93ydRJyTJ`I2G zZp;^8fhX4-&h;Q8M$%jBi{4_}N^=_ute;hkcRYEg+n1KYyuAcREX`V4Rmkao9KkP& zMSD-o(e3>9ssr5rVS3(D@TZfnhoyYDWK?jWbJ1MLKVg5aFM7RV%*3wmsxW4QrXrm=U;ETtfTl=Gb?+-${{$zaj^L_V-TBk z>0GASEuC!l7byN^Oh$w0vxO;RbN=|g7&{Q^QIn}<8wCY}=Ii381=PUq<*jz^zt(s5 zkV~s=LFL(r&3lu7j=%86LlQ_a*@!hoJIZ=6$uf4RYWAdioT9%i%_jxZ_AK@@hJ0hl z9Cde%>atdzaNvx;u$;x1T^Z_xRL+*c=%gxM5TMgOUsm!Gas zMsSHYTmya}v!U?=^gX$k7CNrKRdt1Ri=qycw%&gen!k<19em8mZ7x zY)C&Uxol|o;^1Fj`o+3gmfU!;Ys!v&dB&ExdutypNACIh#o82G^yJM_gRIk4JNMd5 z&W{T-rXDoR3UH68I6U93cD99C@T4o>KnEd%@tl1Na3_6uzUeG&!~kA*#efkyvG08br8SxWK6q2 z8lO?QX+-znzNh|Y=+1*h+iWubomkV2Qe-`nJ05+*nDk{4usPkg5|kq^dW=;A!)r(# zz1<%zSbhKQhIcmT5dYkiw|&TcRla|@GI47WTcI(&8poWy?%B(^A2IT8(I&OFf7i{_ zG|Rc|z|Hr?=H~4BH!NIIuU7VUKb4!!b!9tQ*EK%Ly-|JZ?_=yw3Y=k=oN*-JMBYd5 zRK&S~J03L67sNHDyJgt9Hcv0LYSElnb7ao_h?V&Cd(}mMgGBVQP#s?#8;<9-g!yTu zqDQZGa=w3QH>Q^_Oy;itn3DN?y8g@g9TmB=8IMMe{}cMp?zZ2Mxv(P3sdJX~=lQ68 zHcQzdis1tho%+$NrLNX@OsKPH*9+`QpI@KhS!6TS%?5;7uaa3;E?M0%_w5Nka@zXK zj3X@Tce9NyteKi-T##UTzzXxw{*48+;ypp9O!Vk%=&XR)aMng_J>+$9ithW2q(}N$ zk^3w?PMalnp>}NT!@QbxKG5(>!po>#$Feh%+Cc!d%6nUPQl9R!9!Kjutk{x|yQu8Js^nKX23b z8;N7_!^6YN6rHa}$#hBee7mj5W>FS;H5;0X_vyY*0Rbm&n*7xn+~aHq(+peuAK$d9 z(N)9M;*XWSm$)x15vS=7c76SL)5BoC-Q3PWW$*jDcehR_R)A*usYdNLe}IGiX1#2- zG{~AZ7Z;_gS95>sy))@a)%vO&pKGrce5^g_cv1D8zQ-JH#Cvt-L8bb~emkP2iEMe| z0SL|S=eJkW4Hv9RN+C5>h+bS|p!O_wHLwlNx%1*AidY&2pSjotJ$~4G^R0{=a2x03 zm6er}i9d<2OCn7VnZY8GMlkI0NU1x5C&GIRtl=L@= zZ-X_uko)1f>k&8czMXTHo>+fVb9Lj0)7rSNNsX5UMY8r8UCv=otqih?9-DeVcK zR=i#JeY$ptJZ83dPyF6`F61nIpsm_2v|#S_xNlqPyeFa*tBdO>#o@=>*d5PuRYTp2 z$~blV+G`IMnH-<`&osM+>ix_Ac~cy*b%~c|!^EHQ{-Ggcwmq3}3O&yTYZ;Zc#H;Gb zVP|Q3jmhxnXbS*v=)+DnW$dTB7CEyEOzh?rCH(4Lc`l*9dFsHIr@QNm!mLpH%nNfl z&vJZye3JOPQ?h?!_Ag7mSGQ-0w?Wp6`+G~$bXcpzZ;(2@h$J1>-515=q61XgVrTY~ z=_5#5;+uTme{67;ZZgkJzZXhdACfIAHjQh9A1foq6M*H?;UF#8(?}jq1pinFrEkl~ zeS1CzxXZ8<3y+G?pl3(D5?}@kRt@L*q^4ANhX46JQm@YSP*R*$6on2w+H2Mj$pZ0(r zeyn;Zr+7swx?!pDil95^Z~xh~-O#jf^O~4jmDIgPpVR#-#xiUIclhs|{ki}1J-%6g z?}r;Hi(T#aE%n}45_zSnuCC83IYYn-SgHB>wQ!HAx9pux*XSxq#Khrb?|II(}w%)?!Lo%)aOAjHMZ? z-QZ#Sy563*3eIs4zr;;9T2Z|><0P;hb_bX?zkG9QcV$L>Dj-@7Mm*fJ2nvQ~jxP33 zbj9?Z_Ggqs#mrRq54RE{OV-tcL(rG1MxU5u?$c>E=zLg@Np{-jDzKcYv;zCc)_ET; zGIlo7GnoUcBFZY?T8-5O=dL|X(F}DroTOx1J7P{@DB0b5{GP_k!`~k*tv?W5srn8P zHM(SfjlR7p(MAwiA@t4jRKLEQVYkLI?0Ot;aDMat<^HcH7C<$lKhHHTnSVU9#|N|U z;DGhP!jQAUcIzvL6GUFh-l&3O*Z7C*2&IHs36klQ9j+dl6k@96D^?rr(momoj6M>gD4|VIUdq&Xt^R$qL_TJpFw*7vD0QP%J zA3y#+h!B^HOD9BQvlqhtNt}ke`{TygJZE>*gWtPV1>Qtm`=m-(r!a1mg5fXiL^5pAR=CW}tqp@yocM z+;^W^Av0@?TeNSQcj)t|{3Dkwwo%D}jMw{T`?kq8N1Gj7^XX2{?no;e!rh%GVqdMZ zqYN9qE+Vhna`IFiYrb9L)v{2de%;BD8JM4Et9$lE;!Mn`(mqjfQ<{EX!{+%r_vQJH zQIgM#_nQ>Fhi`nni?I74`StB;dm@P4(mf+umL)gd?3>Z3Fw;+8eOm_(RYc+M|Jb+n z{|Go2$yj>)7x<&nws#S~)y(Z0n+F$LJDzX;>eAgPUwCDWkO<<(4bhsk2Q>TQ6P6 zej2m&-9`HH*!SV@%30H1p2nr7zB)jAy=}YdPm9g1iHaFI(=HL45@n+CFXPY4Fl6$t zZS$gu*XYFPs$`whhLiV|t)o{$uLu6^DDh7K@KRO()e+}m+o|Melv?hE`6YkrsUsQY~eJKrxH=(Aju_GiR&JJ!v&zHe76 zh!(N=rJt^D&55bMU%L0zegLAsz89=I5wLsL@$pE9WTWNOwH&(>sI)Vs*`o6Q6$hhq z`G6F_?ppljTs~#z^`S*Oa~hma24{ZMqA(l6pIjYD&*ZeO`#~;z+vW6Qy7@ zQEEfbg7p7H!H55%;I(0ANM@IFIg!cKTbk)wCc~o3){2+0t>8m}Dd`M)SE|*GLcwjj zDARiT>^u4ER%ahltH1r|pQ=~W;9*?{BEcEKcY5?{-a7W@qG%SCscS9U79FcK$nsoi zcb;{j9r5j&j!8~ovCq>(&&^8K&b;^Xn*W8wj;X&ByOyl4+?e|I{3pBQ#cTPqgLAKK z8+o-k^k7WoMvM9`#iQdNeq{T!*Bv$Kp-wC1W*59Os&~jn02<@m?T)cCYcxvH9s`!) z%H$(ZiQ0IJwXeI zaQQ4;-Bx)F{`#t;y6=xp(Zg;!C=yQ*IuLrj-gif%b^VNNBb~0jfDjepAYL(40+UX*sNx1Mmv5W+~Og9@#Yx`jTsgxsbRXGXi5_&wRDTnZzJ z5mK-XV?O2||AN(!)NezPs)2}plfQuVKIy@&(6_fVgNxUv8a6i`-a8DSOMZ{{ zO{)X)7;)9AW4iATPSM+?(|+qk52CJZrDudRV<`r9FGOVtId%$@e4_nmQAvqK*NT(B zeAJ70%?7Wv6vg-#QIHm|ehfh5zgcazcjyC>_Q-KMgv~{5Y&~d;&S&b`{|APxcT0R` zzbfJ)`Lctj4jF7>mwRlh`(;_h?+mgX7WkL%$bS8)E~au9c<3S%y9jc5J01?*mcDko zj>*c6m4|dak4)a;3*$T4eaRWt16xtSC%0}ExlXHCUFiu=1U$~I)jwR1yq@^um3%#} zeMilljBKmhj`BjXrJCi__`2Hal8%iID}nQ>{#DoaUW+ZdSXn+3z}WhKVJwmU7J%5n zpX*h+*n!-<-@j%WBjbpU(&+1Sv(edkTXN0LSV~W%_4{Xjw2#=-cr|Zn@%nFz^5@%m zeJc|hNyGq;8Du4(RMrV+I~L?w?>@i&cA(9+>85sL?56WR)wgRyWVxDsM9hbQ>s#-R zQ_q!LNGbJccsuyzX%nENDqgJ}TDVtnbZFU`u$h;5L@T>T_MSS5-)-uRF-4hFOyp(N zHcg|XyY0b34;~aOpVLffTk}wgnJrAuJ_A}?3-HPwK+pn@X3Seq5`a%GvopE^nkMDH z=esv7GJ<4j&Bx;2i70V0$f`%K+Sqg2XM37y-HNG3!%L?c%-7rXWBE+*48La20gsX9 zn1IsJ0Ix{Q|GCGp_8=~~?DyOq4FC!L?>{2tzfYLa;9(?Lr2VQI)?Lo_T`LKcg{M=l zq&pDiaUMBf?z{p}#Ey`+ZhF=F2;=wLL{yTCjX|*5o6IwnUuY_kJzhL>%)TSrgR$vv5oM;-Ka)*Jhj8jY%^fFL=~7YsK8BwPsSI(Ph3zTHaSUAMz@) znyR$cn(rDTsvJMhI)8l=fz8uB|AnO`BAT@cf%$fIsqsUvmxICeNBre_=TA!mp}r0Y@xY>SOA9tPd@pr=kdEBtQSS9HpJk zMoGo@7wZB9>iV!csH81&^r_2Y;qE26eq$#8fVqZEQ!x%NShlRJt^016nR{SO`LotO zgyxN^{7TYzAD09yoMXHM>r>H{ab~=R*4MZG!=o#i9;e#WwvQ|Ri)X0o@=WM{p}WT7 z@Yb|)m$uz5HU`hSXEmE{L*b{_bywCX2fA7={K#24d!D*Y|83gLoyy;*(EC>%MGYOx z9g5OPi#>KH^O16;)|9!rc^~BlS!Yo`ZKIoGQC7^y5vDJ0R$7J4J-=e=?s@xj3IZQ} zA%eSFusaGC<_t#jDM7>ZefBU7RYg1dAup-;iSu-T$YYm&?cVTMH)mX@ZNU;NJ8PY1 z59fSKPx1if9-k-}Fs!n;cQjFkxYOY1^K1^v+Utj$)B4Ey+l9Bi!CL#vel6roR4r@n zHeIG?FQZ-hZ|t7#@R%9qVdlL;06Xfha|9%mi1{x1)(hx3ooAb-QX_zSY}^)gO}1P; z(6)3YDg2n8_sG+uZYc{^Q@2gK{(l1DzgluyQ71dYXX+o?HM#2)CNUX%Y{0$b*Xwoy zXd7Osf+F{srvkK1|5&L;XW6B1F?-3;H(r4_wl49)hPyf`c9%s>3oJb1?-vkHN?Pvg zn|o>Ix7TFf%lF;-`q;>i4u|TMl;T5cAJx_x{_6XL`fyz#9qNv#OdMO#({u%O6efZQ z-$8!%G?|_wovs3Sk9Y#1e~DjjaC>~njD9~Q`AtdWN%fB}s^R|So%KaK0k?1xAj5*_ z8x{6p`!1|=hS5Ksf7&oCWtl~|>32MQ3PGp68p8E;Rb(jf9LLBRTYw{G3Ks`_q8Iun#y98pdOz!0#y z_d7w}72CPQQyS)-f#ox`>rE&txStKwp? z(Q^>4?9w@{+;efGv9V;x@VUJXxrnm*a+M4F$)Py|d#gr^eYZ}-9zn#mseTVbTORH$ zLI}r42j5ky%SV6hm}O=u|MKK(#&FR;z(l6RlgJ0(TOVCibWw&!MsC^?WF^IR0clI3v%j}I zFbqAvJ{ohZXTN}Df~8!aHrsqgx;JN?^V<74dzYSUdN7KohN;`HVCU-Vns8u zHXO*#KOK0m@ck)kOom;0M%3vG{|DgyZc5GnCAcSlZWsQ(T9{aTQ1|EL2KjAK%&Mj~ z?M`qh!>7UO(|>||x5Z!wTC2d8`~>q1Rbr1>pMlOSwr?AoC>|fm2G(L)bQz2~F;;9}e5ZDl-5T$Y7UUsg$v)q42!Nh9%&!68yE_>OP z*)}C-K-RQl){xHz=Mn&6@T*Y+AUnZZ&PoB}_?g%GAK703yet{}`YvpEIAu6-c7Zk$ZdGVlzVC&x>1U7>`Py*pcx}@O@;`i+ugMP;xBb6c#&F4} zRN-FQ}@v;1}pY_-9q0!Ve7fN zagOixODkVoPP{33`%7`|;n&w^X4@YaTk%BjFBM>(XWBb$n{29fnUYssG&eNTF4GTs zHCy~S=*)oGfPO5bJn~zcv-eoP3+$@T_73XFXSk!M&4+}ClkqQ4K?<>FyQGwSfPHs+ zjiu3t+I}rvFS&jKXsWV(>P3wxOyo^!`{l1Y?m21Q{Z8L1kWi^dy_9{-kic1 z59;O%J!+0MTY}lAd!EtQosB-a0**CxELhiA@k4p3Ypv10N#o^_^f{$}iYd9IjT8fr zR733(9=^bMJN2>sz3(9%^_=n*gAc;=bYdnXgQKfmgd2arO6eHX*8#oE#z{PathXzUkLafvHBVB8mT+{7RJNAV>3%YxW~ zPnApe{gy7M&a^>xW>ri252_EX71+SUpVG*?kp*3wyd>rp*V7(u4}817=f|EyuIJLI ziTXVYT{bQ#jkH@P|& z;#*@+;d0H-g(U8o`HfU$Qn2}$=Yu4g^My@6mb}0Di}3vrtkiVDnx<2#+p6zIsYVY_ zcaka!B2Ld=5gfVWV&=hSkR>dLx#2k)FD~pXXt*%_mP6RWa?|2_pRV+MP8;7%^WI@e z|Cex?(_w5)YW9Mp^uwnQ7>db;$9kmu$pKcmCf0WzpJ!Nx_`%cH(kN4d!9p5|k zCbb~jhSsQj9;z5G?{IuxB)7W6r_L%_JNsVoh+wVRm$2-lJu@U2Z*h-?$prb4WX)oLND0qHe3rw%5Y$ecS52-2ZxL zf8YEh!CNuyd-q+e)2_`;Mq9@!{ObF57daWW)$ZuEFtg)j{4m})f6hhkH7Vsg!*ol0 z8Vu8Z+6w;gu}8F=4zs9u!yj`%F|)Vn*$3V#TnN8vL3JrS(MUWMB{!c?=sU53irT(a zo$d->t4ztbyLi@hD^A4|Y(Aot{VdY>l4WMo`3j>)eKn>OOZzfjWU^7Omcr|O`f8p7 zJ1A@P<5I7+u7nH+9YudX&jvp7gB6hT?&1dT9gG#Ls|po2`fJbdf`MO|nh6m%rr8m# zy&vMEcS*q%_Z7K=Hjy0`9hQfY zV*0n=swugjFKmZhjiZb9`-rH}CGc_%X>%PVe=Tx$Y+B3q+eyk@=cTG&I>YSX^XrZ} z$@M73ACg6a6~`l*?%H3$Fzv`SX{UcQ=ov&<+A(lCCnC8l=3>I{zRl=EXJ+i{jz~Iqe*MXf_3>BLvCe=%D{M3( z&CYuKx%!o9z5Dqn_o%%Il4Jv5!7x~|oV~|y?M@KC?c#R#uXS72T4U4!yjnF(AwGl_3`ibZ~8M^4|@y3y0LoG zM)76MvZ94`eZ8nBht~50JD+`+&iCMJ^ZjNu6*dc^ss<86Ovg1Y0lnty(1*{(5f;5n z>hYM9ufB2jYX2kt?_WO`={$TAQWUKv)qn_QUY$qqAqRqGw7&8EkdCzp+rsh@=C2Yn zNFvu2W0%?zdajt-sh80=+zGlIK!t3Mzx;GX6SHdVRiD(P8nM^Iy~e|q;c#Z{dF9)O zz^&Poigq6fR;;Xh>z%*3j%^n++LiyK%e8CwM)kTd(d=98D{V3B8*-}0B|!D`ICIe+=t4#x2?Bp)>l}GL#Fh2djAoSDSkb3(%pi8hY2;Ctxxgh!ClWl4hb4s6N zIy+-$wqWx^K$F%lI4W$f9?HZ`^D{1RvN5pyPnO90FH2B37t{EFkK2R-D;xJIRA=Ga#!8{E?uBsHOskJL zK@S`(OzO-I-1NM+-ylnP*Pv+jpUYcoGS)q=IVilTXKFXE9>Lq)QfK8L8L7c#bB5l2 z8(eOX)pjj$h`0E1i9Kq~Z7P-$kk53*QeG_nJ@?Sk1(aiUgy3zqx0mH4-4F3RFr{PX zquDoKSyb?9pFiJr$1YY@3@5-`G8KSC;5Z#wPDy`Qlf1v=u9mKI90gec zf5e&iK_`AahT?_rdpHdg(!RPlIHw@$V!^0e!t(vr9Z@m$4|i>!Y8P=S2^)XF`rCz! z#|KN^?^yrOiq?+7kgSE2!Vmfp8=Z9ZLx&s%8}8v5^$Gj6oGFevC)9zNYV`2YmHI|4 zV+{P@*_yt>@RL@%7Sx=T<&Vxed`5PL;<)78zz&2CXvYc&uIHMc$5KAUKk)^D*9BpF z{LC4Ll2;e4DDZS{n3fIOE!l2O7-HCA+NP)F%r;t)9+B>s?YE6t{hO9+Cmph1 z8=NN^FDR&cwK)U3_vEDzSpicJj8IErHfP)2mj7CwEq3K#y|e!zpNeX(InaNwzN*GM z?qQkQKifyq<*@|+C*jQclkT;ys7y;=GC;Fo{3A4@&A+u}R+=3STz7HyaVB;)7C!JnGT z+ig=HTf!}kp>zbQGixcsr*8q4US(t#G5+-(!{v>raqFS=(C23YW?d3Q7y<-EY>L{w zsd3K)xG{u}jGd8~gVy&Qi?vE$OLj6JW!6KaxW_~ zI`MqAdU5H%oahS^zgj!DAJ;0VfRb$s5QC*_3I?K~Kpcf1#MhMH3=hq7&mtdY*giYw zY1eQf;d@KAksXFBeiJ`8_}I-op4T?+hx#uD`S$?*te=sxZLdQ_AC8<*pRDQphQfR~ zaIm^&!RI~tH|uMFyw=1sHOlC>QZzHj@*tyaSZ|>>>s-dm?g(f5?@x|8^sn@oSI}Vi z#&T2T)#27Q_2ulf48QaFp5-@hFWD;Wsk!X5sZ1yQ_RtmJa|^ch+{XXeI^#m|^UJa8 zqxG|_4{Zi4=i(dW-KYYYf0wadO=_gx|GZ>EER+ut@^kp%7c!ZbKiAS{y~b|yteN;d z5;&-LEB00FWjd=}>sB0oJz7B+s^ZoEflTk5K<#rNP-f98Je&a1Oh5iekh^#3O-!{x z0QHk>_{U@H<>(a-bIWpn475A!G5Z+N*J*LUF>+hkF5{QWi+n4x5AR=h)(3vStISv% zHy_kn>Jaax#Uvw}AyM8GwlKN;I|I?wKKKvA){)Ybkbw%hK78=&r;~>pKb8;pCOh?g z)iOO__6Ao3DgV0cxTOYxlxE@Y@G{WAOy7N(mYS1hs36*JT}fDCZcU5(&@jB*OPfB` z63QMAUB}w2|9%>*GkD<@fT(lsRrP9SOmdC>ez_lJrv44(AL5xUJAb0@SWNP)y$j!V zXJ&$@4&KtjTW%zQZAwW4T7*dweV_E{Iygp)YfF9L`mgT=%VC>5XByt4BqJ@l?P!PMhm>HRV5;)#)J{-g>3q z`B$#3eSX^=-ebirn}CRBR3V+Qbz=Ix<(6q)pWjrUQ;oI2fO4>r_I?I2h;4`bs zVJ88h<>@fo&@?eG-v_$*(z0bngFpXZtg+eCKkC17w#6D2thyJfYu)j!`d+O{(h6y@ zepc9qnf=8_YFHPVT=Q@t3J4#}1&S7F(=%alkH3UY~Oh0cPM~XQu}H5BmLQ%+>cT2|!Hs2#}Qh zFHlPp2^&Ba$oIBt;}mrDawEcJK3OZy7$5JuJ%QZ2*tH-0)+(g9O%){}K!DRwsdkpN zJ^uW9WM8lWE3bIvs^@R2G;upv10>eBHPi2amg-X^W>sG7mb&Ac5pc zt2Rry^!TEv33f^FcD9yh28=6|R;BBy>h~$}sgBRx_~Lx@jRioC7SQ?nTsol6@ z_Zt7%yt80oJXv&DnBA+Z3Yl&3J!@qM0m$S|VY3Y`^Xo}Q%VUOta4XCKJ-~`73|(1F zy^Kvw6B*(Gh~91(em!m_Ah*v{bjZFuS!7Mf`1SK`%w|1urLe(i<{~GAjkxZp8@~ET z51>^_j4}X1qc`74#(rUrb(Yty3(?7T2wP*b_T`F(k82Z0FJ-tkOv@TdnX(I#I6nB+ z9_2u*+D1EIt25a9!2{eDvO4op{fh;8m+&|OU7=~pAn8$ z>34hLkH-PWn9?;BpQmne576`VomrP!-(6%pJ_J2ES_~9f z{L?{{3sv@FFqgQ`^OLC;Gk&y5tO;c&RumyWCH}G)9qQTbE^XO31^gdt5l=J!7~tUu zr`iLncQ4&Ey!>?qn4IfNic>f2%K!fu$(n43`oi>$wB6RZ?oyrGe?}eJ^w%~NW|B`f z>)4#v*}rkc$ccm5Ch%^(POv2SYK!8EWlvYtI=7RA}#IVyXc!YT@?xQRHzOyEB~;<|8cTmcBJ zS=VIk249}#jwSn~&b+_N#1JeR)acJ|-gE6nrjM=mtWGqFNdIk}ehOHnXf;e-CF*a! z%QwSSOb>AHK9-az0~qw>=|G2-^UlpXT<&e2ZCixNK(%*toE=@`K#@J(d_~w`WX&2t zvnTHjy!w<`wTxf%#o%zM@GmlUa)^%`UmcetP7bZYMC`xq6F+s*D`FhzIj7X7oU+ z=M+YipV6dcRSx(xh87Tx6F?2XRUlL?ZDRxdAD@h>_;G6eyn`2Nj4>H?r#CgkW-%pj z>(uChv;}LT3UrB-L%knw8a51MTFWt(2TQzZHflnd-eEi93Bsb9q8ZHXft1`WV%&~5 z@w}ZWnZ+;lBk>;YVNc;LTBiiJ$}D-AJ4IacKiYfmps2F#ZJ2HvB`6sYMI=WB1<9!q zkR;G#$*3R_B}oQp5ecHCCMc;5Tn^eboW)z!8{ zMWncKiRDMP`FpsBEz2tSErX=+&hN?#EIbq4L=xiQ0+XybwGvbMc~-4VvnQzQH`k9p>`FHZ~i+$5gl$LZjrOejzQG(kn?e-&?-s&(fK1& zflc5kZz3<%heh6u2OiOym*?Lf0=c;9CSh%=K&^eA`sVnR?ah4Cp-G`rLmbQo1Qx*r z10m(|%FcaxuHOSbcAk(myWDi>6bX&^@RRswHy(iBb(mQglxvR~0! ztedR%{dy-b`58E!WVP!)QGL^|(#^CUJSeOgJ{y$Opm3J0=YJaAw}(8VSlXnrAM~hA z=UZ9zdbv3#AH@b73RjR6Y=uJ1{>mA+Wc}1envs(^?ZVlvbhQ&)miNk>1&T6zT0d~N zfEhRVn;HN8#C<6tixn;wlZHdjTboR_8*^kT!a&qPdSL`@GaBLwO7|p{53H`6;^7?8tITZbdU^S%%QAS zrt%%>i4&97krppZ1_SA)<2KawStx*@m@w17n zUqJ8_{~jHwc1m;?C87M;?QJu8$f>TJQKDny#4j*?pf>(>`}R0BH6h8C{=)tvm3Yt$ z5F@bBGFsvfeFD z)p#Cw$p>sTu9tJEu4xc`ZI5=a<)KfZmTi*xX{sW%Vc)G}l1x)@<7@)VC zM&Cya-9=3pA-Dk(chG6E?&8Y;uhKJimtN{}DtIT0;9lJ1L(HgE`6GTKhNw2(p%ilU z1o3`c*>QJ0PHyl1R|#o%gOEEcgig45EDLMz-tmK*Pk+4q((Ug%Ww%)S=|ZKW=L&YP z{KwM^IJCtG;cIrsL=aKoMEs!JDAmQ|W|uGJ?lwi>d4S#EHergr!+H{a#fiiC z$m;`uQ7T`^JWA$mhC{y}0rmgFE>If*M-<|K66dQ1ODB=td=(x;VG$0)yxlKQnTP>1 z#YX-&GgZrTfr1xseV2*uF=rbj3d#$>J;J)sf6yH|F!9_pkqjWic_euG7dSNcd;TB{ z!SywTRHt6iAW_f>I^lg6_oC~CEYD{QYBPe@a@>iWrejZ6YWu;Tf4-H*5+BA76OepD z3P7S7!n8^Yx>yCwh)XP!r4|7D>DZlM44WS@RfPcTF7!uX=D3Hz&B`Fu~ zyWaFXC!!SwKzJt-`WG^PAb-vj3qjontA5PA>76L$&TbZ(@?EI+gyQ3Ru6$G;C3hrt zAuHp3ir+F%9{&8Y#!G5V267d}VEoXCjndFP;VqRo(ULdi_zdZ1N zH|PIvo716%U;8H0P!q`UjED_P zyqGNZrxt)2k>G&%1u;qgn_tz(&wY&FxZQw)s@3I&CD)I}TSq-HiF zp4cn6@4_MEf;&DKH0!@YkUbspX<86kT*h{e1flRl~tTK~u zHs|fKPwOSbobmWB>0wh5saRpT|a7t^FKWjS{X zWC!2ned(*Y3VehycZ=#lpd(|^H2-rb!_)V3e(f2 z&O!)0w+wPQJD4~kheL#IKrc)Hf1%>wHdICdVJ`xzC7r}*#;KXlgCrMVh(lKba^O!y zpJoso%Cf9*PVPlJT-gGkg;)r71%G;gTPGnf^!T+fPAv2NHc~L@1R>j<@>Fn+`^kCj zSb(?lz6F|Rbe@*|bza<~^Q|u+o=;E;2{h3FG1)`d3nDw|HAcH@Z({@^Z?kF$WC6R< zpWATc8oFgaC#nd9lefKd5vQulEy0UVytc4w?*Sqx>-LM=Q=-vmj}OhLe2g$ubIq+# z0L5eUmC3UsLsr7Mzc5cL$Q(e&aUgC1H;aGLM6v{T)GlbED}29NoN#-`3~`KE``F_P zubu*tl*uSqQ*ttbS`bRvoNW`h)%%iyKjrsk@#&>Nt^w0oI$d~Q=eG&Jl$4VrKhp5o6ZX>wwa)3#@a1V*5bdQ4aYc8Ho<)NtUZ z)O94fSjqS+x&W>4GAvY2q>H^y9u~E5$$*ZDH7n+bj?EwHq!xTkYR@5RSV>msJ45%RhGP{y6yN zS@q@5`xd9$!s=xuKJ?!Vu)_CThAyjA*L0BsL5TzsJF(0(23$rsQl8q3ColYhD6qkH zXx=$7yZiDeNLoQLY$Cq0*22Sl#CR7-ms?s7UwIHvcZL%R|0z1an83Q4A9o+RAV8%M z^y9QvFBDe-Pqdd$cTpf@ZCNjc%&IZiyq&P2l`PD%IMtbNFYNneP%rff6I42I>%moE zaLoUdj2MHg?=5B4Y99bifhsu5RYZ5_v16Q%3lN~RLYDU0yxR8KrjPug-@puH%JL2m zw-J!wPMts0zc`vw(UW&bkG zV5t`7?k@-FFMy4I;uJjwN`0FoBZ^ZWc-vFUinZIPY=gg3Eah=GC#1$>FTypQj@=7B zYKKva&~8o{;BEgPed&EH&L+vm|Lam72&UP1jb5hq+>q&9!R*+1@joGe5+`SXM&(ht zqf2*|PaaaR)vo-NJE{Q3;3>QZi;~T$OkH>nHWrr$0%(k=P5pkt9?<~Z%KVw-HkTOe zQbw)XVxFu1_o2l+-qj5N-IwPAv((U8Ah?H({NrYGj0juWBq^v1MDm75{%GVcI$JiS zqt!)VuQcOc*fcafs8uLz-f1exo5n;bJmmU}YG_gEZ^As0{oj2zA{l-3zO>d8f z=$fi_{M0dbdp>B>01sZ~K3L<0IOH~U`cm5Dut`ZR?&^(44W(L%PbBQyu+HPW9#F+h zOugK(4)1BT1+yNLdJ!H?49!}>WoOw-;_HUJ-@*!_Vg%a)&OrQM_bBK%WIty zi%)@AW9`k?Z-pem!msb=SCWo_bovw&9y5R&0qOcK06I^A+l)WqWY}L0<=5wcq)a>E z#K_2hI?6V5RXy2r{f8SUd3P0CRGfsGAYjTP&Gb36;l0nJP~$r77}!VaWdI)P7TAKy7he!T$9 zC24yUwzXY^VQXuBo_JV#dOfc^mO8~@7c9R-?9)iMKTdY01AaluAo{fvAFyi;8K!)V zm&@%ke|&+$8QhNa z9)VT8z!v>;Smn2&wjL}5!TSfGA`2;OY;5ME2~p9S(M5}QU>SC=@)RjR7ErYzaHTIB zyzT`2q4N|{1@C;r1!3udc9XmGyW>IpJME3lpJV-V@vcU2F7|}A{PQ`)p`jHkgq!emv{Z=yxCnYM($zlE{-y8o<$tAAsealqpR`$bPAFg znGIHtmvZ&YU#)H|bt8uIgmWJyOu;ZwATla>QlusBux+s@G`rB6Ivl-URt~`MJ=17= zN#S2y4se)hl{Xf`ApsGc$QzJwkC9LN+L`jGX~>|wsdTfP?9LuDSg8$egw_acQWM3N zEFO#YD%Nv$IlNf(8biFL*;P!lKsMRXWAd?Ja{KnXwjtv}x4{Nd>(`(8X4URkXxr3i zk&rOyv0Bzm5MqJ^+CFF7m-SG=$XBFQc8>Qd_c@*-`O14bsiMw#T3y2xE~$ynA>6%p z@y%W6P;og;);zI@cQ_<*n`HwExsi?+ULZ@W&}Mug58WyNUS3(S&v7k~gfi*&EVrO; z(uZ+sf85fMV{eB~}U}YK^8nlo)AB28ypMSDO3jP9SoIQ={ZohWe1)>W_Qd zky87IGHKSdBeqfC2dVlj5u z6Y`C1!!6GWyKjH@_>lp5smcNN1?e9dd~HiFPd6t~2+UG z!g-K{)L-_-=B7zW;sew6^%PeiMpJTl`y!VQkegE^34FA#>#9ul|NQpo$^ne|*WS-S zDkDbv0;o6EJk)-Cqp0 z6e9$RP93$ZG>%*9Gzw6?zQ+K~TPh##b|QdU4EjdoC`AZNY1#Bb$<)K3pYA5t>pQS> zgyh`U@5xu7Qe$N~yIxE?>ur*1u1QuKlV|T50MBy%j>VVYoLCkq+qDU2Kaoyw(NHS8#4Tosxj1@Y@DX{nCpig+x;S|3VaRY5dGCEx zsV%uyBAH?!*=&!~fNzQ#IsvdWb*5cQOmjR}iPjM$4Z$s6r5n(okjXEroXBKVi?w~GR5<<6CxmYq}ihTxsLt5RJ0-FZ45 zO-Z&JB_(R`4JU}FB!tveQ}*R*VW(f>8w4$w&pafP@jr&keGyBw@iSEnf0Y7nT}O85 z5>MbuInCzdAOV?)4c$JJCb2tBVd%I=F7ZWuD`rg0PSQvYilpU5J zeJ$u6m;RS_{W3~A#n3T5jJA7OSqE?A*ZHy#zbWe1P21a1okof`Shwe`^bgYf7zhS? zniJPPT8C{2Y<_X`MchH;Bn0=(THR9+;@3}XAWUIyuqTQ+1o1rue-v(-H|c0PvI31| zyk5tlb)Gi4*2E~Z4?2Zh-!c42*Jji-xV(Ak;PJRCU-sjQxE{mMupi+w^qY(CS zU(6D`{doPSMy#7XG`D~~VN$+dZ(50;)H%bkRQ2&}XKG^hjRaK~BQC4ykt4GJV3h|_ z?Oem&+`55Hr9vn0i38RqMf-jUmOs!tYJDKhSSh3yJ~d58B?CyAI^E!XJzjr;Ed&9~ zr&=?(R@&F29th)pgpF|7YM0jEU%(h%MDz9Vir|d$cPT}rD#*TmED$ej;;;RwhL;Fp z8z3^qC~0zhc4dyY=^EwKQ4$n!MN>MnnFIEB?9QudVja;NqW7?~?B@>e>n2LD*Ek9L zXyD79NP0IC5(0GZQ%Ol(!}#zw&qEb+7uPAgIQzqB5g$ifJ%;~4l zqC4^_Hjdyua?cXd@1N9X5DfaT2vzaC*&7Kzb+kSP0NQ2{F+K9CRekZ!q@x!v+X$dF ztzC58-P0G}3+~fIyK9GyLCcJ1s_80@GG4vLGtp=VI@{-`vOY51PE7T2UI{Ju5TLur zoJn{Uj?u&_|DHIjbq?X>?};z_;LG-2J8G+KKlkG1L59F41d$XP7hJVbB(|>KIn9K1 zrKC!WB5Udt#9fc%3Geclyk8KHUKz(>x>KQg-8_?ecGFNLKv#oyeC39Q;2BaZ*Sw3k zF4-e4UOVoc;n+BC{qcg-#)GO{tA@j-d!MyfzQ?Z`)+{!+wrXr{yn1vml6>iomp%4< z2HV2i3k7IL<$ULngQ{k8FXcjAEZV{UrNqo04fi|LLbzLzPomslc_})+W7T~_qXeVb`$-IE%p$0pi7L(EyPKa!;~7~5XkX{ia7tJA?_Qro_oHsC8}F3uYUPH>)Vwy;HL8 zBCr|y{KOWk%Z{PUf`?9}s^pU!-(ZHOdI~s;mvlo}2j!TfI1Zg@kbBrQT8E$Q#TOWn zo8|C2SuwWt=8;doqIsFLxJZ3ke5`Wseu)>Jmhh7P;;5t3h4M>qV~^GDkvl}R$kn7K zOyGOYg|_{$Dlo*ij~}(%D%I2COm$Ne930JTUSF z&gL3zyto1_o6mI~Y265B!B*8LtK(@2j~x}RY_Wri>j~8O9t+*@H@+Nhs~Ng9y%*SM zkI6O$2*0|`ne{RU${ci{@fHg-Qc?jlZmg(qQefwq!J)_gF`i@hnJV`~yXZJ#fvD!J ztxp-X!!1#ULWPv;pxNQYri&IT)pD|}tFH&h?a0katW>}__ub~^2euM&W3tAhhFd`Y_r0|OD&0h0Y3tYd z%ik*9hF_Oh%a1f&ISftBTCY(tfuM-I0xcP^Xy0D~b>uuQZy!K``y*j_{VavT2atQ> zfgnQ0e}Q=J^#gN>4EXNjifu_}hV0`))wz*sPaek3OY3CxIUT8DhlR~bzK~ov)@64N z(FezW9HOo)E~pezhQK=V!AO*GAIX3mTBp5$MrH;DhJ5VuzNd>{M?H_SZ>!;E;uhrQ zS}a|?cr*!_=}J1d4O zyTkj`2Vya`WLw=`gwyRE`k;zR#yYgcqr!LXHOy|W;AZ7M@*^@Tk@7T8z?6I#+=@cp z6-ZC0X%nHZU>Iyqq4?WU+frU_%mtwTom*TX)|-3$x^e-D(i%mA@dIProZ3?gP4b7ojAaxxFL6WeBHm1YooP80ZVg!-eOi+J&iW&4jqzC0E z@k%K!2OaqHTk&nIb*&E-^yqsIN9N6a-Gdb-()Mlf^c2nzkMCCuEVnqyRFn8s*7ERI z3hlKq;46ZE3^~qM7}hswa`e;ez5kk3yzl1P_NZx1dN1n7h%$@{mN8iLjLF6(K3sDJq*D#`d$z1O*(IHlq`67LA3IOGWnxC&L)!N9iM4#u)}~3nlQ4Kre4?LeH1CjUI3gAW9;3)4hg&^{ls~Jq zz2SZO&Iv8I6)jrA=2k5Umkpal~VwqSC_;%9+m)_rSaVtH{}Z*o<$!*Ud3=pxZSXzFN6md+^i3vIa&w%Qbj$GWs0% za7EdQvzQ_54Qb&yf&Y{E%!wx#+d(08EAr+aem9WmA*-OJ^%M2qCA84xMd*(NLFA{J zVXEMpcv_wgG0K188ZY0_U%!h-Wkut607g_8@7GR!6ov9+YsQqL`-LBRs(9+~BOn+& z%lbpTD^$h5u;O#r$cY^!`6m=u=5J;pwK3hts%MSw=3AgS`7d;cT!fEoyhLf#H2mc; z3gJZrKprc1P5?;2qk;E&8Rdv1RuLki`v*p!qpJT^&4C|+IHFIK;eUWDl;~hO<4Hjy zB6q9U^P<&%Sg`MV7>|)d)~W={#u52%IR3+i$IduxpsF$??uk?V$7cQsgpg~@^^Zdj zv$xyz`$9~_|BjqA0b(*E7IV`!=o9+V6k+SThQa>S7~ZNq2fD^2X-|1|7Vp35QqyvA zne{lc^|gXnofaYZOpv;|=*`Y*HD*J;t%w0g(Yv3@T6}2d)NK6y)OeaR z-wQK*@@wH4U0t%Yo0*ko1iSak<6djC`K=K(c58X247m46w{w?nDeRA=6qIM~i+n|@ z+y@f*nvE&3D+!B>UJxWc8u4sBPpLU-5oZ8(7^9xE>P2Y zGYB|wm;XHKHmleds(l4{=874bj@R;xh%AQaadK zHbHAixs^VnJixLVr8>6yLrac}|EO2rc^<^jVZ$w)R7iz-{Z&vC4-W-1&o z9CE;<_6eUb_TN~_-rg{gKA44<`}H9_&$cPl{qlwUOkayC?WEd=SGKnn;f%c<%r22R zYEiBUiHwOZRwv8G;2I{$wNLvjT_3r#I~NT*3fnE;Ip|)kV&gwfQI$LZ;hLkgLkBaP zxP8>)H(wj7-UsT~1bvmPI(I*EYyUCC88`~C0fd;T@ zuQU{7`Q6v5qOCYw5%Muwz#bZH>0yh_AHQ&uE&R0#79kJL?ze3d`@Dm7Yq*@e5E5ta zeakxlgS>{XpTHQqd4;i%-o4iGKFXxF2glUI2UBGJJw@uhqm^=>GQ1~iKbItdCchKZ zNmFe+ai>Ly%P$Q8!DUpl$@@OA?0@rBVRY{Cno&aTmJiD;Kw{s>Cl#|?zKWMlcz#qH z^6AwbrS3Je4dJVu%8z`xLSN&)SwPm~jSJM%sv7bc#B`+JBZLy{C_J@f+vog1_;etd;!1gryZKzoVX@wF z5rIOB3PrwNG#uv<&D#A${#@h@NblaZTKkPo(QSxn-LoA!bDIXef>t2@fa9TOdWsgn%bXV@Yyga@5S>b~>VG}3G(1lXVXYet2o3c7^ z_}@ECumv8qaCt{l5=(r))Gu|p2Su8)V|-|Ewyi|{z0T`k&_|2tpsr@hl;G@KyH*Yc zto^O!rLSFPv%Xxf_~TuQ-zlAIrDONVa)IJZF!~>Y+7jz+{ANH zG+M0Web<3pwF4>o(8ss-a1iq z7l~??5#_Ku<~Jy-rg{n0guquFSqnYNV$e?|-bRiPjgFq zIThw2=k5a+uZm)^Lr?DRAkJoKlqs=H;8s{i*6jcarfbn8yS?-{--`u17;-@!8_^4m z)<=v24s!74o4VXW!)ZIh_tzT!#+p&-Sly>WQ|T7!*p|%5rn&6D`DjWS%I8{PKe6hn zsVt<6G9?2ve>Z1O(P&S`54w|YUaMo(pE00V$Xj`RVPEfE4=ei<`?`(?bgL$I$uHWm z!x_Qh4omSI;iN~Sb}$#+-!a$2Ff8S7)2_h#H`5LSanbLfh^6>{&hQ#G3}*k|LH^AX z{(rh$f_u(#Bzah)Tz4s4OqT<0+N-n6*=Zrn>su)c&=rH-$w+ zL|jI7h=-1;U=Hl3dv+2#6u)yM+XapRx4H@)E%N~J^#FG|Iflc(e*!{;$-GpX#M;ZB zwZZ$9)#_l3O{>KvE?jMkHR7`1B7PwmB4;L17i*R^-JLDQYVBiCb}2XNl(O%aGfvR# z(^SL&+!o_CD(=7C@&s2jw46)=rsv@zfp~0AyAOy{_4BDts#phYVH$br3HMsJMq3zE3B{nfS%lN@t6#8H1thzynd z@)s8o9d(dNjZCGjm!2Lc<&Ok+>Sa`%#6&h_j4_$#`Ky$ilmQ3OU;*?Ytazv?g~Aw% zPeg`MbGo0VM`5`1RpC;9_`OE_VPV=AHt2Dv=QpXi!#F3MC@BRGD*Q1$dR%+#VYF~q z^>Gyp{WXQXD3n8ZK4J@a)5*}nx4)}mDd?s7qsXqt=W}rqT^9h&QQoj;ic-bSTE2>t zo!(zyR+<%lFI!T6zW%XQ;B21P!js(tlwZap52qksM}WHH6_Gl?(H%gAi-Ar$37D-; z0LW>TrSLU{HuyCj=@Adrn_E5))_mu|Cn!frBgsQJ~^UM2^@bJ-@b6ge^?^ezFm%3FB zohqrBJ}~5vYCV$P1T1;TDnR)uz%_)mmCv2F+iPahC50k5v8IhOAltM}OKpw`z#l9RQ9;{jq@yLPXK}g_8&Xv%hh)l4O8|peV%MM6+q| z7odvEwpm3dbLCK%TMzlkc=|k{U~NO7ldu`6s2qTO7r*dwf6e;0I%{R=_x|@l3T_O| z4C-x~A@Rbs{i{`Zgt`yDVlv`~E+l*Bl%F}-E|5*g&klWeQ$1o7RP&iLMkpERe2av7 z2hFsxvyO!^Y898@n-=hW9E~5Nezvmn^-J9Pj2Pod&ByccRNO%qBD^Tj9k+P@IJdAb zh}6oMG(#QdJ|42zE+9!w0>-n=t!i|-d2TF{_Rw6Hl8FG3!~X-y@!qE*B#^v3e6bdt zr)-A0{}nnzTo%zBu=caIK;@m&syeWnmVL(6r((8x;#QJlcF0?*0uW%8e4d98qG}}I zQ>MF>5Gqf(mxV;ow~pv>Yv?n7C@4XJV&QwmzJBg%8-o?f3LI3p=I`r>m!UA$mLWwA zULLSUV0{@xd!OK8gP?;gW zUKrWddq}txX1n{z%8kIHmr!r_jVH;g8BaT6_ z?Cw9Z4i<&+4C*!y@r&Ib76mRzvYc8Y7Z=OnE9=8!Z!__QB$7vwQLW;AO9vCPz-7N$ zYbnsfJ5w0}S37racjNB82PP|^x^xAfse9_? z8`BfQgvG@CLRTITZs~Lz-sDhxmkBWg>8f@Wy~*Hg^|DoRR$h;rlA>nG1U&W?rXdvA zhHoEgI6?>9)Vr{Jb*Fl6Wl`P5lBYj$<086h{xvJZbG3o@hR+En(#n51Ry8H%)WiF; zJl%bKcJ38un7`1TFQR`F{t@=e`V}~&r1{46u7*q6EwLP!ZXcR?h^6*95cNOjVUl8` zM-TKR--9n9RSTd1*bDZu_3q@&c2< zRC%?U64=571ek)$q9nci7#Y?P+k4&g;G+lu@zUUULV0G!L6s8fL^AMIH0X}M{EO-T zG2gR%NCyfvJZ!6VbatUOYuQ353e#s2DoUrry!DwJ=d@j9* z4lI%)2B=6Qv#e#^PXHH^MXhV?B@O>GGN29*D^Z&@D*}aP^)Yu6+5E|-@KUIgHZNAl zI|i6ulafE`&zMl~FYfg%I|YOl=GuS7FFQN>Uu+6o-G5Q`UqtZ#&7j2KZ7Y;QOeJV= zBmfo}y7efG3{%EU?@)YUN`~u2ULH3K%hv8X0|y6(yen0q3W+|UGLbVBC^vM;6whBVoU_qkq4C_0S`kK|GtbS< zeeN4Wf#Hmo#J}rve%r<9kAj$wnD7_FP}8^jY5O$%%w7I?o#Io9*W=e!AwE9zSIjG% zzBX9U-{4-Px9u|4*x)n&K9fb@;PHL*QP;3i6&5|dUc5?4eN^z=i~siAp}y9zNU3CC zTRY*sh2U#x9+_26y{AlzE%-_s*9wh|joVaqADRq(4_RjfnL$OBD#9Nl{Pp@ORHx)Y zUD>yJ1h0dNx3&oyBaLk;D@T&A;zF!_6fa$3lR8&#-nZ1Tn+o0WocT5?vQ0hrOp<8X z5$cCLK=lw@G0Y-3DSe16S%I5iL9v)IhmMM&sZmp6!wP{Aggo?K#gzo^iYZn|N8aWt zRH#>kGS<`th27FA->tmb`QQ@?@n_cV_x_^v`TSP* z8-#Vg*k4Ov&h7k8j8H|7pUw`i^GsKI)EEx!6fK>`DBy9XmEObX4m!trHT|%fJt&qC zQ#Qrl2|kZcnSLoy!_)}?gnl&*K~O6_Kt$7A$as$3`B_zq{t>?4i@D-d1YZ#7gmB>S z|K>+wdEVN$$dWJC+{{~nY=#VWD70Z*r&dl45v0KEdLn3}ooGw;3OTl~#@(gY8WyZ-2?=BUrdWx102LF;0If~+)1j=H~TFSHh z*pM5*RV$At6yKa$pz z%|ko(`kZC>5K1VPtMD1g%yQSZ(~D zM62Gs>0YsR5gI{*vRr281wOVF9a!I?v3ha z?@_cv(*pa)ucVk1tq?hn?9xk#Ofvb2ScyrfgYYfV0rsL~n9;Q-SF6I)7-eVzpG`Zi z3IRJ6n}YvC(lNus8XN(+Um%KdYF&aBQb?#T==VM#f8*Cg++x1+rj~pC_fxEK)d$hS z?oXEwv!bSf@wKW+uC(3R{6lk37GcW`f#~Kt9K3)JUg}XnOSF3=RBR(!XhWn`UM}=X-bmSi~ z>(uHE7o(%3?%N#gJ(pe+tTp}}Fd`Ck*jp)-B=#qs=I{S7`a2Q?1DRzmqECyK`gM-w zx5_5=0H@ECG;IY|p)W&5x|9ib@KXIFEC2C`Z+i%#5wC*g8$MOOLDI5sjy6NFQ%$j) zB6*%=T40z}OVU=ph)S*Vato_%^^#_7L#kYGafX|Iy8-7Hh!uzOu`olW-BUV&xP z606y@{-3Aa2AAVkk!bM+(J^_s>2pb)9<9Ox_6|1d^@suzF^vJ(!h`oN z&~$g8Di@BNl-=M!C6k{JJr0vOt)_B-lX!IxO?XEbxC;>+Tdr0)Kd*JU!t7U8^x9MH z5M8pP=9uNYoVCoT6O_C+5uef#)P=Y{)(F+ju9|0b%2trk4!c`DcCxx1c%^3z#^q2V z8Q~#6qMGoBj}Q1g8sR<@?X;{ss>si0FVlk{&=fC;jmq1NL0V!B3-SC>C(N30j9$ zL3sF^CqIsp3?H^*w(IkGz-!CWGU+wK6)EFjUdDaa_R zoPs$oCI$Gvl1FXgy2?#{I)@7xseP-_m>j;O9=O6N`?dUZ&@)vb~p+(3Cp=atow zfDfpIQQyw%7knxy1u@1xLu&fb-0`0yy|iVDt%S+~D>OS(xcx?xNtTWe={1@0RxXkT z(zjdeE>CH7EA3_f)hV)Pu^(1~6gRZ^Erc=t>yPL;~XyO5=&X~mfE!QXH#10Z&zt)rAIoK>m1Mz>FzCa z;HF{SDzlcpT-e4D6lE0}uw|NM7{&mL{#fw1;A!*_C22nWbV`Y}I`DPb>Z7&X>8^G+eJo|v-Y{^z51cTk^|2fa3T-=W(@N!mlv_is_;Y7~tUC%ru0N|_+dY`FW-a_3pE z-+5SA$E-K6U1ES5qQ?nmAQ?@-?L8n;2XA#^h#Y^F6E{rfz+xzzp|t)bHUF%hVg=_z z4<>rbTUa+2$?Ai`@hC204<(7s5KkF$p8X^RO|JVR7k_5i>8l? z#2Qx|=$?tGGQ;%kLQ{_$*SFwY{kkH(9;s)n>k6ZsC11925w~oyU;E~4s!Z~?0aDr2 z`ptL67^TT}lDN5>BfZo(XLq5GgC6Mou8i|PDM{O`IC746#uvJ?zIMrF1~0bvKue`r zDARpbcm>GSfz8b9XF0eLtHPoYM#UJLAB;JcgH64 z?+I`don^>dOl{J%I!SlAV8j#bvlM7g7;%C>!*UxIHtVUX=2VK66^j%~iSX&r|+wG)t0`PlZqCCm)nxNfFu#2r{!Z2Urj#DU@ImU+hh0{Bgv7Zk^ z>ObZUcR44FS|T`>8ePNmK~>hz*NO_24H?YratYuFPhuUij-J`a3!XN;Ui!8D%j z5rwFf<-!H=!a=Hq9CrD0>{w1lbe}Wtex7*@0`vdVFcC0{1e?hh%(AL%uPH>~_wNsa zIbdMIV%7JYxcd#cIZ=ku?wn*ON-QTWu!u6Gw~hL64hw&ntI<)Y+Ra|oa2QtXI+C_N zeu@)E2}b1XDa3BF1L-Q8hZD?bNk%L- z;x;F8y^&Q~JQ;ShzTU1?2p&cC5``Rjyi;d97tDZ}4pP%kV*?)i#KZr>XZ$DbMa# zsmA=;eX9D=S$letHu4fmoW#Y$t#iY6H5vS)rLLz|a? literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/seq_net_monitor.png b/utilities/system_monitor/docs/images/seq_net_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..2d2b26fe87499d258121383efb1ed1d0464b7a49 GIT binary patch literal 60053 zcmb5W$IkrDwjFlhfnf;H3wVA2dvFezn;bIdOf~~x2+TQ?%`nu!fL}?Epr>;2_m_O7 ziwoHX_QZPbyBa`Ue@{1xlgfadwrSpW6b@5TE)7k?eii(iw0=Xj6K zphdR74u9SwC=Z%FZ<1zzytrOinV<3U7yBgpVq&wZT?HM!)O6R1eN`RM2hSm zM4lr5fY1{D2aKb|hbRjOY=71L`NC<39~l3`;B^Cy!?g5fvr>}{#o2w+Up#Y~;%2zV zPR78ikj&j)S)n{Le=fs<{~p z^1R7$7?Nf0Kvy#^xfl5m+QP3Ch_gWn^LtN<1TFy`#K=OkK)IQJR5MzXx{{jr&OHl5 zS-sW9!O3IuqrDJ86#Db|uBpNLo7fVka}!Qkx>N#vg}^5_CdE~7Ww48*Hqlwo{`OWV zgxocbGznNR7=<#C3}NHfz>K8qA^`q-aRr`TN?hX*{_`%+K`D6*V#&LRb; zoKNWN6X!wKzJ><110{EVK&r1<{)}55Kzj%^^;Y2fom+E#Jb|{$`mYmzDq}~pGwx5 zg4v?C51c(&?5=9?<8G0XP%YK?aK?=a$L;JyO3?8)f@|Bl7qwrkf3rgX^nW0AC#iX@6g_!5F- zOcOiSBIlxRDITMm2AnCzMf8<|)mb0~YJ%mqBPr(#8-GH25>QTo8qt-Q@OQQ@hKs~4OE51v0!%k0jGX4Bd}Ph%5bRWe@1^f zcM(boN;YY&{XD|x$Dqj>E+BFE3kDjWgJCG_`%HLSn5)h^Kj&u*qO6LjsGw@Lc11M{ zqFM|yOX1Y^Yl(#Q>oR+JD{9HNe>sW>uQpPrf{ifTo8==6!F&){{lF0lK^_j9N%kY4 zZM0-e$q*2R(nkO7{LA+@7gP=k|5U>@&NlZ$np7edOmdHjUez zm?Rjnd+1ww7ou9tZB9jkkm7h88PaFOU`3X&nTwryOt(;q(8;eMflFbp<)=(#do zh99NaR_D-Ql#w?vfy6DW@KwVEaf%#N-aM2HVxn2f!FasnF27c9{^Q&O?JGnj6 zM8GLEthPR*RObxmMQjA_X1}n9^Qek~SQ&c;f?F&)GvI`bP=@P0^Z&2#r>0 zb$D3KF7LVC6~5?sfbu*|qDeJqaQp?6hf%P2w#^C5#Gyb$R5PrF1AR7E_pkJ|R$_1% zi~O9^GO87KRc%DKoCqC@>+c#p{gwl)bf}B<{Gg7H?5e1V%4|c5*?7;n1epJl)(1YO zhNvtTZphZN24`Gv%mz1ad*pkxx>Nhm03|U(fI0ja3rkDZFe(c)BTw^9`s^Ec+@s7# z+l6TPVaVK8gDlghKH@y^O0h#=9BQBmNs`*@8p>*%Ti$g#hndephMcY%smOuCwyKG3 z_1L+lYy0H7v$K;za?2wA$=N&X)18~j{dW8gb|;$PyP3D$TymY)`^7MKSBD#lh+FnP zI3V3jsNwv_o(=$qne-bZd`zbPEVN;4?FcZ1SH+SX^6Q=^dx~9N9RM^KPf5$shVsj5 zzumve}mrt$2>#DI&B&1)$Z>SuTQXnpM`vK_&84*n$Sq&#=nBQ zx^zU*;OpQ9GMr9^M1Ra*GLWEeF2tl#ug~=Fz}Zk2v!h#2hEju|3D(*B#9@gC=9IEL z04wM?>Jk=2P0YO?vCy~oZV>`4@3;khdenobz$yFB$>-#>hM#m4sQ%=xixhQfRjhKH zz*7j`=hCaVDuoUpp%NUZlyfq4(a~7B>IjQ#JH$S)t;{V{LJAHWes<>CJYpLU!rFWj zDI%Eg=P{#%a3*gv)p1x70DCi3DRXKt6}P*8zMc75`9>X9?BM3A0P~G0?1}v)p(b@F zmftb{%OKdC!82$RbL7HDQl)Z$7K;oMWNvfH3xEy!1OR`G%M&1b8#V9!hKb`H>alw> zgf9NqCinLUV5UkQ!@Z5Q3_h29^EuDTuOkDSisdfn%fGavlyhYJvyeJcly<9|P*t=% zE|F2#axVueMrZn>cGl3u#8t@bas!HAF$X1-$J0go8XvF)ospPaFWE#cTwAHjafm5n zj{V5)_xcEn7G|Z0472z>W|tC%Ok>US#m|~fbfnIMPjpbtT>p%Ep0Iik9+MV@K?q~VNNE%hk)m(Z9sy0~)Yxx~f3xp{w-uvYj1u*lM5DemS>2^%2 zaQ4PcR(ymfj4!S%%E2C{r7#EYD)DrgdE_x-l)PxZ<8?fnv=PPP#5{!;#PqCe_&y`T zsXCW9dXWdA;}5`lW{U6H=+7|vBsJXJ4FIm7LxlZnU%paE!qsmT0^(_=ALi_%vf}gA z>{R*u2D#41lgSBtM1wS(c&>d(1{4t>l!nbU?i{JF?EnuTqRzHSLdWbr&DT1shei-)mY?#M}w?iKtTloWcr@U z5E`yT7-BqlZ49a-Z4+e6=OfP?EvJ^4QH#A>+zYqcc>Rtbnv2;ayi;c{{Z73jLOqs8jKRcRHe`peYP9ipf~!M# z87Qe~;9%IxC4(^aq};om($UHo#+Mp>?Y#0?t%X^|5cClR0<>?)gp(VC$8(BM){OSo z;WroLG;(=G4!k)o&A#}QW^;Ns{HvNgsf^hdtkHTA^V}p8=pJFCY$o|ie-<2K}y0Z$P7!xH6`QN593*7=ev@Al%e|4O_3D-P!Wp;@52Yi1iD-5kNC z@rH~qh<1_xj-?U*HA{o?fOFY1FaQL=xs1o_AX!>>S*wZ^2tM#9`6Q{8|4P(9{RBxo z7ORv417VkdsT#++g;rcyVQtTXIapO;&(jgxKsHDaF(GbOgL=J`-2LdH%eV2y>x%)!o!Z%g-8VGl9_lt6?&FFh}Xq5k`Stel!O?xq$#p!frnuH_eRfQmNHtu zWx>|=XIW(T>&jdbajTLkuVn<_?LGOkPBH?Y(8YSy3tDBq>$5C<`V30n$QZ*# zz{?6LT{n?Sr(~R$J2de|&LC(PiA&N-g1D=Ka8oWZv~P%R$leSy$H2Eema}K}KNz2@ z9J!45!Agbk-X0;yk}J^9ZHxSi7IiY#2ZPm7)yk>V%>wiFL1!lI$2Z=UUhN^ZGCpwz z>;eOf_B}F=rA<1S!|&yCON+%L#lTE2COl`TEWo3HpBihOs8elQRtd5hGgc{Ok1pV zAa3r{qYnT+Or8KdC*UD4lS1o%4d`f{k9&N7Ch)!FG(Nb5y%7X)Q1SK-tk6F%8?}Xg zWF#STX60dwT946FT6sP@}M86=S z*TE`~T!I9IWmq2grjO=;QrUv=gI^>>^rK9!0g*u!wYTnJIyM5=_>=lQl~s00c~pl0 zX)X+WC+V|c2ag-El_}00Zlp-!`iYz4%MX5CkB^)`U_ikhtTm!<)7-6_hYI*4$?*Adk^% zv^~E~dKGu?CtjnGaXA@dW6l7`>%_{z2G!!mH*AZO7$hKnBdD~Yv!czzu66;&*5sjv5FpWJ)vwIroSO^Ni4q`tku=t|{z|s+<+l%(WUmru zE)E|1xv}3zYIem(5pwP~_q(q(N>MH)%5XM!O2gBWQ!Og&6l z865!G$L7QFJxZ6vb?rFF$_VcFW|(ncLYW?TuOd4g#0G%0X#`4K;$e^d{R3h>YVuKQ zJ%}1>S#(p~=GN{Jwz{+Lv$$tIHe}8zn4HXRvnv5UL4#be(&QlMlxGUBIZBJ0!==}{ z+n3K|L+}uiJb={u0OsqOvnD=~eja}eCh?;5{&Makrb@M@j6B%B1u3&3zu6Uo2monG zn7@WVr}s{)B>`HE>b$rtXi>fl+#=eP>PPLD?y=?|ln-k`O1R4RYx(Jpn)b4aUoMmd zBnu-)T!8gcfuH$|LfH^n7x~mbq^GBGb`E{T_u??Ui7dGtm1RB03wm44{(|Bl~xh?M9 zs2;R<;C)FKE7l;D@awkLQ8V&r_^rs`*tlP*%07aK5%rd-kW^q9J1pTl=h?GqdaZea z$XxJnO$mK|iKu##mh1fHQdzA+j2m40uI2d>>md(}0X>@*6jY`yG-@ePs#I@3mDfgA zXcgpgeGmbbay2CH^wki}KbLZTXGpZ~Fa1hXnwPfR_l!jPc635y6bAEJDtbA#w?K+l zE0%53-qlNfRx?~Hdy^S#5aO&>Z#y)GmBhvmB%Vq$-K}M!K6vPWb7=q3ZXSsxhnR`U z*K$?O(Pf$!bR*dn0;B;s-Qhq5MlXJrp009fl^c49=@;NoBig);ksArNRyIavV5rn& z`Feh=EZ^J#P1CcoP?)GY@f|8eL+G(U{zU>~jB#(MFY z&ShK>J(=s}Yt(5PI(`fXD;)VCrrR*jUiNWjj6sKgSJ#;q2E29 zudy(Y#!cOf+LzlD>fO*}!Y*0_^bVjuC17yk*6ojY`5;;ECr`H4wBB^i9z(n@j;5BoyJcuqi$G@Tz4G@USc{m}li)y<(@%W=pQN0^2;p91#adwc@X#G)>JGjG<PWO($>>j^brtaw|T+k#^CmkNQ%6YXk7ajW<>y{zj1xsoLB29nx(gc=`|bb=S$B zqmq?I8MF?g@zgfxQxS<8^VTC~Z<~RQ{{O<*{EKQv;s6KrZ>wgQ$7_n|xs2!d4tJMl z84X_gRp5NSSDN7)CRi_H^BVIDFgC^uy%RS!-WY?q5ig!!;EF4bttD|}+RUi`zyYw; zeieo8#YMRCQ^(vJw)|2g8=MJU^J&UjYVX2|p+4aVN})xw*l2ki*K?)|I`Jy-%uG)n zg^Tt3aD1z-bD8CF{gHkL<@Ccx|0Y=4%-Gt0>_y&2d1pt`zNpq<>RIJ2dHr6E?FKl~ zvfqgRK7{%;-)R!XfN#ics5Jv2yDoEHuK7WtFrENKHUT|ErQHEzG3^6mBf|oz12uSL zh5`D)YRRAVTqUhXZwN4t? ze*Lm75OI6p1DPz2#7)n=R7vzlEYD~A=TEr3caMZdL||DYfye>CC#@v=mlmOeN%y0v z>&nlOFA!Vxsbymv7`ul50>ARufcU}vdZ`gR{PqTd{&aPXK)A5_ozB*Pz#;ZXjG*c& z@6+720n`TqjgCregQ?bag}+PR%vOoTb)2WF)M07G%`b+cem=NF(75#4C$IFdDQ&x+ zCy%)G+shuBu=`aC5CYXYD1bIE%o}dhSz`?T*cVf;nO#_KXQ0Y{((^O65CVuDWK8|cRg11jW80r@a6G-?ujW|k z0MnSl$SYbznaJ2!VYu6r*e6J)8Lmo59K2)3L_cpOt?quOWeCuakiV_??zB#Nq!~w| zG;gLSDY>92veXdU>EVoM84j#zL6Cuqar72v>Y{}V%uai&%`_zy*)auII7lV{PD7~9 zlLBJ3BnOHs&Zuk907_6(G5rGd z95u;qWJ4B5d6eI5TcRD6+)W1eF)Bw~ZzKU(bGoiFNTO>jg#hotg`M*)l%icA%2HN{ zbU<~#=Ox#?(g2aZh5@M)1Tg8eeZXu5iI(DCE7ZsVG;-I3fv1H2z^}LCXqbH zlRUZ;P%VEj+zFtQK=DMxH}Q;M4DhPtm|<0-PPPR=!zW{^od-<0cw$c|8wo|nqTnJa zf4b7gfIspZHo_g>0+Nb(Y=;tUuB`Iglke%uPl>*su{A^IZ3zKI+O?kJ-2gdX*1$?7>opAfz2SmM&l$t?^!#293uw%7u7f#x%2gMWe82NY~@I(CO@saYt#fjJ`mFL5sBX9M9m@vXjeJAqu#I@J`E zNS}^QKEETPwX%-bH|S1GPvY)NRH`6cjviT@o#75q4;y+uMxdk7ycaF=CLOegabCXy zwnv`~VA!sHf|t&e^wcRAyk`En2ezV4AZs}~cHy4XH{f-tZxlX0Z_Y9Rv;ZE}GO$E~ zRm+8OH2|V0X>@~BoG|JXDs;c*K%D|p(4Y6iK)En`orU9|9zPeEE#R6l6HX?Zjg-Bf zTkQfD>BsL%Oyy6*Mp&XaARbZC`kTQI2%%;$ogBByg|!FTtO&xFG0F)>8x&T1hsBv^ z!?eX9)gY`*w`9a-&_OdQ?&`Kn(Tf{mhZPX1<%-&b;D)s4h3evZkqr z#xu;l^;B9#FsJMHCcMynLl^_eqt1DX8#!uQLhtMReMhC0C~3;nRKhF`S@r=$Z`U^r z+~o<4-})4vkX7F{wTc0=kI^}*9`0#!{AjS=xPnSV=mfhmJcjIR2s~q$UjZgFj^)x4 zfiVxeFU()0;(@#qPi@6ClX@jKkzzZL&OKD+7kn#!jHKB2bLLJe3{A@rq1gp(LmS~5 z`Lummy_-);jEStFt>obBYP$9{_&we2{bj39fCG`*P~mbo28-~f7y(B$`Gn3H+$-i1 zEa@O#S8bRp5cq)ut;a(YdFONCr^AONsX|>U4If-2hZ;1!-+=;B6odAfiz$(mCGmh| z5%#sC!r{Sb&%etoUuifxxckVV$5wQhJ3B%>*H4WvkMt#wMZ_l_fC=GinQ+|T8Xzpp zr_xy?{{uh|6g}r8EgeHnwSGN*KeYz|%;&g(JcqOKGjXsU87qx2GL9f>Q!-Z?X)3dwx?jyAwJ5`0)EnPMd>Sdg;(SRg=%0np3< zCUqNHB+-gfHk>&JJ}INp+o$IaDs0{5LhF{K~+Y z(R={*WSIRD;esyp^mnHbOUf)Z$x13s5xXxS&3H=hoXL6Zbrr<-pXawSh9(n^G{jOaY)Eyi$Jt;o@Cyk2$ zK}9$1com$??rV0-Yyl)CFA`Xn9k4PxP(b{&5QCQG4^k-3cgBO$H2MFQZ~Yhat{20! z0)O;x19%LH3N%zk8Vja>5T05u92mTR0r>r20eBbyc=~t#k#s@^P@ zdbD@b>gS!}rN7!D12qwpchKG=i}H2Iy@D(CR2rAx4&837-NL;yw@#X8Clu zBs!jdUtc8EN}>rEm9B4JYAWtgDN-w11>hUgp((07W%+|M^1EeQwLWgqDSB_+*9?+x zRCUzaYD9Dh6riAdCFk7S*&LvDEg z0Rg9(_9?b7Sf0VxH4K`iCS+V1srH*P5-#1jgXVBZfqQXMyv8iE7=KIEm>@3mpR)&yI#;73el|h7GA|H`3SWxD5wLm-DahAQ z%9tnd1?0=Gt#+NYVd&#Nwa4fYLI;-EDnM4g`?F@GbYdW=)=Qde(#NN5gEgUX@(!5y zkMfo~dsjg!VY1Q20CgQF-@`}>zyxD1<7<700;3hODvYG_zYhxNJMmbwzEi7VY6NA& zQn)_=tlXG`wrBN^mo_f>MDl*!wf<(h|1~I0^+S^sICcyj1U}Zvcbpyx-3exLT zX=qWyMwDH;X~{uO+g>TWWa{&9BvmIa^e7e$A5IA#!{?@MIhMqn9`HBW3h<6ry#w(q z-_gWl@FQEI+3Mk8>)Peia+4MuXyy|L`9+ff;-Xo~5vfG#Ge>|tjo+&bsM-r%{@vL- z=9$S)``iDv)A zp2nX+6izKXt}+=vuX(ihLD+`-Uuf zut=d#fMpcLiAwt$|A=424L0Xn2D;dWN$n%7g64FaN^1Ue!wzz~HiUwEO?qWkypRw0!il-1`vfXnNL_|QkOb>8`M&0w)lFT^=s3TJxP?}VEa9c?X3H;Bs;8$ z9-xC{fs-^(*46ID8U$xuu|ja29%?*R^WFLpjsnR)7BFRkfrUTynr}6AfqJak3h`N_ zkfWMk?uhd}4yh>mmDMx-CXrJnk-yvrr@Gp~hFR#fa>WDj3H+4E+?Z&+Jy)Ut6ldSA z1uAxX$569whXy|E-qhpw78>qShz;sWdm zb0Qk2buUV&0m3PBw%6E=7(`>v2@vwLERJJ%x9%Qb_P*X0IUr~p78hEKv`U>`dYv-= z=YN1=^{p1tXn!PWzpgM5gDbL;I^6&t2VJFg8P15{R*d{&n+xmDR}v}Anvk#ZSd-!Q zQi)axKCumB8%|dw^zc$2&Jg8FLzTMoPeg{eoHGVkKHQNkD>V79>p6j)l&$k+;aLlx5FjWpi|jbwAkDUkCmLTw(? zNNiy3x627LsRTWbv;?@)XWO#99I|#M!`CX(h8rO7qyTIc^E;nn1C0aGECghB49JY( zAmaey%gY{toQ}6?a2cYL2ibsCOUDAPfm}sc!BRT4kptvgiXJSkjKCL^?387Jr7g9xPFCxP&~Br0@T%^hh(GhpDfh{G|35 zDA&(qrRf0j^rz7$+($4IsO4>`i$-^H_OWVE5YaOfehs3viwSv@NM7vU*Kr^K8iIFu z$LRl1i1#nR&?vwq|28UYO-&TI8saz@to^DW^6pMAEKL%Km~d&qTK>}6??Dg zb6juGlBjCcSrix;dr)!5lHGbSfo}|n@HQop&Ws0EmaYbyT(J?#4?E%-NSUL(PAZ|R z1K1$!xCu0P{x>15A?)7?;{Vb4Wky)dqW(w{`^AP`03pHcYFRY(L7)|azoA#_#z0Zw zu>SA`YAQ`tk(fKd+P45`Oy>#RmCx%YcSrhxp|1Gy?bR5>zPGS{)Is}0^+bUNZ%}r5 zqs&a1bFEo(A3;AmHVQlbR{K24`?WQ4#kM1xYcR&?V6y(UmIT(#e%U+fMxYrSD$-^s zNPHJ);Z=sm4N|3rP(5aF>KsCEV$Il_EEclIInhZo()3wJq>!qx;7<1dg7o0#7#pDi zJML^#4ER-c6_DQRY+i$ls3f@v1IfF&V4`|5!NLanrPB(3!1ts5!byI9jUE&BKKiEq z4=WpFU!AmnnFqQKXZ1I{{-0 znd!5Tf1ONXap*KiojL%-mjNN(aVqS>gY^MFxMx#*>Q3@YzUbjWe_M}%ipRUk*ap-B z16!P$SgVxR5r8$4`8{ZN_I-y8Uj@+$%7R_UQcQp#gsXYHAN8x5=mg);2E-#EzXVdLcauZ|bXwdi#D5=!4EWrXI+rM#xAB2xW#n}Dqy=$?|Tmn^{R&7a~OO*W; zz>2yP79BZNUQWytIJ*VwQGqPW8TKX!Y=l(3yjA&eEi%I;>^<~qW!1Aa3fOzccl!8> z{jX~=9I%W$qEJ^AfCVw&@$zV-bsK;#87te2wt6i1EFNLNi%nSg+8$*`&n;EalBsPS zdp)G1%lyNrACbMgNCdoE%g{_YTrl9*!NYN|8}Avp*8*5;;*NH9AESLVe(K=|TbQoQ zeEjWRM>$X5_48oCWJO!+vtf|mLZ#5rB6T072~_^93&_0qtfjR3 zs&EfjU-b|$sLYX(5v-OFV%Do8x45F@HzTrN}WH=}yUa?bDV5z_#DY7!}gsL|pkauRt zS6bB`^W|>r@AX&o^BQ1)dg-$Mj%JmZ;6nI``qu)e`$K+#sJ@GI>2W?`^u6m}CW<=d z9zc`<#%Diz= zOYt!kKs=0_TNpy}4`|v|z|o&F*D?%=(@0LoF84iwk0kt&T+wBYE$T%lyW( z5vH932*X7-dc^C02Hhc!9CtT_QwL*#)Znx*Sk`0Ra4MA2r>NYIf8nzwERYah3`9?wzhP}+0`U;n z;Q~YpVhk;O81ph1rA$^bMjDPoYdDhi0g;sufT8_b?KA}ceq3Ar|C0b19zZ$&Hdeg9 zxfh(Hy=!1aGv@KX|KI^n@jqq|XR=4)wM;$D3_ragF?&DAjV|JBIK3@&$yB(y>H#4-B-ur;CaC_d#rh+Fy?+E#_KSN9O+w)^-5%W?ORy}ZWM>?dM zfb1)B7A5N`K+04~UR3^c#fYJ9>f3stF39~cD|6%L6~5iDOAV%IPVoyI;FDh*6MQKq z`Pg9Z(5UO=z#YNKDcXi%T6)<5l`TS0mwxF$t|#KaRgNGIUjGSap?pp6P_qf(QJ|-5vi0n`W9%8_w~zMxE45m&QjRZsNIDoD z5>m4EzuLFV*j;!uIqlMTcSj~vR%uz~y8=ODjCbKVhEVOu#NBPJ|3gv0BQE7~@A2%3 znzGD63_yz@B3O3Sm7t`aO)`UIOop_o+<`TsCT|akpU-_c`pn15LoN(c z{6W&Fllb<$DLiqM7B*iUSfU3OnWavgzGe->14CfSytY}xw>Kk{oNXs64`g&tFs-bi zVLdWWncI(D7;t#DV7!>C;h6Ra$ordajOT&H5=bO*g;=+=2Y#|*7HP%|jBeU^mT8;V z;9!fZ${#1^AzhVLTyI;#w7TBV9J>~N$KN(8D?HO&{(r+ElF8yVLFCeROCoaFew89j zro0S0T>%`T5d#hp;6{9+&D#)`Bt_A*OmWMWyJ@`$8C=7N$c)mt|E0Pz& zfi<$}@%oSaa+qphZtxpHz-LzQPp?6SnbtLc#U+PNt`GW&>*%_RSeBvlz|j`aqTfRS zmlztkCb2)Xnzp8|&T1*D1sZKcZE1d1aDm^!@nH1?{2pPaD?FIM2a1DG zO1vom*fCr3vCFvSNIgB_%VnD41+Eu~uTs*6&ytb11=7z|PVGgCCLrg>U!)*Nl+fyH zI1mE}+~OB4TFUD!Cd-h9It^7qHPRWZS^rL0V-V@Lz{xRA3GD|fW^>%^8>|@XVOfc- z6g@>Y8WCdsW!)bb>RhA5c ztkC5V_Gfe6A+v&oH8jr=b%*Iy@O+k0xA8*(f=tbpc$*NW84pG57P;w9e(YooJ~2ri zD76?=D8Bsv&D)=cLm9sP<9I}cHqvU#79kn?L}6ykm|=D^m{4Y6R%2$2St?R#p~%{1 ztF$2%B}HksRJ0IMA*4`AQ3`#p(fc``=lLAZKfix|$1zd&%suzDoY%R$&ewV7g2cws zBm5kAa0eVx5dd*PiXnj%sDv3P1zw-OGnU792~sTx=mp`A7cj_xP9Eg!&LR8zA><;a zTePFIOdN|qL@+>%&7?+hRhlG35*;EHK~b)3NpLVrLUNNKMA013m_iyL3gCd`KQ%yQ zcf~N^Bq4oKpu-i~*#X9g0LVV5??U3Dkg-mYQVtL8BnpWE*u5K`94CrqAqa8KPEnxo zOGqS^9|XD)$pLZ*z6TXei-58nW$rO#KHJrmFGUGr=}|6JCm)hP7%3$o5snlx#EF98 z698-o2iOLPAlZO^A>uJ*08@(-`!FaVw1&|!I4KGw#sgw~LfoJ}074WK*`g?1AQ2;t zLxw>4A#7E2!r@@J2o-in703P$>@d~^;t0K#z@b^CL>3pbJ_MM=V4M08`M}KboL$QL4U;u3$wg zBPCcLs2ftLK+)My1-Q=#8UgwfASiG*6bZCbpc4GzA`qYwo`Uy-gEkhfXm^;u4nQd^O5%tJb{vF><4XAwEL`aVHWC>n zhYRU!UzU{Oj^JTMLPwf|Gm9D=0#UHAObIl=RTb8SBLVyKC!W`KUM<_wY2tc_- z3h7h<%Gp5@rNAlaB2IK1SH$Hz1GB{lR$`s~@k9*F6~*^;iy(`!GP*C?Q9=-s&;psi zJb>*Mr$ERE;s~^>BQ0WPZ$wlVCt!n-N|qnQ4GR1J%`YT~g$$MiEX)7x8=@dwkq;#r z!f^=U#NdUX;SCM?U%nwEk~z~v%^d`&Oen_(P@Vu|G8)uvGMplvaM6)WRqW%$;>(?} z9Ek&lBzE-?H~}A7W!{J}beWVxpp#*sG>;?=l*Pii=s*F^6;E>@MgeL79Vk8|B3jOm zBSeA%Hejeh@<4`i_anlhqS&Z^Uju4dT|pZ(0^J`dSu78MGzQKN2H-Q+%3ziUL1C?O8VGK+VkqQ*p88)by=_iA#{?1n?N}@Xq!VM1p~2!AzZPM5;6FwuM$q9MFMRB zbB&9Y1WH|Fq2A4;&38a zNGw^E`bCms17xbh?2L$kNC6j%%Hsn z)E}cn0^(dW9XG?$0A))gn$j65bn<~ZOM=LJ2At(6fDh3dE@yTQ?+!^r1F*1B$h!~0i9AlZ7jCbUceVpld z6mV}*B9cD~E@jhvqv3cQNREU!__-n@;C>W=0#6f=9MN(9GMp493+94y4j4oh0w+fK z1V`|NfTTboNmTk#h=xl*fgi?)=qQO&snN(dJ_JZP#RX1MV)+~?Peh22GhG~zz%7K4 zl#xQHl&<1#pyb&|Hr05QzywqCn3>@G&pjuru~ zC0IXrU_g*F4mRHA%IgOSX_k+@Me_^SE4VDiibN8Xqcb~ zM*z}*><^j)jS^vK>?j4s!7qe|^hHy!v97LEv?Gn=DD-0m#`@5)47n0Zfbyg<^cX2T zzyVZ$Aea*C>)03#PMPX_y|~(&{bu(LL8weT4WsHKS#^( zVkZKDjf9HbM9yqyfT!UhK46kC1w0m~g46|$9A%_CSqfu0%B7&M7I@29;KRa888|?$ z3FbIZf?Z-mh$xZ5IfCW~N|c>_aSjv?f-P~Dkf1@57SvoQyipz!6YmK zjl|+OQM_oRU}PAOLXE=WPaG9V`N`#cM<$k_U&{omc3FF|(WXgis zfvWCjpvj@w0hBsXXL15QA%ZA~FxD9(@O2Q0@x&;cUkKly3i^Ne(_mtBBpVLLgYG)a zNI5GoP9^zKR8Sk>C}#Q6Vgm>)o(~_(c1B9z1Zp$~uX6PTESA6>tAZE(;R>o8^vV$~ZfrMy9F-L0h>ej^h|#ei(I@o9p?&dUjtdPD zKy!EDM208;K#ybNM6UjL2Ul(k1R5C}jqzgy#bF$Rg;Wud8svup?QG~&2TG7%P%NK< zb@6qWsXz*mv2jF4A{aJ+Y>+Ca+!u*MVw8NEgB%pWIK?|=a4yU3?`N==lI~6Ai;~IJCa~ZiMuN}==cD%U#tjJhs8RQqZu4TG)PEsz$27V zpfD>6=^}uLoahwQT1h}l2dtwno(l#2Hr?3BI4%h%fN)T5Dsgb4#0D`)4A5Q`Fxnz~ zA{4<)s1G+7Msp!Z=|n#t4viqDi$OT8I(h;no-9I10|a!?0EhtC#XhhoGBrx(8Wn^I zjEbOxDrb(XyF8X38_W+BsbEhe)kng2M}txbcf45O3K&xet_#)`@2HTlxX}kxmL49T6=F z0F_N>5mW@)0)xypl`O)B058P}R2W1c9sr+=)ApHmEx z>K+%!1w0fdu@oO8#6qa7SP097%W(2{jA9bSOg|^kml5sg9?gd+nG_s=pd>T~h8d(3 zx}pLUbQR1&bdE&CN?eg#0gr=~3Z-%h2^)cz3h``&62Pqz2w$milgVO)d?hs6Q3;wr z1VlLUBC(Dl1;h`L6un;Vp2#G<6T%9l| zsZ%U4HY_~FhwLkjbPk|l;;60^YEXbXmEbHF$9<#lzVdVcql6d4xz>%-9<8g zC>ut1MIc~O5~zBmGO$PnpNB#^zbh~X{;&jc^G=okdS9r&A|S{v&QNTNXL z0x%sFi1Y{L)ev|<5FUjMQjJeFH5UlzN(h)U4p25RK!{Sg3^U;x+ciYhaS=knmE6(N*CXOJ$0k0J~65Va8H1PCP#x6+wfOWE^HB4Rl$MQ9$R=NH7bSo0v>y(fFW= zL9lZm=!~UQdAE-6SiTd`KuCtapDWc70@$$%P*}*8@EqU)(fo)=2~-{e1Tq3JOd_y> zc&qTwb&SN@uIo0t_h( z5daedQ-Io5jF=3SIR%0bL_xTCd5mu)kf0E3T%41eYp`P=E7DEMjHE(>;2|@8Hc4z0 zs4an!F`!rzG{nWlIdMoq5;AC}>_CC@on$VU$PkDNRKWl>6JnNwDA%A!Xmcl z$gGp*w}O0%U!2kLoBL@sQaRDI?Ym&w)Z!S{(aEFY&k2dUjfdp1q|4)v{HsR=B)m3$ zYSrHajdz<4&JC*Uem?b5K4JIlTifJ0?7Rn~qsU!F(8CrxLgeSHw`Ni+j#+rCt6p2Z z)FFoI(%xVCo;SA{HoRE2OZMW){?Gk_+IMn!$`(%@ME8_VmF)9sy_ypS7sS^`V$6m& zX&s)WdaZzaYh~5HEIH?vzGkx}gBx+-?2@YZ$aVBbSo8tMJWpE-HNDkpdLtU@km*~} zk7E}zr|U_VPg?zGJN;We{micBNCo8jcTa9hM~LcktJR$5J*W~t`+80GUf(anF>U48 zm4!>RJgXG*6Bh~1!|s-?dDU3#w^Kv)x-+Hq;FrX|w=HC}EvhNgAoW@wBF{^2C!ZBr z74fy*^4}Ng#TX^7uxi`!{q;G7TidmrE(VzH7JIK>fx%3+kzMZ0H|^B$JTyzQ@hK`- zz5m1PCtuQM=2o=_T(fL{T9T#CGUmNP%q&(nRKuDOz3G*{wVTP-xU_!*u>{xb??#88 z(YO8{T(RcggPTpg6UE=Job|pjF{@(RzqPhkUDJyDZga-_Slw}#f6tLGRMXBnk>&yh zF!$(N^O*&U(E``}FP{intJ&!Js`S9W=Sb!e3g2umT?+QD4eo z*8JOmof^(sD{Kg6wk(_L_mX-`oDJR=FLCTE-IHf<&YbbPrHs2P@|M0e7U7xrpJfiP zTwLb;`Hf`7+=T_OI#=n)K!^YNuA22Uw~`B$8DHN0ncItsz3-;C(Wboc6w}z#C}QZ z`e{;k`FVxz`uyeb3s>x|x#2}%h29)>dmX!KZ`UHjAZe=M3*CYpB)=Wwg5GfJpbzGy zZ>w}RSAM>~FG(EHG1=pHboHjQzt-R1yKdX%?bGx0fA@J9{_b@qo!P$p(~F`9(_3bb z{Q5?Y9dcUsm@0(VRE2;1xOw^Qr?tfX#%s&%!|qo^HMiDo*>Gb{Ll;&rvf%1b-@r6| z_tA4VR=C9Hb9a~K7`bnElxy19z3cF*UlHk1rOq1MPG|kwA!FF;(8N_vqD?uM-lcA7 z!&B6=hwdN$`1WHg)*eC29tuaG~+0LpNT|wSg7~p1x&MA-ZKFoR@V_H2E{R_s88c zcWnu`!zN?;2N&2Kg=$>?`Ucgpelx?b*7f{^G(;-+nz-cob(B*}NtiDB9a{h7;=OeN z_Q~h-&)6mqr{30Z)nA;$CWX&_#OQ3AjVUyHZ$xES6O0`*JFx#w4_V9oT9TERd^K>k zXVuLx7aX-PBg$s?IoWve(p=gCr42fHrPJBpp11J6xo>JUtndYCS>8#djGw}ULhAke zDy1^dhWwzkxe)DsRbo8;#iMx7r`H8TyN62Oo?kxN_aymiwJTMfay2G8mK}x)>#R&M z(X+&yM_Bi12eK3OpxXt@hek9|+$x{-cHVJFA`3EDrv(w<>{k zqPV*jmDZCtxJ2V!`vJ;OTp?xO$zR=5^M!%8KMX*s+_c<#L0xf=vdKQ` zmU_=m*7+I!5$G)0>KTt@%;>eyXrW8s|1%Wc>giUC1&JHPKjt6*z3{<>+5Yc}cXZud zaz5lzb>q?(8(=ypgt}$gSX*gV*hSpK{krg_Vb{^ZzWN-k9XH($WqDirO+awNe^wrI zI!o+iXpyt;q`%eau3vlHl?PpB|8~#C601*Z2;X`i9=e>5w{=F{znT5~W3`P?E35QL zQk{q0qtL_`$)54J8BIJhnh3p#X}Hz%hU;aGiP}P!hqgFF{Yk`VN^$X??*q+Sx}V&5 zT;HFmIl5}M{;|jJ-+ybBulIe?{kih;@s%qRmEYc5YG<84tpOj@KUo}FF?-?g(cM3t z&ZT5|qiZ)@pIX>jl0*HR*?QJPX0r9&4M@xlDzkz`)ptF>&B%%=)N9cHh1z{ zC*sEMo76Sm@rY2b&x{Rw-AewP&iv%-@7D8J+p@>&im*y>@Sr!^6lj&8%^~~JrZ41= z8bGUNH*Oz4Y2)R%S#D-ywCy0`=GC>L?l!3W_wX@HclfP%tM|%>KGoD~yCoN319)GJ z(3E5R-Ft)5Jo~LWvoiwn*GR>d=cXmpIbKQ2b-z9nyw?s4Jga%hbjJ3qPTa3Le5n27 zmfnfwU)!(r|5Hq_EVmYWH*7ofO89PS*@6Q8G4t)HEXuczlV1APCCEjczW=<5DD|`2 zS$RGk*FNi8SEm|wV*g!csq0(Yrll?voc8`SE8X{>`*7IX8eDc;qy-G%B8O_!KNG75 zt{vIxc8R2&r6>(q^3To(23cmI*r^jE}~lX9r&pX@q;~JeV+7tEWcp6=h#${^z8Qc&kIo41a9< zoae5YQS_uY@vZEuz1M$xAYa}R$5a2yo~>Ej+qHRLc-MwcX?B_h$3tC8oQ~g_fLDx! zH$57`5$}8~4*oA!Nv@x`;?kDd_#ME}s!=MJaLOs8=bNe}QI`rrQjUtqW|S|>zP!PX zANtRChr)ns)ncbN_VJ6z!hiF;cW5Ukt47QFy0>) zbKbs4n38r4W>Fl-swtqUg~CR zu6Et5TcrN*+{nR{u63I$SEEu5{f^k@iL#G|I%+mDyVnGv5*=5%mzb-$nE_WU^KNKu z{6=kk>z#oYNVi%~@86`eWAyQn^}4pyQfuM`+BF;H`0xSx!{nrGQx`X1znt(lKCm=c z7eap^@2%OtDTTB`BQ zgUz{6NmgIhS~4=Px4%EBTK4r+{M2vv9lxE!Zz+>fjXX|;RmZJx<*)cXHni_5=Oz8u zNYAgy@6FH8Vhtw8JB9m~SS@^ADM-m#xB30_)F1YF%hE z{Y0{K>#P*q@2yKqcN2!&g_I*M&RbyUPH4d8*o9mc_hWtxw(4vfA5Oe}-HqFFK9O_= zvzDmWqa5j0i+pl4F=hGsdv$el6Q;(NzbHcQese>@`2FJ(R}=GK5Ud4e@XOokefN@d z7!Q+|)*o44z#X_iKG!`kaPGAk-7+D=0)1-YSVu3|$`e&L#)ySa`k%h`yORgJW4`-w z>0k@dHh}Typu)Dx`c(5O7j97zx(}JUZ;^>v#JxS32d_#)b}uk+Jzpz)Qw1rHYEA_Y zEBPB<9k&j7aK%aHz{8Z~^65$F`?|DCn=-#gHsv08|1hQ2lwd|L-$1>}CQ8HG%EGb_ zHrP<=dtYDUaV;_N8KQ6RAL0@sUtI=+G5dU6X-z2WX`-R;7^%GT8~2yJ1CwdhPA~mY zKS-XQoY>8PoN8un!%;I4MKEKqh;{F7ZG#Bkd5*PZ+Xhifh-RMR`nWA%^+nxx)C@i4 z1i|cgw|5vo7>^!2KaIM=dATObn)rS}Vg`@pyEbmPz4+ice8DN|MH=R};l5DY5<>Y4 z7xuH&`zN8_j~!c*rp{U;_&#*X`&e_XOUBOX#Ut*C;v?rqn3nA4r+jVP)+$E(Fhv$Y z=+u!-OGFv#+@L|JB|(?We0FIZ^-8#{x2EAx#%a#WvzWabVn2>ha~~&XhISR9myCsg zwS@3qm0s7tOovy_g*WD%b_i+E6WvsNKTF$D45afi+xN#Y+cid-jZ0gemSp}XlKO(& zsop=w{HAn>dhOwwhCZm|!}ilCQ!fwE`#rQz9XBNBXq1c^i}W=i6z#Qy66(c!i@YWa zD~ExLwg*T;G2-jq1qL=DomC=p?WHzFW!VUk?v2s@$0g@x?OSM6JRSDnBUmQxHo_iU z zKJ>Qwy7DGYoZ7e6vjLm2uI8}1W&fg;jvBzZr%vEH%2~T>Yilw31@59#8AY;p3e-hd z16fh7ZrK?#icfb>cTQioWy_Y~cegfcW$|@VjW^OZrbnIIt zussi`;xFd)@<~S+<%sjHX7vbkDWZ?bWli-q(>gN~wi|ZeLRz3wG?EBej{U6PPl-n|Ll# zad6e^wMS`p@q_OtlXz7VZD-j!f%PXx3M#Zcei}Y{f)?Jcgzf8jac!Pv}{LcOp!@a#IO!aJ0_ifE5`L!RSu`Udde-nS(o-Pb&%qJ!f{aFn(R=ar?REd z>j-B4O~#v+F1tXUJAcJapyNvtjwEadpRBK4L_?2gEF9frqi`gKtG_-yzT~9__sN5a z;M+=%_%JVuR^ahPjlK82QR@GSj0}HC7rrRMeS4(cGTPeNGTxcG;N{}=(V{ zUEca(@tfNc6ILz%km=Ox!Vhh%Y;Wo3jdL>V#$id#Dfh2em;keSVCMy|8dJi=D04U8 zG?@>j7Uq<;CmT=2-+Sef*-}hteGL6Ce&4axsxCM-uu2+~RH8oEZ?LdVL z8)Xat5M|Gr?s4^gvf0Nxl&(?D0j}=o!Df~wCSO0R&Cy+a>Pcv#Ho7By_So+pwMlpG zvZmbX`F{`W=vsV!bjx)L{bf-+Mf&OB&TRLw0nLLe-k1g?9^bSriPoPUdS>O4->dOg zXzdlOHSf@WE;J@4FR^m1At&tG?eXEB)wW2=hrX5mS7KYK{BS5ytL698>MQiSeq$Xk zvTL{Y;U!n1Qfkk7Xa8wjzJ)S9|Kjmign{JH11plN@;nkWCz2CVI+s_jPM4{ZcOQ~; z1->agsPQIwmL?|th~S8cp)DcW<>v4~vc^3ukZ0h9xu#O{?N_h^Y3 zm8k~rmi9MpFKWtOhq@$7>1n(m{q^-ZL*Mr8;-8oJ5^l{8&jXSz_~Ujd8lEY$G?Uf) zLv&4wuaD~Im%2BkS#18c)>GFSgm@iA;-kis-`6AmwxhLL1}K|PbEYm4N`5aF9*TH4 z__<{;@buT>^UXlzh9uH%$(=WhuSmLB`{n*o6OZ1PdP%!9G1Nl6vo?w5)yr4^nY*%8 z`Z97|-Mup>E=$LX{Is&Vj?T(;A3LH#wTVaFUm-^mB4oxb%pWEt*a<%?}#aku|HnfbAAb5OrG5JbbUsq+Emp|_Q@0f42RJ@$q^W|0o;ilL>`;I;St8XNjPO);q(VbnDO|aqiE0^UR z%YGO*uIzk;yIbAx?yl_V@70`)2S+!2*_J)~;Zo~7_2Umg+;kKePv1nxb?w8!>Blz9 zGZ44wPviJomS-W1X@vmkNPf>U=)IE)z56wBm6sIq2unL3f82`v$eHVJFL~tbuAH>H zUG`FQbl2m49b|W7>xsMSOT~uax3`b&^=^ox4TPV*qMX7#7)#zAcaeJnoy}jb211> zbj+-rkOH4As%aJaPT0&lU-TaD{Q=DMJnCb8Ok(*H!evv7tsXN2|GewflR4zVCq;tz zFaY)bzf)30EaiQd(%Qq{?agY2g`v71R(R+B2azt*Ej

        >&h9S>zs3G<$_uz+r4JV zIq!@t#gp@?(xZOecb_umZI>H-(vEYvLZyOuy4!x{@~7NihkD5)gP*WP4b+BGn~=1-8fE_-XU=JR@E*NW z<4yL=(w1Gh$g4%1GJd-;mC4b$>%ocqfcS)I%e`muzvE2DxgH=sxIXiY8-kdjw~&se zZ80nz4b~s%a~j-4!qYK@}E@jZ_;J82f%-+s&0~AYkm+S?&Se+pDV* z&G|a^%lKaE0cO{`j$U~PE|>iimo=loC6-!*LOZBkj!?fVJ#xa7KKr!K>Ka)+5y;H* zdA8w$(Hd1r1JUN(?Fqkf;(J$C%xTk`_cds~N|m%B*YIR3)zU4a7Ttb*CxnzQHBPX4 zQSs=+Elt>T>KY*551~CLHJH`*zI)SLwk7--jlP{1nwc?>x4JX#I_|f*|J}X$ZHn>s z(^|P+&N^TF`SZ2)H5*S`?Xr@E_j_c2JbOTuy3o#AW7+J{GkCIR1edFhCVlu;(^OGs zjQx-JoKUwU-dR5{EnmmDQ=y$zxA2y|k=K7q=FO}+nBN_H4GXKm$@E#O@3%L795;yF zseZ@#~wN&G5x@iw`F)kM0p^Hj>}xP0jbc)3M&W?3rWiJ+p59wX5GiYC5desW-)|iR0PnKb|z_9WrSyx*uNcp{Dxww~XAWl$|>(w(JCZmh>Ei zqKC~<3yb`Z*ef+dhPhF_b@Zo^5| zo>|pypU}Gk{Dv3aK^JLDH*On8fPdY)HT~-1=JwhIFB@v<{uK~_Rke+Z&d(^D1GRR~T|`az@Z{KOi*o_T90v{8 zuV4S>*0$wiLv3}RUY=8d^RdJ2x}RTPyMH<2{W}%CW zJ?|V`=@j$rz3;DIzq&8gPQ#8na}Ile295=r!Y+Cr2!4A*fd_=@_( zXg~S0r*u$%a&j_oGorK)55jb3FNtrJYV>S_Aq%zB;AmMBkaa5_Uw8P==>Pv8tPg@M z3a*h~d0B95WpvY{v||E#n8ns*GqPG5%-FchqI-CGVVDND=Ux&w$&adJj;&3Yp1j*) z{yU&@fa!up*z`f-C*{L$tCxTO@RXboc0 zfm6XTBRUvZ$7lKui>-5J26oV$VYJNh-@q^qk1@|q`KAO$lSca*vi;CyBt*dh_lBGk zxwdt!B|+({ebk>6cx}_av@zsez7!i_e>%6SOZLv)$&MbUxZb|7Lu>cV@qS=};W zedlh|{wCtlQsx2ow>1j##Z9ecVIIL(Rmf0JKYy~Sct`0Gje|1^cIC<~cAf8Mj!&j{ z65{s%jNTc}u=u$5545hmsE`cct`%D-&}P{3VtrB}040)4;(z%FIxI0+^T_9LlmqVo z{1RARDe6V)+XVWB*&cXrChmWHBnYpz&}c*8RP}xkyr;E{7uM(V=VIsC!dSvQ0nmClO~4t>1DRmI`YXvD-W!q%B__@_k1V$XT6wfcm=`doVx| znd=chNH6WWYQQ^k(B<^ac|$8UMr<>#F}`=I>!Z~vFMl0ZZ=ieRfsG!^?SMoc$ zzka=>_s|NLd*0$xp6ng5gfJSIU+Uf9nmb9hz*%6KkK5Xo0|<`_5Q1&ryjcIm1=t1V zO2zkee2#IAH+#8W_k26r>%s1l&TlxnaI$8*&TVUQz*IFQb=BC-h}DrauKE zR|nnoRetNw)CFc?T~__aPx)6X&(l7=oOj8{Rp}~bJ}y#(7a1&W(o}hA;a47j|M^#? zie<~K4Ho9D#V&)EhE$xT8R-no47L54`qE>(ryJbhO_=r@q79B`@d9c#uC2G!d!jic zDR0|C#)l#|lkk|Er{>{ev%On|?}E^qcW=lZ`?xo9rRouphetGis>FJ=X5$XV>QnhZ zC<8XCS$C$6T3z)6dgJ8K(G8N7jz##SQC3Pxnyc`SkiV?Wx#rLZ*M_c- zgeNo4ldf2tood;feI@1t;m0ZmV=G)9>gAj*5f8cxJuCn3=>B&=lc1&8tE{VP_mh<` zx4u7b%x*9DS~w+Ib%As{C6+^?|GlJk^nLAogUaE%qZ8&W(rrJDe9z^d7JZpq3XbYh zFrebrBO|GI?@x)ojY?ZV6=%**RSLZIvK2R;vdl@H+TB{x_ObKy%2jP8rHz$I9Bn^Hg%w7;ZT#3)aih4m^U{_ zzV3o3b2R&yLtp>pklKmM6 z%ePcMIvg(`d><+=enR&hEsPpKVvhGsT70#D{dX4JGzs-Pv-+bO=J@UDa(!k=sr>o& z{U%<~S(-Lc>Bm<O_e4Hi0 zEC}rWoJ;lkcEq3qy+PStWHX!cPr-?LUv|vJKl!gY5gVFd)vmydCShfn{8#bb#T$Inn2>DGfNl5fcq;@Ip&d1R#+2Gm2pqkr~C2G z9RHkMlk9D@F`g+35=tz{N=={Ikdtlf@5O#giYccuSopEViZ?Vj`G8#%#9 zsZyEHvg&PLP58h2-Rg6mzVz7Eib0O=YHeA*y&+A<268_5mQj<*=B0Lop(E3KCKVMI z{x*?ImmwE^+FxFG$_yi6!>1{g%}(l9eE(EeL{lSpn^Bc@BL`5 zSe|VcPd#;*c2|2Hp}#h|r05EIs<_xt_YyfFoN&)l-LizX`_G0W>-(Q*2i7mG-uHKU zU(qN3o@Y%re3{1eh-N2j!6s&`59o;Y&u!m)(YW5`QD*11#cpLsUT55t{>guxy2|mz z76BYu`2gl0oQ@wlop9-c_0jcnUodS=LiajveO$SN-4QXbY3hpl-;K)owGcJ#wIP73 z_138g((65Z_5j!@44r8~8rZN6K`lfWI8}>*6T|zCpOBrx<^+(^!;`*E|1z)h)-VK;gKt|ZmdInaoeVG-o@~RiD#_N4~yTR$#>%;0}&G)^p4s9^J9^Dnxd7T`! zj@)Zka^$3@&8baEmLG6Z`v+)MXvbvi9jMk-i_%O6IGOWD;&3vswJ&##a_69MS;n@6 zsl5Tj63>cr^PlOTw^I~veRt5uW$&^dCKbHkx``Jai_zQB%-jH@YZ@Um;Z00ECQ3xft@x?UEaXH^_b=4hNcV)Bck5Kd)A5P+qx|#%OlJ6?sKKp ztD{ow?y6`1JpDTO&-dUl<08N&@~NoY-J%^*UUcAFznf9InSvBx^z&BZ*J4_=6XuBB zDRJSP`FX|SvsAkk7e@CY)IlRs4NT>;{|9!P|KmjJp~rP4o=zQevRzYRk}L_pCT7(C zG}*AyF2Jn9j5iu?r~4AB({|zFL#KU5)?Qc|e)>@}r68*5DD}|kt7P$cCJ%>D_<3!~ zwyqV_sbvd6gTaLC*_2|^v&Ni}BdzxayQB}_?=;Ew9{c!niTdAdrQs)6mk3jGq8DDr z>swnzt2NWpoH;4y=Nq{!5#6e3Ir5=s zrGL!ubzkAeBrE*DA!Dya;Mh`a9Ws7wpXgf!$WsUE&7fvWMDHIUZ#sXC*jhlv(9QI$ zL#95y;W<+;bseY*7d+x(4ARJoV?}x=dQcrx4QPy z`oz+Z7v>-fizzJX0%t3qJM`Re-3jo2Mtfl#uh#@nE9ad{`+AyMc~9^BGjv}@ckPZa zg5C{7^MvCm1#8xmNXOk|RLlG%9gU4FD|Hvi7aI#)*5U+1uaZg5@fS2OdobY<_9> zXjtUGzoOyp;HVk_9H&oFb}OA930WpMPQfNb8X7{8C#FlL$di z#|^KAiP~#(<32Bv6iz4f0is{q;>haL@SW;Qjg&R7I(|WpXO$9|BNz67b4>1Jm8+X} zLP0!USJe}Cs4ToCws=AnwTY*9^+IPR_L^z z?dkwaIav94XfE*h3M+qFq@CT~k>*esq;u_7)Bpf9-#$ML?khFO;~(o$-B;wja+7{# z>79;WS6Bn>Y`tfzRVbP$Lp~FnuO%28TIj~U?f7N7Q7;BHgMWHFa{1F|p$gsC5^(Bc zmtW={GFf#0-WTP(nJ5(w%X>RN<)1_F2oJEgAF8CP%HDlh(Kei!32-~yuJ@b>JrF+Z zPt$mlJ_8G;ik@zQ&Okn8-cYTU`#6bfyytwK>LJq^XmF91G|p+mW(R%iNBCfkCca>o z-NcZ2D)kaUPJAl`6M`&Lv2t1_ zFJ7*{Z4|RRM>U1$#gB$zfdEB11v}Jsc&7{aTd3DURV+4i`tZ8{u#PK8de4&X7tc)9ZR02Ntov|6Y zX+xQA?*7Lli#h{_6%CuglrssDZf5@A_=V6t3p7gMJ2%VAOmtL0quB?zb6rIho-17(_M68=JH{)c=vtJZvr1!sf;3;FlkK zZnFnWGnqQ;8~qPhfDYMkyBKiG+Lp{5TazSyqQ7d{cjaYg%+jg?L~rnLEbQ3Z{dQ`= ztvT>*yWZu6D#$wCZU$8TU-Kx`QCpKfv`{Pv9zoGh1U0(pN2q_)5M3ci};;x z{U6hw1J+bJ0Co*G#Lfdim$Kvzz;JrOpI_5|zV7zoy}jvjQ}#6#fQrZ)Y9>2==uS>e z_4M{G>34*MAKf730%nHh4RQaAGoH6}Las*}m2Ig_J&Qdt7>U|+t1-mH0I2KAutQmcLEv({pXjrgSCIB{|H;k z!VJLg^{brOJI6nFdbC>W<^%j`^_JV)ae0@dB)Piu`v)ulnYDox^afDot`uF-2^Ze7 zU(l*2|yTwvSk1>UQ0fU09>K;joab?)T<6m@pJysb6Q!mIGvU20Ld!};D4M^(e)+n zK^LK?R4eLYo_WzRcb2fR$2{MelkwWDI;KZmJkWGVQ)iiXk#FkL6K<#B`xaJh`)LpE zP5Rbb*9(|KfHze+)Rz+9T1=@wY&!eJ8UKBNk)?6TyCL}yA9d@`m+Iou$fw6o244XT zvHOc!8(RQI-NkOX#%p^9(7xf<*L2pBitZeRFbI|Wkk*`t`+Fk>TQ0cAPgcEty$V9# zb91~Q(+czCRascduW!92--`n;oZ6If-m`AmyC0ukQf`n2rvChN2`U7Lb28wG`7lYp zP1^tzwn7&&`RQCi;1+Q4%u&|koCP||?F02zhIg_aVt-q-DPP~c!F{TGPGy%?9^+^C zXvoP6O}_OtWD+lsELD)X3Lw@q-SR8wQaHudZho?-PLNgRio6 zjlJSaD+fjgnoaBo89!q`y*SgIynKE5!ISWP#eJW5?wn=GOYH^ND8>(S#Qu=a?m26Z zWqvMMwCR_(R$!vKX4Xf)6U=Qx;IWujOasDeb9L)`KN_qG&Kq6?R6S&H{=Ali8+8U-+v^L1&9ix?v9_s}k_^=0r8+`n;(UsW@=}gEawEvPIWF zo8=}^|iUr3TCq7XqtH1*YIS}j7R8eX8DD>4FPvIbOPI$5?C7$F@r*dKP{o%UYhzXSv{i+j{mdZU9Hb>^6|8 zn9gt&^j*GY*V2Arn8;4d2vYOgl)3%+q{(6}J*gIe4O z+Y>PT>GNl!(4t)1PR>0PwWX+_{My>h3L}rWz=5PX0`-Z-L>Tp}-kN}U>E`I-BcC6Q zytdzEd0_Y}SbYOq`ChzUO5mLv-1NkGtuu+ZjKEt;DWJXK zs}`(uL&U=Uoy2beLfzk!?4N6fY+!p6d=rG1AJq5)ws zxUuhmdyiS?9@3HC!|{(@-+&_kdRxlp7kDLGEY=sPq+@&`Uc+TRkxV-zNiv0 zEOYYXR7&f?+W)Dv?jt9MF4Y#Vy9B86CF`Z=XE_3EUF(pI8HNRU9Zt>iCOKF_)qqU@Grhczp!Y zO8J_e5oGLl0&quHmU%a52LWNoe)A+3O1?N)AD7=^`(BTzFhh^tXj$KRC}Y0;K8q{< z)6Z)Z-?LUXYQF@z6VuJ{8BBY0U-_6-sl_5pS z{MFIk`?@~YXISf8=Q`KATCc7zWm}y{_>{k09VlSX7AY3VtA%=~KqVk-!)*lF$7dkm zHBrtF^1~V~KWaU@J{J6|*i_mt%CMF~jTz)i4kn#+m5bGCLe>G9>k@k1rcYhN4NDLd z6J<2M#QhVF*wB`E(wahte3ojr!uL2+Y0JQbt)p@kHuX7n(_&}aX!+t#AL6bFquFo9 zC|v6N#YcA3LDazFhWCHn3wt%#oye+yrt3`SCr{(GcCbE>27{WfKS}M3C`%z3d z?nqf&$3Vq}uusn3TLpJ{Cv_^4wj#bEYR-g#r}C;tGZn8EcvOA(7Pn|WbUb-2q{FPV zari{$C9eo(#Gu^$yFnRpdsaq3XK;_x3%=;s7oUI;()wuN_L5GCui-+9xAX180a%e< zg;;?(2(Q#adIb_Jq82G-dGMd47uE9*c5kK-Ewk}8GmmvX6Sj)IYUc+*w~?PrLH!Wm}R9J45US5CF0 zi2uQEhaknw_?KoH={N_p^NZEne9E^*F`i&JC7)na#Q@uWIsT6VnvuYJVDK9a-h6a>g(}tg{5puN&~mFUDWAS zwWPYnJq|RS-q1Z1-{W}x$2Z$D1lFR+f3yvwxh2i(QI4Y)MliY=HMWb@%ppY|k`Bq? znT2%r^07_MpmQY5N7y6z8W3{XlAC^ra)nBDwt(Fz59DAQMTgWdDGaH+Y=Lc_D!4HnkO7utUPF{HyqTxU2MF zM>r;*nI(|Gi93rNo&UJ--zN?Ni24#5^${8*-14HsvYe*_4E`QCP;JI>n;NIx5bZzM zoGs=KCXR3v2H^dq=qeIEC4D*Z9JP3YAmey7n#o!V=H^}WZq)OqLv?)0a32LRCk)`| z0dG+xeCky!vLGr_f*FZ*KO?M#EY5Do^*8hKKZ}Ey!~gFrj)xI(XM4?l3kp!qe|UIL zN+Y41J4BNafM7z4?{TV!5wN^BTP~XDg!Ix2?%Kf9Q|<9Zrll-khMZo-JCtg2CcvJL z;T6l&M;+yEsbAn;VlHw?n=)8jzGe`n=9)1}FAy)lPza6_sz)^Li(~@bzy&AERy}HQ z)oXWSkyPNqtU_{REhX_o*lqAbWy;1WnkaQR#ZsZpt1t6#+mCVi!s51<`#Z8+n>Y5{ zJ?{N6%6N71CZEL}I6W*J?9#W;C*kWgPO^C7jy*BR<^Ua1>jIS-uO9~ouYMXZxHTBT zz$139n;p@11aEz#0Ci32PP6B1_h5r}>E@%6M^|!vzkOWzdXwcyltwJa1Vl})Ns^~p zNWPDGTo=g-KKv||y=(S$fy>e8k(j%m{?r0w9kX8PW`4&~H=~BsOyguArXRsCSkWU{ zj)pzVH23Kc+aqaqsrVcdjBsWhiVWLBKAL4pT}vtN4Tte>x;Y5(o;n7nJeNwNJb>Cn zwo;rjRaZYg%F68<_96lrh9{rCizi&$J?=WBoW+5b9J>---7y2z-f1w!?tOz!2D@&;5Q(KlSW^co?KNJdN!`1;=JNSNJrfkI zv_YhPWXSB1bd-!EQkS`S0r3%X9}xr1$8#TcX?v=qz`{Uf<*+%T>9T7&2=QgD!_~z> zLD+M$&X?{BAm)Ci2=Sc_sxuJpB62ka(9tb_y?xZysM-_sVi2^O^>h7dI{kFd)XUoj zcRe>(FZlZTo$k(%(@fx{LW0^ntr*ZRof&EH_FWsf(jR;ij}bCL1AZRJZxTU|>!ljv zP~b4Z>A53Y$tzNqAqQBFTqv0LSw(Jq*@_P+2L8)aVfiB>kDd zFkz`Y*^MBGTuavc_WHj&6F`GG$1^Qp8Q9|wcUXF`TcK(onuoad%6bk>v#)6n>Sn~8z;U85n}?i#V&+kh1>14Iz*^E zi%k?T;P#y9Dv5zvJ_C5|i5wnEhBMgwXPPI ze?LxF6&ffe)AOT^a*P7{WeJbBx3|Slx1tNt+7+cn`P5kRin3vI5Db2wvIF@OGAaLl zoX&)JKhT7=8~ZO~$snn%c=hD<=-pQl&%tKVAW z3aQ$~V-kPhF-T?oq@!X2p1#nL&H2fVNZfSyUAB;rkf;eDT>7P*HRC_(4TX}u;E%^0 z*o8|hf5N3GmXJ8qw4mSvP1})vW+c3L=lNH7vD@|p)}3}>E=4;8HU7SYl)p=!!8WB) z2~Fz9Faso`RO(z{rc)S)*GV9QpwQ=Soj<$0&!zA8WhFQB3UPjTg{smY2*o-xXh?*l z5JCp!s1bzmZ(3j6)M_z;4Uuv%X1oo-un4fiTA}ZdVU7ee-a(6~!L5rYh`2EJeKYX( z0@Mzc=bMRn>7{sY&6PWv>z{7OK-q2B7CAK+kbX$na16Ur1e=Tt(XClTFhiLp)1GFWIw?E% zNvjs;8GsrW)sd)RcQ<+oxP5wegk9E+1c+~A$NhqMl8u#FjVNZJ(UMQF!-1@Wib5Uf?=K}1D`Q`?Mee}rY4G)-Wz2T5_Mdjr!o)he{{5H$|5%k9>K7e zcX`U+>jP`g)j31WA#P)CLvG{hsOQ%p^CJt-Fgd7R=zt_Tj(>Z4@rWvJIZgG> zRBY$P&aA`0p{oKd=jA#L*41t9H5Z>T*1p8;^mhRe#5N4T*jwI0N~?@@H@SgO@g7k) zhvl>ktQfU`R&&x>Q|+U_fIm+a#gNA|UPre=TCCdX(x1zPwL!%+@@wsZCQSZG%W2WA zY!dcZy|iObB%TKd0~U|;r1zQav};aBh+ zoE|WR@sp14h7f~fd9Tes2Zv~|srC2VZsdPq?4>>>rIzidZ_B-56jQj)zG0LQumfop zd2dAnZc+oJgx(4L$EfIBl6fk%GIJ7D5}rK0YM(eFCbyi=dro`b3t@)!AfZRMc;8>- zhh9Ue5AIgpM7RefE8l|C=(3Cf2b027QAcLWlus_Z{>czwAJXFIxyq}p?Gg>2w!%ZT zSKD0q{ZL3)4-X~dk}N+Z#VV!Hbz34z_UlnveqSbBMUdK;eeXz+Sa zv1aJhd@V?lt7o9zdiTEjYn&mL*!5L>+RW1|*Sjw!n9~8FFVH!i>Nf#|?oFs)K0Vug z*B4m1O|3gnESw8Ti3nCneyDtkgmZElvId&*++ohc5RQm>&gkl9$TEPc{yEHiN#{eq z75?5rgIJL66Y<$68@wk6@11>8sphtIopww#pUsZN;RNhHntjx}H5D*VIc6PEH#ASe zE#H)yix#S39qf!DsnUOuVoGPEXicig|GPHTt;`odzP>3j6>bDZ{rpfhpHYD>)%lTXkNj-&|ex3r@hpalOddeM}0gic;^ICt59Ys8L;*31wHFQ=s6H`Sh->|0ZIbA zzK$MppKMbDupsU>j+=Uwz8@HQ9KaMq=yp+)z$>g_RGTy{o42p{?bz61SckoKph_yK zuziFLVSJJ>3ApH?*F0khM1lcTZXpO+e0TKJyJTLfIB}jh z8PTQrLR@!7TmSyl1V|MWwL`ABJ2{{Ls_jcKtXlhSi~fW}EtgrD#l(;2ogfv&SEum` zt8)u-OIJ5c%0fMVfmzyABarvPS`ZhAAlWv^kg4BE|7v_~Uz+sg5{I69P3O#(+{imcddpsjpfVd#-xn~PY^d2DGKzie zD#C=V=z>bo@db)BB%5*n3+d6~LV*7Z8W*Q^MpIQhh|sg6I3fRTN62xvaT4%Vg;CNx z6xwL@+8*B1@9&{%;M|X2UuHRCRfOT~xaPqQm=H;HDQzvO^ubBAp%4w17t-0Q8F{VUAfVVM1GS`C0fB+06$xc#9Y0gp4JJBL zvU&T$zaJ#CBu^Ch=hX^CX5gv(ud4biq8hGH%yhYr zXfq>@zUFG!(ZzVv{R|`>!I52W?ahMeOf*9n@zu7|zSIV0w;vYfUs!EI`tKVP4tKK1rcmAY8Ll zAzt8P!P=8G+`L}Wv?a7Hzolxy{XOk z*e~hrI?1TvTJl;K@(NqB5);ycGW(pzQjWCr6}Q~nk6WI?RodYSbT@16^2Ou4z;Cw- zSkz#}yoxR|zC`x!T=!)iJ5hr|t?t+x5bm^J+kyajFFF`vUIMyOwfm!UwOq z%VZo1B+c6_l$0dBg%ndyx{`%MhVJu>+1Z^yse@`K4EpzHPu*=Tw_;UO-ts{9+)8fu z^@Dto7769wx2PDJ(he<`PcIt_B?P!kS-<@5T*o>syPP&vtksd5u&BxUa<19d2JQS& zmGkNkqFvI_ys%xoL-^$ z^?GND)^=+pM#UW?mwB&f*f9#l4qIa6re0qvR3nTm#I+3uFY#)qQKSiZ{S z%bXjGDKEAbePx&Pr)JMg#lbz!PPu+geclm2z+0;4(f%VtGx5#Wi_`|hDR1+!0H#&J z2W9$4teBHblrE=Ps#?%dod-3IT33W+MEhh^}!Uy5k7F)cNR4k zw4*`Z!PmQ%r~ryKT#8_yLo ze8j$Uu95#Gnhi>f_b`oLVI}Vzr@#8hchBAV_9MpG^3+LW70E04U0oNeb*t_{b+8y| z&~2zH-6u|+G*38UlPynUqWRg(_i<9@*NfF|n)fd7j!OVIfKQ*iAW9ypcf_tThfq`5 z1ko5|P9-WY2MK8@h+0%}g10LC`B2j?aZ5Lb_nQ1J28!PpVjp2cu&Ex^(xYgUqyKry zIb98xRBA;-;>p(i_u>oJRSTy0?)o>`W4-JW71RVAS0JS%7DMv*r69gd&0Lo6&mY(l z*~uo_Z!@Mg_$*o_jf!FPI#nQ)lGGM5IuU>{vRI-hp*f9DXg)GdvLJ)EwX&_0IhI+OqbanuR^qX>QOWDgsYQWR-RRU&7 zyyy2U<>4;Sg`EvzmkVN`*m)R1L6^m;_0d-_LzHQGwwu|erPwxzS@3d(!ZkGQ?_ZvN zg0Xu-d;D#@b-_vMq#yX}nTOX7qq#3IeyuwS7rQ^j%6p1;cc9VHm0~ZQUZ=)SiXKcQzcYH~* zLHhd282O%kQ#}ReW0`xFyijjaOEX(y9*3Q45tN*xB{(N?3*m>!Fe4jWIlLYwk9_d9 zrX?iTD9F~nkTUV3wM;_MxH=cYhw;wa6eXr)@5-n)uf|sj7=V1K=6$E6W=kTK>XnKH zdDw5HJY7Udk`lcrWJXN9W?vNOwS}@;fMV zR5K?aFr?ZsYDPJbYwuL(-(7mY^pRZ58|(IkUCcSj z$J%cXm9GRTWJu*#kV`cD^AZkMzq~jcGI%cpBOJQ$;U3u?>AiO(_|9Xr6WaJf6pZ;f zIXMLlI$sJ4b_A?Ao$5NUSi4Nixa5Fj|E|nHSDI5^tX_L?HCpk^f{P)&XM@^**wlNR z=$I(C{#B{3#d-U(qUD8zfTHHWYqj50Q-U_gBUqUs1=oT23T@oNMb;vS&s0(od~zT{Sr?3WZa*pyqANz zo9?nYjI#_!@Jt3f!!GgL&cG&Cd9soHs(nZ@Q^7A38ZM0kYlwh0{M)@jTpLii2{qId zP`Y_tHIh;8W^3`vKdI`Fl5mZ6VAzE41wC|sng{Kxg0jjFSmmy^L9`+6&`yug)c2-q zKD)R@;I!;H6nqI+js6v80I6*rS`U==^NS#}xuX==z(y}wL6cDm zVSkQrM#3Lf9F{zLeCxH-)MwVGH}*aqx_@p&8_mswXO(ckOC%ZE$yd6s&b=XnrcL)>FZGvLS2xsr#jkGEOu1HWUC#$gbRu_5W9A74gp0#uv;ypKq+ zK>HXkWX!L7M~w9BigIH*v{q@lntREf?4wh>5|JmEM4!cSV?k@dx5*;dOo| z(Q4OKc_%??)F%3PD-@iZ@cjJyy2=J6yGCCm-1Psx5C-wM#-PZNkmH^+v@@^L3(@5u z_Z_ORnpH=D&Jg# z+Iyt_SRdBrIgAU5Ns(rFB_kd&lm(M_Bpj)~j6JSYjnWwWV^8k=FMCp569QCTh5~pb zu7WLR38I6xSx__7M)2Vw(t82{YyUZq^7b%Fopu#fEp$O-5C?GJ#Xul=loB54u3MvL#U6y#W}c+36^>S1YZQd^;7f4T$a*>Gu|b3K$o z`05%ys(x;xnA|I0M<2RR-sp^HgyIA7>i*r~f%HA7Bf z?rmYL3(9+E%g^Ce8U_jvR3Pf@GaGrGt@4z)2n3s_;iNd%=uT*V#-;+@CH=yV14<4#bY!ntUj@jB+DLu~q zH3d{i{n8z!9~q<}^9vBl^V+`*dv_*-5pn8Z$FKOyA{|VOtOiP}6HQzf38|4}8i3qFqZ3?Z2w*^?#_@@I;Wd|P*M{Js+^AasBt%O+~_gCYnw$6K((00yJEZp8nmaKF=@n(cPAT0|&%%{&wz@?yo$p zGbPi#bLHeCT;>U2&G}FX4@8y8nK$DOd!}U7r@j$TB*&tvnTrI&Y@h9y`$;}g{LY2M zsI{l!z&Tz;s_W}NEs1zV^#iT;{UuIoD}!=zk-e3Ee3OG2H9ur5DCS7|3Vbc0F_h! z_8Kp^{$(;?sw_fCV6i(_WgY$sEJFY90b~Eaez^9d=M(}rnStJodpJ80^n1cJr2aMG z(Z?rqW0gW5KUNM12=FTAhEjpSYDXHR`;CsDI))J%?t&NOHq23d7_@zSr?Sa2r0$;f zuXU!8LZRE&wbMG=AD13?RyWGye(IG^ld8KzrFXPmb&p>C^uy~B*FDS&UKZu$96#2^ zN~^7w^KzYDYC3_d``1d@&imQ%&-Z_f&IS(HeH|V9zOkC^nR!L=)3#F2{ed2ML7eGGlFu5 z4M5a+P`f}8Q0$ft5Y7gQ0YcUd9wfdz`bgI`{iz$|VZ-2Cq(P=`mVQMDbbsvpq+p11E zH!(v%QfrpIUS=Ny{s$g^*hihOW_|Nh<+MTYX5!TJv{o23#sQiM_YzN#8ImHMWLafg zGC&eCe8~|+>(3s(Z@O9sLsbKRFZ|-rm5h5AhaVJg*t%~&uU*RYn_+!hxw-Y_(bqCz zylC@!j@PGmdcea9G@Q&E$nyOdDFHH59v`J&Tb^>zzQ_?e|2lmbhWdmHUjT6&slGUH zbmMzv@DWL;t~daHFAiOWVjjI;bss!#&a03okLLbR6V4>5i6VH|@$laDoEnu?#SN*P z2pnWhes%^52h_#-D(&q#u6`EhQT2LM0@zqRqOZ*IE#=+H=FQGa=K@#XXn4G{Jl6p* zM)220PjIxa;S;avWb;l)8RP-M{rpEEs)R_yLGNIPXU34%cwQS;IQcfn+gh*3@rXrL zOBwYAHt79-%;kfHzWm~`dMH7S z$W=yIFIHhW!p5V6ui%$~(#EsF(zqNhqILqAoE-PY2H!ka&Ba*3*HJHDx1r;+L-fXL z>G3|Aec^WvwM0NR!wsoK@$h`OMEkV{Bhvhw>5n%>rIjC#htlxM$PAR}&oA^uVT7kL zJiEmoUmU8=Kju36q3jf9U`$7}iFfUTXRPHtBl*kHr1|HFUj1{h1Cx{jH`~9xI2=59 zBp5J^#F=N5mLOk23aXs=oFSZ;`8w?Kc-yCb;s#ru+D#Vs7dwx}w!10IA+*qjVy!Ok zhTZ~U>rd~>g{fxB9;R3wQR<>BqVFW+(U3Z;Ho&5gsqHSx$*>#Lv5$Xke+~EcoMSD5 z1qc^U&K2(cap?pFTX!t36EmvJ)+` zeP(q%CM|PPpvy^t^i+CzBg9m!k03^9hbCLmw_LuKTh(YQt&fx4KT{As_G@$Cai?g| zHyT6t2j|~#-yb>P`Wai*t+-}m+2B>|hcZa#xTO5^^Zi@FR^QM?rs$-VgIx0&JZo)S zs7?;*g{R#`yetj3eBNKKV|`+{P9?i2nMrUStjcEK!(yS+m~Y%w>)?j8yxAg%9M3+B zsj#^4R(bYS`W0N#;^4ifm)_4yXKzN;0BxUk`5{z--I3IT7kF$JEkcJL5y)g5LpgsP zZE|{P_`D}pc}Ea(CNjS&xrIju`@^Y^EUJ*FN{{qj8fmB*lFr-RBxShd>vkCzQ#nr( z4#ppabBi-X&h0&XcJ_O-D<9m$q2sm=;A37WRk{tCm^KXFf2IiJM(Q6Rlli7>Va_Mh z<@?a4aeUs67iJzRG^E0x)Xa1FD7qf=UNDjSF?jYB^;^JDJPp%@;a%V9>s_{sNqRl; z{`y*VLtgLkFG`gMRK7GM7oxQ76^X(&4GUg#?;INMeUd%y^Z9(OpsD5sf6-C;fI4P5c$EIy42ENAgzz&AbfqDeXa4w@Wq)^kD_pau1VBIfS}X%6I|ZczPd!W zP%mT~;=fQ_sQc?%TLs0d?7seKkDgZ z!AU$B!K1Yw)feFf^9?=THeX*p9C%PSE3;Ri^^Bf?o^2S>ks@U9%HZX}swWxAy^GeE zK7ZelcV6jubCDV)?@#7E4sSlA6Ut4m#-=)k5U9B_d7&pJPcI)Fh$4rD$<7qlbb*T1 z0R6@S1M_+7nhW#X>FpA_zyXH6D0<3p9Jc0Qx8~Mo3@PTMjb;NqQ9TctOgvw4?47vYwY~GKcc5SY z@S!uLq?GKcxW`}d_O%DE%3oDb;DbBiV&K_2|MqO03umG6%8a54hz9HApP^9nvJp5C z&pAL6dq&X~_D+m&UT9Iju6iu|vf-~^3WAxSq@ld7cM8Oo5+JpEvv#pK0;{cQSo&Op z6b6@);KhZzrFk2CGZB0_X3PZ=9J;VVcfD8HooDfj7ixx;E7onH9n zw&NyqrgUI&!H%+WIN1h$fbHBli&P26Jjl2APW~97EIOmqJJ@2ue~(Kbw{$gzGODT}63Eh|rjR&jS)kincj01w2#Lhq)A3wsM@w#(Qr zoP)p6>}D(qg}pAqH~$ZFWP#(ngnCX@c*oTlmd1yJ)=jbW|fetKn?NY`p*S{~@LV@bTqB{LJ z61=+OuTIj#bCLgkt^iIPf_VPtC;tF^7P$X+XH3nB-go7dj3c}_p&GVm*TZbu#+y(~ zsRKPTryD+1=xl!R@K9Y|No+2Awx8V)4}Tx+6c!0ot#4ao53ry*_oX5ShIW{#36%zse+_p9IQRz8c0bIP53>y+KveaR6TO{Z?km6x0Nx8yKZPEA(cN zZ7P5Y*T^P`vH zr=$ywE8yZJejYDI3`>q42`T2)Iu}tPf{p1q#R<)~^nf3ic2DmcegYxNX^S4u@$42= z>ov~23zT3$d=cYy^E?v{rzROhDF`o!LQkBa?>&Y_Cmm8i&W_pxDo$b!t1>!?!u@RM z5+~(_gD9Bz%s-y1l^(xowgT*J#~Y2qm&fPM=_O-Lr$C5y8xS6b<`PsHFK^6d=>U4C zyMM8-C|&_jX!Ygy((?nAS;fs}ea&b^{*aVGL z)vzW-aUO>|>>>!-DHfDJbm{+TO>^`(bxFSi5I$&_%{>iqS0Z#b?F1$kf${FyeB4CX zQUdZmpW_nsj~72fX^*v5d^J8O;h@psjBj7XYz;GtE`syK?dkNP;4QOrw67HV63m&1HvA zMN4*zx$f*tB^o#YbqY}mi`>kevr|36JNH@5Con}<#sbZufLZ|BOQt~c1MNDOk$q*) z$Ww(Vi#RV74DM%AjT)C2mjG)X@yC7`H^S98_iF<`E+CNMcJdx-0hI1ir6)I^w}E&| z%s#X9WS$_Y6wuZ@F<+X0x*+f5u$%^MM|fAdi~*!BI1LoPC(X~o$|obI7M$fi>Oqin zPP+#GOt%afZuGmqp^wAh0O2<@E_Vt`T=`-n$%63#>7{gz0r_~5VXg!8MsTtbC(X|) z#xnLdBYl1EpEIb3fM%-V(HCk3EqZ(ik6yD1f5cR(VBZ_k+alu-tsnR3Bbx`d)fIlF{E*4^OL&f5&PyXT=1{0S!Ks(5e&PdRDO#ox?^A) z)_b{W(6WkClAIL7`-=JJnNUpzn>{u+;K0ZKc`%sq;uG*vyDrI|B#3)oLZt8YI^}M! zycdl@58w0a-4JtKGV?H@$M6xoO7+x+fW=ko;huLk0H!oLa6)D3+rH%eb|Jmj#y8cP z!qnb*57-JcaMyxZ=zf0D**9jsFl*o6S-W3TZk8B5#X}4YoiV21+&?! zTk%l^cL+v?Ii*Ve<5xlD=tQF%W@spk-#mT|G-sVK9+%n=t8on#oJi14MOD<;s4!{X zqdos{Riqz^s$Q`QVhGqGFB-$JyD>UFrt_BAk(syGrjA$KA@u6L{`4Z6_3XaPPZL*0 z%%*5f9$e)8GMCCJajc5!1L8p<|5&eHE@IN1iqW~+J5hOKJ3s22UPAWm!psGkk=D2U z>5ziE^K=lax=QplL}{Df_we+bhLA(-Yr2tmF2xh3k=CD(UQ%P7d+RU$B=4hM-5&4h zBFG%gXyGt;Y^Rsn{A+hi5VgUWP(HT~-GkYwsU>E+6Y%#yhj#}Vj#TxJpC@rctVlcu zCLVVHg&kIn;%GtwgU!CXbhnNu(B-uJcea`FroFr9x^7wcsd9S!lV#mv8UBc*D#vGP za8?fd$15aTfaQ;LKi;=MS-YhAZfbAJ!COuR>T#uwyaWKAJT=iJBYAsuLE zB4hth=jI;L?FQCB`;@k$Z&DI@60)+2yxn}*x%cmjr?{=Zvw9uEN7NsqY}}YhpLw3V zxvXV%j1mG{L&!HeH9PUYxk1oQGGX-5rPpfd6f*`>NBnK-1jKwkTdd41!cn=;IPEU$ zJ*_q7W!K|lxI-}V-TOPgs zI$jDPtC6sQI4uN*jGOW33GPnPh1eu5zV|CzDBZI~#|PiFz=N?iSM3BX3ph&T&`&PM3avi>}Fjc2j~ z8obJ5+oxg$;m_^syIUFw-Fwd+ZUXCTNR^{xBD)t_YlG=RfU5-bFMo7agp(vBj}mQI zswEeFM;wAVLi}H`sete^DfKKLq%c2mcYP z<79{G&ya=?sq&0UPsBc%-GOjkHT*9wFj+S+!)})KzG>kvq|fv5D_^>z5)Z*sP+rGL z)L7-d>B0r57c;^6dBgozRLN(2nCu+8Fm&pV15yhbG8pU5f<;b(v)F+!h8r6j9`pIP z)3OH2EREq~9%yEe1h4+n1PZ&WhhpzRUPb>^vEZ*DIDk5=7h6s63dWgV8*=RJ;W?jj zwryuSio_Gk)tdNSt2l{ecTke!^z{)A7kkN5)Hr;=@KErvl0JtQS_;58Z^AgE2-L#V z;cGVuCvo*JrNc7;V-FSw2<}%Rdv2C_7kQdcgq*lORY4Q{WT-xmWLZ7KXkLv zQ08fKwp;0W(<<4AL!@&2zt9qhZ8@Su4fm){`fD8!PWCh@>0wHIDW%}7pJuO|#+O?v zU@)0~NBT=4yWDza_&>Sz|N4{tsD<*n(FCBjUqX4N<7C^d(GT)u8>u*m!lsLIVT-m8b?EHg>uD9aiHl3c=l6960Hb*Tz1@>pdxhJ_Uv=g=wdI5J@kv-y z?FO%T6bGeh0*NOpMD-tkNA+U5q!?>I=dtD{nYEX=C;>6&KEV~+zyTZ2y+xe#a=-7Q z^~YVr$orTK6u8W7+{uLvMpfS{#SLnk0OVY3gV|c3zd5O0zCQAM=u3lVW0PUirapaoLI!Q}T6JVKoZ#`4RrCqdsiP`5 z@+{L74y|1>$Rb}G11giq3}7fjVyQ?mvPJ@jfWSD_rbUUqgOFr-rr&ITUlpHKi(qn_ ztBW=NCtn4ZCf64s3%!@>{0tH~*7r4V5kvVG3LvOs>-MF}BtcP=Vgk%8{eOF=38*na zOhh%jXtL$SbpkbeapFD(yuR2ZFB+M$BKqDajNmMuXKHEf@vkNu=n|E~bS~~yGGX}M z*>I?wH3Fr>G;sZu8Ib7lc&jJVak*~9$pvY7vi!lb2gxjjHa2np?7bbn4>C!YZergG zN~2AfbKCADBV(CvWZdP%Jk}?|4{Jlj zeBC^n3w-*AR6?4ZXTjDd`(FtV?ROly@&V{ek;FMlR3rm3y?iM`q*n1>q^;5C&7nL_ zN?01AFW*zbh81WNcw^ucWJ46@Zo0|1j*1}6DuYRwIT1-Dtiki&qDZp79aAZS7K(1LbS#c&x!l}MVV7;2+4fb)P{Vt&#n z)3i1YI7uBSX5v3$^&k#OB6iD8MqgWRLz_UU)2&wk;HS+WZzj)0#gBeE8>`6g=jSKk z@gz~J?H zWs%)YRplY<@)$8UcJh7KrYjqlqY%xL()Ow`pgq?q*a;~hp5d2r*)|$p8@(!8e9=hC z4h#iC@mE9nlibewWIjT4Ry*qOY@I=A2N#}8@_K2I-i$M;6B!Hod6`wgw~E0I8}nek zGmiR>KvqDnO=YlIsoAS7ee*^Wi|6u_UPT0}dXM}$wz0$hb6hKGO&W&-AIzT{ZS-@0 zkt=N0kcP3I@4dI+Y;{0XK`}`Vh3yxaYVg`UymCD!U_F-0+~%CgOT=_XxZj%cVN|g( zCiKtIN!0m~Oaf`;O%`v-=8Ow;#jP(jpb9_gq`Ra;Lka!1*u$G9q1 zlVY5^b4f4~`sSk9@XYdbsx0Y#lrwCyW#DAeR}B1pgx(eC-^Kd#YdxM7EL*~It$YIiU9e)>-1126t`X>c8=xGNXy)o*IfCqksAkv^2@A_cGRk%rsS9^gEe z=~o~ZU7=@A>P^0I`|+0JM^eo<&;*=Y_Nb0L=?w4;E4+v~>7fokiiX!U7Pr5?Ho93D z6%CTS4xU(rGiF4W=8YLL)IvK?Y!V2{QYG=580o{oTla?4uP!~IP^%*m&`WcuU09_} zayh*~>VYxX%&I`om%IVX;_AtvRkwB~yoYY@Og1E#8<#>ajWv(h6zV-si^>I=q0$#$ z77>e6-Intf-cn_7&za0s692)yq!{Vbn{+pK4^i2NsQ02^&;86~y|{?XQ@}S}-skkm zGB+z|v!m>D(Omtfibq`~CWZzR^FMP;1m{2PJKDH(k|}o3*mpRbS|sq~S72kL2R<45 zZeAaSch>4X-pnjkN#~Flt2%v+^;)KB?=RpN_-@;HM9xL^p34e!3iA04l zQd-%QhNstoAUF_GsMllj+$^_MpW~lLf`)WD^=OUHwQRYRIv_*B?XSQWDLnfE7g`En#e z4H~$7%9xkE`h@yuFy&eZ0Dy}~s^J{fs;EbJQP}s~nR06{fzt5Ee1)7!%L#g*7R7jg z3zSiR#gci10ul)f+7oM(Ma)F^NU+*DM!iYuvzYBveZ$4nkG#qS9z+O^7ZJ(j=EP0^U#mFF1q_UHTUGcarER5JB|1XhgR zKpmV@>!KT-r8=RWmULQS8u5_#TeE}QD}zERgEo#HIf!0;H4FCknEfr4Yq-AOo_baU zS=o28U9VnY0!yWZ4THjM%rlplml1gdIJo_fDPGQT(ue=X7VdG7F*uj3VjI~jx(uCL zDlb8sz0xm=)G{D^GhJy42A-G8D*B%6Z^(c-3G)@BLJ4S?p7PG_W*SebzM|1P1gI*c z6APfC#9Ky z{h1ME9c*2B6H04Kb6lk8r0^4`H7yN*)Kw<`@pV7+X>j;W(7M6vD` zS_V92QAPuM zp3|AWE#M}jh}!D;^^i^g@zzS8mgbIxnCy$6orzjXaCKGbY>^<4pi1UA_0#zivP31k z&ijW(!vMW8yZXY7oyIw-D~3E4%nXsQPN1=Hf87ff8%6^|>ng2xiEF zN*T$dK05{ReUH-KgR3jTw7vasOp3gwIfCBmat_f=tAr))`?Wr)=0)>0l!oz9Do>1N z*HOVzu`LYqv%|IrcB0P4&+n{`N=|U-q)A>JeQ4`!^QPa5uNe1G%v$W^hMz4>Y} z$FWjM&-Jjy-z~OGk8US>wd(%Zu^mm1*&E!UF8KY!u~3Z=ft&!w2RDtjVw9}%bXns| zOx2Dy;-^YVdp%Dz7Ey8&f#3;Zd~NMO$;(4rrR}qJjhr**zceb6^Zv@PzU&EyrBm@Q zkKXLMEQzO7jlosd9IR)HmOQmhVO{bI=lO($G?_>k29mBTQ_&ja`HS2~*9o{ew9z(R z30}eEKi?DH@jDf3RNn8Vu2LzEq7=MIFq$|9NzIN|uaZHO{SpYb4h~8ObVx#wU}>Du z#A?5}vhrTf$y=-;Vd(_I6|}Zh>F5al1}!BiMg#Z!dSa9S1|%BZ35bwJbFh9dWd!5dV=}>Ki17JD<4a?T3sn!D?^1n=@jNeW~fV zlC3=4lgH5O_#g60(fd&1sJ@b{dII62B0k88KbQJ0{4SfPjTDXI!jL_QFoD>ha{^mGDi=Q1D}=JQFKzECEQ~!!kr`p2hm-~DcVLRG&2hO-`$28?$YI8 zlFjs*Zd%p)mbxU9)boA277c|xMI`kOhcio_r0qop7J>wI8cu)MiJGZEWFPYNaQn9( zKv@qoaSCL4UTph7CxZ&n zGA2An8-eRY3ma;S>}fh)jGmHNhhU`_914$qm`t67)Rodr{q^5JaJWl2SyQMye<0*B zvW;YguX&OMG9F5Cjm--fOSDBL5G|5dY(U_@Dp7-~RTu|0qkG^S8hK4;J`?|EK>E9QjYm z|Neje?Qj3v|F!esK3rwf7k~RZ%Ko+YcLb`ZZT~yU{T)I0zR31<8o@3&K1_L2Hbwr| zIRrwWe?ZtjAi_h?zoRtrdH*5*{J>QFSNWtW#{XQAK0Qs}Cx1r-{GSl0>VFAg`0pqK z_Oxa^F7SDg#J>>O{|ff#dG3p#NY!S4%cGxvqQrZNDtWs0cZ3D|ebW`-LoBjxdN0Y> z|w zE%v1P>rIF6PW}r*ob$5?_8J(8$Kijy;jdV?1~ku~#`-U}elOndx%lg7Ui_L2JjZ)< z1}(Dvb@=lhL3z;Zd6QIYGJw-#0v`BJRjlQM@A@=0`?UUbZS$X-9YzZnBB<;iBvNGm zAo3LX2ZWaJKVTd!K15kSVEe1?&lgTR{J{7h2Co}v9Hyl=o0XbuD9-Mi{^FU_6gR^? zb~3gO;W{S1V>1Qq0LrrLMZcez7+&&cv0Xl)C5lS&V1f82(GbsW5v;D0`^)cq)EVn!6=l8WI))_P>BU&gf!w+Lz!&S)5rdlI>qkFI6UCV-j@nH%kT@0 zz;JtzZ2bJ57z^bv6$R_y@6?oE_Eo}ARikQp@}grTIT#ZH*$u=FWoLYR9*QidoU=&5 zDd!V9`^0(BwXdN;?Lf)hACT&6mOtZ`2hbiuO}!QPe&^O)A5Wm|vi|GDpUT+LEREh* z1e@!>I|{d<0qo!+Wmk=ID=H^QTG0gnVHt%W(v59aWSdFQDN3gD_y4F^9J8DEDV zyI{8H?E_~|7Q3q&{J2}BBveZ^KAdr*!f`u0krH(Ljo{k0?nSLx44Q@m%%REvO_heod}LIS?hrRo$-rGLF!GyV49?-mkM+~|6aCs z=8Z9o6t6D$O38X7fa$@A^AUU;dbIfJ+^5r2j!?vMC+%{a7Szr6P%<5x#^V z8Pmj$waB@sTZ+f1rU7S)aS?r`V09Kqftp~s?MTY`!p5JFo&=N=CQ;PbP<^Ng`3$9y zR7_!Z?YF>kS_x$K>-O(E3rQGe-FFn2N@Py8r7Pzv3hZ#wtSx8kjm(fY-M?_8t*sbM zqwMj_KSfBTN(ir4TR21Rprb@axa!8s4@@iq+8`~c+Oj@i z)=K!iW~m4=&n4UHlMaF#Kl0-Q?H63yGOk7Wge?pfF(>l~2CpzcuNfSrNqxU9O7_Wn zCK6{#G^cJPj(nU+^Z7CcWPO#@0QD+N&37%ZwT$-z|31`!@gf3wVWCO!b)az3b<&b_ z1qZX)bJMtKRttroE;f=fk(n~KyAskQ#%R5FR#S^aja0<#GA}IH)NV8`vUT(K7)*Ue zs&T?9{pfScVeT_A*4b+>xs_5l7jN%zgWW|-PcR<%4m;ocp{Q932fazHY>j*4An_R{ zA?vx9s#83_QTYf=jq!Fe&89dk##C{(^zV=U^BL`#uxi7Urt+&d>Q7gD9&aDk`X&tzA*g zf~Xe5%u+bD{aPYn{kqIv-iliC?O%=}!mEwcsbC`v_h$JBLogo%RzGlrLXd~UW|I8~ zXd5jVQ!)gEp|sI|JOA?i%>|W%!avn;jkC@DkS3LgMblOsbzOi-Q`+`xbNyj$3^@CK zC@6AeN{K1>><=O|3XJubfpR_V%=qSHKNdWHQ9-PCJB^4rD+!5CkD8P8)v38Pn@!_( zCuRzZ^ZtEjgJQ|@2{#BL#LGorhYU7?Al?}bHr+#p`?oB`0)uZELVgU4?#q4h8JqF> z0LGr2by8R+D5r7_RG`1=Go7{H+9cHN%xS;Y0&L$dKt*4``M1_@-ou?IA9}7# zm*Gb#wpDCPD6QKfnw$*T{kNS3>3C?^;nxmxwIc2~9fG$5dJ;*zwC^KBw*kAx^owZ> zmIV%?!w50+*4`k>EnGwq^_8w{08ALv50mcz_5|NpTg)PU+6KNzp!Msag&ZjQMjwq# zI#!^tcuby=mc3Ibk}*r?kS;niH&EBpO<+FN9bEJSUaprx9n1hpgMnXl==>^}{Z4Mr zG!bx04XdrsDAhT`c@Z0dyV)=7;XJCMAXdhnf#4R4&I~vqBb4EKPkorBIxVD;T#k>C z2ZL-eCxh5M4rdHZ`5Fu5a~HGCa-cv89EG6Y2?jn~LaDuaL%T>`^sY;?W*0@dIzppW zS{)u%v&(y~cZDx{9-ur=lW0;68XSMY62YLXxERx`whE=azS!&SB=WkRhk5Mk;cku&ruh zTRnEJ>DoTI?(FQOkleC}e{%K?`*i1~a=#tFgWZWH_-^KHHgbW@VaX36A9^;@Ea<}q!frt-F`s2K}JNAM^=MMq%XjCiTA;0)(U4` z(p;8@1+BMgw+FTFN#m~c5q00)-}2?sX$T>PAo5wfqkUkym|25oWk7FgMjt2Hcn6z_ z#4@|3D{z6#39nn zkK^dQ*?Z~eJtB7I(2qdlHh`PHg_WL)wtV$E^Sf`mGamn~1(;B$?2N)s+96Mc2N>`z zB>Unt@zz4utHg!N`UtXo;yZbnOt19MXjX1CdR(l09!Ryk1IqDPvjmC4kJY|+f{lS8 zV@@Ywvai-CDYA2nq)e^_TiHNI*OG|zmv@}k!l^&JN_b6f$k88W9SnxD&?<0(h#>=+ zMVF2!8hjnxK!(%Fkm!&3O9m43&4rj$>h+oa9XK26Vs>=v$xvz#G{HK1pExY>z?@Q+ z2VeyqM_s~#sEN7vBNqDh-Yr6)#0@a_~b&;Yjt%_BS z6L<>2`&@bzSEbMaBvgU}m2ysoE;<@3R~=z-ZHL$gww1YsN=U(B!_UrKn@4QpL0Fq_ zB1Hrf{yb)s5YFUnraBHw0$^{3DrHU$rs8(@&$lx_E8nQYiXGfs6=1$Gg*~yqB-Ett z#PU1Fe;EXuGk6AVVvbz+NUBs0&|;Bcg3N7Bc>%CNp8(*Gad`q{Z=>eD-!O5!Lp^qH zhS0_T+T{Ko0nAj%W4O1mmci$eZ$9T)`E_JqQ?cCTeEFAllyZ)2e-=_liqdX%6RL`q z$0affTkhpR#pq05)Xo~3n79g=U2Z_}E9Rht@_4#vU*iL|pfeJa>m{4Wg=;HyISw&p z%&{NY{azno(ZZ}0kzp3U$LvzVkZG)WzW7Eggz?3dMLF2Rv=rvxT_v6_Gmkt*jFK14cf5{glQyDQoS3KZf|#C_4c})( zI92BoM=$aqbo>E$&rI=M8~qtZpQMJHy8*xzbcnEj?aNmRNx1s0LQGJwALi_%vf}gA z>{R*u2D#41lgSBtM1wS(c&>d(1{4t>l!nbU?i{JF?EnuTqRzHSLdWbr&DT1shei-)mY?#M}w?iKtTloWcr@U z5E`yT7-BqlZ49a-Z4+e6=OfP?EvJ^4QH#A>+zYqcc>Rtbnv2;ayi;c{{Z73jLOqs8jKRcRHe`peYP9ipf~!M# z87Qe~;9%IxC4(^aq};om($UHo#+Mp>?Y#0?t%X^|5cClR0<>?)gp(VC$8(BM){OSo z;WroLG;(=G4!k)o&A#}QW^;Ns{HvNgsf^hdtkHTA^V}p8=pJFCY$o|ie-<2K}y0Z$P7!xH6`QN593*7=ev@Al%e|3bU`8xH3Gp;@52Yi1iD-5kNC z@rH~qh<1_xhNThzElY#)fOFY1FaQL=xs1o_AX!>>S*wZ^2tM#9`6Q{8|4P(9{RBxo z7ORv417VkdsT#++g;rcyVQtTXIapO;&(jgxKsHDaF(GbOgL=J`-2LdH%eV2y>x%)!o!Z%g-8VGl9_lt6?&FFh}Xq5k`Stel!O?xq$#p!frnuH_eRfQmNHtu zWx>|=XIW(T>&jdbajTLkuVn<_?LGOkPBH?Y(8YSy3tDBq>$5C<`V30n$QZ*# zz{?6LT{n?Sr(~R$J2de|&LC(PiA&N-g1D=Ka8oWZv~P%R$leSy$H2Eema}K}KNz2@ z9J!45!Agbk-X0;yk}J^9ZHxSi7IiY#2ZPm7)yk>V%>wiFL1!lI$2Z=UUhN^ZGCpwz z>;eOf_B}F=rA<1S!|&yCON+%L#lTE2COl`TEWo3HpBihOs8elQRtd5hGgc{Ok1pV zAa3r{qYnT+Or8KdC*UD4lS1o%4d`f{k9&N7Ch)!FG(Nb5y%7X)Q1SK-tk6F%8?}Xg zWF#STX60dwT946FT6sP@}M86=S z*TE`~T!I9IWmq2grjO=;QrUv=gI^>>^rK9!0g*u!wYTnJIyM5=_>=lQl~s00c~pl0 zX)X+WC+V|c2ag-El_}00Zlp-!`iYz4%MX5CkB^)`U_ikhtTm!<)7-6_hYImi`_uOq5!Ks@kOEC#>^a#GTO`WM!2=Y*@aXQY}E=3|0_vafz{bTh-uK&QPd1X`{oMmXEF(hS4_ou3jYGbgiYUvi zX?uQ~^eXxQ>%Wk~gwcv9Ef5|I1g83HI5Atkx!O9iJSRpGn4iU6qfB+{Dl4}t#_4D2 z=q)yl1v~yR+1u|EW;&L*^a!oH`k72}XzNDq4w2hcG0iKU0KwHJADO}z?;sb1L+GG{ zJD>V{CLe(l?8%#Z593yIVBkK%(dx0gZjo1da?qIlHlR|4z!k}tr*isw7;Tj0Vs^is zu&scS!$4(jeZIA~KkmbOjkIOqhj1tq?(omb1lzA4GolL{K;(p#l|X~pkzZXsX9pJX zL$gH_n!1%0AlVu<`p_~{3{l2^XSmdNPWYS)TJ3ia5Zx8`R-Rd``L$s;`%s%d+jKPX zvEkFl5LGg3w%Et*PIuzkw!LumI_%CLNIYX&K4P<$B@Msj@s(@Whh^ZrLC($(wyht_ z_W3+h|C?ws#kocix^ItUR=7M)Z@zpt*sx-Rp1fdVJ|f~=zM=AQ3>}auz*q_i-rW|~ zfk;}TM9nH*dqoewHcrgcEmS#b+G>xEkZr}L^R};UhArWAbw)wG@P^d;+RD4)_wqz< z1Z8F*q6QFCf%@fcT5`Go(#Q9fsIMG^;<%>;b5h0i~Xfy`8v(k>yz~_=^l7)u1zP-#o zO(srcK!jb95UqP1DF{Ji`OSXUJ#_UEfbbT_ajuBG+>2JxoS3H%&ICd32Qkuen0lD9 zGCBaVkIjeUdz3DT>)LUUl@Z+U%`oG@gfczwUPX2~hz$T~(+HHf#KRu@`v=5&)a0Yq zdJr|%vgoF|&8^)dY;|YfXK~MbY{;BbFgcmsW>*4yf(E%_rO83iDbEyMbCec0hfA+@ zw=bW`hTtJ2c>t;R0nFDmXH9$}{XG5{OyWi9{pH+8OqFU)8F{dM3sPo7ezPkE5dhMX zFnDQ(4u@9xJ9%n)sNaQ-DAx`C?D2>lyH^r*YeXHHSJ{;zg#E_ zNESwpxB%;?0zdN^g|Z>EF7mnS#O<&h0cN|>h2Ur4UYOy}|0)fohZQt7^J7m$9J=Z`Q=^Xou=VjDn3E^OHA2{e37Y;m3@rt#1|b6ecI zQ9Wq!!26OeR;)oP;n!`gqh{pM@LQ3=v2njrm3;&eBkCfReE!X+YrLtOu7&o}~UCZ+&)8l}{e=gRY4lxsx zujQ(mqsufe=ti|&RyguOPBA-@C4_kLNArrhksw`a^IgY5RHb8xsu+9at^z=I zB>>Ey=dk?G#1QK4vGLE?yEJPzFQVxs;`hwL!8DaVc_-#lq`1nO-66A9GkzftSwwMo z+ZWV!sI=P>@cJM-4JP&`N)*vZ73?{2h~N5`aFizGLEa6vDG2n70Mq4Ou!z%vuE%==- zUYJFyx|_uBHc^3lshb5n(P4cO-POKJ-{>zg8`z1yTGF>DOG5qGkw~X&25qUxLce=H zUt?h)jhng|wJ*0R)Vra{gk79j<;j~}RcN@3+s2esa%nyj)Su^mtg1ZXxqrV(auIma#MtTCL$Z zx7=x5clJ7xb<5ogxnsJOiO+mmm8)Ki=gXp_T)FTIni|%vXotU`QXc(5qsF{*Ns&|~ zDSN)Bh@{CdR?~FWN70e0WstSWEuJueD*y%OHZ@ia;~7Cp3kmb!w947q9$FIL-KiLj zrGH~fg%iIZJc`AM=$oQnHkkrANGQT>VN-hW;Z@5X;9*%@Fwfl4tGQGwK6a|DM1m#L zCL6AKtnhsO59;R{NnTAkE>P%T=Ls1nAQ3PDIU$HQJi?rfTBXT*S4iU9M&9L3AP#mbM zM$H=B-D}-Zldp{r`or`B&A9!~qWK-&f5rkJl8_a~aR^9qumA zG8(+}tHAkuuQbCqOt4^Lw&*#ltPPUvC;B4uIEe_bmCRunVFtE z3K#45;rLcv=Q7LV`Xl`g%ISxX{!Os7nX$G1*o(Z4^3IN=eNnB!)U(Q4^7_3R+YNA} zWxo;seF*hyzSAU%0pF0@P-_N4c3tMYT=RoOVLSnfYyx_SO1lHbV%i7BMur7a2Ws%h z3twrR+GTn&1#*Yn?Q( z{rY8FAmaAG2Qpb4iJP8#sgmfASf0=J&!2F6?;Z(_h`_Q)0+9oNPg+U#FD*g`lkP`T z*Oi|mUm&*XQ_IFUFm?_91%BnR0r7+T^-?2t`0Wh@{pso&fpB5!K8Xc9`22-u;3V)ZrnXM9w>o`wUsl(EWn_mn?{d{nVpmFK7PhRO^Q`&Yt zPabjWx0gLMVfU*PAOxy)PylVzco6*u&(e{$C#QRKWy+P#19~N|QIbp?l?EzG=MwoZ z0BtBuN|jZv@G^z=keOtTEUi>F^dgQ`k;PUs8%-9u8+J~KSz3m^eAx8_+3L78OW~qc z2n&rSm^a+0v&Is}^06#}Ku}_dpGhCIBIC#g5iGJQnTHXCl%MhR;A%9!(-D#clNHdN^ zY2HjvQgT64WT_#x)596jG8|abf*=DIwyu4Q7z$455f&r7a(r2!&+4Fggq2w>7_`+(UB5-r8OR;ZB!XymR515XM4fnRUO(J=c!*hr_$ zCwX)ypj!T5xD!Apf#QjXZ{iuj7~oaOF~h1vooow$hEK*+I}ez0@x-1`HWG@CMZrZ< z{&b~}0e|E-Y=k?$1tb;o*bXJyTv_F}C*RYRpAvmNV{3-a+Y$nbv}--by8&{(vcXPE z2f30e>P4H?Km#WZ21+O~sk-pa-k`q8N@~h#xuA$O)7Q+F)@vB{d&32jo->B&>G|uN zmuiOunj+4Po`$4V={H?T$t(xRXHo?ZCcrcG0?Qwnys?qZ|6XUov#k(_Oq4vz7tf}X z(%m@QZLtOF0?lX42LA%F4=C8+bnFh*QnOHe19L?BU*cTM&j!MC;#+;`b^^Jeb*d>S zkv<)re11nnYh@j=Z_u5Xp2Xdks8m6?96ho)JHs8K9yauRj6g@Dc`sV#O*&`~z$}z_4BY1TUQ_>8VpLc+LEC4{Sx9K-O|}?7}^%Z@}wP-za>1-kfCsXaPK`WnhT} ztCkDnY5+u0(&z@MIAPQ&ROo)qfjR}Ipg-@2fpTH?It#}^J$^1STfjAACY($*8!3A| zx7r0R(vRPjn984qjj%*#4MgU{2TXO?aXEhA;+_N1gK&H*(argx=Tr`;JO0QPPyDsf1Y?vg`wh-mY&L zxXTk7zx63TA*;S^Y83-!AER?rJ>1je_|ag!aRrr#&BcnsOs5O~HgzXD8V9LuF8 z0%IO_Uzop0#RGXKp4y6OCiO~eBE@zfoqMRtFZfpe7)i13=ggf{7@C$LLbD6nhBm@A z@@f0BdN-ex7!z4TTgk!M)pYG^@O!%3`^#3J00$zqp~B^G3>M){F#?Wi@(Go`08FzS3}XaQBfzkFDr1cXot&uAdrT9_dRUi-=D=029L3GU2$vH9%OH zPo=X){s({_D0n(p6_WY(9c_SdB>1pSGQ~<%upnjmu|R+j1E84! zOzJkYNTL;|Y&dfcd{RcGw@=S!qFSds2X8Qc_en)QK=1QoW@?;})mwE1_-|@T`IUh) zqxk^r$uRpR!UbLG>F-V>mXuj+l9g1NB6eRun(>t0Ig|6+>ne!zm*S;ALUM>mLZXgR zBdU!jmu0U#w}hdQyD)PZ}2i zf{Je1@hUi(-Pi1v*#byPUL>$CJ78sYpn&*kAqFkWAEZ#6?~DhhY4ZOq-}n10~xWm#TPeAy;N8GSt{bbJ?FrHX)76JYhn&F10U zb9}qhH;@8(KeORqv8EI*7A!{E>3#R**(-{Y4ba;Rpw&^LLX0fG56}}XQBVhFwQjo8q zlrc}@3&@vWTkSe)!_dclYLC$)gbpmRRe-E~_h-#W>BK-#t(P>{q>oSA25Um&VeWzB#)CkIk zrEq@$Sh+C=ZP5%Go=XT;rv#odHTG}DIFUx({*;N=LPeSpM9M6pb*c+h$=O$>T$K&- z9`wpeE)>u-4KmQgjEyyBJoTohRb;eV1&M~`3}Q@+wYRHaO@Q~2!ODc@>IRSv6r|Uw z($J!YjVQZx(~^Unw!Kn#$<*iJNUBa;=us>hKAaLfhR;piax95CJ>YM$72qAMdI#cJ zzN3l9;77JZv(>}H*0sy2^38*I+E40N##liEjE1WV`1kh=_o6nI7N>jmq(3 zE8o|(Qx{9fP(0c)l_T;}^Pd({0wdy*){!S;I?+gbNxNp@Hh zJwOM^0w-yntgGFPH3-hSVuj#3J=A!t=DYPH90ihpEMUq60}FrZHQ#FL0`*w672>l< zAxAa8+!5z{98yvAE30SvO(LgEB7eCLPIa||4YSZ|<%$R56Zk2SxiQgtd#*$QD9*lJ z3smez-;_D=vNHlTOe~6r@#dTuQ8}}b@3DNyrPGw|?~X-3i;3j>fCVEf`J+Ng_?d@L z(r5@^(5)20DNPv$(#A?o|B#=Vb!wB^HAGFZ%gMbACko1&dt*tK4qY{G){B^a#Rb?C z=0r43>t2*l1B6rNY_G8!F^I;T6CmVgSscgkZrwe=?0vm0azM~HEH1PdX_Y#?^g3n! z&;J0$>RTmHW${PuOw2KH6dT+u_nXq zr4p?Yd}15MHk__V=;5V4oFVl0yF0%x6D1t%cv^%#)6%qS0T6(^2TA-QIn&_z;l?9N zfdAm5ADkj$8Nc4-QoB4UhAMUEpNI@`IcF%)td=0dBE&B+3tZt7nu0L7yy_k90F=P} z*%(;8>PPQ{03*~BH_*LlTEJz%UgWXKtCB+&vK5T=oaW zn;e12_P~LLE)HOn)dlYYql7U&z-)sHD6q7kk+BuwHZOgwym)A zCr&f>tLc3Dowo!fmFS36@!{{}$FA*M@6uklU@c8ZYCnPu=vo{Tk{2HC?GYqqSQ*kH zp|Bd)^fL-!JH1B{9ZOY7s9WV)j;VXQZU&^cnWVBpd)ACn?i@ zKeySy<4L|o1>7%0f`Oubv7{YOiF9CGE&dE~Jy@dPa0z)LN#Flj>5*nW4^v-1`AO|B zP_CcJO49-4=})6ixQ}2aP|Mp=7me=Z>|@oSAfjg|{2D}S7ZdU*k-XTyuj4=fGz9PR zj?w?F5bs}sp;3TK{(V%~nwltZHN9zKpp@BnZHos4+!x#M6{^2G;(U8$&Rt= zb~Mr)%>m<2Tsd`jV})E#7xNMchQ^AMAh#xJX>mu20PDpK6CFeFU=b^bYSgi#S3I-E zMoKl|p8cCSL|Gz#XI(}Aw$H#0triU@~d!yTS=c%cDE ztMPe|D>svYr4?JihFEr*hpvA=`JdS2U;$!SVItJ7-}`W(hZco=e#i}taSV7!Vg2A3 ziVCTu>75yQ`mEjLM;3**(FI*VHOg7(g(Ba`j(pr&GxV|rgp05WIS8J_T|b4wVy5a>Qg#nD5%&DeNiKSVbjfeQ3mM7ss{D)wH} z=eXXWB~jI?vnVhy_Mqa9CA;-v0^b-C;cZGHof!|TEL{yYxnd)fA9lnwkTOSmom4_s z2e3idaT93p{BJ^9L)gC)#Q&r7%Z#v^Mg5T^_KOX>078P>)v{>ngFq_;e?zaWKmk-k|LA zMwyv1=UTJoK7xLBY!r6C7Lp?b{V)H#IS#G0`;SuA9abE1=Gr0KJcNFh~W!JX~_1nI%eF*ZU4 zcHG&f81Sp?Dj>br*}Mi9QAu(U29kGk!9?|Bf`twCOQ#k7fbU29g_HdJ8a*cLee_NJ zA67QVzzQbGUA_6*rMIqev(3b^^v0 zGSg=v|2mn(;?QZ3I&}buF9Sln<5bv%2kQfVaL=ar)Scv)e9^;${@AUB% z`(M{$IA9rhM4_%K01INkox#gGFG-3ZS`32Sv*v9O&3fSJ1V|MDXbg`;?@Fn$y_H$4G)}c|p70x~M^w-PRr;pFfZ&Aq z15#VjL~u-8PA#?jj3$kA?*Jlv9fSNn$B|alIwi03J%QYhfxu$0*OnsrYidUB{ohIE zOT%|+D8e%MA%bEYqf|+}a=w+I0F2l$)E`PsXTu=Bg-W5LMe06E6R7-I7m#`JSxag6 zRpB16zUm=hP?;kmBUmk!9I->aUg&E9KQ73|$FNrd1mf|4M3ZdFR6D*gUgBtzP*B3t z)wW0I`nYql9qVARd8%U!m3tBX8AM&Ze8YW`$#76ayke)Qz*2!fQe^{)j`_lNufQGFNb(&K!>=zG_{OcZs@ zJ%A_!Jh3&Rm&4ywewyF4*h~s63w5sW=S#2U<{du-WDcD8FL?>xLs18sRg8)fm3iZ$ zmf~Y7fYe9PKEaa-XTCv95YHB3;D4b*aLoUXOx%>g z!abMl`%7Un04LI#1kMZHdUM$_Xu*)Fn%&F(nDsl~hgvM87Z=17TOErWM)KYvm-&rn zBTPF75Qd9v_zn`&`%JE3weg?d`OWRfMC&=pesN zBaOX1-q-zzv%))P04P`?f_uDw?2iSqjSHn=m&sA+ou2|&hXWsO&O$JdT09l^YNkQ? zKy;2L3Ez<-0ffj@K**33u10cuP^BQpbRY>0C?#;Jo>T??qN4Nz80&$HA~m8@Y(y8$oB?lnG7VqPLPB8kRs;LdGtH4 z7bgNm?u!!1OO+FK#nn7Vc9b;PK=)x{AfbVfW@qTp~TIMioKDJ1`8ES z|2_vq^DP`!U!jz}d}<7Pq6a|IZs8Y&O|d#H6(B^LJ93lLv}`nab=` zPDsUVl~$$02Z6nOOA$trgmMc6BShVc@f~H5PEolZ|H5ZWSRf(17>J%Uf5Y0u1mYpC z!v%;I#28xmFy>`2N|~%=j5HjF)^H^210pLS07Lt=+Gz;>{kXRL|0e-3Jb-fkeXMwY zb1yhYd)L5K3@&$yB(y>H#4-B-ur;CaC_d#rh+Fy?+E#_KSN9O+w)^-5%W?ORy}ZWM>?dM zfb1)B7A5N`K+04~UR3^c#fYJ9>f3stF39~cD|6%L6~5iDOAV%IPVoyI;FDh*6MQKq z`Pg9Z(5UO=z#YNKDcXi%T6)<5l`TS0mwxF$t|#KaRgNGIUjGSap?pp6P_qf(QJ|-5vi0n`W9%8_w~zMxE45m&QjRZsNIDoD z5>m4EzuLFV*j;!uIqlMTcSj~vR%uz~y8=ODjCbKVhEVOu#NBPJ|3gv0BQE7~@A2%3 znzGD63_yz@B3O3Sm7t`aO)`UIOop_o+<`TsCT|akpU-_c`pn15LoN(c z{6W&Fllb<$DLiqM7B*iUSfU3OnWavgzGe->14CfSytY}xw>Kk{oNXs64`g&tFs-bi zVLdWWncI(D7;t#DV7!>C;h6Ra$ordajOT&H5=bO*g;=+=2Y#|*7HP%|jBeU^mT8;V z;9!fZ${#1^AzhVLTyI;#w7TBV9J>~N$KN(8D?HO&{(r?GlF8yVLFCeROCoaFew89j zro0S0T>%`T5d#hp;6{9+&D#)`Bt_A*OmWMWyJ@`$8C=7N$c)mt|E0Pz& zfi<$}@%oSaa+qphZtxpHz-LzQPp?6SnbtLc#U+PNt`GW&>*%_RSeBvlz|j`aqTfRS zmlztkCb2)Xnzp8|&T1*D1sZKcZE1d1aDm^!@nH1?{2pPaD?FIM2a1DG zO1vom*fCr3vCFvSNIgB_%VnD41+Eu~uTs*6&ytb11=7z|PVGgCCLrg>U!)*Nl+fyH zI1mE}+~OB4TFUD!Cd-h9It^7qHPRWZS^rL0V-V@Lz{xRA3GD|fW^>%^8>|@XVOfc- z6g@>Y8WCdsW!)bb>RhA5c ztkC5V_Gfe6A+v&oH8jr=b%*Iy@O+k0xA8*(f=tbpc$*NW84pG57P;w9e(YooJ~2ri zD76?=D84-YfAjVx&`|&X|7b)-izu`zBBH`zmMme$j2UJ(GYpa$V-{n^%owwjtx`zI z)+&@1Sxcpq(rzn0iKLB+lom@-X>nhp&+q^H|L*zTbM8I&+7G3D_77FyY9fS+QK0FIkQNE@%wCRE&uRN1uEfbL|-JZv4CRX-hN&{ zPzBfQD5@BNI8w74IPqP)Wzs;VpDK!_60&e0loH?}QeU(zj*Q~PIYtl!a-j^5RJ(wI zM01r$F^lKJk<;L)D7-`rVLCW-=z&3wDh@tEhVX}KU@cEG5qSu}@p=2P@KJb{Q?!8S z6E0zZQe`GY6y$|+fjhduyy)y8xI-Y(SqZlM2qFZ@$4J0eK!G952PH*QkOX8Dk*RVF zhl)8II3xlA_DfW>kR=DZt`i9gbBL9YcnB|rqYUO0A(X_$MM5YVPc*bQgy#rBkQ8ix z3@lR2qDNz#9b{Y;LCuozMR5X&KO#lY}}iTJPB&@nP%%0vwg0BQt+?*$}JKrtx-b(?IbNGF0QGD3rWoH#?kq0PZkpgT$GyzIvI*_?Q8o&Y@9~vc6 z3gbwTpnwe=)F64Fz`%XU-drvZ^Y=2KrWFco&`2ylu*u@1P-wm|kgeG_(B5)2Sq$)> z4C@u+;14Ppyu?VC2)>vG-s59Pawd%!Bt!;A0XYtYOvNZ2p=^kPCO|3UXj~Bap#$)E znIK9^AUg^)k)KbXFCG>x#Y6?l$gu%x(B0l_9D_^;9R~`3!Q_!e#>V+0oi*PKiVF;o zQ#j-pM=S_E&?u@GK@r7+L;~xwKov^tqy%3A<>0_JhfE0s)6yFS#Yf7d;G;fjB$F8l zb_;K4T&yfW4vke(Nf->$8E~==Vzm?Sa1rw&qr|{$B9`f`@&O^ew}|JDf&*?d4#p#K zodW`aevZkf@CY29fXR@uXzUn<6Nw1$1)z*LQc9$zR?{1c6yQOY%2`DxD!755Sl2I( z;-_|w6oO*i7>O^2=`5QnJp^q+1PS@V7#2b1K=)BQD4|pgC{v82GGb8tzo8407fT>W z6hX06P3jj-jrCV(7PB)d#!(KmSoA0%5R^Jm$YLj;VUh>IQ4~oGSLTo5$rU_A1W)Ng z16f-nOu&x93Zm5Ph$y&&cZ@Iw-dj__4t6gFr=K zRR}+v8V!VVA{Jpvr2)#8C``38TI}S7aF#KsLN<~E5ewu>fm#d)Wv?U&E=r-<4uo(j z2FszTaiRc+C^aKiA#p|uoiQ9gvPJ;}UP3Ark8}n)ah!q}5F|z5fW}xMr4k_ms+Tj1 zhymd(Mndu9Amu!!j|fR5faFM!gD(^vj`XEPtBA~K3IrSHry$6^6@da!&f)E-2tty% zUV-64F%T(GC^F6dD8?dXpui93MTW?@nr$>PPUr|`In4!0QR9Vtd6a|{u8eSTK!dQ* zo1%^sBjha2KhazXn1sM^iiu@;A=LsZ(l4BdabyOvxlwE$MJNsD!mz%6-hdVpqWsCu zF+Q4INOMbYMpFV%Dj8WC1O7)7Z4&(XY9uh1V>v|P7-$UeJOm$u$%(*Y#Xr#B-z$cN z^ryw4{0UxknMxTL6cH4q5bW@wB#{I@5hA4zASVb!8J!>F9~&M=4G)N+ zaG3}N(^mt`1Z;05+r@#Y_6MSQA(RDVACzb>kuyQ<8%p*e(1}O~5);P= zhX9fWWPh-H1XqG%^0+FTgKtn2+6PO+$3mfWEQCpchO>;(&>dfd>YZw3p}K^3K>h#Q0mbTzB&?4m3wm_N;&Y=0&h7-dvSnz46a+&S0~gE1c(EME7dZ+8p)#Quz2P%50;Q}fZ z6yyn2e3w{`+RK4X;c@6_tQzmlcXXh7p&?MQ3n(rXp<{?KQho%m%0qf{Gzgl51;jY8 zQw19mF)}EU?Hr*54`?8TR=NFgN4k15mU`p~!)+28M@n-FM1&%c z7oc%J115)32T zH$s3{k?3B)f``ZD%f)Oc92CM(R1Pjs7!T%0pi>wSe2jud7R7=@pV)_h^&v|6E=-g^ z6Yj!~3{nAtp1>nWpngOLs367>5g91L`LY>tIEO$nT|%Zad@;bzhDCRvF?<=ZLK@!1 z$6=}hDM-O1kRfEyY(UwdH9@%#nt;Zsg-iz}D1vc{aguX^iymI8hGP9Vd{6)w9uvg~ zN3!@-J`abBr7HPe#0Ze!MYA9jZ?y~#1q+?%kM)g}faPzyOE@)Wu%jTq>QbfN~kQ0B$%7 zR5|mZaAmA8Hc%KK(a@e~x|d7{$AVG_I8ho61&S$@zy%K_LR2!2K;(!<@IdW~I6?sd z)|#=gXr3ZE!Z!eiMX)qfCn`Ds_?tO8!W3LSi9(S2up^j0sBnSWOC7`F`ULWU4VMFt z8LecXfJvtlTcHM-8HyaZ;jq0Zv3xqxQ9*#kpt0dlIwwL6<2#2(I;of}lt|_eDx0tp zgap_EgUmLaD!~VVD8&g>7=)vga4-Kj&8h-@2V5W`!QcKtL{>CAAX4ds0yzt;OQ3_V zg9BCRC1Rn3G%>J&BS$-;ofQG>*dQlzfI<>Yh|wIFzAP6B~cFC0PW z7wF>vV}R&34zAHedz0xL6ezuei-}HA0Ng}4`Kf_Q7$w2S!GMI*FV@A^DTYjk#{~$0 z4#i0-C&q~Jj&x3}BgaL+cJhO8BgoPSUnk(ph=ssKLPvE3jQ}Vp8Iz5RV5r4VjK7Md zp*hITk*HW16fKC3;^XCFxl%^KhZE&uA`hhobgRr!s8+!giWsp_jSxZ9zy!iS91<0Y zhe%W$uV^tF2e<|Vs7z8~VqwHUP}io4fueXq4cmwF6RJ5}1P&Du%VGMV17*=(OaMP+ zeq5QKI09r6LAZ$Kfj=xPHx4SqNHnK4coEQkT%ycN27|@;a*1%f0?Uda`Z;(p@Zk|8 zhD59;($W6Tfn+FL5KVUgr--v=4UrJBKr`&^2;(|3HKGR!P^tw;!vn?P5`dC<)XFhmkwQg2RSG zq@UV>LWU{0#)AfF92XsFL?RZDxlmb@Gg3^A z<1zTG7>F0Zh#;0i`ctCNpkmnp#sRjP0_s8~Eh3hVbBgjM&{0ezMZu4VWCE831r0cdMuMmChDoVZ4pRtB3<8}4fHRg_ z6Wv0Pu|g-X1EJY|zEC>E5vXHTpsBa0I0{Pa$$7gRmY=(_nb;Q%s3OfNEP68{+8b zqH;mvfu#`{5*bJWMzbtAAjiRHM5riW0mYR=d>BL;L-V}6SPiMD04f0RL!kLfjdS$H zkV!6@h|QTma8N;^pf16gC<3L2;l7$8B_Koqt~Q#P8zoX9SUkNqz;zT5l`%e%U*En-m@f)RuTtaiCZe z7~&G*ocI)mj0((@9cW0QlfnfT8RY1KP_aSHgp}g|1;S}5ALMjlK{RLpmY|rj`BV6V zu+`fSWIIFxIy_22MmPmJ1cGv41c0HyjRU+%jEejZdKu00Oc}U?O2!`(uTrN?TR9Dj z@(NIH`gl|~cOj;0XPEF@O7A=^@3XyT)$^ZE*D=shDCRENDp7zRI@_#y!@Xw9yrGwW z4LnXbKY8}!=lh@IzQwlH#m}=|;V-9+Q7@?rss`hTI}BEMY`rl#uYP93$k(^?+!Cc` zLz{kf|2Z^yaaOYLrkAOPuvM>5tkoLYfmqib6_=yqo1}S_V^(g%7kw@$*g23%ShZ>N z`S9K&GqSGLRVZA{UcR|h^}F|5pRHMsNBW|X^DD9Y-=;wI=&o%?%1^!(JAFC{}Who0yeT1)7wp0bzDFjA_A7XB)5_e>87oh!`4 zXHC=F2VO}(7o-k%?M1I>e_PU!Zw*@()s%Kc%JOJ8E$rXPXz;VpGFqv5bs46{#L4y; z9NK!NwsNL0h@m|&{=14mzDI zJalCY8)ic~Wo8z)_ixACo~5&f1g5Izx9bc3sUsV2&04LS!0VWOa(Ch${Il`!hRTim z?7uMruPJp{_fq#hPf56QZe!aj?CbBoS!*5VO+v%++72U@#|^ocdbAW;?>5Rs>Aguw zWwhD_U6}S*_#_3ni+GIQNqP71jMm|cOEad|7ouJ;`yCQcT}c~OAXM+U@<=9|rZlfBEVY z`_4nZYST4zo$}l(*R$>kCG;irpImnm+%a$NRa_lpT4%mDT)9j7xin?fKjkl0E?k#8 za{+qBB=WwwBqw1YoiYF}?XFtC{8^NuO?AqY`>HZ_^Aj^0>hU6@_7=)2n%Z**N) z!nST@cRvqLU4}5yKfq7Vcu!?NKH;Gp88zODbGet*W3p0q??Pa0oVEJvk))$bPp=H$ zcDdxylLqFduPx2BOXR2AA=sTzaLb=6JIfJ z=;!)U$Ey-=l%`z&{@5CZ-W!(W({icz$xEM7q6NufR}NaixMicg;JKmErF~D+7CCB5 zCpx_P^?m-i8pX~>D0KVFE;aN$bkFs?I0Q8!PW~`GZ~g7|r~08{(wWup8nNN)hMymE zDoI6i4q=2l{%eN8FQ!;qtSs|g&g`TspT>>&l!M=9aU$%)X5CWHm*u>k(V1gE?p16d zU*dJiCFP*dN7V5D%L6H5xkr+@Jts|~LxUPBR?So+DUHhaX z1JF111NNk%!0pq*bLzKPuhFT$x}~$GIC{3dO|sx+!mQVK_v|_L`9SX^yLa=bO#ARzy>{&z>7JBw#Qax_ZZ?vz;WdAKd-%z9muU14#*_nwNL@#^WJx#n>QXKh+3B`TmI zAf%t)BpDf<8_^U-t?&%Ju5RHck1lsz!EFt_SI3_o;EqJM-aB*tz}blL`D2QvnK_m} z?w+4fOuCtWSTDf$Q)8LQk_+!LKX73Q7NqLtg-&S(m4)4@chbCD*W~2XrkuXHHr)8{ z;Y0k|d$1&-swT~wiOrgbxOiIjY(-}?=}xL4O@)m$S!1Y`m4D{7&uF-3)!V~* z9qoC~9*P?SK0bBE_y76z3Pt~MZ35CI3ND8&*~sTypHfOEW?Iu5w)6>ZD|(bDt>w0=V`eyn5j$ixHVC2h5=_D z8Ou(OGZ3V88|K`6l=#bmE8Up4UH-aHx36)(hi}b7n^x7|YX(Q(L ztJGlMPaj>C+7%n-Qhx-WOgAQB-^?A{dRk}j$L<5~9&_EG!k5JdpB6~x2)5*E_w#bU zBc@L8X?i;flBmJTV-?V|@Ezk@_jm1`ri*jkU;g*>OwtkR%rUkJk}QTsiuQelRV}Nk zX)KQoe5JM_(bH|l^ZqV$Tg`{cJSC?SC`He~uO(RbcPJyxi*|b+>VN&jz$2w$(Z35u z%N-oZUyB6CH`Ho#j^EtO_S7uviDJa6@PFxt%Lzp7fk$K%8U zvH^&t+y_eC`*1zi$8YB?_>y(~`&xrq)~40}cElp&%3BYLudk?MTch&t1nuExRV+gH zzQ0Bt-ZDOIja2SZj)$WDJ-G`!SKg}smKlFJF%H`PR?w^0^?}@_?0*ts+5CLgOFfyo zL;i*JZ&2eY);9Fm`hED-=l6W&76Hr%bu^rw!{)o42aEcTsiA-|swLIe#Uo zJ@kJ@oI!8&pR`QV&Z?_3TqQ!^!3J%67PsM!?!c~jq`BqUUv7Io5vJ?7CEdVi_iJ_S zmIVtm!B|1enL6}by_gg_^5FW?bh``dwc8@GH}HBOE{ol)3VLd|d2dnN+6R;cGMxty zqmMK70uLlL=ylxov&&i;>hfXlqAemDt?rsP)Y6?6uyRL_lY&J8&}|~@jW;^Y>o8fS zCzmD%H=vV-u#e_e`PseQ(jJmtxF;v6AKYQ>#vOIj-1S19bT8UUtuNRS%7FEB3~d+} z9@2T94DPb<((rS0;hw8A#{Nkr!rm;2@Y`wBEB0BEeq>KpQm`Qiz+O|86L*L9E_dDM z$VQ*=&GN2Cʅ&2fm?ex%rQ@tphzSxHL`K|I;CS=3#vi;%rVWm{rBYLD;pm>u%{ z#Z^V>!ZnnGB>|-YdhT1sQOVl6+uSGr{Qe2w`rV;9&u-T&LyN5e>rb@Z>M);6IPS@x z_V5mkROIgl|F}f&U_NMKu50wGYYD%X`0ZbNvxHo{&z5F;zi{JiPsOl<8Yo!MuoTdQcg9b@=t&*%2-K=h`tU z1MIw~&zu)fodb<#mIq&&cTGKZD|!0N-cO(Q2s%rT@g5$><)SVZc*Lg%osWF=^kP(F z?wSSb!>(sUG-aEEemaPdonj^%ol}1wK9+r@A#=qlVu4%W)wp%l+_uUI)#vAk?-LWH z*HZ(V3gMF1@L%`ejew!VKYucAL%KH_8D-f^088Iw*#mItGUHR{*bNEU;)U(pxl5q| z?UvG24d=OS^PM97tyoK8qC1Z(f;;PBf{s~>ArYS6KELSffki*vk+lkA+pYRJzV2n6 zYC9N@vbGb?^AR%A+08dIb#N$udc){ITUE3C(^Fd0!E#FXic8`ix*d5mC!^(ny<)7bAiJ=!t`x*`B?>3KL{Y+MU*wTWN z=${WaoM~Wo=eW=Aj*W~Gl2-*fZMf0=S$x_8>wBO{F<;-2FV6kmdviJ}W04^k$UEbo zp1peW=1Z1mQ*HI}g$Q6Q(@@5!BAt)KTgBHPTk~i(LGPD1^X8-e&D zlZ!IAttQwTp|h0vp0zDhWwp@-VK*f2NbX86Z7WK4nI$HsFb&?c|444$8_+?ihO1_n z*l#M|ft42b@!C(MWgnZje8X0wf$GPU75hA7cTW_1)^58ZiT)S5-FTq^W1CTm&(F`)Jh43FCVP8-MQGM< zF1IzGZ0Ek^+hE0eZ}qQVU)lsM>*?iz2R-7i;J%9fDN4@182zlq z99&~C1iR2Q%Z_>~L#-e4?w@0WiMtoMC;kbEHc0=cDXz#e!!JJDuk)mzX|4_Vb@BC0 zmt)MIw1v3%FSKD~!A^zh=Q`$h>+4-!rIoqBM)Bm>dKy5$Y!dc>>m7q|yorGrTtgl*>*#-E}e>pSBXl$;$6|54?e?|ZnB zegqnQHgPh+id4N09(jM!7^)y|o_=l~+U{%oNzasm#ckj$9JcP2Xx~k?*4m@ZV zg9q$y3Ra4iH@&(HS6Sy-zL{x7sWdA2X;85F&FHztL+;zJK(-`ThYk*52*u17qRT3g z>_+G0m-|G$jz_^)M}mZ6x2<0nUR?Tn$1m0S&6|hz>ZU2A!E+lrLD>lgr!Hk&M040ct{-)q=D6ri7*0NiEuF1t>Ru}Z(~#q>wUU8cFd zFP?UxzO7hr{mZxM8H+A?Rv7uD87;2Xrj-f!!e^@a^`iVG>yxu{PPZ~s9z6TT{$2eL zS7cK4BpraYH&yJijxrlUeqEB*?NjV;FN-g4;U6(7F}2@xEVxh-crD!YxX+k(162Oc zsi3)?2l(e1Z+@jj0a%iu>jzua$~|{hdNU@X^`J>&Xx(1zyGweT9)$8I&pZDZy^lHj!+)nJH1MIJNe3U;1U9L~ICd&P5e)c_|v2LQ6_Gqy5Q`)Ml#e$Qp zD?7Dyag4h1e4XcqlY(dGHfEp4oT_dKc&IgfMp5GApTWeI#Ay43zWSf_(;h8=H~uW? zYeK2?c$rLlxoL?8rZZoBhF=#O8m&$((-AzqT=>uRXTD!QKA&&gVm$AQen)Y`WC^Vl zVx@n4OTz@N=&gPCi4!H{7wH0d$(Ejx#;kSI2ce&~Pk#PP)$TmC+g|kY%5E#!&fc51 zt!+j^?dH7iTGCl>e@v$|YUtd-4V9+N``4yIkH#CWp`h*;{`rE@wi=<-;9M^rb}Om1EJx^<=OopQq*1$vn9E? z@6BXu@xFO4QOgZSGuk-1xPpbbU63cz;~9a;`u+?Z!N;@f1u3V)TeRSE-eRVFiOIg{ z9J>|mCI!A}%Pepk1MK%`U1Qob873b_h%1==LFXc8M&bvzm+J~%-`I=zzV^o@+nG4} z&AJ?uTMyl5XRSdlp=Fk{Dwy>P>dTLm>j+xxf1ZnLvKi|xmDjU6cBH`1vTKmZwxP9i zZ5cM(_Tx*>$T(JZ4X}%OmqV{e7j)15lQff|Sh-&@2f1yptY`jxfSjLag8)3?Ky;zK z(2gWRG}o2v)7>yjQf-xU72I5BFt{+Jr1Pxl^)>sJAEo8>&1p&2-}(xg zZ1kfkyMD&0y`NHQcSAS7z2lL(3|44V(m*UQ51N3iu*w~JGB%SLyJ(wVVkJ%cqP#(? zJjjhgtLH!S___iTYIW+F_*D}(nNeh^mGCRI(kAp*l>GA%nD~`(eNywAiJ>36lRj-M z_TDe+v1u3X(s`aaO*dV;KY_eF-7fp|aKv3~f@QZq@m06Z;L|;>Hk6v$X5DO>RfUe= z_NXJkLC$f1#%JD}_aQ?ZFP%9nx7_ot|Lg4wejZqP`#_=HVW+p1H`{5?&dF})lJo*< zOFwnggxy|YSE|O*1ba&J(u-Bawu3{a_C22af4Ow(cK}YphIA}7)Wk~5C}y3O{zBd6 zi-zxBKYlQ5W)p1mW4Q2HY5t05CI#i5P38#X>;utW4UaFn7~4E^JtE3~k!r94gw5I0 zt;+DDIz7h^ZC|MhxNCdCv&RhI`Dn{Au%lo9`TLvp0!$p$UL0C8X!><2#P}){kNl-9 zeARF&em;yK^j|Ug$hwSy-Z6twlu>ja>U+Z-1hO`y&x^a4gytCrD{CxA7yL9`<@F0* zIIH7);^gfEi0h0YWxG_j+3ev}#n470n{L8~=TUQ@!tUKAo5&rmr#4&|ojf=2&#aE7 zN2Vk3pVlh@tN3{B;^t3@!C-ll5_+W|jutHgYH=hbp;@g(1QhdCXY4A};G zwo>bxrDyVS&sr|98=;|R<)TA@EBs2&Wc}&R1>V}0Mc@p!A?53vYj{eZQ0hQKbKlm?tlv)TE!^3)w-9PopgFZ zkteyxEq>mPI`4BQPkk0!3{1NW5M;CbV>d)E@Tg{TaK;urzBm~IPKBx#yVIVvTW3Ad zGCI3 zN!mWi)xzN=4<-7!hPk0#GycP!Oyi*Fr_09Xceez0#Rb-m=)C-Iy!U1)cQ=4c`>iz{ z6y%XQR+j|8$PL#x?>pFhT3ck`rP;IGt|{~r+RRq^R93F%9mQu)`ybDdV6gYipYCqo zBW1~zpUz6(=!GDlrfCq^HpQ*{doU1Xfo2k?nz?oUhj=Xok$C$jVdD`y|BJ(mC@L*hx|K!1xsH_9ywU!Oq(a@wg_SZ zvGVoEr{Yw@jkEi)Vb9Bt>O3!)T6g1Km7TiHaW5YoaUK5Eq^jHU=``(PdBe*8iTY+Z za-A%DTS1h(&_=OWyeZg5ucQl_8*0*gJ}_T{p56YgVimc~Zr*-y;hSC>oZAY361gaU z_rm?7v$PHDD^S~FJKbJ0RaqL)Ip0jv>Hy{IT?3$prV;@dqp8UN8CE^ieByt8=*nU( z(W~0-q){ojU+gMP|Gzg0DSx8YIfxQnb7W_NjtfC*I!=o3J4d5}YaNmX`uD84zUskO zwGaQW_H^Pbim|?SHTlw-1{aWek(7BIcgdZvh{ubY?&8~^gDZ{8Z!CV*S7 z{tM_;rfqiPJZ;9_2R_H|@6ohY^%XVTx0~^U;PGOa1^iOm0qy>M*#pLxubFH%Z`|?Zd ztlv_>ilplWjZ>pQuU4d~>G7@iGP&eeooaopAmu9)Ge(h{)l1dUtF#ngtxxonjLyEb{PvNqzSN}iVM+Nb_WG*d4rngX{)%?hb!w@-VCQ$4YHM-p zr>!Bqnq9oyHEt#QUWRX$h0k|eNOw2*aMP6spZ6uLo|-0j?Xe(CMD~FYgU2? z-8b8^$$C3LR>`yLw|tuizN!DnlktB8D(@jkp$X1{y`B4#&P;7Sr}TZ}?geVMCTKD7 zMVsmq_E`Dt-`r6`_RX_3e%n@46(%XD#bNacz6EXwbjG6OY%9Ox@(+*UvG3*|N2P76iGBuPn2B<iUNB`V!jFCYTGCnSNW}#I)H9gRGmppSc z*G$z43zFY~^)x$Fb^EF^@Ow@BW)+#WbF1C0%di%d@rFBT3nat6UTc{be1FSQ^o=_N zxwA5tRlhg@m#~&0q&k2%p*>47Fmv++{D@?<4=e1szTCsZV})LBzMUNoKy13aPCcgY z67@Kso$J~c5|omiSLwBVhF4$Pp|*^9j@&m5?-I_r8#!#7I>}J^=jP@Z#f;DX$5z|w zAjgW=UCptDt?}BXgF9i#SaYHcl^@Z9Z*G=+c)SkWar$mkd-^TQTC&uc-;Qb`?V7jT zV=*~MlKllR5#=7>$(FxuJ^C}vv#Gviyy)8VZrhx^wT7nw3_jC&nt4&6n@aaBthKGv z4BS}er|hJHseyBUvs->7e`?^2Y_{~dDn17U3$y(T0GpMGzWwJsm>MN{1pvpE(yW^N zjQAk_+LFwyPjFB8^MiYlV`@iV>tE;*YNdwp{_$*j3TFO3SA|GkX_>yeF>ehO?XC+J z1!=6_C!=6vVr9)tpYaG+lF_}B9!)0)+fU90+|md+%s%Au{EytqIiQQIo#VHD`|J*R zTba)OX=1LvP~v;w8pNb^*{s5<$wU`N=ds1)xYu9%pH#zd@m9{ZL?=8t6M+BD)gfE4t&#Q@09DGv#9NnA4%V7Djd|DT!?~53 zweTXeXe~T;XKYa4S@qbUK)$x*cK3HZJa_u+0A8z0sj&2Z|2f4o|E&d(Gi3aR7kkfZ zyKK3s{^%aFOm=GPui;+CX#2h1&m@v(54A^_v z4DTz|r|?Hgt*3FGk^ktJtO5NIv-HtGIl43#OFD(}8hdDeH375hbMf%I5vnFrS8X-^ z{a%%zbItn$C(p^pbRyago4G0`wSqWs)!X9}!tuU@@28R`KdcZvzp@)$k#O(F?5>!f zt?`z)MFs$1-pkOtMqBPTFvq7#Yk}nLb7SW-VT)JI{5f#$nsP+{#YD#K!MRuGuPZg( zP;+KG^nswH?S%05{@;>;&&U%$+!n9S{G1E`@tY@w16h`mttWi-F!S2JfB~uUXPrQPS*@IARoi^*ihLTX)|)3q6p^*>T|vwZyn2@pl2cclgkg z%W``&x2?yO{wsQx?%ppZ*M(hE?@^AhZYwr#`9-R5)?~XS)cvm?9J$0Joz|Wh6P|kd z{TSIkV11a5%tUmf=bPEpZLQr{ZB}`Jdefsx&#<3nKdT3Ri=MkGdb`yEC2dWGu$(RXP}aK5V&~ zzHV7^&d`!gRadLW7oNI;eNn|XnrqLY|<3I}E<-T?v@FUAu(yp~`DTDgkhIw6= zU>1`8^*v>c>Pl?C$^HjROC!$GZx=LXxokJG$tnYbuUp>OH+rV{&N*p{1rFr{jkY7* zx;E5%=E-^ajN?9g(%XA3c~z~So7b1_x!eOdc@qBA1Pge?bCI`2ziK#F z9%*-O>5TvchZD}^L8jiL{o%iIPhM8C=31aLlJY&|0V{m=qF5~qaaA8pXRz=6Zb8e1 zkTc?#kx_gfptWFa(Ue;ufEEE1n{BTed1ZB4TKSqJg{;n(*Sp#~pcU)|WZU}ADW)RSiT=Ixtrt4^PjCRa@i+z3{VYja$O9==ID z`@0LdZ`~1wfkA0r#+=&H68rDBdip3VQl-E(1aZ;Bv#6&0aMH5w_Og2JI?@7=l0>Ch z{OCP;VgBCFL8<pXtOJBoxq&lehdEfLx|N0sSc0{_)lI@;+t58h0g`Lc4s~F zeq67}zISiT_KX@;*ZNyd(>nm@0>RwRA40C@I)U-Fi);Jy+dx7!xqI%~?2(BF!2$nU z{yuD5bFvY_Eq=Uu$w23Bbcw`ZEy+AI=T08JH-B+)QL|=e4d1i8U|@z$zHte3-3NC2 zai_ubpWlX747WD`+N`AhOON}m?R9PeFR!e(*ZxHQz`3kjN;@4ca24?;q4RWc*Bv-l z*To6N7u74v7TK>@=GjrQN#Hm5XM2OdRnS<{Em+!IV`UO}YcwI);P)06WaY=jS!?4D zC2cq{-8JravdQwDz3qijBRyYChnKsCRm63cP>gQRxZtyPXpwoPXIkvtJq!Hu`| z+L*IrrlM63-nFUdkLvBNxKK>*pY7IypK%ky{eE(2Fi>_oKI)-Sf*bwox%jn;vX#No!~6miFx93-Y)xFKErvwT*t99_SpkuX%Tt zeLH+jx=!Qm!LfQ4$iEAA<7-AEem1S1ep4@?J6qQfhyy@Ae%qX|gvzIdj*7YaE1&K? zy7ZLJKJ`RfeaSB*x3jVllX0h~_x=jIfK9o}#=TeGvOq9f2Ik5RUueAF{e_{u$p26+ zrQ$4>kk{v_yD53%RKzOh=wbJS@}PMSjS}|kwthV0>)lNnB6Ek8T}}9-=5vC)N_OVM zRFemOq1#hm9g-cG{&a27nLIVk^FirJkM|0mF0N*C3hgvhu05C?wJ*=UTRnR%$)a?G zVthNSf&OanqN{D&$BFJeUi!IxwedfEa2G3VF@(aWIJ!?!gbR-TaLJ!{g)2zw> zMNII5Yo+JEwjDErkI4vzaZ$s!l1pDc<uXf8QNQ97;`nIA zTf(O*X;J$AZ(-d=f2x^*V-1yo9*GByO3Z$*zA;p9I%uq4Jy9dNm3FpM4xH>}rL%lXhIe{jnxyZN zu5DPO$7$}f*6kWS$LE(@cHCe5XmfkXXI$zw*FOH`(v5MqlY5AzraLt{CA+TAbLN-) z^7&BA1Okk@`1&gzXWGVDWYudDokPgKQZ!l=vHNpp84OosdF-0%=S}#QKep0=`>C;f zs)hHCS-7IUD^?g^_s++~i-Fjvv>+ijLZmuWE;MY-e}btH>VkAjPNUV$#BY(4mQn;7 zADF5~J+NlYgZ)-VjoRE0zYD7uBp*H>yK`sNZdibw;i%1I%Ymv+)9*XiZRtqQ%gZdP87|-I z4o$8$C6sM4kQM!bNkfvW1+&igyfO!TsDXRI2jQ=GcpTk^!m-V)-&;X{#;Mjee}V7k4+ieYkBpOh~PtdgEIYGWZinZDS~zF_a|pR=xG?4$?dNu&Oz7) z0I98-SYNeb5sZ`e^kt6QVTjfBdr6xfbdDF~8R+M#FqvT6gotCSxmOkd7`adTcZ>BbWn?a#hbt?8&aKu zm#(_?Tmu^tL<-pEyY{Z-T0p%!W4`-keIR3z{HsvjzGk@HJ?lmuTb5-bTczRm7u+uF zDu12ehmRP2|91Y2NrRn8lv!}^e`{-o&dpK2D)8xTO~I!wa&gR#;1e|L9ewzVV6qUP z_=iQhT3IFkt+C#TATvEV%THOX{NH)j-PzWNgVXP>bEE3oy0Vvnrb)_QT(jzK-J+Jw zEZB(1R8;+b{#&YwH$$(?J^*9gd5{WU<9EX~yfvxpw1yHF+73&jLGNYg8l7FQ<&xO4 z{`_a%%U*4300#@3#opu{2&j%*-g^f2B_Y7SLN?CRknA6d_qqQoV?Iwd`e(?EHeUqY#X9=C#M2%?VK0q*lk#l zWt&(uMXat!`IzjdY3#P6d$Ivhcsb>?-n|%_H|XCKyCh|`9Hc(VUE@9iX<5>TsWeDs zruX=bzsjsuG-#G4e+_QF`q=%JSs-5%z)L&lrgw1Hv`fPw8%_RG2TaRpbh){x5(lX3 zk{I3j#G3VBDC7-$-9fe@_XB%sNyIO#p1B^ZXQ^Hs6sLW7ey>Tv>P5F{df-mRmD64~ zJ+|^puKxVw+yJ1YE2o(MS`Yp1>3?DGM(eCzRY*YSMK5M)jfu4Cjzv&))%z15R$ z8$F(PQn2#y<~a;24Q+l|JJmY)0C?{TyP;rt!`IEh#ygE;4SN|N1>$ z)9}GYe$S9%=;bRwWu_WgrH|*GzZbKhH)Jl%JJeP)EU|iP>4F69x;0TwXu#;+1hnVK zBjUz*%CS`Jy^O_@k53%$q#OIiC-gTPHzF3S_Mau2xqofYHXv}?3?x3`mAC)g(a3!o z_AU=R$MQKi`13BG5I6m1*X_EbhK<^2C?6jU%5f^{{?@A1R@n)YmAP zcFtXT9B|g4XLbxm0Zx#7H7>fNBAD^po!@=}Hw=VKpNE;-Y)Ms{+-dcxhnIoj^!YK` zFZufJp+hHk47BP2Vw-0ABUa^HYd<*?8>-WSMV9WEESy&)8xuM@-U;k?x5b5+jEXI@sonO70kUz`NIw<*RHD@+d{BqgZ zc*W20=!G_$nS4Gc82FRMz$5q4azdCwGF-E9C`m>G9VFcyqflzPuKA9 zKyS4faMg|Zi1Qn0HQ!Dc0JeEYW@aXHadou$3`Sw}?4kO}Kga?%m4kA4vz5QG9UVk- zh+)u0Gh;u1X5;qu)mQI<3p#877GLhjz8Apx{JeI%j-F8wr)9t3B<{}Ox1K~yopR)# z`ozS5GWuNmuP5AZwO55D?E;nig zHHITY8lsTX+89w4YklL0bT}2ra?VKeB97oK%^8&;IH~1nOdnQ9Gbp%9AV)i?gRB`A zy|{AHGV*=v_haen`7R|U0{=S6!6nC zzgmUg+EM!Zd95t517=tP$mLg8hptoO!8mHPc#v^GF8B=Yukm?@THSy6*(Gt+<e^Y8H!CM~`)_k?tFj=FN}x^F2|8^r>c{rp(6YjT1klZGy0bgD)%~mO!m}GJSwj%z^bly`M(Vl1lDI;$GwArd=gp25&F0E2CO+!K52s?aapKRvbCocQbR-sQoe zGO&a@>eDV`H`)c1%s=5d_OY9qb|Cu5KO^sIiF&Ox*r+{@T*cHT%i3 zbxh}r71qQQT@#xh+4XUs4jautXjcKGbTr>SSY+V|gq4(M^lFP$nS(7`4krBk1RE1u zcv|6dNo6#P$X0+m*QaIZj-_wkH@F}?w+0N@nWy_d0jI$ffBG|F;(^4gF|W2gU7cHT zAI#O1%i5d|mxQ6sxZHBlr)QUl{eGeK388xYUZf?i#=|P;MO2m_TK7ppCZX-&1+ z-+yT`VG4_GX?z3+M^8qXp-zaNUp{7Z&I(o%^Xishcg5zL+i>?Imf~wBB9;)*Yj zop6(VwAtCe)&*~?-m|*OcHbQ_!n-*+`;)&R>5Si>OLf_v1s`)d;Z4ceJCxW(2R^xF zK@g}5C)%=;?Cn^iS9A=myXP$o|MH)Q46N=m-^`l!?-$lK?Y6K|h3MdV>%$z* zYVpfD<=7zY1`t<{t_oIG-?i@V8v^?YC3s7A>Utv!6-Am#YMc$X>cYL8ZbiI;UEFli z=wY@DRTHu0|7h<$qoUfHc2T-%qDV$T$(aU0K#)w6X<~~6QG!SkL{UI;Xiy}m^b-BVjXK53Nj zda59;ibHtOw<1D-F~T`d-!S;5=L6W`bBtU&xkH(ed5tEeubd7JW5Pf9b53if=Yh7! zaOS)g^A!ce?!^2TyHm$UTZO`}rI@k$1?EP0VjNDHj@CN{q$YbhTNWivw&6Lm8cNkh z<@cS)M=nnJ_ls*#ewGDa3KH*r4!?ZT+sCHLY-?diI{CA}sk9YZF+b&NhRAhnW&d`a z6Dj`~Gb$4|L_MsjXP!Sf*UtJqD88d8^J!hrmsKrLzOkp+qt5SAiSIQT&)sK7Ib&Q` zzwHRyewj#>JNZ?8$d2)_JW2vW_`be8TE9=LkNmVm2!iYyNQ80Ku0xznt%WT#Ay{tp zm+RF10KZT^I;iw{#WY53I-8z8P6MHrExi+~*tby31OB{l$k25dN476M=m-d#JQm0a zIP(@Cy&MJhqEziZPZ=-eGcL}%qv?4@)%BPsbZI0>D@!|;vm*F_Cg-8lRFxIbgHj$u zsf6#By>M6MIv{tC%QRI%`xz*&rr!_ZZP`h%ozw=5M#$4N?XLn7L{y zFU7BHc2>Hdt6e!7;|=)bVWVHUgH&@Dr$gy|*{Nojv+>EGTC(y$hW+EXCj~ z%W`?_dJ<2Cqa~hCV$`KApzvelvT-{Q~Kd zBFGsfPWhlucAI@roD1EH;CD{eZw(GSc~gez?!3+h@x)-vgRHX6^}bctLNIGe67zm- z(SW*WFpT%eQHTd(`lkn~`WiVzf*^QLGo~9E7D&9~!f9Im>HvVpn&)!&Q~3dm^z6n+ ze_O~m9FhmQQHGQk@4AK^TSej*;g?sUSx#Po$Gl+``j&t}wl?YiytVVFU;u`PU2Tx~ zrNEDHU;P~YnBmZYiDxzmBr~P*yD<;+J*cv%V;VEG^m*n+M8db)QY!72q6n@%LWea! zyBE&%Df_H<`iyYaooSFY_{UjK+l%Nt>V-X+?M0-QX(FhdbUEcT%NL82B2K|svRr?x^sd7_hBoeSTWCaTJ~ z4&cC9AJs7S`b!J&_!INbA7}Oo3c}WlqKL5OLn$KXf`)>6;1|aAUEkSvAn3U;+7Jb} z6wwvAKGTk2kAk|LF+jjSAOea%bV_!85h?INuyym7kIh{0zox%HR1pl)2lgW4+@Hlc zyIfP3ovrGx54qCvti87`XICD+)TtEVQ|Xpoe= z7S`=aTXnY~tcPbTU4RZ+cK5WCQ8Rxe{qN7zr_6Sl|D{>Ug2PM86`+N-L&C3jL(2w? zhY>Rs{~+6a*N>^3JkeJHgIzFx+Hw7oJ@PPiE5wQY$F%$%?AP%Dr1`&V_t9quOIhlC z7Gp||7u|-!uJ$y^J1$$UZ86J*Zf(cxbCn_KS}L!T4JKO3(P6aKlLCrMUce^3@3Uyr zoq3cFG9Y=7ZiUajb> zaMQA%fj>89^jh5_27XO;FbS9_J>Y?JEX!`WhicXk{J49oU0E(H5%sA_jDkK!XHv%_ z#VvwwH(&DRu60>-<;jQCceHOJm269(u7k2b3>09|6rUTeIe(%lP~PcfMgcy=lFA~F zm6ZQ93*-+yV?bF7q9uoDT*tSO44HFT5NEDHc19g42rvCuvKwg(*pC$Wfx#o42f!IJ7yWL8WGN5%`y(=>$zdsKy~3q51hug(OJ2ppNcStm@B; zdU;TacFV?=9+Y5%stiRmY*KmNU*03jPWYdvLoPu0{I*i3+UX^|qPJV}HslT63^I;% zh=eArV$I7VsadeaKUqMqs9c*0)lr6>6Z9Xz4`%-iV-1BVS3%Y3RiL^y$q} z=23tC)DK85b68`dSwoBSO5uW%ehNRz0szZpft|5o1egJuB5B(Cs)!WI*}sS}TMSuQ zUY0y>`|^#XAK9~1+u$e&&#@Z|110@Jylt6PL)tfYctZ1bfrZo`U_t!#bBhi#Pc%O& zT@+ngW1?`5kf{j{4vroN`Tc-wX`?QjoYqkLR9$Y$T?@bGFY^?Bo!E#Q!cvQwJo+Z1 zCYXDHc3A#V?|vjvdm@Gmbj)k8+mIu+oTl8a1H}*?4hmU-EYV@TTCRFCKOg5uP+BtCO|mtSGv;dG38+jtkn-+DXO$+$R3+MRST`+qMi0lla?DQyT^1-Ib2Bf6}z0@ zh`FeHr`=4KG`>X_=A_-{-E`@nhkt(%|hdz|+e@A0bWwksH2oGMu3 zop;xYoM0AMrRArdhMKsQ49&F3*v@mE@uamLQ|b@SzCN-D##jQOM+A;zZL!9j>q6Fb zUKx+tsPQfRF!*jZ)L+q=M>Ov2N=8=cVVZD$+s+!SK+#NBYV3xI-B|l^U2ZwV_&+EA zD<}yQINfzF!C?t>xmQIh@e&Q+HcUDa1op&WHB!6*R_4MRQR#-t4p-fc zV3D$$tXpOK;l?%&Pc0;11zDOXKMg%$jB60YV^URXzRTdHeBVEC!5>P(+_kD@T&gni zYfj?N?c!>(#U^oEjwB%4m0kAtcAdLzbMt@tuVPIsqY0V;?O zl9fMz@-gKAo2~(z+3UK?=O%lyPgQrxU7j~>Imh6p%JcNQzRR^#mh?EV%U7?U5oQuz zZ(XrP)oq@HS5UaHHb2-g~mfEeZ&> zJ5Yw8n9O1uG9nz-fbXvP^uTYVMuH&be>o)5fSv1th-IW2o6Qs&S?MCm39?uA;6BJ%`?Dc$*$I=6@iJm-6I zln=tP(wzV)Oer)Iz=kqDNtl4L`^UjM3Z-y^i@}gmHnUyZzGVlSkKufIzZfzFwy4-G zM6e8o+WK7?kVpvIRZ0ORA6!vMkx{x)Wh)t-sS

        d}T^VV=Lgu26Gt&^u_>exlSQs zeb?*ffJ$Ul_J4pq>e$K5EN*q;yui<&TZ^ujb!$X=b5�B<)KpWTAHAawCU=*N>~g z_1<5Ssp#MPM;8QtUx**->Wd?P?!=6wL@e9hn#Fe8R0$hTS_vjG2D+IsT51DrD=HGME*oVl08K`ft7IvB%GEIA$gwKt z;ZbRFLR#zBYPVGsx1SR3& z@tK(jh^KgLn*t#h;dGC6a;_GdNt^+m5Npxtt$Wwv%ln6tK3}bL!y0yu`<{DKehe*C zd%TL}tRe*X6n^!-x?kj_IeSv5vPc~RUZO(mdo9DnoSo1)Vg$9DU7y-o^6@Q80Hd4bW!0EJVfCBnW7| znld-z@s84CW#$zF6Wc4MqpxmhB$IS}rUjlRr}a7*&3ne<_@IQhM}juJfGX1&qvU(Mxz_9-voq8u| zLhhA|T_T=+4gcMC}BM8ReX-I3+`IH)N}rLj)ZX$z9)7PlRiG? zJ{}&-{2=hr@#Rmr!BSkAdCSfgam35#3pz)IEcgd1O_fVGoiUC=`fUa2^vgX#A%5h$ zU^reXWjv_NpbS@$N#=UCGLV(_gJlcQU_Ve<+TaJ{OMTg~i4mK9d6RE5(iJu`SJ+ zLaHb}cgpV%G;-c0<~lHN`foR7Qznf#I40w1hd(-QeSI%;x`p^lNZfc`%yQ+Iqw;w% z-^OVW6Hx~na4M0^zon3Mmkl04faAm+qnUkEcuBv6g@Fx{gGNi%GCm4S^c9~7$pBsJVlM7Yw?pBp>-S+*p&$ekTM9d#*XSHc60-kK@a=Rh3 z@J#%!*^#Auk=xDfspme#$>;o#oT{zb%WvDdlGe;Zcd99A+v)~;6;>c*ZTqJ39l4>E z42Oq!+MygKm%gna!zWZp4PQ&O_x{qk<#^e3Na|Pq3Y+u|-d1nj7D*5hwcl8oTn;(V zJ9`E3xeC)XF2!OK4bH{LHijC;3IpjmhUs^JR1>krMy2!L#2Y>?C+aM=;mvzRzy z6y;L=4YZ@LoYX9h&V>x%)^lmK#sWnwweFM~8)X9aw1+?8ne6 zs-p#YcON%C-u`=n(4$g`IYDB*D`Wg|;M-wUTdea1hwijvJKHa#CUkaIGpdTTa@bv# zr@sX{VC%b&*muFRAtB|%M%KBM_UCn&0# zJO|-PZBP@l@C!N1FsLiuef)(dELLrQW=owkaf?z(HAiV(V?=H=H%m9vqdP%B7iawY zWwF_+y?Oc9SmimRm%3w}dx=$!p?eP!eV4a~4@i^8<#H_yP^Bp!eD{DVk{;EbN;mtC zA(FA}*U=gCO7ckx+{6nCa@xt>LOD*6lqE0pczRh*OH6Zk(NkgRSudh%JXVAdLxF8r z)zHLG7MmaXRRdOxoQ|ARm0ZwpCAFAUl6c_*N$rzl5mM6!$cn4<*8QHrMbYQvDPX&uNnV;y)^tqL@2M`(|=U z*FSH4xBIB_E4gTSVn?9V@L--M)mU{e`}cSO*b&5~9y1?j-OxU}t888hxQDvQuy~{_ zqZ>SBIt6+g`bp*3Mt`yg=P0~pNwO5CnmhSl)cgD#zRY_pWM@jks`(eKLnmhK>t25S z>Bp5~YUmsT?gr1n4?`eCW3?mCrX?IQ5g_Ya#<@tUZmyx4exTpgvCO{hwT*Tl)B9QB z{bg)x>D!^hK?)b=7!UhDm}siPQ29!s4o#OTuEOCtTt}n8k#{m*58hj7-$USe+rk8e8{$`tD2n%$B%r5!^B!by4VI#snwWWBJcF&* zs*NkFJy7%JWyn4J{g{ofXR_6nD}-g41-wFRz-`aZ%QxsK+*hR^M9<+r|pZ~kpj9c zG>|6M;3R|j9_#$ae0%6#+<-fDjU(x6($q5-nU5$V#-btuUl@lcp$ zfvp$Waq0hgz)Ry#FD-x4dc+v|iW1tpl_b#wiC1R(K#Q%{q;S19h-*wcAb)|wK&@_m zjM4hLUU>_cJca7N->dLy;6|71091(6OV}ulH25*St+dsF6zejGhBPM60G96ZtOoP9;I zGr2#LgB=nnPad9o8>i&wVP^8o0Upqvqg?NLYW`zmz@zsWUAd~w^EyzvZaQQeyg>%R zO3NLcSfmvgk}ZwpQZ*MPKzw^_rw%&5ApsiH*caD%&h%8w>m~40ndIw+g8E669JD7d zfJzux@A89|XoT~+nE;Hn12@idk?@*=HcAUZF%IjD7r{NX(1TIw#~-%?MnmJt#&}wM zwE!IKNoNQ_RoUkWwNPq(nkB6ayIa#^?7?cYe;FF) zzlRLkwyUlTBE!&N#vND(iz(eG+>rhax65re5AJ_@ZSPjG{Lo4?vk2oEcx_9Ih-?$Y zxks3ap`9N$B*A=lHf11YE~=ToM$2&^9|y9+18}mBl{xZSR4F^xYX^iTe0CqI5@_09 z>5APHsrokll;UCZWjIX4USJXmCSAr`!+Sn`d+d=_#zQ9$7E$EMzuBd%Lv|7bBpMdg zsS*&pB&?IIaCzX)Ca-EJnd_@OHCHWdbGwCD=+aPn=&6=v|n!G=#xI!v{If=^L)c zbM7Vvcez>;bjA)Tbv#KhJLJ4lum1E&cBcnom13RAv&Y*F`?DI#_yxNIzDO0$ON!A; zc%_x1xu(hNxNg|l#dK|SbQBv~2FdEuy>ppvTG6JRJbi*ulb~ny+4ty0^2DxtTKji* z@j(wG;I3_Z$8Ei%KZ@6Wr8(f+0#&?if#G+wJ)c zbYe@!GrMk#N_$KD-xs((`S5id*tihaQ?I_+`b@BAd}atu5IVTCz0J%tbT_%eA|U<~ zOe$Qk@Q4VY6U-d}(Cx@`%Kq`zYl5dC3s8f;K2Q;47>CH(?q&_oTsLq`l^2`2K=$JR zDTj8FE&bonZE9ir5BD_jSRFh%BPA0G|2{PrO&!=CE8o>S(mkJ;fM!8kQk$l=iccnH z?Sw6vo_mX`b=d_))PFy=g{63jsSp>QJ1!)%v`77Kq=UHpGgOSPGD$r1T8-1tEWy_R zi?Tv1PylK1cX0Af&lvghj-nt9u~MxZn)u@UdC$Aol&IlHx0C(>SfMQq+kFfbs~T}J zl$y(t+VsZ{GC$d7?!Pf|^gl4k6m`=0rN5&HdCtFv`TsVSfr%X^1y#|19=99i{qF(8 z{|Aft>DPP3{l20_Yq6@)t%praZk;iBdg)NB!GXe&Xpz)gS4=g3sZ%NV5 z_LR*Qa9TWAjOOkyP8y^GSahdfPNG*&e82=f%8`z2-OiagC7e3P!p2YQ=g;rW6rWlJ z^Qft*^8x8pfyhdJI?X;Gvhsb9cYUq!`g6*u3zEF}VG%L0r0Wt*CoVKBYuAonJ7_Zh zF;DHv>Ne!zfEVd^VJr6uc3LsfqPQOWp+WFG5$vd$s37Hq_@Zyih(10K#{hk5V>Rf+o zD*@etr9vu?-MPl#3y{fQj}i)4&cC;~wXYsB$=py{B-=Wt`fDTB%6rIh1*H9j1Hm;P zG%I-XvSyU*mXfs%Tn=Zy^o*hJmIj6N z@q$)YU=mDfJsdl_x)RGOo8G^>$ttPN8T`X;sMfP6{r-G^QLNX(yVq-yZ$_b~RJY04 zV#u!mONfO=Rc1fJ&9q8P3iRmHr0e#&vY@7vp5PT`+8ZxL600J@Ht$Je%i3Ul-7(?O z0@i&d@%{ODCcelz?=M(@_p;Th0Fx4+Z_+`@^^KX_gHNPGeg?`y)7+!s+Gm2rD_ zxZi!fBJ3+{R7rK?RIbIw?>2njXqA?5e6)*opT$=L-;X|gYg6w-t{2{~{C&j!n`+zL z&v)yME;R3W^OZmT#FS^wKnHo zGdTf0+pE>RD(9R+p@*>R)jlAH96vpans%<6Ov%g?t&0`03BY=+&Ak5x(65{P3-l?| z1)=gyVa3haJKyK7eA9O>x={b6<}q6DXv24))F=z3d*tlh5BmR-d23}aoB3JBd*K9} zs+$ZK+Q&%1cX=k;=K#;XQ?g>BpADLFcWr?Cf3*RfuDA5P>Yf#xx$~Ha zt&6fst@3hlgTjNprl0`7xq{SuXuA{Oer);98Bv>nx~v+%+hG2_~pnP@I>1iy&*B8d22bqC+b4iZvi189WU*9pXROXx$8YQ+ER7~jL0k( zp)W5_UQY0)%c>ie(LPoD`(U|czuW1VXyaW=Rmt%0qr5a8zCR;KSD`DhnAq2-uV8Q5 z$3U_Cerx#SPr*I=#Nvc4+|G*L`9SeuYR~&ZjRjJgXh{)I#pdT5#3cbE?-_kPi3zXgXVGX`I4eeFbc-< zAUJsW{L5;OqA_RC+Og`5Q>mECLk6+fS1-T#w+)jP+%AHa=!J)NsyWs2J}&fI3hY#G z4&Gq^^_J)h&VceEx&n3mEuhveO7j&SoHg4niHo+zW_kG$$k=x$LL_4MG@5*MBvPVW zH8V6J<;!9kG^=t@**E@kD#lc4Hiz5Vrr*6(=EBH35IJ!bPzj&c`o3rG(Z{vZ`a7~& z;t%HpzxaM(QPw@~9N<+r8@}J>aJI?#?abHf1Osc@0rzeeWeRK#v2Vu``@pn)&Lg|$ z##}tcf3AAANl=-}x-GFMxP)N(+IuS5BEz!m-KdDQRN&6~+n1}eCKK{AS@tOhY8NnJ zrDpX-XHRnHsYf2f??(?r9*H7WQIwXi-y$vQxi;(M$T3^XO&?3lxp=p=1k_^Mgr95u z#z5ch&lAAql|RfNUf0cpt0}qubv1TylQ5p|Og(p_6JV;lEIMR!uE;y$go8{d!XF-x zadk-9x9+3d$L(EXW_|@fHh#Qf5R=hE$%HYbwBw&sCmx6w1k;QYIK@>Lq1_x+&?Qw@ zB;Y;wGZpGPyT8(3FBi&-2%MKXz3{!9B7vLea8Blllk{^M6pOkrzK%XmJ0FipQYLf^ zyx=<3D5!Ad9_%lZgKymZ8^I8Jzc_&-LE{-_->o>Xsd$8~=g3^A&^PLLF|Rj}#^J*0 zUptUTx*62b#|8BBgKLU*n73a^P>^!z|OK(kpi>rOx=GyzhoeSv$*)+i_26{#<){?>GsF@KF{lqxk*AVQs$eKjjuiH1*^vM zEIfbDUt7d1WiygWWXH9h(=KmOcOr}glfaiJVf}_w=X~Z|mq}U2x^TuD%3}IY+I`_9 zGQ5U>FG8trt3ZTzx+&xC4D%&55_AW{St!Ia$drBAaN=aFm$0EO*)h0K?Bwo+TK~Eb zIZgM7xObQ}vTo?=pX{9D_dK#V;VSdP1FF>UkgBAA4NNQO9h)5rWr6ubC4zVrEZz4_ zp8w*$0sK6M@0-MJ1}+~;=)V{7P?X*Nv=(zQN`h%$yqjSiPP(J|Iba+jKQ>R{@>xDU z!AjY^(^FIF?&EU>5w7zeH+JHUlW%mJh?bh#6lkV_b&VWAj(7%p?C_7{U{b19oWU}citg;M+TFGjAAL24>!p~lCc zmfZ!u8(Qbh;38Di2vsbys`iqD`FMJCXM5NF2YoSga{^p zS5IhW5_^<_08e`K8y?l#QmZQd4sbOUDt`H8n8JzFJZh}mf16PxsDLYQHa0nv)6-I` z%(o8D8w@;f>DRPRoed}IC7CjM)6nBvIu9R*lasf*pvrM+7w?{ck03B& zlW{d|HI5JQ)(lu+)9+{8FfTr)s-T|qD9K0 zFs4T)B8V&87ij1?F+7IWINZ>a<9}9x6|HA1<33OvZ(2-v((<}D1Ekb?&^mLnyt*fP z&qBI$PCUGu6aL>8Hulsbp~i7zWdYleorg#&xzH&4r0Xe=xF-Qqtq<60Vza+#er|NX zwb!xE(1ytbeFu;ongAA08rJ=$jWMlyrhd=)Ul3r|j53@@+ff(8rybsa-xq=Ivq_)= z?}VNThajczTk?vLfdC2I6t3VOYP5BYSX-fRUiZ04GEk$;GqKy*Agh(k95gC3t&T$7QfIc{w>T(Vmt$ z`>1=)Y?;Y}3W$_+p*?NBdBw@;$wfc_w%!Zxcz{GGFa?>@SAhQgmA9n{2$TeURTrqv z3jk^LLHN-qeM!xU8jaP>5UFV+iRXPx1Fh#A>3IL_l*h~jNcP1KU#K^vm7k1zjCKW` znv=P%t(y{5Nw2P0vG58|6-RLTw@2QAFsuvyz7&JTw~Y?av{njWyWhh77Y2&oKltPV ziJ}1+=tssa(1$?c*N+#f-83M1$?R4{nUQdKc1ub@TU@{8w*7{-rtb{X4nK)hVIcya zkqSs6Js1L@;KEW}(=8+jviA8P00Ckt^2w7Wel;9f%#jUpHtq!H6cHcpyoLDuKYMaN z8tUV%Z>wuL`+89=!rQ(nnwKJBE3R>kM)LG}Z>-8@@z9oO0x?7G((U`Ncg%#cF1C(3 z9?1^v3$Z{IzP-UF-A&W?!RMoODbeJ9zW&WCmm+=IpO|ePH<^xtRTCo zCVRlb{l5G5I`TVf{ogICj{CQzE_vCS7|fPi*T3nWEat}IadRe_(N)mMA@ZwM-%t*a zD6CtzGu!otO>Ml$^^S&pzV3fLx*SOjcxk%EMR0;QyR#I2`W;S3X@e4IByiwG;3i$HL5cNbD_F-GDh+1VQJiA)7FJPw4QUiDWT1&*^3-cmLyKmwA8u>Nn%uM zvSzX!ga#UO7O&Zg-`WJ6U)+H#EyD-r%aids$ET(l=i(8Gh3bsnUB$CBf=d?Y( zSQy}31ZQ_3>vQB_@8#8canULY?0Xp#*F`pNsU!EOl=gvXjQV35`*`w_(t1W`tJ0$L zRkz3KoI1{fa&&t5LfzG(>Z7@VD^Wu?D%3TPMyK-UdC7{Zs@gXF`WfIkniS3Ufih>7 zaTGL`e4V)Fiv3Im*ikPRf^!U1{ak3GDn{#RrS}N4ELywC-yu!$&(j0m2PqlwxeBFWF~CK!+*9T2^xF<2Tva3gz1Q@ zYRZ!48!=8XdBdUt?YQ~|ez5crWGKgfc@L*NrO1P%S1HtVkME}^crX2b=#kcL6pV~m zt+rau9^V^Q4b$x+dQ|c+}}RspHu3S;Zfa z3X2=)K2Af5#$LU8`rkYe3dKc9C|kZm1jL~KkH~3v0e4|*G|?j`f@%_Ip zr-#d*MzZli-huUBd52Q5bp|FQY>uhi<*y@_9v&VGM)!#jK?@R6P8zui~U0X7qcV>mTWoe_4?KHvNEDtN%T_11Jo*lq!!Y zJtUb9@z#?}=OR8;ref>*8ibmec39gZ(LgUoA1Q`@87!o{o4aTabyL2t?gFwV>%z8b4L0Y2%H`rv`3+ODG#Uc zTdLyM$4@hz3;3cKd}nV(Ox~^ks@KgbO6jZl`^Frsbf^gP{Mk#`qzK|5^7)y#ZJ{2#3;-cw`^S{QnQyNk~0vD4o~o7 z&^H_*nbe03PW=7b0ryi-s;Cc1;oJYsPpMH;?5>*Z(3NXAt3Ur>)0HNAf*RB1eol1f zUgrjkF$oGnT$M7hLkYVq)a?MTTWa9-&T

        Om`` zP77VkJU04sfAT9_B=@UjB&cpLT~UI>zX^fBt-7<8xV`zdIYqRx!Q^i3^nq15Aia_i z?x)ne;=trY^1BpH&dsqabQzAv91pbZL9w(IzjhWN64i0?l^7(8Udav}-A?u>d=^WG zuL&ZwQ|S83WMUtw;$=3I-mE@%7KoW%O!xYyyoLnqgaHm7U^p7QC1%@JPeQVn1FxxO zdVXW`bLCXs=ers>vK0IgOz5-S*Us3LL{gz!M`EY_pk%*o;Op*pYoFgr+)Ed>K$pUY zL_FG9EEZOIN8pAXb`cy-7&Ab*ka~Zbbtzv$_KiE|yuq<#teL?8G;R~FY*>k&9ls57 zi~T`lH=7(D;S&Y>pyX)vd>g2>uJ^nHQ}=0qyv?Hv+3X?P%Sf`9 zKsd!$l;sh<2A#E_L|3?Az3ARO0oUuPXzlr`W52hPI*>@=Q^wyR!EK7O`46! z?rue|V(DWF=fEs3wgclM3I$aOiN-3HrC;7xuuQ^H%$BXly`Sqi9XUhpNb?3&qdVT4+Onk zmDilf25gW?VC@nV7aNYRtgIx=KWa+y2DuXcLt^PNkWP~YsWu59iE4jB!6gRkoeFU> z+xUJ6)}%k&$=46|pF`cQbJ%!)uCfC@)p~QuBop6iF3 zxddcI?^?QqK!#xu%{hzv_NtF}N z_kv6kdp4keX_3R@9Ijy@P0+HNXH4(GmT<$f!h{9$OoeZ9sg8<$X%qiIRDryA^|M0h zi`b^MKF4Y>b6rrw)V(wD{AMC#^3!tHXJ2dlgaBF(D!BD-*k3{wXe;cI@tii;fR=Iv z0AN?%Hvcrs0h4C3B@GfezE|RnYbGZprUUwe-yvu73Gxg|I{+`BGTz0q4wUYQAg3?5abb@R1?G(+hlY1(>X1( z6|+e@wL^7jcaVR{iQ|{NIs{Ua-sgfCGCjx~Ue{g_IA;3^ejsvw13Q;__)CNqGCmgb z3(4=r!T9@`%X#tSF;4=i;9f0x>iYp0Ls$1g@vI9FuIb6xxl_LWHc8Y1%3sGG^czVp zM+WUN9wvkqe0-(&DUuKN&>^LrYY0(oSnuCsx~zXRJp=|`NLOcp5BU)E{e#DIHs{D5 z;h?qGI@2GGl$JGD4=GuT-w4`M=^J9os$4Ia{?(IkK{H`}acMGB%VY>-F6oNneZ2s&!$k9E$0Xf5wSs9`DVUN7v zp!hI!rrDC}$4Ua-#g12dP|3GK4Oi`X^7`0`%pdsjOfWCby9l+McuteF%8z8yd#NMR zdGo4xPiS#Mclz@Ty;(Dku$kn0oxm8clwXX5yQeWg3h`j06IE{tso3}sWxNRg(#I<=v24KNt z5KksNBd-rpPYw(1dbTI<&3B;@=TXs|qfDGD6^}-xBBB8zC^K<`$n$2w|Bp?S!TL$v&LO%W2k9P0XAMA zGDkaK#Tu{RM0U+-&-E){ca+N5=M9pY+I^s*Wfce!%Kg6yE4jgDcp303%`aO0!K}T~ z?=i5b!x&;TD1rE*r%Xf6KXxps>ZnfN5JYpKw=uGnnLIk%-(2(H2b{YnQr=hx@o4PY zS;Ug`!hYVL%wAmRbl8Vt!Ad%@`!SAty?^+xQy7Ot?tAcVN zpgxt!zAZ4gydyZwnS6H%0~cA_tDxksPZUsc*U)%Tl}3UtT^kEoPu9(p<&|ihR8gZR zPzryyjL_K~qb~CQUZ!0sQA!*6?d|bY6ExlQh|?EKKTC5$G3zkLj+sU)t4y}YA+4S5Vf#$8Mr+u)vscokwX|OK04)~r82-Ea2_*<46py5aaT zU8d4XRDQ<$QA%5efChh2NB^ZSx1S&H_1oM$7r*{F#O7|M@~O#3%`9^RB0Ju6zp*aa(%DpxgL7n+*QzAMVr>4(%j|T-!v`( z$0#RLdr5dnGs!s2`&hJXI5lrFHfrGRA&>ViyfeAEIeRArw02+Ew?yI_UJY(GR6#)A zbPvmG3qiN{{I|P&{5d=#+sB^pI_GkvzbL#zAITmHEUpLL3B8DQRkxC#6fen0F{WW? z*RGU9pnURj8Lp|g{&bt3uhBj^-QrL(CfYw3$BYk51JM=hCQ-#Q{Jt=TZL%z+} z@WK_MJ$j(jevGP40|zGSbm{377t9Yr&x6PnrF1>w$#v-}%3`^Iyc3ZTrIK{q z`9(JUMLhB3WxV1gTjUsg8VYmNW`N<}Y3+FGa2Vw}*gM9XM^6ZL5^SW-CgJM5#rGVA zLG$1$$ipO;w2}S)zkCd(u&Q*TO}G(GHHoRwBg064fLW0e$9)>8AYv%_06Uy*$UeTN z!ElqHD6guKpjgNUs~$yx@kv&`ewN3c(#__mM$C^dgKVoxN|YF>P%v1%!helKZx3o! z?WKqH$#)aX=mG{DZX^95az1j?@s)k*kha{nAQz6aLc=JSFkp*zSLr0>y{oCne?Y=A zOdbgZv<{!2lY$Y1F7UL_B<0>m?8tVvfj=1vv20+FI(s#7fBr3bA6jg@fK1Vd=d^XJ zJ~M+Y8lPl3^aWXfDrbg64m2p)cxMA)zc?BpTt%U33!6k9qt*>q<0NM9bOU$?1~KBj zDR@lr;F^x~9WqnAFTQR~h(mcPl|jz#tg-;x419 z2RZN46x1WO6qbvQ$|0M$a+utU3O!0crph{cH7o|lEsk7G753-q2A&p9HFtG29d7zm zl7|^TF&zr1a987yzSpE7R7De~snWlcl4wYcyyrI2?1m z6d2P@dmJ6|ieM=8k*uNROoZZZk&eP2!gq&4>8s2A8Iu$tnWz6}aFm)iT7HohrlplB TuX$9Ez#qJpk>*|X(_#Muc?JKn literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/seq_process_monitor.png b/utilities/system_monitor/docs/images/seq_process_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..b759fcc5cca4bd4cb04f0d2b1cd9149534e9601d GIT binary patch literal 107081 zcmb5W$;$lBwk3AJU`#>1fQNT)UDpzlki6bebv?7jBdEAs!e4DsLpyZ`y${q1jm`}eZMIe+`x|L}i-zyIZb`X9lO z{~i91?BD+OfBdJN5BK3Jo4)wl-%<9jy}u(+J#G8nQSR>u!uLhCuhR&2!SP|ro3bhL zzs?~L0{sKR{s9plg8m()kq`KXVgJNQB>t;>QWfKWu1KGrrtg!#BLe6Z$7gk)MCUI0;Vt%R33=KaoFA<0fUYHviSl z-nT9Gr26Ykr@j7F2Bhm#=OxcSc$Dm;zuxdytXl(`=TBq(ms`IV@Aq8%bu=%2O$MIh zJvxIH+5S5Gd5@qxX!g8Gsx=wF=`jHh{HH3`^1*j~8k>Du|GKvM&&>{_1q=~X_74&% zvVRbHiu?mYOZXo!jus!HEFiG`Rrlu$ryYJ^{11cI4KxnZ(wognO*Rx~_f3EC%xQ|7 z;T}5~TZeER6W_6!f_4C9S@xpePfQFi`LozApU@ITC3&zw{F7-EUe-De-b(O4A62O4 zW-Q3_CdXk&mc0XA&A8-Vbh zTcHqg*ErH7V8LJ%%0x0C>}aUOf-yoG@v0%sOh@@FQo!kBe@dNVcV!$N@MP~xg`H*i zg+^ewJxDfweou^ra+r#Ob?|p;$}jsWVW_H6H9dLJF_Ihymyz8->`->b$LFEQa>_Z2 z6r6HCp|ek%2VMIb8q^My-2DNmzGnF|Zg~LhA=K1cf$w*2&GqpF+AizAPW-8i9nI3{ zeMPXj{=1`a8ydh4E>d>YD7T_=f}7s1&5$Bn+lWdU~lq=kxDn zYiHgV!$|S!g0GaUHv*U*j5r^`$Dv1yug-lsO*P&KwlS?knJSyoA>WTh(pD;xC>r5Q z2$C^P>{yGOi@K$FjA|NirWhB|R|-~VffT3-mfMb`oG)zr3F%2dIbjk-jSba@nvl;> z3Q5HjX4ifTET@$~X1{L#zO#^oVb*;|fvH61R9m`ozM{YmC(YV&#@@&bdDHz1N7~wo z(KN~)&-_z_RH}sVdbNc!aj;n*XD#LjU07a_ zE?}*M&uf;7AoExbY)DPSAeAr7h!Hluy{gU=edNk6`c$1N54~QJU2E+oEKj zyk{bDrbKh{y;n`X682&)t9yi!swDbhyf$y;M%^!-IrEt)j)XLVlHx3e? zVG^>Qd#O6b^Ba|qz|p_>00 z{pH+6C@Cn}q_y_*2%{f^CTF;S#NjU(XnYQap|I~W;ca2AI`90PpD~ECDx#u-s@d8V z)hvi=G0ZH5Q`@g464tNF?B%VfCExz#C?dStNSz8c!fjnv-Oil$Yc0U`?E+Nv1)P6t{pLN~>4kf_>A3N6Q{BNuKj7th8PvfHkTe+hRfo>6g4yrn z_DmB2r_`|8`ixSYGn^N(0GJ5&3wt<^swjw+v1cH-#iBC`nLiyaqY_l9FkOD^`=y!sF50_ACuinruk{7+}lC0T9QLc{A zXq8rnht=%zp6gxVi=GE4&(kEDRD%Y`Uod$X1&e3foWM*R3PeOT!&*4dXLEJ`N?&Uw z28Xf8&p9olT5(s^Ms&-G(6PAwuF=zPIlxMXx>(N->iEd6ikhg*Hl&!1_nb?B`7ddG z;A3it%5vd`Y&~mm#`VT*aPziDzDKJ&wGRzY5+ekd!;i7Bv}6sVvOqKPG~cApzJbR* z%6zn4h?XCQ%xyKuGJWbJ&I7L$I|Rm|2AYs0slBeDtj4+JU8i%H`7C6}>8g>694Kt7 zn%Gv4ool+bPp&&VJ1Hc$EaIP>y~94;xvAW5$M0Zwq6xm6dE3n;*Ll5P40CsNxS@!+ zW$%Ln(#?b#&VTIb0C1Q|zd^#sWa`gC8^+d-08@BXEXg6i?rE~8*yYs$K!fp=v>a_H zzpVBP-j}>SB5-;6)GEBL8v8^-`X&5^$}uSg;!?LCkZzC>(d3cUpc3f|@Ll44@R_y3 zS(h}ID;j%u0ET8yJUMABk{WF@C8;u?pE1w5aE$@JGeAX;MqVQw2@10;{ zV91!$Nto=bHA;%?93v@{Yr$4F(9yLdBK_qZ=e2O^53dqllN)mMhgk=Mp)9ltoFHPz zKxWaUBZ>xJ2RD%6bTTCRWB!tX1buTMCY5@9rhf;{hPs#?-Fh;V8U#(S&fX^uOFS^A zl;r_fLB~;-upnw;?)`{`zP)#g5NLVFE$Gvu9y|q3*?&$xC#N<1q@zIfCwE<>s7tG2 zmE#1SLhwG9Ud2@@bN~sJ;6SCElc9@_#>!PkSX|p7_JM6>ZlMxVaMd7G(@!;%2lo1sdXQ-i6v-Tm|J%+Ja<>ab!5H&+FiZ%koN>@Nv5 zsXMX!j`3dx!R8E}L7SK(7e10Il>@X`WSAgxn^Rr@Y|tkF_+wn20NLB9dG9w&9Pdz% z-J2nF@xL~?zefNwRq`0_ZLDSRx#XMAc~*WM8Q4@TcR64Fr5&Z5Bio;a)RCgJTit}J zqUCXkjKY?CIZ!b=(-*a~h9)MiLS~m6Q2dHHD4{%_F51`lfGy~Z#N>L(CUW80N?nda zOc`_RM|Qv0M_9BlD@A0O#qTk@lrUr(Yo0HD)^wsHbsl`8gKFmbXVmkA)q5BZMBM`D zEEBi^fQArZoZZ*%tcP+x%Qr^Ss9LV((mPPK$x>L$?}%C;OkwffFTW^&nZJZ!5SL50 zV^W2)H*T`xBRpYzab-~s_Ao7lIe1rzr_0PEj}fEfMe`l6AH?DZC)2XJy0p z84*s^xx~?nJO~|s0NyiGeAh;QhS4Xf;pT1ta0MMA>|guxl|mA(eyb1@6zqpN`>3q= zd^I~&KEFY(^YLVI!XD8e4JV!}qM0m+_gw=tTc8VdU5j!0aFB{i3k4W5amS{rjWFLf z?_jC-3o>*f0`laW^K>(S) zr!s_wD-nhm4_+IC>PXuJ+4A|wGe^s*C1%uO?-uvM?KWP&BM7p0{GH(H z5MBmKY8p5g_HxM}Og$<0Zl`p#GKTS`MqfLxd{%2=Rxt#9M1cV98#3YK#^CXsB9t|w z{dM@w1v!meUXcTDj!UyIKBd{5-VOh%CQmA3_62LSUc@{%$ppGb*eIJxz7n|!B)L$k zc$c(S{t~kE%5ZjOoC9T6CS@do^yYxy!B?V_K@8Rt1o*=609I;oV%OYjLAc_x_Ws9N z+WkP)_9yIAQ66s#74r)fc5{4hT7Hmo?n{22j~H1&uLzgCd<;z&AjKo#fMyKZp&8`w9n>3KXw3fMKlG|m=A@$X z3EXTvb|orl@qRQ!u^^FyVa9<#30mLfAwllG5czOsdJVNGnzb?MBi@KwCuPb>YO<$9 z)dvZa{RP8uhFp+EL;Lr>sCTYPZ4EGJEcIvvct9Z%0lH)+UQfjqxpqS{cUH&(Ed}Sg z;b1>dc`82+FfIEE3Wf`ZmTf;5)Y}-pj^m^ce!Arzx1h6ML*Qy98iG$`T~q$E&so>P zY^5O+urf?d1}$ldELz|p82`P|bC{)! z)^Ay`wf$KZ+5NgQmqgsEWXfw90eE{){;ZRXz$bLEUiE@jneX~6OW*!xy0ifI0y}^D z5|?5u&ac~$u*)|`HZU`uGY`$fvphq}zQgzsPlDXSpt@iaLq!@TI?S&IFur=>5Pn>Y0L-Fhzd>jRyqzr|boTdHfDOT&8k2qx&Bc5MRUUmeYDSeu51WQ}e z;0C?QsH#?1?>v9aCNOCsORxeCL6HFQL8Sp}Ot4lkG_cLEzYLQrqy&Z0HL>1N3v=}M z+*GBQ5O<4|^>!M#s-1U?`=qV**5!NvxwxYgwM}j9i%I``*x?|n7PN)7%Ll}DPC~iz zCWzyKHmBr&Pi{P~+bcg5@gduSEmUGtN^g(rU)&S}d@sNUXUmGr-f9%OCX6AOIW^N3 zYaNK2`}F7ofDe-=0M7|{2+X9=`dt@bB7x#lDK~2=J@i1U)SR!=MNZAum@|6=-V`R>*k?Cek{xZ zF*g#H78c_ej+U=Zh)%J{3Q^I^qP*C>O4^7IKBq#v)PLZx9 zk7WG5+=Xc1B4)S7ppVd4JU?uLyo24!Al&e5| zEFHbYrm2_Nv)=|(st~v$`SMgwUk{^=vRusW zw-dG%P;wZk%&pJ2_V&kpc(0MREc_4-g~A>FS(#w_^9?g65^;@-+Li#5MC>}DTo^Jklm zCO$TN`WT{0X3ZA+xZUYaT-&x6u3m@T`2&e(Ov^`X*0QAGw>-Xb?fS3`oHxkX`N6jJ zW7$5RXX<|wO{O^4C_?w`k<1F0$LYNVUfUz}ss38PMv|05lvpDDG!gQhp$X+Ckb*;aWEqwXygC*Ik z#F>kO$9`_?_mP@i@lk}F`_29CYmHKrONla_>bJI*BAn)%en&`6339M#l&&Ei-o}-z z%D<#3!A63GyLY_GPstzYw%dvd1$t)rSlLn2(KzCN!F&g+>5>2wu@Yc7N z*{8|Gi42IaD-xo0uOkH^h%CR^@4APsJ^~Ql;yBI~k(YbXDw-4X^ud`R$o(KjS`JeW zQ&vU?K=!fuaD0!_C2?Il4ze3czQlUS17kqXrUeC+X$y^7N|Y+q+fU`S zkri46xm+JafTdgw$vb^DMDx$3oZlG|?fXl=5|!qqE%!Ymk-i|Cty<-90w`8GDyz?dC-^y+r(;SvZ)c(kJi4T#6J|S+hH2)@sHt9d_xQRKW`UP|oEc-#q35bY2s-XY)bwX^Zi;_JW=sbsX(0ak+pz_| z)5Qz3NL6=}_}wNda4&VUfG0YvPolfpcj+7bMP>s#(N|0Q7G+7OKRXiXbj_eG6WH>39DHiddOG?}oAGpjs#v#SaXmvP&el1gq(91FPqERF-RMG2@pNNGTO z0tOvTK0Qo%-V`lV(SiFiSVAp_R%o3CI3AXmyHZohY-%bw7?3QJY1+8yh}6(*ztFad zY|9$3@*Tjg)}miv(t()~0xlc3{;B{we7a*qT0d`D@n@rwFcx^?ITP8~0i0)6q+a%I$#d1I*xS?eFl&-e&RdcqtrDF$Ug}NSouVSU)(E}% z>_{zSX`r3sv$B9;)+A&jqA={N3w3Ydm(pBw=(gWPpfj(i}8F}bd)O>enC^ix)ts47gWllKWNmLcP=TC zsw8F4_Y{#d8OCaw&iW`iQnd`SHo3(UCU6Cy;M}Ihs$o1MNNFKq9-LM=TiZiR;=4N) zqp`eF5s@%O2oiSzIvB+|jGKR4YDqs;xwV zCDSGwu6eBReEkpV=Nd^~O*t-5=wRmw87CkSFabFsh&MdKoQ+zg$$M8w;@d|f;-7U4 zAWujgXaCDRgS5~;Qk>?#HdESXOBG1Z}47!`I-p4sBuS6V|K)KinJs zzk}oF<2##9;36Ew%fRGTe10SCqE{dFrTo?g;E5Y=tU~;aA|Fzfg_QU8Gh zV5|Kq3f+r~aOJ0txi@V2rARh76T0Tpl(p2}g%v}6!V#20i)OLW@;I*NOc!+GRp6PK zo;(T{>-XXKR$b>Z%j5bZ{SM0MhmZbEu(X-6wg1?Qyp8hCj--82t-;i@%3JdKy&BsM zaHM6w5&wM%^=rP1U^n=xsKkKDi_1IH#K65M*ne zG_d{pWm_QP_P_@+SsaO*o_nd1=#N;Q&-TxsaC`3_35|%rvPc4v1AtFjN%k)-LI;!X zM^o38pCex&w(3*M#yBu`4gUpx<*@KcJ?Vf8zmtpR~U?2#Bj z)m7f7xorce4+I(=mDmPTt?LSZm%f>;5{v6NPgSYI(u$j33`PBXaEYLC>9tQ@>0wja zc0ErXaqG92Jv3qWs}vvvs&!BRZPa)W{Rhv|k+vtNdvs;WmCgftC9hGEOdOR4DoW=P z`7Z!%C{0S0Rj%+dh4zq{WR5JYR5tV?j#ZJxRx=w-7P%XCPKjAshQ55*^#s}KxHU`R zqE-kCjV72k+^Dn082qs>rd~6QEfN5fpr&H_ z1?o9!lHJILEROOhzuC4#J1V)G4DMr8j=0`P0VD5lu6d;aB7F@5QYQ#t(rNpE*$NUZ#l2RjkppPtt_cHA3H^azZ^zLv`#{)8 zr_3jLbSI!%{$RKhKqrCXiHL9F8NnFfRmm~KszjY^3xI}C##B2Gm~!#No=`RtijGCW zMNztQrhXk4;&W)aiq*duRT}jC-2gqkq1rH{`GxY+?ADO(dkR4%Je#P<#V(MEYOiT+Gh~!gJzVed%@rxuA8b zDJYRX9i4oBM?`C79kFlFotU1)-Iu6TLAV?}vN$`#9ikpK^n8p!N27T!TINkUXbr&q+e0<)VWdLXaJgQ}2 zi3F>b3*%}4L{ZY{2B|n<)G1Wxe$9b81*V`s?}veMVfH!;$3Z=QE;3udHDe~6Og0-S zdp)<>1uoK$-<6okpN5UFL~%eoqN4RTgC7t=&0sn?Zj}pb542ekgfC;16O1+}to9Cz zGtY);i$SVESetIih|QpbW>nnOZI_}KH^dGrAX3W}wF$uuY0nGQ#q}Z^AWCM{MMFV# z#l($gn0xD~w2EL(*Y8buq5Fm~29ige^AtC7)V74)*ZKR7N-I&)l&PtNSsJqJ1Bl+P zZy31C6B@tuDLx^qzHMq117;tib5uRt)8zQkV7+k#m59&@c4c@B+1C(w#xTDEOlBO* zr6mGm9(G@tzevRcc_*IQifJbGN^By1om3c_mLWp33)+S@ z!Zq?~`?7jBpOhFASwmaN!P(Vx?Q8IRy4(B9R-XU|BDJByOoIxJV8)XnMZ`1*9kj?KKxuA}LGa z0m~xnYe$8{gVUaWms!5jaCC6@kwcHI=rDJ7gnF)@8ebmiOCXDgPdoq(_Yjs>AmP|71{9a4^x?%NC1&@jOt`3}?w3jU&TJ5X zi-I!&h2U*_xDL@&=Fuud|?N>s2QW%;o{fDi+q znE_1dHnd2h6{l=Ca}In`My0n;&u5}qr#uI5Fn{++MLt09^J8XeoRHO9bp`luYD)Q) zfit7|0PM*y`z68!UFzxYP9v6-S!|M(RGK1oUqG7il-@a$^V;hwi1U}?r9VP)h)6=B zj#4A4jVG67uRXUTlA@V^L;AT$55!{rJeI46gdoWaAmj$*Q*H4|H5qZMf@|i07y_Q3 z>GNv=p?G}ugff6NKsNxLJ7`Hi9UOnu?)8J-p00Ne#seJIfHFBh8@m7EWz9WhXX+xt4bz)vpg*qlTk(6(&lVD}j$Nk-*Rh#0@?420r>-yD+FbIAnTKeELrs z7XgBbZrbrGIGNqo?3URANJ?HLur51bWpqEz2LIP@M0K2d8QB|1ID8FX&w_ zhG_-<=-&qL7!nm|sEjlgO#dJ}wO%+dc>ecn6;=ru zM~gSFS$JvZy)V2k$^w$bnqUS(YVDYQ;O%8uUQvA6CPf*2Jt%a17hI)^fL0S=^~cTT z;oNh4yVN(30(n2P;a{<)6fPDlM%w9p_vP6uijob`+YF%9QKCYOEWZ*y1uDdSARNr{ z>2OJOJpaDFNUD`Y6EG@W-@epT+@n&YRN{VRC&ts2WRAW%eHEL+@e$T-ny?D zB;Tm&sI}FI=nyDCLHWoZ{0(+UAcCL2xcNI%6$`Tvav!@j0KiN>XO}pxH>w`VI$?+0 z@csh=PBZOOY+o_L8uFP#wt0 zU2XlhXeBR})pEQ0SaErcS!OZ*mZ~v9T;@M#4;Xc>Mo0W?f_7zIAQBb66o(^V^%hc) zuc4GNPvQ&6mtR}$I%~tw$9-y#(IbQoEU{I9tbF%p%}D9QKv1ohG}ok$Pum7-LgVBe zFz+AbEqC^=f>gp}qm2RTI!?ZakraRl#$3kN`Va+1D`Zs|N#}nb6wr6#v1om#R>RZ? z%7&$Ie*jpyF$ZnY3>uzG2v(;Ao-#G|Z^k&0M&16DiPu6!nh`|GETVO)3suS4SEXE) z4e}oJ%1SO2&@>G)(8P?5HD)~Zrl(b8v|9yxJiPUF~0C^g}R~b;X7rOkr zvvBH&J2q*LTAcQrA}=Q{Q~u)7_9{FS)dhr+xo zZuSpllN}ChoFHntNxkpL3oY=|Lh%YvnTq2Gh0)&>5fUU^10o@y`GT8h^Xy8VR*KTM zBW65}KZ7WoT6kP#GJan3YAf0~Ep-kYy;@BLH67T5h|{eYjyi7Hobc21to_yDP2Bel zS@d9$LZ1N3D2fx6_BZ|!zla-b&bJJ7u?>^jM_2{T={A+r{ON`rt`-1+A@_R@>27k7#tmEO;obi@h)uf^*Za@ShW@6 zvq&LFHNV^u=X)GdQS>XTXZlSdr%WP$xerctwSx__&}-$22jUa>DUrD`(RzEXL;)zy zzFiAc>_*>|Iq|YH0yRu5iih#$oET9#vytzye8{EKl2y6v8P@83xkEN>2ZfpP6-PliD>zO|i?#y$mM`%A0#*NtO;>HE-67n100t z*c0YNG*0VYlu!eNQ|4^1u^Tan#+(x%0iXI=%Ed zW&Y3q0LAKCEu_)@NYZ{?VIl@sWFvLD0X`18O6xM55y7n(`NcLD)}OB=QkXR%U*)kT z!|kOKtrC1<8^$)Au1M(Nr9PY?^!K|vzb_Ld9PD^nggw*Jv}*wnfV>Au{31Ei;Q8Uk zBTIn);G-X$B4Qc8-sDodJSm1Mb?2Xm3~@PUDA25yAj2ZWFE9&S;S-vIFuA z!2Q`6SiR~;?}P%aY~gUP(WvQuv+g(0y=h$Q!LSQZ{11;PAv(Y?6&h!5nVZ}_5ZYY! z2gRElfynm2frc&)V3gGb?*gNQF+RX-g9|9Iw4jl(74U{Cq{ka+z6~15=8#h$=Uar@ zJf@M@z}jz@6J}BgdLC&BaHY?-WqUbf?M#NRRiq6!c$X_OfURPF=TmH;aUhz7fXt2o znK2w>96)?|*&~qC@iq-ELv->W8?b8WSim)qs|YJtN~bn*fP71lM1z-%+7VHk5kzd; z3QK?DG;_b2&ZpmbOHfjYjz|?B{!V`E+RpVZ?S%{0(uAb;BglZR#W5jy;o;sML1KoL zAuSRLt8q;~qY$>!dlb>JRF#CfRj%cjy0<$nn>fF8?ab6r?n6()pVmO1VNXoL0q}8> zGVS+sn+-gk>CP_z zm&{QURh|meR%jA`0@H&z`&BfM0TmZ(4S-?yDwIy6V179r=xTm5kV2GRjoRU0s~_YD(+aaTQ4T?jUf@5vZv_kMV^lIH0 zC@LJ*AHG0MrKu_sb0=8)766UuJfXYtdEMmhNIx*t6<@x+8iUyP7WR)iXn&}lDA3>y z$}Vq|nJIIwHEZr8=x4`9VaMNUpGSGWwnnblc4Tu6#yA~J*5B5Wz`EHldq>>}G=oD$ z+6)DW?*c8n%J8^BsjBo|>Ic{dkKR8J;Y*kHeOTHz1)ezadW$2Y~o8AjCUPgH3aNq)%}Jv``d>oHLAcvl(Q zfLdT+i&GP8mGU|QutqY!2kp+j?~viEAX-6LunSp=2@r&EHIMhBel-)F;2YY2cm(8^ zzzcvuZ~gkA#wI{+V$2*38ovQ0m0Ff1SU_a^H*WBQ@KLB3yPv&xEtZ)}psLfVEs1l9 zvcCdYQFp?kBd5yCiFpENw_rUgkYzc;-UNY-kgAurDnG78X1IjChhD9$dbUOZd++#8 zA78QmbuESimXSvk>Z$^;AO<{M9*wka1JEU7Wt-7fj|HE_BMf-42@7A_qwMIpr7Bu7 zwXI{XhjetAe;D;6vUeAWfLCi7nkk112K+jBI1YB>JtOy80BcR$(a!E;w2#J5J^Ww` z)0LTzzuoI7=jpqC9xT|b2cAxVR1tv2@JRHolp5PxnZ-)uRQu)$zma-G1uameZz>E3 zPKZAswG~YS$He8-QoGM+(n$9XAi~!%$nSF;X+^D5@;cuW$o&`yECzdRDU!dYX5`-g zon*c=e5ZyYEQ22+D8?~LmBcIOTL}ulhz&#iq11FX4Dws36gpa@?xQq;%Aa)snHQh6 zly+Yg?g8to9s&lHIWjVW)l$h3JJjoiz83J~f^2*YdnG_19uG(~$)-%T;~V28jy4Ge zB|KeidxWl!J15(*4i=lII>u1B7vY~l)YZ#3+$Wg~2Svmyc8Urt75F1XR_2{h^+p8p z&J6iVtJ-6}+>QOc{)&EH0}N0vUDn^xtP&Gk2tQH(S^#x_$S)ApcabhV&L@n%cm2ym zQODc^h%&$vTO)co{7vPj`CW_6q`>l#X@>T7No|9Z&fZl<8Q?tx7K=A>hafVvd;PE$pZ-AD`K=SJZIj9dQVh){0 zzw>%=B2eVMI1vFj@z>%2CsIWKaN-E$7{e8oJ@ewk_-Vn9Cd3R_%=#Bf+{~!h8|i4U zP_gvyb3ioT!eR9lO4-Y&#;_-P03_`eeo@#I+vBGcfB8hTz|iYs>$C5&**kDCghC ziuX77f^)QY4XkL!JpT6|Jm4w*`wZet_DH;zsi&FYr#B>K?+3ZjMVw9N6($*aG5xd=Boos^uQvs)QQvAtYLUy2uzvRHf#9yW`vTn?L_5)jP41h zl{GZ1N9HMW`>_iH4$l^h7jrcn(;fkNf76ZeJg`^-i6pKN>z4MwPgcw#&6t7FO&iZL zZ4(5TFL@wK} zQiRErmtm(XfI~E5z##(MDDoJ!0}ioe8r=R`@(XR(RFA$VaH|3@fq!7@rk6+LJu&*_ zK#Uf8jKd!d4e?&bD2+|>xjSu_%THVdG^7zz`xA$&_=Qczljiq!43$|*XVCW z@x}*7Vg`Ek(6Jqm8I7E)7|ABz)8m`ao*>zJZ^$;gOkj_SoLY)O+S| z0l&K8gK2x_aTB?Ll`euCf%T%dD{MgY9oEdgsgL^?gUDCP%OF0|2LcQt@pFL`2|T{j zZ7v!j#dH4H2W#WjX{!_@%QEY1c}K_IMq!qpLbFrX{UGqWCYYX^1~LNiGy4t7XN%0{ zI{>6;t@*7^o{3oKw{F>;H36|o?29x2K45<9N$XRbScwcS@H;pjte$}1BkXjA2NU=} zaS%$0Hw6GYW=lSH8Mhp%rzd>5OjEqT^&;_AO4{&QGV-=S`nk%fy-3jnM*F!VSbsB=X%_4E&&uLV6tFecGwjX{(4gE-g42XcN;4FVQO>eZy zl3|b)x;(=EY|cAmRjG3}k zRA^69vQ`Qag(6F7)1p+!7Nw9vDJfg;Jv~oP&+~nM$NL`dU+-~Da`0L1&wXE?>prjZ zIgOH;P@l5}ULb_gR1*SvK{yjdY%-9O(=4ob zWM>>IEXdDN47HF4%TOpL8^qXtRDZt8lXytQ9w9;2SU6Wor*otvOF1e?%ma-nLR^Ae zcp&*tby4lR!43cjnYn)mPvB@C!4}ZLn2D%Z20p<`~2Pa|^KsUC?N};6SVhC&1WpS+);5>vi6Z9uQQIM8c5@@GDb;X4;QJ@l@Lc}3K8wPR-2IDZ&P&X7e6yitVhX|#3 zq!I=e5)%-H3}kW9oDhl?N`Mavgfh%5I8?d^M8U!PNv&Prs<4);GDNO5;P@PzS$F}S zWiH|q(aazkC{<=a#U2P0%nAatL{QltR%UdfMHq1TencpehYbR!fC58HG%6TFLK2Vy zB0~XT!UH)RE2y6}@Rul&kQD;FuDL7R(o7cQ%C$zwAyP|oKVeX4s6Uj10uzXFfN~*F zYgakj1#9Ua$fAm{7G}}_1wqLQ;)z4~L42VF*tXboCEmiB=;q`A#|qJwOmZ+@&O$pv zrLKV_N0Hn)%!O+iszAwIgPD$SD1-THZGxyUbFc?vlpGwy(%Rww8!mJW4rFtrU|Rmq z*boch2O%h82+z!eCm{xchBplB-`Ei1@As>TniU98{j7NiAbA3cNinF~WSje&6U6?0 zs@TVzBMh^^^Q2}@q+mEgWDYR0YI}2&u;d{;R~Fd;l;)8_+~qPP-_cz}fD;*JZUI0V zzygjBgA#`cLtXtr0UOw;LGnP3wZgeM1O#xge_aODw8B9fG*^~0aI$y-3d0l9*($$* zaR^bm1%mib>WGk-xqwOrL?9C8#|xx@-|?`nAq)!9Lx`jcfE)+vM#hFg;B2Uz!bgRL zQUU<-!?@$|QobOV;0EEVkRO_k!&{1iu>!i(P3Eoy)9t`^qPbDQ#DT(JU_4TPS*Q!r zLUpD`DBV4T#Bq~A90ByepvVY6;gVtqq1uD=y44eeY!9m*`HxeC~r2`6%_m>8P zL(xhkgW(Ung#$cPCUp;i%fiU6SS->4aI$8BN^{V|C6Mbc2n5Y0WDExd8bEpnG1moU z1-Q*nORj5xg*zSS=NLQ^m%!oj8MI&)g)O0(yAnZs0VpF*Fv(w4tLfl~%0fXU z$^+=2Sl2m}(Ezlfjm_j_PP^2J9fYb%c z4Uu!L{kUN;3dq_bE%|JLBVV9o`w6Vf93(;s3WpF&VS#S`%rK=a6is2m$RMmDb3j8k zo(%N+Adsyc71qv9N(>OriCKhSDh*J!L}Dl{FoEU>YYQojEMy}&&_I4j7+)D^15C=J( z56U?lAaW0+TL6O26b1s30*NG5`Nu#%tpGp^3i_cFf<@12t+BB zCvlN6L&;2c2`PYKEob0Vff=9e5XOd?F_bPqG%tj+fb4@LLWnJhs=Ha?E&at|bZ{8B ziVIe$@*F@B;U|T-S_mbUAiM$$y_v)u#^hLn(m63W5ah4HN;JOATQ$g_vgR#vqBqtc$g+veF@T`#zSYD_=;!0#X1O&oW`<4gP z8q4qx1^Q>PoEU8G>dM7f2U`YNa4i6zMuZ^1LpmssGJ=Xy7eRSSe=Bl`0|y!w0{Uu! zUs;F{9AXHY0K_$Po*9J>lX9^&jD=D{McDgIJ7f!u-P2f;`w z5E;V>RP>UWd@>mn z+A5;Woy_2VesVh3UDf>zG&u}51Eo&XUpWDUhbRCND6?=9q0NGViEaS|oQKev3i^LI zGaP~){kcda5p>t_^AF>=hpH?;fC_2@purq8L+0Yj5g>$kt_4Plbft=UL>1H*aX2C? zyoz3QMk=UbpjVy<=f}q@T&W1qf`=Qx3khVytw13RNnr+qTXHR(2~-jdikHYKZekfo z^aY{`j%Z>q55_>bFsxuae-8y9=m}gx5Zsw)2Ios4*8X&{6OK&_buyy|QiI&6G#nPR zvtd!qC^Q^RCZynDXtQ4xNFH)7!42vLh7Bkij0%*aF$9d0Qphk114S_A67!G%&_xd) ztb{u{b9kTtkSP(+m`E0n%;P#a$;e?m1kn#9crh#}$w4W#f`b>G=;DZz1%c`?8I&w$ z^H5@tkm7+`C<8!YRsaSjf&`hfD5|-Vf|d?=D4NK(2K_cIxtLHsi6DaTu$C%wFsI09 zY!Vx^R|SeTCW5J;`&lFSbO#2^HH77cL+}``!K`2qPODx$k&;Lb!iKnrSfBxrD^M3B z90JJH069E>=Hwp0WPvJY9^5KSCX~^I?m;Tr6GKHvg;tKB6vB!aEP?~Y6p9bS!--IZ zl*1Q8FxFg9yAtRphl19cG8u*|7y04bogA%MDykDDatHm*AP`G=0MC^~2u8F07-$re zuS6&%tN=8f2ikC%aT%g88VWS&G-u0|ATvV>0o`!e2$GCPMMC5RO9{r238!-Wl$JaT zroXv@!9t0pE}*i>F~~Xyv;_v4Z7Mkk?*UMXIjAsTqQa~YE}^Qo3d|ko0^tw7x_A&- zBDTAKm^ljMEF58UGn|m4gDMcUFN!a{&l${LGz|KqZU{!iQP{ z38%9RhBKGAQLRGV`9Oza9vniH1mYo7jts(q@!96i&;UQTU_YEW=*#E`wGs;QEKNVQvo4*}yGK$Ie+mX;D+ z0MQCBcVtP3&SnT2p6TaG3kp;csTdavx*ObzFQS@(UBp854!K&(fM(bMVi^Eos6-DW zpj2}YX3_(hL3}^DI|kvtL{Y zp6dpYpn~A$PS_B08Q5$%L<)k84)M2eVK{|S;S?&(#fnO@48#ygG;@ioLl`Lcft)|*3?xa;^YdqbE(>xB=p5<~ zp2ER0m`vs{grJE5-NGGo#!{-#Efgsengb7nVLRjCR44?fV-=vVkSi6KAzj2mroYrW z%mWxC6DUlWcy}US8X{moRJP%u43-HP0bGV0Y7S~4oaCUJHUS_*rywUnm;+ZXhPVM( zkD;hyc<_H9$=@1O+bY;l2n42pA@QK4ksH*X?g|>svO)kk4vrC{1fT^}KnN5~BT{Ip z=jF;&q@odx`E4Ds`) zLTE^jUwt-7Tr8+9aUeT^VolHxmk?^sBhjQ}&`jBkf)tv|VNU)Y5SX=s4QeKWIc9Jm zoDSxJoUWw@1@7)hkpF7)CwBp`)xjBLJH&jdl|b%hZB93%gK}VN5Qc(o9N?Ekf&c$O zFQa;%Uk%(rC8PdpF=EOTy(x|;gnQWbk7s7c7B{u-jig^rzoYJIsG-)xihd)$bM8+2 z8qJi>h59($9JQp*0gae9i%mD(iCf&%`R&Zex2iFNHO<1K?SB3vmOYZFGs#;9!w1@% z72hgG#Ce;2DtF%eSyH`s!{?9GDckKT_7MlCYi#}!xWz#8-c7Cjq_?OcmnE-HmZhH| z`4&4ysp0<@?{iEJ{^t_lawbIk{rR|o9{I?To7ZFC6;v-2?W%5n=&89Sg7F|9e|5bv zVw%4FpHB&1ukqom4VAW5b_<&46c_cMDhhR5FX_KM?QCsBY|Y6mm!mTdPf`E(hkndH z&-32aDy#MQ18;d>7+-8mT4&C-EsvZTy?OPmi>`JnE@lUip`R1yzyytMg72OtEvbLXuH;x%_q z=9OXgo&P!dD={iF_a{7|ak;B3Yl-D%%%2BT-Ca|C+TwPc{gocFVcEB~(Y!7Hd7j?g zQ_wWs{z3D5+pczi%7>5 zmeGru>%V=^f7e=Xj+$YaTU5ZIY?7?Mu)!l>q2AO#pQlTw#^uMfe7Nni)U7;7*K6B# z?fnbaUv|CNXxjZe`^kNeYugAPed6>F?tfIa4BcenV!Q8uEqLW5_T}%5fYW%=LYIbbs$tw#9?QO}liCwLzrcoLoL{k1HK~ z)s@Y7*J+)zH^{Kyctb$?(#guuxe95(J=-+qcer$BNS#H;yYHV~uVcUp)DK0ka{nQK zkIx^;c&_L04SA&P)0fq8FALePlfKnR-oErW>vCjq&8$$=?y@B=M@23EnnsDn2SZMW zc73Wh=aQ}`iJ!Y4ZwYx^d^&U;V&|-{1C1-&Z7fJ* zd+yzNXxZ7Rximg05IyAQcv<;b?d^kPjimfG)aRi~pT0JVO@=ylZJ*fC)m}b=ONMT= z#SWvM&!pV)Th~+4XR*?|#nQd$Tj~ql;Sa|bTp^IsjFvcEfUCcp*brfuvOx(g4b*&@4?iLbZrFi0K$QvRT~GJI^ccz4BR&RB%L%QD?Xm~Zy|eVko) zZYJb^dv!bEe~rK@x&T$W{Y%9CV;{C8tZZ}K-+tI_8{J}uKA3@6ohww|vcX_4>*D!A zU3c9wPg~MLAEi9gCFnde`n50ZeNV27y90aD|c!5cK`jjX?NYqILp9}o5jJN zE63P{M%kV|#I~~V1(RRyy?LFLeSw}k_pVZgu1Pa8T0If#a;M<=%nZi4qrKhT`>ldl z#@i5R8Y{W8*wwLcO;)*bBHyg}{&l2*@a>Zid8j76 zn?+Sl?cxibS4?b51?dNu)*HL#=xlFqJ>>X&X|6CQ!({r&9J>(O!sZh6s^MpC=oOOJ z&q7?5Kc8zor-A&=F}CS)^|7CQtCpDwXEy#II%JGnKYnAJ>6wRH{k89z%POCXgr$j( zg-u2IqmlKxp1$0lp%*+FmK=QV-1YsHfu!~brGG4BV0m8iwYgQIPi~pz{iW0CgLWSM z#}dB0)p3@X`EI|KDTq7ZckN4(Fm7+t^hb=vMtg$C1JvrgnpY%x4HJa#ph0j|T5SQ=aeenP8Qle+?&%d2)P17*> zwCdoHoi-)2JiLFNK}FI2lMgg~YqcM&M;=*Kx$&Uq(h}D3Y+aH*ao6W{WwUbgQx{Ey8>&x>FB zI6n2v>6|V;tnZRqi(b>Y+^gh;UPbh6evy79M`c$0Nie3X;sY z>3!U2h*3KGv@(Z4%b(nBduMrW!oc^9b0wo~OY*#|w$Z~4%3Jc$-WK^kJNS1pL?l9O zoalwC_ij|=_;*K*8QUb^H?M4gb?76d=#gv&=ZMuAW5TLW*n@*tE4MD=j3%xe$31|BvzO?zD#UF#Z zq%LkhxwCwz<=@x?eBZ4(I|P#BLU{jTrF*UK14)xEF8+J#_Zu*6_=Ws2tym-SjIj79~DhN{jcZeM8;*(>AxL zVoRfm~3d(Zp@?Guf6BKxY3y?n10J|QE)_H zm_~q6mLNytU|LyJaKjc>$9%iDp+Dwti^xsyem6PT6LWUpN$M$f$PNZYTyZMUsTE!QHG&aF(2G}$!>NuO?0d`Wlx3gtK2iqE~q+v13pN)?`_H5X8x@3TYEahy!VshRflTd%)eW_8w|2(qqrs&xk-tbb_ z)dA&dC+mybOE{1JW9ik@*)R9>4zzsPaCe94>|%ULe(J%n&u{v2Dz19z#^vXiE!=JJ zFVv$qwOrqKQKlftbSX0NeD7V&uOTrvIW@J`3L{8Z0Fh5x~sQQ?~VLN=y9P7=;w z=;iOu3V(63IKd+N(BSl-{ugVlXeU>^hlZ{F?@*_x(@*~wsE;vBe0tPU+wFE&FJ183 z{X$xu;MS-Ai9&?Q_IXJQ2s;&$h}A_)_?(Bse(fgqoh|!k;Ev^LtRyeJYR@y-_1`&- zQp-c?H70@Rr)|rYxoI8k*qJ@c8?VoCZrB=Ko>ZzAI(`+Gl$|y3;ntl0nUa_AsRm^v z^pW;IAy1+-R8-#nIOoixT8*8`Rm6dn*v!Bo*WkyQcX$8CG@{g4r=r|s28aI}Zn16P z+wEf2ZwERyWGA-Mt^9!mj zUxIk$T)O<;rYIPKjap~OI#_Wo|B=>$6KiXO|J=HI2$%rV>|8IS@=D?DpR*-|8~wv- zbwe?^JQ_3Z04vb2QZkQ`BKNrvyuUAUx8?KCx){<(@z*~B!> z4TKb2$UB>mKHtvjXv6I{!cO+sg?*ZWJ+vA<+}EIGOwIGXm)x@SVpQg9{W!6O{lS~g zt}?dfw$1oI4iEtb*pHKSR7Ea`jEr)ppT5Hm3cmM=5+PZ+%t_L*gnwZzEX^&a>O6rG>D?s4lg zXKdPjW8afByDa(OtKRyoS?gU+PFb*Ef#0K(S^y8A&N(GMEf&yLZri!+^P4-!k%9L5 zi{uTq;iHR9Jxgv6e`u=DChA%QzVb>mK7BEq5uQYr6}Lc7?2peB=o~bO`SUhpI)PQ6 ziSS%rHa`AC`sfsFZe?YqA^H5gw)XZTTjXN!_iDx(^E|TjW#ArRU%EAh-aXvgkW0&* z_u+zD*74*14^L>UfD5bB5xXUyIuTYjHkpXsGYx6^DGM1|T>(#0nFDRtuLX6@^z!nO z4EIs|?jN427mX`LQH*SiZ@++=(1k8r(S)5j$Pu1!lUwUXk+pkHcrlzJEX>0lZ zIA*IDl8m5-HCXSzY%DvmKIhVqVOa}*0S5VdDSWGdd51pz_V^TxtkZgtoE-tvZG2JL zc*)cF`V#fT{yXuiEu(N@_v6!+?6GhCeZz23iyrpi%HEEus?nb(Og+tb&-4w>>Dooy z-n&5euo=^#n0WBCUF0^W6DB$?GW1De}VU+S%>=u35;w zclZ7C>_TY|;aXYQ%thYTH0V_j%1}5rc8ttFumW`05x;!vRomy(9rm@iUenPsAnnAd zgv{J?jhAMlNd4`M<06V&dDnqYpmu+a;DGOicGm3K-%Nn%Ek=tM%#tSIuPIiMz?F*!d&)>_X5 zw#~`^n1S>8qOzhnR{;I~y>Q&L$P{WyYP;lVxzb7k2(Wp3zYPtMjLlk~Vd{&|HIA2U zTI}5__G$cwF0;2&Iq|EBmo&T^iAh)caU09vuPVp3z9xxcM6{#D>;Bmwrmg}wp)dW& zvdoCtxb@}Cnppn*5bg?ela1&-h^kBaZKD8Y_2`-Af8s$xesX%)vOf<kUp(oHS`|cq(Bg@PUWZ62W zgnNHrLsW>$=XXBHc-Z(}^3Am`X717#eT^CF1?SMTFy(=tgYpuo z?90!{lQkQ&Kb(4R^sqJOxkSe6&>TQ!-`qipbT9C7n%L2Qz8$C8F}0!`hAo|cAc6S^ za7ZfH`Xk=n{i5qMssFs2Jx_c(;VXrE)$xODS$t?zvrRFh@d`PK~qI+Hfi8A~^J zn8gh|_WYSCNK^0IsnuD_-jOAIf2;5NdC|;^*Hk=IRD0x`y|=CxhBl)pO&(twSv#r` zd7f}}@Amb+uij|jPJ$?Y10gDW%lKjVuqCt6yRIVQ%lubWKhqyvS45bT!jIWzKF&Ir z-HVyCg7^oFOpRZZ-us~DeaT&)=u6KPv+~<^=5O!l^qkQV;COzr{r-e)UFz1{$?)z+ zI>TdyMeiP;PAWKtyfDG+ew2K2TewZ!664sZ_*WQ)Y=Q39-7~Ac-m9H(K4L?OD?rH~ z$9B{g_ADEhGUtlhD-Y>DD6!8{CLWJkPduR(K2!0!v46*>G&^l@BKi))+pICmc=@Ee z){2tx47H%K79IZm!0Oa>7Z`>5$}-}uD?OVbPwq{ZPliW5OKg38d-B}(p2n>z?gm7^ zTigjl>?^t_Br0~G_W1Vw1D}sAExaAL z_}RIMnXu(wQG@x9>${U$ZlY+f4mI=*+aH^mctEFJ9KN+Cul)Wc+}P!*{hytW^~F*A zEaSv}wV!SOK~f7Zn@o)x_=##tFy zt2-y+*A)u!j0Fy_yqY1`d{!8g-HCgPDA@G)Mdd*F)+73kEQ1dS^RhK)%Nu16ug8yD zc2x&{$!s%F9NGtU(Eb-suf4{;9-!K@>k1G5+@N`?bGi1pB0yUn9!JXnTN#sG8k*}3 z)rIetQf`EYX@2h7a-qrZd%^wlejMrIoV~o%aEf-*s-G)=$x za69a_UUK7(5#5?6J1#72e}n$AoO7e&@J}i|)v7Gpv0kHKV2y#bQFwCZiX}?hq(2zU z1RIsP(*ILn@-MZ zXqIt-^Ea?vZyH{4;2tqGYv*GEe>?w5ETu5)2Q@6=$C4`1S45+U&SmlQ)x*zi+eZo2 zS9+pP4t8Z|XW4{|Lg&1d-mPEM^Z5-rozeWgu6>qd6P;-K=4wDk(BemF(>pjJxB7<5 z%^o~o5V`8>g7szO8%b}z*UqKe$Sp$qe>^uVTYGPY_vww+{q4m%sGS1%#~AjGrMW|E zkJc}#JrPrIW5e}aX8V~Phvr@xSlqsBXU(T)f3T6S0f=ru8lX%&UgLnhd+eqasxkQ{ zGnQCoW{&j@uehc$M6yHb&&Aa`xW@j-U%UI*`OVaLv|~x}&g9HbsUP#H@=(BY{NfZ+ zIR`(2G(t+bWXW{f8=pstJv9-lUX;RGN=Ma;^iJfpjlX?ASD%ogS-E|>TM@m|H*>{t zXV?0~rh<+e@pTn74|Q+j%fjQ@nQQE;%^ZY*o*-5j| zYyZQRf40Zoy;IOhnYn4N_|uPoi=}Jf-J}2C4%t{%(!MWm)o(x%g$GasoSV7s!?}fv zy(_M|zkLJ#!dGxxnD*~OK+u0mbsxd|ZFh!TIO8R-*!bKnI?aY42Xg>!lKW4FDSgYY z1sSlplserXLwj;*X~f6H?Vof$&;H{c_sv%wBbI$N-`*7o_V$wYC8{r#{~A%mucsb; ze+jO+5#2O%c|Gd?>5%vDyhTSY+0VTlBDosfa(NCyedkWyeSaqbcdhw@xfbqY{<`%% zIby7AynoT6*C#DtN3$Obe3q2%ZrS!H)wtz?X)f+}=wd&u1;obZdimvhTj;Xr1;jTu ze<+jU*1mzV* zuybTc`}V;!?e{~ntM$u^7=H{peeGvu{dV?9^zuU|UdQPF zD^+ammE8We4gp6t>@dPNKm;r`=x9xeNCIG!&0XPs^)^q|1?>5cVnir#?4TmdGx%8yfvHC-&2{^(AAs zQNI(zm)*6|(^@us`Z%ehRv9)s+hO9@>Qvo>I{Yy*y{T8!y5ett)3yZg?iDQU{yY9 zeRBa()7jz26*^{Ff+vAGja#AM=SMQ`N^yFl>cZ9%jTv*bQDw6Cm1Wm1hOb#L`Styx zH@EjMx;W>>Me?lav*x1!gHU7p^XBeZR?4r2IkbXs)fp*kyC~ z=FO>xbnP(UDiYxNcTSG$RO}eR99q5AjCo5fEG$fqeK+BxRnS@^O3t2q@A5aFUf1kf zx_Nb(eDEOQjLmBh9&?+E4Dx-d4sHt{O;>#B&hct?>5sS2PsL5MF#v=ouLdHF|K*rW zpBu|R&`p`E;$n{2bJeV5$rHQOu3~+E481ezGD;@bc555DRxdkyF&t{*QFLYP z4TNQ2VBks{*=*;eO_a?|c^+hr9PPq6#;oH#KYs^M9+L6zL9p>3uWR6@)fSv4paQ$copgr=9K=xVAZM#-@R9dsX$B9aV-pj%sip7;#k6mqA3$nx}KyV>Y zoHub(#nFqsC%#fKIiAzJ5}Zo$_o_uHQU6PSB%0=hue}C+K|h$-|E<3jcid15Fh%EY zQ@aNqH0FD6F}PHr93G9!^pm_BFA=rogoCBNw`<1S%7xwv?^yJ#LOwx1p&+_hj~*FU{6PaPFq4UGE5Qy}L`Ma*sWh;o z@&b6@FVg`TzOuX0u=Djr{d8xrl-}?ayGt~GEv19^{yT^5U#ga}Vz-)bZ&cnhPxV`Lkb@X&68OQ2sQc@BlI(dcqVf*i3eO{Zt(JFENg^Jr>JwA13 z_S7G)FuC+%$*ne|V&y;EhMGDZDYFY7O-PCP&;>#|5XEjQ>M4jfh{)<>y!qMl18e4z zt2^*7(qn@0+PhlN4ZRUDp}l*oSbfm7{bS%WrDjX)@$qId+*{uPfu-swcF2eRUzMdiV@8)fAUh|rJI`vP7X9L z(0P_kUE^IIG|N)_3jISj{%+VlBzA1A*(Z$~cSj&P4+kSx-Wl9+i1qd9ChbGb=Wx@* zh{4#HqMw`312kGwnrxmPIe0>=a{GIu{->q)HeVojVUP6?J~8&C)OEz}@Y*wdc9)v! z9V3PBe|I=)t?$5IBVbUme}jZfjQ#oP7Q&aVk3AQN%vA$++q1ZRU&;#ad;WEl>0_ba z*Epa5S|8$grGTB^TlZV$($Q&`?f)&tW#uw*W@~1RnL!g^O|GI~w@h~fr>{|Z?9-Hm z`(~?VWn-CE#sl`>#9gOgT7PRPt!kC&+|t^#!?y$j0m1i=0_8ybqvU59{5wbaO@ZZy z(rG_y!^Yq0EN{x4r!!~#ZCVFK+j3%rav3DSfkq&~d&lG+zkWhmdFHprUq0JkeDi~% z^RumTFWejR=FPhm*Q6s;pPeP_Z)tew3*Rqf-QiVRGvrCY$p`+i#RrnD7FbSR&t)Z=auq81OBZ!|{be!w zk@wZrX?Bq}LD;Se>-%0d1-{DM;X@R*l`Ty^^Xw)_>iUf}I&x$_Gb`_2P>*u|tI~Yt5@qKiZs8&(MGp^7;L+40G5dL;&7c2+1O?4-AAOJD#h4*+KxXjmy1a!#Z4NdZ8*4Gw^I}}k~=oP*{b_HD^WvDfZS`Pdr zIGMGiefac<;Spo6>KWUlRA$|+VJi@D8C4RFZF4f>7!G{(Nn(E~34eK=dA?->=e~6n zVbz{i`CyiC_@Gs!Y)Mi0X|48A<(t2FA!@DfA6CdM(c=bp`#hQ8(p&05VycPy!t)#V z$KPvOW?qK4>l~gBg&*pMEd}jmLYAOX>>3cX7l=M z#yd$}s)yr1N0XR+=T?wY%jv7D_f1ns4eOVvrqSIq@6ZSFEO>)pfH#`JB}GA8F7UU;oYT@&QbJdx`%{5XV!0 z0y!OI{h|H?ah%Agf3Z(v5ogM03g82`0$1#OTG&H}jZn|R*s&IOFXQ*;&wl$lDYg{vfN-q7K5Kw*%c?L? z{Z-`meWx^bydHShzi-iok~o8_)@5ry15ZZjzY+Q#)iAII-Q<4etd9<=H3dGWe;M$= zmPO%vdyd#&P(>Be| zV^QNJ#iviN_)UF!$jZO!6vVDkDQd#urx$u_td$LE-nYg5j{?Q4QPd zO{C^7l?H5l-vD4O@B3kBZ>`Wn`h9e1>Atx9*^{Ln&?W>((unuw17Y=bs5$ySHTe zH$1!BrgLfwB$z?yljP zR^fYzAE2Y5Ns{3kHeTKA`Y6ZCwX}6m{YT6py3d}gX9ByorJFC}^sI_$uyl+XTo?LV zcD65K+R^&Nj^yoyteBv>d;@6NYIeZIy!W>}*4sBE@7wD6ug=dV24@#xYCX$8 z%Uy;)(~$9;*;nS3!*HJTOwUUsM}0z19C_CGk*+b5zEP=mUJVe?6bg9TwrEA#3($-ol||5d&aaR+~!)U8?IW%cSKX5o9=$j_&aL>F}M6AMpRS3$9sewb4C zb8v1)--hwFYc>ndZi+U}Zd}1uH!6!CFRhMjm@o9$O5s%OSa5Qen)*ujRjAG<-q-jy z{Lk5VzaW0M$oKh?du^Rj8T6|cefWK28~wx!1hf|V*6M8UgQasenkU^mw@4tFxa$pD zFxvg&aYkJJqngRdau>eUbs=yH7dJ0K$qdSkJ>ECk{j`j1c0XfS<}W9Hng4crnIa`@ zvHHoi)gxMCv;M|UDBb9%YE7376R)S$uE|P_Nq}0P+r6**GkK|Nz7ks;<|cX?*ngb?@mfa;V+LR?Pk414j8qJB&SUpNq&^ zgUo!`^zrPTJdc_j&DX+L*G@fn<}j|$GU9Y-N#g^vT2M+{lY*u8ay=0G)C^7 zb>QUwnsRMDahnzWI($l&?ZjpFnbK3UOlztP{I$BCqAa;99oBwpUU#E>`XgzBD?72*ZEgp7|}{@lm(ptlJxzwOg5 zpS`)(W$*aoNgK5%kA@fgl-lKaS%6HyltVhRcMfAFt{!Bx)S^l%quZPwaw5Z}j;V=b1!u3kBcCubTr zqe>CmUtSgIg0u$`Br%@mI-BoQ$>|2YOZZ#1S17ag;Jan#@yAH}JqM>Adwm>YdT^qU z{y0FxrbqT)`4&VP9BGix6cvpIO{BF4eY(%PcET{~?yxa)c+?wHZwi>^#CnM@yzwS?)ML#zLgJdGptXHDYW^va`%^|1zD1tDfd%N7lCB#ITWqW zR7!6!x;xz_o!mOgFBW(#?gMH#KKE+ch->1;`FI&}6UJa}On>ue2g|((pIWG99^su) zX?s6uL;2{gbllCKREl=}nJT|^N7p+hRMl;FL*Adbv3FSyV$e=D2YS}KF7ey31Z8e_ z@$ufc?{iv{q6_qV+;MlycVyoMF-b;F+NoiRsI)HfsF7vfuXXBrJ-sX@y2z?rA1snL ze2ej4auChwYOFVM**Y@5_EqAArwq=ww;MuVRfZR!1kXz^xIWmTAhOe9Yc zUYYPP{)@Qk*HlF=Hfv9$%{bNlp&%Ca(Dq5r5@+Ar=?D4rE2)-o`JtYN0L*U?5Bm9) z>Hmr-Xi1MBrvHWVWvJ@5Cw{9a`!kM4HUA2ruWXsSK!2)q_Q|mfr+V1l^@si@L!98t)|srI?){6V2;H$^-E)J#0*5l;_L+apTKc+a-4W|QTyUC~sP^a=3wo;EBTP^I zBvOS&fQHmUG4HphN{s?O>PXeJC;C(S7pi!?;?^xX$(z)F-MoSG1wYJ95zC$hl3_Z%?dP_AV1Oea&t>a8`y#Vm^v@N2WxWA=b zov)fbzK;)VgIYD|&0BbR?lk%4K*Y!Iyd#^4Sc(r|Au&yxY_=Km!olKvFz;US_i1`- z)li{6cH82Q>&&fzps97u2WH!@&Ye3Ay20{K84vro7f3*!I<%m-toPnLQkUBIZO_7{ zL;g-tmh0=)oJ?zF4+1>E2M^bD|{sm9wz=PDd8inp50s5_gLq^+K}*ETU_VZBS`tB_Sbbpsrc#J)d}WQ#3i7pduJlq)}U2Tiy=HiGPY+ zeo-7EixsL2$AMJtJvTKqwa&M-$9h|eb61g{(i$o%D%>u(uJI2YZV)E?mSkqeRA*Ju z)=|FAtPeKbt}j%LU{i-K#Kjjds)m%D#pc%`ZS%FR-&k{{6$l{qrQH1;CI2d$$^_Lj zNtr9~-UpJ@j7W%$%h7>?*x zcOntw98NWn!;UwAY{;e9#+(^s*`>Ion7_3cQDVSM71zsDTnJp5xeAK_*Xbh5hMUC+ zr~Y1xJiLkk#=pEVv=Pv0UzBqW6)guTn}(;1V&AxY%I6}9lI!2JD$B zXv@BN>`b*dv5RXD>|g31+h6Oc*cyZNI1qI`bL`#2rFo3vIVzs3>gQzq9`!|QBPYju z+pe3Zq@>(B5ZGEG0)$r!?cOT8h?U`^UlBLLJ|~Qk&f=nhu&=WxEfQWC+F3mnaExkz zNJET&|EvMMXxGofFe0&LH{;N7F-MQir}>Ue?Wwu)7NBmS3w5eP$8 zmaW{HQd2%hwR+oiUq=`(GNZ}Dcka|Hdf(lBUTp{n?&uXtSm?)>(dV3#*1Bb)m>8p@ zUZrAh;mgZw-0RO+@D>7s{J>cL_KLWOiP4QyLqkIDq;B1zqO^fdYdX;L-71$4>b)^( zIRs{V#MnCU@?RjGn-lTl-BJ_Jl6iv0yqiF!mq>s3WB&a4MmxMN`y$3C zMmm;l2{lp0OI4Gj&izT7X9LyU{?^jKT=v_SVEGKA?RI=KL8ZnddO1TIUyDFiaCVU0 z-+RZ)4ZtelEoW4F8-{qb%kYtw_YwEn-nh=>7X2)vXGp6xhT*#QbFX;!IYle4u zDEH;%jD@}zTgQKVq3ARf_+URYUV7c%f9Y+=+xtfjn-u$1W^WL7c z4CE%V`ZQl*>NO5&j{JUM!xwfw<%q6s`Ny4|TvrAr=-zq!Y4`JFxK*Nt?V6!vxf0nZ_i+VNz}IdSa?qBBeZ31hjHU$F70)@+$th$jKkr zRU43}Ilw@YADmhZvK&PPt{D!!FD^c(d2qGb!C|>{&KSrmJxJPIu*buXakklPv1id; zK;KgqdSCI!Cq^g!xLH)I$xrq)8BTmuh#MTN`k9ZS#d^#&Z$_Q+xe=C8bhpScR(X4$ zR-es~97yuqu1Wqc_TD-y%e8wO6a)#8l1@Q7L_t8h8>G7>1w`VZ8F${8Mz?$K_xruy%pCL29COUSdUHSbRcoDVt@B)$aXdbkOU`n#Txi>$qI9(I z9$*{+DPGI)cIbOlFib$%38qmp|ZNd-mbWtz+##mLM$foGw@n1G#lD?XvSu&SzRn+V4NX9QHjh!@nHLzhEgvbo?A_r)Es<8gG~ z*(iTZSh&1?14C&+=7#3t5sA1a!Mj-XTr)F^4y!P-F1;tmEv7IKmIfMKzkYq_zD-AX zm*@Nz7m!oDsLS~64%XtX{0|@^{B3pc`9Td&B}rBLmNtPUF7Ye30`^Tcg2>qVQuY_x z^J;ID*$aWo*8J!o@km0=EZ?r(ttzW$ApUa_;2sajc6Y?m2AI0hIx>gpc93ZhPqD-@ z331aD-Ln83Xx&;{b#0>%34-oemLd#^gyDIMn7JWf36Hl6mB(FxLxrbV+%C8{ z7=Iq&|GZEa2vv_1x(fd~W@u2sh;$OlhyOMv`1&F=a}1z4?t)R0BGbos+HXJS=CV;q zH1reJa!ti(uUl&|YA@!2-_b7Vw0UIEi)KA!My$i~G1Fsz!2xm2Z;!m{UycXmwe47@66_8f8;~ zxA_9t)vvZXr*90zJI+7SR@V;XlMB=eWaz>+KW1+w8;F;$c=a?t?i2G;(n$fGm;~TT zpXHhj{pEPGi;e}airmd{WA45?X5I<5s6 zB>kCzHFcO-a3w~>_f^S(A?vOOwts;QG6dpWn~g=4^%e<lG}c_ObWs?)4Hy2)FC|MKeX~v1$I@O{!P&60S{W$hCqeC^@GQJA%GCw z7nr-eQZ-4$`TOi?#RBGQ>_b*v0$@X}M=3skrIt5Z8>#q`u@$n_!B6!CRX&Xuf9JOR z#2>}P8i*S-8=gU6%Bt37OvZGl;T>?~q5y!dz4>xdwg_OI9Y7%a9!>w7KSDr2cm%TT zaHmysdd}}YoWMbb{Kmc~Wf;HfyO1RODI^KcsX7V4(|XPs@)s8XK(rw~Vm55SD+s*1 z)YrWh7{w$R6)nF394rpd4%XGzf3{?4eDs%*5$*=F@x_z$1wI1gE+(g*TExhh9|G_T zzko4tt zKe+h^?s?p8U7}on_vqKlK};n9{$HPy@NeBy`85Q=ORa0!@u83@FBz=SDsIA=iI|$w zN!|a$FPqtoaz6b#F#G@HOEljEoCCKh2*4beY6*Dw*5fm<22a`|Bfy?`;ll8jgBK3R zo!M0kpW}A3hr+&wrns1&q1T@8&2j_RM`+OE9RcVYK2GJRfPcYbKlcd@)P%*?4XZ72 z=Gvm7zC@4)8M+cl9i5(<DzS1vg$dOw8|b41h15p<{V5k7wWc-BDe6AXwl zfdAC5YfE+%w#@ceALE?w%P>s4xH$KS-&Tme<9E`6YClw{-orTN8qPRyzFs@s-{Rw= zSMPuf^Z_40h^Jg@JBb=!_BlW*g5+hfcGVn!|KFduhKF3ar#l#ko)-hQ!+$adrKnqy zl-`aK;xN#x8(>M`8Vme01ijE9l17U+`Aq_rR&bOa7`6J^v5}BxlRgYayG=K|C z=xSeA@zP0HEBkcj{dL-aDvLhJG+w7cCmIu0P=rvj5O@xhGGY-VoDge4Kr`S<7w0>P z1MTOO)ITW}YNIml69805DJUo&0cZkIOQ^&GiGn6N?=JvEW%A=oM0+YvRc9-Z*z~*} zh+i`;Gicg6+BV_j9~~bj1*{NdV*L&sS;<-uP!v)EjsOaPHf<%kwf*JBVrP5b6fM6O zCsjlNVaQ{B-A{^(ea@@jZvhR`{b1WjGM+)DWpLt6ASMebQwoN40uhCP`EUJ$h~=>vA7X4`p3ud(PuJOBC+09$V*_d| z1G6gHaTYU;LNyt)ci_F@KrE8ahRzFH_60=ZxkN+n_j^CT4Y}d)d{;Y_kE6P>3~(DMCa>XBcSmI(--0v(S~u z9CI7twjU>kK7l=+ef$na3K`pu28d1MlOHl_l|kV+4FNF|%cw$!Gs!3Q7n<{x07%IC zO0Y|~)7}UHv?qb~IC`v;{nfmK2udM}+)j?*(stvq>ZbvpaaCXv2WGFG0De<%RG|#f zM^dV+q;_FH(^{nKO1wrrcVpn$P$7OO0c+tLj)?c^LCJ~F%3#3*kif=c1}cDnEpg3K zs%KPUpSnO`uqZBP^Oftv3J47g73NPCDXa_6-=+d4%oAW2m^A8pYp1=#0H8+!;xu3B z#_D6RWg`41t1J{hzX0S5z##P%M7^3ZouGfr*e16-4sVPc&Qy){a5n7cSEf~lQLz~5 zQGZPRbil*{+bO%UsPbiMP70f$AZ;e2YOdO;M7}ttnSCM1!4$O6b}>8h(sHn98+FK& zEOwH>!%Z#C(l^0`49P(;AJ~aQ71YtO>YNxH&F=e!oh+BfOBqZD<(;<&@Si4BVv#+< zwn2DX9(Ygg{GLAijd+92XeAMs4H2*NT0VO@JO6m}%XlIQY`J)*w{zG9@vgU0>X&rz*k`Y7GEws|EE2NXV)x_S8e&7@ zyGu;<&2EcyMpFfJ5|I%2p)k-w$M5`##4{L}|1FL%a5S1h|S1 z5?Q?39p-s~!cQsop4e;JFqV&RZ)tlFBW5tF(&c!rF0c0~U7a)AU+0YE%E0|OXYL){ zUYF;GvRr1j-{Tt>0eWBTV-TY4DvE`cN=KM-0G=CB;j-*^#m*R;^57L9A{?~S(H_ux zqx5DYO6WqVOy;|)=`PqEU+QZYLFE=#B3bNWFWS^lA)fvT+wj5eu4*g`we^T-XemZa zg4;*x5%xDa^LlkeNQS*}vt!h0w6d?1%EIo*zSCV4kUP*cRbnsCdKUX2eytAG>cb1P zcvn)_F2Y;XuL61Ci=Ecu;@rgtSaPrhZhtd_((Z@^6PhsF5mVRNSBF2MgjQzA`>=oE z)fc`^f|tu#`;73lO!wuyaAg#vwS7rL5S?-2sV~0oj5ffz*8vaxB>i29My;}u`V~8U z4d4x0MV1zqGB0h6*J9N>E@@~hba0U@F3UPA6Bxu+nmx{IPd2@7CS7bQLHmtSlwQn5 z;sz}TW7xwEGBq4o9R8TL=%RZlJM1MG0%)JN z8Hm%*Ctaos3`kU9QsG2drh27R!*Q?QJf^Ou9swx}O>Mmxix3ZBd}Lt~?hBk9k8bJ` z!&$?4(M&p|+@2o*=MWIX-*_ zqP%5m#`e6z4>7|j01VIkp$OV4Mnnc}6HwZklwCwPTp!mg2~K5FX9_3h)A)REAFYW0 z;}bQo=hMv6H$VzN6ki|5lbD*7T?gbCO#9NwE1rB-VSW&XCnsP=RB5bk+3_Lp%#A7} z4@CZ#Cubqf%@ zkC$(nJ@k=iUy#E-cJTXcjk!?UJI~nl8LBg?ImFwSD4$iUTPj~AdDqjz%2IZE0({Q8NXw7b6 z9*e4cpN(dt7Hg2&1&EIP#oy4Rm9%LgMULHbC#8&?B`M_stsUE0TTSkbGYHA;?CkDq z$Ob+K5^Al>c+*=@G}J1I8obDV*9yoz7(MJhrasjvA%}p1mi)!K%Oa=Y~d>BQbq#B*YDr$D;69{n* z@c)Iy;a2zl{#a~Ggp0`1<_1(~**7V=mpR2+W3x|p7UZCuHqiAB$e$Daq8?w#HeS#e zbu3YStpWNj5cO6HguWeRMUb0Vmaxl{Px1%VjU1421u5Xj$sNiELVXh_(lV**w?#$!4u1Adgp`KX2;+1 zmG1&v7DTKkz{P7q_dC+&qsNX}qD-`6UQ5;3)5rjODq@PFt!R`5`pY&pMPH!T&9AS6 zc;CS|ckg>1*?pG0IM~`!x?F^KGDb;@D( zX9cJAM>f$yZR=jMxI@9A^#JDQ4{M3S;^K+K`lsvk#XP^m+!0*AVE#+cT&;Ei$$)@LY15aA>fn4^iPTtA@dx<9rO zp7K|YD+QXkwUpF-YbfT|X-V8hcNS^I<#q>4tq;T3i2ePbO`tDrx{u9`z%NXqP;#JH zj-9Ltw|qXr;DrnDwU*y9{&5K z(sy82QB2>zqL{Lx#V6%|))wsICCZz^)ham9l0n*~8g9hKfpOiis^&irK?jra|9{E< zKPUgwKGCghhGa;iCD$6g-ElIeP;?HTuuRS&%{_WVtsI&vonAlq*kINNpJjTt|^f&pvmhAHCbG) z&Yf#Kj*Bni z;^G$2heTu&U1}uWA+kQA*F<@SKY(r4yHTSWHlt^3E3UY(4V}--r&mXO_a6@4W)Fu*9Z)_DBV?NcxfLjAcHdj}19_F!j~}6Az$d^mR4!1V z1qBm)P}GqG<=p-z4;R?VAQ})@OMn2`{`|xVxEvG+#V&N3TV*8hWz>5~cR3l^7~h@| zqwoOKHeXgieyIvOY+Zit1zaiji3fR^WgOC;YYr$L^MKkVvZ0|N7|D%|jg9s+zFI5F z|5r3Pd0KHhc|53^s6pe2`{9NF8QGjy{KBxPr)T>&QRe$Mz&4cwyc#erVYxW07Jg`C zX9gecO1EMlx;GARTYr}~v&nm$b~5CtrFyDUYYT|ZG-~e%*$e=a`;+Wz?&nkCfTdqF zJPvXWWIPU;K9?6Om!S6Z{*6rBt5@Dv#%p28p`8WQBO1sWsUjSj|;fg95;F? zE&6NwKqoAjOD}vRn>`8JM4RtTN;I-dVg@vs+jw9^J-isDx0xMY8VO z77{LMgs;K#y;yC1kakMuO93$pZ6kZ4#=G)^keN;;6CRCspo)7J@Cmfu*(BlWCN(hY zg7n3!>VuV`Rc6!J_wl=c1yOWh27(xnvpkZ8EjSSqkgI*T^-{)M3+WJ40GLw7L47a> zJ7p|yh{DE}GPL*TR`%)I0R@fh>uWx1LVn-%15Kn`oR>#((X-cbN8-3 z*kfOpe>Le64+RV?eNcaxjrb}98H!iD*ot%r*AaB<1~$iPKSbjq%86REd)s%Z&gPJGqbJRM{FnEuCemD&p^!v1dH1j4r(}}g~~X9D*QHeabBOk zGVzp~AO(Z^S{p0%)2T6A0k=GlvQ)gipyNgEPJrsQXr_28j5@*bQ{uKv;v6=-n|*b44$I<7PIcDyyY0| ziQMZh@#Rn6yS`%8Cjz|$MBjVz0O10uiIZsP#wz#o2QC9Qs%$yM8Hc<3U2z66Sg zY@pO&FnGvz177nbq~#vh`2HZ0O2%@lzX#qm&07zghi~fYxSHy$7u=Y_5DgdD|P1EX?5}jVOVazn=2cM z0REu!Hif0gvN?eSIK0WD>Y!`RYr0la0S{?cB$|{-kaFi-m3kpv&aL! z>Ak7ztQb?_b5Kmi0Y}54^4mfKbsNFE6bO2Cb|NKqHaSi#F?0uBuiq^8;UTU4(IGNJG&f4_35yuSU?0@FGFesnn*h0t`L144*GQ7HB8@}6@>Ao z^Lt?mZDxI!G}k!xZ0ERn8w8q=i`1DO&Nel*kn8DPo_6HEo)Fay zXHr;sWi?x|HahPD^O0;CTZo{#(X;H{XMpyb(5<83HuBnVyYINiYS{s>tSjtSDUayP z*lW-oO36lN_?$9zIJMtJXM3FXUWcvm+*o2Wkec=98LBb)9QsmOjJL=nv1BY#^RjKq zO;}Ue)A%fo0Pg!$1R;j5sUR3V7+popJ%(E4&EbiZC=T|kTxt9_s0<2k!tO}NPvPJr z+*B{5ZaV8rJ9>hOmQ?%PWqPCed0z+B{CfAq@kUeJxmo9hqXc;{=QB|s&<$m=R5kJP z7F|>d-;w-IGNTG>|Nn&x+SMYqZ)pC+71)t zZjW{rI!X_Q13yUg-$G`qic-6?hqtwKO#l2do2X*uorBkza{afS992AJV{G-ClAEe- zW`p{Y$i%v!oF1(4nn@0aPWjZ#^I>@U#Oi!!=?Y&UuP;-39u!%!I?2grBQgHCATDzi zPq819Nf^0X4TL-9g->nuk@Wpb>v2AhiE1EV?oq9}xA0Qjo;ksM`!#~9g#^~#!)-eu z-j@Dxd%shmJ^F$QD8I>BQ@(>%KkDR9vi8lfVI{+_S(Ol&j9L)kEe(%ujBS$o-xC?W z$TtZ~SM$BzL_cX|l{Y_Vmh?XUZKo}d)2JGPXd}De{7cts<)><`Ip|x*ZS|3~%ebM+ zy_$b<0bpsQY1Q58=ysVd@eTe@iib7_;t$80HEM4Xct6l9@~I)&7v82m?k^Ghcsezm zb$TD~-s_tYtC}HIQzmVSIUX5NTch;X=NgAINLLz1Zz_;B11W{viE8&N4~e{_xEs_W z{znKyQvJ821qpHy)mpQlugHo-5bmd4=H=#nnpA{0BfQDv!t+&Yk|?z2sQ#vgao52) z5pO2BsiMvF`yUmK=iTk&ifMvD7(9j_dUkcOg}nKTC(ExBe-#SX5&-+2>buuf!!z8jnOBK;2dqQUal2(64{)8m6rlc^mWV}w2}Uu7Z1=*t_Ip;dR7 zux71e7ABltF-_tv$$Ev?qy;?ovnwU#4q|N7OR#J0^8Z>Q;s0DB>pYkV16|HN!}>yV zl|!2oJ+I>HaAkyplYLUlp`QZ9I#u{B=k~ZVaWs;VYe^LzKUmtm>M8pI&xOwX`QaayW9HYKH_y=&6Ip@{eT1^6GDy87HEo!q+33F)k4KU>V9j;R z9dG{}v1|A60Zn+K?zT__>?t%~?zcWUb38`ZaUt>V89$hfVIjV6qa^jp?VXmX5S^l7 zFxB1MnK{G6t(}{SCUa6vL#xr^=N&6a+^*Vg4YSUtm;y#yyPiadg-`tNRt!f+Agq~Au6d&HuC1$R+ zkc<||SQ=w=Sgoy)Z&Dme;q5px=PHxclLzUq$;e^jFyheZ%SR#F8JHh3EP8W1<28uz zrbsvq*`kochVRHN!Wc9jv3-$G4G2*sG#U;}if;NMAv@e=9p9DdGF)4J8T2txl<9Cz#GmrVC$p`{}-acinTNg0GIN7rdyy0XZ5<1_Zv{uiply@Sx zJl3401J^I{)?6EVbUVttC;#G6KYSOPCF2rjXTCEq-kK{%^jJmKc0f46whPxbhmdk7 zoT<%0%@_TVHp1kzKH2s4Lu!%4OlzOP3JFCfV1MFlYid;C5AfoYcL}|V%sGWTTZ&G! zGS~Or^|1*O?(ZD%x%gTSmr896MDXT}XP@6O?R~8wlBGvX=|h~NsibHMjpX>kC|y1y_~M^h~-_`IR>~hK(jV7!-x&;QfE}zzq$+2kKc))VliVPY($w?lr<{Y5jTz;HVLqyt~RJ<}$ zZ5D+%ZX$F~b#o_P4zoU%c=poinSbceSk{Ly#kM-adW-1+ptlJ^H2=Rf_>4Y%zY@NK zqPKN|{SmA83-hBHs*2c8j~BYJ%4bg}iTKx4$tDD`u=uxp5hwG5l%3WEWNWrB8rGF7 z<;C>s-4)J#7Cuze*==vOf6RZJ${!$K&or}=L5f3=z%Z9Sq`T!DB=V@*1L1)DNP^Y+ zaT0sIzrs_)4SeZD;zflb!HBiOd&>apWANN;3S6~lX?ye3(D=ABqEHcpl&746WT(ga z`?4vOD2H(an|E9WtblY%Zl1+fE$t&pgw*%$p99qc)`2GeSZ;xDO++AjQ~Z~`iTNMx zO-KGSKCGFhS=IY4CrV4;4wnJNoLsf-@FPe(3|`C(SZ2yM&|s^l+_UvZ%x7GaCm8JZg+FD)`856Lz~jaJR1|%NCd39LFM9T1EpqZ z?M=-&^xa>A2RNd6)ny-ApYfhxkOfU+vS@Ur4nH4z``C}*k$1s_s+A1v$BFtABz=St zu^^uymiW?(m77F@`8kDmPr^%=>F!Kbel%K}*uBec?n?CWhO?3pOXA4I`=D>z+b?+P z?04xp1vC+Jf}B)O-7;9lQBmIYqA^f_I5gUmMIJfdR}8=ZeDd>yes2^AgB?hb>+Zcl zBwH5vsiDjFmQ<{Qn3kUK((5NX+{I?TcG6*N>tD)apE zvMGWIKSNbw!Hy}(c)uxec=}`wK8@LruR!Si0Fg14{#L%OXZy`Rz~i^qx&FUy&y%M^ zy6wt!RJb&vrH)Ft>q_=NH=8!U=|v)L1s90RR)@Z`T?0Py|>p;+%@aF zV!jxhIMP3+d>u|ELCW`4ki<;S?;~IC9sOoH>GXHO+p=1*=l~ne2qPbz{SeMOv&ID< zusX5)#;jBYV8fz`1uYZB4brIb;m1^}rLvJVF@eWosT)hDi zdV?N44p{2mh{rmMOvsP=8#?tPxipLpcSgOWi`zWN0I|K$@@pkKXOZaN0=)3?Q|^Ua4!pqsug<>)Q6lKjn zI~c-1b|s1@W~zkdC12PMAJ97O_FD{Bp(h=4;u7j*!IPy9gb_}@h)DV&}5=!TXS^~>-R2O1)@LCK|Iv- zy)JNTO5s94-#}n+h)1?3)$;t$B5C+5MGXZ1}90eavd0>GiA>n5>fQf>7^QPGP zn0+6{_d@lXfRZK!=$vO9o&F6#4HNeDty~VE7rG2JgQPE+khk7bZ1hB1Z)}(t70HMc zn8wC8z8go6`)j7JCh=UkjXE)-5=82WUK=`*ZtAnG`_n+%-WSS zpqo=*5QRIcL@3^Sww5!0NM8oHXxQcW`4Ht4?gQwJ?a@@%K~{4iL-}$FxF1{OEbw6; zK>PC;(9mdK2Bc!|+sz2Ktc2f!vFXEKu$y%nfii{Fm*Lf`4{V}9TcZTiW1tGAhkki% z(+yg@KQW$u;-M+dpzFu;+?24us)RTnvt$+J7l@XtBbaaS85>({IZJwb(IDE&d^ zzTKaIGz1A~dEN(L3Ff!%C0V2^UqCtpo!kaM)8Rkg`*yTHYzT2*+lePZ_h@543kMC< zAAp`_K|qiu(Yx%tIYrK%qYD~fH3$!LlX{-)J>@?bF*(|3*i@>vR7TYk+#gg0{i6ji z$$4LZh#o948YIC3+~d26IF~?NVfpnn1y9n|_kmoGL0?_)ElS3HlyyzjL$zIM}rxNV$9@gz71P<;r}NDrvOdL5g>gX;G;qkHFP4-Yy2f7Cet1nHtHSo&A zlG2B>%m5*pMD^2elIpl#QMT{>kt@u5NH|qVNSB+pzmQrbRD(*9i(hG9A;`Cz09_Wk zE6^TAEv0*4RuXC&=`|;6>mSQ!j<`%d|5@36BZ`Dm_WcncnHHHldw}X5I9Tks?Qbdk zY?Fo(n(BZBc-gIYdT;cSx#|P^>e~O65m2DhEGXqewZ|ltq?h=wfXl@p!(~9akqz!PYER)VgG*t4#O;qa z>#bC4P%BWeIv8`A1Y}Cq`h>nl@1Kh(BEzdOtrx)I&u}8c+Fblg&(rCbabfFGyziD} zfb|pW$?tvrKy3Xzeye;uQ#>N*4;Rfc8G#N{7C8hgSIvx;b(7o} zh)>c?s=%L#z=T)!se_=gsR>ku)iR_ebC~l;P7T=hb= zkOy=*eaoH3nmZJR+EXlEvCd{_Rl;k4){gIc)2{2#p+AAFk@g+xQCD$gBcJA4wAaTS zD;fkn?H!h?Zi5!sZb0VhzO>OLaOGRci0~hLBE#N&xBm%o{RVQRif9|y$485`IY4Dl z%Fjqk>vi%oh+b`axgp2a^aAQyrLBiB3EJcpnSH7(<^~)`^uPsElW7kavJq6M!V)~X zg9`&)8w(FkJF}DkRamVmzxi+(I{Y%)kAYUzr%3D#QusoRAR^phtm0b!S{nY=tAJ`G zrO$%(*#V`kjca!ajPUIeosqsH!#+Fn*y~_s#cCV#q-iHGN%=HIS2OS5-0JM;{+fHO zYM2c&>Fxr!BSMg$%l+-=b|J9v$Iq=!FnL%k&{!ZSCUJ88fIBWlCO?fIos^<*6Yt^g z>fQlYk_;AC47@pL`mm zXHV%$Nq`%ltb6hzLluD)>}2Z>(<8d1o_I~f4w+taJ@yFTT){Ohdfu4=d` z#IPtFG^MwPf1gjQ1N%($Zl61fmuf@0&O8kuhhnZQUp!iX#2 z#ej?iTe#B>TzuK9bZo4jAH?;%@_TyFi9w{n7Gv5M2@dI-a;aEG*bhtjWaU2BYN)zns7>t9S zp~;V|xlfxPk6Q8xJH)E153p&Qsb`C$$-C1tiwtK8(t)oaCrN(T^$dO4 z|K4TxPp-bN1{`?(Jy=gy&qC7boPS`l^AB`~=W3%s-{gxL;sIsIv zCQ5xb0{BIS*VA*)C859cFU4`v4upQ!C<1XJ$2y|ac}NzZ;xT+{o3&R|PL!Wm=35UqY#KXN*d( zC?h<`;;A1t} zR9p%1gT)XgQI1D0vVUIJ^V36^h$QEuem>PWn1=2uig2~NKTNJ6fw59SD6SWf_yYX@ z&Y|4r?Z0g&K#aMj_VDVLy85%ANvV@VnA}dwv~Dr{NBrl5a+2?>Tcp9dzvI+9^H4DL?_bsAsj`CCYq9_VazrRgAcQ&2T zwfgc#gibKl7Z#9IC7W?=pT0?kLMDhg$mHg`IZ$(e^UZD@I<&Jh#v)AE>Igm}i5&3o z3?&s|ZXxm8%~IU2r~|y-f<3s7z8txkdcSJ=+uvv0cfc>bb+yCJC@-5aGlddKKM?b3 zzv@HJf~4#D)nZdR*$l*?BY_EX6(A;98*I7S-HB9UQ0!ut_}e75{3Gf&zqRKXRZ9Qy z?mXXH@Y=~}EPQkjl=ybxT^WD_zJz})ghwXfOd4oGko@rJoJ`Y5K|l2AsPHU&!ZlX# zH5;10A+GhmATIr6=i{U|z7Sehz)c+jTT~d?M&;L|^U(}F*#9)pAP3>xNprQ%*0D3i zzjk!ouMejS!iH@UBqLb)%v4BhGPd&Xq$`fz-Tk%w-IA;5z>D*J$$!lVU!%PXY3jg2 z_}@lS5gwn$E_1cvl4%|lUG1Wg-*H0+)vsr>z7RB(g2187>&9!hX3CV5c}7&N+w|jAed?z7U;e}&c2$A>&i(`nj{nPfcY0lJ-lTB*lyGh7WRBA--?7@7d?a?~eJnYPM6mWdc$?T+)+ z0~Vfx236$#N`X1&^jt|8Y&A;OPE`uEwwksO{I^1TEp;bYBc7d{QY zA404mjpchU^xNEn10{YhBqiV92MnzFKlaDU&3j$(iocRGtAulDrAjkfk&M!bWoU^H z8b0VgRJn@fD4GBJ-(R#v9>(yS>AaCO6mG%ZguO&0e7yeoZOestLbkrXF5JbRN@Ytdug}<>fIBS60umky;BP%BQ~8dkb~W8an{+-8hsxqzcqI@-{Z#oy_~yVVWO*Xr z_V&$j1_YB9rSPpWWRM%#``JJv4iFTJ1Y!_xZ2veH4D;RvqC!xq^AxMtS}7{a26{Hv zm4dt{tUe&{vjGC7vc?^B3fCFGhK+`4i$IJgS-!s31!A77zw@WJ zz8hMfUPsEw>??FToO{YMz(DqtTE{&HH zfXskC!BY&xYCr&zTIx-E0DRHfWCJ1K8bOz#L1Fklr`HJ#Ift!r%O6e;C{vF>QxFm^ zn_x&p2s$_~k5t?Rt}6(LEbs91lR=lYfk-+EL~l4?cwYc;ivlTtY!KnPp03y0U!1u; zv>HSO*Mx}xUY$~lx0iYu;@eYCg4p*zeIKs^;Gj9J4GquQa?)*m%!x+!)mFMt0*?r? zsNd~IVNw`4RAEHlc&(B>u%NwaD_-#~TD>*m`Z>sNJn%kq1>zKfK7m6rAp8!bPj?kP z-tx`>A&a8O^2$(=J)lxSlur-=s&f=Wy&05}?@D2Mf<(shP!S;)NT7g4&H?!V2HkhX zh&l*A0Ca^Q9Mr;n2ec$H^gc#TVmA{7RKD#F`iy*HeS{f+!WoVPT{g%<3E3h+Q}|5K z#G|v9()$PjTt24$4)t1>W}#Za+!>4MbxvvWVF*|>2b>M4wP;vxf=HOafx!J%h8O#_ zw;A_ro|%x;Sa_b9flFEm6z6-g>}#89vC-FtQc8%y0RtP0ba=$_D)DK#R!)Ww95y%R z9uS+Va=ZfyfJO_UwR1ra5LV+)pugw@=>{Jvuwl_(1HxiBP!|VyWs;6g++dF9YQ>^klQ|+$&CN zBM&&MJit|L-RT0lryPM50#`0kbDHvM-Hcoe&Q@_%%oqb67N{1M+>8=Rz=vwftLmMS z8vILL@vc8#=52v`t2ejv(eeX4cX%n2%lVgEH6%3lTCYzoQ-5w|f%2dCkWBx++`TDz z?WRpnH+v-q|!p*STPvSqD2Gb1UgSiGce1VRp=lmD?RBV+`exO0u|pVUnFrey>lX5PLSH&r z7l5Jo(9!aFs&Rr)@|al#7L4tz;s&Tye{orLnd#B+8fdUqt+rI@QR4^so70~+ijH6Ks0OKn_AGSaj?-jRQ*&HxrCe-R@b(~9>BaX?Y_#ouMLpu1GCOo9>SX5 z_qwukMC;1flZXjg1wdGw+*1N1r8L;nn;eQaGCy7+7kw|OlbizYl8b4c*>A_LG}bpb zQ%LY(UL5b_G;M@)2xcE0{9v!4)R=KNK8sSy7rqAy^T>$B9tW4j=C1TnXl)#d5;k&L zP0plaP9Btbk25}kO7mT)N?g>HV)^~ZY2OXje}4Ma3gb#<{H$XTIl8&n@PW)I@miP?whdOfmp(LY zU#d&97bm5_#3d6d6f?fT-})fj0`ikJ)moTuK^L8A{fqFEQILrm>i!7~#2`z_S_*z$ zy!KdrW`o_V=-%eEA*=dhaJd4w7cvtw+zK?l_g^V%xghx*imz(6(8`FgfsW6VubP2^ zMN!;L=nHPPtJEQ2onh_DT$o`jP&_zs{`nOdoV1p%?-|}FjNki2d8GqJ+#o={!q-8m zuy4J8*=x1mK<(4q)_>{qybTpz+4x8XZc%RWZK?hID96Qb!~e5&G_4~q9&;+830?2| zPX#y2tv|}Q8%*s*H3hTfHU_cx5r|FFH7UI@vIW<4(|m1R&h$9$RF_Xaz$Y0hD&An! zfeQ)}jUbe%-wV)OgJI= zkSYzLbvI7rT!FWJua&6WlbRdO7V;c$6_W)1GNZ90Z-zt95ReWX9vgKete6|$94L3A z)Z?p?>6tU{GDJ>%Tr39I)%R_`^4p9yQ^vLJg@6r8IRSSf6}s@mdj`jlNc#G@KTnFI z+ENHr%159Sbjo^luM#t9K>xlq(Ui?7me@(HM0{u;GM#V8TQp?4(2hbD00Mxi)m;fB zV*Xbc{g3cg)6fp`{G8={CW!h@Mrva!BeiZ^4hx?1_xj@n-c3#szXUyua)g^xmjMf+ z^r9Ze*f>P#D9PPYs}{FVoi)r|!9B-mH#y(1=n2TI`M^9}mT5desaaM)8++XO!WUO! z*VqnR9k#TCk3r6(&_gm@ctAb1I!pkHcIxliF*eFtGL))5gC@+F^4D(5-A0$ki&NJI z1RVeb-VNSDnjD!o^BtpfwHfe0zaQ1OqNp+7 zyS;o*=N-ZG8j8$=<<2#mK>;`qy4vS(na#PMvB-B51x|%)^@k7bL5KM|?{hlPmp@|h z`IOgd^}V-U-^^Lx7xNgJbWFso_%=ie1m3lu6Gw-64ZjTY`B4K;Q}@_$tXKeSnIYVz zuWU^(o2GsIs5)LoQEW<9Y8_=b(A_X|yB;$|B5#|P@n3>&|d zJf+D$5k3rQjG~f(s~la7GcxGi;g*a{3b}VlO3VY;YK**%E?MsC%JQ19{&j9w|1lqC zxtIk`am4C)X8s~y=QVmq8j!SHFfXP4< z|6$PK1)}PLsTl!NCLh6rTvnJUi~7HkWdDf4JZfiz&b9)0aRlgQ_N7$gCWuTpACODN z-+M+<<0E8&=@zv?ny*o#XF8hC0slv7+bP*0!|%t|xZh{1pAP%naO2spn_EiBC_{|x z#|}%aBQXL)1sx6&D3d~wX_8?F*X?I!aPXL8rE1PwuVWbrZzilvB{?Si$nYu6zh056 zupG7b^Xr7u%8sGWWq_W9L0k6d-J#eeBf}T|MjpQFtG`C#gwMGt2!)=FmQNI@N$CMOPu1DqCilQ>8)oLF5<3Y3xA8hv+vr?ZAW^%O6nzKpMR<|^v@%GmJb2bp z^pCU(MCM}VGmE{N$tK;c*Vl$!7~;WkoR`!v$pOHg^s~7t0tijPe!3nzs$>j(n$k=; zHhwS^On*Vb57xhmr7!ZbQsFEdb)b;OwLfS!ddY+$?6v1NbupzA;hyOlKf0|QJ_T6#m zQZz|3*#t1sR-)<2`-f_RGd*fm{>d`LopPf5drSZm{P!_kS@HcL_*zPY*2(@!yIB`+ zCMmuV=rQW2kv8?QkW+VioRU7~q0E!{_H^O~?q2_i#M5n?k;{)jrsIB7mcRpX*P=NJ zn4O7l1(ZG)__tCH-|OBo{5)f<8V&AYk|!P}OsU;a-E34yeT1_pPwMY~OsNU*W4&0E z@gv6rL|Gwqq8~zMlqxieq1$mwKV}rAhWI=d1nM0wmohL_=skP{53TW-qHh}Zo?T;9 zrD^E8QBeb&idK~^pYxhvFn!okTb{{Bs?AIMagvrv!jj}6@md#2<2{tgp|x61A)f&& z8cewtkG6#p&1`+Mq6X6yRwcNbY{<>dgWi+Jr3=$pIa&e zcTc`XoGcl~GFqJXTX|!e)U!4M_YSA0y(urKTuJBd?5#R^ThNZoyxSnMbe%L)B5q|F zuzUdjGn6eC;|pcmBqYNdveXMST5?oYx3z5yPl255_2-On#@x(-8_1KO;4MoEgv;Jh zEj^rmR%R|;rq`5v(c&G0oXiHR9)cP*x6MOC;TiXz zq5JL88?(~J>=v>`GaAA!fVbF5Q6K2FM-0?WjJTo532b^tr|GwIbH_6W>yp1mHXximJSfDcF zqdzTrAjMIzvWWs8@Sv^Ag=aEXRr`<$y{x$FK6N)zJM*+>rN{F7qCVMVi*(PjWQ~G3 zEY6G}LZ8%}3N&D0BBgtLjGNJ?>!%*}CEIgIBVXff@z^)gbE`pWG6j{h5})8hj! zd2#6F`?r#@=QVsbafz7*lsV*|il(zI9Xjkh5n{IJD{&&Y6-^Fvm4e4Y*i+fB%rYrH z51<#YNgH!GH(+pgZTI}hV^94B2Cr=CH&IIZviwwp{zvJU_uSuA^z*o?#1fe(-3dycz^ zF0jZm|_xF!B^qTGus|w= zu$RQd|K7BIg`ZkE1aRy#)4)Z{sY-rVZ6QCS`qV#b3Rs!&pm%vgYS_nK13~_W#8wBL&+Hp?b`kA;vM=EE$WKakeTsN zORf!!kSvXCzEz9mR>2&J^7#Jic#?3%shdpgimiMq+JnY#ju0Swjj@ktBIcjS^#2ID znsMTcJE^_(f;;BOrUy4~HM1Jzrd}c!Q?@@VpNyYd5<6!i{t>%kp98l68!6s8v(Y)0zQ#DUPGxmx1IRC z4de3vtcm^Wxw+}@@jBtk<8RYnlK4c1uQ&%2R%!hPGgJO9>gKy?tB!{8UV|G(aL*{o zG~T~m+?)QTbZ9h8{^(^A8Ls!%X+6Np+4pOqs>{Y$Z}kv04)0V!14iG>mdg{W97ik| zjeTmEHRihaNzkOUcZ?81&NN;GudrCTxR%qVSKP@kVnNb|RAd-(1p zOy+#>x$F{@wtN&DVPNBQ-S)(L==wb)21;vm@7}#r0y3Q-J#_z4A=PP+J!^6+`Xn$= zphXQDx6(lESur;U0R%zsUse6gCpnQq)uZdYGz(`WhMrrq-@wg>s}MML_m+Y^7XGCc zvNtzqn&L$TJhR5UqI!45Mrb@;RkO%G4<-ydtNo^c@YMR zKY7wPh%zRkEk7y*Vg0Zw_TtT?+W$y9}7iq?>G2jMqa6g>ezdb&W;qcyC2P_L5i>u zllqn>>V#no67b}JHD<&A6Nomhi^VOgAW8NTK7qW-6QHBsdM^)T;OCbwUxv%fP84dt z@rR~-8O}2Yh_om4tK)V66;Kj})}9nmOcGQsKXC#D!~ylqTf0$WKHj)PP%eMi*~|Z+ zS3Krs)cG(hJHM|`8Fg9Ft^KvuardqFHT$ovn3z9d?Cex}xagXZg49wp0zzM7BD{BM zAdFg6(4ws^F~>KPkXw%clR|;R{cz@P7StCB>C3h)BXg{9uftDoGGh5 zGPD5V`$vGar33xdd@^rk<4ex1I9vuc_52_xjONItt@Lr+ea#Hq)N~U$L+o*Z30KLk zXQ1_Y$l1H8>9n(Eya@gOm@A-b|6|OdM`CN5FtlTvCyy=V*vY-ZJr14NktvucaES(C zgMR9?21eEDY@D7n)|-Jdy&R>VOQ;1vBr77`V)ERckFok)ljMJ})>4PW#$8!Z^WWQQ za(rW80}E6IUL&S7-f%i7GZ#ZbfCmrf|7y;lD8X?@;0C+ze+;AcFMRQ$HiYnQF2?#N zIVbGAM7Y06*!}M&5RyBdF%&mZ1-bK=TT_JkS#mLQeucH1va!H4tBsYJ`Xw*cB=ZH3Ojtez3B$kUi(+Y(NWhLN*=3|mOVR>gzIRWYY&`jWdMO`W(1)_ zhQayV%8!`YuKo*V8nN6&AHX&>Fsm>sJ-P6$+8VX)hxoqjWbLSNXd)dEU@wxUXoxx2 z!_xs&)NP3%ghJT6kYZg+?zp+}RY$c!4)=MH`YZaomUEnuj-phPm2wLs_M6# zjVnsQ8KXXChhsIqe$CA{`uUX_TkFAioUZ#ZP_|Smt-`8?kq#OiLB^UkAdqvCxTCEZ zxPpWY%frRkOrEO}XHifMR9)JRk$h=Bn4fE+?6uMtMp%s%Rg$y|eqH^s>@k`S3ojtG zl^J3xjR><%UBWjzmiojC%BMPhZX+`64Xjg~O9c5us3%MI(`5|T&y~Kj7b;~}dwSr` zVx}=qJrxrbpDB-N0)Bw(I*v|}jKA)o<4j;`UiO8RG%R)22G8<4;|=o&Ee$(_IW`M= z4mu3Qx4PSJc4NKZv9N4*0{oQkBWr0*xX4;if?I6-Ea(j8YMSM7`F#Ve1vXj!JVo_U z2HAb&`QzfMTMC+pb-K6AEe1PKKIb)iCWQUoMM2u}R(w(S<|zm)|Jle=zWi)N+wELL z(pSsob6482s(9YBtu$^f6~v4fkH}bTp4;;EL zv~29Xj)ljpsyV3&^0AqN>UwL|27dD(K%_MueP$jFeV-YlbUcGB6}_WIA4WJEb1ECY zgl@ItO{ok~%SW zt%YJKOAHO={)t@ZWm4aKDe}7jk}+lBQ?e1u<2o{RelD|o7;d^qCLd|JSYF$13K}{Q8OYR;a`dzGeF(*6ou{__n5b^k)i{hMHYLcF|Yv7;w@adi%E ze6)IzS!aSUc=`u-P6*pAHJ>taO^c_MFD0dBO{M2zP}D(bCoDo!Q2GL^%eWysvOCKJ zS({IleaTFo+ToJerJ}#ZDRtdn{~5CK0aFb8w08(?!wYNBF>bZ6zgeB(N$&N=+Y>uN zrriviqMEv@4Mb=pWQb^jw3e*;$Ms$kZHqy1+~sWFl>y_c1U$Pes`d7r8gtF$|2z*3 zp?VZnOMa~bfxBqi}1=gI?Y6suXQo&Wrp0t3e5ddJM=E9 zH&HE+T*k$6<6g%s6feZEhS(tz6pzSNBE~mM&>ygAe-gDVk8H+n!kPlBehgfIdC?@b zNK2By>c#scstx*#$8BkaUP25UKrSJmdV2a`9|8q`&Y3_$96ii$7OP(5iMTjA0c5Cd zr%N2^SdGdJDSo22zAFw;81F!g7VG{)$kaAqMxes{h>29*!lYnx1NoZ@+h>=EaKV*y zZ}R-UvHX!UP#}E^F{#y#Oa{fOzSq#sLW#na1S$+(0AS59XcA9y+WWe})z8 zL|xzMh}jHPJ#??@{rRRPp8BOI>DUE@v)(w4prz0vcx+S9$1%L{4=%u$m9A7#v9iKL z9O>|6y16U#huoCeQdyHoA5#LOYCbnFnjO?L|yk~xH^7|H?+IoOL(YF2Vj*oww& z2}>$S-VOpw;I_-xsi6WTGsnUqGg`{m;@~u>g4$WH9pSy#X4ZU#(%|fk`x==Tu|!DxB^61|K+w1 zHij@`D)Lse#XyeVOiMT$nQ43UF$kemCsPFN{Kc|KSt!X485YCmUTp5&E{A8QdTh%|_{TT4A zV!w`iTOA^ZlGO9+GQFE89M{!m&ATti0);lpZhu#(rXh7b3CdxXe; zcm#ratj?jSJ!XC)f@;iP*I8DD1YVoP?*lMfspn9EVm#s;GN#-!%SF6c!3Nes7M44F z%BCY>vkuNUhWOANHj}R~rYFMD zIUz0}wE8G8&;TSoyElcvB~U@D;slnmW~S*8htE`-QAq}Ug+z2h^X+Xot>#ZcV^y#B z@*Q{dV!T&kbc|K)l~M5fyO)rTSq4<{JniRM0JxCE4aWv|5)UyAyh)8RU-Tcv#?c`X zA9}N#WvtpD1pBX*&0*mT0wTzfd0W(l@hC2(frdpq5Dj47+R^Lt%qN@`DGUp?+v{q&Cq1Y zgkbf}G7>cWS#jh+e%H~XO`eS z5zqcuD8eK#8jNeM8i|6PtR4G#z=ilts4b@z^RuCesEMa$dcPq{x}b#LpC54tv40l? zru}n!EAOBQdJQc~4H-TsA&YWqUOa*F4zh>~NY3-;ZrqUO&-rL0wQ>%XOhiZIlBZ-# zugf7;ioWCiEN#+vH}S~Rbv?Cv;DENb9Bean*&|PfEcU;T1qd&p7hB-}_+qPkEKx7G z_Yx+_(Fj;G(D9i+gf^)Mv0trB5G{(^e424XM+bFC#3o-1`53+|u3O5OS19%C6LPcO zI3bSpn{;$nIWl4odR;y|BB4j@9e6a9DV}S=UFxr|Dnpy-j4$DbLi8fi-e6Fq#a3-V zbJKslkKXq_hg!oNKghXK+yt>MGqkfIBhOxyL(p~?#*^@vbUwJxmM^Yt5L&uht8Afg9#=qnT3VpQ<$Lusc<6<>tdNa++8Rll!N^7 z2{cQxX?;C}Mm3q2*8>Nx0ryD?`jWVT7MdX!Lx^xGZP|vR6h(ufq%{5VG2@*>>QxTq zG@Mr&Mb;K?hiOb5;nk1kw%d-KaoJ$;68`d-o z#K%Fg9*oT}&=64@!N; zk^jKgn>y~qsc0E0h^sQIZ4K-eR*Ad7Fc#=u^sDxQVIj!$1B3>O4BxmN&oc}o9E@~e zHXt8TJ%XCZ$Y(D8W?F(~49cn$Xj*~Tzxl7-<*&f|7LJ6d_L8sAtapdrF@55#Q5yxs zA=EHrs|o5*NHZj~4PGlLgu(_}>pnEqS}sx3&jipK`a+UQi*0hL0pGMV+US~UgFBq; zK?}<=T*Sy8EYh%2pFo|z`3wi2ltCQIN@~e4VzC7#`JLWIHRDy=+W;#Ep`Us0EeSxo z1${|)U?{?9uX1Mp?gb_+87=rvs^WS*_o6{4A*z`O_6b(yXj1})+2KxfvkgdKzG^26Vnz`fV6`?umv5PPrR|q@^X1oJ=7rKec|%vSumDhOP5(zb4lRa(MAT_8 zC`LA(CsRnu9Qt*C{+tOf7uRT4E4W9A^i(DzTwI~tt3c!2a(co6RxU$~!%AL*cF@Kr z?L>@;kv0?{5Ui7_Z0*HdsrD4F6q~g@2uHCk~fxL1DK zv?sk1R>ZSQGu`FLSY13BWfj2%l69lm{tXPU=HE~cZg3zTmeS7HA{pB08c}`eh}`1l z!5H*UkAC*P$a}uX*8SIymg8KyBAYD_p&&bsT?$_ymk)%`rp(8`^czP^Y~s2$WhGdBT%9pG8dY3T5qAd_&jXhq-8 z;}Jw*G{X76WA;Da(7&A|Iwdkyb)4Ea^iuiCG0vfoxT8;%EmhkXaAbnlP@dR2{bAHk zv++I{A7|Asfj5f6lh~V(~f)_vw~d&_4RS z#1L6;SHz6wz^hT!y6SJa*)Qx1H6TXh*2L^aC9q%2Bf1J%8&pJCsOc^{-~EdSb01?I z{|;3PuwIfDW^*y z_+^93ygd})SFS#6AIh+1{L$EX`a5wILlNjAIsl$SfpG~?_+?C(aoi*{#k5?efcL)}HwWfk0t z2DEM9{L!}2aghQSxqUnSi&uWDl=LU*vHuqc{9hIb{7F{gKa9G_KZ^StygQen5c8|h zd$qAs%{sFf`i78<0MMv7jdXPNVEIA9$}zN|ocU)k!#pqk)?!lGa@6Z2^+EL$)k`PR zU0+&WOcG0+Cu8c=o>ix_fXEuTk)m*1-1yKr!0gkkofk?-FeiW@62F5vb#HYtQ){s> zs~WO1l8=ZlYG=@Z+YNw*j{8I1OM-4|XP;2F`#qkqy1pY|QvJ$?H%P4(8K-gv?|Ryb^geeSg*Zu zs+dQDZ6T)DCakG>80%^pm-bf9{6Tn=!*yQzoH?b=tkIxuVhzH-G`4#1XzX0AR1JNN zRE_y>H_)OOh*!I%D=A&(G!hYQkG~-Rb}3jwI#l=}-9FrTyTZy!1MTt9+%x z*5D+^y^}Bzn7=Muqe!<2Fqe}Xul8%3Lh_1|t~w-4P_boTIkTaULHX#FZc8+#(7nM_ zK*)h!;(x@n63Wc;^;(x31U%?J)@$VvNAK6xYwDT>?70=(N!a`h^dscuIKu^NPN5Tp z(eN@(UUZ_+^GBjElI3eNS-`;R1as6R_pA$e_~*SRAk?{WoojpjUZ&teIW&+WsU+om zO_2ifl<-Z^`}9q1{br|2e!vaORCnWKB^!6!mNFFMyvHT_NVsdu=k);jv1d6_NL^$$F!@``+ORj|#U2A;|}S|`75 zBLAC6d`{x;Fbsfo7LtFlNFe1tM0U}P@aNWeJCJJIUfwCLTNx~qwtCeHe{^f3ebz%Q zGHRj+x(rQ-BZOTZUYu>mO!2}C62@_rc^dk2XLCV3_fA6spZMBW{$s5smdfHt8Qda7 zm|-#qoj9$?(a~U`m(=KwCB?ea(6(odJwNP4DC{Iw3C^{{mubbM{GDF?(XJZ zkxJ$*>{63`mm;-$#kwApy6 zyzOLkA{^}TR2)WnJ`GH+#Tq`1$U}37cgPb3*okx0h@OjHyN|aW!gZQ7J3+9ImG7?2 z>yzl$!|RajHrGI0M)w+h!7+LCc^3Y|Wo)Z899yYzN(}MeM4qKFrEcN~lNAM>u1exf z`5a>Nm^vqxlnHPiS+LzDTDp`4uwVh+X}>zh3Unm(_;*fQ;&C#3CYK6mV%7DR$aF#Ilm7q>B&*P2C82Ak`tmyNK#?93 z0Qv7BW>c!L)a*}-Ld2~XFc%NxRGgv_v}K0Iw?N=ePl3{iiW79hFaZRr(jWr*DV-@|lN%!%lis@V z-><<8O)T9DZ&QYD>lJfa938`Z3;2}-g~&0ibd7d)*F@6%Iz&VYOzGPF_*zzz4HUs} zOrCDtu%E`(IJl0EI;;xyw<}u+J{f>V!VORqUmmOPb|XI16hI)d&$(F=_$(fozHr0C zDu8>c5%}TEN=X1zJAzP-fq?;{KLmO@7)VDS2v>|%!*Q^pR_E?yd<%M`I6|K3FU^(bOXdsa97W0j z^XFT5(I3@P75eDmYvjNQr5qhN_g0>(p{VJmAkrPz9{gI3q8BQwH2GeYF|2C-o^AQx zAu{cSSw5R;^`34F07rFw@cz+6ZEm)rq30C{hca)k`RS<;P<&C~cnOJTX@ZqJG#-&M ziUc9-hjYzvecXUFyBB2nJ!(e^b%b%NfMTI`2+%btXiKXB%P*%`2dl2c(GA``s|VFQ zXmWec4R_;X#?6_R7mYRYRgX?kCiR#~CE|3(XH@RZ>!1ygkAA<~#QS8^&T_K=d!smv%$>jlJ<98{zARWtU3R6-9pFzzz1Oa>AVm zAj0?9WFo2NR2Z@QWypZS(sH1LDDN5K>d#a|duh6f4#4xf=bVf?Vo7Xje>}p{i64o1 zUx9O9&+|tUOjGWHc-9iW;a^tn$*Z>e@ZnFqUSSUd9FQGMXd;AK!hnaCaQ~;7! zj^8wK)N}oUt5yU*KWJ}M0ga7!GE82MJvaMHq7mU8!gjBYgcFUtYKJWA z{koC9e!+Pf8Dg+1RjL%rp0NjqD5;O+JGa5ysWgmrK5m)T!TM5DzxR**tVVr{-r^aV z-b>^cPvxRS==azm-Q<@z#sthLdh;|su;+`#z4dUcv>JWHp;eJ{esMURE%j2zquHqo zlcCFyhMpnIGVer=bh%nM~ z9%I6X$1Uw`>B;m3k9{TJi%he&_vAJ} zqbItABl52$oUZN0&iIBFCTz(^7@4=|i&7Bus5$+DlpLYM*5a|-Ne>peZrRVT6=*fk z+X$`?%;uynjHa{cvw1j@of683Jw}w{y}vmW@ji`Cz&c-q>q=h9MinH|#h`gJGKTOX z>dJWb*jDm3ldIWpWdiY?W@aJKNL^DwJl43q{@lO?#TTkY7eGiW&N#9~C5|JC|0~-d zayLHm%(;m9=fui9jBKz7zuE;qOHp9!7l-NFklpMeT}8&MiR-+6sr;!1&!1TxgB>>0CVRyz#4@4 z^YalJ#5WUpPB4smICAOL=PP)`ZZEZe@3ilNR@vkRc3-QlrfpP0!Nr9TL~R6Mx?;)R zKbJ2K_S8(Ajjyh+emRIchdRik#U8l3`tW*gftKI#GZ;5{FKA-naJPEk&>6Y(57W;} z$&J0iZVhfrDaWqme1`*)?a2eKG(d)9m(W;kMx z(*E)RlEPeVB-SakyF{{yTo)F}Y%3!%8pKv(sDG@}>2rm8;TSqsm%5hXY{ZJ#ZDR9~ zN*Wt5bF5eBJol`D?aZke%MS8PME>nj83#y~B;HAIemV{X9piFj% z7I(s3>+dC_TkH0d1zM*=oTZP#kB(s$6c1jGZw;blvGe%Sj5psd`ft&NSCd~f<1HRL z9~QNZ{Ae^Sc*|Zo?lO4}mZvSLszhuy))rLn%XKZ%duEW_W3%u3G*#&N*pM3H3$-b6 z5cN6W^f~);8Zs;4{+wdS@n=`WT|{=JZcsX<1###L=^vXoXynf~PpS^XfDb z#ObSn8s064zW1y_JL;wGv9BITLKAbvRH3M~%^R+1_~O%j|Agi>3D~GU>kNfaa|RMG z2^y>FU5v(y5ur2|gey>2>hl(BgZ`&HHAaj|Vwbm=4McqQ<|P<>T&z>)jzUG< zwdx=BP$rcas%mDxiQ9>!DzVRshYXQ*L{v3}bjJMqKG@sE&G3%HnMvJ-Sve6d>$`j2 z=*SFE{2e*w`W1eK9k+m6M^RJtK;!wu0wijR3N&?6ZSaL7gPpdc`2n>qh+NU8Ie~*q z(kIwdRi9L+Y!7yITvV@(_Mdn@(X%k>Qe(A%_dzk@B+&7`?paHoQyNxW8ft>lF?$*Y zQxYw{DmZMg`t6v$Igq#Xd3pEu`FK;+@km~8NAp_Jn|SX!KMfeL(hwBs6QKZ$_`+7c@lx$cbRG4P{QUkpAact*Edvi~4yYaj>I=0$?E#CG_yyYoOYiii| z-tcRuVQI8Mk_;0Y4?Blv7pO;vZaqr`e4Q$F#DrCIC}0uL}d#b&}QYxT( z?P~X-2lrW#F0T0??-&Q@MrR#i^eSJSz0RSbvAVnwOfpDS$|r*Vo2iVv{;p2E!KRK; zYJ!>KP55g=<-_g5hP=*x(cOy>k3M{}FeKCY)%&Lb&SHfbb~G26$j{U-%deR!xz*6P zVFGK71sfW!v(UNy{#piNDW-J))l!V#XK7vT?XXv%^ruCvdt%UGcTHh62_aNW1@c#L`e_r8Z@W2F{bWQ*pt=T&k>M$95;C>P7q z;Bt1bnZP-J8-w%|)*~{3|J_HIu>{Ak9Wl3n!nwr3Zf=+{rM#*v*W5g%`z3y9ZZ!Y zY~qrAO+5v=6f^N@(H9?b@_Q>%|IM#j4m+~p@6z%4zLZQR%ZEbK4WPUJcuyvVkae%i zlQC?2E(~%Yb`BwwIEo&}jUR&{?INU2OU z3O+3^gh6(qzg8uU`UUqFe*T!5C&NSrVY|!!MnCaShP)v{(`zjWetx=)eD>}+Hk&N0 zSmek{4c4&!zJva_@6i6N@_wq%0>@O*+tZ{`?FpY=n^jOU0O=Yb11n-Cily$go(aGB zz)N-TS&Q8!st+47TS>@)KP3Y#`0=lo%)m#sqjZ{`L!|Z(#Yp4^|uZUDKVjN`;B&%fLw)0>-;*{TS0_g5wy$_xa3%VNTv;% zG0{e#w%cS;RQE_xZ2u%kvo^r07n^-Nk4)lwOnU0N9~LgR+nSLPBuc<7y^Q4I^a9qY zfVmLF&1BD1QJlXW1ljs&hi{$p3Ye{+GLa5SGq0?2eUKdH<{IQrxr?%KoXOSOK$@0- zN7`;JY7P|Y(8I5qLG@)I6bO=rF**>!NC3uk*~BLsp`=37>UQSYrb|`P|uVI zq2hQAle`1qq4k4|W%R0+U(!mFgwjY_Hu7JtVl1zr=DtDWr0i?6(JI7# zqEPH6DXyD4EG*~LtFMKTjl-x)yBX=I%%-bjAc?7}3rXc0D8|eJJDtxyokSN$${0v` zB`{u6(skx;84(M`xZpi8r{uDO>uHHX6^jx$JYg6!d>@0XMPDqrCrQOg4b{20iv(Ed zyXBXZqda><&QjMlTX&JOU;jzNuGOZ=MW}_D&PTuhW z>pD@I+p#UXkXD!~*=ei+0;9J>P>jyQ2KGzkLkX8(_#C)NI!o~46VvGP^nzOF<+p6s z3u{ohFfQqY#F#IG;anu@I<-+idLaEJ^ppPCYIg^or_X{pD>kO@pC_Nl8ME);fIMF8`ITDc>R_W2 zTAplbug>nT_DwzXFQ^9s#2DHlKz?$kJ2f%vP>*942g%UaRU z=b?4B&kI^3j6fUU{2nnys8w6!(_ks;T|Kwim^&arb@r;nE8xT%mAnJRCWFQmU7vj? zNqd-gSmYuUe$RX+Kx*hry3k3r1+KHzq+ty&gMBG5oAW4gcoRknTjKkSr3FYTLwqzw z8=i>qBwDoMd-3!o!xX-@5BJ$tskAH&Ff2wZ3U(fn%96@LX`yQLh zGN+7NIb?TAdqgdQ+@u`gCt8}oU5GzXc}ddRC?$k7u#$5ol)L0Z!g@>YR0Nk*`45S- zL@uh10)~4&EPY)C$%4YiF|a~4w!QUh7%%i?22^h=gqyx5VGmcUph_m&HA<`T-gh_a zP4&}u?7Lwsz8=%^wX2}i@~~?= z(cLhu&Cxv&t7_X#T!1JUdU6@oLNoZZv`wr8-3v4~F-+0z}@iI{^zO*~QN>K<@p+MB5LEH_%5jgyF) zpI?Mtn%D7XcKNvoI7@~Ex9R^^NA2&7=E4abjNtX$;rbAVeCC2GC)$S;nYPl@PRymC zh%GRhD4}XM%5%_E&@zlivPSSMq@YJRt3ogUt|~Ronnj)wU|4kFDpq|ZoViiS84whp zJ=1JT{t-r~-+E&|+i6>+N&A&XEFfpv)X1*b3p8ZAzf~9|aXlgh*0(HXUz4#qb2;-@ z=8aa9^lR49g&@Xy)zlM8A&FO+=_~XDex>_r&s=}ywKdZ68GrpvI=`r_()WGd+#f#M0pEv_fC8U`L@tp|d^l{ReS{-)wRFVA{Hb4T;X6Fx8EcQVtwgTYmEh zlV68n0uvXR=j=E>|77k9%frveiW}6EbyRsDQxGiviePF1WB62Hvb<@Mopj_lZBcGo zg1g7)reH8>&cCtyy zr=KFnOWNfV`MWrSG?V1%na);g^2#wPW^PhbjEnG}z7c|p#avybg)N+9TloPFeg*9p z_Pj{|6LPTR#At`fcaw>>jAqVj*>~!bCv-@|6f~^_pBh#9&Fv)d1 zjrD;zD9z*8UeVdOhDSe40;Ar||k@qt{x!nV4~B zGfHh~f?#-Q-{S&M> zg9ZC4{MHngG+rjWx<=nbhFS17|6Z{w>ta8%H-^%g(-9X4eu4b)x4dHr&*JuJ&wUK) zOQhA+r-KU(J-`LsbiCMXVP;nj0aW;as15 z$B*fW5&qZHPj4yj{*Yiw`;=Qsg=ys(figcH<|171HUiZ=N|vLud|dWy_0MGw(9I(x zus(Zg=2Km=<a*3$bsuMFEwMWcV+wA}1x(NhITK@`pMW<-Oh{P{cUvAtlzfml z9f4FOCph3QiO01m#(90^i}Q|-g1`+8qP#a&`hkJ{Z$H}`Q2pIIcr&klOSDPgXm6ry z&hrpPFU%Wpmz8A39)0?|jCqzELQETjy~TzY1P{Qc3t*Tk<>bI=gmSp$bsUB>U_`{P zgNBdRbKE1l<;pN#YzwPaNH=~RpW`A81{Pv4Bn`ADSQ>bm;Qy#$;@KJ!oG7!F>k}aA4kqdcPQtT|8#A9 z4RL6So?@Cv3taR4p8EX@_1pwpmJ2*jH|`c2yB>Xw$fUk>9RCF@?=z`h_3KU1b;(vk zGo2`&^nW>oqA1BSA*aF9sbD%f9BDtSvp1?J=Ut-Xt=EuyhyS%s_?7gI&_a)u4OhI; zhPAuK7JWOZm5-jD!WI`tTm`0J!1Wu*>0)hAQh9 zQ1Q84(fCPZ!jJihq`&dJr-bo*!2o3)v2F1JpWO2~7K8GCUcb?QYYie6wqEwSn|4xw z1#ZW{1*s76L#Nav%o1*M6JX!JkzTG{@9xJ}c%V$t=QSInks%Y#2(uL^MtlzUXPfD5 zc)xO!LIiYa4RVbR2p~BCud5lz*HnR)S!(=GgpT^)OSAvRm$p2`WJXTFI7X7h%QWO@ zj#G@cs;<;+zesZEzPbjv3tPU1W7KreG9)T6_6AhizJ^}uj@VhBBjOnZAnvkOvKQpB zb`Nhq=Way(gdnZ;Qg+g5FyEIe=I7daT%Bwbj_!1rQBbT^w|+BACHc$Ny8>>= z{sJw5V4mvMDx^o#dCX2m;v4yh(n(7TfI31DE`Ui5_h*g#yUKEOT%W6J-8aq6AZ=|M ze&IBzX;S-6$_2VO&kOHB8(#-t9_-mE-qkFx1bu4s8?oM?(n4;Zr}?@J5Mwkpsh~JT z@G|^=)(gpw&uTXZwbo|B#pFPDocP$o&_JRMT^J4x>;lGb8UVcUjVuO`3bls1O$T2{ z=-jGVsb>T1t`Ir^Rgg#^9%4Ri+eTb_*wT3K27Q2nOCYx^_4*0wThWjuXuEGOTOBmH z(wKq_Y8-;bK-hB*&e~JNy*K0a#aeU*TdqI9Z1@#A`{Dp#YX>q-*WlM27&|}S8stMJ zyvQ97(RJg>>N*iuEi*!ml=5ei{~s7`T-Ay3g~FQdh_gw_H=Iw5bO%-Wulj3OJm`Bz zt{-tbV#20=N19ahr+)lZhb#cJ^{lJD;H^VExO?;F%nd2(ueL~t3O(6WcVBV$?L*75 z(Lj!JKXe^`%mRhktZM|!B_+%b!`{DOa!4B_9acfEQjWroC}!k>S@UH!yv6H1VH~HE z0njw4sz#k9yA+1H{}gz&@eV}*tCcOnNtWg(SJmf(YUw%_h7|SPDVH3ZPp@Lyl%N7U z(CP!RJe|KM7zJHt9H$N|AY#0uxj#J0AW+o_V}$NMzfgv&{jE>j%m;EMPZo z;?tM;W%-&hZz`N^MEO99Ll-)I2NsUQ?C7TZcOEZJ@Pv-`{fERCc%oYQ&r?NIfPZL% zE^fnDNE}Sd`yj%M2rD>$9_lRS-rEqR%0l~n=hePv&DedoX3fJkZ}*-118+82=`@dw zgWzr_`I2GyHT8qN$-{PlzpZ&*LyFGX`tCX@dF`2Sk^WZ9J49~jSkuJM_Tc!mita5M z8U;CWhN1i|PkV&@UmpHJK(fDAb|Uk>MYGJ@N@-la@J~N zd_j^Q;>bsg%qzjB(UCiN%JtAQO>)rcILd3YMNtJW4O=kCdzTM_KaC64b$UoJKuup%yWT6yU+$bxgjHcGQPh* zh?6J1H6ks^`Lo&iJkPdsanDo2h2}3x`orQb`Y%oN;p#GfMmlsGi7?5hCw&femfs$F z?|^-G25Je45!*lQyvkEGY)x{FV(xJTAM#1oq(!K`) z>_UXP7^zI%iZZyPb(aq=w=kp!;fN(5(Ma2WzTdvb;%{pAKfIE|9L?;?9DeS&P7=p8 z(0J&oFfpR`0j{}bxp~ZD`H=3pr`zDC6ALPylf}t=vCoFIk=BCpd^HqsF3;Iq#{U*@ zd$^kDI+6c)g_TxR6Rz8%F_>Fb#8S;%mm}FsYZ_|zh%!#dV3e1qzjexAB!Jj|Y}(Xv zy=hjxikNWb%xK6`4`=YQUCSxc4ZqL`l7}8Z@@S&a(SMk~c6hKYmJ1B~#x2tbFYPki zcl4Cx+O=oJov(2Q!fpNRKfJAjh5MS+r{QW!7!8XY!NL46IP@%tbE@f0FF3u4u^_mg zg*$Xy#*Jm~foF_UekoQGA(*`fE%}r;9V0I{Q<+8dNs?ZbG9N1B(6THJd=pHo6>gVz zxq?Ne^7 z4_1sD#~Ygx^~ctN?f~Cvy+DdW$3o?`AtO4T9T(x%C6z*_f~2AEFGWE=LRXb4(OIe# zR#vTwMH2!8`fcY?E7J;xnaL_7MF{!)-(&q3?Ewex^%SoN$epJcdvJeDJGet+)xbTr z^R#b|$kYj%%$VDiY*zK;-iMn>-ggQnuCl6W>~96;YrVb6swSrS=|$M|W8Xo&dR^`t zulVL^#V~S?A73T#OVA39sg|#aW4)|*JBCoXnB;eIw53Zet_TS=MnaeB?Ld@sjZfxO z36Z4>t2R&>OzSTPg~;6H32A`tlb8*w)@kV;$C^&_FLMv_ykD?UvMv=+c#nS;GoCpg zX;1ko_j9T8FY?~qj#reoGT(8MOygtloyK~>>`Py-#Z(<3HB?;p`>#IL`MC1M3cJIm zU@1c}5H)CZ`R0V@y1awOc~N2C5Z1JJ1s%>mOEn;s2qSw?JiYg(#CiOD?wuk-Z?+rX zlUPzWsZD~C;(f7CVDdre&8Ip@^7}vxDo|gSfzQEAd?)l-6h(AGmtvf}?!tkP1(I+b z)Tj0-A!Q3X-jPQHRX2Qp%v0%wTL1U^*S(r-H)ypU46N2^ktM=MB0V zs#9aje_H7zx`<`)7Z1o{++ePiIpq{x&afzpvvwSviF`}nEa8em!rf9E`fgbqLL}u| zIq@I*1C~BD-?sBo4FG3pv|up9Smbas65$yyvvz8yHyuS&#LSJfcwZ1s#I@ zhE1_wSkS@ys%HSL&gUe8pJBdRJKfYOTh0}~)2g~5+}@A;ud#ehu2AlzlJ(6GXojE@ zk@BGCn&d&fD%+=(OiIFH&5QP(pMZcwL!hMsQ@B`rEnq%Q$tQKKt0_aD zaFBf5$r$r(^CzhP6zVx=mi>@|Lp4$O7hAfwk(zSZ@X^#;;pM9Ls67bBTb~LqUld*{ zivm?4>G^@&Gr;7m`!y$ac&T9~_`-__m|D|8D!iy4rko}G0@5NRu5W`ueAbV=XTk)a z?~SztqJ|8SPhg$rhICw#kpX{qfcR+!Oe|ndPU=H^`3z4c1#0|?-B8$!HkMuFHf}$O z)Iw+BL9wGYZ*@SO;u7??l`>vYu^%BsHdaUL;mjvR#7=&c2$%mj0kvk2n%`xfKbIwz zKL&V1_wgDOJ=!5>cowt_!WNvP)-?s434FIWt5K)l%*JYcg=@I7`GZqS-PY$0lrl^f zEX&3!KAZ|5`wG(_kP5njZy$8*vBHYf?i@wfj zH1_}sl7CbRLQHG@x47CQ@K2pBs@qCvbM8(Q=qbZLF0$5ohQt}UFSQ-I_>gR_9Z3N} z&M6|%y87l*(cK4_Bh~Y-@-kos-5T8F?ZB?=s?d%GO7AFYbwEY24MJJNk~~C9_pKJx z)mbKB-;-IqVN61*BMi6`-9?>=Y8-dyxkhsH8YFLDU%w}f0!(jk$Re@y4=%ul$6T^Y z29)d80E+0q#And|I_5T)JnK)y83A!l4{EZ;#YV#9XGW9)&oGNe!d)QfR?_N1juZ>j zy!an1fII>y*!Ju3RS@>FY2|6X+&T{fDUH6iMw;9m#t?i*nx|gCdWXs=?j`!_epnBWugH*sqSTR59l-?;;&#jb8EL(lB^9R%2<&o z-wksW?5+*!CR|7ZY2=qdEt{AQ&YI5Ji$QV*wZ3h@p6nv>2S$x7z_wwFHOtj`BWs?^ zZ|10s9AUq^?*}hOut+|M#+?Zenent%O{FIgvAtO6D{{E~_K=TDaJ2;EE9Ed`g>8v# zxcd^m64k|@=$@x0=OH+ljt14Lg*H;z+BMdYqgO;1-OT^u2IFMfU{0&5A{Y_2ye5tL z^2Yg-IHa>7T=fx9Z*PT;5mhN_FL4tI*5@7f~ULth-;HWx@c1=LK&7i{^VPqi6IAa4^bJFFH--(9#x0 zkCVeWXVZx6cfmm=bei4Aj9eZm&CbP_kY@)4D^BK*09Fk4rgQg&?J}| z4+>GHX(h4K5OH0!JrHD#z} z;l-b5&(_0y({m<{FU5GqA81v(-kjt{?;CpsT zXY3LPi#^Zh=gG+>*J)LYW)BxTs2X_^7V4t9N|6qUk^T3~II4wo*Drqg*DB;?W}!ML zP_KNK6aJ)WoaUI61Onh$>=QgulR+2U+ZR=vRgi;2V)_>cM^pq=97Z+j@Pn4w$hz3e zW%#v0;&+_>AWJS;Dmljm`)S&7s9JR!;n_)3Yj#Pcg%rFO^mtOxuRIx);g2!Rz9e?| z>rD0w_g5o$p?4_y!n(`u?_D9FAq+Z0z|@T`gS*D!5atG`szu3AFZP_XG6kTG(q@*J z&`Dq)$=}3pVdOmNy=UbxSYa!1-UIaP)?g9no+SqjA<&(5mUJv7?r5n*j)Y_6_ziVR zDO%jKZeQL7;@*AF*y?}5B!Q>{Yt%qwtd@Z?DXzJ;g~8!=v8X##+~`h+c6xoebC=VS zq@{x(DZX2}uNmLSKw5yFs%_;eIx3uW&TuqfM#3%AzsMdOHdAFDoz(J_$hW1Xlx610 zui_<)V`B*j3CXdgq8w2fQw?>97pw^`s2k?51y}0dkrP4kp`fFx^`cM_q0;HJ5Qhrp zEU=-aYujUnqBl-L@|)bWqo%zPeOK;u_45-WT1oM^e$8+K;+ox5i~=P{BPpe+sHNOH zI4XHZWQ~GqoEFZ5Vq!(^t+UmwI03#`^qy45jHrZsrPAu5&hSWfdhL>ttpsy%7Vi20z5s>nI6(X36559CXFL0rP(xIpDgKk^DWGXTb2@deNDdt zjd$RF?cA~^S8k=FY<*nN-Rfy5%%e*vKKa3)8oPH63Qhc@-FDuzT5XZ>TR|MqSes(!wS8AROc~LJM(b~A2>K9T$Gd}X|7blg7~t1cgAhK^9_*{OXD-X0ZpQx6QX4^{X}j^5@hA1D zkHoHR1?6ZS(F`svH>WN+hE2pzxD-C?hp_W-zV#nt4tKqbaohHQnu{UA3b(OoMf_dJ zGu-D)AS?Zd;l1^9{JF$PTIt3PTz%YAgg!$w6^$dhwHp|1O(bK?C4sY8jgPz=a0GZ~ zny_}K8F+P{P8rLb4?!;5E5X%o4b1>D8q%XzS^J4Tptt_wfbOJHN3}IMo08v-&^9`6 zr%QddG^ey=P#?ed_*|rfElmA2XuYU=e@f-1a%0!$;lVI!x*a9kAC%pSXBKo-!5V_C zMeknu|62R*c&z(2Yl{@cPUWDuLkVK{sA)5X@f6K5%Ync6ODVlUO&mG>v*{=VRw}8}oFs=mD zVGem3mzsWd87FCs7L1-r{W@TIK&#ZDdB&!=OY`I9n~=ZMDeZw^49d^STo^VxnEbfW z`=AFm-g+pGAnJwmL=)i?Z|JLTs5*K+5?-4;>7J-f*1gWz=|bGYXLXUKkv8(z&}j!T zJ=sHbQFYK2fBNnZpUmmIdVJJWd_+httr={j8@uVu$< zC_kHM!zflQ{KEbvqQ((&Zm)=y%A_I4F;4oj`JpLESB2*4B>tk8>R?z(EtA2#(7T$2 zJ4T1?w2&iJvUrapHN~?xcpSt>hD78{+(1N+jpaIdzT-s{nmvu=vrNq}T4u}Da>9$r zKjA(HRqIZ<5KAE8!TcUP_dX8E`*_e)(D($69K;xvi6N|EiuFj&YUQ@l^1% zen$wVOX6{pBCk=0!NJw*623!rdM*AS#Y+STPc)c0=QTlIIkp(*a+}%!Nf-q;LrA6$ zA|Hc!kD@OCLG|w^M_M7O`Uuvc*lZB6XuIh};H|7KjgI_M*jj{!ar0ry{J-w%k9do^ z4H=&C`67A*nQRH|D-{mm>ZL6~?Not2Cy}J|#2zns?`yWT>L8Pq$0{u#6vDalg@I!H zRRb52F`{^mizf@4P9RS_w#O4&Pbl>)&z^tL6Xg|!g%noa#TZdzvsEKel6xF@JjnL8 zd~mOyepRAu`U$M3RwNJ*pp>Bw^f`fr2iGks-?il+@Zh`QP%)Z766B*?_}dlo$Aa!3 z5fel7p4;8u(hhb@>xVGfloyX*@&56$S~9F;tR{j>?yMc-!JUeKkL2w>LnI$xrRR*f zjs#xzFz>BZlNkR(w)u0(_m7~FSnfa41cY-n(`axTsCwn!uU~E->xMD3a!bKfey_pt zeoJ%~r`N84lWmpbe8zEG>_;o1!+1V{yqmuJ%QyV1GsFlQ=27-{`^rC!TC#D{Yy4!2 z)PsJ`OWHXPAfi)?K45(F7WNCjSc%LLANb3HL5OdE;2%2sfz4in8G?6%6YlHgIZ2prikuK9I*6nW!^$ES9CyHLx+p9-sR%%kQQ=x=^eDEnY z@aQN>kjTUa9{qdlu2~0H0r5utx(0kY2H));la#}dmRjD+@Q4$&Y*zz~-W0eOC2a$q zL+B~{rJ1I$*2{JH(k<3vk#@INfaaWp{6>D*_xos9FQQ3=I+e<|Ve71fd+@V{shatc zcqj{>2h-=H0_Q7YpkExb*1pLzedDv`5Z$&hTBpaB?GIxG?@>-bUFzS#gdQG!r`uw5{psuw2)=-t50)noHanvnJ zHV4tf`^L{a9=4t3G#@In)QravVj@MWpp#(^hb@fd!!{>~eb1PAf8vpz%?_S|;*r>J zHxx!vzOe_LJm{78dyWnP12Nj=wYFp%)R+a>jnA37-&vg>JOv8E zbBxE`?hhx1e}$%_%&eK-bBBkm((JW7DiPk@HSlu~ZvF{%d$Hzar2bFAdb|}%&K9Ci zuP;^K<0u5oCX?ki2CN@amvW@MAhuRmDh$kkW1{c8=O4NZTPCH@6Y3p~pcgi(aVzvvdJJ?K8*oI6 z^#ySDm~kewgnbtjv6OLb%!nTYZtQBYWfy&7tkZiU_qpK*5>vc95Hka{!-i=>Vl%pc zTD+gYruP!7&Q>51R+Fqck55zKdInk0^X+(kkq;0;Q^SIW&14u7Pnzx#PxgEaK8U8J zr{}nS>)|Ut_KMaUL5+7o@l4-Wpv??Ta-(j~=1{islN_#EK4j&_6%%tOL*BQh?G2}L z1izqYNUMQE-P*uSgNgLRt%pJ#Kx(Qrz(D95YpSAPQij+KlplKn#MtTYv*B86M<3N* zt~$ka^tLk~WYKucchGK1I)Gc6#!GASv-g1kr}!HC{V+>V_7Yk!-C${E@}@mhqsL}p zHq(>kNFpSPX+3}Mgj;w#q4@_w!fv*cgk=FST+F5>xOy+c12qM!o5jHrKY{;zg&GkB z%hME-7@Ec0g(sDhM`a+&eDUyyUrDj)6ZN7u^Y>XYx+ZQy2~5px(#mUYk_$PN&X)i6 zRFX@g+&~KZTHI%8oC_0AX0TaxEZ)ZrOgq7t0xPX?a7i#&0lF`$@}gvR6Sey`Qw?Pfry8F z>?Q2)R6c|(4l8V~#t)atf&W2#zbetO136^Xx8ptneko~O8v7+`pV?)D2WPbffsAq4 zmsUtNrt($Qr~B!C8=qPv_jQC+4NWYFhNtn}M$ z^xPtrtHNBqE+~(Gqf?-2nF8Q)u?$6~*hRv&6JZXfISjKn+W|KpzLEK0eXN;U{cQ7`4izP<2n<3c;PjEUs2woLOmWEI)D1Q4lx_ggx_Rtri7VMWBfLb;6QOAQc5y1L%9 zmgQW$EYf%tiZUDEC$r9)9p-3>14k%=h+30DtGK)eFvbxm(DTSs95+5ZsRiMeX*$wn`4J zw#Hlz7YaQfn2Se>28w{{2Nxa-Cugby-8r1sZ>QaM7NoJ3EUly;xrwy=1)!%a5GdXB zj4Cr{a5d0w&fRp)w7#)*bpU~N-U|gxr@UOM;dXc?wWd0n-j(xuxL7%RFU)|&J}JlB z#lo!|WlgOUL28arN;$+Fw%-|++!WaKNw~xQlyVWJdoj3&GqCdnag5rV!J;!AD0LJ0 zko|%r+*MyDJj`2h@ksC@BOET(Iz13olbu$bW?Tu@4W12>#kV%82w8dkgP&$0P^`)G zFpf)@Kr4Gqa>HYOI8(!h$H+PN8Rg=wKkjEtakM)L7|(2);pfXZ8%P%hs}bpLA@ifs zqAMXEn>tVyVWng^-X{*GhY;x`(?7!#H9~f&H1#)|teV*K;car-6CiXyvlyi6nJW}=l^73UPYo&1h{8L&jj+m*J=c(D^Za1*IFd$MmO z)0c6OMQ!!sZ(sf?q{h}=b@{scrCN6UmX~CBAzFlm4*+UAwt#-!RCyU;K&T!&_MH|;?99d^lhVF%p)7Zl+TxIcN^G7eK$tY_A zkKA!Wol8yFv+TOeV_vFOsHhKWaTxuQ+9QAaE0Uw}h$N*FUurf~;5DXdsW~mdS&(_8 z#rFtOmtAWs@+b=e0@9#V2Sr1R#PxKJQ{1&kSXo()dz~s!3j*OT?o^d%%fGJkKk~G< zx?|Mbxa`Sj#vI3L4CW*j&5kf|*W{mQCPFt#9RUf z@HIQ@*Va}aG%rD2%IQW2kf3l~Kd^LX&Buj_gLx>2Brl-i$gN8b13vlStsBtM#kg!3T zCb|2=!LfO~SsP|UT*dgas^?ZzY3QXtFc-_4O3~(w7M4@sE}jTQpSyLh=OMs6*7JHE zoR6_@5mr+7eHVvVtP>2#gl~)^-W@7PvIH$^EI~>+o%R44yzi&dnPU+nz^cQN8S6>h z5x}Qz4gq|+Dz}?{vxuD!Au`k+5$wkS@`MUFHjr+roAbyBBwZpH- zDxTJ%^E)}nTE&t=V!@2NxRN1MupnT*^M(GMhg$IGY6daqJh^eN+=B!CFNXV5r-DE5 z9Y8Vi2llVNZ!a(PJCKT`IjV^U+mb8DOv9VQTmd&P3+qwNpdY`~!5i~TP2N#1H^d9I1AUd`uw9d_$P_!W}(_kh}} zD7~r8Y+HvhTv%%Qe5@Yp?II+iyrnwci&lh?@(if~Q`heOZJwI`dIkW%uh?Oe7jA5; z+_nE1^7)fCFvYufMW$xp5HPY-cNkfA&HT3ukXVGDDMX(t@G|nO*U0zCOT{*`i9h&4 z0cL6h7KP=OA_Ybu-H5thJ#$$GjKx0hEKyfVUqh0uiz_ zu!-}4Jkkd;TxwDwm_h%e1SNn6i~$7VK)Tfd3Tg6TfvC@-W&*f6chh!v1VTx&M};6n zxkcM^|Hc*9x#E+G&rqD0esiXoL~O!bPOtmKM=4vpY02Z*jo-Kc9gy%J-eX|@PVits z!x_UtaGR?(VsJmMNt5s%Td^(MYQ`fwAxbU7i_@P*pFLTf>+ksG4>4?KPcbir^XjdE zTY?F|H`C0j=gPbGo@#qzJu*rC5wpn6T6Zq>g4@_58G$=N%jJmaypz3p1Y zpb)rSAwPGmaO5)eCbzD_hxc9YirK*2+M;_&0{jxdtg6E}>EXGkji}vcs!Jjq>I0(D zjoXwPs7RfRev&H}2t;xp+!P-mhs`L$p?EZ){UakDz`fnQu2Cn1<2Nd$m6P}Jptf-=85 zUW;uZDt~lW50+N7^3n?jbfRL1UVdsJ_6Cb^zjRmubU^EeI z^7p|1A5ZPQ)K$V_HJ@;`h_xvjq`n`*^cyER=e@cu@Io28BYjvW6050@ruzKbxw8lv z02XBZ{h|JK4-J~r2Np*KzGCR3H;EMZ5v;3KTXK|}OErRoEI_tD5kCK3tLX1OKV$Bp zTL-=GYo$qOA30aT4^0;&(N6$!66xzbbq3JiMXUc5vi$DlMQpG{CD>3bVWU&c<<0Ur z4d@5Y_t9$?w8U4>kwaWQvIo2C??h)-QK>!vRQBCfCay+kOn^d(y3OhWWK+s-Tm>yC zS#0u{E8+W#7=4}nkb=_3;-Fo~5_r0Wy1C-w>d`X9rWn z0bRrB$l2m6c{m>g4(E^($mO}QkBBE+psCcbI$ixat zLn|3qa2;^T5BTT!d5k5Z>gexCzHfbP z9@=7M>jA9RIXng$wIe6byPU^XWQei*-|_qZjpVLVFFq$!u!?aqeGxn>r+}{_JmUa} zs{aAZA}FxLfq$jwsWoP{DDL7WCJKo%o=K#t6b zSxobHg}pyTc|N_r#aYpzvs)WK--}*)>v$-bS>P&H^5-@xu#b_6!~%2wt=^N1v!=`V zdweuKzog^?Izf=t(O7sGhT>4MXgTae<^^*>}>iZ@#5N!{82N z4RX(S&Y?fZPZv*Q!eLz(4CP9=bm#2NMX~e#A6CTe6z+ao4@81~)_>l7(CBNsOtBA) zpkB-+*%|c$f8F_C*v)IN!sGAuc^GAq)X>k+viuyhcxW|FGGBrxfKo>_mu_7;hp_kR zl@-!^&_*Hg2>xWHL1>@D?mW{TS)Y&%u)p|{F@C~rGFTq{K;K#bq87fW*+bN3ekad` z*EC=c@cBoPhrRr`KxTY01zNPZ%@1hTcr2dhM1<&1^7qIEe)rM(LLG2)^;AkUXYtYO zLMZ6s5xeduZ6+ABKzGu!vgcZTa+&0gDB53l;a@poS|M0Y{3VotOb{Cy6XWGmnZX&e zqlZ>^`#ppB@6H$yHV5wK&}D&Vwjvp)zWLA6T0Pj7c5C9jH&vPYSrxLj8lR4@aD?}?RoRb#UAHTQ?uSG@77Q`i(&tum z-R?mBE0r!!x$Vx%nau?j>BDpaP6EOzv4kZZwv`q=4ce`Uk9a&xuj+KmsFY6pT- zAX>xk7Zv2Bw_?1NfZsy0vxm3N+U(#f;)+)1IJ40>1lPbAWSVX|M=<|#?U6vO+?3sL z|4*(Se;HyRDI(EYwMw>l5VQI#2=o8PknLh1PD8FOZt9EO`o8HchfmwR;N8$LU1-}F zVlE~ox_Q1~e|2y`7OJ3VwL#$sv zKOIi|x5nYmIse}!IT7md%9L^jP?om6<0@a5R3~qhgRj`BynN zQvL5_5cdKKr3Fa9f?RX?PRXz5Aq;pZ@YXY2nQ7REKp_=>EkOM3D->HcMO&vGT7rOQmE<)Yz#OwN9I(e!*P);Q5fvd&QI-3c$ z9n&+=-6uH$ams@KH>f# zzVB3`L5+gwSq)6IW`cTN2YgOUz}WZYg&`hSs^|Y9zC;~qDrtK?q+)_h@R zmlXt9g(+0d)xsSl5iHyVJJY;?A|~fNGDWqihWL*WW8@YdzpwxcGeWUMRX3WEM`m^B zp|vDCaNpw)K2=s!3s;97O8NkOHjwSG~yDs z=BR|bWV7DmN3=I}r~c=6avr05atPYr7^h0uA3>O1;L?0QbP0HrA3?4h2WoC6dndE+ zh#mu)E6pg%=&0wU`LgZ4kJWo)xl|13fKQ8<=eS%-6ycNB-M_;c+8^n7H*Vkp)R>N* zD-lmRU@zu8&mwG=GcX z9DBM;-Kqlbn3uYW%CW6V2WG^32VuDBql8kjCAx%H_7@gYbTSV(ZA-h}ocAd;EYJkuvRJw=X`1H=~ z_tsg!#exoNjmbtR5Hp9NC1b}EK?#(Tb{%S>r*hH=)2cJ^jI*4-7+4s;Yw3(*BN=M8 z^;27l{tayQuazZ^LoSN$T2FwBz9XPzkKP%WgUlk~IX0Vw=xaR%l=K!(T-3B-w@?9TDQ|wK~J^Psoc6gHK1e{O+jZt~rmM9Mzc@Vy{Vh zw^g~`a>QXm08t0>wi1+~a5={*0(I=?+j=i;`$-h#HFZpCDBu6_e)ppP29nbXliQmj z9L1GaV;;K?AXL#IKWdvtpyb=NCCQ_HWU@Up+_4+A%{T|HmXQ}Lj;o)J-wR){cH1=# zv76|p?D~3AWB1_Q@^n6^0m+ls{oAgwKeDe;i12=9z#hEbc2oOrm#ihlIhZbuJb46$ z9u{`Vdw91vzrH*wozN@s*oDufyI?w4-n!TIGJy98nS!{bGbj{7 z(T@^F!bJB-m;%ARFvYkFT&3+=9rSJ_0fM0N&yi`&?4SH>h){fCfFFwCI2~60A66_j z_5x|+ht27Sn)wc|m-4%tJOvKqT>g!u`1^0#8e;U9s3a(4WlMmUSs2VF1VHU2y8Zs% zDYg}{`7r!VjumI;K6TzU;50&0)FTKb>XX+J6Se89Xp7z9HXmHQ?g@@8#JVlK^Bttw=@KPK~!=t>4ujv42)?hUeX z+Q!ST$9FI?rxLxqrd^CIaDg2sNXDWSbJLk)+QY@z(tgAh$vCqaZHvMwY#=l zCmz>pU1c_`pG{JihMMV|rlhk8gb?d8s7OVd_Za}b0Ts)N~2(ivhzq&S5t zMRFqUno{?`1X`>PQ{!=&b0&uq`1*GMfc{nM$ZdTlJVc_ppH05D!isToH@}k1jbeE6 z9G=HP>dNYeCaqxVksG(M2e0y4j78lJ=KF;am)ca};mMr&l+ho=FU5i_^-QQu<%a%_ zBb!A9)!*0N+%=iQk^Z`}Vuo}tc`*IKU4POpqmv{k404O?0yVeI3fZs{Yme80ifV3hVs=E$$dz0FI{<%98&I46Oq)1Nx`r zcz}=?1J0F|&Fk#*2+{`R=n9X(c%9?wEzxX3&lbwU*BA;txG~xXN?D!^A}{S~cb`S; zRL%q9j6Y%LVS@GtkKlnP2C&v_TG?8sm>p|5AbyNTjEA5Xt^xl$rkrQ5b!6J0qqfB@ zRu8qbSwW++W}j$}@y5Ub!N&-Dsw2_Z!A4HCh*jN9UxokGVkH?0EE|}Q5WfcXxsvrC zHSS6|nrXLgD@ueq+*kxgH-D0eOW4BG$tV|?Xl>B1xbsnrSEL^i#uQ)-jxxY#s~3Ps z2<3Q3<>c`8SwDz&3xvvQ+1~(ZH?_icP$vchi1jH;AP9@X%EpyO3;>XGim(8ZjRr(J zE9~0;(D>ZV{fwN5!WTxYCE^V9C8-9FSWA!r$HDR61_G-?zzd811=l)VVj{i1?7wY0 zrO`Rt4LPA|1OtcdKyfTc9MmAMBNH7-Srwrk)yhc;DTNsb)ldemo&rdfnQ!blzQf!# z(5EEnK}n4UzmvbGsh78o#L6h4K8;thAQ;2-O zf)Kj{5|k-mo{CSt1AzE+<<&Evz>YVr5PGZ}2AOhg+bm=P(JmMjdd8d@peP|E>5n1w zX2N9w0nw~712L|sHE0IY4q8~tsoMb2UJ35Z-E?@ict~>8EuO`x5w{Njm568bVGb=E z?lRdPxF>Sv2PoF1jsvOv$ey#g6+TddUtNGMr}^!N9l+E)6Ndf{w9puEJ!gm?-v)NG zpR2?ZzMP-4xzVW-QrnPK|D>~HQ&pv3V{hj}jA0pvfl69!m_v3tTwq}H=XXi_m^%A` z;uI*LbfLz;b(k&!$t~I;6|hB~dM*YNIgLI`Ka!GL-u}OhKX_20KP!GijGchu9S4~y zpUneNC!tz*#u+QF6E%>d$1@T-3qWoaF4DRJv`9{=qu~oSKtk94+1zpe_OtXOBDvvY z`H4aoGSN5FBpn4?g&{KxL~5$3`a=5J%WqaDYJ}CCIb>`nw!sK2g{;^q zjIK(5C1MFMo)hGc)f|znRZ{j82c~}{{qG*Kk!e`hj+iI~A(MBVorEF)xbKv@GY__g>e#MKZHy4G((!RihX#9I#O!^sX#fv z4n*jsdK2hfAP}5Pt7U)jl;Hsg5@5=_*Be9U9DPej66W9;eHn}!yZ&U{2uhmiyPV@e zvn^DbC{vWlyRvl35aXnk=lc$~W+RiL0OzV!YTWD`dE4KdK^Y&FF3h{C|HcJygRh|Z z36p!PBzW>HcTE&-_v&Zt{R?7yw!f&ktw~(oYm>zZE9w5qUBd}A90yan4+EB_>4d}W z5|2+1Xg-UXA_#*I&*mQr8V}nJSg@bPGN8m`P0GrWBScMpMS{d4iA$# zto;lJ3PtcRTMWCVu@)jnY-XyZ}y~zZqAP-8p)flK;Dn%)5d0Kg_42`!=A>a+T zFmeIISY?2x5&;=q0yEvM*KAHeh^GEZtF1l6s32xa%6Z2K$+^OB?l_j7;BGg}wT)7= zx(1Z&uTZU=$#P0)W!HrxL3$#Tt1PoEa{S2-W+{3@Q?U{G)_4By*%TLlDI$Wc|CQsg zV`UQ_`j1tK-`hm~-T{XDA8YxldQ7%ZC{5ZrLEsXNpjL?E5n@OBdsn$tErnU6B`D&d z{3jw>qKpw%TPnlsY{iMf8XS{hE0}*YIJTZsQh->25ul;!2kbF!Rg@cGlGy=(tOZ!g5E4A`S^qlV@|cUN^(1zZrbQ2Q)N3J`a96#( z6c-iW-$HtsbHRSkg9zcFRyxHHM@(fGL=b8HO7`RqgUg|nKMd?!A!cE`@fsCKjb(6A z?qOHfI$cwL}f1`#4p zKhpWVKpV<^@pI4|j9$M1A~D{6_*6Xweo3Yt>P6e2>DSssjv<3>@K{OpdSFl(X8;l1 z`?POR{?;zq2J~HP6aL9G*anZ6)D5|BLtKShh-3a5h;6J-Z-U#7{q!gpr^L-A30-h_ zJNeFqQy!|OVryX5qE@sG;gYs5$f@GzKu&aZ4zwZ5c^jY_YC?$CM+^O6Wf#c78wcL^ z+R}Xk30fze^2VMjyG&TCs1D#v+fpO13``5X~c-rVJ;fHjq)}?8P@eC%c+S} zeeF^GMp2<7I1QfOL=+-(K*Dd%+W_bFv<;}Z@b<%L)KRbnCNvsFSrYcCg^pm+ae5P6 zMy|{mL#e}H8=QcWH}rL+c?tpl&yrjNUx=%x<)Tcp5!*%eHN;P)P+>AcEN<>g9OXyw zc+o2Ihm~a6)&9}NENwvD@9P`a?Fp{|n^yIn=KJs+NK+@Ltg@$^z;*V*^M&)YoVZ zX$h}^camliGBRCK^d?S9r#GQQrL_q$bFzT~6cqJA=I}Fb19W7~5&m!x@bpJR*6;@D zJgB|~^(N6t#GgccjZ)#) zxCIth!fQae(LB8gtI%Q25hO)<8{iSu6+t;n^YIlE;ac7G?}@u~!L%)&1NF&A$nQ@0 zJN}vTYgcgj2>N?Tm?dGjH2)37vr6K*K?+rT7`BfBRYOg`A{5^80i`Jm?f!$&e@gH3 zE4k8x;dr$C)YO{LVWBe`lf${eN=MIUc!N7CSY=;36#o(oqE*QE(TRmELZ*8Gk4E5j z&X-cD6Jd0EdUAC7e1>j3@RyA3vzXlYxzbSO=Mw^@zR=M`%eR6gqUF_P6wi5a)ip!e z9CUc+6@LB`dXO?_iObuC1iidEQ40!~`od_sI?NBlU+@=G_Ya0!CS1{DjSNwdY=`tb zzU37sD`EIbvsaJw42wSEOQouu=3hE=(hJ;DD-Y)yrk4FXA4W6a z3P1Q+Zqd~T@NAj4AAAgk-kcN?$?^IkiqGTyiK;6+iIdM$ zJ?=ieSx)wNzQ*NENKftN;5p3ow?7(>=350*xb))wOy2NX+4lWJdk24hP-Oe(!jCk| z~_<+($+z z^ql(DD@{?_T5-+dN2brJ3Xwx4e(p;dIgj^YdUzUFc#m3mk16HnnhnigzMMu83X#&x zf1#%O2o+9^qDRnaq%hj-gzCzKCAY?EpC}WV&@sKwabnIswFD~9H8IWJwc;x4kZ;D# zT^q5N)Mu-6i=2+!IyAv!KOyBA79NyT6Snq4=5|n0W7wLfdc;?dI`Qs6py<~xNb$M*ktH}i1A&WYye1Q?wG+OZ{iUmm>B?Mkomjz;x!17Cxzp|7O z_;lS-Q-i@Dt9{u^oK-^!ez~_rYlp_bxuwFl`#c|*Xn5_^@m88IO4DI4A}v9Cj~8!> z%IFI&HdJ91KT0t-&kdx92lby?GYUf(NrVKSH!`xBcsxHrFtKBxK6!C*)g8+;-!OC~ z;EWLjnTi_~e_g{)1op&jdEe6zAZC*o6|k*7UEug~Iua$4-~B}i8!3G$^*Wx4HAP`f z7)~Ow00RzND<^&%+C5^WzvC+aDSMY-+cmS{H19jN5(8%Q1xv?p*T7RDfc=Q>oxRFr zXi0>I{QnZ2|IRaD*^YV?v8kW#&NvEyh8SD5b(;_YXut)3%=&=iZyrQ;>pU#^ZPy7Z z{H;MuH@2ExPsJ$1LRNETey5RZL?fCtv!;|9;leG^eX0Ezkt zheje;?Z-);uqIu3s+DU>5SX1}8AA#)B1N%uO5~3PvZDv?yELtrmji|+~SG+OY zYmh4nv5j=Sa;~wVlt7Tv-1ITSzi}vD(FK!8W z&4Mz4XgD;HD))reOAM!uU%81JiE%n-cDV0uuv+|~r36ll`>lr^vFdK7Im`{EmB>7r zw7$+9iDYB8!Gb?gft`qQi$9aQhOs4{BK4A@x%j)smpGXvZ$JI@l`^a(i$XbP{@$ny zPvy7e{b3Fz{0SFUknxmkSWvZT!den7fqUq`-adp(#rqp=%JKe;9B3Bu*j-vQtVGjo zQnCvB^Ivw3xv>am(Z1J`jWfmwnQJfO8Ata|suOn!XNxeG*q)=RRX@J%BYE30e759# zr3Pa2jmWEup{qdEd%x@JJ^ou<`T8on|JPaEQ~^KE`Vz#$r+;rH)kX$PrjRs(Z)AFeuZhAu-E<5=~yyB z)Tj3spkYMk(R6_v8Hm}C)wFK43`r!{1;6$Db$=hSD!`_VxN4x769)t(G~!ht4H*Eq zLoJ_X5uv2&MZQ#*^5jQFZfus>D3u;ZLW|`z@~FAJZUlD@BF{j#m%KNIz{>{_Br&9)f4>}Oo58;Z}LZSt!S3@gUTyOxFX{=KjF+eCh^B@t-5c(^iFGKPJ z|LrYNu>Ko<>YR)82=E5B6Ot@WObu7q#78h4(=Y=|LFI|q3{EWg8`>Kj?bB4Gr3qVt zgc-3LxC3-wG7|o2sg2oOOXyb2cQzAoSiB+%bC>6Y^sP{_F^a*wTz0xiXPlu2g%BZW zXg`OzXv70jKZ3G|F{HIPuOz+=ssSV{Ufy@3719l% zTP!Z2NJT4R1ttLfQA*LqR*I7;=B>9E#8;h7!8DYM<#J-eXfw#JU9>r&70|4?-f;s8Zj%FOQiWk`@PAk! zKtrt4JCNyLEDMz`F?0=p#5N-w{kYK0N`-&n+uH^)?wU(K)${6*Mf~sfI{|1(@`z8_ zHUY0nY`9{`bDmjsF?p?YNp`K9q(6*ohuRf^wG|Lq&nUV<2Y6esw!1c3nc~1+Gt_PJ zX4n`t3JAtY@HM^gdKq#*(HYBV>1l>z;5s@GLuyv7l~hkCRRHL*;yv*PpL<3N1&d&ef+Fb5_EaF)i2Hhrzi&WxsKG>K6%VF>Y8 zA_9-v>xieXmg@K7^6n$-HOBUpcPbp;kELTCA`SSU#h@KqJ*)^q<1By>sLE9st=-@R zzABi5*Y?uCwV0FaC%CbutdtE6u$W#x!*IWeaTK^!7M3|5m#NefRoYeXf=n@=7^V#nqew#*PIS!^R-#wJBd|}K% z#M!exxji9$9GR=SWlLh0r= zz$t{?5s^i;JL5=Ru5l7s2R`05coT0oeCwXBEP4?B;(VpFkx#|q2TqfbfT)M=bTJDDeFz%{DYB&)N zTto4u2FPs=8DD-BX1f-IS-YKa5%ri;vElqBvD6!wV@)9#_r{k7Jp?WyHJPPoHi}$k z->@7F-RoR8Fp))ekvzHmWU5a}sY`_kn5oo{3aJl<$tB!(MNBG#mechQac zdFDb6b{vMOuWOqi<8W>PEH4khIP6Qqa7UC-mAnk5x{ohgaGa)b_BfXvH;(EPs)aVe zqPp&jZt()8gUyxR&u6_~>Ijnh{ zq(7xGn3xiN#M}4&{W429&Kin=kuf$i^Wbo~^(i^BGL5eU703trn*Xf~_o10^jhPb- z0iF)Q>^WYaqBaK81BW6?@DCLbaSMx!bBl?I$qtjZ4xOBxQ(yY=<0)XY=b=&R2QF@r zeH__!R86yVoS_mUZ(wGGo3Z!G;%*%CAs4Qph`^4bHIC?aUtouaH7A(Ei7rGL1~#TyU$gKX#AQ&*_QXRz^b^m*3Y;r2 zpHzfUS2A%nnd*rcOo>}a-rye8=Xi`4c-C<(s)+>e<<8i?)P%PnV2^?R-bOJGO_| zkU{BsbL$Mp;~03$vy@_DoX*_eoVI{ zM1B><^vnkf6hRP7-QT^9K!70U3o&JN}p?ckHt!9oD8pD>5;Gd z_o%9y-OTTjn@Y8Mse5NDLyt$=T;B)Mri+R9c%uv*nPLb;*f_fy}m{um#df}rZTO_jR2$CHG(*cBImL%^;}6nM-QJ@Am` z(*o^qnTo}Chi3}1m9zp8f~rp<1TQB&C%qEsutsosD{Sf4$;1a!MZ7ghf?;+ebh2mY z0u&bsDmL|azV*D1|GKNz&mA5vkmPIzV%C&oHW`qa^!m{; z8MQ30pmPZ*jSt%(ZzvXXV ztR+RJVfTGf99(NS3dNc(;tJO!s?rBDYsC}jB;XMH=7ex9p2xnev8Hs+1vI>^!)iYF zb3BsXM_=d|b8WA_rK^S7ko-Q9Xb2ZWLj^H;Lw^B z;8h*$o%MjVQdA8_u0A)U%>v_%eBo8*&AT){?Yv6e+ncS}S0UMGz7fC(uM%-CBUc0l z?pnPX!`ShU?dL^k#38>?i(^Ie5rUT2o^|tAAMUm(bGKZEm}iHzC1LPyt=j) zQo{O$19bqGV&i_hl4$JCvz0X+ONc^V>E^!XGL)fWfM4V}3S>q~j-8HYBxs@@&!+51 znzf<9ew4-IKikca2`n_x92g)6Z<1*`o5Elk;cz9AssV+^vKm60YJVPk>A`)D9`VSA zV|C73B7q%whn!1pA~j!%;ydFw8KD;Hp31gCnE%V+(8^ zlV^BScvN5#7P`dRbz!If!)oDJ!F$NQ(}x##Ru48(&yGmUriEK2PwF7r+gQZ_Ai z1H+s=e>$QgBtYHY;QH3|Pr0&7E3qb3J@WfWlV?L#-k=0uaEzzmY|b&>f91q5YI(70 zEaMaFT4<^+iZ6Qi1P=Tv(H+H+&EDv)iW|m}MVd|D4CkC;V+0PeSr#y;D#M{35I~Q| zKrh4)P8wu(`|vU5t^gdz)mM7xh$T^X#cXGi1b*ajoYDxG*DAR~UM{pseeOq=Z+wKTPxJn$3q?Ly5{$SX#kejeG<1vg%X@tQPps>IV}L^tH?i>T71AKXSQv;2{sIif3YdxmcrC`fie^t+EyB zM;yG~%e$lz4lM5MWdGWVu`h;?CkrnX3U4>3NQb=@^1qRhgu9N1HTvIu8N)NDA;^OR O|Ea6!pi53%4EjIo6lkCT literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/msr_reader.md b/utilities/system_monitor/docs/msr_reader.md new file mode 100644 index 00000000000..fa9a9b31c3c --- /dev/null +++ b/utilities/system_monitor/docs/msr_reader.md @@ -0,0 +1,34 @@ +# msr_reader + +## Name +msr_reader - Read MSR register for monitoring thermal throttling event + +## Synopsis +msr_reader [OPTION] + +## Description +Read MSR register for monitoring thermal throttling event.
        +This runs as a daemon process and listens to a TCP/IP port (7634 by default). + +**Options:**
        +*-h, --help*
        +    Display help
        +*-p, --port #*
        +    Port number to listen to + +**Exit status:**
        +Returns 0 if OK; non-zero otherwise. + +## Notes +The 'msr_reader' accesses minimal data enough to get thermal throttling event.
        +This is an approach to limit its functionality, however, the functionality can be expanded for further improvements and considerations in the future. + +| Register Address | Name | Length | +| --- | --- | --- | +| 1B1H | IA32_PACKAGE_THERM_STATUS | 64bit | + +For details please see the documents below.
        +- [Intel® 64 and IA-32 ArchitecturesSoftware Developer’s Manual](https://software.intel.com/sites/default/files/managed/39/c5/325462-sdm-vol-1-2abcd-3abcd.pdf) + +## Operation confirmed platform +* PC system intel core i7 diff --git a/utilities/system_monitor/docs/ros_parameters.md b/utilities/system_monitor/docs/ros_parameters.md new file mode 100644 index 00000000000..0a33222598c --- /dev/null +++ b/utilities/system_monitor/docs/ros_parameters.md @@ -0,0 +1,84 @@ +# ROS parameters + +## CPU Monitor + +cpu_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| temp_warn | float | DegC | 90.0 | Generates warning when CPU temperature reaches a specified value or higher. | +| temp_error | float | DegC | 95.0 | Generates error when CPU temperature reaches a specified value or higher. | +| usage_warn | float | %(1e-2) | 0.90 | Generates warning when CPU usage reaches a specified value or higher. | +| usage_error | float | %(1e-2) | 1.00 | Generates error when CPU usage reaches a specified value or higher. | +| load1_warn | float | %(1e-2) | 0.90 | Generates warning when load average 1min reaches a specified value or higher. | +| load5_warn | float | %(1e-2) | 0.80 | Generates warning when load average 5min reaches a specified value or higher. | +| msr_reader_port | int | n/a | 7634 | Port number to connect to msr_reader. | + +## HDD Monitor + +hdd_monitor: + +  disks: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| name | string | n/a | none | The disk name to monitor temperature. (e.g. /dev/sda) | +| temp_error | float | DegC | 55.0 | Generates warning when HDD temperature reaches a specified value or higher. | +| temp_error | float | DegC | 70.0 | Generates error when HDD temperature reaches a specified value or higher. | + +hdd_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| hdd_reader_port | int | n/a | 7635 | Port number to connect to hdd_reader. | +| usage_warn | float | %(1e-2) | 0.95 | Generates warning when disk usage reaches a specified value or higher. | +| usage_error | float | %(1e-2) | 0.99 | Generates error when disk usage reaches a specified value or higher. | + +## Memory Monitor + +mem_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| usage_warn | float | %(1e-2) | 0.95 | Generates warning when physical memory usage reaches a specified value or higher. | +| usage_error | float | %(1e-2) | 0.99 | Generates error when physical memory usage reaches a specified value or higher. | + +## Net Monitor + +net_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| devices | list[string] | n/a | none | The name of network interface to monitor. (e.g. eth0, * for all network interfaces) | +| usage_warn | float | %(1e-2) | 0.95 | Generates warning when network usage reaches a specified value or higher. | + +## NTP Monitor + +ntp_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| server | string | n/a | ntp.ubuntu.com | The name of NTP server to synchronize date and time. (e.g. ntp.nict.jp for Japan) | +| offset_warn | float | sec | 0.1 | Generates warning when NTP offset reaches a specified value or higher. (default is 100ms) | +| offset_error | float | sec | 5.0 | Generates warning when NTP offset reaches a specified value or higher. (default is 5sec) | + +## Process Monitor + +process_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| num_of_procs | int | n/a | 5 | The number of processes to generate High-load Proc[0-9] and High-mem Proc[0-9]. | + +## GPU Monitor + +gpu_monitor: + +| Name | Type | Unit | Default | Notes | +| :---- | :---: | :---: | :---: | :--- | +| temp_warn | float | DegC | 90.0 | Generates warning when GPU temperature reaches a specified value or higher. | +| temp_error | float | DegC | 95.0 | Generates error when GPU temperature reaches a specified value or higher. | +| gpu_usage_warn | float | %(1e-2) | 0.90 | Generates warning when GPU usage reaches a specified value or higher. | +| gpu_usage_error | float | %(1e-2) | 1.00 | Generates error when GPU usage reaches a specified value or higher. | +| memory_usage_warn | float | %(1e-2) | 0.90 | Generates warning when GPU memory usage reaches a specified value or higher. | +| memory_usage_error | float | %(1e-2) | 1.00 | Generates error when GPU memory usage reaches a specified value or higher. | diff --git a/utilities/system_monitor/docs/seq_diagrams.md b/utilities/system_monitor/docs/seq_diagrams.md new file mode 100644 index 00000000000..8fadedb6416 --- /dev/null +++ b/utilities/system_monitor/docs/seq_diagrams.md @@ -0,0 +1,29 @@ +# Sequence diagrams + +## CPU Monitor + +![CPU Monitor](images/seq_cpu_monitor.png) + +## HDD Monitor + +![HDD Monitor](images/seq_hdd_monitor.png) + +## Memory Monitor + +![Memory Monitor](images/seq_mem_monitor.png) + +## Net Monitor + +![Net Monitor](images/seq_net_monitor.png) + +## NTP Monitor + +![NTP Monitor](images/seq_ntp_monitor.png) + +## Process Monitor + +![Process Monitor](images/seq_process_monitor.png) + +## GPU Monitor + +![GPU Monitor](images/seq_gpu_monitor.png) diff --git a/utilities/system_monitor/docs/topics_cpu_monitor.md b/utilities/system_monitor/docs/topics_cpu_monitor.md new file mode 100644 index 00000000000..74b54ed779b --- /dev/null +++ b/utilities/system_monitor/docs/topics_cpu_monitor.md @@ -0,0 +1,98 @@ +# ROS topics: CPU Monitor + +## CPU Temperature +/diagnostics/cpu_monitor: CPU Temperature + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | warm | +| ERROR | hot | + +[values] + +| key (example) | value (example) | +| ---- | --- | +| Package id 0, Core [0-9], thermal_zone[0-9] | 50.0 DegC | +*key: thermal_zone[0-9] for ARM architecture. + +## CPU Usage +/diagnostics/cpu_monitor: CPU Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | +| ERROR | very high Lload | + +[values] + +| key | value (example) | +| ---- | --- | +| CPU [all,0-9]: status | OK / high load / very high load | +| CPU [all,0-9]: usr | 2.00% | +| CPU [all,0-9]: nice | 0.00% | +| CPU [all,0-9]: sys | 1.00% | +| CPU [all,0-9]: idle | 97.00% | + +## CPU Load Average +/diagnostics/cpu_monitor: CPU Load Average + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | + +[values] + +| key | value (example) | +| ---- | --- | +| 1min | 14.50% | +| 5min | 14.55% | +| 15min | 9.67% | + +## CPU Thermal Throttling +> Intel and raspi platform only.
        +> Tegra platform not supported. + +/diagnostics/cpu_monitor: CPU Thermal Throttling + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| ERROR | throttling | + +[values for intel platform] + +| key | value (example) | +| ---- | --- | +| CPU [0-9]: Pkg Thermal Status | OK / throttling | + +[values for raspi platform] + +| key | value (example) | +| ---- | --- | +| status | All clear / Currently throttled / Soft temperature limit active | + +## CPU Frequency +/diagnostics/cpu_monitor: CPU Frequency + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | + +[values] + +| key | value (example) | +| ---- | --- | +| CPU [0-9]: clock | 2879MHz | diff --git a/utilities/system_monitor/docs/topics_gpu_monitor.md b/utilities/system_monitor/docs/topics_gpu_monitor.md new file mode 100644 index 00000000000..34151cdda71 --- /dev/null +++ b/utilities/system_monitor/docs/topics_gpu_monitor.md @@ -0,0 +1,107 @@ +# ROS topics: GPU Monitor + +> Intel and tegra platform only.
        +> Raspi platform not supported. + +## GPU Temperature +/diagnostics/gpu_monitor: GPU Temperature + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | warm | +| ERROR | hot | + +[values] + +| key (example) | value (example) | +| ---- | --- | +| GeForce GTX 1650, thermal_zone[0-9] | 46.0 DegC | +*key: thermal_zone[0-9] for ARM architecture. + +## GPU Usage +/diagnostics/gpu_monitor: GPU Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | +| ERROR | very high load | + +[values] + +| key | value (example) | +| ---- | --- | +| GPU [0-9]: status | OK / high load / very high load | +| GPU [0-9]: name | GeForce GTX 1650, gpu.[0-9] | +| GPU [0-9]: usage | 19.0% | +*key: gpu.[0-9] for ARM architecture. + +## GPU Memory Usage +> Intel platform only.
        +> There is no separate gpu memory in tegra. Both cpu and gpu uses cpu memory. + +/diagnostics/gpu_monitor: GPU Memory Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | +| ERROR | very high load | + +[values] + +| key | value (example) | +| ---- | --- | +| GPU [0-9]: status | OK / high load / very high load | +| GPU [0-9]: name | GeForce GTX 1650 | +| GPU [0-9]: usage | 13.0% | +| GPU [0-9]: total | 3G | +| GPU [0-9]: used | 1G | +| GPU [0-9]: free | 2G | + +## GPU Thermal Throttling +> Intel platform only.
        +> Tegra platform not supported. + +/diagnostics/gpu_monitor: GPU Thermal Throttling + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| ERROR | throttling | + +[values] + +| key | value (example) | +| ---- | --- | +| GPU [0-9]: status | OK / throttling | +| GPU [0-9]: name | GeForce GTX 1650 | +| GPU [0-9]: graphics clock | 1020 MHz | +| GPU [0-9]: reasons | GpuIdle / SwThermalSlowdown etc. | + +## GPU Frequency +> Tegra platform only. + +/diagnostics/gpu_monitor: GPU Frequency + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | + +[values] + +| key (example) | value (example) | +| ---- | --- | +| GPU 17000000.gv11b: clock | 318 MHz | + diff --git a/utilities/system_monitor/docs/topics_hdd_monitor.md b/utilities/system_monitor/docs/topics_hdd_monitor.md new file mode 100644 index 00000000000..6b447c2bacc --- /dev/null +++ b/utilities/system_monitor/docs/topics_hdd_monitor.md @@ -0,0 +1,45 @@ +# ROS topics: CPU Monitor + +## HDD Temperature +/diagnostics/hdd_monitor: HDD Temperature + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | hot | +| ERROR | critical hot | + +[values] + +| key | value (example) | +| ---- | --- | +| HDD [0-9]: status | OK / hot / critical hot | +| HDD [0-9]: name | /dev/nvme0 | +| HDD [0-9]: model | SAMSUNG MZVLB1T0HBLR-000L7 | +| HDD [0-9]: serial | S4EMNF0M820682 | +| HDD [0-9]: temperature | 37.0 DegC | + +## HDD Usage +/diagnostics/hdd_monitor: HDD Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | low disk space | +| ERROR | very low disk space | + +[values] + +| key | value (example) | +| ---- | --- | +| HDD [0-9]: status | OK / low disk space / very low disk space | +| HDD [0-9]: filesystem | /dev/nvme0n1p4 | +| HDD [0-9]: size | 264G | +| HDD [0-9]: used | 172G | +| HDD [0-9]: avail | 749G | +| HDD [0-9]: use | 69% | +| HDD [0-9]: mounted on | / | diff --git a/utilities/system_monitor/docs/topics_mem_monitor.md b/utilities/system_monitor/docs/topics_mem_monitor.md new file mode 100644 index 00000000000..c05e680b95b --- /dev/null +++ b/utilities/system_monitor/docs/topics_mem_monitor.md @@ -0,0 +1,27 @@ +# ROS topics: Memory Monitor + +## Memory Usage +/diagnostics/mem_monitor: Memory Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | +| ERROR | very high load | + +[values] + +| key | value (example) | +| ---- | --- | +| Mem: usage | 18.99% | +| Mem: total | 31G | +| Mem: used | 5.9G | +| Mem: free | 15G | +| Swap: total | 2.0G | +| Swap: used | 0B | +| Swap: free | 2.0G | +| Total: total | 33G | +| Total: used | 5.9G | +| Total: free | 17G | diff --git a/utilities/system_monitor/docs/topics_net_monitor.md b/utilities/system_monitor/docs/topics_net_monitor.md new file mode 100644 index 00000000000..63bff875523 --- /dev/null +++ b/utilities/system_monitor/docs/topics_net_monitor.md @@ -0,0 +1,30 @@ +# ROS topics: Net Monitor + +## Network Usage +/diagnostics/cpu_monitor: Network Usage + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high load | +| ERROR | down | + +[values] + +| key | value (example) | +| ---- | --- | +| Network [0-9]: status | OK / high load / down | +| Network [0-9]: interface name | wlp82s0 | +| Network [0-9]: rx_usage | 0.00% | +| Network [0-9]: tx_usage | 0.00% | +| Network [0-9]: rx_traffic | 0.00 MB/s | +| Network [0-9]: tx_traffic | 0.00 MB/s | +| Network [0-9]: capacity | 400.0 MB/s | +| Network [0-9]: mtu | 1500 | +| Network [0-9]: rx_bytes | 58455228 | +| Network [0-9]: rx_errors | 0 | +| Network [0-9]: tx_bytes | 11069136 | +| Network [0-9]: tx_errors | 0 | +| Network [0-9]: collisions | 0 | diff --git a/utilities/system_monitor/docs/topics_ntp_monitor.md b/utilities/system_monitor/docs/topics_ntp_monitor.md new file mode 100644 index 00000000000..37545ed2d6f --- /dev/null +++ b/utilities/system_monitor/docs/topics_ntp_monitor.md @@ -0,0 +1,19 @@ +# ROS topics: NTP Monitor + +## NTP Offset +/diagnostics/ntp_monitor: NTP Offset + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | +| WARN | high | +| ERROR | too high | + +[values] + +| key | value (example) | +| ---- | --- | +| NTP Offset | -0.013181 sec | +| NTP Delay | 0.053880 sec | diff --git a/utilities/system_monitor/docs/topics_process_monitor.md b/utilities/system_monitor/docs/topics_process_monitor.md new file mode 100644 index 00000000000..786f8d473e8 --- /dev/null +++ b/utilities/system_monitor/docs/topics_process_monitor.md @@ -0,0 +1,72 @@ +# ROS topics: Process Monitor + +## Tasks Summary +/diagnostics/process_monitor: Tasks Summary + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | + +[values] + +| key | value (example) | +| ---- | --- | +| total | 409 | +| running | 2 | +| sleeping | 321 | +| stopped | 0 | +| zombie | 0 | + +## High-load Proc[0-9] +/diagnostics/process_monitor: High-load Proc[0-9] + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | + +[values] + +| key | value (example) | +| ---- | --- | +| COMMAND | /usr/lib/firefox/firefox | +| %CPU | 37.5 | +| %MEM | 2.1 | +| PID | 14062 | +| USER | autoware | +| PR | 20 | +| NI | 0 | +| VIRT | 3461152 | +| RES | 669052 | +| SHR | 481208 | +| S | S | +| TIME+ | 23:57.49 | + +## High-mem Proc[0-9] +/diagnostics/process_monitor: High-mem Proc[0-9] + +[summary] + +| level | message | +| ---- | --- | +| OK | OK | + +[values] + +| key | value (example) | +| ---- | --- | +| COMMAND | /snap/multipass/1784/usr/bin/qemu-system-x86_64 | +| %CPU | 0 | +| %MEM | 2.5 | +| PID | 1565 | +| USER | root | +| PR | 20 | +| NI | 0 | +| VIRT | 3722320 | +| RES | 812432 | +| SHR | 20340 | +| S | S | +| TIME+ | 0:22.84 | diff --git a/utilities/system_monitor/include/hdd_reader/hdd_reader.h b/utilities/system_monitor/include/hdd_reader/hdd_reader.h new file mode 100644 index 00000000000..abb57447e96 --- /dev/null +++ b/utilities/system_monitor/include/hdd_reader/hdd_reader.h @@ -0,0 +1,61 @@ +#ifndef HDD_READER_HDD_READER_H +#define HDD_READER_HDD_READER_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file hdd_reader.h + * @brief HDD reader definitions + */ + +#include +#include +#include +#include +#include + +/** + * @brief HDD information + */ +struct HDDInfo +{ + int error_code_; //!< @brief error code, 0 on success, otherwise error + std::string model_; //!< @brief Model number + std::string serial_; //!< @brief Serial number + int temp_; //!< @brief temperature(DegC) + + /** + * @brief Load or save data members. + * @param [inout] ar archive reference to load or save the serialized data members + * @param [in] version version for the archive + * @note NOLINT syntax is needed since this is an interface to serialization and + * used inside boost serialization. + */ + template void serialize(archive& ar, const unsigned /*version*/) // NOLINT(runtime/references) + { + ar & error_code_; + ar & model_; + ar & serial_; + ar & temp_; + } +}; + +/** + * @brief HDD information list + */ +typedef std::map HDDInfoList; + +#endif // HDD_READER_HDD_READER_H diff --git a/utilities/system_monitor/include/msr_reader/msr_reader.h b/utilities/system_monitor/include/msr_reader/msr_reader.h new file mode 100644 index 00000000000..aaa9e1ebba4 --- /dev/null +++ b/utilities/system_monitor/include/msr_reader/msr_reader.h @@ -0,0 +1,50 @@ +#ifndef MSR_READER_MSR_READER_H +#define MSR_READER_MSR_READER_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file msr_reader.h + * @brief MSR reader definitions + */ + +#include +#include +#include + +/** + * @brief MSR information + */ +struct MSRInfo +{ + int error_code_; //!< @brief error code, 0 on success, otherwise error + std::vector pkg_thermal_status_; //!< @brief Pkg Thermal Status + + /** + * @brief Load or save data members. + * @param [inout] ar archive reference to load or save the serialized data members + * @param [in] version version for the archive + * @note NOLINT syntax is needed since this is an interface to serialization and + * used inside boost serialization. + */ + template void serialize(archive& ar, const unsigned /*version*/) // NOLINT(runtime/references) + { + ar & error_code_; + ar & pkg_thermal_status_; + } +}; + +#endif // MSR_READER_MSR_READER_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.h new file mode 100644 index 00000000000..ef7b4d3916c --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/arm_cpu_monitor.h @@ -0,0 +1,51 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_ARM_CPU_MONITOR_H +#define SYSTEM_MONITOR_CPU_MONITOR_ARM_CPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file arm_cpu_monitor.h + * @brief ARM CPU monitor class + */ + +#include + +class CPUMonitor: public CPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief get names for core temperature files + */ + void getTempNames(void) override; + +protected: + /** + * @brief check CPU thermal throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_ARM_CPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.h new file mode 100644 index 00000000000..d2d6c7fe1bc --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/cpu_monitor_base.h @@ -0,0 +1,163 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_CPU_MONITOR_BASE_H +#define SYSTEM_MONITOR_CPU_MONITOR_CPU_MONITOR_BASE_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file cpu_monitor_base.h + * @brief CPU monitor base class + */ + +#include +#include +#include +#include + +/** + * @brief CPU temperature information + */ +typedef struct cpu_temp_info +{ + std::string label_; //!< @brief cpu label + std::string path_; //!< @brief sysfs path to cpu temperature + + cpu_temp_info() : label_(), path_() {} + cpu_temp_info(const std::string &label, const std::string &path) : label_(label), path_(path) {} +} +cpu_temp_info; + +/** + * @brief CPU frequency information + */ +typedef struct cpu_freq_info +{ + int index_; //!< @brief cpu index + std::string path_; //!< @brief sysfs path to cpu frequency + + cpu_freq_info() : index_(0), path_() {} + cpu_freq_info(int index, const std::string &path) : index_(index), path_(path) {} +} +cpu_freq_info; + +class CPUMonitorBase +{ +public: + /** + * @brief main loop + */ + void run(void); + + /** + * @brief get names for core temperature files + */ + virtual void getTempNames(void); + + /** + * @brief get names for cpu frequency files + */ + virtual void getFreqNames(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitorBase(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief check CPU temperature + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check CPU usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check CPU load average + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkLoad(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check CPU thermal throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + */ + virtual void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check CPU frequency + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + int num_cores_; //!< @brief number of cores + std::vector temps_; //!< @brief CPU list for temperature + std::vector freqs_; //!< @brief CPU list for frequency + bool mpstat_exists_; //!< @brief flag if mpstat exists + + float temp_warn_; //!< @brief CPU temperature(DegC) to generate warning + float temp_error_; //!< @brief CPU temperature(DegC) to generate error + float usage_warn_; //!< @brief CPU usage(%) to generate warning + float usage_error_; //!< @brief CPU usage(%) to generate error + float load1_warn_; //!< @brief CPU load average 1min(%) to generate warning + float load5_warn_; //!< @brief CPU load average 5min(%) to generate warning + + /** + * @brief CPU temperature status messages + */ + const std::map temp_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "warm"}, {DiagStatus::ERROR, "hot"} + }; + + /** + * @brief CPU usage status messages + */ + const std::map load_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "high load"}, {DiagStatus::ERROR, "very high load"} + }; + + /** + * @brief CPU thermal throttling status messages + */ + const std::map thermal_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "unused"}, {DiagStatus::ERROR, "throttling"} + }; +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_CPU_MONITOR_BASE_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.h new file mode 100644 index 00000000000..f3f5ccf5074 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/intel_cpu_monitor.h @@ -0,0 +1,58 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_INTEL_CPU_MONITOR_H +#define SYSTEM_MONITOR_CPU_MONITOR_INTEL_CPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file intel_cpu_monitor.h + * @brief CPU monitor class + */ + +#include + +class CPUMonitor: public CPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh); + +protected: + /** + * @brief check CPU thermal throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief get names for core temperature files + */ + void getTempNames(void) override; + + /** + * @brief Add a loadable kernel module msr + */ + void modprobeMSR(void); + + int msr_reader_port_; //!< @brief port number to connect to msr_reader +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_INTEL_CPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.h new file mode 100644 index 00000000000..5729cdfd598 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.h @@ -0,0 +1,73 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_RASPI_CPU_MONITOR_H +#define SYSTEM_MONITOR_CPU_MONITOR_RASPI_CPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file raspi_cpu_monitor.h + * @brief Raspberry Pi CPU monitor class + */ + +#include + +#define raspiUnderVoltageDetected (1 << 0) // 0x00001 +#define raspiArmFrequencyCapped (1 << 1) // 0x00002 +#define raspiCurrentlyThrottled (1 << 2) // 0x00004 +#define raspiSoftTemperatureLimitActive (1 << 3) // 0x00008 +#define raspiUnderVoltageHasOccurred (1 << 16) // 0x10000 +#define raspiArmFrequencyCappedHasOccurred (1 << 17) // 0x20000 +#define raspiThrottlingHasOccurred (1 << 18) // 0x40000 +#define raspiSoftTemperatureLimitHasOccurred (1 << 19) // 0x80000 + +#define raspiThermalThrottlingMask (raspiCurrentlyThrottled | raspiSoftTemperatureLimitActive) + +#define throttledToString(X) ( \ + ((X) & raspiUnderVoltageDetected) ? "Under-voltage detected" : \ + ((X) & raspiArmFrequencyCapped) ? "Arm frequency capped" : \ + ((X) & raspiCurrentlyThrottled) ? "Currently throttled" : \ + ((X) & raspiSoftTemperatureLimitActive) ? "Soft temperature limit active" : \ + ((X) & raspiUnderVoltageHasOccurred) ? "Under-voltage has occurred" : \ + ((X) & raspiArmFrequencyCappedHasOccurred) ? "Arm frequency capped has occurred" : \ + ((X) & raspiThrottlingHasOccurred) ? "Throttling has occurred" : \ + ((X) & raspiSoftTemperatureLimitHasOccurred) ? "Soft temperature limit has occurred" : \ + "UNKNOWN" ) + +class CPUMonitor: public CPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief get names for core temperature files + */ + void getTempNames(void) override; + +protected: + /** + * @brief check CPU thermal throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_RASPI_CPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.h new file mode 100644 index 00000000000..605baefcea9 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/tegra_cpu_monitor.h @@ -0,0 +1,51 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_TEGRA_CPU_MONITOR_H +#define SYSTEM_MONITOR_CPU_MONITOR_TEGRA_CPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file tegra_cpu_monitor.h + * @brief TEGRA CPU monitor class + */ + +#include + +class CPUMonitor: public CPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief get names for core temperature files + */ + void getTempNames(void) override; + +protected: + /** + * @brief check CPU thermal throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_TEGRA_CPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.h b/utilities/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.h new file mode 100644 index 00000000000..5b44f67bdfa --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/cpu_monitor/unknown_cpu_monitor.h @@ -0,0 +1,37 @@ +#ifndef SYSTEM_MONITOR_CPU_MONITOR_UNKNOWN_CPU_MONITOR_H +#define SYSTEM_MONITOR_CPU_MONITOR_UNKNOWN_CPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file unknown_cpu_monitor.h + * @brief Unknown CPU monitor class + */ + +#include + +class CPUMonitor: public CPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); +}; + +#endif // SYSTEM_MONITOR_CPU_MONITOR_UNKNOWN_CPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.h b/utilities/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.h new file mode 100644 index 00000000000..c357019dc07 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/gpu_monitor/gpu_monitor_base.h @@ -0,0 +1,123 @@ +#ifndef SYSTEM_MONITOR_GPU_MONITOR_GPU_MONITOR_BASE_H +#define SYSTEM_MONITOR_GPU_MONITOR_GPU_MONITOR_BASE_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file gpu_monitor.h + * @brief GPU monitor class + */ + +#include +#include + +class GPUMonitorBase +{ +public: + /** + * @brief main loop + */ + virtual void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + GPUMonitorBase(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief check GPU temperature + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check GPU usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check GPU memory usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkMemoryUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check GPU throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check GPU frequency + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + virtual void checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + + float temp_warn_; //!< @brief GPU temperature(DegC) to generate warning + float temp_error_; //!< @brief GPU temperature(DegC) to generate error + float gpu_usage_warn_; //!< @brief GPU usage(%) to generate warning + float gpu_usage_error_; //!< @brief GPU usage(%) to generate error + float memory_usage_warn_; //!< @brief GPU memory usage(%) to generate warning + float memory_usage_error_; //!< @brief GPU memory usage(%) to generate error + + /** + * @brief GPU temperature status messages + */ + const std::map temp_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "warm"}, {DiagStatus::ERROR, "hot"} + }; + + /** + * @brief GPU usage status messages + */ + const std::map load_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "high load"}, {DiagStatus::ERROR, "very high load"} + }; + + /** + * @brief GPU throttling status messages + */ + const std::map throttling_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "unused"}, {DiagStatus::ERROR, "throttling"} + }; +}; + +#endif // SYSTEM_MONITOR_GPU_MONITOR_GPU_MONITOR_BASE_H diff --git a/utilities/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.h b/utilities/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.h new file mode 100644 index 00000000000..87615dcf9e2 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.h @@ -0,0 +1,113 @@ +#ifndef SYSTEM_MONITOR_GPU_MONITOR_NVML_GPU_MONITOR_H +#define SYSTEM_MONITOR_GPU_MONITOR_NVML_GPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file nvml_gpu_monitor.h + * @brief NVML GPU monitor class + */ + +#include +#include +#include +#include +#include + +#define reasonToString(X) ( \ + ((X) & nvmlClocksThrottleReasonGpuIdle) ? "GpuIdle" : \ + ((X) & nvmlClocksThrottleReasonApplicationsClocksSetting) ? "ApplicationsClocksSetting" : \ + ((X) & nvmlClocksThrottleReasonSwPowerCap) ? "SwPowerCap" : \ + ((X) & nvmlClocksThrottleReasonHwSlowdown) ? "HwSlowdown" : \ + ((X) & nvmlClocksThrottleReasonSyncBoost) ? "SyncBoost" : \ + ((X) & nvmlClocksThrottleReasonSwThermalSlowdown) ? "SwThermalSlowdown" : \ + ((X) & nvmlClocksThrottleReasonHwThermalSlowdown) ? "HwThermalSlowdown" : \ + ((X) & nvmlClocksThrottleReasonHwPowerBrakeSlowdown) ? "HwPowerBrakeSlowdown" : \ + ((X) & nvmlClocksThrottleReasonDisplayClockSetting) ? "DisplayClockSetting" : \ + "UNKNOWN" ) + +/** + * @brief GPU information + */ +typedef struct gpu_info +{ + nvmlDevice_t device; //!< @brief handle for a particular device + char name[NVML_DEVICE_NAME_BUFFER_SIZE]; //!< @brief name of device + nvmlPciInfo_t pci; //!< @brief PCI information about a GPU device + nvmlUtilization_t utilization; //!< @brief Utilization information for a device +} +gpu_info; + +class GPUMonitor: public GPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void) override; + +protected: + /** + * @brief check GPU temperature + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU memory usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkMemoryUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief get human-readable output for memory size + * @param [in] size size with bytes + * @return human-readable output + * @note NOLINT syntax is needed since struct nvmlMemory_t has unsigned long long values to return memory size. + */ + std::string toHumanReadable(unsigned long long size); // NOLINT(runtime/int) + + std::vector gpus_; //!< @brief list of gpus +}; + +#endif // SYSTEM_MONITOR_GPU_MONITOR_NVML_GPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.h b/utilities/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.h new file mode 100644 index 00000000000..7038717684b --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/gpu_monitor/tegra_gpu_monitor.h @@ -0,0 +1,101 @@ +#ifndef SYSTEM_MONITOR_GPU_MONITOR_TEGRA_GPU_MONITOR_H +#define SYSTEM_MONITOR_GPU_MONITOR_TEGRA_GPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file tegra_gpu_monitor.h + * @brief Tegra TGPU monitor class + */ + +#include +#include +#include + +typedef struct gpu_info +{ + std::string label_; //!< @brief gpu label + std::string path_; //!< @brief sysfs path to gpu temperature + + gpu_info() : label_(), path_() {} + gpu_info(const std::string &l, const std::string &p) : label_(l), path_(p) {} +} +gpu_info; + +class GPUMonitor: public GPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + +protected: + /** + * @brief check GPU temperature + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU throttling + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief check GPU frequency + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat) override; // NOLINT(runtime/references) + + /** + * @brief get names for gpu temperature files + */ + void getTempNames(void); + + /** + * @brief get names for gpu load files + */ + void getLoadNames(void); + + /** + * @brief get names for gpu frequency files + */ + void getFreqNames(void); + + std::vector temps_; //!< @brief GPU list for temperature + std::vector loads_; //!< @brief GPU list for utilization + std::vector freqs_; //!< @brief GPU list for frequency +}; + +#endif // SYSTEM_MONITOR_GPU_MONITOR_TEGRA_GPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.h b/utilities/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.h new file mode 100644 index 00000000000..aa9c435d40d --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/gpu_monitor/unknown_gpu_monitor.h @@ -0,0 +1,37 @@ +#ifndef SYSTEM_MONITOR_GPU_MONITOR_UNKNOWN_GPU_MONITOR_H +#define SYSTEM_MONITOR_GPU_MONITOR_UNKNOWN_GPU_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file unknown_gpu_monitor.h + * @brief Unknown GPU monitor class + */ + +#include + +class GPUMonitor: public GPUMonitorBase +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); +}; + +#endif // SYSTEM_MONITOR_GPU_MONITOR_UNKNOWN_GPU_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.h b/utilities/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.h new file mode 100644 index 00000000000..3200b4d0271 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/hdd_monitor/hdd_monitor.h @@ -0,0 +1,106 @@ +#ifndef SYSTEM_MONITOR_HDD_MONITOR_HDD_MONITOR_H +#define SYSTEM_MONITOR_HDD_MONITOR_HDD_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file hdd_monitor.h + * @brief HDD monitor class + */ + +#include +#include +#include + +/** + * @brief error and warning temperature levels + */ +struct TempParam +{ + float temp_warn_; //!< @brief HDD temperature(DegC) to generate warning + float temp_error_; //!< @brief HDD temperature(DegC) to generate error + + TempParam() : temp_warn_(55.0), temp_error_(70.0) {} +}; + +class HDDMonitor +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + HDDMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief check HDD temperature + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief check HDD usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief get temperature parameters + */ + void getTempParams(void); + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + + float usage_warn_; //!< @brief HDD usage(%) to generate warning + float usage_error_; //!< @brief HDD usage(%) to generate error + int hdd_reader_port_; //!< @brief port number to connect to hdd_reader + std::map temp_params_; //!< @brief list of error and warning levels + + /** + * @brief HDD temperature status messages + */ + const std::map temp_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "hot"}, {DiagStatus::ERROR, "critical hot"} + }; + + /** + * @brief HDD usage status messages + */ + const std::map usage_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "low disk space"}, {DiagStatus::ERROR, "very low disk space"} + }; +}; + +#endif // SYSTEM_MONITOR_HDD_MONITOR_HDD_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/mem_monitor/mem_monitor.h b/utilities/system_monitor/include/system_monitor/mem_monitor/mem_monitor.h new file mode 100644 index 00000000000..45c739669d1 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/mem_monitor/mem_monitor.h @@ -0,0 +1,79 @@ +#ifndef SYSTEM_MONITOR_MEM_MONITOR_MEM_MONITOR_H +#define SYSTEM_MONITOR_MEM_MONITOR_MEM_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file mem_monitor.h + * @brief Memory monitor class + */ + +#include +#include +#include + +class MemMonitor +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + MemMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief check Memory usage + * @param @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief get human-readable output for memory size + * @param [in] str size with bytes + * @return human-readable output + */ + std::string toHumanReadable(const std::string &str); + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + + float usage_warn_; //!< @brief Memory usage(%) to generate warning + float usage_error_; //!< @brief Memory usage(%) to generate error + + /** + * @brief Memory usage status messages + */ + const std::map usage_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "high load"}, {DiagStatus::ERROR, "very high load"} + }; +}; + +#endif // SYSTEM_MONITOR_MEM_MONITOR_MEM_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/net_monitor/net_monitor.h b/utilities/system_monitor/include/system_monitor/net_monitor/net_monitor.h new file mode 100644 index 00000000000..590a578483b --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/net_monitor/net_monitor.h @@ -0,0 +1,98 @@ +#ifndef SYSTEM_MONITOR_NET_MONITOR_NET_MONITOR_H +#define SYSTEM_MONITOR_NET_MONITOR_NET_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file net_monitor.h + * @brief Net monitor class + */ + +#include +#include +#include +#include +#include + +#define toMbit(X) (static_cast(X) / 1000000*8) + +/** + * @brief Bytes information + */ +typedef struct bytes +{ + unsigned int rx_bytes; //!< @brief total bytes received + unsigned int tx_bytes; //!< @brief total bytes transmitted + + bytes() : rx_bytes(0), tx_bytes(0) {} +} +bytes; + +class NetMonitor +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + NetMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief check CPU usage + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief get wireless speed + * @param [in] ifa_name interface name + * @return wireless speed + */ + float getWirelessSpeed(const char *ifa_name); + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + std::map bytes_; //!< @brief list of bytes + ros::Time last_update_time_; //!< @brief last update time + std::vector device_params_; //!< @brief list of devices + NL80211 nl80211_; // !< @brief 802.11 netlink-based interface + + float usage_warn_; //!< @brief Memory usage(%) to generate warning + + /** + * @brief Network usage status messages + */ + const std::map usage_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "high load"}, {DiagStatus::ERROR, "down"} + }; +}; + +#endif // SYSTEM_MONITOR_NET_MONITOR_NET_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/net_monitor/nl80211.h b/utilities/system_monitor/include/system_monitor/net_monitor/nl80211.h new file mode 100644 index 00000000000..dd84ed9976c --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/net_monitor/nl80211.h @@ -0,0 +1,58 @@ +#ifndef SYSTEM_MONITOR_NET_MONITOR_NL80211_H +#define SYSTEM_MONITOR_NET_MONITOR_NL80211_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file nl80211.h + * @brief 802.11 netlink-based interface class + */ + +class NL80211 +{ +public: + /** + * @brief constructor + */ + NL80211(); + + /** + * @brief initialize + */ + void init(void); + + /** + * @brief get bitrate + * @param [in] ifa_name interface name + * @return bitrate + */ + float getBitrate(const char *ifa_name); + + /** + * @brief shutdown + */ + void shutdown(void); + + float bitrate_; //!< @brief bitrate + +private: + bool initialized_; //!< @brief Indicating whether initialization was completed successfully or not + struct nl_sock *socket_; //!< @brief Netlink socket + int id_; //!< @brief Generic netlink family id + struct nl_cb *cb_; //!< @brief Callback handle +}; + +#endif // SYSTEM_MONITOR_NET_MONITOR_NL80211_H diff --git a/utilities/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.h b/utilities/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.h new file mode 100644 index 00000000000..5f8de6c1fbd --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.h @@ -0,0 +1,74 @@ +#ifndef SYSTEM_MONITOR_NTP_MONITOR_NTP_MONITOR_H +#define SYSTEM_MONITOR_NTP_MONITOR_NTP_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file ntp_monitor.h + * @brief NTP monitor class + */ + +#include +#include +#include + +class NTPMonitor +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + NTPMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief check NTP Offset + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void checkOffset(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + bool ntpdate_exists_; //!< @brief flag if ntpdate exists + + std::string server_; //!< @brief Reference server + float offset_warn_; //!< @brief NTP offset(us) to generate warning + float offset_error_; //!< @brief NTP offset(us) to generate error + + /** + * @brief NTP offset status messages + */ + const std::map offset_dict_ = + { + {DiagStatus::OK, "OK"}, {DiagStatus::WARN, "high"}, {DiagStatus::ERROR, "too high"} + }; +}; + +#endif // SYSTEM_MONITOR_NTP_MONITOR_NTP_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/process_monitor/diag_task.h b/utilities/system_monitor/include/system_monitor/process_monitor/diag_task.h new file mode 100644 index 00000000000..1aa64c37157 --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/process_monitor/diag_task.h @@ -0,0 +1,177 @@ +#ifndef SYSTEM_MONITOR_PROCESS_MONITOR_DIAG_TASK_H +#define SYSTEM_MONITOR_PROCESS_MONITOR_DIAG_TASK_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file diag_task.h + * @brief diagnostics task for high load/memory procs + */ + +#include +#include + +class DiagTask : public diagnostic_updater::DiagnosticTask +{ +public: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief constructor + * @param [in] name diagnostics status name + */ + explicit DiagTask(const std::string &name) : DiagnosticTask(name) {} + + /** + * @brief main loop + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + */ + void run(diagnostic_updater::DiagnosticStatusWrapper &stat) + { + stat.summary(level_, message_); + + if (level_ != DiagStatus::OK) + { + stat.add("content", content_); + } + else + { + stat.add("COMMAND", command_); + stat.add("%CPU", cpu_); + stat.add("%MEM", mem_); + stat.add("PID", pid_); + stat.add("USER", user_); + stat.add("PR", pr_); + stat.add("NI", ni_); + stat.add("VIRT", virt_); + stat.add("RES", res_); + stat.add("SHR", shr_); + stat.add("S", s_); + stat.add("TIME+", time_); + } + stat.summary(level_, message_); + } + + /** + * @brief set dagnostics status + * @param [in] status Diagnostics error level + * @param [in] message Diagnostics status message + */ + void setDiagnosticsStatus(int level, const std::string &message) { level_ = level; message_ = message; } + + /** + * @brief set error content + * @param [in] error_command Error command + * @param [in] content Error content + */ + void setErrorContent(const std::string &error_command, const std::string &content) + { + error_command_ = error_command; content_ = content; + } + + /** + * @brief set process id + * @param [in] pid process id + */ + void setProcessId(const std::string &pid) { pid_ = pid; } + + /** + * @brief set user name + * @param [in] user user name + */ + void setUserName(const std::string &user) { user_ = user; } + + /** + * @brief set priority + * @param [in] pr priority + */ + void setPriority(const std::string &pr) { pr_ = pr; } + + /** + * @brief set nice value + * @param [in] ni nice value + */ + void setNiceValue(const std::string &ni) { ni_ = ni; } + + /** + * @brief set virtual image + * @param [in] virt virtual image + */ + void setVirtualImage(const std::string &virt) { virt_ = virt; } + + /** + * @brief set resident size + * @param [in] res resident size + */ + void setResidentSize(const std::string &res) { res_ = res; } + + /** + * @brief set shared mem size + * @param [in] shr shared mem size + */ + void setSharedMemSize(const std::string &shr) { shr_ = shr; } + + /** + * @brief set process status + * @param [in] s process status + */ + void setProcessStatus(const std::string &s) { s_ = s; } + + /** + * @brief set CPU usage + * @param [in] cpu CPU usage + */ + void setCPUUsage(const std::string &cpu) { cpu_ = cpu; } + + /** + * @brief set memory usage + * @param [in] mem memory usage + */ + void setMemoryUsage(const std::string &mem) { mem_ = mem; } + + /** + * @brief set CPU time + * @param [in] time CPU time + */ + void setCPUTime(const std::string &time) { time_ = time; } + + /** + * @brief set Command name/line + * @param [in] command Command name/line + */ + void setCommandName(const std::string &command) { command_ = command; } + +private: + int level_; //!< @brief Diagnostics error level + std::string message_; //!< @brief Diagnostics status message + std::string error_command_; //!< @brief Error command + std::string content_; //!< @brief Error content + + std::string pid_; //!< @brief Process Id + std::string user_; //!< @brief User Name + std::string pr_; //!< @brief Priority + std::string ni_; //!< @brief Nice value + std::string virt_; //!< @brief Virtual Image (kb) + std::string res_; //!< @brief Resident size (kb) + std::string shr_; //!< @brief Shared Mem size (kb) + std::string s_; //!< @brief Process Status + std::string cpu_; //!< @brief CPU usage + std::string mem_; //!< @brief Memory usage + std::string time_; //!< @brief CPU Time + std::string command_; //!< @brief Command name/line +}; + +#endif // SYSTEM_MONITOR_PROCESS_MONITOR_DIAG_TASK_H diff --git a/utilities/system_monitor/include/system_monitor/process_monitor/process_monitor.h b/utilities/system_monitor/include/system_monitor/process_monitor/process_monitor.h new file mode 100644 index 00000000000..c4c1cea09bf --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/process_monitor/process_monitor.h @@ -0,0 +1,118 @@ +#ifndef SYSTEM_MONITOR_PROCESS_MONITOR_PROCESS_MONITOR_H +#define SYSTEM_MONITOR_PROCESS_MONITOR_PROCESS_MONITOR_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file process_monitor.h + * @brief Process monitor class + */ + +#include +#include +#include +#include +#include + +namespace bp = boost::process; + +class ProcessMonitor +{ +public: + /** + * @brief constructor + * @param [in] nh node handle to access global parameters + * @param [in] pnh node handle to access private parameters + */ + ProcessMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh); + + /** + * @brief main loop + */ + void run(void); + +protected: + using DiagStatus = diagnostic_msgs::DiagnosticStatus; + + /** + * @brief monitor processes + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void monitorProcesses(diagnostic_updater::DiagnosticStatusWrapper &stat); // NOLINT(runtime/references) + + /** + * @brief get task summary + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @param [in] output top command output + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void getTasksSummary + (diagnostic_updater::DiagnosticStatusWrapper &stat, const std::string &output); // NOLINT(runtime/references) + + /** + * @brief remove header + * @param [out] stat diagnostic message passed directly to diagnostic publish calls + * @param [in] output top command output + * @note NOLINT syntax is needed since diagnostic_updater asks for a non-const reference + * to pass diagnostic message updated in this function to diagnostic publish calls. + */ + void removeHeader + (diagnostic_updater::DiagnosticStatusWrapper &stat, std::string &output); // NOLINT(runtime/references) + + /** + * @brief get high load processes + * @param [in] output top command output + */ + void getHighLoadProcesses(const std::string &output); + + /** + * @brief get high memory processes + * @param [in] output top command output + */ + void getHighMemoryProcesses(const std::string &output); + + /** + * @brief get top-rated processes + * @param [in] tasks list of diagnostics tasks for high load procs + * @param [in] output top command output + */ + void getTopratedProcesses(std::vector> *tasks, bp::pipe *p); + + /** + * @brief get top-rated processes + * @param [in] tasks list of diagnostics tasks for high load procs + * @param [in] message Diagnostics status message + * @param [in] error_command Error command + * @param [in] content Error content + */ + void setErrorContent(std::vector> *tasks, const std::string &message, + const std::string &error_command, const std::string &content); + + ros::NodeHandle nh_; //!< @brief ros node handle + ros::NodeHandle pnh_; //!< @brief private ros node handle + diagnostic_updater::Updater updater_; //!< @brief Updater class which advertises to /diagnostics + + char hostname_[HOST_NAME_MAX+1]; //!< @brief host name + + int num_of_procs_; //!< @brief number of processes to show + std::vector> load_tasks_; //!< @brief list of diagnostics tasks for high load procs + std::vector> memory_tasks_; //!< @brief list of diagnostics tasks for high memory procs +}; + +#endif // SYSTEM_MONITOR_PROCESS_MONITOR_PROCESS_MONITOR_H diff --git a/utilities/system_monitor/include/system_monitor/system_monitor_utility.h b/utilities/system_monitor/include/system_monitor/system_monitor_utility.h new file mode 100644 index 00000000000..13d45cf492d --- /dev/null +++ b/utilities/system_monitor/include/system_monitor/system_monitor_utility.h @@ -0,0 +1,91 @@ +#ifndef SYSTEM_MONITOR_SYSTEM_MONITOR_UTILITY_H +#define SYSTEM_MONITOR_SYSTEM_MONITOR_UTILITY_H +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file system_monitor_utility.h + * @brief System Monitor Utility class + */ + +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +typedef struct thermal_zone +{ + std::string type_; //!< @brief thermal zone name + std::string label_; //!< @brief thermal_zone[0-9] + std::string path_; //!< @brief sysfs path to temperature + + thermal_zone() : type_(), label_(), path_() {} + thermal_zone(const std::string &type, const std::string &label, const std::string &path) + : type_(type), label_(label), path_(path) {} +} +thermal_zone; + +class SystemMonitorUtility +{ +public: + /** + * @brief get thermal zone informaton + * @param [in] t thermal zone name + * @param [in] pointer to thermal zone informaton + */ + static void getThermalZone(const std::string &t, std::vector *therm) + { + if (therm == nullptr) return; + + therm->clear(); + + const fs::path root("/sys/class/thermal"); + + for (const fs::path& path : boost::make_iterator_range(fs::directory_iterator(root), fs::directory_iterator())) + { + if (!fs::is_directory(path)) continue; + + boost::smatch match; + const boost::regex filter(".*/thermal_zone(\\d+)"); + const std::string therm_dir = path.generic_string(); + + // not thermal_zone[0-9] + if (!boost::regex_match(therm_dir, match, filter)) continue; + + std::string type; + const fs::path type_path = path / "type"; + fs::ifstream ifs(type_path, std::ios::in); + if (ifs) + { + std::string line; + if (std::getline(ifs, line)) type = line; + } + ifs.close(); + + if (type != t) continue; + + const fs::path temp_path = path / "temp"; + therm->emplace_back(t, path.filename().generic_string(), temp_path.generic_string()); + } + } +}; + +#endif // SYSTEM_MONITOR_SYSTEM_MONITOR_UTILITY_H diff --git a/utilities/system_monitor/launch/system_monitor.launch b/utilities/system_monitor/launch/system_monitor.launch new file mode 100644 index 00000000000..f23c446894a --- /dev/null +++ b/utilities/system_monitor/launch/system_monitor.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/utilities/system_monitor/package.xml b/utilities/system_monitor/package.xml new file mode 100644 index 00000000000..4b57a6a2576 --- /dev/null +++ b/utilities/system_monitor/package.xml @@ -0,0 +1,19 @@ + + + system_monitor + 1.13.0 + The system_monitor package + Fumihito Ito + + Apache 2.0 + + catkin + rostest + diagnostic_msgs + roscpp + roslint + std_msgs + libnl-3-dev + sysstat + ntpdate + diff --git a/utilities/system_monitor/reader/hdd_reader/hdd_reader.cpp b/utilities/system_monitor/reader/hdd_reader/hdd_reader.cpp new file mode 100644 index 00000000000..4764a82761f --- /dev/null +++ b/utilities/system_monitor/reader/hdd_reader/hdd_reader.cpp @@ -0,0 +1,606 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file hdd_reader.cpp + * @brief HDD information read class + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +// 7634-7647 Unassigned +constexpr int PORT = 7635; + +/** + * @brief HDD information + */ +typedef struct +{ + std::string model_; //!< @brief Model number + std::string serial_; //!< @brief Serial number + int temperature_; //!< @brief Temperature +} +HDD_Info; + +/** + * @brief ATA PASS-THROUGH (12) command + * @note For details please see the document below. + * - ATA Command Pass-Through + * https://www.t10.org/ftp/t10/document.04/04-262r8.pdf + */ +typedef struct +{ + uint8_t operation_code_; //!< @brief OPERATION CODE (A1h) + uint8_t reserved0_:1; //!< @brief Reserved + uint8_t protool_:4; //!< @brief PROTOCOL + uint8_t multiple_count_:3; //!< @brief MULTIPLE_COUNT + uint8_t t_length_:2; //!< @brief T_LENGTH + uint8_t byt_blok_:1; //!< @brief BYT_BLOK + uint8_t t_dir_:1; //!< @brief T_DIR + uint8_t reserved1_:1; //!< @brief Reserved + uint8_t ck_cond_:1; //!< @brief CK_COND + uint8_t off_line_:2; //!< @brief OFF_LINE + uint8_t features_; //!< @brief FEATURES (0:7) + uint8_t sector_count_; //!< @brief SECTOR_COUNT (0:7) + uint8_t lba_low_; //!< @brief LBA_LOW (0:7) + uint8_t lba_mid_; //!< @brief LBA_MID (0:7) + uint8_t lbe_high_; //!< @brief LBE_HIGH (0:7) + uint8_t device_; //!< @brief DEVICE + uint8_t command_; //!< @brief COMMAND + uint8_t reserved2_; //!< @brief Reserved + uint8_t control_; //!< @brief CONTROL +} +ATAPassThrough12; + +/** + * @brief Attribute Table Format + * @note For details please see the documents below. + * - SMART Attribute Overview + * http://www.t13.org/Documents/UploadedDocuments/docs2005/e05171r0-ACS-SMARTAttributes_Overview.pdf + */ +typedef struct __attribute__((packed)) // Minimize total struct memory 16 to 12 +{ + uint8_t attribute_id_; //!< @brief Attribute ID + // Flags + uint16_t sarranty_:1; //!< @brief Bit 0 – Warranty + uint16_t offline_:1; //!< @brief Bit 1 – Offline + uint16_t performance_:1; //!< @brief Bit 2 – Performance + uint16_t error_rate_:1; //!< @brief Bit 3 – Error rate + uint16_t event_count_:1; //!< @brief Bit 4 – Event count + uint16_t self_preservation_:1; //!< @brief Bit 5 – Self-preservation + uint16_t reserved_:10; //!< @brief Bits 6–15 – Reserved + + uint8_t current_value_; //!< @brief Current value + uint8_t worst_value_; //!< @brief Worst value + uint32_t data_; //!< @brief Data + uint16_t attribute_specific_; //!< @brief Attribute-specific + uint8_t threshold_; //!< @brief Threshold +} +AttributeEntry; + +/** + * @brief Device SMART data structure + * @note For details please see the documents below. + * - ATA/ATAPI Command Set - 3 (ACS-3) + * http://www.t13.org/Documents/UploadedDocuments/docs2013/d2161r5-ATAATAPI_Command_Set_-_3.pdf + * - SMART Attribute Overview + * http://www.t13.org/Documents/UploadedDocuments/docs2005/e05171r0-ACS-SMARTAttributes_Overview.pdf + */ +typedef struct __attribute__((packed)) // Minimize total struct memory 514 to 512 +{ + // Offset 0..361 X Vendor specific + uint16_t smart_structure_version_; //!< @brief SMART structure version + AttributeEntry attribute_entry_[30]; //!< @brief Attribute entry 1 - 30 + // Offset 362 to 511 + uint8_t off_line_data_collection_status_; //!< @brief Off-line data collection status + uint8_t self_test_execution_status_byte_; //!< @brief Self-test execution status byte + uint16_t vendor_specific0_; //!< @brief Vendor specific + uint8_t vendor_specific1_; //!< @brief Vendor specific + uint8_t off_line_data_collection_capability_; //!< @brief Off-line data collection capability + uint16_t smart_capability_; //!< @brief SMART capability + uint8_t error_logging_capability_; //!< @brief Error logging capability + uint8_t vendor_specific2_; //!< @brief Vendor specific + uint8_t short_self_test_polling_time_; //!< @brief Short self-test polling time (in minutes) + uint8_t extended_self_test_polling_time_; //!< @brief Extended self-test polling time in minutes + uint8_t conveyance_self_test_polling_time_; //!< @brief Conveyance self-test polling time in minutes + uint16_t extended_self_test_polling_time_word_; //!< @brief Extended self-test polling time in minutes (word) + uint8_t reserved_[9]; //!< @brief Reserved + uint8_t vendor_specific3_[125]; //!< @brief Vendor specific + uint8_t data_structure_checksum_; //!< @brief Data structure checksum +} +SMARTData; + +/** + * @brief print usage + */ +void usage(void) +{ + printf("Usage: hdd_reader [options]\n"); + printf(" -h --help : Display help\n"); + printf(" -p --port # : Port number to listen to.\n"); + printf("\n"); +} + +/** + * @brief exchanges the values of 2 bytes + * @param [inout] ptr a pointer to ATA string + * @param [in] size size of ATA string + * @note Each pair of bytes in an ATA string is swapped. + * FIRMWARE REVISION field example + * Word Value + * 23 6162h ("ba") + * 24 6364h ("dc") + * 25 6566h ("fe") + * 26 6720h (" g") + * -> "abcdefg " + */ +void swap_char(char* ptr, size_t size) +{ + for (int i = 0; i < size; i+=2) std::swap(ptr[i], ptr[i+1]); +} + +/** + * @brief get IDENTIFY DEVICE for ATA drive + * @param [in] fd file descriptor to device + * @param [out] info a pointer to HDD information + * @return 0 on success, otherwise error + * @note For details please see the documents below. + * - ATA Command Pass-Through + * https://www.t10.org/ftp/t10/document.04/04-262r8.pdf + * - ATA Command Set - 4 (ACS-4) + * http://www.t13.org/Documents/UploadedDocuments/docs2016/di529r14-ATAATAPI_Command_Set_-_4.pdf + */ +int get_ata_identify(int fd, HDDInfo* info) +{ + sg_io_hdr_t hdr; + ATAPassThrough12 ata; + unsigned char data[512]; // 256 words + + // Create a command descriptor block(CDB) + memset(&ata, 0, sizeof(ata)); + ata.operation_code_ = 0xA1; // ATA PASS-THROUGH (12) command + ata.protool_ = 0x4; // PIO Data-In + ata.t_dir_ = 0x1; // from the ATA device to the application client + ata.byt_blok_ = 0x1; // the number of blocks specified in the T_LENGTH field + ata.t_length_ = 0x2; // length is specified in the SECTOR_COUNT field + ata.sector_count_ = 0x01; // 1 sector + ata.command_ = 0xEC; // IDENTIFY DEVICE + + // Create a control structure + memset(&hdr, 0, sizeof(sg_io_hdr_t)); + hdr.interface_id = 'S'; // This must be set to 'S' + hdr.dxfer_direction = SG_DXFER_FROM_DEV; // a SCSI READ command + hdr.cmd_len = sizeof(ata); // length in bytes of the SCSI command that 'cmdp' points to + hdr.cmdp = (unsigned char*)&ata; // SCSI command to be executed + hdr.dxfer_len = sizeof(data); // number of bytes to be moved in the data transfer + hdr.dxferp = data; // a pointer to user memory + hdr.timeout = 1000; // 1 second + + // send SCSI command to device + if (ioctl(fd, SG_IO, &hdr) < 0) + { + return errno; + } + + // IDENTIFY DEVICE + // Word 10..19 Serial number + char serial_number[20+1] = ""; + strncpy(serial_number, reinterpret_cast(data)+20, 20); + swap_char(serial_number, 20); + info->serial_ = serial_number; + boost::trim(info->serial_); + + // Word 27..46 Model number + char model_number[40+1] = ""; + strncpy(model_number, reinterpret_cast(data)+54, 40); + swap_char(model_number, 40); + info->model_ = model_number; + boost::trim(info->model_); + + return EXIT_SUCCESS; +} + +/** + * @brief get SMART DATA for ATA drive + * @param [in] fd file descriptor to device + * @param [out] info a pointer to HDD information + * @return 0 on success, otherwise error + * @note For details please see the documents below. + * - ATA Command Pass-Through + * https://www.t10.org/ftp/t10/document.04/04-262r8.pdf + * - ATA/ATAPI Command Set - 3 (ACS-3) + * http://www.t13.org/Documents/UploadedDocuments/docs2013/d2161r5-ATAATAPI_Command_Set_-_3.pdf + * - SMART Attribute Overview + * http://www.t13.org/Documents/UploadedDocuments/docs2005/e05171r0-ACS-SMARTAttributes_Overview.pdf + * - SMART Attribute Annex + * http://www.t13.org/documents/uploadeddocuments/docs2005/e05148r0-acs-smartattributesannex.pdf + */ +int get_ata_SMARTData(int fd, HDDInfo* info) +{ + sg_io_hdr_t hdr; + ATAPassThrough12 ata; + SMARTData data; + + // Create a command descriptor block(CDB) + memset(&ata, 0, sizeof(ata)); + ata.operation_code_ = 0xA1; // ATA PASS-THROUGH (12) command + ata.protool_ = 0x4; // PIO Data-In + ata.t_dir_ = 0x1; // from the ATA device to the application client + ata.byt_blok_ = 0x1; // the number of blocks specified in the T_LENGTH field + ata.t_length_ = 0x2; // length is specified in the SECTOR_COUNT field + ata.features_ = 0xD0; // SMART READ DATA + ata.sector_count_ = 0x01; // 1 sector + ata.lba_mid_ = 0x4F; // Fixed + ata.lbe_high_ = 0xC2; // Fixed + ata.command_ = 0xB0; // SMART READ DATA + + // Create a control structure + memset(&hdr, 0, sizeof(sg_io_hdr_t)); + hdr.interface_id = 'S'; // This must be set to 'S' + hdr.dxfer_direction = SG_DXFER_FROM_DEV; // a SCSI READ command + hdr.cmd_len = sizeof(ata); // length in bytes of the SCSI command that 'cmdp' points to + hdr.cmdp = (unsigned char*)&ata; // SCSI command to be executed + hdr.dxfer_len = sizeof(data); // number of bytes to be moved in the data transfer + hdr.dxferp = &data; // a pointer to user memory + hdr.timeout = 1000; // 1 second + + // send SCSI command to device + if (ioctl(fd, SG_IO, &hdr) < 0) + { + return errno; + } + + // Retrieve C2h Enclosure Temperature + for (int i = 0; i < 30; ++i) + { + if (data.attribute_entry_[i].attribute_id_ == 0xC2) + { + info->temp_ = data.attribute_entry_[i].data_; + return EXIT_SUCCESS; + } + } + + return ENOENT; +} + +/** + * @brief get Identify for NVMe drive + * @param [in] fd file descriptor to device + * @param [out] info a pointer to HDD information + * @return 0 on success, otherwise error + * @note For details please see the document below. + * - NVM Express 1.2b + * https://www.nvmexpress.org/wp-content/uploads/NVM_Express_1_2b_Gold_20160603.pdf + */ +int get_nvme_identify(int fd, HDDInfo* info) +{ + nvme_admin_cmd cmd; + char data[4096]; // Fixed size for Identify command + + // The Identify command returns a data buffer that describes information about the NVM subsystem + memset(&cmd, 0, sizeof(cmd)); + cmd.opcode = 0x06; // Identify + cmd.addr = (uint64_t)data; // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x01; // Identify Controller data structure + + // send Admin Command to device + int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd); + if (ret < 0) + { + return errno; + } + + // Identify Controller Data Structure + // Bytes 23:04 Serial Number (SN) + char serial_number[20+1]; + strncpy(serial_number, data+4, 20); + info->serial_ = serial_number; + boost::trim(info->serial_); + + // Bytes 63:24 Model Number (MN) + char model_number[40+1]; + strncpy(model_number, data+24, 40); + info->model_ = model_number; + boost::trim(info->model_); + + return EXIT_SUCCESS; +} + +/** + * @brief get SMART / Health Information for NVMe drive + * @param [in] fd file descriptor to device + * @param [inout] info a pointer to HDD information + * @return 0 on success, otherwise error + * @note For details please see the document below. + * - NVM Express 1.2b + * https://www.nvmexpress.org/wp-content/uploads/NVM_Express_1_2b_Gold_20160603.pdf + */ +int get_nvme_SMARTData(int fd, HDDInfo* info) +{ + nvme_admin_cmd cmd; + char data[4]; // 1 Dword (get byte 0 to 3) + + // The Get Log Page command returns a data buffer containing the log page requested + memset(&cmd, 0, sizeof(cmd)); + cmd.opcode = 0x02; // Get Log Page + cmd.nsid = 0xFFFFFFFF; // Global log page + cmd.addr = (uint64_t)data; // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x00010002; // Bit 27:16 Number of Dwords (NUMD) = 001h (1 Dword) + // - Minimum necessary size to obtain a temperature + // Bit 07:00 = 02h (SMART / Health Information) + + // send Admin Command to device + int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd); + if (ret < 0) + { + return errno; + } + + // Bytes 2:1 Composite Temperature + // Convert kelvin to celsius + unsigned int temperature = ((data[2] << 8) |data[1]) - 273; + info->temp_ = temperature; + + return EXIT_SUCCESS; +} + +/** + * @brief check HDD temperature + * @param [in] port port to listen + * @param [inout] list a pointer to HDD information list + */ +void run(int port, HDDInfoList *list) +{ + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) + { + syslog(LOG_ERR, "Failed to create a new socket. %s\n", strerror(errno)); + return; + } + + // Allow address reuse + int ret = 0; + int opt = 1; + ret = setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast(&opt), (socklen_t) sizeof(opt)); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to set socket FD's option. %s\n", strerror(errno)); + close(sock); + return; + } + + // Give the socket FD the local address ADDR + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(port); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = bind(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to give the socket FD the local address ADDR. %s\n", strerror(errno)); + close(sock); + return; + } + + // Prepare to accept connections on socket FD + ret = listen(sock, 5); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to prepare to accept connections on socket FD. %s\n", strerror(errno)); + close(sock); + return; + } + + sockaddr_in client; + socklen_t len = sizeof(client); + + while (true) + { + // Await a connection on socket FD + int new_sock = accept(sock, reinterpret_cast(&client), &len); + if (new_sock < 0) + { + syslog(LOG_ERR, "Failed to prepare to accept connections on socket FD. %s\n", strerror(errno)); + close(sock); + return; + } + + std::ostringstream oss; + boost::archive::text_oarchive oa(oss); + + for (auto itr = list->begin(); itr != list->end(); ++itr) + { + HDDInfo *info = &itr->second; + + // Open a file + int fd = open(itr->first.c_str(), O_RDONLY); + if (fd < 0) + { + info->error_code_ = errno; + syslog(LOG_ERR, "Failed to open a file. %s\n", strerror(info->error_code_)); + continue; + } + + // AHCI device + if (boost::starts_with(itr->first.c_str(), "/dev/sd")) + { + // Get IDENTIFY DEVICE for ATA drive + info->error_code_ = get_ata_identify(fd, info); + if (info->error_code_ != 0) + { + syslog(LOG_ERR, "Failed to get IDENTIFY DEVICE for ATA drive. %s\n", strerror(info->error_code_)); + close(fd); + continue; + } + // Get SMART DATA for ATA drive + info->error_code_ = get_ata_SMARTData(fd, info); + if (info->error_code_ != 0) + { + syslog(LOG_ERR, "Failed to get SMART LOG for ATA drive. %s\n", strerror(info->error_code_)); + close(fd); + continue; + } + } + // NVMe device + else if (boost::starts_with(itr->first.c_str(), "/dev/nvme")) + { + // Get Identify for NVMe drive + info->error_code_ = get_nvme_identify(fd, info); + if (info->error_code_ != 0) + { + syslog(LOG_ERR, "Failed to get Identify for NVMe drive. %s\n", strerror(info->error_code_)); + close(fd); + continue; + } + // Get SMART / Health Information for NVMe drive + info->error_code_ = get_nvme_SMARTData(fd, info); + if (info->error_code_ != 0) + { + syslog(LOG_ERR, "Failed to get SMART / Health Information for NVMe drive. %s\n", strerror(info->error_code_)); + close(fd); + continue; + } + } + + // Close the file descriptor FD + info->error_code_ = close(fd); + if (info->error_code_ < 0) + { + info->error_code_ = errno; + syslog(LOG_ERR, "Failed to close the file descriptor FD. %s\n", strerror(info->error_code_)); + } + } + + oa << *list; + // Write N bytes of BUF to FD + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to write N bytes of BUF to FD. %s\n", strerror(errno)); + } + + // Close the file descriptor FD + ret = close(new_sock); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to close the file descriptor FD. %s\n", strerror(errno)); + } + } + + close(sock); +} + +int main(int argc, char** argv) +{ + static struct option long_options[] = + { + {"help", no_argument, 0, 'h'}, + {"port", required_argument, 0, 'p'}, + {0, 0, 0, 0} + }; + + // Parse command-line options + int c = 0; + int option_index = 0; + int port = PORT; + while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) + { + switch (c) + { + case 'h': + usage(); + return EXIT_SUCCESS; + + case 'p': + try + { + port = boost::lexical_cast(optarg); + } + catch(const boost::bad_lexical_cast& e) + { + printf("Error: %s\n", e.what()); + return EXIT_FAILURE; + } + break; + + default: + break; + } + } + + HDDInfoList list; + const fs::path root("/dev"); + + for (const fs::path& path : boost::make_iterator_range(fs::directory_iterator(root), fs::directory_iterator())) + { + boost::smatch match; + const boost::regex fsd("sd([a-z]+)"); + const boost::regex fnvme("nvme(\\d+)"); + const std::string dir = path.filename().generic_string(); + + // /dev/sd[a-z] or /dev/nvme[0-9] ? + if (boost::regex_match(dir, match, fsd) || boost::regex_match(dir, match, fnvme)) + { + HDDInfo info = {0}; + list.insert(std::make_pair(path.generic_string(), info)); + } + } + + // Put the program in the background + if (daemon(0, 0) < 0) + { + printf("Failed to put the program in the background. %s\n", strerror(errno)); + return errno; + } + + // Open connection to system logger + openlog(nullptr, LOG_PID, LOG_DAEMON); + + run(port, &list); + + // Close descriptor used to write to system logger + closelog(); + + return EXIT_SUCCESS; +} diff --git a/utilities/system_monitor/reader/msr_reader/msr_reader.cpp b/utilities/system_monitor/reader/msr_reader/msr_reader.cpp new file mode 100644 index 00000000000..4f89aa68e5f --- /dev/null +++ b/utilities/system_monitor/reader/msr_reader/msr_reader.cpp @@ -0,0 +1,303 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file msr_reader.cpp + * @brief MSR read class + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +// 7634-7647 Unassigned +constexpr int PORT = 7634; + +/** + * @brief Package Thermal Status Information + * For details please see the documents below. + * - Intel® 64 and IA-32 ArchitecturesSoftware Developer’s Manual + * https://software.intel.com/sites/default/files/managed/39/c5/325462-sdm-vol-1-2abcd-3abcd.pdf + */ +typedef struct +{ + uint64_t pkg_thermal_status_:1; //!< @brief 0 Pkg Thermal Status (RO) + uint64_t pkg_thermal_status_log_:1; //!< @brief 1 Pkg Thermal Status Log (R/W) + uint64_t pkg_prochot_event_:1; //!< @brief 2 Pkg PROCHOT # event (RO) + uint64_t pkg_prochot_log_:1; //!< @brief 3 Pkg PROCHOT # log (R/WC0) + uint64_t pkg_critical_temperature_status_:1; //!< @brief 4 Pkg Critical Temperature Status (RO) + uint64_t pkg_critical_temperature_status_log_:1; //!< @brief 5 Pkg Critical Temperature Status Log (R/WC0) + uint64_t pkg_thermal_threshold_1_status_:1; //!< @brief 6 Pkg Thermal Threshold #1 Status (RO) + uint64_t pkg_thermal_threshold_1_log_:1; //!< @brief 7 Pkg Thermal Threshold #1 log (R/WC0) + uint64_t pkg_thermal_threshold_2_status_:1; //!< @brief 8 Pkg Thermal Threshold #2 Status (RO) + uint64_t pkg_thermal_threshold_2_log_:1; //!< @brief 9 Pkg Thermal Threshold #2 log (R/WC0) + uint64_t pkg_power_limitation_status_:1; //!< @brief 10 Pkg Power Limitation Status (RO) + uint64_t pkg_power_limitation_log_:1; //!< @brief 11 Pkg Power Limitation log (R/WC0) + uint64_t reserved1_:4; //!< @brief 15:12 Reserved + uint64_t pkg_digital_readout_:7; //!< @brief 22:16 Pkg Digital Readout (RO) + uint64_t reserved2_:41; //!< @brief 63:23 Reserved +} +PackageThermalStatus; + +/** + * @brief print usage + */ +void usage(void) +{ + printf("Usage: msr_reader [options]\n"); + printf(" -h --help : Display help\n"); + printf(" -p --port # : Port number to listen to.\n"); + printf("\n"); +} + +/** + * @brief check CPU thermal throttling + * @param [in] port port to listen + * @param [in] list list of path to msr + */ +void run(int port, const std::vector &list) +{ + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) + { + syslog(LOG_ERR, "Failed to create a new socket. %s\n", strerror(errno)); + return; + } + + // Allow address reuse + int ret = 0; + int opt = 1; + ret = setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast(&opt), (socklen_t) sizeof(opt)); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to set socket FD's option. %s\n", strerror(errno)); + close(sock); + return; + } + + // Give the socket FD the local address ADDR + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(port); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = bind(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to give the socket FD the local address ADDR. %s\n", strerror(errno)); + close(sock); + return; + } + + // Prepare to accept connections on socket FD + ret = listen(sock, 5); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to prepare to accept connections on socket FD. %s\n", strerror(errno)); + close(sock); + return; + } + + sockaddr_in client; + socklen_t len = sizeof(client); + + while (true) + { + // Await a connection on socket FD + int new_sock = accept(sock, reinterpret_cast(&client), &len); + if (new_sock < 0) + { + syslog(LOG_ERR, "Failed to prepare to accept connections on socket FD. %s\n", strerror(errno)); + close(sock); + return; + } + + ret = 0; + std::ostringstream oss; + boost::archive::text_oarchive oa(oss); + MSRInfo msr = {0}; + + for (auto itr = list.begin(); itr != list.end(); ++itr) + { + // Open a file + int fd = open(itr->c_str(), O_RDONLY); + if (fd < 0) + { + msr.error_code_ = errno; + syslog(LOG_ERR, "Failed to open a file. %s\n", strerror(msr.error_code_)); + break; + } + + // Read from a file descriptor + PackageThermalStatus val; + ret = pread(fd, &val, sizeof(uint64_t), 0x1b1); + if (ret < 0) + { + msr.error_code_ = errno; + syslog(LOG_ERR, "Failed to read from a file descriptor. %s\n", strerror(msr.error_code_)); + close(fd); + break; + } + + // Close the file descriptor FD + ret = close(fd); + if (ret < 0) + { + msr.error_code_ = errno; + syslog(LOG_ERR, "Failed to close the file descriptor FD. %s\n", strerror(msr.error_code_)); + break; + } + + msr.pkg_thermal_status_.push_back(val.pkg_thermal_status_); + } + + oa << msr; + // Write N bytes of BUF to FD + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to write N bytes of BUF to FD. %s\n", strerror(errno)); + } + + // Close the file descriptor FD + ret = close(new_sock); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to close the file descriptor FD. %s\n", strerror(errno)); + } + } + + close(sock); +} + +int main(int argc, char** argv) +{ + static struct option long_options[] = + { + {"help", no_argument, 0, 'h'}, + {"port", required_argument, 0, 'p'}, + {0, 0, 0, 0} + }; + + // Parse command-line options + int c = 0; + int option_index = 0; + int port = PORT; + while ((c = getopt_long(argc, argv, "hp:", long_options, &option_index)) != -1) + { + switch (c) + { + case 'h': + usage(); + return EXIT_SUCCESS; + + case 'p': + try + { + port = boost::lexical_cast(optarg); + } + catch(const boost::bad_lexical_cast& e) + { + printf("Error: %s\n", e.what()); + return EXIT_FAILURE; + } + break; + + default: + break; + } + } + + if (!fs::exists("/dev/cpu")) + { + printf("Failed to access /dev/cpu.\n"); + return EXIT_FAILURE; + } + + std::vector list; + const fs::path root("/dev/cpu"); + + for (const fs::path& path : + boost::make_iterator_range(fs::recursive_directory_iterator(root), fs::recursive_directory_iterator())) + { + if (fs::is_directory(path)) continue; + + boost::smatch match; + boost::regex filter(".*msr"); + std::string msr = path.generic_string(); + + // /dev/cpu/[0-9]/msr ? + if (!boost::regex_match(msr, match, filter)) continue; + + list.push_back(path.generic_string()); + } + + std::sort(list.begin(), list.end(), + [](const std::string& c1, const std::string& c2) + { + boost::smatch match; + boost::regex filter(".*/(\\d+)/msr"); + int n1, n2 = 0; + if (boost::regex_match(c1, match, filter)) n1 = std::stoi(match[1].str()); + if (boost::regex_match(c2, match, filter)) n2 = std::stoi(match[1].str()); + return n1 < n2; + } + ); // NOLINT + + if (list.empty()) + { + printf("No msr found in /dev/cpu.\n"); + return EXIT_FAILURE; + } + + // Put the program in the background + if (daemon(0, 0) < 0) + { + printf("Failed to put the program in the background. %s\n", strerror(errno)); + return errno; + } + + // Open connection to system logger + openlog(nullptr, LOG_PID, LOG_DAEMON); + + run(port, list); + + // Close descriptor used to write to system logger + closelog(); + + return EXIT_SUCCESS; +} diff --git a/utilities/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp b/utilities/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp new file mode 100644 index 00000000000..df54ab3d929 --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/arm_cpu_monitor.cpp @@ -0,0 +1,46 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file arm_cpu_monitor.cpp + * @brief ARM CPU monitor class + */ + +#include +#include +#include + +CPUMonitor::CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : CPUMonitorBase(nh, pnh) +{ +} + +void CPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + // TODO(Fumihito Ito): implement me +} + +void CPUMonitor::getTempNames(void) +{ + // Jetson TX1 TX2 Nano: thermal_zone1, Xavier: thermal_zone0 + std::vector therms; + SystemMonitorUtility::getThermalZone("CPU-therm", &therms); + + for (auto itr = therms.begin(); itr != therms.end(); ++itr) + { + temps_.emplace_back(itr->label_, itr->path_); + } +} diff --git a/utilities/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp b/utilities/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp new file mode 100644 index 00000000000..9de0c572d58 --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp @@ -0,0 +1,295 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file cpu_monitor_base.cpp + * @brief CPU monitor base class + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace bp = boost::process; +namespace fs = boost::filesystem; +namespace pt = boost::property_tree; + +CPUMonitorBase::CPUMonitorBase(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh) + , pnh_(pnh) + , updater_() + , hostname_() + , num_cores_(0) + , temps_() + , freqs_() + , mpstat_exists_(false) + , temp_warn_(90.0) + , temp_error_(95.0) + , usage_warn_(0.90) + , usage_error_(1.00) + , load1_warn_(0.90) + , load5_warn_(0.80) +{ + gethostname(hostname_, sizeof(hostname_)); + num_cores_ = boost::thread::hardware_concurrency(); + + // Check if command exists + fs::path p = bp::search_path("mpstat"); + mpstat_exists_ = (p.empty()) ? false : true; + + pnh_.param("temp_warn", temp_warn_, 90.0); + pnh_.param("temp_error", temp_error_, 95.0); + pnh_.param("usage_warn", usage_warn_, 0.90); + pnh_.param("usage_error", usage_error_, 1.00); + pnh_.param("load1_warn", load1_warn_, 0.90); + pnh_.param("load5_warn", load5_warn_, 0.80); + + updater_.setHardwareID(hostname_); + updater_.add("CPU Temperature", this, &CPUMonitorBase::checkTemp); + updater_.add("CPU Usage", this, &CPUMonitorBase::checkUsage); + updater_.add("CPU Load Average", this, &CPUMonitorBase::checkLoad); + updater_.add("CPU Thermal Throttling", this, &CPUMonitorBase::checkThrottling); + updater_.add("CPU Frequency", this, &CPUMonitorBase::checkFrequency); +} + +void CPUMonitorBase::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void CPUMonitorBase::checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (temps_.empty()) + { + stat.summary(DiagStatus::ERROR, "temperature files not found"); + return; + } + + int level = DiagStatus::OK; + std::string error_str = ""; + + for (auto itr = temps_.begin(); itr != temps_.end(); ++itr) + { + // Read temperature file + const fs::path path(itr->path_); + fs::ifstream ifs(path, std::ios::in); + if (!ifs) + { + stat.add("file open error", itr->path_); + error_str = "file open error"; + continue; + } + + float temp; + ifs >> temp; + ifs.close(); + temp /= 1000; + stat.addf(itr->label_, "%.1f DegC", temp); + + level = DiagStatus::OK; + if (temp >= temp_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (temp >= temp_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + } + + if (!error_str.empty()) + stat.summary(DiagStatus::ERROR, error_str); + else + stat.summary(level, temp_dict_.at(level)); +} + +void CPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (!mpstat_exists_) + { + stat.summary(DiagStatus::ERROR, "mpstat error"); + stat.add("mpstat", "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); + return; + } + + // Get CPU Usage + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c("mpstat -P ALL 1 1 -o JSON", bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + + if (c.exit_code() != 0) + { + std::ostringstream os; + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "mpstat error"); + stat.add("mpstat", os.str().c_str()); + return; + } + + std::string cpu_name; + float usr; + float nice; + float sys; + float idle; + float all_usage; + float usage; + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + + pt::ptree pt; + try + { + // Analyze JSON output + read_json(is_out, pt); + + for (const pt::ptree::value_type& child1 : pt.get_child("sysstat.hosts")) + { + const pt::ptree& hosts = child1.second; + + for (const pt::ptree::value_type& child2 : hosts.get_child("statistics")) + { + const pt::ptree& statistics = child2.second; + + for (const pt::ptree::value_type& child3 : statistics.get_child("cpu-load")) + { + const pt::ptree& cpu_load = child3.second; + + if (boost::optional v = cpu_load.get_optional("cpu")) cpu_name = v.get(); + if (boost::optional v = cpu_load.get_optional("usr")) usr = v.get(); + if (boost::optional v = cpu_load.get_optional("nice")) nice = v.get(); + if (boost::optional v = cpu_load.get_optional("sys")) sys = v.get(); + if (boost::optional v = cpu_load.get_optional("idle")) idle = v.get(); + + usage = (usr+nice)*1e-2; + if (cpu_name =="all") all_usage = usage; + + level = DiagStatus::OK; + if (usage >= usage_error_) level = DiagStatus::ERROR; + else if (usage >= usage_warn_) level = DiagStatus::WARN; + + stat.add((boost::format("CPU %1%: status") % cpu_name).str(), load_dict_.at(level)); + stat.addf((boost::format("CPU %1%: usr") % cpu_name).str(), "%.2f%%", usr); + stat.addf((boost::format("CPU %1%: nice") % cpu_name).str(), "%.2f%%", nice); + stat.addf((boost::format("CPU %1%: sys") % cpu_name).str(), "%.2f%%", sys); + stat.addf((boost::format("CPU %1%: idle") % cpu_name).str(), "%.2f%%", idle); + + whole_level = std::max(whole_level, level); + } + } + } + } + catch (const std::exception& e) + { + stat.summary(DiagStatus::ERROR, "mpstat exception"); + stat.add("mpstat", e.what()); + return; + } + + stat.summary(whole_level, load_dict_.at(whole_level)); +} + +void CPUMonitorBase::checkLoad(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + double loadavg[3]; + + if (getloadavg(loadavg, 3) <0) + { + stat.summary(DiagStatus::ERROR, "uptime error"); + stat.add("uptime", strerror(errno)); + return; + } + + loadavg[0] /= num_cores_; + loadavg[1] /= num_cores_; + loadavg[2] /= num_cores_; + + int level = DiagStatus::OK; + if (loadavg[0] > load1_warn_ || loadavg[1] > load5_warn_) level = DiagStatus::WARN; + + stat.summary(level, load_dict_.at(level)); + stat.addf("1min", "%.2f%%", loadavg[0]*1e2); + stat.addf("5min", "%.2f%%", loadavg[1]*1e2); + stat.addf("15min", "%.2f%%", loadavg[2]*1e2); +} + +void CPUMonitorBase::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("CPUMonitorBase::checkThrottling not implemented."); +} + +void CPUMonitorBase::checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (freqs_.empty()) + { + stat.summary(DiagStatus::ERROR, "frequency files not found"); + return; + } + + for (auto itr = freqs_.begin(); itr != freqs_.end(); ++itr) + { + // Read scaling_cur_freq file + const fs::path path(itr->path_); + fs::ifstream ifs(path, std::ios::in); + if (ifs) + { + std::string line; + if (std::getline(ifs, line)) + stat.addf((boost::format("CPU %1%: clock") % itr->index_).str(), "%d MHz", std::stoi(line)/1000); + } + ifs.close(); + } + + stat.summary(DiagStatus::OK, "OK"); +} + +void CPUMonitorBase::getTempNames(void) +{ + ROS_INFO("CPUMonitorBase::getTempNames not implemented."); +} + +void CPUMonitorBase::getFreqNames(void) +{ + const fs::path root("/sys/devices/system/cpu"); + + for (const fs::path& path : boost::make_iterator_range(fs::directory_iterator(root), fs::directory_iterator())) + { + if (!fs::is_directory(path)) continue; + + boost::smatch match; + const boost::regex filter(".*cpu(\\d+)"); + const std::string cpu_dir = path.generic_string(); + + // /sys/devices/system/cpu[0-9] ? + if (!boost::regex_match(cpu_dir, match, filter)) continue; + + // /sys/devices/system/cpu[0-9]/cpufreq/scaling_cur_freq + cpu_freq_info freq; + const fs::path freq_path = path / "cpufreq/scaling_cur_freq"; + freq.index_ = std::stoi(match[1].str()); + freq.path_ = freq_path.generic_string(); + freqs_.push_back(freq); + } + + std::sort(freqs_.begin(), freqs_.end(), + [](const cpu_freq_info &c1, const cpu_freq_info &c2) { return c1.index_ < c2.index_; }); // NOLINT +} diff --git a/utilities/system_monitor/src/cpu_monitor/cpu_monitor_node.cpp b/utilities/system_monitor/src/cpu_monitor/cpu_monitor_node.cpp new file mode 100644 index 00000000000..0ce353079b4 --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/cpu_monitor_node.cpp @@ -0,0 +1,52 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file cpu_monitor_node.cpp + * @brief CPU monitor node class + */ + +#include +#include + +#if defined _CPU_INTEL_ +#include +#elif defined _CPU_ARM_ +#include +#elif defined _CPU_RASPI_ +#include +#elif defined _CPU_TEGRA_ +#include +#else +#include +#endif + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "cpu_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + + std::shared_ptr monitor; + + monitor = std::make_shared(nh, pnh); + + monitor->getTempNames(); + monitor->getFreqNames(); + monitor->run(); + + return 0; +} diff --git a/utilities/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp b/utilities/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp new file mode 100644 index 00000000000..4e552883283 --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/intel_cpu_monitor.cpp @@ -0,0 +1,194 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file _cpu_monitor.cpp + * @brief CPU monitor class + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +CPUMonitor::CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : CPUMonitorBase(nh, pnh) +{ + pnh_.param("msr_reader_port", msr_reader_port_, 7634); +} + +void CPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) + { + stat.summary(DiagStatus::ERROR, "socket error"); + stat.add("socket", strerror(errno)); + return; + } + + // Specify the receiving timeouts until reporting an error + struct timeval tv; + tv.tv_sec = 10; + tv.tv_usec = 0; + int ret = setsockopt(sock, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(tv)); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "setsockopt error"); + stat.add("setsockopt", strerror(errno)); + close(sock); + return; + } + + // Connect the socket referred to by the file descriptor + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(msr_reader_port_); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "connect error"); + stat.add("connect", strerror(errno)); + close(sock); + return; + } + + // Receive messages from a socket + char buf[1024] = ""; + ret = recv(sock, buf, sizeof(buf)-1, 0); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", strerror(errno)); + close(sock); + return; + } + // No data received + if (ret == 0) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", "No data received"); + close(sock); + return; + } + + // Close the file descriptor FD + ret = close(sock); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "close error"); + stat.add("close", strerror(errno)); + return; + } + + // Restore MSR information + MSRInfo info; + + try + { + std::istringstream iss(buf); + boost::archive::text_iarchive oa(iss); + oa >> info; + } + catch (const std::exception& e) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", e.what()); + return; + } + + // msr_reader returns an error + if (info.error_code_ != 0) + { + stat.summary(DiagStatus::ERROR, "msr_reader error"); + stat.add("msr_reader", strerror(info.error_code_)); + return; + } + + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + + for (auto itr = info.pkg_thermal_status_.begin(); itr != info.pkg_thermal_status_.end(); ++itr, ++index) + { + if (*itr) level = DiagStatus::ERROR; + else level = DiagStatus::OK; + + stat.add((boost::format("CPU %1%: Pkg Thermal Status") % index).str(), thermal_dict_.at(level)); + + whole_level = std::max(whole_level, level); + } + + stat.summary(whole_level, thermal_dict_.at(whole_level)); +} + +void CPUMonitor::getTempNames(void) +{ + const fs::path root("/sys/devices/platform"); + + for (const fs::path& path : + boost::make_iterator_range(fs::recursive_directory_iterator(root), fs::recursive_directory_iterator())) + { + if (fs::is_directory(path)) continue; + + boost::smatch match; + boost::regex filter(".*temp(\\d+)_input"); + std::string temp_input = path.generic_string(); + + // /sys/devices/platform/coretemp.[0-9]/hwmon/hwmon[0-9]/temp[0-9]_input ? + if (!boost::regex_match(temp_input, match, filter)) continue; + + cpu_temp_info temp; + temp.path_ = temp_input; + temp.label_ = path.filename().generic_string(); + + std::string label = boost::algorithm::replace_all_copy(temp_input, "input", "label"); + const fs::path label_path(label); + fs::ifstream ifs(label_path, std::ios::in); + if (ifs) + { + std::string line; + if (std::getline(ifs, line)) temp.label_ = line; + } + ifs.close(); + temps_.push_back(temp); + } + + std::sort(temps_.begin(), temps_.end(), + [](const cpu_temp_info& c1, const cpu_temp_info& c2) + { + boost::smatch match; + boost::regex filter(".*temp(\\d+)_input"); + int n1, n2 = 0; + if (boost::regex_match(c1.path_, match, filter)) n1 = std::stoi(match[1].str()); + if (boost::regex_match(c2.path_, match, filter)) n2 = std::stoi(match[1].str()); + return n1 < n2; + } + ); // NOLINT +} diff --git a/utilities/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp b/utilities/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp new file mode 100644 index 00000000000..b06307b1bda --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/raspi_cpu_monitor.cpp @@ -0,0 +1,80 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file raspi_cpu_monitor.cpp + * @brief Raspberry Pi CPU monitor class + */ + +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +CPUMonitor::CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : CPUMonitorBase(nh, pnh) +{ +} + +void CPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + int level = DiagStatus::OK; + std::vector status; + + const fs::path path("/sys/devices/platform/soc/soc:firmware/get_throttled"); + fs::ifstream ifs(path, std::ios::in); + if (!ifs) + { + stat.summary(DiagStatus::ERROR, "file open error"); + stat.add("get_throttled", "file open error"); + return; + } + + int throttled; + ifs >> std::hex >> throttled; + ifs.close(); + + // Consider only thermal throttling as an error + if ((throttled & raspiThermalThrottlingMask) == raspiThermalThrottlingMask) level = DiagStatus::ERROR; + + while (throttled) + { + int flag = throttled & ((~throttled)+1); + throttled ^= flag; + status.push_back(throttledToString(flag)); + } + if (status.empty()) status.emplace_back("All clear"); + + stat.add("status", boost::algorithm::join(status, ", ")); + + stat.summary(level, thermal_dict_.at(level)); +} + +void CPUMonitor::getTempNames(void) +{ + // thermal_zone0 + std::vector therms; + SystemMonitorUtility::getThermalZone("cpu-thermal", &therms); + + for (auto itr = therms.begin(); itr != therms.end(); ++itr) + { + temps_.emplace_back(itr->label_, itr->path_); + } +} diff --git a/utilities/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp b/utilities/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp new file mode 100644 index 00000000000..44cf98918da --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/tegra_cpu_monitor.cpp @@ -0,0 +1,48 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file tegra_cpu_monitor.cpp + * @brief TEGRA PU monitor class + */ + +#include +#include +#include + +CPUMonitor::CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : CPUMonitorBase(nh, pnh) +{ + // There is no event record for thermal throttling. + // Need to manually monitor temperature to figure out if thermal limits crossed or not. + updater_.removeByName("CPU Thermal Throttling"); +} + +void CPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ +} + +void CPUMonitor::getTempNames(void) +{ + // Jetson TX1 TX2 Nano: thermal_zone1, Xavier: thermal_zone0 + std::vector therms; + SystemMonitorUtility::getThermalZone("CPU-therm", &therms); + + for (auto itr = therms.begin(); itr != therms.end(); ++itr) + { + temps_.emplace_back(itr->label_, itr->path_); + } +} diff --git a/utilities/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp b/utilities/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp new file mode 100644 index 00000000000..a6efa968343 --- /dev/null +++ b/utilities/system_monitor/src/cpu_monitor/unknown_cpu_monitor.cpp @@ -0,0 +1,27 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file unknown_cpu_monitor.cpp + * @brief Unknown CPU monitor class + */ + +#include + +CPUMonitor::CPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : CPUMonitorBase(nh, pnh) +{ +} diff --git a/utilities/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp b/utilities/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp new file mode 100644 index 00000000000..1606dbc1eb8 --- /dev/null +++ b/utilities/system_monitor/src/gpu_monitor/gpu_monitor_base.cpp @@ -0,0 +1,88 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file nvml_gpu_monitor.cpp + * @brief GPU monitor class + */ + +#include + +GPUMonitorBase::GPUMonitorBase(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh) + , pnh_(pnh) + , updater_() + , hostname_() + , temp_warn_(90.0) + , temp_error_(95.0) + , gpu_usage_warn_(0.90) + , gpu_usage_error_(1.00) + , memory_usage_warn_(0.95) + , memory_usage_error_(0.99) +{ + gethostname(hostname_, sizeof(hostname_)); + + pnh_.param("temp_warn", temp_warn_, 90.0); + pnh_.param("temp_error", temp_error_, 95.0); + pnh_.param("gpu_usage_warn", gpu_usage_warn_, 0.90); + pnh_.param("gpu_usage_error", gpu_usage_error_, 1.00); + pnh_.param("memory_usage_warn", memory_usage_warn_, 0.95); + pnh_.param("memory_usage_error", memory_usage_error_, 0.99); + + updater_.setHardwareID(hostname_); + updater_.add("GPU Temperature", this, &GPUMonitorBase::checkTemp); + updater_.add("GPU Usage", this, &GPUMonitorBase::checkUsage); + updater_.add("GPU Memory Usage", this, &GPUMonitorBase::checkMemoryUsage); + updater_.add("GPU Thermal Throttling", this, &GPUMonitorBase::checkThrottling); + updater_.add("GPU Frequency", this, &GPUMonitorBase::checkFrequency); +} + +void GPUMonitorBase::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void GPUMonitorBase::checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("GPUMonitorBase::checkTemp not implemented."); +} + +void GPUMonitorBase::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("GPUMonitorBase::checkUsage not implemented."); +} + +void GPUMonitorBase::checkMemoryUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("GPUMonitorBase::checkMemoryUsage not implemented."); +} + +void GPUMonitorBase::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("GPUMonitorBase::checkThrottling not implemented."); +} + +void GPUMonitorBase::checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + ROS_INFO("GPUMonitorBase::checkFrequency not implemented."); +} diff --git a/utilities/system_monitor/src/gpu_monitor/gpu_monitor_node.cpp b/utilities/system_monitor/src/gpu_monitor/gpu_monitor_node.cpp new file mode 100644 index 00000000000..174e1301d34 --- /dev/null +++ b/utilities/system_monitor/src/gpu_monitor/gpu_monitor_node.cpp @@ -0,0 +1,46 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file gpu_monitor_node.cpp + * @brief GPU monitor node class + */ + +#include +#include + +#if defined _GPU_NVML_ +#include +#elif defined _GPU_TEGRA_ +#include +#else +#include +#endif + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "gpu_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + + std::shared_ptr monitor; + + monitor = std::make_shared(nh, pnh); + + monitor->run(); + + return 0; +} diff --git a/utilities/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp b/utilities/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp new file mode 100644 index 00000000000..7c08d12429e --- /dev/null +++ b/utilities/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp @@ -0,0 +1,277 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file nvml_gpu_monitor.cpp + * @brief GPU monitor class + */ + +#include +#include +#include +#include +#include +#include + +GPUMonitor::GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : GPUMonitorBase(nh, pnh) +{ + // Include frequency into GPU Thermal Throttling thus remove. + updater_.removeByName("GPU Frequency"); + + nvmlReturn_t ret; + + ret = nvmlInit(); + if (ret != NVML_SUCCESS) ROS_ERROR("Failed to initialize NVML: %s\n", nvmlErrorString(ret)); + + unsigned int deviceCount = 0; + ret = nvmlDeviceGetCount(&deviceCount); + if (ret != NVML_SUCCESS) ROS_ERROR("Failed to retrieve the number of compute devices: %s", nvmlErrorString(ret)); + + for (int index = 0; index < deviceCount; ++index) + { + gpu_info info; + ret = nvmlDeviceGetHandleByIndex(index, &info.device); + if (ret != NVML_SUCCESS) + { + ROS_ERROR("Failed to acquire the handle for a particular device [%d]: %s", index, nvmlErrorString(ret)); + continue; + } + ret = nvmlDeviceGetName(info.device, info.name, NVML_DEVICE_NAME_BUFFER_SIZE); + if (ret != NVML_SUCCESS) + { + ROS_ERROR("Failed to retrieve the name of this device [%d]: %s", index, nvmlErrorString(ret)); + continue; + } + ret = nvmlDeviceGetPciInfo(info.device, &info.pci); + if (ret != NVML_SUCCESS) + { + ROS_ERROR("Failed to retrieve the PCI attributes [%d]: %s", index, nvmlErrorString(ret)); + continue; + } + gpus_.push_back(info); + } +} + +void GPUMonitor::run(void) +{ + GPUMonitorBase::run(); + + nvmlReturn_t ret = nvmlShutdown(); + if (ret != NVML_SUCCESS) ROS_ERROR("Failed to shut down NVML: %s", nvmlErrorString(ret)); +} + +void GPUMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + int level = DiagStatus::OK; + int index = 0; + nvmlReturn_t ret; + + if (gpus_.empty()) + { + stat.summary(DiagStatus::ERROR, "gpu not found"); + return; + } + + for (auto itr = gpus_.begin(); itr != gpus_.end(); ++itr, ++index) + { + unsigned int temp = 0; + ret = nvmlDeviceGetTemperature(itr->device, NVML_TEMPERATURE_GPU, &temp); + if (ret != NVML_SUCCESS) + { + stat.summary(DiagStatus::ERROR, "Failed to retrieve the current temperature"); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.add((boost::format("GPU %1%: bus-id") % index).str(), itr->pci.busId); + stat.add((boost::format("GPU %1%: content") % index).str(), nvmlErrorString(ret)); + return; + } + + level = DiagStatus::OK; + stat.addf(itr->name, "%d.0 DegC", temp); + if (temp >= temp_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (temp >= temp_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + } + + stat.summary(level, temp_dict_.at(level)); +} + +void GPUMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + nvmlReturn_t ret; + + if (gpus_.empty()) + { + stat.summary(DiagStatus::ERROR, "gpu not found"); + return; + } + + for (auto itr = gpus_.begin(); itr != gpus_.end(); ++itr, ++index) + { + ret = nvmlDeviceGetUtilizationRates(itr->device, &itr->utilization); + if (ret != NVML_SUCCESS) + { + stat.summary(DiagStatus::ERROR, "Failed to retrieve the current utilization rates"); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.add((boost::format("GPU %1%: bus-id") % index).str(), itr->pci.busId); + stat.add((boost::format("GPU %1%: content") % index).str(), nvmlErrorString(ret)); + return; + } + + level = DiagStatus::OK; + float usage = static_cast(itr->utilization.gpu) / 100.0; + if (usage >= gpu_usage_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (usage >= gpu_usage_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + + stat.add((boost::format("GPU %1%: status") % index).str(), load_dict_.at(level)); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.addf((boost::format("GPU %1%: usage") % index).str(), "%d.0%%", itr->utilization.gpu); + + whole_level = std::max(whole_level, level); + } + + stat.summary(whole_level, load_dict_.at(whole_level)); +} + +void GPUMonitor::checkMemoryUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + nvmlReturn_t ret; + + if (gpus_.empty()) + { + stat.summary(DiagStatus::ERROR, "gpu not found"); + return; + } + + for (auto itr = gpus_.begin(); itr != gpus_.end(); ++itr, ++index) + { + nvmlMemory_t memory; + ret = nvmlDeviceGetMemoryInfo(itr->device, &memory); + if (ret != NVML_SUCCESS) + { + stat.summary(DiagStatus::ERROR, "Failed to retrieve the amount of used, free and total memory"); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.add((boost::format("GPU %1%: bus-id") % index).str(), itr->pci.busId); + stat.add((boost::format("GPU %1%: content") % index).str(), nvmlErrorString(ret)); + return; + } + + level = DiagStatus::OK; + float usage = static_cast(itr->utilization.memory) / 100.0; + if (usage >= memory_usage_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (usage >= memory_usage_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + + stat.add((boost::format("GPU %1%: status") % index).str(), load_dict_.at(level)); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.addf((boost::format("GPU %1%: usage") % index).str(), "%d.0%%", itr->utilization.memory); + stat.add((boost::format("GPU %1%: total") % index).str(), toHumanReadable(memory.total)); + stat.add((boost::format("GPU %1%: used") % index).str(), toHumanReadable(memory.used)); + stat.add((boost::format("GPU %1%: free") % index).str(), toHumanReadable(memory.free)); + + whole_level = std::max(whole_level, level); + } + + stat.summary(whole_level, load_dict_.at(whole_level)); +} + +void GPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + nvmlReturn_t ret; + std::vector reasons; + + if (gpus_.empty()) + { + stat.summary(DiagStatus::ERROR, "gpu not found"); + return; + } + + for (auto itr = gpus_.begin(); itr != gpus_.end(); ++itr, ++index) + { + unsigned int clock = 0; + ret = nvmlDeviceGetClockInfo(itr->device, NVML_CLOCK_GRAPHICS, &clock); + if (ret != NVML_SUCCESS) + { + stat.summary(DiagStatus::ERROR, "Failed to retrieve the current clock speeds"); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.add((boost::format("GPU %1%: bus-id") % index).str(), itr->pci.busId); + stat.add((boost::format("GPU %1%: content") % index).str(), nvmlErrorString(ret)); + return; + } + + unsigned long long clocksThrottleReasons = 0LL; // NOLINT + ret = nvmlDeviceGetCurrentClocksThrottleReasons(itr->device, &clocksThrottleReasons); + if (ret != NVML_SUCCESS) + { + stat.summary(DiagStatus::ERROR, "Failed to retrieve current clocks throttling reasons"); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.add((boost::format("GPU %1%: bus-id") % index).str(), itr->pci.busId); + stat.add((boost::format("GPU %1%: content") % index).str(), nvmlErrorString(ret)); + return; + } + + while (clocksThrottleReasons) + { + unsigned long long flag = clocksThrottleReasons & ((~clocksThrottleReasons)+1); // NOLINT + clocksThrottleReasons ^= flag; + reasons.push_back(reasonToString(flag)); + + switch (flag) + { + case nvmlClocksThrottleReasonGpuIdle: + case nvmlClocksThrottleReasonApplicationsClocksSetting: + // we do not treat as error + break; + default: + level = DiagStatus::ERROR; + break; + } + } + + stat.add((boost::format("GPU %1%: status") % index).str(), throttling_dict_.at(level)); + stat.add((boost::format("GPU %1%: name") % index).str(), itr->name); + stat.addf((boost::format("GPU %1%: graphics clock") % index).str(), "%d MHz", clock); + + if (reasons.empty()) reasons.emplace_back("ReasonNone"); + + stat.add((boost::format("GPU %1%: reasons") % index).str(), boost::algorithm::join(reasons, ", ")); + + whole_level = std::max(whole_level, level); + } + + stat.summary(whole_level, throttling_dict_.at(whole_level)); +} + +std::string GPUMonitor::toHumanReadable(unsigned long long size) // NOLINT +{ + const char* units[] = {"B", "K", "M", "G", "T"}; + int count = 0; + + while (size > 1024) + { + size /= 1024; + ++count; + } + const char* format = (size > 0 && size < 10) ? "%.1f%s" : "%.0f%s"; + return (boost::format(format) % size % units[count]).str(); +} diff --git a/utilities/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp b/utilities/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp new file mode 100644 index 00000000000..d0d34db7571 --- /dev/null +++ b/utilities/system_monitor/src/gpu_monitor/tegra_gpu_monitor.cpp @@ -0,0 +1,201 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file tegra_gpu_monitor.cpp + * @brief Tegra GPU monitor class + */ + +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; + +GPUMonitor::GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : GPUMonitorBase(nh, pnh) +{ + getTempNames(); + getLoadNames(); + getFreqNames(); + + // There is no separate gpu memory in tegra. Both cpu and gpu uses cpu memory. thus remove. + updater_.removeByName("GPU Memory Usage"); + // There is no event record for thermal throttling. + // Need to manually monitor temperature to figure out if thermal limits crossed or not. + updater_.removeByName("GPU Thermal Throttling"); +} + +void GPUMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (temps_.empty()) + { + stat.summary(DiagStatus::ERROR, "temperature files not found"); + return; + } + + int level = DiagStatus::OK; + std::string error_str = ""; + + for (auto itr = temps_.begin(); itr != temps_.end(); ++itr) + { + // Read temperature file + const fs::path path(itr->path_); + fs::ifstream ifs(path, std::ios::in); + if (!ifs) + { + stat.add("file open error", itr->path_); + error_str = "file open error"; + continue; + } + + float temp; + ifs >> temp; + ifs.close(); + temp /= 1000; + stat.addf(itr->label_, "%.1f DegC", temp); + + level = DiagStatus::OK; + if (temp >= temp_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (temp >= temp_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + } + + if (!error_str.empty()) + stat.summary(DiagStatus::ERROR, error_str); + else + stat.summary(level, temp_dict_.at(level)); +} + +void GPUMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (loads_.empty()) + { + stat.summary(DiagStatus::ERROR, "load files not found"); + return; + } + + int level = DiagStatus::OK; + std::string error_str = ""; + + for (auto itr = loads_.begin(); itr != loads_.end(); ++itr) + { + // Read load file + const fs::path path(itr->path_); + fs::ifstream ifs(path, std::ios::in); + if (!ifs) + { + stat.add("file open error", itr->path_); + error_str = "file open error"; + continue; + } + + float load; + ifs >> load; + ifs.close(); + stat.addf(itr->label_, "%.1f%%", load / 10); + + level = DiagStatus::OK; + load /= 1000; + if (load >= gpu_usage_error_) level = std::max(level, static_cast(DiagStatus::ERROR)); + else if (load >= gpu_usage_warn_) level = std::max(level, static_cast(DiagStatus::WARN)); + } + + if (!error_str.empty()) + stat.summary(DiagStatus::ERROR, error_str); + else + stat.summary(level, load_dict_.at(level)); +} + +void GPUMonitor::checkThrottling(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + // TODO(Fumihito Ito): implement me +} + +void GPUMonitor::checkFrequency(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (freqs_.empty()) + { + stat.summary(DiagStatus::ERROR, "frequency files not found"); + return; + } + + for (auto itr = freqs_.begin(); itr != freqs_.end(); ++itr) + { + // Read cur_freq file + const fs::path path(itr->path_); + fs::ifstream ifs(path, std::ios::in); + if (ifs) + { + std::string line; + if (std::getline(ifs, line)) + stat.addf((boost::format("GPU %1%: clock") % itr->label_).str(), "%d MHz", std::stoi(line)/1000000); + } + ifs.close(); + } + + stat.summary(DiagStatus::OK, "OK"); +} + +void GPUMonitor::getTempNames(void) +{ + // Jetson TX1 TX2 Nano: thermal_zone1, Xavier: thermal_zone0 + std::vector therms; + SystemMonitorUtility::getThermalZone("GPU-therm", &therms); + + for (auto itr = therms.begin(); itr != therms.end(); ++itr) + { + temps_.emplace_back(itr->label_, itr->path_); + } +} + +void GPUMonitor::getLoadNames(void) +{ + const fs::path root("/sys/devices"); + + for (const fs::path& path : boost::make_iterator_range(fs::directory_iterator(root), fs::directory_iterator())) + { + if (!fs::is_directory(path)) continue; + + boost::smatch match; + const boost::regex filter(".*gpu\\.(\\d+)"); + const std::string str_path = path.generic_string(); + + // /sys/devices/gpu.[0-9] ? + if (!boost::regex_match(str_path, match, filter)) continue; + + // /sys/devices/gpu.[0-9]/load + const fs::path load_path = path / "load"; + loads_.emplace_back(path.filename().generic_string(), load_path.generic_string()); + } +} + +void GPUMonitor::getFreqNames(void) +{ + const fs::path root("/sys/class/devfreq"); + + for (const fs::path& path : boost::make_iterator_range(fs::directory_iterator(root), fs::directory_iterator())) + { + // /sys/class/devfreq/?????/cur_freq ? + if (!fs::is_directory(path)) continue; + + const fs::path freq_path = path / "cur_freq"; + freqs_.emplace_back(path.filename().generic_string(), freq_path.generic_string()); + } +} diff --git a/utilities/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp b/utilities/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp new file mode 100644 index 00000000000..3fe675a442c --- /dev/null +++ b/utilities/system_monitor/src/gpu_monitor/unknown_gpu_monitor.cpp @@ -0,0 +1,27 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file unknown_gpu_monitor.cpp + * @brief Unknown GPU monitor class + */ + +#include + +GPUMonitor::GPUMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : GPUMonitorBase(nh, pnh) +{ +} diff --git a/utilities/system_monitor/src/hdd_monitor/hdd_monitor.cpp b/utilities/system_monitor/src/hdd_monitor/hdd_monitor.cpp new file mode 100644 index 00000000000..bb63199daeb --- /dev/null +++ b/utilities/system_monitor/src/hdd_monitor/hdd_monitor.cpp @@ -0,0 +1,280 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file hdd_monitor.cpp + * @brief HDD monitor class + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace bp = boost::process; + +HDDMonitor::HDDMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh), pnh_(pnh) +{ + gethostname(hostname_, sizeof(hostname_)); + + getTempParams(); + pnh_.param("usage_warn", usage_warn_, 0.9); + pnh_.param("usage_error", usage_error_, 1.1); + pnh_.param("hdd_reader_port", hdd_reader_port_, 7635); + + updater_.setHardwareID(hostname_); + updater_.add("HDD Temperature", this, &HDDMonitor::checkTemp); + updater_.add("HDD Usage", this, &HDDMonitor::checkUsage); +} + +void HDDMonitor::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void HDDMonitor::checkTemp(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (temp_params_.empty()) + { + stat.summary(DiagStatus::ERROR, "invalid disk parameter"); + return; + } + + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) + { + stat.summary(DiagStatus::ERROR, "socket error"); + stat.add("socket", strerror(errno)); + return; + } + + // Specify the receiving timeouts until reporting an error + struct timeval tv; + tv.tv_sec = 10; + tv.tv_usec = 0; + int ret = setsockopt(sock, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(tv)); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "setsockopt error"); + stat.add("setsockopt", strerror(errno)); + close(sock); + return; + } + + // Connect the socket referred to by the file descriptor + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(hdd_reader_port_); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "connect error"); + stat.add("connect", strerror(errno)); + close(sock); + return; + } + + // Receive messages from a socket + char buf[1024] = ""; + ret = recv(sock, buf, sizeof(buf)-1, 0); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", strerror(errno)); + close(sock); + return; + } + // No data received + if (ret == 0) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", "No data received"); + close(sock); + return; + } + + // Close the file descriptor FD + ret = close(sock); + if (ret < 0) + { + stat.summary(DiagStatus::ERROR, "close error"); + stat.add("close", strerror(errno)); + return; + } + + // Restore HDD information list + HDDInfoList list; + + try + { + std::istringstream iss(buf); + boost::archive::text_iarchive oa(iss); + oa >> list; + } + catch (const std::exception& e) + { + stat.summary(DiagStatus::ERROR, "recv error"); + stat.add("recv", e.what()); + return; + } + + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + std::string error_str = ""; + + for (auto itr = temp_params_.begin(); itr != temp_params_.end(); ++itr, ++index) + { + // Retrieve HDD information + auto itrh = list.find(itr->first); + if (itrh == list.end()) + { + stat.add((boost::format("HDD %1%: status") % index).str(), "hdd_reader error"); + stat.add((boost::format("HDD %1%: name") % index).str(), itr->first.c_str()); + stat.add((boost::format("HDD %1%: hdd_reader") % index).str(), strerror(ENOENT)); + error_str = "hdd_reader error"; + continue; + } + + if (itrh->second.error_code_ != 0) + { + stat.add((boost::format("HDD %1%: status") % index).str(), "hdd_reader error"); + stat.add((boost::format("HDD %1%: name") % index).str(), itr->first.c_str()); + stat.add((boost::format("HDD %1%: hdd_reader") % index).str(), strerror(itrh->second.error_code_)); + error_str = "hdd_reader error"; + continue; + } + + float temp = static_cast(itrh->second.temp_); + + level = DiagStatus::OK; + if (temp >= itr->second.temp_error_) level = DiagStatus::ERROR; + else if (temp >= itr->second.temp_warn_) level = DiagStatus::WARN; + + stat.add((boost::format("HDD %1%: status") % index).str(), temp_dict_.at(level)); + stat.add((boost::format("HDD %1%: name") % index).str(), itr->first.c_str()); + stat.add((boost::format("HDD %1%: model") % index).str(), itrh->second.model_.c_str()); + stat.add((boost::format("HDD %1%: serial") % index).str(), itrh->second.serial_.c_str()); + stat.addf((boost::format("HDD %1%: temperature") % index).str(), "%.1f DegC", temp); + + whole_level = std::max(whole_level, level); + } + + if (!error_str.empty()) + stat.summary(DiagStatus::ERROR, error_str); + else + stat.summary(whole_level, temp_dict_.at(whole_level)); +} + +void HDDMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + // Get summary of disk space usage of ext4 + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c("df -Pht ext4", bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + std::ostringstream os; + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "df error"); + stat.add("df", os.str().c_str()); + return; + } + + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + + std::string line; + int index = 0; + std::vector list; + float usage; + + while (std::getline(is_out, line) && !line.empty()) + { + // Skip header + if ( index <= 0 ) + { + ++index; + continue; + } + + boost::split(list, line, boost::is_space(), boost::token_compress_on); + + usage = std::atof(boost::trim_copy_if(list[4], boost::is_any_of("%")).c_str())*1e-2; + + level = DiagStatus::OK; + if (usage >= usage_error_) level = DiagStatus::ERROR; + else if (usage >= usage_warn_) level = DiagStatus::WARN; + + stat.add((boost::format("HDD %1%: status") % (index-1)).str(), usage_dict_.at(level)); + stat.add((boost::format("HDD %1%: filesystem") % (index-1)).str(), list[0].c_str()); + stat.add((boost::format("HDD %1%: size") % (index-1)).str(), list[1].c_str()); + stat.add((boost::format("HDD %1%: used") % (index-1)).str(), list[2].c_str()); + stat.add((boost::format("HDD %1%: avail") % (index-1)).str(), list[3].c_str()); + stat.add((boost::format("HDD %1%: use") % (index-1)).str(), list[4].c_str()); + stat.add((boost::format("HDD %1%: mounted on") % (index-1)).str(), list[5].c_str()); + + whole_level = std::max(whole_level, level); + ++index; + } + + stat.summary(whole_level, usage_dict_.at(whole_level)); +} + +void HDDMonitor::getTempParams(void) +{ + XmlRpc::XmlRpcValue params; + + pnh_.getParam("disks", params); + if (params.getType() != XmlRpc::XmlRpcValue::TypeArray) return; + + for (int i = 0; i < params.size(); ++i) + { + std::string name; + TempParam param; + + // Skip no name + if (!params[i]["name"].valid()) continue; + + if (params[i]["name"].getType() == XmlRpc::XmlRpcValue::TypeString) + name = static_cast(params[i]["name"]); + + if (params[i]["temp_warn"].getType() == XmlRpc::XmlRpcValue::TypeDouble) + param.temp_warn_ = static_cast(params[i]["temp_warn"]); + + if (params[i]["temp_error"].getType() == XmlRpc::XmlRpcValue::TypeDouble) + param.temp_error_ = static_cast(params[i]["temp_error"]); + + temp_params_[name] = param; + } +} diff --git a/utilities/system_monitor/src/hdd_monitor/hdd_monitor_node.cpp b/utilities/system_monitor/src/hdd_monitor/hdd_monitor_node.cpp new file mode 100644 index 00000000000..ade059a9c31 --- /dev/null +++ b/utilities/system_monitor/src/hdd_monitor/hdd_monitor_node.cpp @@ -0,0 +1,33 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file hdd_monitor_node.cpp + * @brief HDD monitor node class + */ + +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "hdd_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + HDDMonitor monitor(nh, pnh); + monitor.run(); + + return 0; +} diff --git a/utilities/system_monitor/src/mem_monitor/mem_monitor.cpp b/utilities/system_monitor/src/mem_monitor/mem_monitor.cpp new file mode 100644 index 00000000000..b8103ad0919 --- /dev/null +++ b/utilities/system_monitor/src/mem_monitor/mem_monitor.cpp @@ -0,0 +1,122 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file memory_monitor.cpp + * @brief Memory monitor class + */ + +#include +#include +#include +#include +#include + +namespace bp = boost::process; + +MemMonitor::MemMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh), pnh_(pnh) +{ + gethostname(hostname_, sizeof(hostname_)); + + pnh_.param("usage_warn", usage_warn_, 0.95); + pnh_.param("usage_error", usage_error_, 0.99); + + updater_.setHardwareID(hostname_); + updater_.add("Memory Usage", this, &MemMonitor::checkUsage); +} + +void MemMonitor::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void MemMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + // Get total amount of free and used memory + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c("free -tb", bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + std::ostringstream os; + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "free error"); + stat.add("free", os.str().c_str()); + return; + } + + int level = DiagStatus::OK; + std::string line; + int index = 0; + std::vector list; + float usage; + + while (std::getline(is_out, line) && !line.empty()) + { + // Skip header + if ( index <= 0 ) + { + ++index; + continue; + } + + boost::split(list, line, boost::is_space(), boost::token_compress_on); + + // Physical memory + if (index == 1) + { + // used divided by total is usage + usage = std::atof(list[2].c_str()) / std::atof(list[1].c_str()); + + if (usage >= usage_error_) level = DiagStatus::ERROR; + else if (usage >= usage_warn_) level = DiagStatus::WARN; + + stat.addf((boost::format("%1% usage") % list[0]).str(), "%.2f%%", usage*1e+2); + } + + stat.add((boost::format("%1% total") % list[0]).str(), toHumanReadable(list[1])); + stat.add((boost::format("%1% used") % list[0]).str(), toHumanReadable(list[2])); + stat.add((boost::format("%1% free") % list[0]).str(), toHumanReadable(list[3])); + + ++index; + } + + stat.summary(level, usage_dict_.at(level)); +} + +std::string MemMonitor::toHumanReadable(const std::string &str) +{ + const char* units[] = {"B", "K", "M", "G", "T"}; + int count = 0; + double size = std::atol(str.c_str()); + + while (size > 1024) + { + size /= 1024; + ++count; + } + const char* format = (size > 0 && size < 10) ? "%.1f%s" : "%.0f%s"; + return (boost::format(format) % size % units[count]).str(); +} diff --git a/utilities/system_monitor/src/mem_monitor/mem_monitor_node.cpp b/utilities/system_monitor/src/mem_monitor/mem_monitor_node.cpp new file mode 100644 index 00000000000..8f87c5b78d3 --- /dev/null +++ b/utilities/system_monitor/src/mem_monitor/mem_monitor_node.cpp @@ -0,0 +1,33 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file mem_monitor_node.cpp + * @brief Memory monitor node class + */ + +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "mem_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + MemMonitor monitor(nh, pnh); + monitor.run(); + + return 0; +} diff --git a/utilities/system_monitor/src/net_monitor/net_monitor.cpp b/utilities/system_monitor/src/net_monitor/net_monitor.cpp new file mode 100644 index 00000000000..6a6ef460004 --- /dev/null +++ b/utilities/system_monitor/src/net_monitor/net_monitor.cpp @@ -0,0 +1,190 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file net_monitor.cpp + * @brief Net monitor class + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +NetMonitor::NetMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh), pnh_(pnh) +{ + gethostname(hostname_, sizeof(hostname_)); + + pnh_.getParam("devices", device_params_); + pnh_.param("usage_warn", usage_warn_, 0.95); + + updater_.setHardwareID(hostname_); + updater_.add("Network Usage", this, &NetMonitor::checkUsage); + + nl80211_.init(); +} + +void NetMonitor::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } + + nl80211_.shutdown(); +} + +void NetMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (device_params_.empty()) + { + stat.summary(DiagStatus::ERROR, "invalid device parameter"); + return; + } + + const struct ifaddrs *ifa; + struct ifaddrs *ifas = nullptr; + + ros::Duration duration = ros::Time::now() - last_update_time_; + + // Get network interfaces + if (getifaddrs(&ifas) < 0) + { + stat.summary(DiagStatus::ERROR, "getifaddrs error"); + stat.add("getifaddrs", strerror(errno)); + return; + } + + int level = DiagStatus::OK; + int whole_level = DiagStatus::OK; + int index = 0; + std::string error_str = ""; + float rx_traffic; + float tx_traffic; + float rx_usage; + float tx_usage; + + for (ifa = ifas ; ifa ; ifa = ifa->ifa_next) + { + // Skip no addr + if (!ifa->ifa_addr) continue; + // Skip loopback + if (ifa->ifa_flags & IFF_LOOPBACK) continue; + // Skip non AF_PACKET + if (ifa->ifa_addr->sa_family != AF_PACKET) continue; + // Skip device not specified + if (boost::find(device_params_, ifa->ifa_name) == device_params_.end() && + boost::find(device_params_, "*") == device_params_.end() ) continue; + + int fd; + struct ifreq ifrm; + struct ifreq ifrc; + struct ethtool_cmd edata; + + // Get MTU information + fd = socket(AF_INET, SOCK_DGRAM, 0); + strncpy(ifrm.ifr_name, ifa->ifa_name, IFNAMSIZ-1); + if (ioctl(fd, SIOCGIFMTU, &ifrm) < 0) + { + stat.add((boost::format("Network %1%: status") % index).str(), usage_dict_.at(level)); + stat.add((boost::format("Network %1%: interface name") % index).str(), ifa->ifa_name); + stat.add("ioctl(SIOCGIFMTU)", strerror(errno)); + error_str = "ioctl error"; + ++index; + continue; + } + + // Get network capacity + float speed = 0.0; + strncpy(ifrc.ifr_name, ifa->ifa_name, IFNAMSIZ-1); + ifrc.ifr_data = (caddr_t)&edata; + edata.cmd = ETHTOOL_GSET; + if (ioctl(fd, SIOCETHTOOL, &ifrc) < 0) + { + // possibly wireless connection, get bitrate(MBit/s) and convert to B/s + speed = nl80211_.getBitrate(ifa->ifa_name) / 8; + if (speed <= 0) + { + stat.add((boost::format("Network %1%: status") % index).str(), usage_dict_.at(level)); + stat.add((boost::format("Network %1%: interface name") % index).str(), ifa->ifa_name); + stat.add("ioctl(SIOCETHTOOL)", strerror(errno)); + error_str = "ioctl error"; + ++index; + continue; + } + } + else + { + speed = edata.speed; + } + + level = (ifa->ifa_flags & IFF_RUNNING) ? DiagStatus::OK : DiagStatus::ERROR; + + struct rtnl_link_stats *stats = (struct rtnl_link_stats*)ifa->ifa_data; + if (bytes_.find(ifa->ifa_name) != bytes_.end()) + { + rx_traffic = toMbit(stats->rx_bytes - bytes_[ifa->ifa_name].rx_bytes) / duration.toSec(); + tx_traffic = toMbit(stats->tx_bytes - bytes_[ifa->ifa_name].tx_bytes) / duration.toSec(); + rx_usage = rx_traffic / speed * 1e+2; + tx_usage = tx_traffic / speed * 1e+2; + if (rx_usage >= usage_warn_ || tx_usage > usage_warn_) + level = std::max(level, static_cast(DiagStatus::WARN)); + } + + stat.add((boost::format("Network %1%: status") % index).str(), usage_dict_.at(level)); + stat.add((boost::format("Network %1%: interface name") % index).str(), ifa->ifa_name); + stat.addf((boost::format("Network %1%: rx_usage") % index).str(), "%.2f%%", rx_usage); + stat.addf((boost::format("Network %1%: tx_usage") % index).str(), "%.2f%%", tx_usage); + stat.addf((boost::format("Network %1%: rx_traffic") % index).str(), "%.2f MB/s", rx_traffic); + stat.addf((boost::format("Network %1%: tx_traffic") % index).str(), "%.2f MB/s", tx_traffic); + stat.addf((boost::format("Network %1%: capacity") % index).str(), "%.1f MB/s", speed); + stat.add((boost::format("Network %1%: mtu") % index).str(), ifrm.ifr_mtu); + stat.add((boost::format("Network %1%: rx_bytes") % index).str(), stats->rx_bytes); + stat.add((boost::format("Network %1%: rx_errors") % index).str(), stats->rx_errors); + stat.add((boost::format("Network %1%: tx_bytes") % index).str(), stats->tx_bytes); + stat.add((boost::format("Network %1%: tx_errors") % index).str(), stats->tx_errors); + stat.add((boost::format("Network %1%: collisions") % index).str(), stats->collisions); + + close(fd); + + bytes_[ifa->ifa_name].rx_bytes = stats->rx_bytes; + bytes_[ifa->ifa_name].tx_bytes = stats->tx_bytes; + whole_level = std::max(whole_level, level); + ++index; + } + + freeifaddrs(ifas); + + if (!error_str.empty()) + stat.summary(DiagStatus::ERROR, error_str); + else + stat.summary(whole_level, usage_dict_.at(whole_level)); + + last_update_time_ = ros::Time::now(); +} diff --git a/utilities/system_monitor/src/net_monitor/net_monitor_node.cpp b/utilities/system_monitor/src/net_monitor/net_monitor_node.cpp new file mode 100644 index 00000000000..f3b1ec694f0 --- /dev/null +++ b/utilities/system_monitor/src/net_monitor/net_monitor_node.cpp @@ -0,0 +1,33 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file net_monitor_node.cpp + * @brief Net monitor node class + */ + +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "net_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + NetMonitor monitor(nh, pnh); + monitor.run(); + + return 0; +} diff --git a/utilities/system_monitor/src/net_monitor/nl80211.cpp b/utilities/system_monitor/src/net_monitor/nl80211.cpp new file mode 100644 index 00000000000..e48310c80a4 --- /dev/null +++ b/utilities/system_monitor/src/net_monitor/nl80211.cpp @@ -0,0 +1,200 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file nl80211.cpp + * @brief 802.11 netlink-based interface class + */ + +#include +#include +#include +#include +#include +#include +#include + +NL80211::NL80211() +: initialized_(false), socket_(nullptr), id_(-1), cb_(nullptr), bitrate_(0.0) +{ +} + +// Attribute validation policy +static struct nla_policy stats_policy[NL80211_STA_INFO_MAX + 1]; +static struct nla_policy rate_policy[NL80211_RATE_INFO_MAX + 1]; + +static int callback(struct nl_msg *msg, void *arg) +{ + int ret; + float *rate = reinterpret_cast(arg); + + // Return actual netlink message. + struct nlmsghdr *nlh = nlmsg_hdr(msg); + // Return pointer to message payload. + struct genlmsghdr *ghdr = static_cast(nlmsg_data(nlh)); + + struct nlattr *tb[NL80211_ATTR_MAX + 1]; + struct nlattr *sinfo[NL80211_STA_INFO_MAX + 1]; + struct nlattr *rinfo[NL80211_RATE_INFO_MAX + 1]; + + // Create attribute index based on a stream of attributes. + ret = nla_parse(tb, NL80211_ATTR_MAX, genlmsg_attrdata(ghdr, 0), genlmsg_attrlen(ghdr, 0), nullptr); + // Returns 0 on success or a negative error code. + if (ret < 0) return NL_SKIP; + + // Information about a station missing + if (!tb[NL80211_ATTR_STA_INFO]) return NL_SKIP; + + // Create attribute index based on nested attribute. + ret = nla_parse_nested(sinfo, NL80211_STA_INFO_MAX, tb[NL80211_ATTR_STA_INFO], stats_policy); + // Returns 0 on success or a negative error code. + if (ret < 0) return NL_SKIP; + + // current unicast tx rate missing + if (!sinfo[NL80211_STA_INFO_TX_BITRATE]) return NL_SKIP; + + // Create attribute index based on nested attribute. + ret = nla_parse_nested(rinfo, NL80211_RATE_INFO_MAX, sinfo[NL80211_STA_INFO_TX_BITRATE], rate_policy); + // Returns 0 on success or a negative error code. + if (ret < 0) return NL_SKIP; + + // total bitrate exists + if (rinfo[NL80211_RATE_INFO_BITRATE]) + { + // Return payload of 16 bit integer attribute. + *rate = static_cast(nla_get_u16(rinfo[NL80211_RATE_INFO_BITRATE])) / 10; + } + + return NL_SKIP; +} + +void NL80211::init(void) +{ + int ret = 0; + + // Allocate new netlink socket. + socket_ = nl_socket_alloc(); + // Returns newly allocated netlink socket or NULL. + if (!socket_) return; + + // Connect a generic netlink socket. + if (genl_connect(socket_)) + // Returns 0 on success or a negative error code. + if (ret < 0) + { + shutdown(); + return; + } + + // Resolve generic netlink family name to its identifier. + id_ = genl_ctrl_resolve(socket_, "nl80211"); + // Returns a positive identifier or a negative error code. + if (id_ < 0) + { + shutdown(); + return; + } + + // Allocate a new callback handle. + cb_ = nl_cb_alloc(NL_CB_DEFAULT); + // Returns newly allocated callback handle or NULL. + if (!cb_) + { + shutdown(); + return; + } + + // Set up a callback. + ret = nl_cb_set(cb_, NL_CB_VALID, NL_CB_CUSTOM, callback, reinterpret_cast(&bitrate_)); + // Returns 0 on success or a negative error code. + if (ret < 0) + { + shutdown(); + return; + } + + initialized_ = true; + return; +} + +float NL80211::getBitrate(const char *ifa_name) +{ + int ret; + struct nl_msg *msg; + void *hdr; + int index; + + bitrate_ = 0.0; + + if (!initialized_) return bitrate_; + + // Get index of the network interface + index = if_nametoindex(ifa_name); + // Returns index number of the network interface on success or 0 on error and errno is set appropriately + if (!index) return bitrate_; + + // Allocate a new netlink message with the default maximum payload size. + msg = nlmsg_alloc(); + // Returns newly allocated netlink message or NULL. + if (!msg) return bitrate_; + + // Add Generic Netlink headers to Netlink message. + hdr = genlmsg_put(msg, NL_AUTO_PORT, NL_AUTO_SEQ, id_, 0, NLM_F_DUMP, NL80211_CMD_GET_STATION, 0); + // Returns pointer to user header or NULL if an error occurred. + if (!hdr) + { + nlmsg_free(msg); + return bitrate_; + } + + // Add 32 bit integer attribute to netlink message. + ret = nla_put_u32(msg, NL80211_ATTR_IFINDEX, index); + // Returns 0 on success or a negative error code. + if (ret < 0) + { + nlmsg_free(msg); + return bitrate_; + } + + // Finalize and transmit Netlink message. + ret = nl_send_auto(socket_, msg); + // Returns number of bytes sent or a negative error code. + if (ret < 0) + { + nlmsg_free(msg); + return bitrate_; + } + + // Receive a set of messages from a netlink socket. + ret = nl_recvmsgs(socket_, cb_); + // 0 on success or a negative error code from nl_recv(). + if (ret < 0) + { + nlmsg_free(msg); + return bitrate_; + } + + nlmsg_free(msg); + return bitrate_; +} + +void NL80211::shutdown(void) +{ + if (cb_) nl_cb_put(cb_); + nl_close(socket_); + nl_socket_free(socket_); + initialized_ = false; +} diff --git a/utilities/system_monitor/src/ntp_monitor/ntp_monitor.cpp b/utilities/system_monitor/src/ntp_monitor/ntp_monitor.cpp new file mode 100644 index 00000000000..79dcaa9008e --- /dev/null +++ b/utilities/system_monitor/src/ntp_monitor/ntp_monitor.cpp @@ -0,0 +1,115 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file ntp_monitor.cpp + * @brief NTP monitor class + */ + +#include +#include +#include +#include +#include +#include + +namespace bp = boost::process; +namespace fs = boost::filesystem; + +NTPMonitor::NTPMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh), pnh_(pnh) +{ + gethostname(hostname_, sizeof(hostname_)); + + // Check if command exists + fs::path p = bp::search_path("ntpdate"); + ntpdate_exists_ = (p.empty()) ? false : true; + + pnh_.param("server", server_, "ntp.ubuntu.com"); + pnh_.param("offset_warn", offset_warn_, 0.1); + pnh_.param("offset_error", offset_error_, 5.0); + + updater_.setHardwareID(hostname_); + updater_.add("NTP Offset", this, &NTPMonitor::checkOffset); +} + +void NTPMonitor::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (!ntpdate_exists_) + { + stat.summary(DiagStatus::ERROR, "ntpdate error"); + stat.add("ntpdate", "Command 'ntpdate' not found, but can be installed with: sudo apt install ntpdate"); + return; + } + + int level = DiagStatus::OK; + + // Query NTP server + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c((boost::format("ntpdate -q %1%") % server_).str(), bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + std::ostringstream os; + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "ntpdate error"); + stat.add("ntpdate", os.str().c_str()); + return; + } + + std::string line; + float offset; + float delay; + boost::smatch match; + const boost::regex filter("^server.*offset ([-+]?\\d+\\.\\d+), delay ([-+]?\\d+\\.\\d+)"); + + while (std::getline(is_out, line) && !line.empty()) + { + if (boost::regex_match(line, match, filter)) + { + float ofs = std::atof(match[1].str().c_str()); + float dly = std::atof(match[2].str().c_str()); + // Choose better network performance + if (dly > delay) + { + offset = ofs; + delay = dly; + } + } + } + + // Check an earlier offset as well + float abs = std::abs(offset); + if (abs >= offset_error_) level = DiagStatus::ERROR; + else if (abs >= offset_warn_) level = DiagStatus::WARN; + + stat.addf("NTP Offset", "%.6f sec", offset); + stat.addf("NTP Delay", "%.6f sec", delay); + stat.summary(level, offset_dict_.at(level)); +} diff --git a/utilities/system_monitor/src/ntp_monitor/ntp_monitor_node.cpp b/utilities/system_monitor/src/ntp_monitor/ntp_monitor_node.cpp new file mode 100644 index 00000000000..1ee3eb75467 --- /dev/null +++ b/utilities/system_monitor/src/ntp_monitor/ntp_monitor_node.cpp @@ -0,0 +1,33 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file ntp_monitor_node.cpp + * @brief NTP monitor node class + */ + +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "ntp_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + NTPMonitor monitor(nh, pnh); + monitor.run(); + + return 0; +} diff --git a/utilities/system_monitor/src/process_monitor/process_monitor.cpp b/utilities/system_monitor/src/process_monitor/process_monitor.cpp new file mode 100644 index 00000000000..d8c65932e13 --- /dev/null +++ b/utilities/system_monitor/src/process_monitor/process_monitor.cpp @@ -0,0 +1,320 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file process_monitor.cpp + * @brief Process monitor class + */ + +#include +#include +#include +#include +#include + +ProcessMonitor::ProcessMonitor(const ros::NodeHandle &nh, const ros::NodeHandle &pnh) + : nh_(nh), pnh_(pnh) +{ + int index; + + gethostname(hostname_, sizeof(hostname_)); + + pnh_.param("num_of_procs", num_of_procs_, 5); + + updater_.setHardwareID(hostname_); + updater_.add("Tasks Summary", this, &ProcessMonitor::monitorProcesses); + + for (index = 0; index < num_of_procs_; ++index) + { + auto task = std::make_shared((boost::format("High-load Proc[%1%]") % index).str()); + load_tasks_.push_back(task); + updater_.add(*task); + } + for (index = 0; index < num_of_procs_; ++index) + { + auto task = std::make_shared((boost::format("High-mem Proc[%1%]") % index).str()); + memory_tasks_.push_back(task); + updater_.add(*task); + } +} + +void ProcessMonitor::run(void) +{ + ros::Rate rate(1.0); + + while (ros::ok()) + { + ros::spinOnce(); + updater_.force_update(); + rate.sleep(); + } +} + +void ProcessMonitor::monitorProcesses(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + bp::ipstream is_err; + bp::ipstream is_out; + std::ostringstream os; + + // Get processes + bp::child c("top -bn1 -o %CPU -w 128", bp::std_out > is_out, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "top error"); + stat.add("top", os.str().c_str()); + setErrorContent(&load_tasks_, "top error", "top", os.str().c_str()); + setErrorContent(&memory_tasks_, "top error", "top", os.str().c_str()); + return; + } + + is_out >> os.rdbuf(); + std::string str = os.str(); + + // Get task summary + getTasksSummary(stat, str); + // Remove header + removeHeader(stat, str); + + // Get high load processes + getHighLoadProcesses(str); + + // Get high memory processes + getHighMemoryProcesses(str); +} + +void ProcessMonitor::getTasksSummary(diagnostic_updater::DiagnosticStatusWrapper &stat, const std::string &output) +{ + bp::pipe p; + std::string line; + + // Echo output for grep + { + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c((boost::format("echo %1%") % output).str(), bp::std_out > p, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + std::ostringstream os; + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "echo error"); + stat.add("echo", os.str().c_str()); + return; + } + } + // Find matching pattern of summary + { + bp::ipstream is_out; + bp::child c("grep Tasks:", bp::std_out > is_out, bp::std_in < p); + c.wait(); + // no matching line + if (c.exit_code() != 0) + { + stat.summary(DiagStatus::ERROR, "matching pattern not found"); + stat.add("name", "Tasks:"); + return; + } + + std::getline(is_out, line); + boost::smatch match; + boost::regex + filter("^Tasks: (\\d+) total,\\s+(\\d+) running,\\s+(\\d+) sleeping,\\s+(\\d+) stopped,\\s+(\\d+) zombie"); + + if (boost::regex_match(line, match, filter)) + { + stat.add("total", match[1].str()); + stat.add("running", match[2].str()); + stat.add("sleeping", match[3].str()); + stat.add("stopped", match[4].str()); + stat.add("zombie", match[5].str()); + stat.summary(DiagStatus::OK, "OK"); + } + else + { + stat.summary(DiagStatus::ERROR, "invalid format"); + } + } +} + +void ProcessMonitor::removeHeader(diagnostic_updater::DiagnosticStatusWrapper &stat, std::string &output) +{ + bp::pipe p1; + bp::pipe p2; + std::ostringstream os; + + // Echo output for sed + { + bp::ipstream is_err; + bp::child c((boost::format("echo %1%") % output).str(), bp::std_out > p1, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + stat.summary(DiagStatus::ERROR, "echo error"); + stat.add("echo", os.str().c_str()); + return; + } + } + // Remove %Cpu section + { + bp::ipstream is_err; + bp::child c("sed \"/^%Cpu/d\"", bp::std_out > p2, bp::std_err > is_err, bp::std_in < p1); + c.wait(); + // no matching line + if (c.exit_code() != 0) + { + stat.summary(DiagStatus::ERROR, "sed error"); + stat.add("sed", "Failed to remove header"); + return; + } + } + // Remove header + { + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c("sed \"1,6d\"", bp::std_out > is_out, bp::std_err > is_err, bp::std_in < p2); + c.wait(); + // no matching line + if (c.exit_code() != 0) + { + stat.summary(DiagStatus::ERROR, "sed error"); + stat.add("sed", "Failed to remove header"); + return; + } + // overwrite + is_out >> os.rdbuf(); + output = os.str(); + } +} + +void ProcessMonitor::getHighLoadProcesses(const std::string &output) +{ + bp::pipe p; + std::ostringstream os; + + // Echo output for sed + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c((boost::format("echo %1%") % output).str(), bp::std_out > p, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + setErrorContent(&load_tasks_, "echo error", "echo", os.str().c_str()); + return; + } + + // Get top-rated + getTopratedProcesses(&load_tasks_, &p); +} + +void ProcessMonitor::getHighMemoryProcesses(const std::string &output) +{ + bp::pipe p1; + bp::pipe p2; + std::ostringstream os; + + // Echo output for sed + { + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c((boost::format("echo %1%") % output).str(), bp::std_out > p1, bp::std_err > is_err); + c.wait(); + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + setErrorContent(&memory_tasks_, "echo error", "echo", os.str().c_str()); + return; + } + } + // Sort by memory usage + { + bp::ipstream is_out; + bp::ipstream is_err; + bp::child c("sort -r -k 10", bp::std_out > p2, bp::std_err > is_err, bp::std_in < p1); + c.wait(); + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + setErrorContent(&memory_tasks_, "sort error", "sort", os.str().c_str()); + return; + } + } + + // Get top-rated + getTopratedProcesses(&memory_tasks_, &p2); +} + +void ProcessMonitor::getTopratedProcesses(std::vector> *tasks, bp::pipe *p) +{ + if (tasks == nullptr || p == nullptr) return; + + bp::ipstream is_out; + bp::ipstream is_err; + std::ostringstream os; + + bp::child c((boost::format("sed -n \"1,%1% p\"") % num_of_procs_).str(), + bp::std_out > is_out, bp::std_err > is_err, bp::std_in < *p); + + c.wait(); + // Failed to modify line + if (c.exit_code() != 0) + { + is_err >> os.rdbuf(); + setErrorContent(tasks, "sed error", "sed", os.str().c_str()); + return; + } + + std::vector list; + std::string line; + int index = 0; + + while (std::getline(is_out, line) && !line.empty()) + { + boost::trim_left(line); + boost::split(list, line, boost::is_space(), boost::token_compress_on); + + tasks->at(index)->setDiagnosticsStatus(DiagStatus::OK, "OK"); + tasks->at(index)->setProcessId(list[0]); + tasks->at(index)->setUserName(list[1]); + tasks->at(index)->setPriority(list[2]); + tasks->at(index)->setNiceValue(list[3]); + tasks->at(index)->setVirtualImage(list[4]); + tasks->at(index)->setResidentSize(list[5]); + tasks->at(index)->setSharedMemSize(list[6]); + tasks->at(index)->setProcessStatus(list[7]); + tasks->at(index)->setCPUUsage(list[8]); + tasks->at(index)->setMemoryUsage(list[9]); + tasks->at(index)->setCPUTime(list[10]); + tasks->at(index)->setCommandName(list[11]); + ++index; + } +} + +void ProcessMonitor::setErrorContent(std::vector> *tasks, + const std::string &message, + const std::string &error_command, const std::string &content) +{ + if (tasks == nullptr) return; + + for (auto itr = tasks->begin(); itr != tasks->end(); ++itr) + { + (*itr)->setDiagnosticsStatus(DiagStatus::ERROR, message); + (*itr)->setErrorContent(error_command, content); + } +} diff --git a/utilities/system_monitor/src/process_monitor/process_monitor_node.cpp b/utilities/system_monitor/src/process_monitor/process_monitor_node.cpp new file mode 100644 index 00000000000..ceefd55fab7 --- /dev/null +++ b/utilities/system_monitor/src/process_monitor/process_monitor_node.cpp @@ -0,0 +1,33 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file process_monitor_node.cpp + * @brief Process monitor node class + */ + +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "process_monitor"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + ProcessMonitor monitor(nh, pnh); + monitor.run(); + + return 0; +} diff --git a/utilities/system_monitor/test/config/test_hdd_monitor.yaml b/utilities/system_monitor/test/config/test_hdd_monitor.yaml new file mode 100644 index 00000000000..0688807f928 --- /dev/null +++ b/utilities/system_monitor/test/config/test_hdd_monitor.yaml @@ -0,0 +1,5 @@ +hdd_reader_port: 7635 +disks: +- name: /dev/sda + temp_warn: 55.0 + temp_error: 70.0 diff --git a/utilities/system_monitor/test/config/test_net_monitor.yaml b/utilities/system_monitor/test/config/test_net_monitor.yaml new file mode 100644 index 00000000000..1a556319354 --- /dev/null +++ b/utilities/system_monitor/test/config/test_net_monitor.yaml @@ -0,0 +1,2 @@ +devices: [ wlp82s0 ] +usage_warn: 0.95 diff --git a/utilities/system_monitor/test/config/test_ntp_monitor.yaml b/utilities/system_monitor/test/config/test_ntp_monitor.yaml new file mode 100644 index 00000000000..4421ef54aee --- /dev/null +++ b/utilities/system_monitor/test/config/test_ntp_monitor.yaml @@ -0,0 +1,3 @@ +server: ntp.ubuntu.com +offset_warn: 0.1 +offset_error: 5.0 diff --git a/utilities/system_monitor/test/src/cpu_monitor/mpstat1.cpp b/utilities/system_monitor/test/src/cpu_monitor/mpstat1.cpp new file mode 100644 index 00000000000..71faee793f0 --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/mpstat1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file mpstat1.cpp + * @brief dummy mpstat mpstat to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/mpstat2.cpp b/utilities/system_monitor/test/src/cpu_monitor/mpstat2.cpp new file mode 100644 index 00000000000..a13810ab06d --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/mpstat2.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file mpstat2.cpp + * @brief dummy mpstat executable to provide nothing + */ + +int main(int argc, char** argv) +{ + return 0; +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp b/utilities/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp new file mode 100644 index 00000000000..09eb7476872 --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/test_arm_cpu_monitor.cpp @@ -0,0 +1,668 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* TEST_FILE = "test"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestCPUMonitor : public CPUMonitor +{ + friend class CPUMonitorTestSuite; + +public: + TestCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempName(const std::string &path) { temps_.emplace_back(path, path); } + void clearTempNames(void) { temps_.clear(); } + + void addFreqName(int index, const std::string &path) { freqs_.emplace_back(index, path); } + void clearFreqNames(void) { freqs_.clear(); } + + void setMpstatExists(bool mpstat_exists) { mpstat_exists_ = mpstat_exists; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void changeLoad1Warn(float load1_warn) { load1_warn_ = load1_warn; } + void changeLoad5Warn(float load5_warn) { load5_warn_ = load5_warn; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class CPUMonitorTestSuite : public ::testing::Test +{ +public: + CPUMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + mpstat_ = exe_dir_ + "/mpstat"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string mpstat_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestCPUMonitor::diagCallback, monitor_.get()); + monitor_->getTempNames(); + monitor_->getFreqNames(); + + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + void TearDown(void) + { + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(CPUMonitorTestSuite, tempWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 90000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 95000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearTempNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "temperature files not found"); +} + +TEST_F(CPUMonitorTestSuite, tempFileOpenErrorTest) +{ + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(CPUMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(1.00); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageMpstatNotFoundTest) +{ + // Set flag false + monitor_->setMpstatExists(false); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); + ASSERT_STREQ(value.c_str(), "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); +} + +TEST_F(CPUMonitorTestSuite, load1WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad1Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad1Warn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, load5WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad5Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad5Warn(0.80); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, DISABLED_throttlingTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqFrequencyFilesNotFoundTest) +{ + // Clear list + monitor_->clearFreqNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "frequency files not found"); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatErrorTest) +{ + // Symlink mpstat1 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat1", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatExceptionTest) +{ + // Symlink mpstat2 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat2", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat exception"); +} + +// for coverage +class DummyCPUMonitor : public CPUMonitorBase +{ + friend class CPUMonitorTestSuite; +public: + DummyCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(CPUMonitorTestSuite, dummyCPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + monitor->getTempNames(); + monitor->getFreqNames(); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp b/utilities/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp new file mode 100644 index 00000000000..ad542593a35 --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/test_intel_cpu_monitor.cpp @@ -0,0 +1,952 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* TEST_FILE = "test"; +static constexpr const char* DOCKER_ENV = "/.dockerenv"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestCPUMonitor : public CPUMonitor +{ + friend class CPUMonitorTestSuite; + +public: + TestCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempName(const std::string &path) { temps_.emplace_back(path, path); } + void clearTempNames(void) { temps_.clear(); } + bool isTempNamesEmpty(void) { temps_.empty(); } + + void addFreqName(int index, const std::string &path) { freqs_.emplace_back(index, path); } + void clearFreqNames(void) { freqs_.clear(); } + + void setMpstatExists(bool mpstat_exists) { mpstat_exists_ = mpstat_exists; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void changeLoad1Warn(float load1_warn) { load1_warn_ = load1_warn; } + void changeLoad5Warn(float load5_warn) { load5_warn_ = load5_warn; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class CPUMonitorTestSuite : public ::testing::Test +{ +public: + CPUMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + mpstat_ = exe_dir_ + "/mpstat"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string mpstat_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestCPUMonitor::diagCallback, monitor_.get()); + monitor_->getTempNames(); + monitor_->getFreqNames(); + + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + void TearDown(void) + { + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +enum ThreadTestMode +{ + Normal = 0, + Throttling, + ReturnsError, + RecvTimeout, + RecvNoData, + FormatError, +}; + +bool stop_thread; +pthread_mutex_t mutex; + +void* msr_reader(void *args) +{ + ThreadTestMode *mode = reinterpret_cast(args); + + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) return nullptr; + + // Allow address reuse + int ret = 0; + int opt = 1; + ret = setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast(&opt), (socklen_t) sizeof(opt)); + if (ret < 0) { close(sock); return nullptr; } + + // Give the socket FD the local address ADDR + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(7634); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = bind(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) { close(sock); return nullptr; } + + // Prepare to accept connections on socket FD + ret = listen(sock, 5); + if (ret < 0) { close(sock); return nullptr; } + + sockaddr_in client; + socklen_t len = sizeof(client); + + // Await a connection on socket FD + int new_sock = accept(sock, reinterpret_cast(&client), &len); + if (new_sock < 0) { close(sock); return nullptr; } + + ret = 0; + std::ostringstream oss; + boost::archive::text_oarchive oa(oss); + MSRInfo msr = {0}; + + switch (*mode) + { + case Normal: + msr.error_code_ = 0; + msr.pkg_thermal_status_.push_back(false); + oa << msr; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case Throttling: + msr.error_code_ = 0; + msr.pkg_thermal_status_.push_back(true); + oa << msr; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case ReturnsError: + msr.error_code_ = EACCES; + oa << msr; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case RecvTimeout: + // Wait for recv timeout + while (true) + { + pthread_mutex_lock(&mutex); + if (stop_thread) break; + pthread_mutex_unlock(&mutex); + sleep(1); + } + break; + + case RecvNoData: + // Send nothing, close socket immediately + break; + + case FormatError: + // Send wrong data + oa << "test"; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + default: + break; + } + + // Close the file descriptor FD + close(new_sock); + close(sock); + + return nullptr; +} + +TEST_F(CPUMonitorTestSuite, tempWarnTest) +{ + // Skip test if process runs inside CI environment + if (monitor_->isTempNamesEmpty() && fs::exists(DOCKER_ENV)) return; + + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 90000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempErrorTest) +{ + // Skip test if process runs inside CI environment + if (monitor_->isTempNamesEmpty() && fs::exists(DOCKER_ENV)) return; + + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 95000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearTempNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "temperature files not found"); +} + +TEST_F(CPUMonitorTestSuite, tempFileOpenErrorTest) +{ + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(CPUMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(1.00); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageMpstatNotFoundTest) +{ + // Set flag false + monitor_->setMpstatExists(false); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); + ASSERT_STREQ(value.c_str(), "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); +} + +TEST_F(CPUMonitorTestSuite, load1WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + // Depending on running situation of machine. + ASSERT_TRUE(status.level == DiagStatus::OK || status.level == DiagStatus::WARN); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad1Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad1Warn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + // Depending on running situation of machine. + ASSERT_TRUE(status.level == DiagStatus::OK || status.level == DiagStatus::WARN); + } +} + +TEST_F(CPUMonitorTestSuite, load5WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + // Depending on running situation of machine. + ASSERT_TRUE(status.level == DiagStatus::OK || status.level == DiagStatus::WARN); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad5Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad5Warn(0.80); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + // Depending on running situation of machine. + ASSERT_TRUE(status.level == DiagStatus::OK || status.level == DiagStatus::WARN); + } +} + +TEST_F(CPUMonitorTestSuite, throttlingTest) +{ + pthread_t th; + ThreadTestMode mode = Normal; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, throttlingThrottlingTest) +{ + pthread_t th; + ThreadTestMode mode = Throttling; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "throttling"); +} + +TEST_F(CPUMonitorTestSuite, throttlingReturnsErrorTest) +{ + pthread_t th; + ThreadTestMode mode = ReturnsError; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "msr_reader error"); + ASSERT_TRUE(findValue(status, "msr_reader", value)); + ASSERT_STREQ(value.c_str(), strerror(EACCES)); +} + +TEST_F(CPUMonitorTestSuite, throttlingRecvTimeoutTest) +{ + pthread_t th; + ThreadTestMode mode = RecvTimeout; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + // Recv timeout occurs, thread is no longer needed + pthread_mutex_lock(&mutex); + stop_thread = true; + pthread_mutex_unlock(&mutex); + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), strerror(EWOULDBLOCK)); +} + +TEST_F(CPUMonitorTestSuite, throttlingRecvNoDataTest) +{ + pthread_t th; + ThreadTestMode mode = RecvNoData; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), "No data received"); +} + +TEST_F(CPUMonitorTestSuite, throttlingFormatErrorTest) +{ + pthread_t th; + ThreadTestMode mode = FormatError; + pthread_create(&th, nullptr, msr_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), "input stream error"); +} + +TEST_F(CPUMonitorTestSuite, throttlingConnectErrorTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "connect error"); + ASSERT_TRUE(findValue(status, "connect", value)); + ASSERT_STREQ(value.c_str(), strerror(ECONNREFUSED)); +} + +TEST_F(CPUMonitorTestSuite, freqTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqFrequencyFilesNotFoundTest) +{ + // Clear list + monitor_->clearFreqNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "frequency files not found"); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatErrorTest) +{ + // Symlink mpstat1 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat1", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatExceptionTest) +{ + // Symlink mpstat2 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat2", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat exception"); +} + +// for coverage +class DummyCPUMonitor : public CPUMonitorBase +{ + friend class CPUMonitorTestSuite; +public: + DummyCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(CPUMonitorTestSuite, dummyCPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + monitor->getTempNames(); + monitor->getFreqNames(); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp b/utilities/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp new file mode 100644 index 00000000000..e4582eca099 --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/test_raspi_cpu_monitor.cpp @@ -0,0 +1,668 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* TEST_FILE = "test"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestCPUMonitor : public CPUMonitor +{ + friend class CPUMonitorTestSuite; + +public: + TestCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempName(const std::string &path) { temps_.emplace_back(path, path); } + void clearTempNames(void) { temps_.clear(); } + + void addFreqName(int index, const std::string &path) { freqs_.emplace_back(index, path); } + void clearFreqNames(void) { freqs_.clear(); } + + void setMpstatExists(bool mpstat_exists) { mpstat_exists_ = mpstat_exists; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void changeLoad1Warn(float load1_warn) { load1_warn_ = load1_warn; } + void changeLoad5Warn(float load5_warn) { load5_warn_ = load5_warn; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class CPUMonitorTestSuite : public ::testing::Test +{ +public: + CPUMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + mpstat_ = exe_dir_ + "/mpstat"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string mpstat_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestCPUMonitor::diagCallback, monitor_.get()); + monitor_->getTempNames(); + monitor_->getFreqNames(); + + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + void TearDown(void) + { + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(CPUMonitorTestSuite, tempWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 90000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 95000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearTempNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "temperature files not found"); +} + +TEST_F(CPUMonitorTestSuite, tempFileOpenErrorTest) +{ + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(CPUMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(1.00); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageMpstatNotFoundTest) +{ + // Set flag false + monitor_->setMpstatExists(false); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); + ASSERT_STREQ(value.c_str(), "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); +} + +TEST_F(CPUMonitorTestSuite, load1WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad1Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad1Warn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, load5WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad5Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad5Warn(0.80); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, throttlingTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqFrequencyFilesNotFoundTest) +{ + // Clear list + monitor_->clearFreqNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "frequency files not found"); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatErrorTest) +{ + // Symlink mpstat1 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat1", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatExceptionTest) +{ + // Symlink mpstat2 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat2", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat exception"); +} + +// for coverage +class DummyCPUMonitor : public CPUMonitorBase +{ + friend class CPUMonitorTestSuite; +public: + DummyCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(CPUMonitorTestSuite, dummyCPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + monitor->getTempNames(); + monitor->getFreqNames(); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp b/utilities/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp new file mode 100644 index 00000000000..8ad9acdfced --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/test_tegra_cpu_monitor.cpp @@ -0,0 +1,653 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* TEST_FILE = "test"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestCPUMonitor : public CPUMonitor +{ + friend class CPUMonitorTestSuite; + +public: + TestCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempName(const std::string &path) { temps_.emplace_back(path, path); } + void clearTempNames(void) { temps_.clear(); } + + void addFreqName(int index, const std::string &path) { freqs_.emplace_back(index, path); } + void clearFreqNames(void) { freqs_.clear(); } + + void setMpstatExists(bool mpstat_exists) { mpstat_exists_ = mpstat_exists; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void changeLoad1Warn(float load1_warn) { load1_warn_ = load1_warn; } + void changeLoad5Warn(float load5_warn) { load5_warn_ = load5_warn; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class CPUMonitorTestSuite : public ::testing::Test +{ +public: + CPUMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + mpstat_ = exe_dir_ + "/mpstat"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string mpstat_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestCPUMonitor::diagCallback, monitor_.get()); + monitor_->getTempNames(); + monitor_->getFreqNames(); + + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + void TearDown(void) + { + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + // Remove dummy executable if exists + if (fs::exists(mpstat_)) fs::remove(mpstat_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(CPUMonitorTestSuite, tempWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 90000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 95000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, tempTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearTempNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "temperature files not found"); +} + +TEST_F(CPUMonitorTestSuite, tempFileOpenErrorTest) +{ + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(CPUMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(1.00); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, usageMpstatNotFoundTest) +{ + // Set flag false + monitor_->setMpstatExists(false); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); + ASSERT_STREQ(value.c_str(), "Command 'mpstat' not found, but can be installed with: sudo apt install sysstat"); +} + +TEST_F(CPUMonitorTestSuite, load1WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad1Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad1Warn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, load5WarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeLoad5Warn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeLoad5Warn(0.80); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Load Average", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(CPUMonitorTestSuite, freqTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(CPUMonitorTestSuite, freqFrequencyFilesNotFoundTest) +{ + // Clear list + monitor_->clearFreqNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("CPU Frequency", status)); + + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "frequency files not found"); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatErrorTest) +{ + // Symlink mpstat1 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat1", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat error"); + ASSERT_TRUE(findValue(status, "mpstat", value)); +} + +TEST_F(CPUMonitorTestSuite, usageMpstatExceptionTest) +{ + // Symlink mpstat2 to mpstat + fs::create_symlink(exe_dir_ + "/mpstat2", mpstat_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("CPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "mpstat exception"); +} + +// for coverage +class DummyCPUMonitor : public CPUMonitorBase +{ + friend class CPUMonitorTestSuite; +public: + DummyCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(CPUMonitorTestSuite, dummyCPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + monitor->getTempNames(); + monitor->getFreqNames(); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp b/utilities/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp new file mode 100644 index 00000000000..cc28369567b --- /dev/null +++ b/utilities/system_monitor/test/src/cpu_monitor/test_unknown_cpu_monitor.cpp @@ -0,0 +1,72 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include + +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +class TestCPUMonitor : public CPUMonitor +{ + friend class CPUMonitorTestSuite; + +public: + TestCPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : CPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void update(void) { updater_.force_update(); } + +private: + diagnostic_msgs::DiagnosticArray array_; +}; + +class CPUMonitorTestSuite : public ::testing::Test +{ +public: + CPUMonitorTestSuite() : nh_(""), pnh_("~") {} + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestCPUMonitor::diagCallback, monitor_.get()); + monitor_->getTempNames(); + monitor_->getFreqNames(); + } + + void TearDown(void) + { + } +}; + +TEST_F(CPUMonitorTestSuite, test) +{ + ASSERT_TRUE(true); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp b/utilities/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp new file mode 100644 index 00000000000..99e82a1044d --- /dev/null +++ b/utilities/system_monitor/test/src/gpu_monitor/test_nvml_gpu_monitor.cpp @@ -0,0 +1,534 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include + +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +class TestGPUMonitor : public GPUMonitor +{ + friend class GPUMonitorTestSuite; + +public: + TestGPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : GPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addGPU(const gpu_info &info) { gpus_.push_back(info); } + void clearGPU(void) { gpus_.clear(); } + + void changeTempWarn(float temp_warn) { temp_warn_ = temp_warn; } + void changeTempError(float temp_error) { temp_error_ = temp_error; } + + void changeGPUUsageWarn(float gpu_usage_warn) { gpu_usage_warn_ = gpu_usage_warn; } + void changeGPUUsageError(float gpu_usage_error) { gpu_usage_error_ = gpu_usage_error; } + + void changeMemoryUsageWarn(float memory_usage_warn) { memory_usage_warn_ = memory_usage_warn; } + void changeMemoryUsageError(float memory_usage_error) { memory_usage_error_ = memory_usage_error; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class GPUMonitorTestSuite : public ::testing::Test +{ +public: + GPUMonitorTestSuite() : nh_(""), pnh_("~") {} + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestGPUMonitor::diagCallback, monitor_.get()); + } + + void TearDown(void) + { + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } +}; + +TEST_F(GPUMonitorTestSuite, tempWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeTempWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeTempWarn(90.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, tempErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify error + { + // Change error level + monitor_->changeTempError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeTempError(95.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, gpuUsageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeGPUUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeGPUUsageWarn(0.90); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, gpuUsageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify error + { + // Change error level + monitor_->changeGPUUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeGPUUsageError(1.00); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, gpuMemoryUsageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeMemoryUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeMemoryUsageWarn(0.95); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, gpuMemoryUsageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify error + { + // Change error level + monitor_->changeMemoryUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeMemoryUsageError(0.99); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, throttlingTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(GPUMonitorTestSuite, gpuNotFoundTest) +{ + // Clear list + monitor_->clearGPU(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "gpu not found"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "gpu not found"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "gpu not found"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "gpu not found"); +} + +TEST_F(GPUMonitorTestSuite, illigalDeviceHandleTest) +{ + // Clear list + monitor_->clearGPU(); + // Add blank device + gpu_info gpu; + monitor_->addGPU(gpu); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "Failed to retrieve the current temperature"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "Failed to retrieve the current utilization rates"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "Failed to retrieve the amount of used, free and total memory"); + + ASSERT_TRUE(monitor_->findDiagStatus("GPU Thermal Throttling", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "Failed to retrieve the current clock speeds"); +} + +// for coverage +class DummyGPUMonitor : public GPUMonitorBase +{ + friend class GPUMonitorTestSuite; +public: + DummyGPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : GPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(GPUMonitorTestSuite, dummyGPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "GPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp b/utilities/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp new file mode 100644 index 00000000000..58a5fdaaa95 --- /dev/null +++ b/utilities/system_monitor/test/src/gpu_monitor/test_tegra_gpu_monitor.cpp @@ -0,0 +1,483 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include + +static constexpr const char* TEST_FILE = "test"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +class TestGPUMonitor : public GPUMonitor +{ + friend class GPUMonitorTestSuite; + +public: + TestGPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : GPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempName(const std::string &path) { temps_.emplace_back(path, path); } + void clearTempNames(void) { temps_.clear(); } + + void addLoadName(const std::string &path) { loads_.emplace_back(path, path); } + void clearLoadNames(void) { loads_.clear(); } + + void addFreqName(const std::string &path) { freqs_.emplace_back(path, path); } + void clearFreqNames(void) { freqs_.clear(); } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class GPUMonitorTestSuite : public ::testing::Test +{ +public: + GPUMonitorTestSuite() : nh_(""), pnh_("~") {} + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestGPUMonitor::diagCallback, monitor_.get()); + + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + } + + void TearDown(void) + { + // Remove test file if exists + if (fs::exists(TEST_FILE)) fs::remove(TEST_FILE); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } +}; + +TEST_F(GPUMonitorTestSuite, tempWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 90000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, tempErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 95000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 89900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, tempTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearTempNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "temperature files not found"); +} + +TEST_F(GPUMonitorTestSuite, tempFileOpenErrorTest) +{ + // Add test file to list + monitor_->addTempName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(GPUMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addLoadName(TEST_FILE); + + // Verify warning + { + // Write warning level + std::ofstream ofs(TEST_FILE); + ofs << 900 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 890 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Add test file to list + monitor_->addLoadName(TEST_FILE); + + // Verify error + { + // Write error level + std::ofstream ofs(TEST_FILE); + ofs << 1000 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Write normal level + std::ofstream ofs(TEST_FILE); + ofs << 890 << std::endl; + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(GPUMonitorTestSuite, usageTemperatureFilesNotFoundTest) +{ + // Clear list + monitor_->clearLoadNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "load files not found"); +} + +TEST_F(GPUMonitorTestSuite, usageFileOpenErrorTest) +{ + // Add test file to list + monitor_->addLoadName(TEST_FILE); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "file open error"); + ASSERT_TRUE(findValue(status, "file open error", value)); + ASSERT_STREQ(value.c_str(), TEST_FILE); +} + +TEST_F(GPUMonitorTestSuite, freqTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Frequency", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(GPUMonitorTestSuite, freqFrequencyFilesNotFoundTest) +{ + // Clear list + monitor_->clearFreqNames(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("GPU Frequency", status)); + + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "frequency files not found"); +} + +// for coverage +class DummyGPUMonitor : public GPUMonitorBase +{ + friend class GPUMonitorTestSuite; +public: + DummyGPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : GPUMonitorBase(nh, pnh) {} + void update(void) { updater_.force_update(); } +}; + +TEST_F(GPUMonitorTestSuite, dummyGPUMonitorTest) +{ + std::unique_ptr monitor = std::make_unique(nh_, pnh_); + // Publish topic + monitor->update(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "GPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp b/utilities/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp new file mode 100644 index 00000000000..305ca446e42 --- /dev/null +++ b/utilities/system_monitor/test/src/gpu_monitor/test_unknown_gpu_monitor.cpp @@ -0,0 +1,70 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include + +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +class TestGPUMonitor : public GPUMonitor +{ + friend class GPUMonitorTestSuite; + +public: + TestGPUMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : GPUMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void update(void) { updater_.force_update(); } + +private: + diagnostic_msgs::DiagnosticArray array_; +}; + +class GPUMonitorTestSuite : public ::testing::Test +{ +public: + GPUMonitorTestSuite() : nh_(""), pnh_("~") {} + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestGPUMonitor::diagCallback, monitor_.get()); + } + + void TearDown(void) + { + } +}; + +TEST_F(GPUMonitorTestSuite, test) +{ + ASSERT_TRUE(true); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "GPUMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/hdd_monitor/df1.cpp b/utilities/system_monitor/test/src/hdd_monitor/df1.cpp new file mode 100644 index 00000000000..1bc6535993c --- /dev/null +++ b/utilities/system_monitor/test/src/hdd_monitor/df1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file df.cpp + * @brief dummy df executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp b/utilities/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp new file mode 100644 index 00000000000..4dc4292c6e6 --- /dev/null +++ b/utilities/system_monitor/test/src/hdd_monitor/test_hdd_monitor.cpp @@ -0,0 +1,654 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestHDDMonitor : public HDDMonitor +{ + friend class HDDMonitorTestSuite; + +public: + TestHDDMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : HDDMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void addTempParams(const std::string &name, float temp_warn, float temp_error) + { + TempParam param; + param.temp_warn_ = temp_warn; + param.temp_error_ = temp_error; + temp_params_[name] = param; + } + void changeTempParams(float temp_warn, float temp_error) + { + for (auto itr = temp_params_.begin(); itr != temp_params_.end(); ++itr) + { + itr->second.temp_warn_ = temp_warn; + itr->second.temp_error_ = temp_error; + } + } + void clearTempParams(void) { temp_params_.clear(); } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class HDDMonitorTestSuite : public ::testing::Test +{ +public: + HDDMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + df_ = exe_dir_ + "/df"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string df_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestHDDMonitor::diagCallback, monitor_.get()); + + // Remove dummy executable if exists + if (fs::exists(df_)) fs::remove(df_); + } + + void TearDown(void) + { + // Remove dummy executable if exists + if (fs::exists(df_)) fs::remove(df_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +enum ThreadTestMode +{ + Normal = 0, + Hot, + CriticalHot, + ReturnsError, + RecvTimeout, + RecvNoData, + FormatError, +}; + +bool stop_thread; +pthread_mutex_t mutex; + +void* hdd_reader(void *args) +{ + ThreadTestMode *mode = reinterpret_cast(args); + + // Create a new socket + int sock = socket(AF_INET, SOCK_STREAM, 0); + if (sock < 0) return nullptr; + + // Allow address reuse + int ret = 0; + int opt = 1; + ret = setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast(&opt), (socklen_t) sizeof(opt)); + if (ret < 0) { close(sock); return nullptr; } + + // Give the socket FD the local address ADDR + sockaddr_in addr; + memset(&addr, 0, sizeof(sockaddr_in)); + addr.sin_family = AF_INET; + addr.sin_port = htons(7635); + addr.sin_addr.s_addr = htonl(INADDR_ANY); + ret = bind(sock, (struct sockaddr*)&addr, sizeof(addr)); + if (ret < 0) { close(sock); return nullptr; } + + // Prepare to accept connections on socket FD + ret = listen(sock, 5); + if (ret < 0) { close(sock); return nullptr; } + + sockaddr_in client; + socklen_t len = sizeof(client); + + // Await a connection on socket FD + int new_sock = accept(sock, reinterpret_cast(&client), &len); + if (new_sock < 0) { close(sock); return nullptr; } + + ret = 0; + std::ostringstream oss; + boost::archive::text_oarchive oa(oss); + HDDInfoList list; + HDDInfo info = {0}; + + switch (*mode) + { + case Normal: + info.error_code_ = 0; + info.temp_ = 40; + list["/dev/sda"] = info; + oa << list; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case Hot: + info.error_code_ = 0; + info.temp_ = 55; + list["/dev/sda"] = info; + oa << list; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case CriticalHot: + info.error_code_ = 0; + info.temp_ = 70; + list["/dev/sda"] = info; + oa << list; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case ReturnsError: + info.error_code_ = EACCES; + list["/dev/sda"] = info; + oa << list; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + case RecvTimeout: + // Wait for recv timeout + while (true) + { + pthread_mutex_lock(&mutex); + if (stop_thread) break; + pthread_mutex_unlock(&mutex); + sleep(1); + } + break; + + case RecvNoData: + // Send nothing, close socket immediately + break; + + case FormatError: + // Send wrong data + oa << "test"; + ret = write(new_sock, oss.str().c_str(), oss.str().length()); + break; + + default: + break; + } + + // Close the file descriptor FD + close(new_sock); + close(sock); + + return nullptr; +} + +TEST_F(HDDMonitorTestSuite, tempNormalTest) +{ + pthread_t th; + ThreadTestMode mode = Normal; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(HDDMonitorTestSuite, tempWarnTest) +{ + pthread_t th; + ThreadTestMode mode = Hot; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); +} + +TEST_F(HDDMonitorTestSuite, tempErrorTest) +{ + pthread_t th; + ThreadTestMode mode = CriticalHot; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); +} + +TEST_F(HDDMonitorTestSuite, tempReturnsErrorTest) +{ + pthread_t th; + ThreadTestMode mode = ReturnsError; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "hdd_reader error"); + ASSERT_TRUE(findValue(status, "HDD 0: hdd_reader", value)); + ASSERT_STREQ(value.c_str(), strerror(EACCES)); +} + +TEST_F(HDDMonitorTestSuite, tempRecvTimeoutTest) +{ + pthread_t th; + ThreadTestMode mode = RecvTimeout; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + // Recv timeout occurs, thread is no longer needed + pthread_mutex_lock(&mutex); + stop_thread = true; + pthread_mutex_unlock(&mutex); + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), strerror(EWOULDBLOCK)); +} + +TEST_F(HDDMonitorTestSuite, tempRecvNoDataTest) +{ + pthread_t th; + ThreadTestMode mode = RecvNoData; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), "No data received"); +} + +TEST_F(HDDMonitorTestSuite, tempFormatErrorTest) +{ + pthread_t th; + ThreadTestMode mode = FormatError; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "recv error"); + ASSERT_TRUE(findValue(status, "recv", value)); + ASSERT_STREQ(value.c_str(), "input stream error"); +} + +TEST_F(HDDMonitorTestSuite, tempConnectErrorTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "connect error"); + ASSERT_TRUE(findValue(status, "connect", value)); + ASSERT_STREQ(value.c_str(), strerror(ECONNREFUSED)); +} + +TEST_F(HDDMonitorTestSuite, tempInvalidDiskParameterTest) +{ + // Clear list + monitor_->clearTempParams(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "invalid disk parameter"); +} + +TEST_F(HDDMonitorTestSuite, tempNoSuchDeviceTest) +{ + // Add test file to list + monitor_->addTempParams("/dev/sdx", 55.0, 77.0); + + pthread_t th; + ThreadTestMode mode = Normal; + pthread_create(&th, nullptr, hdd_reader, &mode); + // Wait for thread started + ros::WallDuration(0.1).sleep(); + + // Publish topic + monitor_->update(); + + pthread_join(th, NULL); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Temperature", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "hdd_reader error"); + ASSERT_TRUE(findValue(status, "HDD 1: hdd_reader", value)); + ASSERT_STREQ(value.c_str(), strerror(ENOENT)); +} + +TEST_F(HDDMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.95); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(HDDMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(0.99); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(HDDMonitorTestSuite, usageDfErrorTest) +{ + // Symlink df1 to df + fs::create_symlink(exe_dir_ + "/df1", df_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("HDD Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "df error"); + ASSERT_TRUE(findValue(status, "df", value)); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "HDDMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/mem_monitor/free1.cpp b/utilities/system_monitor/test/src/mem_monitor/free1.cpp new file mode 100644 index 00000000000..8007b0c45e4 --- /dev/null +++ b/utilities/system_monitor/test/src/mem_monitor/free1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file free1.cpp + * @brief dummy free executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp b/utilities/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp new file mode 100644 index 00000000000..0a3bffbc059 --- /dev/null +++ b/utilities/system_monitor/test/src/mem_monitor/test_mem_monitor.cpp @@ -0,0 +1,264 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestMemMonitor : public MemMonitor +{ + friend class MemMonitorTestSuite; + +public: + TestMemMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : MemMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + void changeUsageError(float usage_error) { usage_error_ = usage_error; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class MemMonitorTestSuite : public ::testing::Test +{ +public: + MemMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + free_ = exe_dir_ + "/free"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string free_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestMemMonitor::diagCallback, monitor_.get()); + + // Remove dummy executable if exists + if (fs::exists(free_)) fs::remove(free_); + } + + void TearDown(void) + { + // Remove dummy executable if exists + if (fs::exists(free_)) fs::remove(free_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(MemMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.95); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(MemMonitorTestSuite, usageErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeUsageError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageError(0.99); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(MemMonitorTestSuite, usageFreeErrorTest) +{ + // Symlink free1 to free + fs::create_symlink(exe_dir_ + "/free1", free_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Memory Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "free error"); + ASSERT_TRUE(findValue(status, "free", value)); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "MemMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/net_monitor/test_net_monitor.cpp b/utilities/system_monitor/test/src/net_monitor/test_net_monitor.cpp new file mode 100644 index 00000000000..4bfb0a6f1c5 --- /dev/null +++ b/utilities/system_monitor/test/src/net_monitor/test_net_monitor.cpp @@ -0,0 +1,186 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* DOCKER_ENV = "/.dockerenv"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +class TestNetMonitor : public NetMonitor +{ + friend class NetMonitorTestSuite; + +public: + TestNetMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : NetMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void changeUsageWarn(float usage_warn) { usage_warn_ = usage_warn; } + + const std::vector getDeviceParams(void) { return device_params_; } + void clearDeviceParams(void) { device_params_.clear(); } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class NetMonitorTestSuite : public ::testing::Test +{ +public: + NetMonitorTestSuite() : nh_(""), pnh_("~") {} + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestNetMonitor::diagCallback, monitor_.get()); + } + + void TearDown(void) + { + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } +}; + +TEST_F(NetMonitorTestSuite, usageWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("Network Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Disabled since it depends on the system performing the test. + // TODO(icolwell): Re-enable or re-work test to focus on functionality of code rather + // than the system running the test. + + // // Verify warning + // { + // // Change warning level + // monitor_->changeUsageWarn(0.0); + // + // // Publish topic + // monitor_->update(); + // + // // Give time to publish + // ros::WallDuration(0.5).sleep(); + // ros::spinOnce(); + // + // // Verify + // DiagStatus status; + // ASSERT_TRUE(monitor_->findDiagStatus("Network Usage", status)); + // // Skip test if process runs inside docker + // // Don't know what interface should be monitored. + // if (!fs::exists(DOCKER_ENV)) ASSERT_EQ(status.level, DiagStatus::WARN); + // } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeUsageWarn(0.95); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Network Usage", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(NetMonitorTestSuite, usageInvalidDeviceParameterTest) +{ + // Clear list + monitor_->clearDeviceParams(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Network Usage", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "invalid device parameter"); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "NetMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/ntp_monitor/ntpdate1.cpp b/utilities/system_monitor/test/src/ntp_monitor/ntpdate1.cpp new file mode 100644 index 00000000000..c9057563f8d --- /dev/null +++ b/utilities/system_monitor/test/src/ntp_monitor/ntpdate1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file ntpdate1.cpp + * @brief dummy ntpdate executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp b/utilities/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp new file mode 100644 index 00000000000..a75b9f02899 --- /dev/null +++ b/utilities/system_monitor/test/src/ntp_monitor/test_ntp_monitor.cpp @@ -0,0 +1,289 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +static constexpr const char* DOCKER_ENV = "/.dockerenv"; + +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestNTPMonitor : public NTPMonitor +{ + friend class NTPMonitorTestSuite; + +public: + TestNTPMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : NTPMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + void changeOffsetWarn(float offset_warn) { offset_warn_ = offset_warn; } + void changeOffsetError(float offset_error) { offset_error_ = offset_error; } + + void setNtpdateExists(bool ntpdate_exists) { ntpdate_exists_ = ntpdate_exists; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class NTPMonitorTestSuite : public ::testing::Test +{ +public: + NTPMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + ntpdate_ = exe_dir_ + "/ntpdate"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string ntpdate_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestNTPMonitor::diagCallback, monitor_.get()); + + // Remove dummy executable if exists + if (fs::exists(ntpdate_)) fs::remove(ntpdate_); + } + + void TearDown(void) + { + // Remove dummy executable if exists + if (fs::exists(ntpdate_)) fs::remove(ntpdate_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(NTPMonitorTestSuite, offsetWarnTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeOffsetWarn(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::WARN); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeOffsetWarn(0.05); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + // Skip test if process runs inside docker + if (!fs::exists(DOCKER_ENV)) ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(NTPMonitorTestSuite, offsetErrorTest) +{ + // Verify normal behavior + { + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } + + // Verify warning + { + // Change warning level + monitor_->changeOffsetError(0.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + } + + // Verify normal behavior + { + // Change back to normal + monitor_->changeOffsetError(5.0); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(NTPMonitorTestSuite, offsetNtpdateNotFoundTest) +{ + // Set flag false + monitor_->setNtpdateExists(false); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "ntpdate error"); + ASSERT_TRUE(findValue(status, "ntpdate", value)); + ASSERT_STREQ(value.c_str(), "Command 'ntpdate' not found, but can be installed with: sudo apt install ntpdate"); +} + +TEST_F(NTPMonitorTestSuite, offsetNtpdateErrorTest) +{ + // Symlink ntpdate1 to ntpdate + fs::create_symlink(exe_dir_ + "/ntpdate1", ntpdate_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + ASSERT_TRUE(monitor_->findDiagStatus("NTP Offset", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "ntpdate error"); +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "NTPMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/process_monitor/echo1.cpp b/utilities/system_monitor/test/src/process_monitor/echo1.cpp new file mode 100644 index 00000000000..e83d3e1af1b --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/echo1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file echo1.cpp + * @brief dummy echo executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/process_monitor/sed1.cpp b/utilities/system_monitor/test/src/process_monitor/sed1.cpp new file mode 100644 index 00000000000..b7fd1af7a79 --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/sed1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sed1.cpp + * @brief dummy sed executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/process_monitor/sort1.cpp b/utilities/system_monitor/test/src/process_monitor/sort1.cpp new file mode 100644 index 00000000000..83285b82d8c --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/sort1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sort1.cpp + * @brief dummy sort executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/process_monitor/test_process_monitor.cpp b/utilities/system_monitor/test/src/process_monitor/test_process_monitor.cpp new file mode 100644 index 00000000000..3e602232b18 --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/test_process_monitor.cpp @@ -0,0 +1,356 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace bp = boost::process; +namespace fs = boost::filesystem; +using DiagStatus = diagnostic_msgs::DiagnosticStatus; + +char** argv_; + +class TestProcessMonitor : public ProcessMonitor +{ + friend class ProcessMonitorTestSuite; + +public: + TestProcessMonitor(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) : ProcessMonitor(nh, pnh) {} + + void diagCallback(const diagnostic_msgs::DiagnosticArray::ConstPtr& diag_msg) { array_ = *diag_msg; } + + int getNumOfProcs(void) const { return num_of_procs_; } + + void update(void) { updater_.force_update(); } + + const std::string removePrefix(const std::string &name) { return boost::algorithm::erase_all_copy(name, prefix_); } + + bool findDiagStatus(const std::string &name, DiagStatus& status) // NOLINT + { + for (int i = 0; i < array_.status.size(); ++i) + { + if (removePrefix(array_.status[i].name) == name) + { + status = array_.status[i]; + return true; + } + } + return false; + } + +private: + diagnostic_msgs::DiagnosticArray array_; + const std::string prefix_ = ros::this_node::getName().substr(1) + ": "; +}; + +class ProcessMonitorTestSuite : public ::testing::Test +{ +public: + ProcessMonitorTestSuite() : nh_(""), pnh_("~") + { + // Get directory of executable + const fs::path exe_path(argv_[0]); + exe_dir_ = exe_path.parent_path().generic_string(); + // Get dummy executable path + top_ = exe_dir_ + "/top"; + echo_ = exe_dir_ + "/echo"; + sed_ = exe_dir_ + "/sed"; + sort_ = exe_dir_ + "/sort"; + } + +protected: + ros::NodeHandle nh_, pnh_; + std::unique_ptr monitor_; + ros::Subscriber sub_; + std::string exe_dir_; + std::string top_; + std::string echo_; + std::string sed_; + std::string sort_; + + void SetUp(void) + { + monitor_ = std::make_unique(nh_, pnh_); + sub_ = nh_.subscribe("/diagnostics", 1000, &TestProcessMonitor::diagCallback, monitor_.get()); + + // Remove dummy executable if exists + if (fs::exists(top_)) fs::remove(top_); + if (fs::exists(echo_)) fs::remove(echo_); + if (fs::exists(sed_)) fs::remove(sed_); + if (fs::exists(sort_)) fs::remove(sort_); + } + + void TearDown(void) + { + // Remove dummy executable if exists + if (fs::exists(top_)) fs::remove(top_); + if (fs::exists(echo_)) fs::remove(echo_); + if (fs::exists(sed_)) fs::remove(sed_); + if (fs::exists(sort_)) fs::remove(sort_); + } + + bool findValue(const DiagStatus status, const std::string &key, std::string &value) // NOLINT + { + for (auto itr = status.values.begin(); itr != status.values.end(); ++itr) + { + if (itr->key == key) + { + value = itr->value; + return true; + } + } + return false; + } + + void modifyPath(void) + { + // Modify PATH temporarily + auto env = boost::this_process::environment(); + std::string new_path = env["PATH"].to_string(); + new_path.insert(0, (boost::format("%1%:") % exe_dir_).str()); + env["PATH"] = new_path; + } +}; + +TEST_F(ProcessMonitorTestSuite, tasksSummaryTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::OK); +} + +TEST_F(ProcessMonitorTestSuite, highLoadProcTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + for (int i = 0; i < monitor_->getNumOfProcs(); ++i) + { + ASSERT_TRUE(monitor_->findDiagStatus((boost::format("High-load Proc[%1%]") % i).str(), status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(ProcessMonitorTestSuite, highMemProcTest) +{ + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + for (int i = 0; i < monitor_->getNumOfProcs(); ++i) + { + ASSERT_TRUE(monitor_->findDiagStatus((boost::format("High-mem Proc[%1%]") % i).str(), status)); + ASSERT_EQ(status.level, DiagStatus::OK); + } +} + +TEST_F(ProcessMonitorTestSuite, topErrorTest) +{ + // Symlink top1 to top + fs::create_symlink(exe_dir_ + "/top1", top_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "top error"); + ASSERT_TRUE(findValue(status, "top", value)); + ASSERT_STREQ(value.c_str(), ""); + + for (int i = 0; i < monitor_->getNumOfProcs(); ++i) + { + ASSERT_TRUE(monitor_->findDiagStatus((boost::format("High-load Proc[%1%]") % i).str(), status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "top error"); + + ASSERT_TRUE(monitor_->findDiagStatus((boost::format("High-mem Proc[%1%]") % i).str(), status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "top error"); + } +} + +TEST_F(ProcessMonitorTestSuite, matchingPatternNotFoundTest) +{ + // Symlink top2 to top + fs::create_symlink(exe_dir_ + "/top2", top_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "matching pattern not found"); +} + +TEST_F(ProcessMonitorTestSuite, invalidFormatTest) +{ + // Symlink top3 to top + fs::create_symlink(exe_dir_ + "/top3", top_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "invalid format"); +} + +TEST_F(ProcessMonitorTestSuite, echoErrorTest) +{ + // Symlink sed1 to sed + fs::create_symlink(exe_dir_ + "/echo1", echo_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "echo error"); +} + +TEST_F(ProcessMonitorTestSuite, sedErrorTest) +{ + // Symlink sed1 to sed + fs::create_symlink(exe_dir_ + "/sed1", sed_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + ASSERT_TRUE(monitor_->findDiagStatus("Tasks Summary", status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "sed error"); +} + +TEST_F(ProcessMonitorTestSuite, sortErrorTest) +{ + // Symlink sort1 to sort + fs::create_symlink(exe_dir_ + "/sort1", sort_); + + // Modify PATH temporarily + modifyPath(); + + // Publish topic + monitor_->update(); + + // Give time to publish + ros::WallDuration(0.5).sleep(); + ros::spinOnce(); + + // Verify + DiagStatus status; + std::string value; + + for (int i = 0; i < monitor_->getNumOfProcs(); ++i) + { + ASSERT_TRUE(monitor_->findDiagStatus((boost::format("High-mem Proc[%1%]") % i).str(), status)); + ASSERT_EQ(status.level, DiagStatus::ERROR); + ASSERT_STREQ(status.message.c_str(), "sort error"); + } +} + +int main(int argc, char **argv) +{ + argv_ = argv; + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "ProcessMonitorTestNode"); + + return RUN_ALL_TESTS(); +} diff --git a/utilities/system_monitor/test/src/process_monitor/top1.cpp b/utilities/system_monitor/test/src/process_monitor/top1.cpp new file mode 100644 index 00000000000..c3cc1dfbe98 --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/top1.cpp @@ -0,0 +1,25 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file top1.cpp + * @brief dummy top executable to return error + */ + +int main(int argc, char** argv) +{ + return -1; +} diff --git a/utilities/system_monitor/test/src/process_monitor/top2.cpp b/utilities/system_monitor/test/src/process_monitor/top2.cpp new file mode 100644 index 00000000000..3ee69702f67 --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/top2.cpp @@ -0,0 +1,27 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file top2.cpp + * @brief dummy top executable to provide nothing + */ + +#include + +int main(int argc, char** argv) +{ + return 0; +} diff --git a/utilities/system_monitor/test/src/process_monitor/top3.cpp b/utilities/system_monitor/test/src/process_monitor/top3.cpp new file mode 100644 index 00000000000..1e6a6594290 --- /dev/null +++ b/utilities/system_monitor/test/src/process_monitor/top3.cpp @@ -0,0 +1,28 @@ +/* + * Copyright 2020 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file top3.cpp + * @brief dummy top executable to provide invalid output + */ + +#include + +int main(int argc, char** argv) +{ + printf("Tasks:"); + return 0; +} diff --git a/utilities/system_monitor/test/test_cpu_monitor.test b/utilities/system_monitor/test/test_cpu_monitor.test new file mode 100644 index 00000000000..a8ff5f9c7b2 --- /dev/null +++ b/utilities/system_monitor/test/test_cpu_monitor.test @@ -0,0 +1,3 @@ + + + diff --git a/utilities/system_monitor/test/test_gpu_monitor.test b/utilities/system_monitor/test/test_gpu_monitor.test new file mode 100644 index 00000000000..bd8858454bd --- /dev/null +++ b/utilities/system_monitor/test/test_gpu_monitor.test @@ -0,0 +1,3 @@ + + + diff --git a/utilities/system_monitor/test/test_hdd_monitor.test b/utilities/system_monitor/test/test_hdd_monitor.test new file mode 100644 index 00000000000..b7e4deb9aa6 --- /dev/null +++ b/utilities/system_monitor/test/test_hdd_monitor.test @@ -0,0 +1,6 @@ + + + + + + diff --git a/utilities/system_monitor/test/test_mem_monitor.test b/utilities/system_monitor/test/test_mem_monitor.test new file mode 100644 index 00000000000..d49de68ae93 --- /dev/null +++ b/utilities/system_monitor/test/test_mem_monitor.test @@ -0,0 +1,3 @@ + + + diff --git a/utilities/system_monitor/test/test_net_monitor.test b/utilities/system_monitor/test/test_net_monitor.test new file mode 100644 index 00000000000..250eb6a9a70 --- /dev/null +++ b/utilities/system_monitor/test/test_net_monitor.test @@ -0,0 +1,6 @@ + + + + + + diff --git a/utilities/system_monitor/test/test_ntp_monitor.test b/utilities/system_monitor/test/test_ntp_monitor.test new file mode 100644 index 00000000000..0459ad3a3b5 --- /dev/null +++ b/utilities/system_monitor/test/test_ntp_monitor.test @@ -0,0 +1,6 @@ + + + + + + diff --git a/utilities/system_monitor/test/test_process_monitor.test b/utilities/system_monitor/test/test_process_monitor.test new file mode 100644 index 00000000000..2d00fcb3c7f --- /dev/null +++ b/utilities/system_monitor/test/test_process_monitor.test @@ -0,0 +1,3 @@ + + + From 9996977ed8900550a05f6a23c2b44b6d9108e146 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Mon, 5 Jul 2021 16:58:50 -0400 Subject: [PATCH 05/23] Updated noetic/develop tags (#159) * Update build scripts to point to noetic/develop * Update tags for noetic develop * Fix build script for -d argument * Update job and load limits in CI * Resolve docker build issues --- .circleci/config.yml | 4 +- Dockerfile | 6 +- autoware/ros/carma_autoware_build | 86 ------------------- .../tvm_utility}/COLCON_IGNORE | 0 docker/build-image.sh | 6 +- docker/checkout.bash | 6 +- docker/install.sh | 14 ++- hooks/pre_build | 4 +- 8 files changed, 24 insertions(+), 102 deletions(-) delete mode 100755 autoware/ros/carma_autoware_build rename {core_perception/ndt_gpu => common/tvm_utility}/COLCON_IGNORE (100%) diff --git a/.circleci/config.yml b/.circleci/config.yml index 95c51ea219a..d18d6b1e168 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -52,7 +52,9 @@ jobs: command: | source ${INIT_ENV} cd autoware.ai/ - build-wrapper-linux-x86-64 --out-dir /opt/carma/bw-output ./autoware/ros/carma_autoware_build -k -b "-DCMAKE_CXX_FLAGS=${COVERAGE_FLAGS} -DCMAKE_C_FLAGS=${COVERAGE_FLAGS} -DCMAKE_BUILD_TYPE=Debug" + export ROS_PARALLEL_JOBS='-j2 -l2' # try to reduce memory consumption on build + export AUTOWARE_COMPILE_WITH_CUDA=1 + build-wrapper-linux-x86-64 --out-dir /opt/carma/bw-output colcon build --install-base ./ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Debug -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=${COVERAGE_FLAGS} -DCMAKE_C_FLAGS=${COVERAGE_FLAGS} # The free version of Circle CI does not have enough memory to run tests in this repo # The following run statement can be used as a starting point for future implementation of automated unit tests # - run: diff --git a/Dockerfile b/Dockerfile index 1067e737363..bc61fe3eeda 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,11 +1,11 @@ -FROM usdotfhwastoldev/carma-base:develop as build +FROM usdotfhwastoldev/carma-base:noetic-develop as build RUN sudo apt-get install -y ros-noetic-velodyne-pcl COPY --chown=carma . /home/carma/autoware.ai RUN /home/carma/autoware.ai/docker/checkout.bash RUN ./home/carma/autoware.ai/docker/install.sh -FROM usdotfhwastoldev/carma-base:develop +FROM usdotfhwastoldev/carma-base:noetic-develop ARG BUILD_DATE="NULL" ARG VCS_REF="NULL" @@ -21,4 +21,4 @@ LABEL org.label-schema.vcs-url="https://github.com/usdot-fhwa-stol/autoware.ai" LABEL org.label-schema.vcs-ref=${VCS_REF} LABEL org.label-schema.build-date=${BUILD_DATE} -COPY --chown=carma --from=build /home/carma/autoware.ai/ros/install /opt/autoware.ai/ros/install \ No newline at end of file +COPY --chown=carma --from=build /opt/autoware.ai/ros/install /opt/autoware.ai/ros/install \ No newline at end of file diff --git a/autoware/ros/carma_autoware_build b/autoware/ros/carma_autoware_build deleted file mode 100755 index d945c2db5d6..00000000000 --- a/autoware/ros/carma_autoware_build +++ /dev/null @@ -1,86 +0,0 @@ -#!/bin/bash - -# Copyright (C) 2018-2021 LEIDOS. -# -# Licensed under the Apache License, Version 2.0 (the "License"); you may not -# use this file except in compliance with the License. You may obtain a copy of -# the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT -# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the -# License for the specific language governing permissions and limitations under -# the License. - -# This scipt builds the Autoware.ai components used by the CARMA Platform - -usage() { - echo "USAGE carma_autoware_build [OPTION] - carma_autoware_build will build the Autoware.ai components used by the CARMA Platform - - -a Path to Autoware.ai workspace. If this is not specified it is assumed the current workspace will work - -b Replace CMake build arguments for Autoware.ai's build - -k Use catkin_make_isolated instead of colcon. Note: This will limit job count to 1 - -h Print help - "; -} - - -# Default environment variables -autoware_src="$(realpath .)" -autoware_build_args="" -use_catkin=false -# The list of packages which are required by carma from autoware -AUTOWARE_PACKAGE_SELECTION="autoware_msgs map_tools lidar_localizer map_file deadreckoner points_downsampler points_preprocessor lane_planner waypoint_maker autoware_config_msgs as waypoint_planner pure_pursuit twist_filter twist_gate lanelet2_extension vision_darknet_detect vision_beyond_track lidar_euclidean_cluster_detect range_vision_fusion imm_ukf_pda_track naive_motion_predict ekf_localizer detected_objects_visualizer calibration_publisher mpc_follower autoware_camera_lidar_calibrator multi_lidar_calibrator runtime_manager" - -# Read Options -while getopts a:kthb: option -do - case "${option}" - in - a) autoware_src="$(realpath ${OPTARG})";; - b) autoware_build_args=${OPTARG};; - k) use_catkin=true;; - h) usage; exit 0;; - \?) echo "Unknown option: -$OPTARG" >&2; exit 1;; - :) echo "Missing option argument for -$OPTARG" >&2; exit 1;; - *) echo "Unimplemented option: -$OPTARG" >&2; exit 1;; - - esac -done - -echo " -Attempting to build Autoware -Autoware Source Dir: ${autoware_src} -" - - -echo "Building Autoware required packages ${AUTOWARE_PACKAGE_SELECTION}" - -cd ${autoware_src} - -if [[ -z ${autoware_build_args} ]]; then - if [[ "${use_catkin}" = true ]]; then - echo "Building release with catkin_make_isolated. NOTE: Formal releases should use colcon" - catkin_make_isolated --source . --install --install-space ./ros/install -j1 --only-pkg-with-deps "${AUTOWARE_PACKAGE_SELECTION}" - else - # Default Build Behavior - ./autoware/ros/colcon_release --executor sequential --install-base ./ros/install --packages-up-to ${AUTOWARE_PACKAGE_SELECTION} - fi -else - if [[ "${use_catkin}" = true ]]; then - echo "Building with CMake args: ${autoware_build_args} and with catkin_make_isolated. NOTE: Formal releases should use colcon" - catkin_make_isolated --source . --install --install-space ./ros/install -j1 --only-pkg-with-deps "${AUTOWARE_PACKAGE_SELECTION}" --cmake-args "${autoware_build_args}" - else - echo "Building with CMake args: ${autoware_build_args}" - echo "Build with CUDA" - AUTOWARE_COMPILE_WITH_CUDA=0 colcon build --cmake-args "${autoware_build_args}" --executor sequential --install-base ./ros/install --packages-up-to ${AUTOWARE_PACKAGE_SELECTION} - fi -fi - -source ./ros/install/setup.bash -echo "Autoware built successfuly. Binaries sourced from $(realpath ./ros/install/setup.bash)" - -echo "Autoware Build Complete" diff --git a/core_perception/ndt_gpu/COLCON_IGNORE b/common/tvm_utility/COLCON_IGNORE similarity index 100% rename from core_perception/ndt_gpu/COLCON_IGNORE rename to common/tvm_utility/COLCON_IGNORE diff --git a/docker/build-image.sh b/docker/build-image.sh index e916e8bd894..56f5e158bc3 100755 --- a/docker/build-image.sh +++ b/docker/build-image.sh @@ -40,7 +40,7 @@ while [[ $# -gt 0 ]]; do ;; -d|--develop) USERNAME=usdotfhwastoldev - COMPONENT_VERSION_STRING=develop + COMPONENT_VERSION_STRING=noetic-develop shift ;; esac @@ -54,8 +54,8 @@ echo "Building docker image for $IMAGE version: $COMPONENT_VERSION_STRING" echo "Final image name: $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING" cd .. -if [[ $COMPONENT_VERSION_STRING = "develop" ]]; then - sed "s|usdotfhwastoldev/|$USERNAME/|g; s|usdotfhwastolcandidate/|$USERNAME/|g; s|usdotfhwastol/|$USERNAME/|g; s|:*[0-9].*[0-9].*[0-9]|:$COMPONENT_VERSION_STRING|g" \ +if [[ $COMPONENT_VERSION_STRING = "noetic-develop" ]]; then + sed "s|usdotfhwastoldev/|$USERNAME/|g; s|usdotfhwastolcandidate/|$USERNAME/|g; s|usdotfhwastol/|$USERNAME/|g; s|:*[0-9].*[0-9].*[0-9]|:$COMPONENT_VERSION_STRING|g; s|checkout.bash|checkout.bash -d|g" \ Dockerfile | docker build -f - --no-cache -t $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING \ --build-arg VERSION="$COMPONENT_VERSION_STRING" \ --build-arg VCS_REF=`git rev-parse --short HEAD` \ diff --git a/docker/checkout.bash b/docker/checkout.bash index 3e0e47f4524..b34b0c48ed7 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -21,7 +21,7 @@ while [[ $# -gt 0 ]]; do arg="$1" case $arg in -d|--develop) - BRANCH=develop + BRANCH=noetic/develop shift ;; -r|--root) @@ -34,8 +34,8 @@ done cd ${dir}/autoware.ai -if [[ "$BRANCH" = "carma-develop" ]]; then - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/develop +if [[ "$BRANCH" = "noetic/develop" ]]; then + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch $BRANCH else git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/release fi diff --git a/docker/install.sh b/docker/install.sh index ee21cc39f54..1b849d42f62 100755 --- a/docker/install.sh +++ b/docker/install.sh @@ -14,9 +14,15 @@ # License for the specific language governing permissions and limitations under # the License. +# Source environment variables source /home/carma/.base-image/init-env.sh -autoware_src="/home/carma/autoware.ai" -cd ${autoware_src} -#build autoware -./autoware/ros/carma_autoware_build -a ${autoware_src} -b "-DCMAKE_BUILD_TYPE=Release" +# Enter source directory +cd /home/carma/autoware.ai + +# Build with CUDA +echo "Build with CUDA" +sudo mkdir /opt/autoware.ai # Create install directory +sudo chown carma /opt/autoware.ai # Set owner to expose permissions for build +sudo chgrp carma /opt/autoware.ai # Set group to expose permissions for build +AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --install-base /opt/autoware.ai/ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=-Wall -DCMAKE_C_FLAGS=-Wall diff --git a/hooks/pre_build b/hooks/pre_build index 4966ea38cd6..03e70de7fe4 100644 --- a/hooks/pre_build +++ b/hooks/pre_build @@ -1,8 +1,8 @@ #!/bin/bash -if [[ "$SOURCE_BRANCH" = "carma-develop" ]]; then +if [[ "$SOURCE_BRANCH" = "noetic/develop" ]]; then # update image dependencies - sed -i "s|usdotfhwastol/|usdotfhwastoldev/|g; s|:[0-9]*\.[0-9]*\.[0-9]*|:develop|g" \ + sed -i "s|usdotfhwastol/|usdotfhwastoldev/|g; s|:[0-9]*\.[0-9]*\.[0-9]*|:noetic-develop|g" \ Dockerfile elif [[ "$SOURCE_BRANCH" =~ ^release/.*$ ]]; then # update image dependencies From 0791333055315fe1a976a36ad48345cec9ddefac Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Wed, 7 Jul 2021 18:05:15 -0400 Subject: [PATCH 06/23] Add pacmod_msgs dependancy to autoware.ai image for use in carma-platform and ssc images (#161) * Add pacmod_msgs dependancy to autoware.ai docker build --- docker/checkout.bash | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docker/checkout.bash b/docker/checkout.bash index b34b0c48ed7..0884fea8a73 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -39,3 +39,6 @@ if [[ "$BRANCH" = "noetic/develop" ]]; then else git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/release fi + +# Required to build pacmod_msgs +git clone https://github.com/astuff/astuff_sensor_msgs.git ${dir}/src/astuff_sensor_msgs --branch 3.0.1 From 1d2bffdbee1c4fed0b998d7cb6f450081dc83daa Mon Sep 17 00:00:00 2001 From: Patrick Musau Date: Wed, 7 Jul 2021 17:06:06 -0500 Subject: [PATCH 07/23] Feature/lanelet2 autoware update (#160) * lanelet and minimal autoware update Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * maintain c++ 14 Signed-off-by: Patrick Musau * revert lanelet CMakelists.txt to ensure correct catkin imports * update autoware packages * revert back * revert ekf_localizer except tf_rate, broadcast, tf_rate * let map be configurable * new package upgrades * unit test edits --- .../health_aggregator/health_aggregator.h | 1 - .../autoware_health_checker/health_aggregator/status_monitor.h | 1 - .../autoware_health_checker/health_checker/diag_buffer.h | 1 - .../autoware_health_checker/health_checker/param_manager.h | 1 - .../autoware_health_checker/health_checker/rate_checker.h | 1 - .../autoware_health_checker/health_checker/value_manager.h | 1 - .../system_status_subscriber/system_status_subscriber.h | 1 - .../include/libwaypoint_follower/test_libwaypoint_follower.h | 1 + common/libwaypoint_follower/src/pure_pursuit.cpp | 1 + common/ros_observer/src/ros_observer.cpp | 1 - common/tvm_utility/include/tvm_utility/pipeline.h | 1 + common/vector_map/lib/vector_map/vector_map.cpp | 1 + core_planning/twist_gate/src/twist_gate.cpp | 2 +- .../src/velocity_set_lanelet2/velocity_set_lanelet2.cpp | 1 + 14 files changed, 6 insertions(+), 9 deletions(-) diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/health_aggregator.h b/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/health_aggregator.h index 9feca7cbbc4..e47ff38fdf7 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/health_aggregator.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/health_aggregator.h @@ -39,7 +39,6 @@ // headers in STL #include -#include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/status_monitor.h b/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/status_monitor.h index 1f02c25d69d..e2b74c16ae5 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/status_monitor.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_aggregator/status_monitor.h @@ -18,7 +18,6 @@ #include #include -#include #include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_checker/diag_buffer.h b/common/autoware_health_checker/include/autoware_health_checker/health_checker/diag_buffer.h index e41fd325f4a..fe8e50ee44b 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_checker/diag_buffer.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_checker/diag_buffer.h @@ -25,7 +25,6 @@ // headers in STL #include -#include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_checker/param_manager.h b/common/autoware_health_checker/include/autoware_health_checker/health_checker/param_manager.h index 45383c89ad1..8de8e5007ee 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_checker/param_manager.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_checker/param_manager.h @@ -19,7 +19,6 @@ #include #include -#include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_checker/rate_checker.h b/common/autoware_health_checker/include/autoware_health_checker/health_checker/rate_checker.h index fd60bfcb33f..2cf6894ad1b 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_checker/rate_checker.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_checker/rate_checker.h @@ -23,7 +23,6 @@ #include // headers in STL -#include #include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/health_checker/value_manager.h b/common/autoware_health_checker/include/autoware_health_checker/health_checker/value_manager.h index b3fba76a343..45ca10551f3 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/health_checker/value_manager.h +++ b/common/autoware_health_checker/include/autoware_health_checker/health_checker/value_manager.h @@ -29,7 +29,6 @@ // headers in STL #include -#include #include #include diff --git a/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h b/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h index d0a435f1046..42f14b93543 100644 --- a/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h +++ b/common/autoware_health_checker/include/autoware_health_checker/system_status_subscriber/system_status_subscriber.h @@ -28,7 +28,6 @@ // headers in STL #include -#include #include #include diff --git a/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h b/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h index bd2e4be3f21..8b0dbca8155 100644 --- a/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h +++ b/common/libwaypoint_follower/include/libwaypoint_follower/test_libwaypoint_follower.h @@ -18,6 +18,7 @@ #define LIBWAYPOINT_FOLLOWER_TEST_LIBWAYPOINT_FOLLOWER_H #include +#include #include "libwaypoint_follower/libwaypoint_follower.h" enum class CoordinateResult diff --git a/common/libwaypoint_follower/src/pure_pursuit.cpp b/common/libwaypoint_follower/src/pure_pursuit.cpp index 5edb0b721f8..8ccd4f28501 100644 --- a/common/libwaypoint_follower/src/pure_pursuit.cpp +++ b/common/libwaypoint_follower/src/pure_pursuit.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include diff --git a/common/ros_observer/src/ros_observer.cpp b/common/ros_observer/src/ros_observer.cpp index a8d943f2f2b..e398650971c 100644 --- a/common/ros_observer/src/ros_observer.cpp +++ b/common/ros_observer/src/ros_observer.cpp @@ -16,7 +16,6 @@ */ #include -#include #include #include #include diff --git a/common/tvm_utility/include/tvm_utility/pipeline.h b/common/tvm_utility/include/tvm_utility/pipeline.h index 0c199bab09e..e0ef0d137f9 100644 --- a/common/tvm_utility/include/tvm_utility/pipeline.h +++ b/common/tvm_utility/include/tvm_utility/pipeline.h @@ -21,6 +21,7 @@ #include #include #include +#include #include #include diff --git a/common/vector_map/lib/vector_map/vector_map.cpp b/common/vector_map/lib/vector_map/vector_map.cpp index 6602cbdde20..25ee33f9afc 100644 --- a/common/vector_map/lib/vector_map/vector_map.cpp +++ b/common/vector_map/lib/vector_map/vector_map.cpp @@ -20,6 +20,7 @@ #include #include #include +#include namespace vector_map { diff --git a/core_planning/twist_gate/src/twist_gate.cpp b/core_planning/twist_gate/src/twist_gate.cpp index 3c785a70216..6ef01d21fc9 100644 --- a/core_planning/twist_gate/src/twist_gate.cpp +++ b/core_planning/twist_gate/src/twist_gate.cpp @@ -31,7 +31,7 @@ #include "twist_gate/twist_gate.h" #include -#include +#include #include #include diff --git a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp index 560d7e9a134..41126bf8cf1 100644 --- a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp +++ b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include From 506bd3d132a028da830bbc4cc2cb635845485bce Mon Sep 17 00:00:00 2001 From: Adam Morrissett Date: Thu, 8 Jul 2021 15:04:15 -0400 Subject: [PATCH 08/23] 1339 - Add tf2_geometry_msgs as package dependency (#164) Previously, the tf2_geometry_msgs package was unlisted, which prevented the amathutils_lib package from building unless tf2_geometry_msgs was already installed. common/amathutils_lib/package.xml * add tf2_geometry_msgs as package dependency common/amathutils_lib/CMakeLists.txt * add tf2_geometry_msgs as package dependency --- common/amathutils_lib/CMakeLists.txt | 2 ++ common/amathutils_lib/package.xml | 1 + 2 files changed, 3 insertions(+) diff --git a/common/amathutils_lib/CMakeLists.txt b/common/amathutils_lib/CMakeLists.txt index 80160794267..f567196fbee 100644 --- a/common/amathutils_lib/CMakeLists.txt +++ b/common/amathutils_lib/CMakeLists.txt @@ -22,6 +22,7 @@ find_package(catkin REQUIRED COMPONENTS roslint tf tf2 + tf2_geometry_msgs ) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") @@ -33,6 +34,7 @@ catkin_package( autoware_msgs tf tf2 + tf2_geometry_msgs ) include_directories( diff --git a/common/amathutils_lib/package.xml b/common/amathutils_lib/package.xml index 1266baba1a2..6159e5bd279 100644 --- a/common/amathutils_lib/package.xml +++ b/common/amathutils_lib/package.xml @@ -15,6 +15,7 @@ roscpp roslint tf2 + tf2_geometry_msgs tf eigen From 72d995c2f1f9034667e4bea558d88d725443c162 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Thu, 15 Jul 2021 11:43:48 -0400 Subject: [PATCH 09/23] Fix develop tags for autoware image (#163) * Update build scripts to point to noetic/develop * Update tags for noetic develop * Fix build script for -d argument * Update job and load limits in CI * Resolve docker build issues * Add pacmod_msgs dependancy to autoware.ai docker build * ci test * Correct tag in circle ci config * Fix checkout.bash for circle ci on noetic/develop * Fix build args in ci --- .circleci/config.yml | 4 ++-- docker/checkout.bash | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index d18d6b1e168..1b706937a10 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -28,7 +28,7 @@ jobs: # Pull docker image from docker hub # XTERM used for better catkin_make output docker: - - image: usdotfhwastoldev/carma-base:develop + - image: usdotfhwastoldev/carma-base:noetic-develop user: carma environment: TERM: xterm @@ -54,7 +54,7 @@ jobs: cd autoware.ai/ export ROS_PARALLEL_JOBS='-j2 -l2' # try to reduce memory consumption on build export AUTOWARE_COMPILE_WITH_CUDA=1 - build-wrapper-linux-x86-64 --out-dir /opt/carma/bw-output colcon build --install-base ./ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Debug -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=${COVERAGE_FLAGS} -DCMAKE_C_FLAGS=${COVERAGE_FLAGS} + build-wrapper-linux-x86-64 --out-dir /opt/carma/bw-output colcon build --install-base ./ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Debug -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS="${COVERAGE_FLAGS}" -DCMAKE_C_FLAGS="${COVERAGE_FLAGS}" # The free version of Circle CI does not have enough memory to run tests in this repo # The following run statement can be used as a starting point for future implementation of automated unit tests # - run: diff --git a/docker/checkout.bash b/docker/checkout.bash index 0884fea8a73..deb6c1e0f64 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -37,7 +37,7 @@ cd ${dir}/autoware.ai if [[ "$BRANCH" = "noetic/develop" ]]; then git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch $BRANCH else - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/release + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/develop fi # Required to build pacmod_msgs From a4d4ffa22c6682b2f9ec2d1eaf0358903fa3ae8d Mon Sep 17 00:00:00 2001 From: Adam Morrissett <22103567+adamlm@users.noreply.github.com> Date: Tue, 3 Aug 2021 14:53:36 -0400 Subject: [PATCH 10/23] Remove `COLCON_IGNORE` from `vector_map_msgs` (#169) * 1339 - Add tf2_geometry_msgs as package dependency Previously, the tf2_geometry_msgs package was unlisted, which prevented the amathutils_lib package from building unless tf2_geometry_msgs was already installed. common/amathutils_lib/package.xml * add tf2_geometry_msgs as package dependency common/amathutils_lib/CMakeLists.txt * add tf2_geometry_msgs as package dependency * 1380 - Remove COLCON_IGNORE from vector_map_msgs The COLCON_IGNORE file prevented colcon (and catkin_make) from building the vector_map_msgs package, which is a descendant dependency for the map_file package. This prevented the map_file package from being built from source. See issue usdot-fhwa-stol/carma-platform#1380 messages/vector_map_msgs/COLCON_IGNORE * remove file so package will be built from source when needed --- messages/vector_map_msgs/COLCON_IGNORE | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 messages/vector_map_msgs/COLCON_IGNORE diff --git a/messages/vector_map_msgs/COLCON_IGNORE b/messages/vector_map_msgs/COLCON_IGNORE deleted file mode 100644 index e69de29bb2d..00000000000 From fc128a2880ac3307ae19e94ca7bc360adbe8402b Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Fri, 24 Sep 2021 15:36:31 -0400 Subject: [PATCH 11/23] Refactor lanelet2 extension (#174) * Initial refactor of lanelet2_extension to remove ros dependency * Resolve build errors in lanelet2 extension * Split out package can build * Update remaining autoware packages to support lanelet2_extension refactor * Resolve build errors * git try fix * revert change * Add comment to explain c++17 conditional --- .../CMakeLists.txt | 123 +++++++++++++ .../autoware_lanelet2_ros_interface/README.md | 75 ++++++++ .../docs/lanelet2_format_extension.md | 161 ++++++++++++++++++ .../utility/internal/query.tpp | 2 +- .../utility/message_conversion.h | 6 +- .../utility/query.h | 6 +- .../utility/utilities.h | 6 +- .../visualization/visualization.h | 8 +- .../lib/message_conversion.cpp | 2 +- .../lib/query.cpp | 4 +- .../lib/utilities.cpp | 2 +- .../lib/visualization.cpp | 6 +- .../package.xml | 31 ++++ .../src/sample_code.cpp | 2 +- .../src/validation.cpp | 2 +- .../test/resources/test_map.osm | 105 ++++++++++++ .../resources/test_map_nogeoreference.osm | 88 ++++++++++ .../test/resources/test_map_v.osm | 88 ++++++++++ .../test/resources/test_map_value.osm | 89 ++++++++++ .../test/src/test_message_conversion.cpp | 4 +- .../test/src/test_query.cpp | 4 +- .../test/src/test_utilities.cpp | 4 +- .../test/test_message_conversion.test | 5 + .../test/test_query.test | 5 + .../test/test_utilities.test | 5 + common/lanelet2_extension/CMakeLists.txt | 63 +++---- common/lanelet2_extension/README.md | 24 --- .../lanelet2_extension/logging/logger.h | 49 ++++++ .../autoware_traffic_light.h | 8 - .../lib/CarmaUSTrafficRules.cpp | 12 +- .../lib/DigitalMinimumGap.cpp | 1 - .../lib/autoware_traffic_light.cpp | 14 +- .../lanelet2_extension/lib/mgrs_projector.cpp | 12 +- common/lanelet2_extension/package.xml | 11 +- .../test/src/test_local_projector.cpp | 2 +- .../test/src/test_projector.cpp | 3 +- .../test/src/test_regulatory_elements.cpp | 3 +- .../test/test_message_conversion.test | 5 - .../test/test_projector.test | 5 - .../lanelet2_extension/test/test_query.test | 5 - .../test/test_regulatory_elements.test | 5 - .../test/test_utilities.test | 5 - common/map_file/CMakeLists.txt | 1 + .../lanelet2_map_loader.cpp | 4 +- .../lanelet2_map_visualization.cpp | 6 +- common/map_file/package.xml | 1 + common/object_map/CMakeLists.txt | 1 + .../wayarea2grid_lanelet2.h | 6 +- common/object_map/package.xml | 1 + .../imm_ukf_pda_track/CMakeLists.txt | 1 + .../imm_ukf_pda_lanelet2.h | 6 +- core_perception/imm_ukf_pda_track/package.xml | 1 + .../trafficlight_recognizer/CMakeLists.txt | 1 + .../feat_proj_lanelet2_core.h | 2 +- .../feat_proj_lanelet2_core.cpp | 6 +- .../trafficlight_recognizer/package.xml | 1 + .../costmap_generator/CMakeLists.txt | 1 + .../costmap_generator_lanelet2.h | 2 +- .../costmap_generator_lanelet2.cpp | 4 +- core_planning/costmap_generator/package.xml | 1 + core_planning/decision_maker/CMakeLists.txt | 2 + .../decision_maker_node_callback.cpp | 6 +- core_planning/decision_maker/package.xml | 1 + .../test/src/test_node_lanelet2_functions.cpp | 2 +- core_planning/lane_planner/CMakeLists.txt | 1 + .../lane_rule_lanelet2/lane_rule_lanelet2.cpp | 4 +- core_planning/lane_planner/package.xml | 2 +- .../ll2_global_planner/CMakeLists.txt | 1 + core_planning/ll2_global_planner/package.xml | 1 + .../src/ll2_global_planner_nodelet.cpp | 2 +- core_planning/waypoint_planner/CMakeLists.txt | 1 + core_planning/waypoint_planner/package.xml | 1 + .../velocity_set_lanelet2.cpp | 6 +- 73 files changed, 948 insertions(+), 188 deletions(-) create mode 100644 common/autoware_lanelet2_ros_interface/CMakeLists.txt create mode 100644 common/autoware_lanelet2_ros_interface/README.md create mode 100644 common/autoware_lanelet2_ros_interface/docs/lanelet2_format_extension.md rename common/{lanelet2_extension/include/lanelet2_extension => autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface}/utility/internal/query.tpp (99%) rename common/{lanelet2_extension/include/lanelet2_extension => autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface}/utility/message_conversion.h (93%) rename common/{lanelet2_extension/include/lanelet2_extension => autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface}/utility/query.h (97%) rename common/{lanelet2_extension/include/lanelet2_extension => autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface}/utility/utilities.h (92%) rename common/{lanelet2_extension/include/lanelet2_extension => autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface}/visualization/visualization.h (95%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/lib/message_conversion.cpp (98%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/lib/query.cpp (99%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/lib/utilities.cpp (99%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/lib/visualization.cpp (98%) create mode 100644 common/autoware_lanelet2_ros_interface/package.xml rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/src/sample_code.cpp (98%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/src/validation.cpp (98%) create mode 100644 common/autoware_lanelet2_ros_interface/test/resources/test_map.osm create mode 100644 common/autoware_lanelet2_ros_interface/test/resources/test_map_nogeoreference.osm create mode 100644 common/autoware_lanelet2_ros_interface/test/resources/test_map_v.osm create mode 100644 common/autoware_lanelet2_ros_interface/test/resources/test_map_value.osm rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/test/src/test_message_conversion.cpp (97%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/test/src/test_query.cpp (98%) rename common/{lanelet2_extension => autoware_lanelet2_ros_interface}/test/src/test_utilities.cpp (99%) create mode 100644 common/autoware_lanelet2_ros_interface/test/test_message_conversion.test create mode 100644 common/autoware_lanelet2_ros_interface/test/test_query.test create mode 100644 common/autoware_lanelet2_ros_interface/test/test_utilities.test create mode 100644 common/lanelet2_extension/include/lanelet2_extension/logging/logger.h delete mode 100644 common/lanelet2_extension/test/test_message_conversion.test delete mode 100644 common/lanelet2_extension/test/test_projector.test delete mode 100644 common/lanelet2_extension/test/test_query.test delete mode 100644 common/lanelet2_extension/test/test_regulatory_elements.test delete mode 100644 common/lanelet2_extension/test/test_utilities.test diff --git a/common/autoware_lanelet2_ros_interface/CMakeLists.txt b/common/autoware_lanelet2_ros_interface/CMakeLists.txt new file mode 100644 index 00000000000..a52d6e5db02 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/CMakeLists.txt @@ -0,0 +1,123 @@ +cmake_minimum_required(VERSION 2.8.11) +project(autoware_lanelet2_ros_interface) + +# +#- Modified to install add CARMA regulatory elements to build +# - 2/19/2019 +# - Michael McConnell +# + +set(CMAKE_CXX_FLAGS "-std=c++17 -fext-numeric-literals") + +find_package(PkgConfig) +find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h + PATH_SUFFIXES GeographicLib + ) +set(GeographicLib_INCLUDE_DIRS ${GeographicLib_INCLUDE_DIR}) + +find_library(GeographicLib_LIBRARIES + NAMES Geographic +) + +find_library(PUGIXML_LIBRARIES + NAMES pugixml +) + +find_path(PUGIXML_INCLUDE_DIRS + NAMES pugixml.hpp + PATH_SUFFIXES pugixml +) + +find_package(autoware_build_flags REQUIRED) + +find_package(PROJ4 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + amathutils_lib + roscpp + lanelet2_core + lanelet2_io + lanelet2_maps + lanelet2_projection + lanelet2_routing + lanelet2_traffic_rules + lanelet2_validation + lanelet2_extension + autoware_lanelet2_msgs + autoware_msgs + geometry_msgs + visualization_msgs + roslint +) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++17") +roslint_cpp() + +catkin_package( + INCLUDE_DIRS include + LIBRARIES autoware_lanelet2_ros_interface_lib + CATKIN_DEPENDS amathutils_lib roscpp lanelet2_core lanelet2_io lanelet2_maps lanelet2_projection lanelet2_routing lanelet2_traffic_rules lanelet2_validation autoware_lanelet2_msgs autoware_msgs geometry_msgs visualization_msgs lanelet2_extension +) + +include_directories( + include + ${GeographicLib_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${PUGIXML_INCLUDE_DIRS} + ${PROJ4_INCLUDE_DIRS} +) + +add_definitions (${GeographicLib_DEFINITIONS}) + +add_library( autoware_lanelet2_ros_interface_lib + lib/message_conversion.cpp + lib/query.cpp + lib/utilities.cpp + lib/visualization.cpp +) + +add_dependencies(autoware_lanelet2_ros_interface_lib + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) + +target_link_libraries(autoware_lanelet2_ros_interface_lib + ${catkin_LIBRARIES} + ${GeographicLib_LIBRARIES} + ${PROJ4_LIBRARIES} +) + +add_executable(autoware_lanelet2_ros_interface_sample src/sample_code.cpp) +add_dependencies(autoware_lanelet2_ros_interface_sample ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(autoware_lanelet2_ros_interface_sample + ${catkin_LIBRARIES} + autoware_lanelet2_ros_interface_lib +) + +add_executable(autoware_lanelet2_validation src/validation.cpp) +add_dependencies(autoware_lanelet2_validation ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(autoware_lanelet2_validation + ${catkin_LIBRARIES} + ${PUGIXML_LIBRAREIS} + autoware_lanelet2_ros_interface_lib +) + +install(TARGETS autoware_lanelet2_ros_interface_lib autoware_lanelet2_ros_interface_sample autoware_lanelet2_validation + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) + +if(CATKIN_ENABLE_TESTING) + roslint_add_test() + find_package(rostest REQUIRED) +add_rostest_gtest(message_conversion-test test/test_message_conversion.test test/src/test_message_conversion.cpp) +target_link_libraries(message_conversion-test ${catkin_LIBRARIES} autoware_lanelet2_ros_interface_lib) +add_rostest_gtest(query-test test/test_query.test test/src/test_query.cpp) +target_link_libraries(query-test ${catkin_LIBRARIES} autoware_lanelet2_ros_interface_lib) +add_rostest_gtest(utilities-test test/test_utilities.test test/src/test_utilities.cpp) +target_link_libraries(utilities-test ${catkin_LIBRARIES} autoware_lanelet2_ros_interface_lib) + +endif() diff --git a/common/autoware_lanelet2_ros_interface/README.md b/common/autoware_lanelet2_ros_interface/README.md new file mode 100644 index 00000000000..2c1a1b14bc4 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/README.md @@ -0,0 +1,75 @@ +# autoware_lanelet2_ros_interface package +This package contains external library for Lanelet2 and is meant to ease the use of Lanelet2 in CARMA and Autoware. + +## CARMA Lanelet2 OSM File Format Changes + +By default Lanelet2 supports a modified version of the OpenStreetMaps (OSM) file format to describe its roadways. See [here](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_maps/README.md) for an introduction. Part of this standard describes how road regulations are defined by interpreting tags on various Lanelet2 primitives. In addition, regulatory elements also fill a similar role. Unfortunately, this creates a confusing situation where some regulations are tied intrinsically to the physical markings on the road. For example, a double yellow line could never be crossed even if nearby signs instructed the user to do so around a work zone. To resolve this, while also preserving the description of the physical markings on the road, CARMA Platform supports an additional set of [regulatory elements](./docs/RegulatoryElements.md). Using these regulations separates all road regulations from physical road markings allowing for situations such as the work zone use case described above. In addition, all Lanelet2 Maps must follow the Autoware.ai tagging specification rules described in this document and [here](./docs/lanelet2_format_extension.md) due to the use of legacy map handling nodes. This is a requirement which may be depercated in the future. If a Lanelet2 map is loaded which does not contain these elements the carma_wm_ctrl package will make a best effort attempt to add them using Lanelet2's default tagging rules before forwarding the map to components using the carma_wm library. + +### Local CARMA mods to this readme file + +- Added section on CARMA file format requirements + - 2/19/2019 + - Michael McConnell + +## Lanelet Format for Autoware +Autoware uses extended Lanelet2 Format for Autoware, which means you need to add some tags to default OSM file if you want to fully use Lanelet2 maps. For details about custom tags, please refer to this [document](./docs/lanelet2_format_extension.md). + +## Code API +### IO +#### Autoware OSM Parser +Autoware Lanelet2 Format uses .osm extension as original Lanelet2. +However, there are some custom tags that is used by the parser. + +Currently, this includes: +* overwriting x,y values with `local_x` and `local_y` tags. +* reading `` tag wich contains information about map format version and map version. + +The parser is registered as "autoware_osm_handler" as lanelet parser + +### Projection +#### MGRS Projector +MGRS projector projects latitude longitude into MGRS Coordinates. + +### Regulatory Elements +#### Autoware Traffic Light +Autoware Traffic Light class allows you to retrieve information about traffic lights. +Autoware Traffic Light class contains following members: +* traffic light shape +* light bulbs information of traffic lights +* stopline associated to traffic light + +### Utility +#### Message Conversion +This contains functions to convert lanelet map objects into ROS messages. +Currently it contains following conversions: +* lanelet::LaneletMapPtr to/from lanelet_msgs::MapBinMsg +* lanelet::Point3d to geometry_msgs::Point +* lanelet::Point2d to geometry_msgs::Point +* lanelet::BasicPoint3d to geometry_msgs::Point + +#### Query +This module contains functions to retrieve various information from maps. +e.g. crosswalks, trafficlights, stoplines + +#### Utilties +This module contains other useful functions related to Lanelet. +e.g. matching waypoint with lanelets + +### Visualization +Visualization contains functions to convert lanelet objects into visualization marker messages. +Currenly it contains following conversions: +* lanelet::Lanelet to Triangle Markers +* lanelet::LineString to LineStrip Markers +* TrafficLights to Triangle Markers + +## Nodes +### autoware_lanelet2_ros_interface_sample +Code for this explains how this autoware_lanelet2_ros_interface library is used. +The executable is not meanto to do anything. + +### autoware_autoware_lanelet2_ros_interface +This node checks if an .osm file follows the Autoware version of Lanelet2 format. +You can check by running: +``` +rosrun autoware_lanelet2_ros_interface autoware_lanelet2_validation _map_file:= +``` diff --git a/common/autoware_lanelet2_ros_interface/docs/lanelet2_format_extension.md b/common/autoware_lanelet2_ros_interface/docs/lanelet2_format_extension.md new file mode 100644 index 00000000000..a0d3683a355 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/docs/lanelet2_format_extension.md @@ -0,0 +1,161 @@ +# Modifying Lanelet2 format for Autoware +## Overview +About the basics of the default format, please refer to main [Lanelet2 repository](https://github.com/fzi-forschungszentrum-informatik/Lanelet2). (see [here](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_core/doc/LaneletPrimitives.md) about primitives) + +In addition to default Lanelet2 Format, users should add following mandatory/optional tags to their osm lanelet files as explained in reset of this document. +Users may use `autoware_lanelet2_validation` [node](../README.md#nodes) to check if their maps are valid. + +## Mandatory Tags +### Elevation Tags +Elevation("ele") information for points(`node`) is optional in default Lanelet2 format. +However, some of Autoware packages(e.g. trafficlight_recognizer) need elevation to be included in HD map. Therefore, users must make sure that all points in their osm maps contain elevation tags. + +Here is an example osm syntax for node object. +``` + + + +``` + +### TrafficLights +Default Lanelet2 format uses LineString(`way`) or Polygon class to represent the shape of a traffic light. For Autoware, traffic light objects must be represented only by LineString to avoid confusion, where start point is at bottom left edge and end point is at bottom right edge. Also, "height" tag must be added in order to represent the size in verticle direction(not the position). + +The Following image illustrates how LineString is used to represent shape of Traffic Light in Autoware. + + + +Here is an example osm syntax for traffic light object. +``` + + + + + + + +``` + +### Turn Diretions +Users must add "turn_direction" tags to lanelets within intersections to indicate vehicle's turning direction. You do not need this tags for lanelets that are not in intersections. If you do not have this tag, Autoware will not be able to light up turning indicators. +This tags only take following values: +* left +* right +* straight + +Following image illustrates how lanelets should be tagged. + + + +Here is an example of osm sytax for lanelets in intersections. +``` + + + + + + + + + + +``` + +## Optional Taggings +Following tags are optional tags that you may want to add depending on how you want to use your map in Autoware. + +### Meta Info +Users may add the `MetaInfo` element to their OSM file to indicate format version and map version of their OSM file. This information is not meant to influence Autoware vehicle's behavior, but is published as ROS message so that developers could know which map was used from ROSBAG log files. MetaInfo elements exists in the same hiararchy with `node`, `way`, and `relation` elements, otherwise JOSM wouldn't be able to load the file correctly. + +Here is an example of MetaInfo in osm file: +``` + + + + ... + ... + ... + +``` + +### Local Coordinate Expression +Sometimes users might want to create Lanelet2 maps that are not georeferenced. +In such a case, users may use "local_x", "local_y" taggings to express local positions instead of latitude and longitude. +Autoware Osm Parser will overwrite x,y positions with these tags when they are present. +For z values, use "ele" tags as default Lanelet2 Format. +You would still need to fill in lat and lon attributes so that parser does not crush, but their values could be anything. + +Here is example `node` element in osm with "local_x", "local_y" taggings: +``` + + + + + + +``` + +### Light Bulbs in Traffic Lights +Default Lanelet format can only express shape (base + height) of traffic lights. +However, region_tlr node in Autoware uses positions of each light bulbs to recognize color of traffic light. If users may wish to use this node, "light_bulbs"(`way`) element must be registered to traffic_light regulatory_element object define position and color of each light bulb in traffic lights. If you are using other trafficlight_recognizer nodes(e.g. tlr_mxnet), which only uses bounding box of traffic light, then you do not need to add this object. + +"light_bulbs" object is defined using LineString(`way`), and each node of line string is placed at the center of each light bulb. Also, each node should have "color" and optionally "arrow" tags to describe its type. Also, "traffic_light_id" tag is used to indicate which ID of relevant traffic_light element. + +"color" tag is used to express the color of the light bulb. Currently only three values are used: +* red +* yellow +* green + +"arrow" tag is used to express the direction of the arrow of light bulb: +* up +* right +* left +* up_right +* up_left + +Following image illustrates how "light_bulbs" LineString should be created. + + + +Here is an exmaple of osm syntax for light_bulb object: +``` + + + + + + + + + + + + + + + + + + + + + + + + +``` + +After creating "light_bulbs" elements, you have to register them to traffic_light regulatory element as role "light_bulbs". +The following illustrates how light_bulbs are registered to traffic_light regulatory elements. + + + + +``` + + + + + + + +``` diff --git a/common/lanelet2_extension/include/lanelet2_extension/utility/internal/query.tpp b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/internal/query.tpp similarity index 99% rename from common/lanelet2_extension/include/lanelet2_extension/utility/internal/query.tpp rename to common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/internal/query.tpp index 659400c3a60..ae0fbe591d2 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/utility/internal/query.tpp +++ b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/internal/query.tpp @@ -65,4 +65,4 @@ query::References query::findReferences(const primT& prim, const lanelet::Lanele return references; } } // namespace utils -} // namespace lanelet +} // namespace lanelet \ No newline at end of file diff --git a/common/lanelet2_extension/include/lanelet2_extension/utility/message_conversion.h b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/message_conversion.h similarity index 93% rename from common/lanelet2_extension/include/lanelet2_extension/utility/message_conversion.h rename to common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/message_conversion.h index f9ab4be148e..92026e71e6f 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/utility/message_conversion.h +++ b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/message_conversion.h @@ -16,8 +16,8 @@ * Authors: Simon Thompson, Ryohsuke Mitsudome */ -#ifndef LANELET2_EXTENSION_UTILITY_MESSAGE_CONVERSION_H -#define LANELET2_EXTENSION_UTILITY_MESSAGE_CONVERSION_H +#ifndef AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_MESSAGE_CONVERSION_H +#define AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_MESSAGE_CONVERSION_H #include #include @@ -81,4 +81,4 @@ void toGeomMsgPt32(const Eigen::Vector3d& src, geometry_msgs::Point32* dst); } // namespace utils } // namespace lanelet -#endif // LANELET2_EXTENSION_UTILITY_MESSAGE_CONVERSION_H +#endif // AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_MESSAGE_CONVERSION_H diff --git a/common/lanelet2_extension/include/lanelet2_extension/utility/query.h b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/query.h similarity index 97% rename from common/lanelet2_extension/include/lanelet2_extension/utility/query.h rename to common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/query.h index 9ef9231f68a..a2865684455 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/utility/query.h +++ b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/query.h @@ -16,8 +16,8 @@ * Authors: Simon Thompson, Ryohsuke Mitsudome */ -#ifndef LANELET2_EXTENSION_UTILITY_QUERY_H -#define LANELET2_EXTENSION_UTILITY_QUERY_H +#ifndef AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_QUERY_H +#define AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_QUERY_H #include #include @@ -185,4 +185,4 @@ std::vector getAllWayStopStopLines(const lanelet::Co // Therefore include implementation to allow for template functions #include "internal/query.tpp" -#endif // LANELET2_EXTENSION_UTILITY_QUERY_H +#endif // AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_QUERY_H diff --git a/common/lanelet2_extension/include/lanelet2_extension/utility/utilities.h b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/utilities.h similarity index 92% rename from common/lanelet2_extension/include/lanelet2_extension/utility/utilities.h rename to common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/utilities.h index 5fa01e4ebd5..2ba6f8cbcae 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/utility/utilities.h +++ b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/utility/utilities.h @@ -16,8 +16,8 @@ * Authors: Kenji Miyake, Ryohsuke Mitsudome */ -#ifndef LANELET2_EXTENSION_UTILITY_UTILITIES_H -#define LANELET2_EXTENSION_UTILITY_UTILITIES_H +#ifndef AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_UTILITIES_H +#define AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_UTILITIES_H #include @@ -61,4 +61,4 @@ void removeRegulatoryElements(std::vector regem_l } // namespace utils } // namespace lanelet -#endif // LANELET2_EXTENSION_UTILITY_UTILITIES_H +#endif // AUTOWARE_LANELET2_ROS_INTERFACE_UTILITY_UTILITIES_H diff --git a/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/visualization/visualization.h similarity index 95% rename from common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h rename to common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/visualization/visualization.h index 97d109ae482..462f42b0fc8 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/visualization/visualization.h +++ b/common/autoware_lanelet2_ros_interface/include/autoware_lanelet2_ros_interface/visualization/visualization.h @@ -16,8 +16,8 @@ * Authors: Simon Thompson, Ryohsuke Mitsudome */ -#ifndef LANELET2_EXTENSION_VISUALIZATION_VISUALIZATION_H -#define LANELET2_EXTENSION_VISUALIZATION_VISUALIZATION_H +#ifndef AUTOWARE_LANELET2_ROS_INTERFACE_VISUALIZATION_VISUALIZATION_H +#define AUTOWARE_LANELET2_ROS_INTERFACE_VISUALIZATION_VISUALIZATION_H #include #include @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include @@ -152,4 +152,4 @@ visualization_msgs::MarkerArray trafficLightsAsTriangleMarkerArray( } // namespace visualization } // namespace lanelet -#endif // LANELET2_EXTENSION_VISUALIZATION_VISUALIZATION_H +#endif // AUTOWARE_LANELET2_ROS_INTERFACE_VISUALIZATION_VISUALIZATION_H diff --git a/common/lanelet2_extension/lib/message_conversion.cpp b/common/autoware_lanelet2_ros_interface/lib/message_conversion.cpp similarity index 98% rename from common/lanelet2_extension/lib/message_conversion.cpp rename to common/autoware_lanelet2_ros_interface/lib/message_conversion.cpp index efa79f0828c..0bfabffda82 100644 --- a/common/lanelet2_extension/lib/message_conversion.cpp +++ b/common/autoware_lanelet2_ros_interface/lib/message_conversion.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include diff --git a/common/lanelet2_extension/lib/query.cpp b/common/autoware_lanelet2_ros_interface/lib/query.cpp similarity index 99% rename from common/lanelet2_extension/lib/query.cpp rename to common/autoware_lanelet2_ros_interface/lib/query.cpp index 74c01e6394b..5d36d4525a9 100644 --- a/common/lanelet2_extension/lib/query.cpp +++ b/common/autoware_lanelet2_ros_interface/lib/query.cpp @@ -20,8 +20,8 @@ #include -#include -#include +#include +#include #include #include diff --git a/common/lanelet2_extension/lib/utilities.cpp b/common/autoware_lanelet2_ros_interface/lib/utilities.cpp similarity index 99% rename from common/lanelet2_extension/lib/utilities.cpp rename to common/autoware_lanelet2_ros_interface/lib/utilities.cpp index cc3c0f7b29a..e56644d956a 100644 --- a/common/lanelet2_extension/lib/utilities.cpp +++ b/common/autoware_lanelet2_ros_interface/lib/utilities.cpp @@ -29,7 +29,7 @@ #include #include -#include +#include #include #include diff --git a/common/lanelet2_extension/lib/visualization.cpp b/common/autoware_lanelet2_ros_interface/lib/visualization.cpp similarity index 98% rename from common/lanelet2_extension/lib/visualization.cpp rename to common/autoware_lanelet2_ros_interface/lib/visualization.cpp index ecea92f5330..85bd072fb7e 100644 --- a/common/lanelet2_extension/lib/visualization.cpp +++ b/common/autoware_lanelet2_ros_interface/lib/visualization.cpp @@ -25,9 +25,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include diff --git a/common/autoware_lanelet2_ros_interface/package.xml b/common/autoware_lanelet2_ros_interface/package.xml new file mode 100644 index 00000000000..9e15256cbaf --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/package.xml @@ -0,0 +1,31 @@ + + + autoware_lanelet2_ros_interface + 1.12.0 + The autoware_lanelet2_ros_interface pacakge contains libraries to handle Lanelet2 format data. + + mitsudome-r + + Apach 2 + + autoware_build_flags + catkin + + amathutils_lib + roscpp + geographiclib + lanelet2_core + lanelet2_io + lanelet2_maps + lanelet2_projection + lanelet2_routing + lanelet2_traffic_rules + lanelet2_validation + lanelet2_extension + autoware_lanelet2_msgs + autoware_msgs + geometry_msgs + visualization_msgs + pugixml-dev + roslint + diff --git a/common/lanelet2_extension/src/sample_code.cpp b/common/autoware_lanelet2_ros_interface/src/sample_code.cpp similarity index 98% rename from common/lanelet2_extension/src/sample_code.cpp rename to common/autoware_lanelet2_ros_interface/src/sample_code.cpp index 7550569ce4d..a6d7aff4feb 100644 --- a/common/lanelet2_extension/src/sample_code.cpp +++ b/common/autoware_lanelet2_ros_interface/src/sample_code.cpp @@ -117,7 +117,7 @@ void usingAutowareTrafficLight(const std::string map_file_path) int main(int argc, char* argv[]) { - ros::init(argc, argv, "lanelet2_extension_example"); + ros::init(argc, argv, "autoware_lanelet2_ros_interface_example"); ros::NodeHandle nh; ros::NodeHandle pnh("~"); diff --git a/common/lanelet2_extension/src/validation.cpp b/common/autoware_lanelet2_ros_interface/src/validation.cpp similarity index 98% rename from common/lanelet2_extension/src/validation.cpp rename to common/autoware_lanelet2_ros_interface/src/validation.cpp index 466e2177fef..a84b1f95c2a 100644 --- a/common/lanelet2_extension/src/validation.cpp +++ b/common/autoware_lanelet2_ros_interface/src/validation.cpp @@ -48,7 +48,7 @@ constexpr const char* Elevation = "ele"; void printUsage() { std::cout << "Usage:" << std::endl - << "rosrun lanelet2_extension autoware_lanelet2_validation" + << "rosrun autoware_lanelet2_ros_interface autoware_lanelet2_validation" "_map_file:=" << std::endl; } diff --git a/common/autoware_lanelet2_ros_interface/test/resources/test_map.osm b/common/autoware_lanelet2_ros_interface/test/resources/test_map.osm new file mode 100644 index 00000000000..882c36c6e4f --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/resources/test_map.osm @@ -0,0 +1,105 @@ + + + +proj=tmerc +lat_0=39.46636844371259 +lon_0=-76.16919523566943 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/common/autoware_lanelet2_ros_interface/test/resources/test_map_nogeoreference.osm b/common/autoware_lanelet2_ros_interface/test/resources/test_map_nogeoreference.osm new file mode 100644 index 00000000000..21ed1431d13 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/resources/test_map_nogeoreference.osm @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/common/autoware_lanelet2_ros_interface/test/resources/test_map_v.osm b/common/autoware_lanelet2_ros_interface/test/resources/test_map_v.osm new file mode 100644 index 00000000000..a46dd4f72f6 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/resources/test_map_v.osm @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/common/autoware_lanelet2_ros_interface/test/resources/test_map_value.osm b/common/autoware_lanelet2_ros_interface/test/resources/test_map_value.osm new file mode 100644 index 00000000000..541b065f157 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/resources/test_map_value.osm @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/common/lanelet2_extension/test/src/test_message_conversion.cpp b/common/autoware_lanelet2_ros_interface/test/src/test_message_conversion.cpp similarity index 97% rename from common/lanelet2_extension/test/src/test_message_conversion.cpp rename to common/autoware_lanelet2_ros_interface/test/src/test_message_conversion.cpp index a110f92889f..33cdb63c104 100644 --- a/common/lanelet2_extension/test/src/test_message_conversion.cpp +++ b/common/autoware_lanelet2_ros_interface/test/src/test_message_conversion.cpp @@ -18,8 +18,8 @@ #include -#include -#include +#include +#include using lanelet::Lanelet; using lanelet::LineString3d; diff --git a/common/lanelet2_extension/test/src/test_query.cpp b/common/autoware_lanelet2_ros_interface/test/src/test_query.cpp similarity index 98% rename from common/lanelet2_extension/test/src/test_query.cpp rename to common/autoware_lanelet2_ros_interface/test/src/test_query.cpp index e257aa370f4..284ef707f19 100644 --- a/common/lanelet2_extension/test/src/test_query.cpp +++ b/common/autoware_lanelet2_ros_interface/test/src/test_query.cpp @@ -15,8 +15,8 @@ */ #include -#include -#include +#include +#include #include #include #include diff --git a/common/lanelet2_extension/test/src/test_utilities.cpp b/common/autoware_lanelet2_ros_interface/test/src/test_utilities.cpp similarity index 99% rename from common/lanelet2_extension/test/src/test_utilities.cpp rename to common/autoware_lanelet2_ros_interface/test/src/test_utilities.cpp index f4f343e1905..deacc849c4c 100644 --- a/common/lanelet2_extension/test/src/test_utilities.cpp +++ b/common/autoware_lanelet2_ros_interface/test/src/test_utilities.cpp @@ -15,8 +15,8 @@ */ #include -#include -#include +#include +#include #include #include #include diff --git a/common/autoware_lanelet2_ros_interface/test/test_message_conversion.test b/common/autoware_lanelet2_ros_interface/test/test_message_conversion.test new file mode 100644 index 00000000000..3601a0c8743 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/test_message_conversion.test @@ -0,0 +1,5 @@ + + + + + diff --git a/common/autoware_lanelet2_ros_interface/test/test_query.test b/common/autoware_lanelet2_ros_interface/test/test_query.test new file mode 100644 index 00000000000..9acdc23ce72 --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/test_query.test @@ -0,0 +1,5 @@ + + + + + diff --git a/common/autoware_lanelet2_ros_interface/test/test_utilities.test b/common/autoware_lanelet2_ros_interface/test/test_utilities.test new file mode 100644 index 00000000000..2d761096dde --- /dev/null +++ b/common/autoware_lanelet2_ros_interface/test/test_utilities.test @@ -0,0 +1,5 @@ + + + + + diff --git a/common/lanelet2_extension/CMakeLists.txt b/common/lanelet2_extension/CMakeLists.txt index 28cd2d1b8b8..ef716b32a6f 100644 --- a/common/lanelet2_extension/CMakeLists.txt +++ b/common/lanelet2_extension/CMakeLists.txt @@ -28,13 +28,26 @@ find_path(PUGIXML_INCLUDE_DIRS PATH_SUFFIXES pugixml ) -find_package(autoware_build_flags REQUIRED) - find_package(PROJ4 REQUIRED) +# Extract environment variable value +set(LANELET2_EXTENSION_LOGGER_TYPE $ENV{LANELET2_EXTENSION_LOGGER_TYPE}) + +if(LANELET2_EXTENSION_LOGGER_TYPE EQUAL 1 ) + + message("lanelet2_extension using std::cout and cerr for logging") + add_definitions(-DLANELET2_EXTENSION_LOGGER_TYPE=1) + +else() # Default to ROS logging + + message("lanelet2_extension using roscpp for logging") + add_definitions(-DLANELET2_EXTENSION_LOGGER_TYPE=0) + set(LOGGER_DEP roscpp) + +endif() + find_package(catkin REQUIRED COMPONENTS - amathutils_lib - roscpp + ${LOGGER_DEP} lanelet2_core lanelet2_io lanelet2_maps @@ -42,21 +55,14 @@ find_package(catkin REQUIRED COMPONENTS lanelet2_routing lanelet2_traffic_rules lanelet2_validation - autoware_lanelet2_msgs - autoware_msgs - geometry_msgs - visualization_msgs - roslint hardcoded_params ) -set(ROSLINT_CPP_OPTS "--filter=-build/c++14") -roslint_cpp() catkin_package( INCLUDE_DIRS include LIBRARIES lanelet2_extension_lib - CATKIN_DEPENDS amathutils_lib roscpp lanelet2_core lanelet2_io lanelet2_maps lanelet2_projection lanelet2_routing lanelet2_traffic_rules lanelet2_validation autoware_lanelet2_msgs autoware_msgs geometry_msgs visualization_msgs hardcoded_params + CATKIN_DEPENDS ${LOGGER_DEP} lanelet2_core lanelet2_io lanelet2_maps lanelet2_projection lanelet2_routing lanelet2_traffic_rules lanelet2_validation hardcoded_params ) include_directories( @@ -73,11 +79,7 @@ add_library( lanelet2_extension_lib lib/autoware_osm_parser.cpp lib/autoware_traffic_light.cpp lib/local_frame_projector.cpp - lib/message_conversion.cpp lib/mgrs_projector.cpp - lib/query.cpp - lib/utilities.cpp - lib/visualization.cpp lib/CarmaUSTrafficRules.cpp lib/PassingControlLine.cpp lib/StopRule.cpp @@ -98,22 +100,7 @@ target_link_libraries(lanelet2_extension_lib ${PROJ4_LIBRARIES} ) -add_executable(lanelet2_extension_sample src/sample_code.cpp) -add_dependencies(lanelet2_extension_sample ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(lanelet2_extension_sample - ${catkin_LIBRARIES} - lanelet2_extension_lib -) - -add_executable(autoware_lanelet2_validation src/validation.cpp) -add_dependencies(autoware_lanelet2_validation ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(autoware_lanelet2_validation - ${catkin_LIBRARIES} - ${PUGIXML_LIBRAREIS} - lanelet2_extension_lib -) - -install(TARGETS lanelet2_extension_lib lanelet2_extension_sample autoware_lanelet2_validation +install(TARGETS lanelet2_extension_lib ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) @@ -122,18 +109,10 @@ install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) if(CATKIN_ENABLE_TESTING) - roslint_add_test() - find_package(rostest REQUIRED) - add_rostest_gtest(message_conversion-test test/test_message_conversion.test test/src/test_message_conversion.cpp) - target_link_libraries(message_conversion-test ${catkin_LIBRARIES} lanelet2_extension_lib) - add_rostest_gtest(projector-test test/test_projector.test test/src/test_projector.cpp) + catkin_add_gmock(projector-test test/src/test_projector.cpp) target_link_libraries(projector-test ${catkin_LIBRARIES} lanelet2_extension_lib) - add_rostest_gtest(query-test test/test_query.test test/src/test_query.cpp) - target_link_libraries(query-test ${catkin_LIBRARIES} lanelet2_extension_lib) - add_rostest_gtest(regulatory_elements-test test/test_regulatory_elements.test test/src/test_regulatory_elements.cpp) + catkin_add_gmock(regulatory_elements-test test/src/test_regulatory_elements.cpp) target_link_libraries(regulatory_elements-test ${catkin_LIBRARIES} lanelet2_extension_lib) - add_rostest_gtest(utilities-test test/test_utilities.test test/src/test_utilities.cpp) - target_link_libraries(utilities-test ${catkin_LIBRARIES} lanelet2_extension_lib) catkin_add_gmock(carma-additions-test test/src/CarmaTestsMain.cpp diff --git a/common/lanelet2_extension/README.md b/common/lanelet2_extension/README.md index b96e42d62d0..ec00911f09a 100644 --- a/common/lanelet2_extension/README.md +++ b/common/lanelet2_extension/README.md @@ -38,30 +38,6 @@ Autoware Traffic Light class contains following members: * light bulbs information of traffic lights * stopline associated to traffic light -### Utility -#### Message Conversion -This contains functions to convert lanelet map objects into ROS messages. -Currently it contains following conversions: -* lanelet::LaneletMapPtr to/from lanelet_msgs::MapBinMsg -* lanelet::Point3d to geometry_msgs::Point -* lanelet::Point2d to geometry_msgs::Point -* lanelet::BasicPoint3d to geometry_msgs::Point - -#### Query -This module contains functions to retrieve various information from maps. -e.g. crosswalks, trafficlights, stoplines - -#### Utilties -This module contains other useful functions related to Lanelet. -e.g. matching waypoint with lanelets - -### Visualization -Visualization contains functions to convert lanelet objects into visualization marker messages. -Currenly it contains following conversions: -* lanelet::Lanelet to Triangle Markers -* lanelet::LineString to LineStrip Markers -* TrafficLights to Triangle Markers - ## Nodes ### lanelet2_extension_sample Code for this explains how this lanelet2_extension library is used. diff --git a/common/lanelet2_extension/include/lanelet2_extension/logging/logger.h b/common/lanelet2_extension/include/lanelet2_extension/logging/logger.h new file mode 100644 index 00000000000..e8119a95f6c --- /dev/null +++ b/common/lanelet2_extension/include/lanelet2_extension/logging/logger.h @@ -0,0 +1,49 @@ + +#ifndef LANELET2_EXTENSION_LOGGER_H +#define LANELET2_EXTENSION_LOGGER_H + +/* + * Copyright (C) 2020-2021 LEIDOS. + * + * Licensed under the Apache License, Version 2.0 (the "License"); you may not + * use this file except in compliance with the License. You may obtain a copy of + * the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations under + * the License. + */ + +#define LOGGER_TYPE_ROS_LOGGER 0 +#define LOGGER_TYPE_STD_LOGGER 1 + +// If the logger type is not set then set it to the default + +#if LANELET2_EXTENSION_LOGGER_TYPE == LOGGER_TYPE_STD_LOGGER // Logger type of 1 indicates usage of std::cout + +#include // Include std::cout and cerr + +#define LOG_DEBUG_STREAM(args) std::cout << args << std::endl; +#define LOG_INFO_STREAM(args) std::cout << args << std::endl; +#define LOG_WARN_STREAM(args) std::cout << args << std::endl; +#define LOG_ERROR_STREAM(args) std::cerr << args << std::endl; +#define LOG_FATAL_STREAM(args) std::cerr << args << std::endl; + +#else // LOGGER_TYPE_ROS_LOGGER By default this library will use ros logging + +#include // Include rosconsole macros + +#define LOG_DEBUG_STREAM(args) ROS_DEBUG_STREAM(args) +#define LOG_INFO_STREAM(args) ROS_INFO_STREAM(args) +#define LOG_WARN_STREAM(args) ROS_WARN_STREAM(args) +#define LOG_ERROR_STREAM(args) ROS_ERROR_STREAM(args) +#define LOG_FATAL_STREAM(args) ROS_FATAL_STREAM(args) + +#endif + + +#endif // LANELET2_EXTENSION_LOGGER_H \ No newline at end of file diff --git a/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/autoware_traffic_light.h b/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/autoware_traffic_light.h index 6f0b3af540d..4a3b03935b4 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/autoware_traffic_light.h +++ b/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/autoware_traffic_light.h @@ -79,15 +79,7 @@ class AutowareTrafficLight : public lanelet::TrafficLight const Optional& stopLine, const LineStrings3d& lightBulbs); explicit AutowareTrafficLight(const lanelet::RegulatoryElementDataPtr& data); }; -static lanelet::RegisterRegulatoryElement regAutowareTraffic; -// moved to lanelet2_extension/lib/autoware_traffic_light.cpp to avoid multiple -// defintion errors -/* -#if __cplusplus < 201703L -constexpr char AutowareTrafficLight::RuleName[]; // instanciate string in -cpp file #endif -*/ } // namespace autoware } // namespace lanelet diff --git a/common/lanelet2_extension/lib/CarmaUSTrafficRules.cpp b/common/lanelet2_extension/lib/CarmaUSTrafficRules.cpp index 1183991eac7..0f510c1d7a8 100644 --- a/common/lanelet2_extension/lib/CarmaUSTrafficRules.cpp +++ b/common/lanelet2_extension/lib/CarmaUSTrafficRules.cpp @@ -13,7 +13,7 @@ * License for the specific language governing permissions and limitations under * the License. */ -#include +#include #include #include #include @@ -261,14 +261,14 @@ SpeedLimitInformation CarmaUSTrafficRules::speedLimit(const ConstLaneletOrArea& if(config_limit > 0_mph && config_limit < MAX_SPEED_LIMIT && speed_limit > config_limit)//Accounting for the configured speed limit, input zero when not in use { - ROS_DEBUG_STREAM("Configurable speed limit in use: " << config_limit.value()); + LOG_DEBUG_STREAM("Configurable speed limit in use: " << config_limit.value()); speed_limit = config_limit; } //Determine whether or not the value exceeds the predetermined maximum speed limit value. if (speed_limit > MAX_SPEED_LIMIT) { - ROS_WARN_STREAM("Invalid speed limit value. Value reset to maximum speed limit. ");//Display warning message + LOG_WARN_STREAM("Invalid speed limit value. Value reset to maximum speed limit. ");//Display warning message speed_limit = MAX_SPEED_LIMIT;//Reset the speed limit value to be capped at the maximum value. } } @@ -281,20 +281,20 @@ SpeedLimitInformation CarmaUSTrafficRules::speedLimit(const ConstLaneletOrArea& if(config_limit > 0_mph && config_limit < MAX_SPEED_LIMIT && speed_limit > config_limit)//Accounting for the configured speed limit, input zero when not in use { - ROS_DEBUG_STREAM("Configurable speed limit in use: " << config_limit.value()); + LOG_DEBUG_STREAM("Configurable speed limit in use: " << config_limit.value()); speed_limit = config_limit; } //Determine whether or not the value exceeds the predetermined maximum speed limit value. if (speed_limit > MAX_SPEED_LIMIT) { - ROS_WARN_STREAM("Invalid speed limit value. Value reset to maximum speed limit. ");//Display warning message + LOG_WARN_STREAM("Invalid speed limit value. Value reset to maximum speed limit. ");//Display warning message speed_limit = MAX_SPEED_LIMIT;//Reset the speed limit value to be capped at the maximum value. } } } - ROS_DEBUG_STREAM("Returning Speed Limit: " << speed_limit.value()); + LOG_DEBUG_STREAM("Returning Speed Limit: " << speed_limit.value()); return SpeedLimitInformation{ speed_limit, true };//Return Speed limit data. } diff --git a/common/lanelet2_extension/lib/DigitalMinimumGap.cpp b/common/lanelet2_extension/lib/DigitalMinimumGap.cpp index 727c82ff332..866bf8defb8 100644 --- a/common/lanelet2_extension/lib/DigitalMinimumGap.cpp +++ b/common/lanelet2_extension/lib/DigitalMinimumGap.cpp @@ -1,4 +1,3 @@ -#pragma once /* * Copyright (C) 2021 LEIDOS. * diff --git a/common/lanelet2_extension/lib/autoware_traffic_light.cpp b/common/lanelet2_extension/lib/autoware_traffic_light.cpp index a5e4030e373..4ad7c222474 100644 --- a/common/lanelet2_extension/lib/autoware_traffic_light.cpp +++ b/common/lanelet2_extension/lib/autoware_traffic_light.cpp @@ -28,8 +28,18 @@ namespace lanelet { namespace autoware { + +// InLine static constexpr not supported until C++17. For earlier versions the variable must be forward declared in cpp file +#if __cplusplus < 201703L +constexpr char AutowareTrafficLight::RuleName[]; // instanciate string in cpp file +#endif + + namespace { + // this object actually does the registration work for us +static lanelet::RegisterRegulatoryElement regAutowareTraffic; + template bool findAndErase(const T& primitive, RuleParameters* member) { @@ -147,9 +157,5 @@ bool AutowareTrafficLight::removeLightBulbs(const LineStringOrPolygon3d& primiti return findAndErase(primitive.asRuleParameter(), ¶meters().find(AutowareRoleNameString::LightBulbs)->second); } -#if __cplusplus < 201703L -constexpr char AutowareTrafficLight::RuleName[]; // instanciate string in cpp file -#endif - } // namespace autoware } // namespace lanelet diff --git a/common/lanelet2_extension/lib/mgrs_projector.cpp b/common/lanelet2_extension/lib/mgrs_projector.cpp index 8b89618c745..55d75b4d188 100644 --- a/common/lanelet2_extension/lib/mgrs_projector.cpp +++ b/common/lanelet2_extension/lib/mgrs_projector.cpp @@ -17,7 +17,7 @@ */ #include -#include +#include #include #include @@ -54,7 +54,7 @@ BasicPoint3d MGRSProjector::forward(const GPSPoint& gps, const int precision) co } catch (GeographicLib::GeographicErr err) { - ROS_ERROR_STREAM(err.what()); + LOG_ERROR_STREAM(err.what()); return mgrs_point; } @@ -65,7 +65,7 @@ BasicPoint3d MGRSProjector::forward(const GPSPoint& gps, const int precision) co if (!prev_projected_grid.empty() && prev_projected_grid != projected_grid_) { - ROS_ERROR_STREAM("Projected MGRS Grid changed from last projection. Projected point " + LOG_ERROR_STREAM("Projected MGRS Grid changed from last projection. Projected point " "might be far away from previously projected point." << std::endl << "You may want to use different projector."); @@ -88,7 +88,7 @@ GPSPoint MGRSProjector::reverse(const BasicPoint3d& mgrs_point) const } else { - ROS_ERROR_STREAM("cannot run reverse operation if mgrs code is not set in projector." << std::endl + LOG_ERROR_STREAM("cannot run reverse operation if mgrs code is not set in projector." << std::endl << "use setMGRSCode function " "or explicitly give mgrs " "code as an " @@ -113,7 +113,7 @@ GPSPoint MGRSProjector::reverse(const BasicPoint3d& mgrs_point, const std::strin } catch (GeographicLib::GeographicErr err) { - ROS_ERROR_STREAM("Failed to convert from MGRS to WGS" << err.what()); + LOG_ERROR_STREAM("Failed to convert from MGRS to WGS" << err.what()); return gps; } @@ -139,7 +139,7 @@ void MGRSProjector::setMGRSCode(const GPSPoint& gps, const int precision) } catch (GeographicLib::GeographicErr err) { - ROS_ERROR_STREAM(err.what()); + LOG_ERROR_STREAM(err.what()); } setMGRSCode(mgrs_code); diff --git a/common/lanelet2_extension/package.xml b/common/lanelet2_extension/package.xml index 3aab30f8b3d..4a13fcc76f3 100644 --- a/common/lanelet2_extension/package.xml +++ b/common/lanelet2_extension/package.xml @@ -1,5 +1,5 @@ - + lanelet2_extension 1.12.0 The lanelet2_extension pacakge contains libraries to handle Lanelet2 format data. @@ -8,11 +8,9 @@ Apach 2 - autoware_build_flags catkin - amathutils_lib - roscpp + roscpp geographiclib lanelet2_core lanelet2_io @@ -21,11 +19,6 @@ lanelet2_routing lanelet2_traffic_rules lanelet2_validation - autoware_lanelet2_msgs - autoware_msgs - geometry_msgs - visualization_msgs pugixml-dev - roslint hardcoded_params diff --git a/common/lanelet2_extension/test/src/test_local_projector.cpp b/common/lanelet2_extension/test/src/test_local_projector.cpp index 306e5659df5..a51f37f43ea 100644 --- a/common/lanelet2_extension/test/src/test_local_projector.cpp +++ b/common/lanelet2_extension/test/src/test_local_projector.cpp @@ -14,7 +14,7 @@ * limitations under the License. */ -#include +#include #include #include diff --git a/common/lanelet2_extension/test/src/test_projector.cpp b/common/lanelet2_extension/test/src/test_projector.cpp index 62897adfac2..6f860dd92e9 100644 --- a/common/lanelet2_extension/test/src/test_projector.cpp +++ b/common/lanelet2_extension/test/src/test_projector.cpp @@ -14,7 +14,7 @@ * limitations under the License. */ -#include +#include #include #include @@ -82,6 +82,5 @@ TEST(TestSuite, ReverseProjection) int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "TestNode"); return RUN_ALL_TESTS(); } diff --git a/common/lanelet2_extension/test/src/test_regulatory_elements.cpp b/common/lanelet2_extension/test/src/test_regulatory_elements.cpp index d24188b1397..444f8007958 100644 --- a/common/lanelet2_extension/test/src/test_regulatory_elements.cpp +++ b/common/lanelet2_extension/test/src/test_regulatory_elements.cpp @@ -15,7 +15,7 @@ */ #include -#include +#include #include #include @@ -128,6 +128,5 @@ TEST(TestSuite, TrafficLightWorksAsExpected) int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); - ros::init(argc, argv, "TestNode"); return RUN_ALL_TESTS(); } diff --git a/common/lanelet2_extension/test/test_message_conversion.test b/common/lanelet2_extension/test/test_message_conversion.test deleted file mode 100644 index 0147c064737..00000000000 --- a/common/lanelet2_extension/test/test_message_conversion.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/common/lanelet2_extension/test/test_projector.test b/common/lanelet2_extension/test/test_projector.test deleted file mode 100644 index 70cfff5cf14..00000000000 --- a/common/lanelet2_extension/test/test_projector.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/common/lanelet2_extension/test/test_query.test b/common/lanelet2_extension/test/test_query.test deleted file mode 100644 index 648bbbd9f90..00000000000 --- a/common/lanelet2_extension/test/test_query.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/common/lanelet2_extension/test/test_regulatory_elements.test b/common/lanelet2_extension/test/test_regulatory_elements.test deleted file mode 100644 index 8e064ff43a7..00000000000 --- a/common/lanelet2_extension/test/test_regulatory_elements.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/common/lanelet2_extension/test/test_utilities.test b/common/lanelet2_extension/test/test_utilities.test deleted file mode 100644 index 8b204c685af..00000000000 --- a/common/lanelet2_extension/test/test_utilities.test +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/common/map_file/CMakeLists.txt b/common/map_file/CMakeLists.txt index c7313688d57..e4670492649 100644 --- a/common/map_file/CMakeLists.txt +++ b/common/map_file/CMakeLists.txt @@ -22,6 +22,7 @@ find_package(catkin REQUIRED COMPONENTS autoware_msgs vector_map lanelet2_extension + autoware_lanelet2_ros_interface ) find_package(PCL REQUIRED COMPONENTS io) diff --git a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_loader.cpp b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_loader.cpp index 8be77390b07..a5c43ad3744 100644 --- a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_loader.cpp +++ b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_loader.cpp @@ -22,11 +22,11 @@ #include #include -#include +#include #include #include #include -#include +#include #include #include diff --git a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp index 86f5e7cdd13..4215c6fc801 100644 --- a/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp +++ b/common/map_file/nodes/lanelet2_map_loader/lanelet2_map_visualization.cpp @@ -25,9 +25,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/common/map_file/package.xml b/common/map_file/package.xml index 33eccff3691..b42745e3a0e 100644 --- a/common/map_file/package.xml +++ b/common/map_file/package.xml @@ -22,6 +22,7 @@ vector_map visualization_msgs lanelet2_extension + autoware_lanelet2_ros_interface libboost-filesystem-dev diff --git a/common/object_map/CMakeLists.txt b/common/object_map/CMakeLists.txt index 56240741753..8ac9b830aaa 100644 --- a/common/object_map/CMakeLists.txt +++ b/common/object_map/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(catkin REQUIRED COMPONENTS autoware_msgs vector_map lanelet2_extension + autoware_lanelet2_ros_interface ) # TODO add other files into roslint diff --git a/common/object_map/include/wayarea2grid_lanelet2/wayarea2grid_lanelet2.h b/common/object_map/include/wayarea2grid_lanelet2/wayarea2grid_lanelet2.h index 161f884b769..d5cb7035b60 100755 --- a/common/object_map/include/wayarea2grid_lanelet2/wayarea2grid_lanelet2.h +++ b/common/object_map/include/wayarea2grid_lanelet2/wayarea2grid_lanelet2.h @@ -32,9 +32,9 @@ #include #include #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/common/object_map/package.xml b/common/object_map/package.xml index 8a438c3b5f5..582994151e1 100644 --- a/common/object_map/package.xml +++ b/common/object_map/package.xml @@ -21,5 +21,6 @@ sensor_msgs tf vector_map + autoware_lanelet2_ros_interface lanelet2_extension diff --git a/core_perception/imm_ukf_pda_track/CMakeLists.txt b/core_perception/imm_ukf_pda_track/CMakeLists.txt index bf43c3bdb64..5b67034de49 100644 --- a/core_perception/imm_ukf_pda_track/CMakeLists.txt +++ b/core_perception/imm_ukf_pda_track/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(catkin REQUIRED COMPONENTS roslint tf vector_map + autoware_lanelet2_ros_interface ) diff --git a/core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h b/core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h index cf9ec6d50e6..f328c998ea9 100644 --- a/core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h +++ b/core_perception/imm_ukf_pda_track/include/imm_ukf_pda_lanelet2/imm_ukf_pda_lanelet2.h @@ -39,9 +39,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include diff --git a/core_perception/imm_ukf_pda_track/package.xml b/core_perception/imm_ukf_pda_track/package.xml index e83943eda53..3f564667d76 100644 --- a/core_perception/imm_ukf_pda_track/package.xml +++ b/core_perception/imm_ukf_pda_track/package.xml @@ -17,4 +17,5 @@ tf vector_map lanelet2_extension + autoware_lanelet2_ros_interface diff --git a/core_perception/trafficlight_recognizer/CMakeLists.txt b/core_perception/trafficlight_recognizer/CMakeLists.txt index 0aa84d34cf5..dc451cd8890 100644 --- a/core_perception/trafficlight_recognizer/CMakeLists.txt +++ b/core_perception/trafficlight_recognizer/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(catkin REQUIRED COMPONENTS autoware_msgs vector_map lanelet2_extension + autoware_lanelet2_ros_interface ) find_package(OpenCV REQUIRED) diff --git a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h index 0af4eff77d5..e9fce1426b0 100644 --- a/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h +++ b/core_perception/trafficlight_recognizer/include/trafficlight_recognizer/feat_proj_lanelet2/feat_proj_lanelet2_core.h @@ -27,7 +27,7 @@ #include #include -#include +#include #include #include diff --git a/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp b/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp index ec6c7cb6245..7889bc08d93 100644 --- a/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp +++ b/core_perception/trafficlight_recognizer/nodes/feat_proj_lanelet2/feat_proj_lanelet2_core.cpp @@ -27,9 +27,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/core_perception/trafficlight_recognizer/package.xml b/core_perception/trafficlight_recognizer/package.xml index f841959a7bc..cf3326a61a4 100644 --- a/core_perception/trafficlight_recognizer/package.xml +++ b/core_perception/trafficlight_recognizer/package.xml @@ -24,6 +24,7 @@ vector_map vector_map_server visualization_msgs + autoware_lanelet2_ros_interface lanelet2_extension diff --git a/core_planning/costmap_generator/CMakeLists.txt b/core_planning/costmap_generator/CMakeLists.txt index 16e410545de..b3908777182 100644 --- a/core_planning/costmap_generator/CMakeLists.txt +++ b/core_planning/costmap_generator/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(catkin REQUIRED COMPONENTS tf vector_map lanelet2_extension + autoware_lanelet2_ros_interface ) catkin_package( diff --git a/core_planning/costmap_generator/include/costmap_generator/costmap_generator_lanelet2.h b/core_planning/costmap_generator/include/costmap_generator/costmap_generator_lanelet2.h index ccb95bc9b40..3034dc33883 100644 --- a/core_planning/costmap_generator/include/costmap_generator/costmap_generator_lanelet2.h +++ b/core_planning/costmap_generator/include/costmap_generator/costmap_generator_lanelet2.h @@ -46,7 +46,7 @@ #include #include #include -#include +#include // headers in STL #include diff --git a/core_planning/costmap_generator/nodes/costmap_generator/costmap_generator_lanelet2.cpp b/core_planning/costmap_generator/nodes/costmap_generator/costmap_generator_lanelet2.cpp index 1421846b84d..1ddde4442a6 100644 --- a/core_planning/costmap_generator/nodes/costmap_generator/costmap_generator_lanelet2.cpp +++ b/core_planning/costmap_generator/nodes/costmap_generator/costmap_generator_lanelet2.cpp @@ -31,8 +31,8 @@ #include #include -#include -#include +#include +#include // Constructor CostmapGeneratorLanelet2::CostmapGeneratorLanelet2() : private_nh_("~") diff --git a/core_planning/costmap_generator/package.xml b/core_planning/costmap_generator/package.xml index cfd775f1367..954a44d255a 100644 --- a/core_planning/costmap_generator/package.xml +++ b/core_planning/costmap_generator/package.xml @@ -17,4 +17,5 @@ tf vector_map lanelet2_extension + autoware_lanelet2_ros_interface diff --git a/core_planning/decision_maker/CMakeLists.txt b/core_planning/decision_maker/CMakeLists.txt index 44977eb25c5..5be4a40eaf5 100644 --- a/core_planning/decision_maker/CMakeLists.txt +++ b/core_planning/decision_maker/CMakeLists.txt @@ -27,6 +27,7 @@ find_package( vector_map vector_map_msgs vector_map_msgs + autoware_lanelet2_ros_interface ) catkin_package( @@ -44,6 +45,7 @@ catkin_package( tf vector_map vector_map_msgs + autoware_lanelet2_ros_interface ) set(ROSLINT_CPP_OPTS "--filter=-build/c++14") diff --git a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp index bee95e20f6e..1a444f42cb1 100644 --- a/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp +++ b/core_planning/decision_maker/nodes/decision_maker/decision_maker_node_callback.cpp @@ -17,9 +17,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/core_planning/decision_maker/package.xml b/core_planning/decision_maker/package.xml index 2595144d36a..584a41a4a64 100644 --- a/core_planning/decision_maker/package.xml +++ b/core_planning/decision_maker/package.xml @@ -26,6 +26,7 @@ vector_map vector_map_msgs lanelet2_extension + autoware_lanelet2_ros_interface rostest rosunit diff --git a/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp b/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp index 19ce3aaf7d7..2448600393f 100644 --- a/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp +++ b/core_planning/decision_maker/test/src/test_node_lanelet2_functions.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include diff --git a/core_planning/lane_planner/CMakeLists.txt b/core_planning/lane_planner/CMakeLists.txt index 6c5cee00d2a..22a54a6bc35 100644 --- a/core_planning/lane_planner/CMakeLists.txt +++ b/core_planning/lane_planner/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(catkin REQUIRED COMPONENTS std_msgs tablet_socket_msgs vector_map + autoware_lanelet2_ros_interface ) set(CMAKE_CXX_FLAGS "-O2 -Wall ${CMAKE_CXX_FLAGS}") diff --git a/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp b/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp index d2541b1a1d8..766cfd9a03e 100644 --- a/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp +++ b/core_planning/lane_planner/nodes/lane_rule_lanelet2/lane_rule_lanelet2.cpp @@ -30,8 +30,8 @@ #include #include -#include -#include +#include +#include #include #include diff --git a/core_planning/lane_planner/package.xml b/core_planning/lane_planner/package.xml index 7e9eb4e0cec..14ef3cc063a 100644 --- a/core_planning/lane_planner/package.xml +++ b/core_planning/lane_planner/package.xml @@ -18,7 +18,7 @@ std_msgs tablet_socket_msgs vector_map - + autoware_lanelet2_ros_interface rostest rosunit diff --git a/core_planning/ll2_global_planner/CMakeLists.txt b/core_planning/ll2_global_planner/CMakeLists.txt index 2e23cb55223..2472d6ceb0d 100644 --- a/core_planning/ll2_global_planner/CMakeLists.txt +++ b/core_planning/ll2_global_planner/CMakeLists.txt @@ -15,6 +15,7 @@ set(catkin_deps roslint tf2 tf2_ros + autoware_lanelet2_ros_interface ) find_package(catkin REQUIRED ${catkin_deps}) diff --git a/core_planning/ll2_global_planner/package.xml b/core_planning/ll2_global_planner/package.xml index b161d8effda..7aab0c8ab08 100644 --- a/core_planning/ll2_global_planner/package.xml +++ b/core_planning/ll2_global_planner/package.xml @@ -17,6 +17,7 @@ roslint tf2_ros tf2 + autoware_lanelet2_ros_interface diff --git a/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp b/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp index cae02022a9b..27f0ff01d8b 100644 --- a/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp +++ b/core_planning/ll2_global_planner/src/ll2_global_planner_nodelet.cpp @@ -16,7 +16,7 @@ #include #include -#include +#include #include #include #include diff --git a/core_planning/waypoint_planner/CMakeLists.txt b/core_planning/waypoint_planner/CMakeLists.txt index 7e5790b600a..1c7d1b1a159 100644 --- a/core_planning/waypoint_planner/CMakeLists.txt +++ b/core_planning/waypoint_planner/CMakeLists.txt @@ -20,6 +20,7 @@ find_package( std_msgs tf vector_map + autoware_lanelet2_ros_interface ) catkin_package() diff --git a/core_planning/waypoint_planner/package.xml b/core_planning/waypoint_planner/package.xml index 62c90854875..ed87cacc1bd 100644 --- a/core_planning/waypoint_planner/package.xml +++ b/core_planning/waypoint_planner/package.xml @@ -24,5 +24,6 @@ std_msgs tf vector_map + autoware_lanelet2_ros_interface diff --git a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp index 41126bf8cf1..1a7be158514 100644 --- a/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp +++ b/core_planning/waypoint_planner/src/velocity_set_lanelet2/velocity_set_lanelet2.cpp @@ -27,9 +27,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include #include From cd200c807e41a313d118a2b60642a3f6d1768751 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Wed, 29 Sep 2021 16:59:10 +0000 Subject: [PATCH 12/23] Remove ros::Time dependency from CARMA Traffic Light --- common/lanelet2_extension/CMakeLists.txt | 5 ++ .../regulatory_elements/CarmaTrafficLight.h | 56 +++++++++++++++---- .../lib/CarmaTrafficLight.cpp | 53 +++++++++++++----- .../test/src/CarmaTrafficTest.cpp | 23 ++++---- 4 files changed, 99 insertions(+), 38 deletions(-) diff --git a/common/lanelet2_extension/CMakeLists.txt b/common/lanelet2_extension/CMakeLists.txt index c4f4dcc8fe6..2c11712a2d0 100644 --- a/common/lanelet2_extension/CMakeLists.txt +++ b/common/lanelet2_extension/CMakeLists.txt @@ -58,11 +58,14 @@ find_package(catkin REQUIRED COMPONENTS hardcoded_params ) +find_package(Boost REQUIRED) + catkin_package( INCLUDE_DIRS include LIBRARIES lanelet2_extension_lib CATKIN_DEPENDS ${LOGGER_DEP} lanelet2_core lanelet2_io lanelet2_maps lanelet2_projection lanelet2_routing lanelet2_traffic_rules lanelet2_validation hardcoded_params + DEPENDS Boost ) include_directories( @@ -71,6 +74,7 @@ include_directories( ${catkin_INCLUDE_DIRS} ${PUGIXML_INCLUDE_DIRS} ${PROJ4_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} ) add_definitions (${GeographicLib_DEFINITIONS}) @@ -99,6 +103,7 @@ target_link_libraries(lanelet2_extension_lib ${catkin_LIBRARIES} ${GeographicLib_LIBRARIES} ${PROJ4_LIBRARIES} + ${Boost_LIBRARIES} ) install(TARGETS lanelet2_extension_lib diff --git a/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/CarmaTrafficLight.h b/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/CarmaTrafficLight.h index a9fa17b874a..9c06954abb9 100644 --- a/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/CarmaTrafficLight.h +++ b/common/lanelet2_extension/include/lanelet2_extension/regulatory_elements/CarmaTrafficLight.h @@ -18,7 +18,7 @@ #define LANELET2_EXTENSION_REGULATORY_ELEMENTS_CARMA_TRAFFIC_LIGHT_H #include -#include +#include namespace lanelet { @@ -51,6 +51,42 @@ enum class CarmaTrafficLightState { CAUTION_CONFLICTING_TRAFFIC=9 }; +// Namespace for time representations used with this regulatory element +namespace time { + + /** + * \brief Converts a boost time duration into the number of posix seconds it represents + * + * \param duration The duration to convert. + * \return The number of posix seconds with microsecond resolution + */ + double toSec(const boost::posix_time::time_duration& duration); + + /** + * \brief Converts a boost time duration into the number of posix seconds since 1970 + * + * \param duration The duration to convert. + * \return The number of posix seconds since 1970 with microsecond resolution + */ + double toSec(const boost::posix_time::ptime& time); + + /** + * \brief Returns a boost posix time object which matches the input posix seconds since 1970 with microsecond accuracy. + * + * \param sec The number of posix seconds since 1970. Fractional seconds are supported. + * \return Initialized posix time object matching the input + */ + boost::posix_time::ptime timeFromSec(double sec); + + /** + * \brief Returns a boost posix time object which matches the input posix seconds duration with microsecond accuracy. + * + * \param sec The number of posix seconds the duration should reflect. Fractional seconds are supported. + * \return Initialized posix time duration object matching the input + */ + boost::posix_time::time_duration durationFromSec(double sec); +} + /** * \brief Stream operator for CarmaTrafficLightState enum. */ @@ -69,32 +105,27 @@ class CarmaTrafficLight : public lanelet::RegulatoryElement public: static constexpr char RuleName[] = "carma_traffic_light"; int revision_ = 0; //indicates when was this last modified - ros::Duration fixed_cycle_duration; - std::vector> recorded_time_stamps; + boost::posix_time::time_duration fixed_cycle_duration; + std::vector> recorded_time_stamps; /** * @brief setStates function sorts states automatically * * @param data The data to initialize this regulation with * NOTE: to extract full cycle, first and last state should match in input_time_steps */ - void setStates(std::vector> input_time_steps, int revision); + void setStates(std::vector> input_time_steps, int revision); /** * @brief getControlledLanelets function returns lanelets this element controls */ lanelet::ConstLanelets getControlledLanelets() const; - /** - * @brief getState get the current state - * - * @return return current, ros::Time::now - */ - boost::optional getState(); + /** * @brief prefictState assumes sorted, fixed time, so guaranteed to give you one final state * - * @param time_stamp ros::Time of the event happening + * @param time_stamp boost::posix_time::ptime of the event happening */ - boost::optional predictState(ros::Time time_stamp); + boost::optional predictState(boost::posix_time::ptime time_stamp); ConstLineStrings3d stopLine() const; LineStrings3d stopLine(); @@ -110,6 +141,7 @@ class CarmaTrafficLight : public lanelet::RegulatoryElement */ static std::unique_ptr buildData(Id id, LineString3d stop_line, Lanelets lanelets); + private: // the following lines are required so that lanelet2 can create this object // when loading a map with this regulatory element diff --git a/common/lanelet2_extension/lib/CarmaTrafficLight.cpp b/common/lanelet2_extension/lib/CarmaTrafficLight.cpp index 90d4222fb93..c5e9de0cc3c 100755 --- a/common/lanelet2_extension/lib/CarmaTrafficLight.cpp +++ b/common/lanelet2_extension/lib/CarmaTrafficLight.cpp @@ -16,10 +16,14 @@ #include #include +#include #include "RegulatoryHelpers.h" namespace lanelet { + +using namespace lanelet::time; + // C++ 14 vs 17 parameter export #if __cplusplus < 201703L constexpr char CarmaTrafficLight::RuleName[]; // instantiate string in cpp file @@ -76,16 +80,11 @@ std::unique_ptr CarmaTrafficLight::buildData(Id return std::make_unique(id, rules, attribute_map); } -boost::optional CarmaTrafficLight::getState() -{ - return predictState(ros::Time::now()); -} - -boost::optional CarmaTrafficLight::predictState(ros::Time time_stamp) +boost::optional CarmaTrafficLight::predictState(boost::posix_time::ptime time_stamp) { if (recorded_time_stamps.empty()) { - ROS_WARN_STREAM("CarmaTrafficLight doesn't have any recorded states of traffic lights"); + LOG_WARN_STREAM("CarmaTrafficLight doesn't have any recorded states of traffic lights"); return boost::none; } if (recorded_time_stamps.size() == 1) // if only 1 timestamp recorded, this signal doesn't change @@ -93,11 +92,11 @@ boost::optional CarmaTrafficLight::predictState(ros::Tim return recorded_time_stamps.front().second; } // shift starting time to the future or to the past to fit input into a valid cycle - ros::Duration accumulated_offset_duration; + boost::posix_time::time_duration accumulated_offset_duration; double offset_duration_dir = recorded_time_stamps.front().first > time_stamp ? -1.0 : 1.0; // -1 if past, +1 if time_stamp is in future - int num_of_cycles = std::abs((recorded_time_stamps.front().first - time_stamp).toSec()/ fixed_cycle_duration.toSec()); - accumulated_offset_duration = ros::Duration( num_of_cycles * fixed_cycle_duration.toSec()); + int num_of_cycles = std::abs(toSec(recorded_time_stamps.front().first - time_stamp) / toSec(fixed_cycle_duration)); + accumulated_offset_duration = durationFromSec( num_of_cycles * toSec(fixed_cycle_duration)); if (offset_duration_dir < 0) { @@ -109,7 +108,7 @@ boost::optional CarmaTrafficLight::predictState(ros::Tim // iterate through states in the cycle to get the signal for (size_t i = 0; i < recorded_time_stamps.size(); i++) { - if (recorded_time_stamps[i].first.toSec() + offset_duration_dir * accumulated_offset_duration.toSec() >= time_stamp.toSec()) + if (toSec(recorded_time_stamps[i].first) + offset_duration_dir * toSec(accumulated_offset_duration) >= toSec(time_stamp)) { return recorded_time_stamps[i].second; } @@ -123,11 +122,11 @@ lanelet::ConstLanelets CarmaTrafficLight::getControlledLanelets() const return getParameters(RoleName::Refers); } -void CarmaTrafficLight::setStates(std::vector> input_time_steps, int revision) +void CarmaTrafficLight::setStates(std::vector> input_time_steps, int revision) { if (input_time_steps.empty()) { - ROS_ERROR_STREAM("Given states for the CarmaTrafficLight Id: " << id() << " is empty. Returning..."); + LOG_ERROR_STREAM("Given states for the CarmaTrafficLight Id: " << id() << " is empty. Returning..."); return; } @@ -153,6 +152,34 @@ void CarmaTrafficLight::setStates(std::vector(sec * 1000000L)); +} + +boost::posix_time::time_duration durationFromSec(double sec) { + return boost::posix_time::microseconds(static_cast(sec * 1000000L)); +} + +} // namespace time + + + namespace { // this object actually does the registration work for us diff --git a/common/lanelet2_extension/test/src/CarmaTrafficTest.cpp b/common/lanelet2_extension/test/src/CarmaTrafficTest.cpp index b5ccc7e03d1..6e434aac2b3 100755 --- a/common/lanelet2_extension/test/src/CarmaTrafficTest.cpp +++ b/common/lanelet2_extension/test/src/CarmaTrafficTest.cpp @@ -54,29 +54,26 @@ TEST(CarmaTrafficLightTest, CarmaTrafficLight) std::shared_ptr traffic_light(new CarmaTrafficLight(CarmaTrafficLight::buildData(lanelet::utils::getId(), { virtual_stop_line }, {ll_1, ll_2}))); ll_1.addRegulatoryElement(traffic_light); - std::vector> input_time_steps; + std::vector> input_time_steps; - input_time_steps.push_back(std::make_pair(ros::Time(1001),static_cast(0))); - input_time_steps.push_back(std::make_pair(ros::Time(1002),static_cast(1))); - input_time_steps.push_back(std::make_pair(ros::Time(1003),static_cast(2))); - input_time_steps.push_back(std::make_pair(ros::Time(1004),static_cast(3))); - input_time_steps.push_back(std::make_pair(ros::Time(1005),static_cast(4))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1001),static_cast(0))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1002),static_cast(1))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1003),static_cast(2))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1004),static_cast(3))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1005),static_cast(4))); EXPECT_THROW(traffic_light->setStates(input_time_steps,0), lanelet::InvalidInputError); - input_time_steps.push_back(std::make_pair(ros::Time(1006),static_cast(0))); + input_time_steps.push_back(std::make_pair(time::timeFromSec(1006),static_cast(0))); traffic_light->setStates(input_time_steps,0); ASSERT_EQ(6,traffic_light->recorded_time_stamps.size()); - ASSERT_EQ(ros::Duration(5),traffic_light->fixed_cycle_duration); + ASSERT_EQ(time::durationFromSec(5),traffic_light->fixed_cycle_duration); ASSERT_EQ(0,traffic_light->revision_); - - ros::Time::init(); - ros::Time::setNow(ros::Time(1.5)); - ASSERT_EQ(static_cast(1),traffic_light->getState().get()); - ASSERT_EQ(static_cast(0),traffic_light->predictState(ros::Time(1)).get()); + ASSERT_EQ(static_cast(1),traffic_light->predictState(time::timeFromSec(1.5)).get()); + ASSERT_EQ(static_cast(0),traffic_light->predictState(time::timeFromSec(1)).get()); ASSERT_EQ(traffic_light->getControlledLanelets().size(), 2); ASSERT_EQ(traffic_light->getControlledLanelets().back().id(), ll_2.id()); From 337628a86df9787a59a738c101d0174868e21f7b Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Wed, 29 Sep 2021 18:53:59 +0000 Subject: [PATCH 13/23] fix build error in pure_pursuit after merge --- core_planning/pure_pursuit/src/pure_pursuit_core.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp index 46fd8dd657b..ff7e33a7f79 100644 --- a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp +++ b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp @@ -112,7 +112,7 @@ void PurePursuitNode::initForROS() void PurePursuitNode::run() { ROS_INFO_STREAM("pure pursuit start"); - ros::Rate loop_rate(LOOP_RATE_); + ros::Rate loop_rate(update_rate_); ros::Timer command_pub_timer = nh_.createTimer( // Create a ros timer to publish commands at the expected loop rate loop_rate.expectedCycleTime(), @@ -132,7 +132,7 @@ void PurePursuitNode::run() bool can_get_curvature = pp_.canGetCurvature(&kappa); this->publishTwistStamped(can_get_curvature, kappa); - this->publishControlCommandStamped(can_get_curvature, kappa); + this->publishControlCommands(can_get_curvature, kappa); health_checker_ptr_->NODE_ACTIVATE(); health_checker_ptr_->CHECK_RATE("topic_rate_vehicle_cmd_slow", 8, 5, 1, "topic vehicle_cmd publish rate slow."); From 0b0c24c7f727d398bf2196bade79d0b9fa0d841d Mon Sep 17 00:00:00 2001 From: SaikrishnaBairamoni Date: Tue, 12 Oct 2021 10:30:21 -0400 Subject: [PATCH 14/23] updated docker tags to candidate --- .circleci/config.yml | 2 +- Dockerfile | 2 +- docker/checkout.bash | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 1b706937a10..8bae55db1c5 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -28,7 +28,7 @@ jobs: # Pull docker image from docker hub # XTERM used for better catkin_make output docker: - - image: usdotfhwastoldev/carma-base:noetic-develop + - image: usdotfhwastolcandidate/carma-base:elise user: carma environment: TERM: xterm diff --git a/Dockerfile b/Dockerfile index 28029af1419..1a371fc2611 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,4 @@ -FROM usdotfhwastoldev/carma-base:noetic-develop as base_image +FROM usdotfhwastolcandidate/carma-base:elise as base_image FROM base_image as build diff --git a/docker/checkout.bash b/docker/checkout.bash index deb6c1e0f64..131768933fe 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -37,7 +37,7 @@ cd ${dir}/autoware.ai if [[ "$BRANCH" = "noetic/develop" ]]; then git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch $BRANCH else - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch noetic/develop + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch release/elise fi # Required to build pacmod_msgs From 5b2bb7b0f181c7babeec63d916872dde4c39c35e Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Tue, 12 Oct 2021 19:49:16 +0000 Subject: [PATCH 15/23] Cleanup print in pure_pursuit --- core_planning/pure_pursuit/src/pure_pursuit_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp index ff7e33a7f79..6a765e1a96f 100644 --- a/core_planning/pure_pursuit/src/pure_pursuit_core.cpp +++ b/core_planning/pure_pursuit/src/pure_pursuit_core.cpp @@ -121,7 +121,7 @@ void PurePursuitNode::run() if (!is_pose_set_ || !is_waypoint_set_ || !is_velocity_set_) // One time check on desired input data { - ROS_WARN("Necessary topics are not subscribed yet ... "); + ROS_DEBUG("Necessary topics are not subscribed yet ... "); return; } From 5a2a6ef8cdd5a9ae1b2c452e6525465f509d4a5d Mon Sep 17 00:00:00 2001 From: carma developer Date: Tue, 12 Oct 2021 15:53:27 -0400 Subject: [PATCH 16/23] Revert NDT matching to carma-develop --- .../launch/ndt_matching.launch | 6 +- .../nodes/ndt_matching/ndt_matching.cpp | 289 +++++++++--------- 2 files changed, 139 insertions(+), 156 deletions(-) diff --git a/core_perception/lidar_localizer/launch/ndt_matching.launch b/core_perception/lidar_localizer/launch/ndt_matching.launch index 824742349ae..6d0fd94b8ac 100644 --- a/core_perception/lidar_localizer/launch/ndt_matching.launch +++ b/core_perception/lidar_localizer/launch/ndt_matching.launch @@ -10,11 +10,11 @@ - + - + @@ -28,8 +28,8 @@ - + diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 40ab46777cc..4f1dad2c3b3 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -30,23 +30,23 @@ #include +#include #include #include #include -#include #include #include #include -#include +#include #include #include #include -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -62,6 +62,9 @@ #include #endif +#include +#include + #include #include @@ -105,7 +108,8 @@ static double offset_odom_x, offset_odom_y, offset_odom_z, offset_odom_roll, off static double offset_imu_odom_x, offset_imu_odom_y, offset_imu_odom_z, offset_imu_odom_roll, offset_imu_odom_pitch, offset_imu_odom_yaw; -static pcl::PointCloud map; +// Can't load if typed "pcl::PointCloud map, add;" +static pcl::PointCloud map, add; // If the map is loaded, map_loaded will be 1. static int map_loaded = 0; @@ -143,6 +147,12 @@ static geometry_msgs::PoseStamped predict_pose_imu_odom_msg; static ros::Publisher ndt_pose_pub; static geometry_msgs::PoseStamped ndt_pose_msg; +// current_pose is published by vel_pose_mux +/* +static ros::Publisher current_pose_pub; +static geometry_msgs::PoseStamped current_pose_msg; + */ + static ros::Publisher localizer_pose_pub; static geometry_msgs::PoseStamped localizer_pose_msg; @@ -167,6 +177,7 @@ static double current_velocity = 0.0, previous_velocity = 0.0, previous_previous static double current_velocity_x = 0.0, previous_velocity_x = 0.0; static double current_velocity_y = 0.0, previous_velocity_y = 0.0; static double current_velocity_z = 0.0, previous_velocity_z = 0.0; +// static double current_velocity_yaw = 0.0, previous_velocity_yaw = 0.0; static double current_velocity_smooth = 0.0; static double current_velocity_imu_x = 0.0; @@ -177,6 +188,7 @@ static double current_accel = 0.0, previous_accel = 0.0; // [m/s^2] static double current_accel_x = 0.0; static double current_accel_y = 0.0; static double current_accel_z = 0.0; +// static double current_accel_yaw = 0.0; static double angular_velocity = 0.0; @@ -197,9 +209,10 @@ static autoware_msgs::NDTStat ndt_stat_msg; static double predict_pose_error = 0.0; -// hold transfrom from baselink to primary lidar +static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; static Eigen::Matrix4f tf_btol; +static std::string _localizer = "velodyne"; static std::string _offset = "linear"; // linear, zero, quadratic static ros::Publisher ndt_reliability_pub; @@ -211,8 +224,6 @@ static bool _use_imu = false; static bool _use_odom = false; static bool _imu_upside_down = false; static bool _output_log_data = false; -static std::string _output_tf_frame_id = "base_link"; -static std::string _map_frame = "map"; static std::string _imu_topic = "/imu_raw"; @@ -222,7 +233,11 @@ static std::string filename; static sensor_msgs::Imu imu; static nav_msgs::Odometry odom; -static tf2::Stamped local_transform; +// static tf::TransformListener local_transform_listener; +static tf::StampedTransform local_transform; + +static std::string _base_frame = "base_link"; +static std::string _map_frame = "map"; static unsigned int points_map_num = 0; @@ -230,23 +245,23 @@ pthread_mutex_t mutex; static pose convertPoseIntoRelativeCoordinate(const pose &target_pose, const pose &reference_pose) { - tf2::Quaternion target_q; + tf::Quaternion target_q; target_q.setRPY(target_pose.roll, target_pose.pitch, target_pose.yaw); - tf2::Vector3 target_v(target_pose.x, target_pose.y, target_pose.z); - tf2::Transform target_tf(target_q, target_v); + tf::Vector3 target_v(target_pose.x, target_pose.y, target_pose.z); + tf::Transform target_tf(target_q, target_v); - tf2::Quaternion reference_q; + tf::Quaternion reference_q; reference_q.setRPY(reference_pose.roll, reference_pose.pitch, reference_pose.yaw); - tf2::Vector3 reference_v(reference_pose.x, reference_pose.y, reference_pose.z); - tf2::Transform reference_tf(reference_q, reference_v); + tf::Vector3 reference_v(reference_pose.x, reference_pose.y, reference_pose.z); + tf::Transform reference_tf(reference_q, reference_v); - tf2::Transform trans_target_tf = reference_tf.inverse() * target_tf; + tf::Transform trans_target_tf = reference_tf.inverse() * target_tf; pose trans_target_pose; trans_target_pose.x = trans_target_tf.getOrigin().getX(); trans_target_pose.y = trans_target_tf.getOrigin().getY(); trans_target_pose.z = trans_target_tf.getOrigin().getZ(); - tf2::Matrix3x3 tmp_m(trans_target_tf.getRotation()); + tf::Matrix3x3 tmp_m(trans_target_tf.getRotation()); tmp_m.getRPY(trans_target_pose.roll, trans_target_pose.pitch, trans_target_pose.yaw); return trans_target_pose; @@ -300,7 +315,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setStepSize(step_size); + omp_ndt.setStepSize(ndt_res); #endif } @@ -318,7 +333,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setTransformationEpsilon(trans_eps); + omp_ndt.setTransformationEpsilon(ndt_res); #endif } @@ -336,7 +351,7 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu #endif #ifdef USE_PCL_OPENMP else if (_method_type == MethodType::PCL_OPENMP) - omp_ndt.setMaximumIterations(max_iter); + omp_ndt.setMaximumIterations(ndt_res); #endif } @@ -351,15 +366,15 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu if (_use_local_transform == true) { - tf2::Vector3 v(input->x, input->y, input->z); - tf2::Quaternion q; + tf::Vector3 v(input->x, input->y, input->z); + tf::Quaternion q; q.setRPY(input->roll, input->pitch, input->yaw); - tf2::Transform transform(q, v); + tf::Transform transform(q, v); initial_pose.x = (local_transform.inverse() * transform).getOrigin().getX(); initial_pose.y = (local_transform.inverse() * transform).getOrigin().getY(); initial_pose.z = (local_transform.inverse() * transform).getOrigin().getZ(); - tf2::Matrix3x3 m(q); + tf::Matrix3x3 m(q); m.getRPY(initial_pose.roll, initial_pose.pitch, initial_pose.yaw); std::cout << "initial_pose.x: " << initial_pose.x << std::endl; @@ -418,7 +433,9 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) if (points_map_num != input->width) { std::cout << "Update points_map." << std::endl; + _map_frame = input->header.frame_id; // Update map frame to be the frame of the map points topic + points_map_num = input->width; // Convert the data type(from sensor_msgs to pcl). @@ -426,20 +443,19 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) if (_use_local_transform == true) { - tf2_ros::Buffer tf_buffer; - tf2_ros::TransformListener tf_listener(tf_buffer); - geometry_msgs::TransformStamped local_transform_msg; + tf::TransformListener local_transform_listener; try { - local_transform_msg = tf_buffer.lookupTransform(_map_frame, "world", ros::Time::now(), ros::Duration(3.0)); + ros::Time now = ros::Time(0); + local_transform_listener.waitForTransform(_map_frame, "/world", now, ros::Duration(10.0)); + local_transform_listener.lookupTransform(_map_frame, "world", now, local_transform); } - catch (tf2::TransformException& ex) + catch (tf::TransformException& ex) { ROS_ERROR("%s", ex.what()); } - tf2::fromMsg(local_transform_msg, local_transform); - pcl::transformPointCloud(map, map, tf2::transformToEigen(local_transform_msg).matrix().inverse().cast()); + pcl_ros::transformPointCloud(map, map, local_transform.inverse()); } pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); @@ -528,9 +544,9 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) static void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input) { - tf2::Quaternion gnss_q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z, + tf::Quaternion gnss_q(input->pose.orientation.x, input->pose.orientation.y, input->pose.orientation.z, input->pose.orientation.w); - tf2::Matrix3x3 gnss_m(gnss_q); + tf::Matrix3x3 gnss_m(gnss_q); pose current_gnss_pose; current_gnss_pose.x = input->pose.position.x; @@ -595,21 +611,22 @@ static void gnss_callback(const geometry_msgs::PoseStamped::ConstPtr& input) static void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& input) { - tf2_ros::Buffer tf_buffer; - tf2_ros::TransformListener tf_listener(tf_buffer); - geometry_msgs::TransformStamped tf_msg; + tf::TransformListener listener; + tf::StampedTransform transform; try { - tf_msg = tf_buffer.lookupTransform(_map_frame, input->header.frame_id, ros::Time::now(), ros::Duration(3.0)); + ros::Time now = ros::Time(0); + listener.waitForTransform(_map_frame, input->header.frame_id, now, ros::Duration(10.0)); + listener.lookupTransform(_map_frame, input->header.frame_id, now, transform); } - catch (tf2::TransformException& ex) + catch (tf::TransformException& ex) { ROS_ERROR("%s", ex.what()); } - tf2::Quaternion q(input->pose.pose.orientation.x, input->pose.pose.orientation.y, input->pose.pose.orientation.z, + tf::Quaternion q(input->pose.pose.orientation.x, input->pose.pose.orientation.y, input->pose.pose.orientation.z, input->pose.pose.orientation.w); - tf2::Matrix3x3 m(q); + tf::Matrix3x3 m(q); if (_use_local_transform == true) { @@ -619,9 +636,9 @@ static void initialpose_callback(const geometry_msgs::PoseWithCovarianceStamped: } else { - current_pose.x = input->pose.pose.position.x + tf_msg.transform.translation.x; - current_pose.y = input->pose.pose.position.y + tf_msg.transform.translation.y; - current_pose.z = input->pose.pose.position.z + tf_msg.transform.translation.z; + current_pose.x = input->pose.pose.position.x + transform.getOrigin().x(); + current_pose.y = input->pose.pose.position.y + transform.getOrigin().y(); + current_pose.z = input->pose.pose.position.z + transform.getOrigin().z(); } m.getRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); @@ -828,24 +845,19 @@ static double calcDiffForRadian(const double lhs_rad, const double rhs_rad) static void odom_callback(const nav_msgs::Odometry::ConstPtr& input) { + // std::cout << __func__ << std::endl; + odom = *input; odom_calc(input->header.stamp); } -static void vehicle_twist_callback(const geometry_msgs::TwistStampedConstPtr& msg) -{ - odom.header = msg->header; - odom.twist.twist = msg->twist; - odom_calc(odom.header.stamp); -} - static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) { double input_roll, input_pitch, input_yaw; - tf2::Quaternion input_orientation; - tf2::fromMsg(input->orientation, input_orientation); - tf2::Matrix3x3(input_orientation).getRPY(input_roll, input_pitch, input_yaw); + tf::Quaternion input_orientation; + tf::quaternionMsgToTF(input->orientation, input_orientation); + tf::Matrix3x3(input_orientation).getRPY(input_roll, input_pitch, input_yaw); input->angular_velocity.x *= -1; input->angular_velocity.y *= -1; @@ -859,9 +871,7 @@ static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) input_pitch *= -1; input_yaw *= -1; - tf2::Quaternion tf_quat; - tf_quat.setRPY(input_roll, input_pitch, input_yaw); - input->orientation = tf2::toMsg(tf_quat); + input->orientation = tf::createQuaternionMsgFromRollPitchYaw(input_roll, input_pitch, input_yaw); } static void imu_callback(const sensor_msgs::Imu::Ptr& input) @@ -876,9 +886,9 @@ static void imu_callback(const sensor_msgs::Imu::Ptr& input) const double diff_time = (current_time - previous_time).toSec(); double imu_roll, imu_pitch, imu_yaw; - tf2::Quaternion imu_orientation; - tf2::fromMsg(input->orientation, imu_orientation); - tf2::Matrix3x3(imu_orientation).getRPY(imu_roll, imu_pitch, imu_yaw); + tf::Quaternion imu_orientation; + tf::quaternionMsgToTF(input->orientation, imu_orientation); + tf::Matrix3x3(imu_orientation).getRPY(imu_roll, imu_pitch, imu_yaw); imu_roll = wrapToPmPi(imu_roll); imu_pitch = wrapToPmPi(imu_pitch); @@ -924,9 +934,9 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) { matching_start = std::chrono::system_clock::now(); - static tf2_ros::TransformBroadcaster br; - tf2::Transform transform; - tf2::Quaternion predict_q, ndt_q, current_q, localizer_q; + static tf::TransformBroadcaster br; + tf::Transform transform; + tf::Quaternion predict_q, ndt_q, current_q, localizer_q; pcl::PointXYZ p; pcl::PointCloud filtered_scan; @@ -1099,7 +1109,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) pthread_mutex_unlock(&mutex); - tf2::Matrix3x3 mat_l; // localizer + tf::Matrix3x3 mat_l; // localizer mat_l.setValue(static_cast(t(0, 0)), static_cast(t(0, 1)), static_cast(t(0, 2)), static_cast(t(1, 0)), static_cast(t(1, 1)), static_cast(t(1, 2)), static_cast(t(2, 0)), static_cast(t(2, 1)), static_cast(t(2, 2))); @@ -1110,7 +1120,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) localizer_pose.z = t(2, 3); mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1); - tf2::Matrix3x3 mat_b; // base_link + tf::Matrix3x3 mat_b; // base_link mat_b.setValue(static_cast(t2(0, 0)), static_cast(t2(0, 1)), static_cast(t2(0, 2)), static_cast(t2(1, 0)), static_cast(t2(1, 1)), static_cast(t2(1, 2)), static_cast(t2(2, 0)), static_cast(t2(2, 1)), static_cast(t2(2, 2))); @@ -1217,8 +1227,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_q.setRPY(predict_pose.roll, predict_pose.pitch, predict_pose.yaw); if (_use_local_transform == true) { - tf2::Vector3 v(predict_pose.x, predict_pose.y, predict_pose.z); - tf2::Transform transform(predict_q, v); + tf::Vector3 v(predict_pose.x, predict_pose.y, predict_pose.z); + tf::Transform transform(predict_q, v); predict_pose_msg.header.frame_id = _map_frame; predict_pose_msg.header.stamp = current_scan_time; predict_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1242,7 +1252,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_msg.pose.orientation.w = predict_q.w(); } - tf2::Quaternion predict_q_imu; + tf::Quaternion predict_q_imu; predict_q_imu.setRPY(predict_pose_imu.roll, predict_pose_imu.pitch, predict_pose_imu.yaw); predict_pose_imu_msg.header.frame_id = _map_frame; predict_pose_imu_msg.header.stamp = input->header.stamp; @@ -1255,7 +1265,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_imu_msg.pose.orientation.w = predict_q_imu.w(); predict_pose_imu_pub.publish(predict_pose_imu_msg); - tf2::Quaternion predict_q_odom; + tf::Quaternion predict_q_odom; predict_q_odom.setRPY(predict_pose_odom.roll, predict_pose_odom.pitch, predict_pose_odom.yaw); predict_pose_odom_msg.header.frame_id = _map_frame; predict_pose_odom_msg.header.stamp = input->header.stamp; @@ -1268,7 +1278,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_odom_msg.pose.orientation.w = predict_q_odom.w(); predict_pose_odom_pub.publish(predict_pose_odom_msg); - tf2::Quaternion predict_q_imu_odom; + tf::Quaternion predict_q_imu_odom; predict_q_imu_odom.setRPY(predict_pose_imu_odom.roll, predict_pose_imu_odom.pitch, predict_pose_imu_odom.yaw); predict_pose_imu_odom_msg.header.frame_id = _map_frame; predict_pose_imu_odom_msg.header.stamp = input->header.stamp; @@ -1284,8 +1294,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) ndt_q.setRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw); if (_use_local_transform == true) { - tf2::Vector3 v(ndt_pose.x, ndt_pose.y, ndt_pose.z); - tf2::Transform transform(ndt_q, v); + tf::Vector3 v(ndt_pose.x, ndt_pose.y, ndt_pose.z); + tf::Transform transform(ndt_q, v); ndt_pose_msg.header.frame_id = _map_frame; ndt_pose_msg.header.stamp = current_scan_time; ndt_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1312,7 +1322,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) current_q.setRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); // current_pose is published by vel_pose_mux /* - current_pose_msg.header.frame_id = "map"; + current_pose_msg.header.frame_id = _map_frame; current_pose_msg.header.stamp = current_scan_time; current_pose_msg.pose.position.x = current_pose.x; current_pose_msg.pose.position.y = current_pose.y; @@ -1326,8 +1336,8 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) localizer_q.setRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw); if (_use_local_transform == true) { - tf2::Vector3 v(localizer_pose.x, localizer_pose.y, localizer_pose.z); - tf2::Transform transform(localizer_q, v); + tf::Vector3 v(localizer_pose.x, localizer_pose.y, localizer_pose.z); + tf::Transform transform(localizer_q, v); localizer_pose_msg.header.frame_id = _map_frame; localizer_pose_msg.header.stamp = current_scan_time; localizer_pose_msg.pose.position.x = (local_transform * transform).getOrigin().getX(); @@ -1354,19 +1364,24 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) predict_pose_pub.publish(predict_pose_msg); health_checker_ptr_->CHECK_RATE("topic_rate_ndt_pose_slow", 8, 5, 1, "topic ndt_pose publish rate slow."); ndt_pose_pub.publish(ndt_pose_msg); + // current_pose is published by vel_pose_mux + // current_pose_pub.publish(current_pose_msg); localizer_pose_pub.publish(localizer_pose_msg); - // Send TF "base_link" to "map" - transform.setOrigin(tf2::Vector3(current_pose.x, current_pose.y, current_pose.z)); + // Send TF _base_frame to _map_frame + transform.setOrigin(tf::Vector3(current_pose.x, current_pose.y, current_pose.z)); transform.setRotation(current_q); + // br.sendTransform(tf::StampedTransform(transform, current_scan_time, _map_frame, _base_frame)); + /* Removed to allow CARMA localization node to publish this TF if (_use_local_transform == true) { - transform = local_transform * transform; + br.sendTransform(tf::StampedTransform(local_transform * transform, current_scan_time, _map_frame, _base_frame)); + } + else + { + br.sendTransform(tf::StampedTransform(transform, current_scan_time, _map_frame, _base_frame)); } - tf2::Stamped tf(transform, current_scan_time, _map_frame); - geometry_msgs::TransformStamped tf_msg = tf2::toMsg(tf); - tf_msg.child_frame_id = _output_tf_frame_id; - br.sendTransform(tf_msg); + */ matching_end = std::chrono::system_clock::now(); exe_time = std::chrono::duration_cast(matching_end - matching_start).count() / 1000.0; @@ -1376,7 +1391,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) // Set values for /estimate_twist estimate_twist_msg.header.stamp = current_scan_time; - estimate_twist_msg.header.frame_id = "base_link"; + estimate_twist_msg.header.frame_id = _base_frame; estimate_twist_msg.twist.linear.x = current_velocity; estimate_twist_msg.twist.linear.y = 0.0; estimate_twist_msg.twist.linear.z = 0.0; @@ -1436,7 +1451,7 @@ static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) std::cout << "Sequence: " << input->header.seq << std::endl; std::cout << "Timestamp: " << input->header.stamp << std::endl; std::cout << "Frame ID: " << input->header.frame_id << std::endl; - // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; + // std::cout << "Number of Scan Points: " << scan_ptr->size() << " points." << std::endl; std::cout << "Number of Filtered Scan Points: " << scan_points_num << " points." << std::endl; std::cout << "NDT has converged: " << has_converged << std::endl; std::cout << "Fitness Score: " << fitness_score << std::endl; @@ -1551,84 +1566,45 @@ int main(int argc, char** argv) private_nh.getParam("imu_upside_down", _imu_upside_down); private_nh.getParam("imu_topic", _imu_topic); private_nh.param("gnss_reinit_fitness", _gnss_reinit_fitness, 500.0); - private_nh.getParam("output_tf_frame_id", _output_tf_frame_id); + private_nh.getParam("base_frame", _base_frame); - std::string lidar_frame; - nh.param("localizer", lidar_frame, std::string("lidar")); - tf2_ros::Buffer tf_buffer; - tf2_ros::TransformListener tf_listener(tf_buffer); - geometry_msgs::TransformStamped tf_baselink2primarylidar; - bool received_tf = true; - // 1. Try getting base_link -> lidar TF from TF tree - try + if (nh.getParam("localizer", _localizer) == false) + { + std::cout << "localizer is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_x", _tf_x) == false) { - tf_baselink2primarylidar = - tf_buffer.lookupTransform("base_link", lidar_frame, ros::Time().now(), ros::Duration(3.0)); + std::cout << "tf_x is not set." << std::endl; + return 1; } - catch (tf2::TransformException& ex) + if (nh.getParam("tf_y", _tf_y) == false) { - ROS_WARN("Query base_link to primary lidar frame through TF tree failed: %s", ex.what()); - received_tf = false; + std::cout << "tf_y is not set." << std::endl; + return 1; } - - // 2. Try getting base_link -> lidar TF from tf_baselink2primarylidar param - if (!received_tf) + if (nh.getParam("tf_z", _tf_z) == false) { - std::vector bl2pl_vec; - if (nh.getParam("tf_baselink2primarylidar", bl2pl_vec) && bl2pl_vec.size() == 6) - { - tf2::Vector3 tf_trans(bl2pl_vec[0], bl2pl_vec[1], bl2pl_vec[2]); - tf2::Quaternion tf_quat; - tf_quat.setRPY(bl2pl_vec[5], bl2pl_vec[4], bl2pl_vec[3]); - tf_baselink2primarylidar.transform.translation = tf2::toMsg(tf_trans); - tf_baselink2primarylidar.transform.rotation = tf2::toMsg(tf_quat); - - received_tf = true; - } - else - { - ROS_WARN("Query base_link to primary lidar frame through tf_baselink2primarylidar param failed"); - } + std::cout << "tf_z is not set." << std::endl; + return 1; } - - // 3. Try getting base_link -> lidar TF from tf_* params - if (!received_tf) + if (nh.getParam("tf_roll", _tf_roll) == false) { - float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw; - if (nh.getParam("tf_x", tf_x) && - nh.getParam("tf_y", tf_y) && - nh.getParam("tf_z", tf_z) && - nh.getParam("tf_roll", tf_roll) && - nh.getParam("tf_pitch", tf_pitch) && - nh.getParam("tf_yaw", tf_yaw)) - { - tf2::Vector3 tf_trans(tf_x, tf_y, tf_z); - tf2::Quaternion tf_quat; - tf_quat.setRPY(tf_roll, tf_pitch, tf_yaw); - tf_baselink2primarylidar.transform.translation = tf2::toMsg(tf_trans); - tf_baselink2primarylidar.transform.rotation = tf2::toMsg(tf_quat); - - received_tf = true; - } - else - { - ROS_WARN("Query base_link to primary lidar frame through tf_* params failed"); - } + std::cout << "tf_roll is not set." << std::endl; + return 1; } - - if (received_tf) + if (nh.getParam("tf_pitch", _tf_pitch) == false) { - ROS_INFO("base_link to primary lidar transform queried successfully"); + std::cout << "tf_pitch is not set." << std::endl; + return 1; } - else + if (nh.getParam("tf_yaw", _tf_yaw) == false) { - ROS_ERROR("Failed to query base_link to primary lidar transform"); + std::cout << "tf_yaw is not set." << std::endl; return 1; } - tf_btol = tf2::transformToEigen(tf_baselink2primarylidar).matrix().cast(); - std::cout << "-----------------------------------------------------------------" << std::endl; std::cout << "Log file: " << filename << std::endl; std::cout << "method_type: " << static_cast(_method_type) << std::endl; @@ -1641,9 +1617,11 @@ int main(int argc, char** argv) std::cout << "use_imu: " << _use_imu << std::endl; std::cout << "imu_upside_down: " << _imu_upside_down << std::endl; std::cout << "imu_topic: " << _imu_topic << std::endl; - std::cout << "localizer: " << lidar_frame << std::endl; + std::cout << "localizer: " << _localizer << std::endl; std::cout << "gnss_reinit_fitness: " << _gnss_reinit_fitness << std::endl; - std::cout << "tf_baselink2primarylidar: \n" << tf_btol << std::endl; + std::cout << "base_frame: " << _base_frame << std::endl; + std::cout << "(tf_x,tf_y,tf_z,tf_roll,tf_pitch,tf_yaw): (" << _tf_x << ", " << _tf_y << ", " << _tf_z << ", " + << _tf_roll << ", " << _tf_pitch << ", " << _tf_yaw << ")" << std::endl; std::cout << "-----------------------------------------------------------------" << std::endl; #ifndef CUDA_FOUND @@ -1665,6 +1643,12 @@ int main(int argc, char** argv) } #endif + Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation + Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation + Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); + Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ()); + tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix(); + // Updated in initialpose_callback or gnss_callback initial_pose.x = 0.0; initial_pose.y = 0.0; @@ -1691,13 +1675,12 @@ int main(int argc, char** argv) // Subscribers ros::Subscriber param_sub = nh.subscribe("config/ndt", 10, param_callback); - ros::Subscriber gnss_sub = nh.subscribe("gnss_pose", 10, gnss_callback); + ros::Subscriber gnss_sub = nh.subscribe("gnss_pose", _queue_size, gnss_callback); // ros::Subscriber map_sub = nh.subscribe("points_map", 1, map_callback); - ros::Subscriber initialpose_sub = nh.subscribe("initialpose", 10, initialpose_callback); + ros::Subscriber initialpose_sub = nh.subscribe("initialpose", _queue_size, initialpose_callback); ros::Subscriber points_sub = nh.subscribe("filtered_points", _queue_size, points_callback); - ros::Subscriber odom_sub = nh.subscribe("vehicle/odom", _queue_size * 10, odom_callback); + ros::Subscriber odom_sub = nh.subscribe("/vehicle/odom", _queue_size * 10, odom_callback); ros::Subscriber imu_sub = nh.subscribe(_imu_topic.c_str(), _queue_size * 10, imu_callback); - ros::Subscriber twist_sub = nh.subscribe("vehicle/twist", 10, vehicle_twist_callback); pthread_t thread; pthread_create(&thread, NULL, thread_func, NULL); From 8cac8d414d6fbfdd01a916aaaa6bf390e5639fa9 Mon Sep 17 00:00:00 2001 From: carma developer Date: Tue, 12 Oct 2021 16:32:53 -0400 Subject: [PATCH 17/23] fix build of ndt_matching on noetic --- core_perception/lidar_localizer/CMakeLists.txt | 2 ++ .../lidar_localizer/nodes/ndt_matching/ndt_matching.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/core_perception/lidar_localizer/CMakeLists.txt b/core_perception/lidar_localizer/CMakeLists.txt index 2c917a539f2..0beac7c77e5 100644 --- a/core_perception/lidar_localizer/CMakeLists.txt +++ b/core_perception/lidar_localizer/CMakeLists.txt @@ -52,6 +52,7 @@ find_package(catkin REQUIRED COMPONENTS tf tf_conversions velodyne_pointcloud + velodyne_pcl ) catkin_package( @@ -65,6 +66,7 @@ catkin_package( ndt_tku std_msgs velodyne_pointcloud + velodyne_pcl DEPENDS PCL ) diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 4f1dad2c3b3..3557429a469 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include From ac98639745795b682115889b8a48faa0d3fe6848 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Thu, 14 Oct 2021 20:04:33 +0000 Subject: [PATCH 18/23] Fix EKF publication --- core_perception/ekf_localizer/src/ekf_localizer.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/core_perception/ekf_localizer/src/ekf_localizer.cpp b/core_perception/ekf_localizer/src/ekf_localizer.cpp index 5acad4a5923..990ab33aead 100644 --- a/core_perception/ekf_localizer/src/ekf_localizer.cpp +++ b/core_perception/ekf_localizer/src/ekf_localizer.cpp @@ -135,6 +135,7 @@ void EKFLocalizer::timerCallback(const ros::TimerEvent& e) /* publish ekf result */ publishEstimateResult(); + broadcastTF(); } void EKFLocalizer::showCurrentX() From c2de371e8764a68918f4fd9db76fdcc2eac3ee88 Mon Sep 17 00:00:00 2001 From: carma developer Date: Mon, 18 Oct 2021 10:27:26 -0400 Subject: [PATCH 19/23] Remove colcon ignore from message packages --- messages/autoware_can_msgs/COLCON_IGNORE | 0 messages/autoware_map_msgs/COLCON_IGNORE | 0 messages/autoware_system_msgs/COLCON_IGNORE | 0 messages/tablet_socket_msgs/COLCON_IGNORE | 0 4 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 messages/autoware_can_msgs/COLCON_IGNORE delete mode 100644 messages/autoware_map_msgs/COLCON_IGNORE delete mode 100644 messages/autoware_system_msgs/COLCON_IGNORE delete mode 100644 messages/tablet_socket_msgs/COLCON_IGNORE diff --git a/messages/autoware_can_msgs/COLCON_IGNORE b/messages/autoware_can_msgs/COLCON_IGNORE deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/messages/autoware_map_msgs/COLCON_IGNORE b/messages/autoware_map_msgs/COLCON_IGNORE deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/messages/autoware_system_msgs/COLCON_IGNORE b/messages/autoware_system_msgs/COLCON_IGNORE deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/messages/tablet_socket_msgs/COLCON_IGNORE b/messages/tablet_socket_msgs/COLCON_IGNORE deleted file mode 100644 index e69de29bb2d..00000000000 From 72baa455ac6f70929b400f439179959f9392dcaa Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Tue, 26 Oct 2021 08:50:35 -0400 Subject: [PATCH 20/23] Fix the ray ground filter point size calculation (#180) --- .../launch/ray_ground_filter.launch | 2 +- .../ray_ground_filter/ray_ground_filter.cpp | 17 ++++++++++++++--- 2 files changed, 15 insertions(+), 4 deletions(-) diff --git a/core_perception/points_preprocessor/launch/ray_ground_filter.launch b/core_perception/points_preprocessor/launch/ray_ground_filter.launch index fb6cffdaa90..bf2836f7f19 100644 --- a/core_perception/points_preprocessor/launch/ray_ground_filter.launch +++ b/core_perception/points_preprocessor/launch/ray_ground_filter.launch @@ -14,7 +14,7 @@ - + diff --git a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp index 33b05cf947a..881867c710c 100644 --- a/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp +++ b/core_perception/points_preprocessor/nodes/ray_ground_filter/ray_ground_filter.cpp @@ -104,7 +104,12 @@ void RayGroundFilter::filterROSMsg(const sensor_msgs::PointCloud2ConstPtr in_ori const std::vector& in_selector, const sensor_msgs::PointCloud2::Ptr out_filtered_msg) { - size_t point_size = in_origin_cloud->row_step/in_origin_cloud->width; // in Byte + size_t point_size = in_origin_cloud->point_step; // in Byte + + if (point_size == 0) { + ROS_WARN_THROTTLE(5, "Cloud point_step of zero, can't filter message"); + return; + } // TODO(yoan picchi) I fear this may do a lot of cache miss because it is sorted in the radius // and no longer sorted in the original pointer. One thing to try is that, given @@ -263,7 +268,13 @@ void RayGroundFilter::ConvertAndTrim(const sensor_msgs::PointCloud2::Ptr in_tran std::vector* out_no_ground_ptrs) { // --- Clarify some of the values used to access the binary blob - size_t point_size = in_transformed_cloud->row_step/in_transformed_cloud->width; // in Byte + size_t point_size = in_transformed_cloud->point_step; // in Byte + + if (point_size == 0) { + ROS_WARN_THROTTLE(5, "Cloud point_step of zero, can't filter message"); + return; + } + size_t cloud_count = in_transformed_cloud->width*in_transformed_cloud->height; const uint offset_not_set = ~0; @@ -328,7 +339,7 @@ void RayGroundFilter::ConvertAndTrim(const sensor_msgs::PointCloud2::Ptr in_tran z = ReverseFloat(z); } // --- - + if (z > in_clip_height) { out_no_ground_ptrs->push_back(point_start_ptr); From 4a080ff0bf66516ee7e0d4f9b8e86530b2df5f41 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Mon, 6 Dec 2021 15:32:37 +0000 Subject: [PATCH 21/23] Change noetic-develop back to develop for builds --- docker/build-image.sh | 4 ++-- docker/checkout.bash | 4 ++-- hooks/pre_build | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docker/build-image.sh b/docker/build-image.sh index 56f5e158bc3..072efce9bb8 100755 --- a/docker/build-image.sh +++ b/docker/build-image.sh @@ -40,7 +40,7 @@ while [[ $# -gt 0 ]]; do ;; -d|--develop) USERNAME=usdotfhwastoldev - COMPONENT_VERSION_STRING=noetic-develop + COMPONENT_VERSION_STRING=develop shift ;; esac @@ -54,7 +54,7 @@ echo "Building docker image for $IMAGE version: $COMPONENT_VERSION_STRING" echo "Final image name: $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING" cd .. -if [[ $COMPONENT_VERSION_STRING = "noetic-develop" ]]; then +if [[ $COMPONENT_VERSION_STRING = "develop" ]]; then sed "s|usdotfhwastoldev/|$USERNAME/|g; s|usdotfhwastolcandidate/|$USERNAME/|g; s|usdotfhwastol/|$USERNAME/|g; s|:*[0-9].*[0-9].*[0-9]|:$COMPONENT_VERSION_STRING|g; s|checkout.bash|checkout.bash -d|g" \ Dockerfile | docker build -f - --no-cache -t $USERNAME/$IMAGE:$COMPONENT_VERSION_STRING \ --build-arg VERSION="$COMPONENT_VERSION_STRING" \ diff --git a/docker/checkout.bash b/docker/checkout.bash index 131768933fe..4f23d28b5b2 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -21,7 +21,7 @@ while [[ $# -gt 0 ]]; do arg="$1" case $arg in -d|--develop) - BRANCH=noetic/develop + BRANCH=carma-develop shift ;; -r|--root) @@ -34,7 +34,7 @@ done cd ${dir}/autoware.ai -if [[ "$BRANCH" = "noetic/develop" ]]; then +if [[ "$BRANCH" = "carma-develop" ]]; then git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch $BRANCH else git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch release/elise diff --git a/hooks/pre_build b/hooks/pre_build index 03e70de7fe4..4c44c7d2b4a 100644 --- a/hooks/pre_build +++ b/hooks/pre_build @@ -1,8 +1,8 @@ #!/bin/bash -if [[ "$SOURCE_BRANCH" = "noetic/develop" ]]; then +if [[ "$SOURCE_BRANCH" = "develop" ]]; then # update image dependencies - sed -i "s|usdotfhwastol/|usdotfhwastoldev/|g; s|:[0-9]*\.[0-9]*\.[0-9]*|:noetic-develop|g" \ + sed -i "s|usdotfhwastol/|usdotfhwastoldev/|g; s|:[0-9]*\.[0-9]*\.[0-9]*|:develop|g" \ Dockerfile elif [[ "$SOURCE_BRANCH" =~ ^release/.*$ ]]; then # update image dependencies From 42bc959dbf7801bb480f15ce5e478c290ef973a2 Mon Sep 17 00:00:00 2001 From: Michael McConnell Date: Tue, 14 Dec 2021 10:53:25 -0500 Subject: [PATCH 22/23] fix pcl version 1.10 compatibility with ndt (#190) This PR resolves usdot-fhwa-stol/carma-platform#1559 by updating the NDT optimization parameters to reflect the new PCL 1.9+ API changes. ROS Noetic targets PCL v 1.10 whereas ROS Kinetic target PCL v 1.7.2 It seems that in v1.9 the API for the error epsilons was changed (see PointCloudLibrary/pcl#1724) Now the translation epsilon is actually a squared error and there is an additional epsilon which is the rotation angle error in an axis-angle rotation representation. This PR updates the translation error setting in NDT to therefore be 0.001 which makes the optimization selectivity closer to the old value (TODO I'm still evaluating if 0.001 or 0.0001 (which is 0.01*0.01) is better) (No longer investigating, see comment below). The rotation error is computed as 1.0-translation error which is the default used technique in the ICP matching algorithm (seems they didn't add a default for NDT matching). This may seem strange but actually makes sense as the input is cos(angle error). And arccos(0.999) =0.044 rad or 2.5 deg error. This PR also removes the --sequential build argument from the docker image to hopefully speed up build times. I performed some comparison runs using translation epsilons of 0.001 and 0.0001 respectively. Both gave similar over all NDT score values. The first value required fewer iterations overall and hit the max less often while the second value more often hit the max. Both ran within reasonable time frames though the second value did go above 100ms more frequently. Since I did not see a noticeable improvement in NDT score, I plan to continue with 0.001 for now as it stayed under the 100ms execution time target more reliably. However, I have left a comment describing that 0.0001 can work as documentation of its feasibility. --- .../nodes/ndt_matching/ndt_matching.cpp | 27 ++++++++++++++----- docker/install.sh | 2 +- 2 files changed, 22 insertions(+), 7 deletions(-) diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 3557429a469..867082306f7 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -130,8 +130,9 @@ static pcl_omp::NormalDistributionsTransform omp_n static int max_iter = 30; // Maximum iterations static float ndt_res = 1.0; // Resolution static double step_size = 0.1; // Step size -static double trans_eps = 0.01; // Transformation epsilon - +static double trans_eps = 0.001; // Transformation epsilon. In PCLv1.10 (ros noetic) this value is squared error not base epsilon + // NOTE: A value of 0.0001 can work as well. + // This will increase the required iteration count (and therefore execution time) but might increase accuracy. static ros::Publisher predict_pose_pub; static geometry_msgs::PoseStamped predict_pose_msg; @@ -322,18 +323,27 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu if (input->trans_epsilon != trans_eps) { trans_eps = input->trans_epsilon; + double rot_threshold = 1.0 - trans_eps; + - if (_method_type == MethodType::PCL_GENERIC) + if (_method_type == MethodType::PCL_GENERIC) { + ROS_INFO_STREAM("Using translation threshold of " << trans_eps); + ROS_INFO_STREAM("Using rotation threshold of " << rot_threshold); ndt.setTransformationEpsilon(trans_eps); - else if (_method_type == MethodType::PCL_ANH) + ndt.setTransformationRotationEpsilon(rot_threshold); + } + else if (_method_type == MethodType::PCL_ANH) { anh_ndt.setTransformationEpsilon(trans_eps); + } #ifdef CUDA_FOUND - else if (_method_type == MethodType::PCL_ANH_GPU) + else if (_method_type == MethodType::PCL_ANH_GPU) { anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps); + } #endif #ifdef USE_PCL_OPENMP - else if (_method_type == MethodType::PCL_OPENMP) + else if (_method_type == MethodType::PCL_OPENMP) { omp_ndt.setTransformationEpsilon(ndt_res); + } #endif } @@ -460,9 +470,13 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); + double rot_threshold = 1.0 - trans_eps; + // Setting point cloud to be aligned to. if (_method_type == MethodType::PCL_GENERIC) { + ROS_INFO_STREAM("Using translation threshold of " << trans_eps); + ROS_INFO_STREAM("Using rotation threshold of " << rot_threshold); pcl::NormalDistributionsTransform new_ndt; pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); new_ndt.setResolution(ndt_res); @@ -470,6 +484,7 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) new_ndt.setMaximumIterations(max_iter); new_ndt.setStepSize(step_size); new_ndt.setTransformationEpsilon(trans_eps); + new_ndt.setTransformationRotationEpsilon(rot_threshold); new_ndt.align(*output_cloud, Eigen::Matrix4f::Identity()); diff --git a/docker/install.sh b/docker/install.sh index 1b849d42f62..7102fcf1e13 100755 --- a/docker/install.sh +++ b/docker/install.sh @@ -25,4 +25,4 @@ echo "Build with CUDA" sudo mkdir /opt/autoware.ai # Create install directory sudo chown carma /opt/autoware.ai # Set owner to expose permissions for build sudo chgrp carma /opt/autoware.ai # Set group to expose permissions for build -AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --install-base /opt/autoware.ai/ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=-Wall -DCMAKE_C_FLAGS=-Wall +AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --install-base /opt/autoware.ai/ros/install --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=-Wall -DCMAKE_C_FLAGS=-Wall From c2b24e404a132500cefedc5c336da3b3393c481b Mon Sep 17 00:00:00 2001 From: SaikrishnaBairamoni Date: Tue, 14 Dec 2021 18:35:50 -0500 Subject: [PATCH 23/23] updated docker files to point 3.10.0 --- .circleci/config.yml | 2 +- Dockerfile | 2 +- docker/checkout.bash | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 8bae55db1c5..c22c9cfd025 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -28,7 +28,7 @@ jobs: # Pull docker image from docker hub # XTERM used for better catkin_make output docker: - - image: usdotfhwastolcandidate/carma-base:elise + - image: usdotfhwastol/carma-base:carma-system-3.10.0 user: carma environment: TERM: xterm diff --git a/Dockerfile b/Dockerfile index 1a371fc2611..d55df9251d0 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,4 @@ -FROM usdotfhwastolcandidate/carma-base:elise as base_image +FROM usdotfhwastol/carma-base:carma-system-3.10.0 as base_image FROM base_image as build diff --git a/docker/checkout.bash b/docker/checkout.bash index 4f23d28b5b2..3fe102a345c 100755 --- a/docker/checkout.bash +++ b/docker/checkout.bash @@ -37,7 +37,7 @@ cd ${dir}/autoware.ai if [[ "$BRANCH" = "carma-develop" ]]; then git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch $BRANCH else - git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch release/elise + git clone --depth=1 https://github.com/usdot-fhwa-stol/carma-msgs.git --branch carma-system-3.10.0 fi # Required to build pacmod_msgs

        a;|UQd^TNy(%|3J)1Tq;}!HhTU`(7Cf%@~BA9ovkH z^j%ywT)g->1V>z(iq>*ZnOd$s{2-vU&T=4TVtd#w)di{9XRoePTpHvA#*pRubN2Iu zUC*G9IK_F2Zuo=2+GTgwWG;{jli;rV^b$8r3`TACjOlFmQ`&K?mPvZD2vM~mTM}}F zDe+`no!Y#|ll)6NlS1wEB9dI*z5dPb@+U&fkW8RN4YX@~XKX)H3_pqwruV<6rh$v2 z0{9Obm&4~e6nW1FQr&2gwG*m|;gCNcI42B?_{7^|TZf?VW5OK~$%<&~Xk}+W>ewH<&93BgKXjw=Ggd5v$Z`G7TbM99m*}ZDcLv@Hu}Bltnczybj}s?&oAteC!oNo>#6D!h{3A2mEL?neO@|TV-Fb2tS zOWYDaF8Xbz6(iX6ucIO;%jrX;I_G)dNWSm`56uj$DdI5#n7km9E><>-oVqRMjsWm2 z-EYbX{o{fG-ZaRN%<1mFW!8$h=yD~7zfpS=Pa{Dqeesqm(yP*j$gb1k@y z`?dge6y>$r%8ZoXTepTBT$3B3rRH_qu-K;jOj9wl%UKB6gnf&EgvYp#N2gKz7oa&L zN=xR>;K09d3IqgR5MPx9VHSO2D7`BrYLyRi_5S+YIS>5GKT{u46hUk)crWmu{{@fb zX#n3fvdIh-)@s6|1m5>#@xKo`A4D|e5H>!uB0zu&_jlO|;eQ~*thJ~3tVKEQI>LX9 zL0}aE?~<1L3f}A@^ha_2{;EXIWWP-vfH~uV4@@2Kt_JE9@LpN|?Y;gB4p`=!l=~Z^ zIs5W^-vaQ!Twomk9y#>*yW(c!*Wf}@E~t34Eg`wH#TgrOk<4y zo>~s@8y}9FJ2YWnUH&un1*pQ4-1*T+XyyhDTD<=@!q2|^t8YXQF!24~Q~NtG0M-R6 zzVh2g1HyzBCg-o74L0NdTK3=jrlAO?wkq_0-&SB<{xfzj&>;}fBl8k)12EBL>b{r}(c{~z7*0Hti(^lIKDU$+JA3zYpD06kD%q#ATbGYR$(T57xKMI3sf&N4$ygm9IVMfqGKjPQQ0?1W3 z00&Yn@Ob`zCIUoX?}I0_4vD>v!36%$0$u*EUlRw8VX$NnG*dTtK!Z=;39>x?eKHxr zYc)78OP)DH_K+}*5gtwY{fS$U@_D*6g+4=%{v)LViXdcmDS40zAhU>UFb_%HAzNi< zvi{E%Nr0a4yjo%p4PI3fbQ1mTf#u&T4!*pHvRBHjJPM#6|EGvVK!PrKLeo+y79wq! zLJRi&@lM_E%i#)%*ISVI4EPLA~KS2+hbm+g+!?`k5U4e@C-_pu#-d$BZ6z8(goPal2b}m!V&FRv*fZ+AY0utzz!; zfOSWDX7AwaGw0_gyTwIJrH%z|rsDnDrC$x9EJVd|e)qct64E=1eU7<$^5)r@4Hz8{ z((@%tHRG>9ooD57KY7*Rq#rVUOYWaIYYyHj4Ot)ERjH5Rqj@RzU5U`J=hZYT=@(MQ z!=gvhub-bQeB0G7wsc!t3L7Mh{#BmtFU=j90nO}fi&XErxn|z}cT46&Zn2Rv#j3a` zZx=mc=*2aM?;5L-+)^mc&-9@{MG)*P7G9gSt@PSql-roW^Ql?Zt{1-&R)Cn}eS0J&NVVe(XL64%p=met9dGw?bx}ya_i=+yU=3V{ zRSXL1h~?illm1uLxxYGiDG79t)I8;YI>=SjUQ4xaa!;5d9mB7~Yp2?e%>D3s5bf_Xua#@5uda66M->~+oyPV9rn$OW_ ztddlrQLY1Ao&#;OU#MBL^OgO2!<6HS@lEobB~MSd%B)W%N<3CxHhS{0eZ}_oB2Sry zUz3dD+q92=c=4-dP^z#l7R$Yq{B*6@ZUq0$aIUtuocQj|H*#}a?v1}%E}E@;lja5i z7I4|6<3HO_I3NaCbvB$62R%u!hhly&&dI-iBUm%h$3{J4l(Qa#K~J5$BQdI7^{knV z+`6wE)S5`k4JCNB$7H?~qN_)s0<}x)R6(X<(d~9UvYfW0fw3MU0h! z#Nh0cRiiUR*yS%jD)h-Xsd~GmH>e74l1c7RKJQ+aUVk;kiP7`VS2d$3g`(e?@>VSt zNsDImt?ZHZmo}Ds2ic=Ng$2BX=$!v4tFR?*d@3n%kq{kt4|(51(&wOGYsI4Ysf@YT zlhqZ!yP!~rE|IeI{O#qkVU>NgODh?E58UK7I(4p9f6VvR0{UX_(0liH@yi5k$2J1R zElwuXzbcV!n-!2L%XVVN%l6zfTv!%OwVRn}09m}X4t=kKoEF^Q)tGOsrAe$e0p@<} z;jM+4G*q&sfUoA8rF6PryadZlQVTkeX_s}toht2^@%`c6RlBe{8jwTEhrIYldLCR4 zj`lsd`}plE6CsS|gaAe6{G}>H{N>vETJ!TQXtUQ*kZ8NE*VX>JXoEqb4a9pn;A}6Z zos6D2d`VS!gZU~txamOCb z@li+V+sCC+8B0sh`EM&;jyE8JP+=?U^ku_r#*ykF# z(Y%w1;hms}H_rJqvVYb0D5z$;PA{>bp%~QTGdfx`mgZ_kRvGo`i(4cO`X1e_?9Cu^ zAALNxG|MDpuAY>&T2{alikHmau&>ttYPA^Kr_}JI=8ekhk2hK+eNEq7-+5+{qpJO6 z0TdtY0|}X$RZGS3=0GFf81V9v_r03J z!k0w0Yd!wnVK1Cdo3p3LKNSFCjD&#eop;Xth)ry+`LY8BV~16B?aCWpD~3R5P4uP- zi+Us;sCV&~zyG(agdG16)rsBOO#K0iJ^L}!-23YRMuCbD>x#^K`xdizAG@Xp2nCFT zI#HL5lJ?i9^$e#AD_S1snei`PxdhG1)1_JT@3TS;nYQm?3ZH6Au53|*%;js4_JS1c zp1et%=(K`gO1|_K?F+X7S@FGA?z5!wlWn46Vmkkoi^L&pt8V^AnP287k zxbH76z`+6G_v|+xcHQrTl17XhCYkGAAs1qd?w;0f59O(guTP?DHVoalU{&V1^8vfnFoeSfU_;yA+(Svj!tYu{!( z{e9c8L#U62m9}Svw!)EeIHg>zMcy-~Y7_~r&+}=$hKuw|v7_VW-fQnnF@CY5pI(6~ z52^d#NJmfS>B&3`lLe*rW~>H5DlDta(Ptiqu^E%}`!=I_su5v?vAs9bouTRjq&7`o zs>r`FiO$(IFBhmV^)IDm1GUh5PWBEHDsV2N#y}vo-@vzvy@ZQ#t*i0)<*S;J7p%sY zduRBZU-jc4#%sr-eUTrxsGSm4RYG9nmWC>$=Vpln}3Yt=D3Hg7Xj)HeD4$y zB90Bet#(d-=cPB$SilwvyxrE%+|_?q(wyS3bL}0JEI5fd+F67nm7eQjOs3oQ`avdk zA^EJpmE^B<^HoN#+*e}u<_l;_7b19h@z5Nl_tL#wabvuFUw*Z7s|O`Y_q;eR(>gyc zN(F_Li>~YH{YxDnAay|eF~2l6o71wpQK(k4mq$JaRK_ah)f&0Kl)LD&l$(06I4!fd z&NzAUkx*>lk?b8hSADks)82PSHN6D?A{Im>G!d1K2BHXf1*C-{L4hb8M5T!hY0`^8 zC{iLI(m_Nz5otl`0s$e?6sZDA3q8_%5AZhNRqngLbKZOZyuU7olamv|?#%A&?9P1m z^BE);*Q}c%^rXgMP&6ma2Yx^U>__H8Rg-oPgrvXspohZrEarsTWeW=p-KV!46#UEL z_44oEs+wzznM-x-!IirZtZnEyz-dJrw_RC9?@V;PC;3zUSYG>V>NS8F?x*v=;?G#-%(0Uv{N+03=Ez$IyeALW z`Ls%`e0zWxl46`A&40*y^9ReDvC!ItdTJs-O7*`9Xo^B%LcKS}N6uP}`G+!*PoB7~ zySB*(B%sA3cefF0?T+1#naYF@(V{N-=ng|4ikLYoln+%eq!8GHsf-8FBU%Ob$BwXD ze~&SaVNk6L)Chqw_*$uN55HN;MFrj;A%Tr!B-cfA@5bRvjyH{41#p&%{(`Q%YyfO> zpNJ9tR*&8d!mEEzUW=fQ(gdPGOU?w> z#Jg&r$Hk@{XaY-%_`s>sB^ zK94v3pRu8#K!277%&7C96(k1qVqS7^30L#C?H$-Jtga>7;ZeK21* zRWs>1zvxN|^fsIr6B1p8xlfKGFLr)S*&9c~$alR07|Kh@SLDxu_qk>g(kJ)!vIkt? z)k@yTO>aJEYT0w5V8mzuqBP^hqjcY&{9JGbIjzz%{tFFF+cpO zut0KtZ{M;6P#LLcziSES!>1=TUY=GipSoWg-mw0u$*wuPwF>k832)w3eeieDz-M4i zcqpeH@6|DvoX(dwyr$s4pcbua6?I#Yu*ntKtMl*)iB#!ovuhDNcb0ocS^ zAV%@=20?kP@c|}tLn)7lJYj)ue;$|WRIK5$=3u&w!-TFVH>pMW$)4U^D9Zn$+KNJ@ zN;_>3hTk-WNiIcnkj}QtD4qIC-DN;$46BHd-41i?y*2LPt^Gh~EHt#WN-dR+MVXI{ z-(l*VVCs7&j4RbOk4@%#JF>`Y&^Jys&$&z zovZwj(HySGR}~7k7to7qEPrty*k`g5Fj2@bb2ju5dvTvJZMCa>j;aQX@KXO80t`&(Bjg7=)j_ zeRg2~Qwdp{>W_G|Cr=^`{~>zy8~d2)k5xYN^wN0_yL#Yde7xm5BG}m)fFb0s&zBmEYQbB&_ zKx>bwjd;KDe)m`p&9u){(Gu|f6gA8Z#cM0U(U;86s}yUMEOD5wi`O$VBWjh}YHmO- zl@;W$T$AEFFMScZrPp+Mt~sI-HJHRbMHeDj6ui=%6=#oU4wEYDd=Wm)aXPz4X}m*> zBg(c#g1L6BcSW;QE4B7y{&{u_FFJyTj$ey)cocH4T`7ylO8NE^i z^K3zhW6l$})rFXA*kyvqt&({c(~kS5IEPf4L(1maYu)O+!XPWkvB5{I-H@HVIrix^ z<{n+Rp_`862lQftwrQmlGhRD`wLEl+WL5G$eXkBo_KEFYc6@5vMA57i`}w7@v?9Z)yPh_E=M| z^8?Z->A9f|tl!hPG&@x|I9PU}POJ4JLu-THxfg8-uB*zXlOX{P>qoIN5yh6N`J0#K zTvV2$IbL!}uiKXyIDN(y+uon8Blt0H=@l-Q3eQZPu`D(YTbwscYV(^3NUpuF{`IM|=I5<;?HFc!5Z9ANf2lMd}D{5%K ze10?R@6o34x_kW5x3{5D=WiuH$op!b-V`JhsGj^r0xHOQHs}@XYwXGBW!HMPjtf)V zrjz%_BE?c2voY6PK1I^USPgE9fpX0DFY@m(jRgdzs$9x&TfT^(&Y7q`EiBcuT~M^x zoZXt0mTF=Yh28vO)wHE1tE?Lou%AN6$b*$`;3Zu1_F_=JBHB4Va6qgEucF^#Z7-HS z5BS`7J@L$Xs)jMXg4!L+;Os$tkIPoe}eootR+DwUI%>_Ub+T zlQ!3DSK$@bMkH4>V~lL)vP&j$L#@1&FQQKO`4Ypf1p_laRVD{+t%{m7vRUS9L_#b= z>mpFFxgYZBo9V5Fr8UeDR8!DM=EkybH34a|7;6?-#VyfD#Tn@RA{HCaX)~fwk=cr7glNXQsGbrP z-y(gZf}*8$5dQj8LfWvodZOl+l)-Zm8P`;9MOet{Mr7_Lj^WvB|U9IkJg7Nnf`U5qW#OQ!lg!-FnGeohSR)1h*#zK^zOe?!vnVhy5=^LJBiofYQQIumovwC8y$h_KS z-Exz`0HerT%cSEt#jHkoYl;7I_~&OCk&M{y;#)n%ns?fDQimEt;fqOTFkoz^k_$4) zB9V;dIXX7(@Unr#p}_%ucDk@~{bOpBF4exRrJSSKh&souU<>{!!mU>>-uY|1HV^8j z+J>k_fWNF)d{Cj9TOgF)ql``3LJWdqA4mLQ`+n=O*-Nbf{G$-4nJbQY#Ne!J%3&yS z(x*lL&#GN#`Pp5R6D4Sn0m$RqJ?>?gUcTkSh?ShZ9}*Mj{YaeDfb6DPd~zfb26Qz_HB>bVQSf+p2=VmtFD|9!}Ymns}^g%9}D{TSquA{iV>*0PNpq)O;eUq`+8HgT*z=Jgeb{L z&F9C|nRH^z+?Moxp0(wm1gI$CR>>mCS@3B?0DX?|oSZGYW1^QUD zzCiDiXa3wFn>yj~iX+*c*75UZiGY8Vy7RjpP6zBZ&y2DiFx>f6fjlQ^eymniX!UQUHYnw^! z+^bB@d6XfY+tYLY?|bkw;o<&ZE2ZW zX{x8ht?y{)T&G8V+b+0FLode_2fCEx>yZEbUAe^D`*g2^N)d_xmZb&iSA5HTa81;* zOPkf=omZ4f&3NZ~b|9s9o)l=e0Q`6M*eciGYZxqKX3BVyEhtFvO4_v$@YN;y(y(NJ zyVT=^3XeEp+@+F6r+NtRhF-U6EL>kz+~sYU??S~DG-L|DSpT3L+g)W5n!W1}c0Gff zA*DNv_yjI=@y1mOFBitcs0yBlw`olEkN>z-dZh#MvcsnXfh#$NwM zNa1xzVCO3>i9&o3jz4Fb6J*(0@PD-&IzSIo^J-q|3t5r;S51^3ME*@HmZv>t&>@<=?P@hLZAKn|mh ztp4`m;A3O*chHvXdI(@t=XTpEF8Q-2=---TxWzE{l~RH!AYy9+mNZZZ3&DXP3Ic#CyFNT*F@Z>5;8h)IqLK60Rzl-kRP8mg&+4VcSp* zKBthaIsmv8GX)Jwege3~^DY-q26*iIz2NNjLIBK318jF!$d$&w^?_^mT4;91?>XI) zGi3|;KOV-`Z>yA+tqulC0#dP*<&oQhB|mvk0B&Cw5(RX-vE}P#IB*ZQrhastT1Ejm{42ewzNi9@#}-fl zC=0MCssU=f%)cUT0(jeqdUZUQHiLY31TA#5AtnW2KE^AlIKKh3D4Q=MneOubU?O0X zdeIE(CLcEl94SftU^HSk>BG48=>6VhbC6zXA!No3t#389c?bYjf^`9=>RiFBAM4|1 zl-}gh%9^mytl_2)C3ng7XPJ>?c*gB_cf0_J-&xCdm4{j$x-3to17y=pfHQr33`tsS zQ`1Q6tn`c~Ls!PjKG;o&Edc9{nJylJ;D9k`JnC1q)jT^Omkf|HxAPx`IsyRD+tZU% zM^9Yfa$%i98G39k**@??us9vqi~&#~GXT_SnX&pXa(oI@0%|eI0cgCp2pquZDs0S! zokXrKxbx4PqtvByX2s^u&UaR9>3D2(6Y>H7AbDfa@Kv&fl=T5y&jQtbuL8cUfUexZ z0RD3-7$0vYkG|Txdfr%tZc|X*QQLnO;7ukHwn=GZzC4(CZrhvK$ESXf(RS+q$-4xq zVJHJ>4UWm{WP_*^JM4Vp)&piT_^L&;1?TF-4h%%pj}eluzpww!q!$&(stPQ0!p+3I zh#&e!ErG*V4cqhmZlJ)hIT_pgyirdjlF`V04WlYP-~+Q>*g~Dhj#@`H`}4)0U?%_! z7gkMXP2u#_=Kw;;e(b}#i|c$n-)SqO)1dy;nhHjt&~fb}s&|9nDd48E1qu$eEWJLD zX0ugVoM|Rz=tqmJWV*eGQ|I9n=(zIR^T;JqP?~bg+xaq*OCfxlbEIl!|2`g-dQ>(& zLaD>Xq!%I1#+G`rd;s!Nc4)KMZidmZ=qvl`03NNF^a)h7O|~r2`e}S-+OtFwZ#8Z} z4Umu~3UTwnGV8GM=aQb*P{c(yyj8q`<_yvwVB?GcD__cJV;t+0$+x!}8pL+1tll4G zptSoEuoK1Z7;uIFOO6Ru6DU>GM+_3{JK-=aec)b7(4}?J2y4EMIG2hwN50ksC-EV< zkKDf76$BTslGZg8+cs=qHoznm_SFI~XG)SF$JG{q$a|}$uLT>RAEfhGMdS+={WuP} z1j?UF8rXdmC2#a1sUHUdrA8s)79++ihJ;3lrdzp1#7X3^S+sP|7C`?A98rUdyfO2P zoGQ5m@Qh0Ueab)nN$R5+fK_3T{`y2Iy;1-{q!2Z2JyUYk?IW=LlK#h7H1@K#40E3ro_gcd3v~KC-5Jh!o z5?;vYTHhN~SaoMwx9pSoValGf0r$d9r*+rzBmRfk`@u24`LNH*6X%Sjs(8OVC|1DH z8GnA-N9xS1o?gY28WVC=0LM??2v9O_Q>Jpa@{@d|YE0rBqT+#_zRe@P$RIeEBBs@= z*qy1Uf%A0#cC5l+27tk|Tl&?j5VDSaPl!LQu=36TXF4oKX!m8Dws(2yFBM}*D(sGv zb5b%e?kDi!;gcgttkd6JY>3U=0oxOe<^00>m=JAbF;5ly_v%0v#Y#^WC+*%F6~-07 zGbB^+NF3tK%MRl{&!TUAc~Pw5Rt0e3DUDcKebIr8kcMhzNR#ZgTYg1@-IIyzqN~g& zI3PfrOZ77B^WPtW#i^kL&eo3~r*((#Oc(lRan}&o$O1ENz-#@Q2;}l!n=;*l7rt~x zY)?r1<<={qK1YJqzh?Z<=v3%fT2fg%eQ$p7Go5bBDygf*>uFA8Lp8C7*hXxcniG9} zfRaP=zG5l4w7ji4u{x4Zrb$NC$Ov1myrr`C%3*caM!Zj=C1m)P?H&a33$VF;FslmW z7nQXCNq-PJQbLc6n1~rE{&Si*l_mEIP128Kbf1_ITb_1y!Hq{{Fd4WsloF||sk)dJ z*J$$ypG${|YEGGxO8i0X6Gg<~p1G#UVb`$hPBpzY%L*QlD`DzYnE7c6GJ$f7qy9+0 zY7d&z{e*+aW{r%g$$Z|5o&jut;uCaz`Xyf=nyYw$c|9OA>l)D8wqgUj)R@<-m#D~crJbD;5cDTwz#(bW$d|>`ZvR zWRL4mkk~n2#t&U1vz7aT5d6A9&Z^W@Dt$TNd8YG;@El7ctG_orZRBuDb;;kSGxAwn zj_WJJ9pnj$UlZ7MoE9%egUlTn*BBrf8pC98L;7e1wk`Z!+gnq}6LO}t!sjP5W`(a;T zH%N1|(?ZT&l$x6sDLIu~qF$A-6#Jwps9$UhLKy}!C4Rl{mj)B7EFIE1DlgAZF=Ff9 z`68(4ysS^C_ZB&Q6LG`GO@ny(3jTPHmm|eMBT6O72SHcFx3&zSy4>gS5I~#_u!%O+ z@|w~iueB1)=}hZy7~BiaNb=dw!umwXA8~f0Sd*uFt+C^=RX5%~V`KS+2wu!hdSiWF zA={8NgMaY>6lD>@UQlj~MVv$%$3&6`b!hnlD;4~45rUS^$d+s1GnWuJIuN+1q4Q!x zOnZj%0P|r6Wbq{7!4QO&v`h%hLbD6I&Skurvu4xnOQnXovHxh<_sW~ysI3=`B z5zXNOJMxH4ebw9!WP|jl<`2ArIJsG_FJLd)yd)Yc*I!_yvX8erowv^W^K0_qOHrfl zk!r$V{9EoC{0_kO9XP^8Kh8~vlL)qS;;T3IlrrIH?f2yFR)~&456zLL6J5o92wbkt z=%Q#h)+?jdhdmnE<%7ShC;{N$P$j(ei*X`AqGYH6BmL_I)+z$@~;6nK%F2djJb|x{h;p_T;|| ze_b7}TA~%(z}#;}<@8fJ#|xb+PXFEx7%kridsb=v8umx%qtnH%GKW1D6bc7eIZ6il zKiL@o>^uC`emq`OU&45MSnqOf!Iyo(Xv^;%3(n4(s!i?2!cBPtM-J)- z5p1K)ufx^;*TZ^(`kRB+wO-+f6rc&Q`dwU8P$m@4=g$vid;8?2q61zG-cZjSE8xaH zRk6JlnkGxMyHnd>buhh4FlWN-7+MRw{jni?S-aNXA;ytiV=uXhD zpL6U5&7TnR{!R$l;Kh=dguOW%YZg79m&!7GCOtmww4F@oV!}fen&R;qCa?7gO8`S( z%e_KP&Mm;YulepLN3Odvz?jLgD#o_Q_fZkN*r3eH||d|2a*8%!%rhNi(`WjJ}du z7A(KJq40_zi=s6h)eip4tL)%T4q;yApxbXn!N>2&-@zBY*hzjc@3y0Fu*VI3%Og*Q ziwv7%Fa_m*(olouPJoMHS3Up51)%mR9!TgiIg-OiX(U}=SMt#)o~}Xwpxf zsd#PFlznFfcsIGPl$lv=+OZ;~#iPtx*vqg`#sIRL{Oz!I-f?AtT=z}2!auGKq&jze zT0w9y$>$>8=mSsS$sRm)_-&aT)q$E*`%9)lB$1eRCR9cg-{9kQ_Xo9w&$99st z|M;Wa&3*Fz@8T`~-IgY3E7j+&=$^yUt`vv)zlq{RjcK literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/class_gpu_monitor.png b/utilities/system_monitor/docs/images/class_gpu_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..857f3bc8b0ff13e3c14145a5970cac331bd350e3 GIT binary patch literal 135193 zcmeFYdHn2TnJ20?c7xL@V5=i8AbJ`VfuvGNRk@N>l1eQ}DoIr~6s<~StL$r~f@ou- z1Jdp&0*WI_qXHrx78?}C21jKT6y$))6$F&crcpo;xNop~8rw7X-ueHYPfk^S$(y{} z^E}`0v()iZZt(o)?f1NAJ?mM|A2Ou)tY_`9<5|yo&X@N5OK_#r{=kjTde)n7$SE}s zD$DiFXYD}xe>~gKf}AMJcOc}BR*UjYBTu6coPz5?v~n%iT>bH03u-}!K~uokKNjLw?bn)$;1<4ilzAv|uU zn;t%9*kMS<@)V4$X;YeM=7QyUda?e!>*hwjjm2=D zSMI`27Xi2(F2I1FepP=u2Y<6s=;l%S$7kJtTXv(pFf7FE9Rj1Mc}S<#Y8}!uEDZeF zS;7mr-RpL(Kfb#oS4#uUFlyR{L(l7Yo3?GEQ>I0Q3l^P1`Y7>y%w);QIPXh+-s20e z1dD)W0y{C597`=y!=FHdR2K)G5Ybhr7!rXkPCIqL)49bCLF*3ArrQvoMV2zs;|DVO~m1JXh$10<-8a45Nu0IfR|R!zmk zq=;h0=iGW^Qk`DB8q+AhG`ED2q4>DUm8e=y6?#(PBOsH6YO7#5MuyN=+dZY<4~I)l zwj_Cj3sE1Y+SGL7usOv;0%(l12_?2k-JpG3Rn@$`4XX%T%Y3VJ}>B z@Dg8P$vRaemovPvVMu1!ohlSTSsPuUrIIUqb+!!0ngMTUW*~yG42HCZhb_~Ep~axz zQbRM&JDoL{qqDT?wqdz4l&BSEVrETtEd_Ic1`)#~mrQrHH3FFPrhLlvkR*o5cYjj3hTv_l7RtV5DfLu{pu<4(Ur!ZWn* z&1_qZqmgK6Xz6I_(wpQ#z%1m}fOieI-(p)4Gm=|&pCA!S@<_X4&A#RKu&7R!<1U4) z*_JwrGQ1 zF-~r8X27fxxH8^2VGQIEo8pF4mhy1zkMM;#Xv10tNm%7|>B`Lvx4V@=`!&XE>y%Sn z7N7U%O*+;Gn^aJddbO1@v^43ovVci4R4i!eVVxmHXNvZU{(6Isqy#BgwnwaHHMKSr z0W4_Ss`z$cbz5{bOXK0P?hO`QFN|?%F3N*GG4JL_$k7gWTX#q3ro<;3KecI_LI@|Dl8o6BM_5GVo#nW*G@;pAnz0b?>x@B3A*`;W<{$(IxoV~9q}j_nBFEQ46UygVBR!~ zw$x2cBI|BG+^okf6z*nZg}IJe`7L_3WD{3*_%e$v4y+jsgonm@gr*50?g(fS0~1L1 zj2Y5yDI~-sE`dt0&5dUXFu3%1?dg6wSy5p26P8;IXGZ1tFg?N8eirb+@{rrsRuVS- z@uIOVU5E1P_0mDW^4bBXuT#8Rwl<>)*D)7Fr9=bY>}*3mHD>_qX*v& zM;!L>2nHBo@qKGFO5lW{J8m^eg=}IZ3c4mYEEo2MmZqqw>{;^A^r8;efhD(`cX_%< z2OGidY{f~TfeD3@m+0Ac;Bw*;%g|aQ!WF8tgK$nHP>)g8lTtDeH}7IybunM-IgCO} z7qegmj0jrHwMiYK%i370ZEXqO2W5O**^JT)WgA(cu!@?)0)RGAh10FMrd5(DO20Re z#9;19aJ-S`lLlza71c8Uogs9kCuEqfqZ@>+Lk)JY=?Yn+h_$Zaz}S#o%o@}Q(N+Dd zt!g@9We`$&UI0z(vY6v@Mh5nRFhGzF4lPOv?3OUIkmmT=^7`@(z|)D%~e1VbS2~nAf-NfRvKf%);{dyh>;#&u%gC{NjF=9R4mX9776i5|(#4D`bzfKQ z0wORXp)G=@a1UJ&F*UVAd#O@Vf33CGz(^1qJ4idTLDZw^VAWc*OO;;>B@0N?242xU z&W-ayvw*1PWT1C?vqn0_pp7ui;$1&e9Xs8SMPL_#Lw44xz z$__0*UTimx;|+|!X9eGbw2I^x9drYpVy9cYH`9Anu|fs2;kflS1T27_7JS{qJAic% zCImhVW-{kIAY?SK!PXpax*U_$70x71W|tl!y&zV9FfYLAMoL1kghgg3-iCK!3% zS_~PB?#mN(LC#h=Kjbl}UjiQ_XrpU&1h_CkW<^IdGmhe2ro>CZZ9{MkuCM&%xU|qN zt6G~W;KrcGf2YU)i7Wp*9ZnCi^;9sr`0|jsmn{8xi~}12rv3~zJ^0UT8lgIJzMA*4 zHa&&lU@=(P7R|IHk@0LIr(rjkbLonPmYSPzKzmVrDE!fY^|Gx+sqTEbw$UcMkZ}*xSrY~oG6JR+bt|4(5^TO<;7qC zT8&v>rdN%JLJS@7!S%&1tqmz>&P@__UTnv<4Oexsq?Zn>(0q3>6niR38bv=zl}=Zf z&0BMrR5-Zpu+3oo*~(0Ci>D+kt0z=ro21G#P%lK58Ktb)n6ex#5=dV4F|}M*q2et; z_jI%B1v+iCX*KN+HqLgX+Zf*~1FzVK{CMfYiw+YhmSJ_g&__A5QI#@om)xq?2u!^y zTa+CK3$Qr!G+nm(ZG9vR0b?dzOaX}Dk`mDYcA(Ej70!d%(#>G(Ku9pC-q4gbD#q-v zuk==$i`|T;ff~TIH1U?>)p9jz zm_gc!lG#@F#SX-+^WjJ_x#6lM%_MCzvBZf7dII=|cj#GviaRr=yPlvG+S(2P!J%R* z1D+j))0!YT6F1tV*>EA#l$pzA0g$P328_Ykqt-y{JBmCMGpXL>07e9NJx>97NwXx)*9ydkQ7W%5RbK3SR4rXq#*Ys|r@9!i=?~&DN)9jni#&|Tc!Ju@lEeKO@%t*n2UsP6)+h*z3D_{l4Dm?DUdb4kNC8yR>L}0>{e8KG^ z8J2pjKG|a{NVeO83r|2RIU*t}aLb9PP8$;FcVZ+0++F%%xn|O-`cks@_4LUG0pD=c2 zz;aY=4R+obL);e!;&LJ=gL%!ahOAe@)zAQ%PGeGI>xLWC;@4W^mJ9=uT}abbH&h&~ zv+fvepauhC3doIsGg}6#+zxnxG>7dC=#&o4HZL#NOx?v=?ZPnDZNsy8p!2wdQ=@ic zJQp$oq4TW}`f|NQ;e6c6)HxuHGYO3}mCQy|MAeQ|(|Lcnasv-0`qFeg=FJ&N;Ilz5 zO7pl37@lHWhiQ0O=t>*$|fX%Ln$JH@LREgQI6m8d9_;3N==G4qYlGEAVO2B zL*1vicsQ7&X)#V3UXns=3zf*S4Y9yp0|wU1P_H#D=E^J=#5gFI)6l4M8H59&_F9aR z1hnE?4z0j}7t&MC2@++v9TU6{T#mSmhm)?}Et1J%nsC8ye>^4kv(F(u;u`Xdb-@An-Ow6Jla&`|M&-#l(a)4XAJ% ziDB8!q}%EQ+9K+12jMnvDWwm$m#V20xjJrbEO?%F5Y=A0j5Nm$fS-M0(Xldkm<)zm zlBV5`IVVu9_S>dRYW`pjsh+hoQQCv2eKxKA&>IS5-;(2z>4${5=<(7d?{z&0-j?$u zTtt&TEY3Rwmt*M+44lvVP&){CaRRSWj4C>+y4=LAp4?cF+yRuTDpJ56$dzhVJ-!~Y z$h?D4S)c-pB7k?th66N$sRhPwK!8YWo=Us4Q&1faY!(rEd^7W2#5J%paFKjH;aA;g zEfZZ&ZNz6eC$V~!s?4gP=(Bdw*aL9HmQo~aqjm*ptvW53+*lY4{6G6ghuKD?7)zZ7T(5ZM*MUrqg}qe-puC87L&V#w(7WkJe^y}V8i;Yd2NtV zP;AX5cts~#B6csy{J8>eTJ59>MMoy@MnhH;+B_A_JCY+z+D@Y{V|U=jR>QEisyVc= zh)w3bt=`IPftkW-Pmj?hgE@%W=`r0V!u$V)+13jsB1~^;EvSw(h{mi=fB+lN*k>?X zh6F*FXU2&eW*aV-1>2&g&;svybe@xRcb!Z#9iBjo8JDJjrS*MVq+(Y{BpjuHA15-Q3QcnqiAJb zO=jd6c&L*UCO||4H!E?Sm8wj$+X!1z(J)p*iObBsQH|rZ0FTG3m6216ZD$eDQWkJp z6|Hk6?afkh1U_5kU}?J?i)4_`BW-bmf)$O}_KYrq`M8EGN5vB-X|f7LAo4*I&a<}d zH6np1HqnVvXkK}<#?XPon);n?;i=3vv39V5RGRvYpWVtfQ3n zh_ko;tU+sH)t_tG9N=2Hjp!8_t&3_q@Uzxt)1ye8>?&L`$~Ls!GR8Cv;??s-95Zf) zEl6?{jnh6V&SJj_7LHI#Gn5(U=Z!v+QKrpiKBU?GzQn`$K%EjIG|)zrCsbg{^KmLt zT~l``ua20sHHula>&|1EbGx3>f-=`gCLZnASpq;k&+`?BZY|y~l_)H8m*1cg=%pNz zx@l{s58)HFk1HwM?i)rk8gGrb%cqUf{Y|D$bx0UN4ZgAVopfbnPWvXWAAXXF64xU9y0?k>g1| z#_BZ>V$ky`x7v`svF-Hd{CFD5uo2kDrn&pMr{Qy#C(A@fd+6-b{1G; zB1glO+m$s+?DCE6rAM835EZUJ%$jXuh?3|Cz3DU$02eGwb-dz%@zjx}+krteUmEa@ zscfEXuw$^8W2GL|15W{0Abc@Yu=P@d%f;BCm-M9Iym;1xt+={1F_a0qU?$>d!)>X- zLY>`%sL@O)|?2I!hQqG1D zh>=R6jL$Y~&t16lUOKWeX;NjD3<rgsw%jmALkn;c=;|LpcWaXx6B^O(KTS1OK}W zOX@N*hN5IK>Q|^KF996TfN#+o#KaVgF+<{37ga~^GIU#W~ zix4Pn&s1Ft7|S;UE@@t5daDrkmR^@h_y+jq{?byx^`3^gnXuq$j5ix@!z{Ax8VrT5 zF?VgqSR0(qFt0`C=p9*E zOJ{Xx+0wOfv;{apFPsfX^vGtjkE?aGEYKQi%vsLhJz(@hJwVD>vVw^*Hej9~PQxm~ zAPC_LrUy3-opr6HGk(y_DD<@c2+t7@pc=$1%8t`-wi_IT@HE8zKcn1#vHWq&II64Inj|1;3d3&(Akj=t{n#T89?%XBm?v@S99 zDM=gp%D5W<;igNEAHf`4LD?*t0-)0vs?7}JngnEpV0xLe8l|O0%+s}5p*A0mGmTtr zQ^@2ss2kAXCf;^Hn1bFS9EcPWToQ9hJ)B`%&h)o)Z$pHWxdn0;b8ji;z1mr~bfXwJ zJh{yMa=1`Sg{G9Y4zE#ny2wEw!`50Yc(N$L&Jja>MDsr(-Fu;b<)Q3h+U?!8ccU#0TzR-mMGx!w3pdcV|38A1B*jSFUK>X z&ixMFa*KIK+fJ#do(zXuTr(RJD7V)YTl5l*jDs~qF8x|`1+|H=Y$qz4^l)J<1xdX`-LUeJ&9K}6H_4$U6UVa%qtfkM+DsH@o+SlSJJU55EQacgu!bsR z(RN=6yHuy(OpdK}dbC*?@<^U(9?79@HR{tVAZ{S-HNwe3P{*l~Z`{#%XloqPCBZ;E zLGqA|XYvEhT(_;YOh#L4qo&(YWAJ6$ZmU$WK__d7$mGtJB()s16SZHhMq(8wF=&M7 zbt4TNIMp-T;I@v%igjFyy6h>9GqTb60A|Vv6*@xFZe&}}26C$~U=D9Z(Q4`;t}nTf z03kL_^c9QHpsj|@8fey9e0#JM#vp@QV1oel$ib8cj4V!dWlIl@aiS#_ZV$Kmyj3E2 zY|713{t!)NrJrEaE+J($RkxLCVfC>d+rmB4Z9jgSEIL-)o*K!-uLiJUYb&@W(lF!ji= zJ0HLtSQ6R-|KWtd+aSi%9|)+ELD8r$5PfSZNr6;jaw=CmG8zw}7QSt?p0`aC0@6Yh zYe`nwz-KCUfsCnMUCF)%A{}&l(c=~s4ZPV3SAqp1B4oa9wnC}qE(=2&mEZ6dL2+df z@EtKN0Qav)`gS(<$1F0GItoj0z=#6*lX(Vete6wYVx2XnyEX9ENsUVioLYm}XJ%5= z!~8KQUznS@DJU_!0l~+dCd&X9fUL;zB&I2V*7FvoCwyha!M3(>7}Tt!Jx+AEc2`oM&NAWvtPt}8 z9Sv&*&s@S3w8g}t0}B9QcS#Z?6#|n_v#sgct>-<4;1O&y562P2cu0i@xGZkPLC!IR z6~gffArTXVziiZ2M`A$Mo3$6>vidYhV@zNaX%2D2Wv?zq5Qp#)SwyKjqZnNb8GW)+ zl(A>6u^t!@7?#nhOs*4#P(ZcB5-C&zP|ymS0S5=XXxy9ev$a{ML#>I{BV)}>;XXfG z2yKO2b%tq+sqltn5DUGKV|$1*Kq9)E!93B{8*;j?Q!+y7L6L4V?ca2WSPoam+X$PL|8K^M$e;k zHI1WGE$8}B8OuKK`j|#xxru~V@&x6pzFZqiGU?RU5{o$8&xat>P4MTaXl|3~n~nfdc6icT=W--W4*h2K_|3jkn$#5O+%UMMjHRU>U!;#zXg6Wu;vGk7si)K!uC1p=48 zTxibFTE}ob8#dAg4hITXc{}bb^{BUDC92fhQ?R;W=ye?jTU0q%Dta`>+(ktRa5(L3 zmJ3E-BkD>6WjA3JZzW7!6U>-c3_M$=5<)1k*{~LByi~b95zl05v=K!P^G23IpO?dqK4MMaMYINC+NicbSzEVDEy7_AMghD4nuhy1LFCR*q_#2wsynoS=xUuJ zUCo3L%jWV{WZeHR5)U<*!= zvKbmj^~wUCz|w+3!46DnP{tm*>hh#CcR_?-T~DI5-=!QF5o~rkP>Jz?R$Ixk)1LI% z{c6LsW@87PX|_yW|3l%CDvDDDQckt(cs zpYegA1%*V)U_BNZW6~J|M@96ef?f~C%R#OhAXEXbHN{-$cp(W9NMSFvna4rvr2$t` zVIH&MBylzZ)1?JBp9(>jy2ATWOO}eRAZB@Sc@6vBWH_5z>$^R z)K4Jb?6-&QB89O@E-qRd+DuSc1>VzK7;qFZ&uY=nMyr|Xw|z5YiA41RFxmk}+ksZJ z1bsC(pgz8yrs0^T4b+KLbBWP4Z;__4!B@tVM?ibl+;E!7%`h_enHpWFizIF{xH6k? zZK_KePBH`G6LJW3wj2p+5sCzqFLgUi)$RAeWN1gxRnY>$fPi8RA>~0Zg5XG|mx2nz zIcDptp7eBL8LYp&P!TPek6ny@C`JKvi&znav+0hAny9yH!9^ty?ji>(V!L9{kk4gFXiR7T3ToOo zs-`2bgv(%^jE3fXR;VKoo=)q!oKB0%>@RC4o5u~BZHHZ7vY38DR@$nLLQc8TP{H5! zVj)CVG9-IB#`H~nis>Ae*~~OohXPSZ3j__YI0|vK)HhWYjoag4*@-8{9ON@>h1*!l z8ZLrfMFkS1uU2tuQdOj9k!;*bR>Ei-GacO*`v8XMsyDT|4&Yq$R>gg!i{t-iST+N8 zYxjOyz(?CcoUiOoh91JUGC}VEQP@3}@%)?y0s2Z{N*Q1oFf>@+aoDXp4>CSnf(WA3 z>&;dz5GE4lTnt<4_jeN_)sO1PMxgMUO%9 zne{=YPsNtoNePE2ZXp)7tj$@^IwS&Q>Kd>j%>z*`I~2a?#tQ%LOE=RY3KY z5GW*6X$sE!tPB#Q;3>lgFoxz4NY>di)-7hPmsU``sx_?5aV#erz>Aqjj;Xi3sz1^z zZ|tiZGQvfD=(FRgXfEuer#YOWGrTLa@?Zr@LOpKK8Us&~pIf$sZM@kmpqt^vz+uXl z!`Q^jk%-M(k{ouOh41u}#!$9l+9B+%7ICqR`ZOqBVR;uMc2UB{J&%A|706`_w zvNc?<5bIcXd& z&Sq&MUqx$any;X4rzW~}U?4NwwL+(<6Cx%GI+S9XC%P~W5G~gdki4OiVnA|ie~1*2 zhL!Zdwg=sz+N!cp9rZ1ZSnBB53F|JAF4%fL8*;D>Qt2khfv(CGMYh&Uut*?Jz10JG zJVzB#WL%zJ5W^Pd1-`GgS7W=iP$u=Z1&a$Tmtv4t9mLo~(u5qfWMv(&rBb#v9^oc3 zsuT_!4V8jQKps7b@~TY?>$LCMs%E5a-q*@9H&AF!0VE>^y>3K-G7bq#P<~5`&ZxOs z_Z2Cj`gAL31#>^_EZ3l3tOLA?a?|SIu+y%lQ321bsTZ%dxE~sXPOT<(B@8gK@c}$% zNr*aPFBrj?g0w}Zl{_(52zyn+TFlF{up~=rEQk{o#e+EOCLqPx>|i_TAZ@IJRPKW2Bl5^ zg+P{!YR8IctpZRrT@v$rk#Y{h^^7Rp5Cww8B;Sp(cuEvl!_Esqln@qCXOhGuir&js zUbtzEZK(@PV1G~z<5j?pf?Adu(=un+g2#h7(_7$ZQBE%+eI_v#3CA>z@GoVrPux=@HkB)!^{Ad z?;g?GTqkCAPzFrtc``1j);I?2;E#wFFK3|7>}l`JpE-<{%Z6EiG^UETm7w48*|MPO z@hE`pwqZ(be}r0Kc*Im&#?d4n(t(ev7(5WVY}*e@2P_4>%DHNkGb!1|r0y_917?|} z&72m-yxqwI1U7x7?dfCLbE+l2or4h00G_*;=E*&+-;q~YzX6q*U5xEDl}Pk(Zn|4O zlZ-K&38+#nWi;9-A#l-f+MrnASkYoqO3fzpC-ZqyE^EOkSln+YuIV~~+Nai&p%V82 z6H`YdI;!9h=+A8IrWgYPRl?Q;MM;aPEr17rDI{Er1ZaOYrLwdNoA8>ufG}#3_;~M7AZj4h^7vE^c_tnst=11lD&Z^%p!yRM8u>Mew6t;rP#JX>$Zsh%y_rv!XjBKyf~p06mzj>`;ju zh!XS^twW(rjn=6U76<`;siP32B!F6+88It>-O5R3;^QEwHNqwXN2IIiDh9z-f{6kW z6h0?Vi%osF3Y=ucPts5{blk0NL6SgG$|yG75wr~_pazfS18dv^c}dUCGJg$MF=8&H zrK4pd7evHdMQB&;fjgRm2@YasTx?TCH}swhuexQKjghPuBtVlvCd$z(0Pi?OO>1E^ z$U3d=ayb{{t|xbUV`L4SE0wUj=^6vfcnHPLGEy2)6^9}yBiH+OQUDF4RY>$Qw%SUg zJ{h4itK&|(pjZXvp(bWPtn{>Oh{6& zM0cb?6*~ZUGyrj2y00cJHC`^*nGnzA#sgbT^Bjp8x$x1f44y81m`5TGs$FW`QTq&J zRP~%IRsgDcWIDVfHo&xe1$NW$Zx9Y!fpcrBEq?l`NbOS z;9_Zyxxmo!}BEG7l|GkGZMDXKi@6RD}UmYWRva=Aim=u8i2C zS-pPTY)=fQ2%#3^%|L?qtkp^z#2o=B+Cse{vRE#+45-W7T1aOa)L1X)x=qxx+fqB_ zxCpXT@8JrjY7Bu+WHn6H0;_;CMJTO_z6?nYUMrlaW2+gIx~+w+Xkli`N-Sa# zjhF^g$V|?sn~pYEkJxb0o$9kxz$YzZDz&6>zf#9=EvsuAPB+$uK?`j*0HNHCf#fih zTN+@P(@vTR$##q64xR(YIHkca5^|H+!7Ul<}+;AgcjpL1dwc!wgrEE(j5#_C|_rmIHm_QxJull2eWprhH4$ z+7V?+4Rf>zNXU6M-nQG_HEl6tZNg{ZhX#?|g#}P!wggp$b4!C-ygmYp2DW%1)}|3p z3dh4}gh2@&M+z#nr`=A34*&&I)N)Aq^JXK!`^%XR$eW`&T#61n{ z`CPSAUgcAAf=$%%4Ez$156KBFt5uKER!i1sBRmKaZ$lV7POuo@l*Go`P5BVG{ck_t zMW{=mKLpQu)&b8NlK8AT^1jdQ_1SA~eEfU+zhNwX!T-QFs4GAH{YyW2;%momAdmaL zexUc-U5~t#{KPx2-0$>bPyd@wopa#*2VS|~2cEk3=m(y9^JU&CZ_ezye(qlVo@?*D z^SeL&{d=!_r1zWbf#UPmZBM)VOWkkY`GFJ8{K(P956(Dabn5ljey(@QJ3e?;@}a-m z^SJ+X9De$1KX$0}>hXCVb@>U;y{Z_W_?I8N{L4Sv{{`p0|AMSrIn@2ijf%Gb!l_xSVU{RbT&99YR0i@Ui; z9&qd)uN@t`_di~|@1MOD^t0z_hu=&dA3glkyYIi`1?PSKeQ))ZGg;&4i!b`d6jpn}gq{yAHeTRp&j=JmJ<~UVm8kgoj>oj`#Naj@)N)^c^obOnv;O51)PC zTdDW&FYK*+^@rx(AIp#bvxWJ)J&!&4aFsk>I`ca9<2QUbxaHBe$>+Tzd2@Z=H;=y1 z_~`tc*$v0<`^kSi>>JPB`IonT;J>`|?05d;JMuTDZ}YDI(nrYSA^yUPU;5|cKjsSZ zfH$6g#h2U@{6~KN7g+uMolos|)@85z&S3-oJwJNE6XlN|E2AC4f$%whz3ad~Tl52- zv-sP+Um~3T#LoWN@A>uVH~s1t`#qaF{`bhc&g0*HTX4v&m#zALnScF5<_Y5y_k3t| z)=|6J7G|=?KOZ=H%dW3o_SWfH@4xZemwkdg?b4f%JnD{DKK}cYE-&Msv`)J8`fpPF z!87P0^UCUT=vS4?_j}9inrlDz_^si$cYfrF^Ec)m`>*-DzWBUP9jbM|boER+@Jrnr zPu|V)U2%M~d|&vYz3VGKdY^XLtIm1NKfFOb{nGoNT>WAPy5qnjKKs_EzRjJ;eEh%< zJU;)feok=Hi7!1w`G}wF_m2O5DiDCbIrB}sk*s67`|Nqb>ylqS^7gZ5cUl)Z4^I!) zyO%wfoxDE8zs)}3i!a`B5B9)4;@kH7$+_-P49w z-!s{b)Da`FFMGV?y%!qi77xHbeex~uz2V8<-~Fw^dFZ$c>f68IP{;q~(x-Nv=6C+b zlaJnU?28VhFTDZ%<@b(Ro_gR8;^Ghf_ObLEE3s2VAt{c z+Wafe>)&?tyL-QR*_S`?>fLPof&a4qzD#-g6)(KxB}ZKRM)Qq#9CE=^{rl?kck{;M z4nKXL9gQe`V|DF+z3FAYf8xxbyywxyRoXW;>gT_BEwwv+T>kCe2MNoceefLl68xYy zzvtcOoN?J*>qkz6KY7#@(KXuF zuRN`~?-=!w7yaz{HoyOQPuzOu5fA+9oMIE_6^?j{BJz@ z?OVQi$D7?3zV)%QpZM)V(S^n3XWx9pFE-!1?y^^0Xa$ema>^Mmy8TA}m#1F#)cWJ^ z{Nx2^-+&RL`R9)RPX-M9dH7HFx+6TUmA?6VpMQ`0dg&j}U;M?JwUfmUeE4rZ{JkT7_l@^#(_3!&-4W+F zzxcxg?>+Kd`OI@pIPuHsSr;7r;Ef&mm)E`r+vfb{OU~U7T>i83PT#!vVCRcR{(7yv zvpC~|``_~Y=e_hwTRQRx|J-jq`VTjrt-tAj=bjNRo4_ zcF4QBSB8gu?AFtqA6@sMmmc!&SKjiL+sWh4z3hqa$cOHC2l=7HS@-3?(BE{AvKuwH zeQ?0Fr(bczRoKn1yy)%=CNDd8=kLci-Td3Vjy_x6^}Wx&?)v}!>xXXo?;+}`=U%+? zfd@Xs2LJs12R{AKU1#re`(K>eH{I_S)llkKJ-XaLm2-@9%kG z@XtSf?uGC9g>%qo_J++#X#Gw4{5|qp=s&#VxCdUc8zUL-bKFUihNl(w>Mw8@*4l@AKrc6r$4*vuzhyycTx47Th9OT{?ij5 zO@DIH!^}gkdic)oJ@n4EAN&*lLij~@-*V-5jnBSLI7fW_QICG-4bR^7iYK1>5tjby z{13#t6|@Yc`%`Y-PP zzg~Em3arj&)#Uaoe*Ism<8S-ulkR+f$NPMA${pP8-#_B~uZ{2g<{|Go^r&yV^L@aa zezb6(Qvcy}lDvifr^Tn=^lk3e;~sk6^&j3Hw*KvN9(>7;z4!UrB@gd6{`i5^v9H6w za20pm3$qU#=Kjs;Z+zE3-n`?vhiu>aRc5av-}mT);RCPzXma@_|MZ-bu6y_ucRuz{ zcRc(StaL6qjyUOhYV^9`HIswspY0CzkK6MK0N>Z|y!@u;pBa4iZSTGL#0&SquDD0t zolvj`{GhQ>Plbi9QEjJ_wT!d_@Ma8XTs4t9@t~=9nbsmlfO*&|KNQM z`#a|A``oT?&`tySif%6smv;EF~Mw7z{ug-TwAt&mDj+|CidlHUOINiHHBN&OtX1HnjZ7zrOMB|KmPrNDdD_{n(d$ zu(?L^;8Z^DPi`N3Jm?uZW_}TP!SI9N{I$rZ_IqZN!^mnLUAmy+|$o)GY72+++%_nVg?cb$6lV;|V{&1XM&??JDA;OF1G@r}PZ#M;$5=!zdL-%J1e zU#*wF^yF7Q@tTJpdg8k6&WmnC&r+`Pzjx@)3lBSX^X)6%vfn%R0c*e4A$$GFDEE93 znCgRjTw;AuyW}+MuoAuGqEEc+1$X^&m-Wy|CkO9v9=_w;^ERU4-Ei_{@41fs{Gk_a zj;x=!^R=V5T>stsPQJ_9{Oo0y!T;@^2VOI{rgda=;p3;?eBC1_9d*r-ud*@w?C4b= z{rtcD?u<`6V2hZx^y>aI*Z33rH64HU`t?Uox$&~=&c5c3lgi)TCGK3`dChy@{I736 z=y$hMJKy`7Yvc&JB)&JyPu%mzAARa~H^ccScAfqy>+b7Ly}-Y3=l;U--n*@r9{T8$|MMfizWnO&+Pks~ zKmWd6_dW9Vt8e&H>)t2N*M9dr>wQlJH<^F8>!3GZeeJuTOD;L?u;pvm_09|SKjr!R z+2sS#ZR!Uffv-yce%D#iDfd5i%YFCtcK-d_AA7}v%71(Gv={BV_RH0)AN%Xi`JcX@ z-ud%aUh}|N>93Ez>Neyk^IN;V0z!Y|&piJ(=BMBAsawX?x^9>vJ^xN*c;JMc0FFd6<`pVAtK53nL|4;9~ouc+5h^h z6K>k`Z(a}A7w`J#JFVA?pZU~b?oH?J+%;F8xbEklJoB12pwQzF9jl%9=Bw)qpL*Aq z$gh{zA2GS^_`6&D0~d`?WF9#9@H?LATkhEi_k)KY^@lHM$Be8aZu|X3{rii1KY!_Y zcm2iAWA3{Gvt5z zxOVrat-?Fy{+~ting6uw(`Q(xz8yX4=#TIE>4VmBuRQF-@LBU+Z~VzM){E~s_1nMu zs&>p<-uB<#d+Q5!y8WYX|K8VsVBLH7sphr6e9@a*@A%D&-t>nf4mk3KH$i9p^oIxi ziu}ll-Tdai{(|$}$Z*@u5*zvl&SIOo=@ zEKmmOJ@FasdZ08;^zh;6&cFW2@8A2;ckg}Uy&wPlFOT2%FD`lR=IFa$dd>6hLcAxw zeD0YqI`itUaUSM^x-z2CfV^|1b>yZ_<658m+c z=iYwf7pQj&??34f~X&Z+2?kNoxNuM7_{F0}uC*Xb{|j(8h- zYU}1lF1h%SYxMTN9{+z6_nu)*E^XAP6d{N}LJ{c@x=3%K7b75Qlp;z;y7Ugx2`E9S zg7glGNSEHLfPx?>y@P;skSg^|eD}Lw_Bs1I=jXXDe&k9fPv)6>X707tz2-r&@zh+a zBw%E6-zT%}?Y+~X{b1cMo@Co0JZd*pUDoYm#pASV%^Q3}=o5Bo?p^+6-xosOJWRFf z3@@TPp%(!YQ6a1U+4&)ZL#4ouZQQZ)Di3zmK}no{Ypp?f;1~;-6G*Pw?(O2FIiI!m znt!27aP{mDt-&?1h_62@(T+l!-|$M9?`Ax3J+t_oV~@YwadyZ7R%DUY;JcnTSCk96 zXHLfJ0`7S*ziPGKQ9!n3xqfkYZPO5+^vEn2_@1vLQCe8QzlPbtr{D2A{cU)c2+rD*vOS<>wBN9Dp_G2a zCo^d1oxA)*p#Ib`zj46SMbDI}o34jSE<+UDGyTGehpC5M_6-_0V)I|EkCRLLqjfej!GqlSsfjH-Tcfi zs6DO2r<@(rEq{5-fD?_YW;{h`P8@rYU)8(ni_L<{RQ%7{`fS^LUu=s3ug3Y__sq88(}qNH2HgWIVJPp{^stfG%I+(L0!MRI+HqR4 z)((*{>E$7@y#CJBwI}A43nHxV{m~KpGK+aL(|$Xa=_(=ebw*(-iZ!?Ah2l`mOIKdg z9xfw(RDaC3B`a;Y_=T~dH}02046YjQx5eL=4EYk4OF6GDrm2L?XndLUX{G+y@`(HA ztwy0cjpyWQNU@4s8vIGBI` z)Pry5hfggstB|2Z@*q;6V-B$MmKq@7r11ix9cluzJ0eBbt` z{MsTOYH(;#34fwb$&mZb^7g%>Ww`@!e3o|iSv%OCTJ%5OV5dkn}(LKhvPMs z;vTt7eB(<`q$rQF89Un)8jMo{P*dst9DQ`i?jJp7Vy`Gv?CQQ7s3S4bGdr(nT8;Tt zzv`whM!MZ7d+sNKg2Z||tte(9ost~G&WjVw%~-f0@ZIz4JnDiPt{`r+3a>T{VBh?= zx`6=l{SU)oX&w2iid0u^3i+7f?ShSW_sdOh0xb6-(T+sxe>?!m%!0+=Dx;o*W_Pg= zS;l8e&>$1({d39Sf0qN-#Q;D{#7l;K50eUB7C`^;@gJ=97&p%jsA{h+gU#=j`8Cn= zO#<4Kz^@x8!A4kd;gQ4G`>+v)d;J48o%>#Z0Jtp}NAdFczRCkYYe|A#T=F~Em(TuQ zXMf&12bUvFu|FWBksENn37Z&pRK`L(839i?-=Du_{eOJ#Jf1(dkEI<@A&|$?gEpi}<9X2Z_jMt}Aa0MF-=qFr z8O6eS4#mUs>-2B>B>xDEH-uQr_1ZaV_xGqmu|Ql9*1z$u7j97m{ zzy=i)66wqTuNS@o0@{Lpkn%6Ojz6Rg%U$jS?VOkY159sBA4PbM=9)~gC2d)yW8(_d z#a$BmQJ%biIdshyrznmKCKR)*axSjZPMl3~bLjaR{q@$!lRsY(!>yI0H@;~7g;@LS zU+FKKs@}RV*Ackm7O<|6RYZAy=k71S6sxR!Nbw}m`#)(g%oW&J#l{zcSgF{7*KCzE zLmuZxkUSJ57yKIqgn)VLy#+1w-coRu{-cE)82AvsaMKJ3rpXWdWSd`?;l1<0S82gs zdFIo=SFjQlv5`;_cu#Szr#P?!ac~hGsz0|agMG<7Brf=F zrT9Y8hd{Yw;~{;ou-E(=-3H4OgO?`V^62_RwY$c0zgdhoYGkWC7N3e4VYGhKb+~V1 zf|aGq61pA%bwSU6c6yJR-$5%?HtODsdJupr*Ro2W{`i zr`k`FR$g4`VX{C+zvcZ`4UEmRgt5vVcE%ob&Nz9`8+U+Eca!{nnFl!LZqF@&?tLsU9@~txjnm1@y zK|&{2&Vna7EPPLfyo}3n{`Es_EzRZ!k3RhyyZVmd&Mo_4xwGVmO0JT#+BBP^MX!9P zXXHJD@UhWB-%`QnSUoUK zqvAb!=lmnYXft_hUvAt^SMH>r(cUG^tjjZyf_=S8CcUgNx#;D-bbu6)5}Ik`04hskDvpfdxuwMX345QWIbvFPbaG}5<$i9MFTSq+ zw>#2LJb&(EWD6T4!}OD6CmNANd{ygjU&Qj?Lmh2SJOMY+D?QNJj!IobhKS^9==O|R z>mCh~*pA2iM#XeGI$!D1%`QAj;tHM5lXYoK5-cf_*&4=+6}2ak@;T&R87O!&5xL}v zm7u+{eM!8W54++phlBM1E>~JMn)b9SbHyPu8_P-xF ze*btY8qA+;i6Yw9=Rpdb8SIF#JBo0DnKvxo^7n63*shIHDrUX+C#bSzAbFb{$ z^uMD{=8EFCC)E|Qh`&7*U-?siWyBB7B6OMNtDvRY>~8MKT7pHe&J<(8b=yRd!TOCy zbW*Dl*8T4zDA;9ByerFXP{p+_l~N*@%vK^R+WM#{8ro2*ht{irRPyoFy1ry$2}@gZg$rorcL^c$ngJu~fsxMrwob{JhOGU_VUQ$pNMT$gxv zN!}EA&Z}1(7C6G(q_gxnop0nv)|l`9_`OYnYpg#S%&G> zO(R3zbcsJ|1Qwa?(Iu^#*9o_@{_6!WeLO_nM=5Qx7+Z~sshZoXLm@NN#Akoxeydpg zcC+sVIX`J4xk)4Cu3n?JQ!--tZ8i|)kp0OI!&J{tGZ++1GYAI@EPiuf{iLuE54Y)v zCujJNE?Ee%%>ITT|MelvCDD?-D&!oF?Wu|hXLL)2Pc#-yW=Cp8b& zR!5v;SuD)*G}rlbODyjs-z4H!hY$NwG=J|5Ldt{A!sGE1{?3iyMWhH8f+cR##;M7S zX6DpaJCsX>mul^P*c+S4s_@#%%g&O~rBQo;`f41L}7Aw4K4a zvhE!|6;FRXPC|SL_W3nZ2vN&a8t}UAyl%C=*Gf1zx?Ik56GLurH$>OTtn{IQcYADI z=_JQJL;9#5m`yf5ny8QNjNKNcX|fhM&!J@zUO5QrB8=8fkS)EE45nGdBGG!QMau#`{pov~T;R*LO~hU%mC_G#sl{7_$vvK5Nwa|qnRoGfhIY?RKMkH zAbJgey{}j_DH*$b>)afX$LC`K2##10``-VLU@nB*(GV|fZP?oVfyems%Ri0u)1Hpg ziug=2WN24=6aAS(QhVWF>Nq9__SSkTuYtRViiHYr<5N zMzfW?KRIQNEx-AAl~q{xzbRkz46FE_t1+@cIHX;Z_pN57j#a7%RMd{wdE zQE#d$brKL`$&c*xN>5GZ@FRhPB<%IA|K`-g`RD@m-?iw5p<4U7<%eO>vYFNzhPuXP z8{D(u?DZa7#+`$=U3%#yJ!4%rqy5XD@s%!C5Kg0R;s*FI5I<#t%g54wI+qa0(&WAO6 za8>WpIbQ1>B$;lpX~D_imt{y_<_a;ZZCjQ2YF@#%?Z?`r^!37 zy>9ES@SE!7>^*6XM!*8muc~QjydP8dt(|1$iijWIJp&UeW8nNM2A&iwLbfv^JKcOa;i=5v z)!;0=@>`Gic3OcVQhD{c-@&?wm(ThoIuY;ZK4+~(u^=aKY83}IZg&+Gs3f!x9{rBp zTR;yCuJ#=jJgnqAV^^iD7H(V{*-!B~86od-bdJTS5FtZ8+BaH|$xVJSzq4w6PkPV4 zcE4hFclCWpIPpyJVZU;O5t zUpcS-X~RS;f83W8!OjyI^M1XRVcYnZVhIAS87EJVv&(I@rwI0*j)pxM+tVMcK5`h_ z`ZyHJ?yR(52OvcWCAWH&ueDZfM>vDjV~7;C>>u`0>wO!;UY}RdNbQEtkG2G#Df%+w zXT-xR8b`XRy7m=*rxNySX$&^b)D70vPUfY{uWyfRmXv0N#$b9*JEO=o%&%9(1%GkK zzfIXV@#P*EgAeo<8<8O)kO&ptyw!TM=zQbqSw7n=R2JW0<}HSm!Q6zCgKsQ(T8mGtcN|FeX=mHsMz~dR5xDI- zjyis*E%O_HuX+73`-_QFel=Xq?ccH{t5JudDetD=*fXmh?+!_HCD$en84!` zLVMq2`ao^y@%hljo{B|PdRvoKcW2LQ@7v^S6x)+;TV@s%nMyWrc85dZAMb1iuEjYi zc8@>H)As|#cN0UuqZ?(J$iX_%)y*h5o4q`|>s?_q1#W@iS`99OSfGZ1TvX?{y5Zkk zG@3;GaO|z(1PG+6!hPxSINkVdpm<&UN2*5*DL)RDK;8eDqImyZcclv%q z=kj@;y~x`+3Q((47r9!NZ@U%dOZZ6=76~$aZ__9wmM0BAjk?jALhh=)vBx)&TcX3_ zmG!!uDA7X0Zz00_;y+Extzt^Va~f^ta(XIzCX|P#PZ`EHjt|x$J}dOqG=zj zm+ajWEmPLraYAcucQ6&(Xxlp|hH_qd`b0*Uv(fS{-B9=#`rd*&Fc&Ql%eS8AHxMR} z1sqMr-gH3dBz(h9d^csf;%9V@){oNkf8eW8@bCJLCYCLmlr9z&Pwf?z(AjrR%dlH<-Qh|`s~fn(@8IjNrKmq9d+szjck0BjPV5+eVG@NXZv7%<3JDNh%uPnjy<9+m!6O?*&em1KD4zv@v10U z9kFw1={-&;dK4J^ex%yjPwH{DcY<++)u%^UQve!|xf|Bc9kT2AV_v%z(ADga@V^KE zhZ1;gDGc>3*J?;BZcH^;r=&93IbX^DU?P`axl(l79-u1Y6N0-$T&iuRa+%0awU6VDG3;Ztc15`TX&aI?iW8@ zbK%kdP+Tj%xK^HmDR%DC<5Z=rThroXL$a%SDBc(?%jGqD5#x5+@|0S8>l0zo81YH_ z*b#8d7zT^idflq^ct6(#Jd5$G$}vr`3$})3VM%hO!hR{PaMg8PJEv_b;Lsb}C6}-b z;!1pAT`~O0P`qYKFS@*LLbtvwk5e(G>otvPwFpc9t?$O57L8m@SR(xgZHHhh<>>+^ zE1Bl^cFRY$wItQhhXjIa-hRbTY9Hhej6T~KsxCrPuoLW9dEMeA+F&`2B9Hi9G=m?U zdcrw8@zLJ>qG-JeQL=#*68b^Taa3_-SMN4;?hL=`@vmL0m6Lv?Zmn-#=~jmfk4;nL z!#Orp2V;D{hLN+Z`n`53K6bN7>p(rvn^-^ML03w_?W2xR3IQwWVLrIeg)RSYvU_%h zt2TkHu?4ct=D&76qGF7c)5@OjGI<+6Sht_cyo+gLR&RO9mu_kDJo$BjdUfsi6332L z$J$dY%gUr=m(B=~B;OzRv1p^8jNvVn0ani26kBk1qn-Z9Cw~ns^RwV;MekhoEj#g! zWPI{aE||mzj<>sTkf%4sswRQKwD5;Z+PMuLs76?bJ|3%bXNk^$@hppEz1%!v!v4fC zVHr*dnV0i9EP50|p3{45R=tsL66`Cr{6fSt6F;_8_?{1>pJ30YV))nmr{DZ)vvc)fmhll0hvhA=x^-o31RpR*p^@kB2e%U#=C{(b{CA>2eA6I^vPPJAs6`=gx3B$6&2YH(P z1I-?;3%YyX_=9bKqtyx-mGUeMK4{&O{;{m);$ipB=WMR%uYsHvp}gd-?)~cbPnjla znh&n6*NS%8xBACv|s zZ_3jFTq@-{JG!%E)0WOx$i=C6!5AIa5GAt`hLY#@R+govakMU6g=OOB*xoms{k|kz zxQFA)W0~C0xAgn*`VNWJ9T&?ZOu7BU*Au=ET+P=1HyWZhieHXEyvA!bZ|l;>%2Ryh zXs*zY_C@ZZh~W3K7R>}UAh^s1YZrwyNAWnsR`?Ui?!Gn0qFpZKrVf2yky9+Rc{H^B#D-JNsAfb`CdM(`Kfb_QSZRjndbnm}Rl-GojOumkC zKc--9{keKCbnkEs$q=r)kw2%dqf)N+5?g|IoO@e)o{J%wm4HZSjHKMewL&_q&PC!d z=&3X$B176L2vqWxCf$>L4x4S_X0xt{gLbp+ciqpMi7@h^*t^H5P-8W7XVBu+Z``k& z=Y`G|WzgG$;rA9`P_nT-?~hjw`$O#h>IO3mt2;qBZ*qVuvt0w%ARln)yn1fO49LdH z#p;Q7!)^jemLB|KP~iJRtkvm%f5OpR8D@V#|GyhwHrJk4xUF~h3G5bP3n9qqU!0NG zY?Zn+o)~u$psywy550I!O+1)L{Q)%)^^f7!3&+>X4r-t_4A#zTbK0fo;^%6xfyS+G;IaW2eDc3(b+BA=1{x0Po zCq*{$N05&Kzv8T(88jIGkGnaR1HBr#@(9~Q6)Swj6A5lLcy0kSO!*xDX6^wWm`U|K z|Ect+UG`t?qEKbs=P9F#2k88Vlug#J6xcCkuKTN9-S(Tw^K*cY72D2-hD84@wj3aT z|F3pjt2O7vd}awKWH)Z@N7Ee>5L^|5zgj&lU0I3+IcMAu0LNI*Hgl_ zI})O;xr43df%W~L-@QNVdVaddJ269-`Nuv5B(!sZ-qrop>X(ijZNa%X$ctdFrd#}H z)N)~v-NkI6Vpb@Mfb!Shb2pgcrIL&_^xhHpGdbGb$3CJH(Z+{`lel#mW*2;P?zr9!}w(DsY8BAQ^H?Sd-*}2~~FYuhzk8tdGEqtAEaI~oL z^pJmW$k4BT?opX#pAi$ynyc%|pey}G)m%6vRnXP@VDqu{_jge#Qtmzd*|$uHuUs#_ zOd~YxKILPvKjqh`>wcVnMF%(IFnK5c6&Gyux0?O=6&)uSVANnU2OZ3N$Un_B^>mTJ zx<5N4j9#Lj(PJ8C@#@?Kx$SOY6c^Wn_c6{pV`Wd~=(TBkBzvZUnS3pEEA2>hVh&D^ zHb`KZHX|Qkd(sEffjwJk63*s8d0cJIZQL8R4m$4 zM;y)pzl5s*B2WPCs4(xxHC1NhxXZV@dux?bv~`!RT(|5tyA$U6E%PREgCoTJbw)miJ0;x-!n#L$YYfqjbL}HJX}(s%=G_>gJYS~UxXs?E_P4h~ z$V)QbSf5|3uSBr-Op!YsLZsHrrJju`w;AaVfu54&P$=)b;3+(aB9xw;Hao}}%q z*KQC{aVy~Cg>%EM7%;8sEq;pbAR?a^Rm3QL>nnS3MXA*8azg)uP zcicDWdt}QQzbQ_lh8s+~WwyUQ;WptqbOLbO6t$suA2?ZH-<2qu_ma&h)bC_BuGanA z+q%A`C7byXBjn3&;8dq8}Lzcel+THAET3u?W+L&N#LjgmV6@%7DZYTX)_TnfT# z58nScWUG0m5>&fh(^X+JGTTNO4=)z*3nU=<5JJJJ(;iAwpb$vVvlT|q4NUb!)6xF^Cq-)F zn59X8^W_!Z4|>&3)t1lO!|2BB8&4JxY0^*oM`$I~;gR~29{q1_FSg${MK1QFux3W} zBuki7J1+&0n{MfM%8tm-fU zDu;IBlO9&4@SUBdZ(+sW^a{zJz_1}WBfi7vn~E9^KTE74 zFo-S4)vj1x=kW3IYUdQLfVqvdhUOE*GE&unBopuP)Q zTmH_?qhC`-N9e|KzbPH;mFosU(RhTUh+t_BHT1jK^@-YA23H$C?GM=$T8vMBz~U4g zessd9Cln3Af^%D<35~O0%{Tq@>f_Ci%v{JT><*FDOu-Bp>BtarKI7+t{YIq0CLQ4t zoT)o6<7rn2o_7m}OFO5?caEv9M4qM)<_ij(TO%-!Jxb|F5U48ulWz5#+LqOnJu5Rz}k9AE)V4C8?Jtya%d$%O>g!~50i8(btL4>&>L@n&1(Jhe#8akfjsVj z3niwX$cG5SCU(o7e3P8PRgNp8wkN&H6vc$R@RfRQds%aO+*r=!MvVN=EnnqE!guDFxD|qM>0t_%#prq4%84sq?Sfc+d$*r-#qqme zh6OxQhNvK04#eT~74}o>gK=kGXu;C(a8WL;Vq6hnzHM?6NfMiJ}3(o$>ie!8ePqp4om!V|M(kEm@9T4TlcK*^$p zUr_Ok+aXXQJ+x0Ci0Gh-(v@COgFOA(3g>Ak*>C~p`@rYSvnTYxL{}bonka6+zRn^P z(C`ya4XsJ2E^CPxLYkU(#eO+i9qF1vni>g{=5wkt7v9&S2p+H=zL!WOHL>dH^^qAC zxVJvB;x<2?F_;+3c1Iq4@EJOFxeffKCkDxgtR18Xt@suxPdE=jmUwk9RpHON` zWWyraQC&$|nVJBZ0oD_g8I!ox#@%)~6AvTb^r=I;NFyhlqWqfXyXhcuI6pCbdZmNpuL7WW`a+SuaxDD1w@$r6wq=kqefhkD-Bx)J>^`%}8L(kbzAJ zN-iY5<^{RW!sP|hqD!78!v9YjVeVUesRo1wrOS>zVj2;d$~9y7Q%Fct{R-xN6V6_; zPGK{wHDs@)-|@3Y*gHbE{ac?re$U6TB0)(JZ3*Gm@lWyMe*v$^#E&A!z$a>4ojF)P ze5FRoX5xplcv~VRildocb1B&3!1*vP%#s0?5IFlg@o9-j!~}*Msla@>X+TOJcQM+_ z;kl!6mSjC^d?L9tU5USi1`m31noSu*Okl>}E5{u=5}*%Q_y*3)ryXSMOt3tD&xW#yC#NpYtUp*MF7js5VgwlnprA)#!?h@fM z4AOJUU<5E1AYy_cp5L4=1xY5s>za5xX<^#!O9ilif-oRM0ug1{5 zXlj$nrv?`*bNL6neZ>Loj$4aI5-CoO;3x|ibzJG7B_!zxp}icmuKYlwh3WcDYR5s0 zN7GjOV-Cs`Nt{)5snjad(Rusk|4ptao^@s*yFHk2#irvfG3 zP*0lN)JYQ9lYB!XCOp-Z;4jG$pAf52-^7cPlsx2M(C_;4n#`lPx+5vUf_;>f4Q+jG zTO6LIAO=0Ko9XW!m1O2A$lG2-Ub+hX-L#eXJ*%l9-bxjEB5(K|&YbA~F5)=}T}?GH zCAWenq>uFb{pm8ot4*RGxD;^i(wk+9K`%lHF)l23pT`gnLkHwvw9wht%`6PO6jHD; zB0XW1HoBr6GcD=?SAxwn(*|-!k>*onUMZ$#{O$xX75}J`aAT0q`sGT9DYFne$WRm} zP->NdnWx#P$nYR}D*bHysO$L*gA{Q3J~-yaX(rOe4Hkm0+aHS&Q25ULqC>9#`Tpf7 zq0=JvC9-0CT0QJ67QFed$w1Svg2-Cgn;Ct9FzVffWF>lw-s(_3b+olZKeq^mRdo%| zt@T!4Q`B~{TCzp5I=!M5p+`B7v|7vA4oR|KCN*R+XD`UFhT!C)>Qs|9yGv+^CE~wc zfU`Go22K)ZlS_2NL98Kj!JFjTF-^@m1c81Tw|fojVJwr(k{(f{$#ww{=k;-k%Iyf} zJGKPsLWyFw%a;UyN#>F!Uug-K=DvWGc2FefW5(bVlW?e`Pk&MqCU@e}o2hF+NgPbG zRHuyg840oj9MF(nMG=e-&bNCFnz_mdcV*ia=a; z7W19R{<*14a(1X=amvvW_2Uakb>GBQ$hI!Y6MRUrfUY&ghv0uolWXL8dkgjjOwt#6 zLcNsRZFWckgwO`&T0p;eym*k%LKG$aqb7(TsY0jJ3`eAXH$xOVL?{{E;`L027IV9s zX_gKS&5U-xWBKZIQ?;r2*|KxLuy!UA7nRER4~ALwhl$QI+IkeUHnWE{Ns)`x-Mg(* z@0FwBkt=Y^+J#7%_J!B024qUK5lZaV)x1~j8vo(tPx6WXDV5;=A*=Wt`W5=cb127~ zaNJ8&*IY)z=Nbi)TV7|w-+fHEkjsjU`uQWQO8Byi#UG&}$T$3Z);aRoWTwje-LQgR z<1&kI64XnbP^B-uAutibhL5BEMCIb+iKx*GEGfdu68}btfPT;rs@Ca(#U7Yf{}Dqh zv0BFeM5?AU3c%!T1O8CuY$fLJY0*F$8oku#aXt&q-of@`&ZhHhsxz11OQLA$sxU~kOc_TvjG07k{;rU0QSo$@{U^1<|z@k4{B zZ=9EZj~&gOZ6{<&*|c`ZDN8AZKMB3|zNvO;)VipgQO0vPlI6x~2a{hJK)W>0_CJ_^ zS?0SH%@KC=8!#WfOK7w=ow!}uIdX9 zg(zIjrZ4juc>9ynkItD?z!IN$?G8MoIH~KB2f9WOFkZkPBUZTo!GmdV=ual=y~aM6 zb?Ip;R6EVDR*cy>!!96sljZy-CAN-U?~Z?bJNCL`hZEemiBK)@v@3>t4oO$I+b_<6O8yxXxw|qnmaCDI z@3PdtE*U}|HL@Bh3g#J%f?9A{OnxMnRrj3 zE+kuQChehvfbqtm13DF^Af(4*)<8vatAp~?sf5sqS`A}`pnK9=LA96rE;azsw>;ma z6vD<0mKdttyy-pn|8s4?no2l6`g>m5vIWbKR4L{Fs6@&B^0(voQt}j{cy-03+}D#S zxS>~7rXXypml>sp_co@OIMvWQ5vUZ&YA(!3sYUG$2|j5XVWv>sY!VW=vpmo>G7rvH zBtaFLPs%LPdBpe_vO%s-xVP@iGlc9HHtLFgV6w? z41*w#$+{6@=>b;Z+-Si%_Q-dD2iVuKTBXOm5Xt{3mB5Ky1i9ZCWg<{&(aT6qfmKvx zm7-b{Oxu7AsTYISk-R=y-c?xl>+^w2p4T7M^S|n@!M6;os{VIgIK7Qa87A$#aHmZ$ zZmXOfn;=Zc`pB~#9LU?Tn&gkpsKR!Ttw6Fljsxis=-0E2$#-RR|91%_(614n;I7Nx z3o$0|bbu%y{F!eT9ByF74SDvLcpsban&JFFlyF4CZ(agS?d@ASY+snyv4xG4l=bsv z1{Gs`a-A5D<=mX{C7PxFH_jJ1C1!==v5U>Xsb5K8AL;&OcgWCw=jrwrab>-|UtRpV zX|g`!z0`bq4&1!Q8IIkY9U;$4qpbRYY|+cf#(#De9r zPs@p39VuNTKWcrV>*C|=N$e`c=(SpM8wC$pPX)vrII}nGf#8}|y9zWoAjY=;AO@gq6Tkn3n?`AXM`hgbe_9q~ZtvCVI#4g1N-`3bFn2f1HDU6n; z50!1C_Ei)JZF>{$Q#2R##qGv_`jWcNK^|`$jCJ}973dBv4;2+Deo&AH7JPg*{qx6) zBc&m1Wn5ce#g76}CV6h;{R5sPK@+9>=@g1Fo8tJ&JK<96#XyH4G&A((PZYI|t>5mE z>Z#VNbt{na+)1);aGdQtJvp+SZVK1~oBzn(+E|K8v)UW_ltdx3&j+%Slly*qBNl^M z%4E9bRml4_Sc$Mbg2^68a1}r|s~v*oBD4n2RKQ`R-amlA-p+B!f43=_3~Wxtcy_~>rv3&W zuOar?9w5EY?s)Ntxgo_H!4nxcLBZtz_E;$95Q>8$WC*|(wLb$>WxP&bZf4$mIljVq zFSYFRYo4*Zq6RBNzmswvo!>vA?~MZWBYC@P1qh%n`*USL!(QS0kO8(PKH5N)K&*hK zQ(^N&?szkBz9(hOyeE0dZSI7X-D40)fVN=P!BD=Y;22zk&tQ$K^%0nF`Y|o>f+qQ3 z4po?RkOB!m;iaij&dG3ziJ0Ro@}VY05)Y6y>GhM_z~-Q{yF8#Tf)g&)!`hgG1sEZs z0A4gAV>W~FUV_3vHHHZ6O!y@2X8=Cv0{M`E5cS|UP&w%NlTW0d{(AKL*Zc%Zl63C| znT)CXglnAb$cK+5GyBBUd@em=Ef7-46PTdD(_f|*O#4Cva3Ti`?6pG>G1avn?fUOE zxxIk-5AN2V`vBc~N96L5`|5BX5V@>Y1`A5TIFACwflg4`<{2;grJo-}L@g}h_jcnt zmTX+S8^V~uV&@^JY$guB_?h0wC=_4@`xWY4U%SCZeidd7=9d6lI5=&*7z)vJd{G2e`KZozX^ z5u60{c1${huS}sF3C838yw7^Unpv zgVGb7v&)!mrG)u#nz+3|2Mr8DNR5LVg`0EOD|Z$O#rzDEomt)}gY%IvNPd4KKh3p$ zIoV_(O>R^1Yx7oz_CD>9#|eXsr^xidanUw4%g>IpMR_+?+DN`Y=P(}tu$=Z-tys8H zBwarXnRowOFgrc|jk=s^h@coyq$Kfass)-Z>IX0;l?SM_R>7`MPv&ZHQb#q{nCSOY z&!QT$zlCjf*gS&_h1HYV#+em0HH8cf#et-P^!;J*%4d9;nJ7qAEN`f2a~DdhMF z#~;IYKlVKZRf3eO%{}>kH!PXaxH&0q0E=@POtZ~iWsvh7uSc2UNmXX!PCuHx^NrIM zEW35ceK@W|afoVq$#!p#z${)5i_|8#QLh(QfL>D68%3nrW( z1~b}ldZ``&eH`TGTxP$vBuu#UUV+Ova5;+2v@o^bC1z7?3hKnm6h3BUM}l z!%uqflKe}OxVvJ|{^f&`+FtLLmzLzIfmP~nRH>-V0-ENgn8fgD4U04JYme1N?#d7> z^A*QJf6enyDfF4O$GzJznBQ__;4qwU|DOX@ z|1}VQ3X)fRK@O6pb8QX62O;LX*mFW{<~Eqi6o8nSf)B-Po+WTyatoIsjM5CauKl4( z$rEs>#cT3sZ46iZrBQGY@g^tge6p64RZ&Lx4}D^cDg~giaeIj-$W82Md3cj z9cU=A7R_wWgjA*tO!papIvy zdOGx2xi}N~>=IQnZ)h5Z#A!F=Ju~~oT4Qo{P=OI-s{xxR!VIS*ppk|moU3*YL%y0w zkuvk9BhnWg%>e3Jw%Pg~$03>uF-Ak?Ud?OdXJr zSLEZ>K4y9D$V=k31N?XYFM;s?CWTAc5yeGB-_RMRL-Cz1T^6641|g4dK%533 ziRewjRlop6$mx z&5WGBFehIM{;}A_#vET9S2E0H3@QfrM$Lm$6Ujl<&h;6;qbH5jo$BXhq{*J@M)AV! zEy*n4KP~d?t3k;L(|%I*&T!UT$iUeOEW-&RfAq>cATlU$eOEc^tNa{mO;c_7R*3=E zXvkcImVaCi(%NbX;V9i_~dShg|Zgvm@E3!#vlR;u^YaQjH2lmMtW zdkU<42~maT*_a9kKDlZPb9d5&ZnAZR30e?FcRu5Vy~DZWIC~(BqIb9HxV66#(HR25MBd`Xr-+*go4suP(ghEn z3eJi2xPY#Ng0!Mhg??3ery0!dH0~@08=K9WPV1d zhHH_wf-^)H;2GT^H~pX$}``+)E5-ZK*1$2_A zp}$>+Q)`jD5k;0btn!Kq)OnI+tQz`!Oapq+fv_goc|Ln92)r4Tpn@cFt0M}Ccn=#< zNW|S0Q5?WrVDa>~U`5?;Y?5LW)$F}5cgEq*)vTxdx_z4A=55W}RkUgh*;8#Uzm%#{ zi+oMMQBk}=yh9*9-)C$*S#E)K=Z zCX0w$NTP7Ik6UwB+kuoe2K-_+^PgX@TdJW3{dtrzr$Zz;2p|%!537y>FU{j8{n?Iw zxT4`UH)D+Si}@rHV@$*(u2DU1YHXDELHgR+NKBVGYjSqH?Z?_#9=;5eWI`N?gcHqo zK4`mE^gGRoe9WSK-xHtS>bZa$Y8R`F>p%X6zDTS@FYL9@O>@Hmbn?NYAj)ux`kCi+ zaFpj(JDVDOc?3vfQxA%;XYa8h%b&kjmjljJV}|R!DtQg+hQW!h-~6$_Q*b^0Z?v33_A zebmg6pJ&bOsHZMb-zF1QY_apRFC1@gcKFww z1vJAR&?Rb4Wsg>c7d_y7us1LaVPo(j);)owSl@-SXC@jRwxKc=p-gq{b;9<^<}*`F zQSiG-Vy;mvh-qMNs{kwpvDI`YiBFn&v5t!n$>>}7u*e{0TO~lnW}?xrQ8>eXs=+RF zxLdCeuwJuZQU<4%i@5hA7-jTu)NH28tslmWhq(OS`F4*%x6mXX;|#fzZ;jaUI;>wQ ztks+9c2D0e@i}ti3}qHM28}9wPdqtQizk0F3C;s2SY?FlAs3omOsFWe>XoRq7Uyvc z&qKc1#QCnc+O1;JI<0IK7@f37@ypH-D-wqkzwEYjg+QCxwvfWF9B9%OlXMM>SKWk9 zt`h?Pe{7RW^?9D$&;DPY%*TsT%TRol%=&TNE}G*m7;QJ0KX^Kk1&>bIJKKqx0f|TS zMVPsJ2Yw;s?8&9=G8%91IO5`k%c8hg_8}J$%7|jbbWr}>{ihv9voR%IVGOBUz?7ti z$Qq~9I3z&Pqb6!M8dj2P!1mr@O%LfcY zb3w+ODAtONiP|BFFbFl4T13%E*MeZia%*sKmTlU%cMV4{$*t3Wk789G1!_g+kAQe| zYZwIz9CmuInM*!@?6xsE5ticG2RQAVq#qE_qFCd0l#v(vs3Dq=Ynv9fEXdz-Lli6^ z@gY-@q7mJMYBa@gAAFn;M=(E!#cYPB7vgszW7yJ!ECz2fmm{F6^c46(Hy%xS%!Q$l z3N9ux!gg(}K^O6_3=&?(ijV#)fxcDYTjEyVxn@sVJs!*ZVT?nYts(TGgfoHdNB&QD zr*y3*Fbyv`z%_s(Mv` z2}pnv&k)T!w@fPI4lg0$%&OCM{TQQkr3Tt?Cs-{^_QP^M1+T-M`OH9bw9ArClmq*c?S zDpJA$3UX_$y^oSTg|qd?8l8xv!g#ji$hMxjGjiSAl!+5@HOR0N*DhE96vs)_&ZY zL>Xy>Bq}5li5PhQz}dN-scI&YRR{?BpF$827>4us?&lUzidqG9($NinHXJx3rVCbp zPgLSD9u7ES4jf9TcmEe%ksADp9F!%BVPGm^dE2D~zE0dQXk#yz}e=SOJJLUM{iuz${22sU@521^W zMm?myOqnEa|Cs7b5`ML#`|@m*xao{p538_1*|~%NID}e!`OWzc7vMjYa)vjZ&|}dS zag~PVW3=u3?fhwDqDx6d34%-iDUvx8bH=TC1i8{A8me#^v+o3KL0t5jqGvwkf>O<6 zKa=9=7Fs@hEwv`joyu>xz&&|&wo`c_Z9I_2sGY7Okxi%V86bqcDFlGExO2tz$2u3qPJ%RNSJoE>vkex^1^!st|V#Ng&lCsw;y zpL|hrUC&GJlJZD5bYvg;g${c3eFW2U?2YNF#>Jbb%qXxz&v#N))bX^d6jEfg`BfZ8 zhwuyV5N1BLrMy7&DJm2W55Air2aC|klSz4x)PLGY)+m0#vzcOdPL3~R8LI`H6f}VM z&m1Q(wm-O$ONo=d$8kKa7AxAqS0*a#UB{j&@NU;J@3DA*IunA7oZR#o=zxi@J=Kb* z7oWk!=GkjkIi0Z&_*9~{{hdLRe)%_6PwT32uooy8;pdaONPHqQz`Fl}KCm>aKKkZ4 z_4iIH6WUo~U9_H~E1cijUZyk>&Lmr^%>f;T)-&x%Ve9jw05}oIiwKQNhLO~x+8nYU zx>6ySafCgEc9{KwJ&%GiXW~`v-2u@8nbl{ zfy52W^4#)_X*2er-R)RylhV#cmF3%oN*KlmGqqEo8JE@tl=gi@%*ZNGCrw*lBx)YJ zd3~2gc|MO_Yn=Q8SBVsHK(UZYi#n4ZE%?sSkPl4IrCa7!EkUlMQN`-Gj1r7vghe4$ ztf|HN1-?G9{R8eGqhJaI=ivc@vn9{uMO+7F`h-n(3E;f3#aTzonn~zslRhY6`lETD zO_D2k8p(PM^(9*#YsT>}#t!Q{J@lmjwBhN51wr_q>5?_5@*ZyTonw_!Gq#G}uRrr< z`#rZv?2zu&%(NZUHyVCWsuyDPKJw3CSHsUDO=H~)!IrKez=^{}WL&sjZYr4-&*GG} z#mJN>FO-n%rEv6b)JC$kN@FFybcCcHP#F`XtTEK9o&A3(`0TZL_7h;DSn$` zA-ynlNo7{{b=<}0I5*{3SeiO0%v=;fq$((ht!G9m)>GMfR+5hqD>`>{;7;Bni68r3 zsq?Ro97QiZpdCy7cGTH?wn#HOlM}J4%gG;sw*2x~i$CIOZ%-0lb}93!?2?6Ryby?( zbr<9sL{T0CU384c`@8!SZQD@D2ldDL{c;^-tV2l zG(AosgC$P#xN)}Q{@f=LULVId(Z&$B<5js6O`~WI{Wlz zyEKI~&Sb?y`6XDypz3eUT&)O8HHJ#+RC1~=QxIV23yxawmOPfQMd9;F!iyJGqbRxPj~3R zSSILNHg$uI>4w;)=vk;oGK(lQDaqpx60AG8X2oL3TIHlJO_J17a062hVvAYqIjS5Z zVz%}_E5Kej`Blm#o^!d)xcQ`%`KKMNKY{4Rz@M zsf%xex)^c9kSanmL04NL2s1g~e%hSt=MP*R+_U9bZF5iO4n7x-xTO>5X^f=K=fNam zl;j4A{l>ZT0JyjKT^PCHkSwZMl8^(FQ&VKU*%Cf`fbGnaCb4@6^SvN`(IV7+W|_O;Y^S^$ZuR3Zv($E~?@@UC;Yl zC9fm4mRA+@H+bYh+3oayj8MfMfbu%Ksr4RE-fEaZCNs}oCUyL2o&Wbmli?24@Lb`l zz=a=m8yc7ahyBOD6B4#1pklQ|R`WdBa{-L7R+~-E_s=w~bt0eSAfi;tYOz^D^Q97# zmiP;iM+aMO@m3};W9hjpk{$}^nYpje_d_%=&fB8Ta9waJ=pi2OCrp?y!4DAp6qU|_?ry7d zPDWw-E4v2U?u$Jl;Y@LC+V^f1(uo;lY_*)$=R9Fy#wM(HPoJ{~=ysGesRa1~WeZ3DBX}Ozhz0RSJB3`g(Z3+;A;x zS@t`^#?X}q$XRfG`>l=QPt|~}lW`6M?!y~MJ(6Sb^77|PJCG=Wo8u+u#)v->bG|*i zf83h&R`XFEXq19VZnv(z43994y;Ud68g1sB!}=oAcS#vnlzXca;8(If|GHolMFm{% zjHxr|BzEZg0eZusjFyo>*a1MR2fA9z4*(YMAoBwuEGQ=zQIt6hbzQHk7Y_mJv*6-2 zK+n5Afz0c2dHBZteJiM9e0J6st`};7c3hudB&ig%IY&V2JTJha*5B#EefgKE+zJC5 zsfZvzsAzb8Jny%l0cb@k486W~!3_hra^K{`f4jTcIx#xyIr+b|sq7%}=1Mxn%9!2N zzJ2Oa;V!6*U%hAzSew)D%~x$OyeHeOdcPtXh?78@qoA(N|A<9>-*NQywV>G_U*5cU zF@tqyy=Lr(2&;-)ahzL zO;)%hE)GfG7vQ<|r(%OCdNmFWb1N#r-N0Dy;BZ5}(sv+0zcwP#o1;P*N@JQ!f0 zY$2$oU)>b}Y5ZPlq2mK#$2=?Bxz%qRP< zgF@SMaq2+zX~6I^^G+$Z6Hu2KFc^a(_5gh(v~-H546q04LOi}!zm(bCVU(-^Dx!wH z+|zyMt}lBFwLdn^jF+=*imW>TrGG*q+lt>`O7ywy^6S>X)qz<_lispisLl&C z^6jF_7b>-9hJZ#!(O7JV{?O+2)e1m^Xt*h9-+Ia5Q@G3Q4T2{!B6x*w=+2Fmx&_{? zJV0^!0v@1oWNcK^em-ko8JNsQ+eJbzwnkHyHIM&@)|(SUcohCL{<~5fWz`ckjr~ap z>5MuMPw40}iEwwoj+D7dNFc|N#h7ZnA?p!#j&#wRno+&hbL=|HaUsc9YWpN@x4xN< zCg1UMAS|-yCN|X+=;{>C-=1toU9Jm!!ks7r-po3TGy+>QO~&yQjH--2j4rmnm44{f z5=FJLA9_*`PyNDT2Ne;_@Y6{31Aa3{q=2M9Q-?x=+As<&DQ_?GDRu`{?G2QUoWpUn zETIXB0dT*JblGnScNf-V1cwOG2vGbk%**Jh*CKwi5X2t_9E{Q z2BVQ*EEvK7(b6{Ag3%MX&i6>*jpygr5LOo8qPipFm1-UE<4I1vBtQP*5N8{EQGt>G zucJw2u_Wk{1Z=k{jA$>JZ%Rb4YIBj}8ckkamaFL`6*~F7wj#_!E6o0I#hn&(vg52y zq*KA`YLe!@z(rR;De<+(aaRlg&0|PD4@?Zk1L==u7z-)((iYgo%-W;Wf&kl8jjt~? zsw)za^_|iwxiMWTU9u&AYP~gIr;6x;QzeE-hRvobjH&5*6R)&6ge2^I7zE|{HoiLKCXOX?79?D7 z!ja0z`rrD3Dr9Y}+DvU!Z7B)xm=v`cN*#_4wggU^yoJNGiklTUMBlbzYR9&KC7(8@ z3wIk#JGsJN+Gw`@j+=8Nf0Dna(JcBzQEy7lmI}4J&zCu)5UJ-Ld1Ef3(v}2H%!yT8 zLS{dmsz`T|AhHFSiOB~0l3Z?@lR?wy35U%r^AHtk$CUT_1Bq-RMzvYdjOT}l5%NJg z*|3fj5jEnnM&CGDwAlDz_+sk{=VetD{qNkG z6csn&3E%gyO*UHq;i}uJ<*OhcWE;A*(H2BL$WcZON=&pP){TZ~kX41nJ;|_?K}T&d zfxoX?J@4Qk{+>fEaMTVc0~lviK8Y%pVeek^Y#8xg3%nYiwaR~t7@JUoD4^Rskva&U zwul_~o*1$*pSnOjLqox3kCI%r)dS;xv8ln<2Zmk)CAB9>IGC3*eC zC*0t7ScMC-h9>_;mC>kt7{DW>9EoHL0;x`ErZE*K8l666s<$fd{GLe9H*Y<HafqyDkwZ1i6xsBK8en48F9|DO@ByCmg$fd8AUoB z(zq}x55je`r^1jToj6~E^ z@P%;6x=&HX1J;}l=zA(6%P}71d`^iKMtn#DzSE^Y3ZJM(${=3B%}=uAg;zGi-aed8 zjm7r9K@Li`ISSiSu)r7(!QC{I{)UJqPQD$_cf`001>O+=9upG zu?S8C+>diJ5`2kuh9i6!p6TvmQQ{aH{p_UTX#Y=t3yDCQiwFRJsX9(|P|#2fwxedQ zo>-w=xq7?8DHuqjzjBJm8aYQ5RqT%M}LgpulAR{ndQ?Ju2(pHnPDJIy3 zq?~l@8)C_MFhB3QNiw&`g25NhNWQh6xA?lAO_ZUaydz1WqJUwZ#meo_AX)g;WjlH? zpioQ_Op?x*O3~ABSW=3f4WZ)ch)>kLI1NYyl0=4>gqEHW$qA{$#;dmoo%i@}Ooh#G zaBKAsMxTh~$!kc<=R53ovYhtW`1ZKVS>wZ!0URXXi0URMsOvlZ;LT+PHeT{+ee1K zK`8-vG_>wI(%93PFe)4U3|LH?=#s;d_t2^8WVxw0ey3#<2K+KZ4ts2ak`DC*SzbAt zSxmr9sdxs(R!W*o^&j$ zVVuacJcF#Ow=!6?F2V)jGVlb_9PulqX}oy=fjw!ub41vRW{|Oivl_;V{2>+ZhthZ_ zp(GCLbyPXL^$@&s6KmH6ha5+OS_c(5848cnC{QpDw<=|ew(uy4=~B5&FX%;G~ATI>kiErV`jy1NR;S3>1!bxxjMFHCaRz07Jj2u`G#Q1`x-in0M@((!(-V zR7f?qq|nmS_RO%brRYsE3fjfKg`C4$7S~boy2*k z7`=aRzbOA-tM1ep2=a1NbPRS<$+Bj4q0&D6G{LmHTYhw3ilXr+cMC*2$RcNo8M^MwQl=yu06n*TtQMj05UZycsuued=1qEvr6Iy zDv>sytCZXx(RbXG(TS!7W;B;HwMQw1jp|%DKFDI-!ZBOW7?%O=ACjTKBfr01KkCPmtkwOisy}F_kf`3Bgas zT&I7;gOP$C7P3cE5pLDJZ$rX`VP8pFNi$wlDwOF7Cbt!47Dwsc1I{+?VX51{h-M7X z84snWu^JPUtrxr05tFHsthS4E3lNz+2;@w$F>OY6=#^0U9%KeaizJfQ>A?kHAt;`f z0-{Wl&Eug%HuLO<&l#t!?CZv|YiR(?H1pik=#*mpCQ8_ms2&Mv<5O%V{n(87bumM| zZ%Lp#a83bZomF~^>W;d*+Pwc~1Mx`Slor{M(ZAQD5ESTJ;s);_O zXtIhmV7G`yEwxQLl&Jl|A4UX$QYmzCUe4gNSxCnb*AxFR=4^iJJq=bT_f%ntB+WdcA=hZ*(3Id<0)2(4}*66C$|{3`9EE92UYzbt1!?Rt@Mb7Uy^K% zJ@!lBmc^YjHXlUwlLL&q&F0T1>$19ret*|;TYG7uvEd5v$k=XEl@XI|$2A`veqAlz zKRH`8=ThF0&jk>dvo^2WSD$2`d?K$;(DyKlj(#-Hu^b|`L2ec3XL4ic#br}Kd9Zrx z3;--&TiG?=a`{7{w2EK%w=c6D1&MhWbPqx7dMN<|66eEA%q{7M*~|D~mq~t}Rfpez z_NekDiHF16?!(l@%rBK~4cbA z(7+c0(N9Br3i27@#@?@*hCLAPBu!_4Nl!2xYWS7i;wg!C)QWca#DM$u|#Kj{JmiMsNK=$7QIL3?W#g+qcjIPW)>wg>9G7Wo03#EsPI4WyYvfX1M}F~q=(&v~7N zQC0zNMFa0TKgNJE0OE#(l};IIUCIC&H$|6wQUDDS^Hgu)HKo-gPV(_eN%i{yZi$;+ z4iK*>OoD!Oy&6J+(A+8O+mjvsS+@io2)G`P?=zj5;8+EZMAmYe^s zbsB|m2s?R)yViS0$pvqg1wi4D1l`$=)CbdZa*VHlDrYpFYYym7mg^VAPdhXbWPpOH zK>FIvhD3S$E0} zX8JVnc&cX;Mk;hj(})JOqB>C>8pX|!-U(0_ya6JztOS~egnS^HiU7*Uyv(1;thGO8 zAH`Jk9uloP-pxfFx(rw>5Wg0Jig!5-FEygbDPs%2B;NSjY~dw2Wvxu~e9JbRg{0$@ zD)nCo#M*q5X)jqdmOs@bt_0wxay9dqf^sXk=|2$2&Ux7G>JfNRBOKs3c*0cN0(Ar# zc~Tf8Y!XL10}N~+D=tKPN)IT!*xaoB&}RasZD7lF zlez#l^Q)Z-N8hfJ|F&Qi>BM5fNqy3fu$r)UaeM0pM`8OuupDTGQ~Eais;+Fxf)66q zW4Wf)mhJ*k&S9ySwRy)|x2%MR9qZc{*Ny-eul-WS^m?z#Xc6dj7X!skEu3d41W=EB z`KH1G)toLSuf65!)dmK3Z!f*i{T~_@_ycP^)UvwB>;jLYn=Nu1%s0XlVXF#wPR6r1 z8ZMDuX1!L?!9=^b=u`N@&{ z$S|ZAG8T!?Z)jAw18Pwkp(jcnfbSHVpzLyTiF}$YfLxoE@wSRsJ7RaEQ+kgh)?~ReglRO3)_ne_}FzHyFi}G z7NR0zEjYxZoeSU<|LEu>otAlySE2~-F_>j3L%x!~Q^D$W6&8{fmVeMS56|+5$bfME zHBtmSCc7y+ZMYP%YXcVkPlQ#1#u!mKcDQknK?_zk8xZFPk2MF&gl#nLNBI_FXn*hX zp7)xKM!SXuF$+6Ln+Hg4KbLh!v`MRp5Arsq<$`#%RMJU8iXT}P`|eH2P2b)@XS?K= zvi(6iNIR=)WfOAcKy3Qp_h_`$wvM}6_`d?E=-Bl1Or3#%aDZ$&n?n%C_WL`NAZuKY zvd6|hc*kYc>o;DB5GYv4j4n&+-moQnFurEHSO_V2+4*ZzA0Px321z%CF)+k>zs6zyb;&X+}v>G0>ZL{v;; z%V`;{wY*38^1ir~x?Bx9F-XFr{TP#2TROU*DMYc|)SRv2VF#}XdjH))BrJzWNfD=> zE2^1G&IlLLlG8%Lp8*w$6VMH-zGyaCXRykK$@}8sfsL7R#myaQKD^H+HSbv_E?NIa z`b##OC%wB~YR&Re2}mqaO*6UVzj0}PZCuv4dHMR;z2rt5v1JkF&wItbldYR=QY9Th zRR=kHNbPK$rl4@*h)jSBkStrdX*FAW-)m0d`lr6V15ahfQXNYRGnU$qpAb$ebu!#9 z@ET%WL9X2^SBIOD)SR2cQoTqNnWBhYJ_MjIZS&bM{herxl7%{pl4(*#lGd1$G)R#h z95qIy4u7oZ8jx@dAPWOn)2>tJQ?%gi19hg1(gSAwk|+oRjdScojkgcygZTtmtU?(v zMjw>wHfw5=Sdk$}pM21Pw%xs!hTOo&qXDnmm|};QK*|AVqM~+&Qsx4AivXZ~oL1BM zDbc(?gV#3x12nL2g%d2MKxMQ|hagts;5=OXG|16MXu5WU(N|R$_RN^35z51k#U#tT zq1kDK`8JI+)m~f%D;Ldamo`l2_SP-^HQq(+wq|XdgEvf0{U`)>6{CO&JC!T)h{-;U z&Tr{3pmMP5c&sRnNUT&%C{^W0l5`lgvmK4wauVFA@LgIXx22|ti!iP+b-xLf8u|C!g}53APW7PHudxSh>)#8Sx>si2_@Ae1y$f2$AF)zX zbuIRV5-UNew8vs8C(ui#o4i4BnG0eq3%o{a*+~ZuVEwQ7KcXG|>_02nd3Tq03#9e>>DPFyl8&Kz!)&aJG&xcW2iJ6mgv6h1SdR|xx%*TqO{TvUbeo|KNYKZ_N1=-AydJ_XM&Z`3R@&xbIvd zsDm;<={Y{`Jl2GrPUgQb!Z2|fdH;W*0!s)gFdiT``i`)ctd)|iW1o10P6nO2S|tI4 z%p?Rql~i0g^_qsGqM*h;sf{I#c83KM3M8ZBG6zb+a7W3|?z?1GYrOui2YDRhV`3y* z3J}joLZ}vjo#TYVKakMQIlV4@JsSPfPFfi99roDN`x|fL668=q9c&C>{(ie<_FBE$ zK`TYv0ClYV4syYE&=%on9gUXVl#HNqN>%N>F%uQ|)EhWNgr%eWiMdj6*0|O5PB<^m zKd6BQTJSebCIvQe16`}B=a`O3jf$CyrPV9XW3|2T!D0y6f~{lainn5<;NRl6m`ZM` zCpG1m$41n$`!UV;)mQ40@-m9i-=j4^C;5G}qZ|l_{-5SNcH|F<=}~NEBI2TeGM%ILxM^2r(H2q!VBPk(YJaplbi*5luQ zrxUHXO_j>qH2pv&NPSSald|}*eLxTezoQ{IM=r=(#EYeJ*?3l*ALu0V{)HcyvB1ho z6~pc#>_<7+=BOLf!q!so{Z@MhvVVW!K~F^fu^XlonlMvJC)!7G{$z}%yRD>ecVU#U zvq^f$EEVOE-R&2Cs1Xz2TdVv%Q*^{HPO^e17?j{oOU2x( z3S)~A=}@3KK~AnIa?+H7oN6^8Z2Bw~fKyJYUDMdEw_N4ReYby}NIHgN;BU$>xjn`Q zyD=9ywH~)XTRN4pYCL0jDq#COT}P`M-mUW05)+l`rf@68UdkYKE7{)dM)uO(gsm`F z^$b|n+*5n)$eH!@PF59!I&75mKe)gGyJq}qgwyGY=py0t)7jsp!%DMs#QtuElR;3Q zUd*${J-Uu0LFspr+mZv%f?GV!`EFzQrugCA^U)_KgmFCZR}VpLPRiB@PRh?XZW=p` zFqx_3zs&EL>2LXKAGlL1MkoCIL-_yi1_c!lX$~SeSXo%K%waAXq9~RatHW%YX(o*> z^171(pE10T1aKTv2U?=E_KbObFW&Nzm*ISVOVUJl8SksA!aZYkwM%-qS9kWahXB&> z-{SgzOlyE&Ea>ga)T5g-{aIK=Zq>wGy(!exexdcWwt+8=mau3WQf%w`E!kUsl>D(K zv}ky%(x;gm4d|w1I z|1x3tPX=1!4Jc?+V+|r*?7Y0I^LG?G+!%5r_$O~%6L?F%8~WcV0~s^?Nj-V_hl)uD z1=zK&4SoE3Z+A-)us!rK0kX2-;A2oQ(@k4T!+!-ci9_dzzqbq$(Barxpu<3153M)< zyWtuSB_y`8TYQ8<($^p!$d2#_vcCa9R>;~OC-8CssxyF22u=5k>aWQSj3S`ahcEOH z9FkEE{f0Ass{eX_(m?_c9EYwp@SD)f1V=pXy7u|;-V2r8kM*npsKk1wCjXBW$A6)q3>e*s018P7ld-|Y}J zr?&FrgTIdugMtQ84Cf*Vqu)JTIdoo}l=e-sIp7lW=E$|l>g-=G^$7KQK$;JIHM|#b z@RPf;Gd%ZYgdo8!%EoI}U^*w8qsORE-HVbu8k>*0QS@Pa^&+?s;kji_Y#ae`S?N|A(h^e&P$^QGgJWc0xfp_8%jr9e>wWmrQaw|w)g%=Z;R+k zZ>#&i4!cWz_+%J+3*-9_m0T=~oTq~KzXZDSHD9~4@tla-k7gNisPuJxdo$N(%o!N- zyM_hbH3Y3Jou>t9y!7?KQMdsSs`v5HkTcCm2Mr)hZ_4->X+rdymx|xgmom=h4Q*@cDsUf zW{N%pN-N9&$JMN`5b&{I$4I*2WQt9*k!$n5>*nf$D~x5I&qzYm<<25k<>G1T_LKmb zKKZj!djVxOgO6Nk4<#?;bd*|MspPudXWjd4<-T3PV5#dj;y&SUYk6sq%#l&M{{E#px$+J>8tVBdAMr}*x0JR8eEysDjobG)^H13xZKRPEo!q+H zs4~2?$Jbw9E#0sZJs~YYxGL{gF-pymd+Cgi{KLvo;hbFRuY4``N0BdV%8Dr?Sf*1N zyX;9r_uU*Gj4n+#P)_Jao^)@?FOY3IH|TW?q((6m`2Nj4)6)lQ29=Frt3qs;f%o3P zQkrgm{x3JnX4k2D191LTXN{6v#nX;FMkhRmc9UcLNoeKDmy@}l!-O1j*-j!ZW;^P& z>SEbkY3F zu~n|9!C;igUF4NAJacg9T!~HQb654qtCod#Mo+u+`JOq3DVq>W`vUQA9`vP*Fu7UK)!Tj2V z9g~{+(f&7m;WY{kv+|V}IbCSxwz7#O1*(UWO6<>Et0OImU3RZOEPZpMj6(TNy+@=K zx4W>=Sck1oUsZQds!Y8=;e0`I;@9rI+qJ6>YTBLmPHd}&nhHE!UFZ(j94ks;eKCCB z@Mv-jPFwBGfGH+YPRB^5KZxk_RB_+z-y=__$lz zlu)0lew=_is1%(TWNbArj7UNmL{`1`UL$GnU4J9#H6)oKLaq61?ErhYN_8q@xYX_= zF$DAUVxEV*S8(6n?Dk~K7SqbKQ_GjxaV&gob~i?Wc|tPjx-6Q#T?5d326ep+$PEk8 z^wwy@e{IL4p;%EIqqKIYY7r%Ji?KHq0v z)uC9M>ng7Qbu=Zq)y~NaNeBdt#mTZ zJzjRLdfKoO&pFTpIu(&SZ$@)HTvz-g8=fVNb~U-aXZroUuze<{|5g8q?`%bR%@Q`p zVF;qhmO^x4uVX&z)-VHx5A$k&EZQ!f?7~Ww>dA={d$dODjdPh8y#FrmsmL~Nzu&77 z(OVt7b^zX}|1Hw=xVfhI?zdhxSf$7K-cpDY%T&MFi=Mg^R+dm04);!P>c_zWHk90$ zO2SlZ0**^<7c%gk*!8pSY&_e4S%DdMYw@c_b4nV)e!yZsy!LPL8`uw+3Uqnm z=qE|sabsyoq|FG|k2(i6mCkaMk681Isa`E%lpIx@ue!u!M$F80YbbWQ_4cWazzOQc zxFm6dsprPI#Nii|6WqTOTXf$fJ!t61h=+0euNEARMR#(V%P|qo=0EVR-e`zcr64GS zCc4^$_vZXf;*WEwc@%SZwhsoQ+Z5nTq?5?i<~-K6j{BL)TF|?_n~nyr45hLURq8w_f4su&8-9I@{lGz@CyP`u=tC=u2Trdqvqm z#qt{g$A#;enQ;PPJTAMrRA2cHhZDD?8#cr%kC#!k+TNJp1LZ+>((;=Yd#8h)i@5du z$G^{qr@3T`2BiHTgdha)nq&@x5q}pVcZXBr~=ie=J`sS0V1fxSet0>N1)PkuMHe;t`qcBpcDEkw4izM zn!0Kx`3e~>c2%3=wj#_hZ1Dl`Drt@vG|7qe>GD^?h(haSSCd)0Bgy3=|6YT;pm-p1 z(^zqWCw$J3`0W8boy&G1j2|n%2+~`2TF&h~aBVotrq4fEICD+eA_YH5n_5Q(F zxzzNN_5B{hNrNdRO$wvueoH%}XQC%GMsOUVQahhxG;6;-$nA9u7obd#nV`1lN6~5w zz39*X;T0Nn7{nnASInIy(YflT{;m6pX+*b73+r?d$(&C$o#5yA*!bSHp-LYOMf&4S(=2XI zc3rDP!iOg^i<4p*xLZ0S)SqohCvDy=Pae|c5Z&D(?KhZI)Bx&?V|cU3HbRL}gb&OH z{4V2}(N~=29@ECW&8wkw;#d;7mB!kN_;{#M3aj=zr|Pl!{$%B8ncR(N75F^>-@mAJ zn+~kB9i;^9xF7ZLSVZUVeQz6qt#3I=svsE;y&Ycl_niL#&3Wu_96D>`dFRqgc!4%Q zOWTJ_u2~6h7tB9hcV>O4BKAmGmNA-&?^KM?w|Tzx`czlrM#t)_I%d29=nl|L6hMCd zQ*Zv$?lFJ@k+D`%Qs`uD-M(c{U-_zHo4Ye~Do(26nlSjXBq^-&x`SNXyRylp$+dDi z=@>;7+;h>I36IU8Uf1|F+Ec#pQ_{6pc+Oq0uK~-H{o<4Ne;2v!f?)r>3R8IcitTc? zb@jOn+43JzuBu;zNLM#%sRaFZ`6`7(HT{=6LwfuWm|7(6%bw zWS5VqjwVT0EsTViHQ9o+ANv!j|Edc$p=!xwEc{QL4PZm~{9i@K|7%^D1Xfx)V=Jhz zgkyy?ANr@rAhYpETf{(muN;EhlQ1-(36H^vy5s@$zXvti}LjMjo z1*N0FP4fp(8EHWgX~X{Po!}EA<8>&h2fKc<+~*hU0>1qR*eXZ-_=JTXG@(=AW+mTr zU;*@4J*ey#%DMeP5e%O-1ypPQkT5jXAn%8;vH~3tD3qZA9R_z-)d9uyC?xyv&N2E! zuf?LF)z@@&aT<)KJ0ARkxz}b~#i0CmhTsD0xeePtHSh%V3syEheuvJJ1P-I3c-aXJ z<_Z}9tzREJ{zw@!N}$6|-B7g!=c$7*A6rXJJUGlbb2te4&QM_x=0F%W zE`sg{3OWxgm_p5UQi8U0@L@pp?*}2FQ&R;LxJ<`1_kzwY!H z7U~28L4i%n;+l2Aa{tmJnm0b94U46lswaHr%pa6q>Fh8azWw~uNYmbpnu7|rH>xt> zPeWGrVxJh^?_l2F2D(X)@ayAQ+9IP5oy^a;B=nAlEPQ;;QR1O6VM3gU3L-4J_VhBm zj2ykcl+d~}Sa-#bFp=u>36fZT;>a{`|UmFwh8+U_UNxsUOl`$<}z6s}O`6x2bteX;W{&w&&eDZ1h;s0Vo-- z@hJwx1;{-09{yZqRm@zmxBUEuQOYK;dmE{AaR?CTnf2kTIy!x8GVR3C*ABycm&wSQ zUbQQGH^(i0?*{!e=O`8j_ugzc+^hP}gDnRB29kjfz(exb9r|Qwtx0lPE`qQix;R`J z&-C--InO|Iw==JSw#0gt_U8!4mFA#)R#jz%H%^qwwO*DlcRoG;?B!#u_Wnc9M4-z^ zAv*a!{gv*S^WJOU)iyzNr1JDbOof)wu~l^P-7<-aVqL>ZyM`^B7K%C_y`xYg#?iHJ zHKFEpI=+l6rC%KRd`6rO!-@1|?Ay@q zmhd~`c3dI`XY3@uc#c~RY;1h!Q+OHHpt;%esd%Yn&ujEcx>`+|s?L{9ztGG1wxd43 zyOu30FWX%Im9*eCGSXc+&f_PVJ!y}8-+yW>yfT7C0w0jI@a52f<%`|M^N|#nJsV&Z zXFk+n@U1daG_yw`<|&w>D2f0fFcZ_Jg71UL_Y-=FTzk27U>N>|pfFLX`ZdRTfXC)n zdvaDNX{)*LWZ1Qi(@VWRN5_TbeI|T`Ppf&`DXVzbTsnKATJ-&+OWOC3<_$pbotd_f z`?yDm9HHjvSxnFqz}38RP%&=V{4yd{lCC|OW!SH}OfBD~*!alhyutWFhf+9N;Y!`S z`9h=Q>dwT_^HEjP!uAh4MLuKMN<($SmGY4$x)CLsXGM70ha{X%+kH`ovTAuaws>#jhqcorW z$op&oG+RC{a?fv9sKs@Boo>_hIq1n5S6PXwO=QD9zf}MBr^1rAscV@>U`kV{?8)KF-w&CgrG3u9dpE4I^wNfem(W`%dkC{C-tk|Z}_F5 z{*{mkR-E7O2+!DlhpG?rgIrEI_V>iSO=n&z4UV2*I``Gh%i+!RAh4We;j7G3dOfnZ zZmDQmxaxA?GqfZ;P}@1Bn^9s?S*NP{uyOsAMz$jlTYf}qGFct{a7EfnKL32!VIC_k zkd#*^lh8m)_22dRQ1Z&KK=xg~YPb=deFN|d_93#Jeef`bgKkHGR8qVD`ohaA1q(i( za&0!(YkGZ#^P?=EdYUUt+)1Bsx!uE&-t%acSk&k<5PN;8tLe>va^bX~@rc#e(2*SO z`NyTHw|m?`nA~kYGD8Pw#hlRt3nNd<4|%Ybeu5Usp38oCXZ+j)hsJARK@PJ7A+?F^ zCsA*HMYy@|olpKQ;}<;nOFVnJ@pFN7s`6L7@fPzxT!1g{M81x)+3}^;m%5K8R38mb z{>nLVx)8r#&}8E(d|Gu0N5vSu+_DH9mEq_iFt?(QHZvC!3CD+zH+&?OyYG!07-bVF zANi%vhi-S7Hq6{J7`Q;;7jIICRy+_;gs07L2+=nBgL!5#s#6nOA`s5`t00_-Zxd%moM$Dm$ivkJ-%M!I=~$pfZE3-s~P91 zczAq#T%oOArfGV9i-viZP^w!!b?L+zSuO)s78qBWg*+ORaC{Gv|iPL;zZUzL|% zshhB$xU-kl#Z*>dk`S?XX8aQ0*8w~Ay7J5xL3_rZViogkhL&}q7dR43n~k0*rm((O z71r8VLE2Pa4J`E>A8*;+3hxUuhBrwC{EQSanCrRwneLdZmQp^K)MsJl z@vU+C#WAn!etS|HgKmq=TQBOh1*88@SBK%wE+LgiHMrz_ZfuM_-ux`%h2-k|t*u|J z4B}OCy~VXA@!ylhi_A3?iSI->(AfPtZ}5286_gn>%;8C`{BU8CV(kl4tF2N)K7#X0 zK0YpCgVM+&wih>axpVYh|IpsBtus*(tM<$D(@p1Pxspu^G|#Ad-8pNBe_cGi39gjz zliOl$8#8OALt%ou+ptpNxux=H{L33}#|_U*h?Ktj|r85adPfodc%yyET2>{@yL(fa>aZX%bBf);@! zXyY0{Rs0n^`(_-_^5EAfH4?$X%W{TAZC_m9%$28C&R^L~o>iKUO02 zzVZlpr6RELU}wRpp~;bVA!^km?#r@SvuGxN+qKY36P`nj=4@80Z4w6lzwpEC4OBS| zTl>!E>A{L^9P;|q@eB1=Z-a`2M=8AT`6u6N4$%!C>qESkRJdAy4XfMx<#X8jW7jiE z?1~7gd%{OiH|c`bytZ{130;`R>d$aNYTt;JOLh_v)c7U>+^F)&+9o8nBCh%nQ9-2QPa) zh29}h|H*eOI0riFaVYf39`n0>uup1*-Y91-LXnNAX@-D73Yu4^@TkOdY~MpY@HKNR5*h z;m?PTRIG~;W`*e3vlYC5x>Bo9n~UIhsTh1Lma5@=FkBdNg4zQN|mtw{0#ir zKrq8vz1o~hw;$Rieq+@uUFim$vxcFq3c=>+oInl(nLpLix{$xkQ;IvqOBw4+-zL8T zuM5T}=fIb$*9}J98EWAAybc=28H(f$RZb66tt$h`^&t9wxGza|61_ksLKX1-K}Iat zezChg{%uJ4SZDiK`hqlvUBn@k^IpEnkx2Vk9PsuNcyZ%To#G0<=PDU+SJ5a0tbNmE z4_M|@fh4`poFVC|o4G)!eAZrvGfi|Ah?_^*j8&X~GL|8N5xfJdQ$Xdtv>0diU7;FS ze*MH;?aG)Y?5R#NLji%qwn3>fB#-F*)kGi;8#u^8p0)iG^j8V-pn+Z3@lDC2odrH< z_Yr4b@D7wt%bn$qezYdRlYT`=3$P?VVgu#>dCP-8n7}_JuAVfwii%&!tUxMW3A|9P z0daYNYj1aBaa>F_pHlW{Qa6?B8kBkhBJ{ojc5&V#JQ1tVzV@y6C8YnAB(9VD;U${3 zTN@QzIvBa7uO>kOAwcNq0_K%0I^}4u`KWR-`e+>Zf4i(S?Y)8==5JR$LPxt;G{))2o2$n@eO%fMR%OdWl7QZ9*?c2P+dEe+s=i?hB+uY4OXRNS zFHj@yiy}PLr3Zm}XcQRlkB>RhTu~7Q8L@1gw;MZod6h#;fq4F>`rayJ&cBG)2nNY! zU%$UEdI@qT7pnNO`Z(ff0@<-6O(L@lIsf~7f*$zhA3}u?Cq>H*Z^-(1K#;tMQ_2xI zWgBTg(rn;2Anv&jNNBrAS@(>ngN@-k!WY=x%3YS6ehbJGet)(fpD2k@bD|P9gACsDC@1=zyaTzG}U5+dX#R$ z~6HS@QUxQ+(zoV|Zv;ov-nFtD2cNnnGczo$sGEP=W-_z_(nrRgk0Wap{n zD+&edNpV}@h|ML)TEF4v^A~yl4`pv173CMT4G#?hQc}_}0xB)tC0(MRbP7m!cMA&0 z04gb|(%p@Kq|!ZfcQ@Y|{5|jYuJx_wk8jOiEMR8t`#$@ey{~=k>oV$3<6L1<{%VSl zlZa>2o7{Vh@U!tk7y<2E16!YJQG~XAFeU2!ucVFYfGk{hzLK~uGdm4f#HDQ?#XRCD_gz>{C$aZ zIaaWe#HA&sYffjqQq-F3hjLYS$-Fjy=_97piP$WFh)&B1!-7IvDDI5D1g!*R9guxa z#sq@hatL8KCea39Fw1K{C(a~E_txVwcC`(8A32&n80YgfV3yg=w9Z7!uS80q#4`T} zI{k?8Z{>S2pJCMvHrNPN+F>l(=g?3Zrmla((#C;JzaA+Vwi`R&ne>=X8}-Js>Wq>f zKErv3(+}JagrtsvM~Uk%Vy)^^4&;5cX69px0C$Z&>RF^`9bbUB-54o-C$KE_Q8A+a ztA$Ju+}KdEIMH$i8eqwTi+@|rEW=TwNZS&;@Z~KKyzk@fDLw_5`)Z0?#>I*>RU4HZ z1T`2)1=Pm5KYT9i)XLxaxwH9KTr>8-8IVyjegNIenVXnB!xE5q`93cf72OqZ=~IfO zH^++7fcXq^po65agp!0sIvvM6ZXjfy6bj~QSE@@oE!>-9s)8DV#E~NHTZLN*pvIHY zsr>E2?@8HrI{epKJsA`zgxJK5}HaVL!xU^@i>W;uD;#H*R5Cd#+mQ>InU zARApH#_)6%Wbf4P)TYpnEo~6R^m!AMG@_ zk$k9{`kCPBr(dz6k*8TyamhV4qq}v%&ydRR(pa&6Rqj)KC6i~r*>}?a6Sre}WB4h} zs;G;}1_IY}DQbF)!1d&ShsyZMv$Q|&fgYV;5Lug`XQVQWwi6OTW;wgQk8p3b63(5~ zXNY~2iYnl^WUr4(cJvI#AQ->($<=e(4(c&IpW_jApScu&bCfZkqrb8z-A{_zzdZg% zQoVTD`H`PU4<@ceTfYEk?k*k7M&y{x!ORHV7xmv9`^a-yGlww$q{L?r2C#N_!_kvl zS9?g$)Io^JO##W0x&#k|07!`IGmAgX{O7XP;lDMI7r~hQH->2vAk@(soTwJ(P*Ums z7j+Re4&n96GmpW#`GG8ee~}crw_|vd>K>3D=++IkgAHk{ddof0@B*Nx(d)rD?XjAo zo`{&0(F8UNOk2%Qa<0Qk@iR~kt3lMvGz4E4&w^P?uWANSI?2Bnx2LP)>vOPODo%yK+du^9rt$sQ|I9k(!>TKDFhQ z+e01+Jc@6b6m;VSGF>cY{zTyS%<7rviH%z@pu3gdFQCTMfmNR^MCSYSgq}I;`CUN%FkQw0E>v(3+b%u`vK9XUB}?wL&Va>Wgh1Dr@wG|X%H z{|V?Oss+ud+2Fk!V6C8yoyXkR(8m8Q!G5m)d)A$c8+#$|j`iXp$EWllM z&OxH>_3mgvQeJwCeEBL%Kq5*ifx80!#{k;q+usZUoF6&xL7Oz{2$%scimhEg_thOk zGa)o;-%N|MZ6(eCA-qSVAkm2NFrJ!>U9uHOBjO^3b|nAa#ZO`m$VIK8#dJxZ7x70@ za(_QI_q-aZLr_vy2?!U64Ct1cM%3XtVDul+fhh{FpCcb{wd2l9|}ea^`;Pm65lx; zMK(JxX!%j6qA}&eX?ufWNFUCUM}=_^jyeMqVcWu`=SKJc%3$f6-=9rAiRK}^D+hRjQq*|p17v=F+m9~Y7ZXqH+XP*ePx4Zj9TsuNCNAOw zfZz_8|^0dFa;F~N(Gid|1r=s_%MBl-^N%kn~OO#L)lOBDrnXDI4fSs8RX(GyU zo0|olo&=t<3hyK8&DkF%m)EfZsyummnaO7Tu$G)Y&z{1bw4RlIGTSlIE)!qX2w82s zVk)sMhXKQ=D1bHEH5KGv-(1p>CR7{$tq#`16k(M|!19cVGC_#Ud>s+jCkp=b{Px;c zK*r_<17rW1Yz6aPI3`&JP#f}vF-u&Dpi?p3k|hLF#V`ca69gL?+AkdYdxcLHmC1^aVZ99mh_+--L(wd_oU$YGPXb%r#^1@-6^gOOHLF`Jiu$EA#+$a6IC z_(Pv_QKJfDvlG-S*C!K3QL&@HE)jLF<>*i|!e^v|a;{ERSm|{kw-V&urZP(eDmwD- zF~mA>l8j?42B(YDV3O}KVxUt~=hGR{x`*to0<-#|Woo)|WQX_X3pM^)&z;rjU#egM z^~PWX*LuGNCz_Is6J0vu^9jQx+F!KPCD?eeQP7>lCQJB(UcA5az%kG@gYuG?9aEau zPOKHRG29l@(>((JXS*)`kE>KpmTMs>v|lwtT0wVYSSS|&w68C18LUSmgY@{(Z9wlJ z!(Z3aQV`K8xFvvA)0*^mYwpzwSGxWhE|!V7U+{49vwT?!b1a*Uc8`;ko)x?_;6sXV zX9Qu5lUW%u-^}t&G-=0znbnNf&?8~XXkq6tGj_G1kJKWzK3?U;c}2B@U#log@uszg z^t~+CfbrzlXNj-B{8TPz5#g~m+|^82-cTwz@wz(0vU0xNX2Z$WFL?jMO~YbE9h9LK z+@QJ-7pKR^JTXa%GmCmD$tWlHd!6Gqk;ywU<8VyfAUc%{`RNr-WCxv2|F&u-5*mk~ zrH`06WHC!r&CMO$NC8M~Uls7k=G-BMjK&=Q_gvUy>0v!|?`bop430Q0-7eZZ6Jxh@RDj~q z{`u`k{FX9+0i{YP?_fTDWe-RUn9un(CA*}+gkH*CkQQo3gO(4nn$*1L*JC~s8MdG~Y@LrfapT~&Ty%YbP zWOzHUPug91&aCRJ-rA%OsNltX1W2!GKIJ%yJ>7?iKf|n`nb^f7>&2xD-6U|we~$1k z4dx|G@HCRzk`UIux{MXYU&dd1&G0yS@5*T+I%1DFT{iST#;<%S-QIBckI~&9SSLG4 ziv^zX{#vtW%%zoGHz{cQ9Acydjm+#3Xgy_5;o4u5`qQG`ljAZH%ep^|q~>I=eEU52Kwk{Yvj+ zq#1T6zdHR;Jh|>`tb(~dH;UHZD=tMTP=%PJh4)sE-w2^bn|qEAlSdkFlg65^Y9ZOF z@DSWlby4nMaa82}a}x>%d`{#{ULM|QiH58&vO}`Ymu+$%aV3z7h#jLC#}Xz_O&s;A zvN(3mu2OM$#Nttv@8zW(ba2f7@))h`;qdZUfLL7^ittGs$o$!uJ*^fw>CyuO)QM|@ znQBM3_r|^Kl#8Em>l;}XHI4v$&7=oTMuGN2s*0e$$7qwuN$-;qq29vZVvFDJE)NIV zKtDxWF_HJfNRh_GL!M1=+hiiOru=i6rfS^`N_7-ToqXn%TevH|kHD;;ZT&ZYB6W+U z5B%Os-)-RhVn7CFZ~b@4iQ=s6SZ3G>V#@e85S_ ze>LP3hYa2TfgL^2(zA`&A2=!HW!;J7%neQ( z{;!RhulvQA4aam_Hm%Mvtsn_*h3ImKURzs%{$iQuo1U+?yl$68V)a%%a6KAubpp`B zKCchB6yq%^7#*zB(u&b}@th zb}_kpnyCnmR|p3IanuEA1U$CPLXf*WsBDDK?{NUb^;m%>olhE1HJp+rjuQ?G?v=;E`^n8@sil0y{cyUfx>D;pB zw84jCUCT&}=w;s{d82{oWqaPiW`hjh2<{-c-hbF%uxr*GWcL)TPOKgsRRr{gBuiUK zGxd@P;mf1<3a3cgqI!*9&t(o6^;ICeIziH|>mgsH{wt`P=1Oe(xreGFqgn>{%S_K- zjXsw*ail>9xr{|wrlyQvNvR!xyjCbrp`5UW54dr`;H`Im?|BNG<^jZ2hr#sg)>fiuxEFLY;p%`HYYIf#8Jh4P*r@Bo~cJMbA(WBSESXa+O z5tU>>BXAR8vd0w!^zvss!m{M!I$HN(08a?@>IZHOtiT1JFb&i}bqW*+pH&1_^^r;_ zxtQDU#+&aJC=6<6KL211H2pM7P348aNPdf8Z7vYX3TbMs1q*V{8>{_9#G~;Vqs|~h z+B^1D)7=f>Mr=X(jX_0)JVKVODvG$~`CDQJ6xf{tTvrcR)ZulT*O`b#+6at#d(dhDT>THk)WXZkxvzyF2N|Tr-{?Hiv1?dX+2h<} zNr@l}AlR`Zn_liotO5|yP(zeCBozxtGh}jiYvsQ-vTHog@v;N%3BdL8d6KA)XY!+H zW(g0~o9GfyRl+Is@9CeR56I9WJPVUK#Or`MW&wDz{Xr&RNMFT29q1lR_hG09#>4>0 zZJBrsJ>VLB2j(Ks8HG8XSRfx-))5uf1{@%!4-r0tTDlG)Ubnz@*NK{}H|e|yOnIvh z91YOK2JSy#*B5@59M#DVsPvK3J z-23oD19<8?1&A^72-a}I;M6&ufJD>}_C)n8qQEp4Ok)7(h|Rhkj?am(26>{H|CvY* zU%&zY#dSosWLDqLi5|APlkt6U;G%8u z+DPpt?J#bNbwf7CQ(T@*#oTOf-M(MKqv!{Z-2|Mx^KZry0dJ-|f$g11+B$)&Scx9l zkW;FLbV_4vGk5qmJ6cxJx8U#UM8_L21uj{ zEm2^Lyr@0~;O}wmw-c%IFT$-NpbC55^@Nz*EgC3v%|M*Xs_l}l{WSpzzB2xOP~+nA zIkzhB6^p|xfL}Hdit*1`0-ZDTd0HTL>2m(8%Y_ptzcG2YKT@Fe(dCVR&c z$A>a=CJJXR^9=*0Rq~q;jd~K{lgi5v-!!GNZdKIu6s!jw=Yu}D`YCDkI@{E~)Ep#J z=?4XZ>R|J$`*^fr7yG2oO-y^=IK*ZJCV^-^yKW3yTET6qfeGo()=6_il@7dR(dJi% zLjtQJaQ4d8N|fE&*U#KK_UM^ua2qZ(W&gNsWjT~n!h{}GK`<~-tfvD9jwq!$3E9KK zi*mGsO;hKmi~olyM;Uemp8{B%1?&1!$!GT0Z!b3%1%NT5m}b_n4}t-IG+9$kC(87W(^kE&*0n|pH|;5S%FD79lRBU=^Ckn^jN@q7VvwIs2b(G)C@BcNE^2#>G8aKdjt?W9Se zm?g9ZWrZFIapoNOB}UUct2l+Z|9ZJ-l9TJGE30*^l{u_a*VDr?p2qkPs~JOc*X#cwhN1e%WB$zp>OZ(3x58bbs5msBH>%?mH+v<^q#ZOP&6>0QUB743m>c?JU&w`8zs) zw^q>1pZWpktLErh%a9(aEwG*mWj#5yqY+?)?@n7GxGRF??<{O+>fjNCD5(~ffPKcL zsct+s6bJa$ajZTU<*xH+q?7A@DpUK5Oj|=d+y$rp4watU9p6`#QY)LaT^@QSFwgq| z-(j1I%9OAPt*OSUA+RGZeX^KcQt@)I7Gqd#|MjJtzbMj@=w@^Oi}tAIAx^Y-mS0tm z2EFi3Etu-0O~sPF=wTgfQwEuFY--rWT^sj|KISz%&Rs1cmH7CPje-==Z0)^=Q=UvO{q$0~QF z`R+}61}YY>-+0Yf0vnkLd!MeU6KSK>FT2Oqhvpyb(->O$YRmn)mXp^`!o%RlE=>ZtSB9RJ4nTUp2L0x<{~Sv47bj)B`O4Inh=j zIeYnq-}E5|6J5E2Z{puWZ7%tQq=5X%ROuqVm)XgSyqAr^tbj&1tA7%3?CBVl*R2jP zq?4^bY_2*ZgRTqh@>a99#jM^|@x+fmkJ&bDYo01~$k6w#QIkiKG}!^_&BjjV1?c@z zyN*SZP5*rlD5cO^Zx3Tyhn%m7F=A@Oc&ZEHaIS@p1tVw@WMHFYv6kRTNk_$}J0NWs zN?p77j=K)$RhQqsT=qBXwXf+B;Jm6?SE*0$?!*l_OdG1Mwp+sH-tH`#t<)8GMR=4v zm)#o40PajG;SYNv4~<6?eXQ|G$uj=d^~62IRiw|I%j#>29CoiSrglfo|G0Zutv^is z!spg+eWKPjIa=lAq!_nC=+<{>#aF}6`;J{>P_f{0@PUopdGuHJ^05fRx z=MX-_)#9cy_SPpww)xsKS={-R+X}c$2X!!qfe6-y3ri^Mz`TpR25Gqz~h+s z$&>bw2e$jepzl{Y)zvk7kC&84?oZdv@o^vWg?lGGMHn^%C(yzKNAGeVv!MW`67?R& zVoB8ddXxVx*ppqfBVRO#DEufIQ!Sptg;NYU`s%jKpVPiIK4U`B2OKRxVc`9x$xQ^P=drK_;_dZ zX}1WjYPj}kd6k=%k2PT2RbaE%H+RpB_M)HInq7N|tX#}TUer<5A=));6va(u{Th89 zYIE_NHlsSOdN;bfZXNb@jpEd9}qMN$DN zHDD_@AN&Dm=j+VYd*G@Y0|#VY-z)b^z)&f$8Y>(H%Q$9es?n!z2JlS^)7EfRBY^bB z8z4#cq2z7v=Y6q^c2LpU%rytN{$JYo_ej~cIyxH=URen1c?B5rd_CJ9j2~!~fyRBm zhszxK-)~YF2p>EODR5L=ecu?&j${R#hIqyxEFXO!I_7#h<6xut+I zeSocYjsE|`xWGRG7{(X42K{(7eS_FA0AWpF7}(+3LRJ4i^s8;5ks60)K~6Hn#%paHyd7;;|sV!E2epNn# zabE#`HadK?d0CW9*Z6eJ_#^qGRaL=Yt6~Gw^|qbg04*l1q%rlr&CL77FjH#Lt7bj! z$b}#;s+39(_=RQnL}%^~zS-DOV9;HDoUoaz=Q{o@hzNe$A|k;1G2mcjnO8M0zuZ~y zq8N|q`%cB!Eo~5?EcMm5@&%zPRaLQTrHhX9wC=emUeW!zS6`_1>zLA1KEAv-5J=2o z@;x+FdFFf->yFfOo{D94bsbL_JZ!;1`76y$sM-Y)LmCMWfArNGa6@%*yt=z?rLTo{VQ`Tk5 zg3B?V*B;C9Lv&%3pDtM$r5eCm)Vt63 z#&yDsdyV!%dl}Lb?5D-z34G#NM6mBxiJ}QF7}Xg66r$c^{#z)lXd{D+c$vIHw%Oc9 zgOTMii1@owxwMk6m*pm>sa$WhSWcbV#Jo+~h7RrS9P3pj6WZ!}{+1b9DxyqE(7Rx@ zZ0I}bjS44CYxD{A^s`@8jVt?jI%QRNG(jYquv358coboxs>(O(sCBVvkh`o))J#yr zLT@Yb5DnIxT76q+w-h~FdgV2g?9?bcYwnJweeSI6W z9-MiiQj}`9)9YS+w8@m+$M=SNwdD2TOr4pUaT4p;0C_0h&A7_>pu6O;?BqC%;-Y}w2HEKcFocegQ-bO*7D`|c=FVmurvY1itHqh2f~s4_hP|+< z12;Ue3u$fViM~NuSGZuqjZ4w*sF_zfL5w9)&7k6Q@YFk{vi-iNATs_Xo1`&YrX%IS;B z63R*tP)7+>^-!Zp9GUjb?h1c6cdA_05^i`~L3v$mTkkDnjwURj-@dWj-9;jvLc_d7}M@76k zexgo}PGK{1YRY>0Z+}unf;jY_C+3=``miy5a~AC2Qfv@d)m}T9!5+%#i_r+Iay)ml zPNeo-ia6@=YK$M?BRMF(6zyC^746s3Z1=XiYV;Wzfj976uO$@a!mn?BJX>C{8f3zo z^0|nhA~Y&29sMYP7vlY3WDpy+W~wlKbX_-8$2-ZYEO?P=nOd{jZG)8~9qb8#R!+TZ z!%^F6m})N{NS#vgoAy5JPiYA^5j~El?BDOMSy2+QxlLs>l?m@|I2F^qoPmU;>xxQa zl{Zx5mI&OsdZm>1;U}0Fg%E3Yq4P-T+(&&HXo&kA=ZwRsHTVeJa2A733%~OogH+&) z_Jfj;^Ie&oLzc4_A%x@O; z6-4A9Vu${}*fHhC(2#I%wKUgH9yKr@>GcdBJf8t7GMjKhJ$=_-r-Lg~zQPpS27>1? zz25GZUxl*LW=_>6k7kIt+U7fwcDt=Zsj8+JeU6VZ9jU{Qd8eK*{WRSJR(EoA6U%*L z-p~e<5pt6%uK>bv;>~*VXdJGs>gz}AYeWOR$A;?sg%7;@Vk z^X!suy8DTJTRNSAQ-Cd39`K1{^-p*Jtn4eX)KQ zb-n{`e8tSXK6Nuc@&hY~Vup?dL`^ak4SslH0(yiovKie`e|ElcK`)kJd%8+kG8UNV z!S%S1P*8FSGyR4|#Ysdf)9o)S^Uc7V1c0Hr%f>KHA%uDMxX{f^O)^6P5?W8>k7@LD zoIyO=R{+{2rT59**i_C|z+s{NX_{b8`xN}bE` z;+eSlW%~#Wnr+Vu^iUMqIi@PT7}X!{8|z}r#SuM))tuM+erd|s>_->nJ@=E$PTCdq z57KHDNewP$lHCt(FsPMp_i0#IZxTX=kS@1k9@&=6HeuzEGS4p*Dc8_50jsjbrk;V$ zKQW(QoNtjby z3KnO;{n%aPMF~HE*(W%e$horc1=ZuJ;MV}~|8VtUT^gV6fl3X&V*n2_Y}_w>BZ-sexcpuxVQHh)=3%zlmq7JaN4oxKLsHx2m3mwHvTQpn|!H& zSmSkspWlc_{N0eP%T)jGK9h-p@KhmDGd}D1Ijjq^2o4BVl$KhCC20WR$AYV0?7n}G z5*+pZMM(80@hOFOL;ZL?vFQ|g<460;we$gq*BcdNo1#-R*yrUOwRQX0=5bhaK12ai z247$8?t^2Sdzk|&a(@n;TPi^`jK_|%*Unn9%5Fe^09vQDG|{CZ*mrNIcQL(F(~|R!7MWtkDVxHv!~vc zjb7-9M~q6pdHfixB(nFYZ(Y@lnM+wtNw6M(R}=9>`{(xAD;4R8gCpBLr@n+fNfPc%h^y_i?mttkI22_sy27h}J-fui0 zcAamxLc~Q$T-))kCwJ4fTBPA@0X|qa=GXZ-K6pqn;kEU=^J2Vt)C6xo4(^lm_Fj(n z*?5R|Dl5JFfbLR%LS^Wy|E|bF_TNnf7GVmkxX``5Ox3J9zpKOY(ct*OywxP3f@ely zyBvwATFd8TA z+LKa^A>_k>!~`9msdBjfRJM-Yt^CD$LzB{GQQ14e-QLV0-J;Lj*PVHq3R9}n%qh3= zCXRJqAC4Tdmb*^c&x{Oil{G!nbN^jodHgCtF)gj!Z*nInEW6Y9ddhkDTV1x#=``Dz z$Lh>!_VxW6rP|fpCOPbS*T(Xxew{3olL_dpy_>4wwJXX=<<*|*Gvzl$B_>ZZz4`g*jHpTRa=XDt@GviNr4mD9 zA&WgZQAK2N;b>_$O(n^$^z8+hQj~M*-7g(oZO+#;LV~`nAYi{{MQmXcjDIRWO}-RG zgIPTO@m~yy3lUm)HL#~k3oQebG_XU`pD z-P<@Cjh{_y@$X?57MO9IiXQ636A_>~jSw07cDc)Cp@!_fKkekFoF?E4$8oi28&qWb zD(ccJy6)d5mRL-Av$r;Ubalv{#m8Rd;kigbB9|t(lDYmq&raSzcrnAdKk?(;iH#F@ zwao6P97a=Z<=L0Fin#K%^1jPaRgHd8UvxF(vyyIYp_~Yv{6tZYwH?cwvEHew*`^y8 z?Mc@>+`$ft{8-+Jy_5<^yuC%LJhsG-f~Kd=M_JrMeN{KiGk#-yo}#NLQ?|)>B?0$< zXyWDJ48@Kd_zJC*?~q~DO9z`n3Aev6B10#EN#2*(DxzYNPM|$odZhy)<%+H2$3<=iaQMUWme0#Z)`x z2`y~?6}C#35xz##bv9i9p?^Ty&0K3RYw<;GUDmZ&trWnAE=?<2{xYS0p{~CCWIerG zd&;?<;iRgh)8IDq%w{sua+a?!ezxY~-ui~3>hJXS`osFiD3E&$e*FRlsXH|;-8kv( z2R&>F`sWu|EEf)=V{Dr`yFCUcrAKQG@SP{S5GV((ezV$EjN+CnYkgpSJy>&Sg_Zgzxi@^^?kK3CVcR+%`|5OQ3(C9=&&&; zZ_aUEdmonmSpQDcFIVMzx>Y{e-LtaFUcS@;vPgq3zK&C9iG8A8o+o~`8)I1qJ~W85S}FG53AGP) zYHkmaAsi z!m>e$%QoZHDPvhVq0iNTWv9RNpoWOt8)(H3Z&3QbeDOc$ zu`A=B6Hf#22-lA6W9>%AovOhwQAg{^^XsG>WnNu|ZKpr->-$VVWesNU`D;B*=vkPC z+?M;G!(~pi-_o_^#7L!lwD3jJv-5nDAs!7o#Z{FX70;=AcFOR&pQo`2$`TP{O*=dS zr){mb*B8zUOk$tdu1|2+d&~{EM3OUEG$iFvA!Z?Fqyygw71>I<{5PncGMCIw<_(LQ z_wbekFSSDXrwS50IH+cG%B`D-*d1^RMo_cI%5DVp0`mC@9_{Twfv* z8@<~EC^ysFXLk(*Qv}av-`KoX@Qb`FmmVq_7Huag7zp2*e<-rs1UIJ~`um0I-LWpt zjaUO;k~^+n9X#Vl3T$aQ)436{Dc*Uv9z2j7hiihx2Cbbwl+wwjxmmkGgwd+$XNP<3 z!xX!6bz2_J7em~BDq%EdEy=19;Q>Rep7A;9!AprM@bT01xPx^H>_*?4qrW1R@?N{V zoLcY)uoz*-s%YxOM+WY%zV3Y_9(tANZ6tntp9B`;T&8ttSG``CoUE}E5p*)e>Em)x zHH4_3Y?C}yE>^{EzjPvD9){)K@D(&}l&<$`+*ieBFQ2PUbIP0vD7mjt-f;G@vcBi= z-&Id0G+PwJfs@6HQPJmLGSUD=JoL|mChi>q9gaI%eepz(RRqtco%dpMmx=>!uLf>= z(}NdTdw$@VxI+|&&>2CNgCnQAyznnXIGOH3gzD-48X^&yOl~s{hvnDp9}s&)BEU@T z&W|F)s6B*(2ssk9ki~aH9dZOz@w=rT2MFIt(^Dpc=P5|bs%RTg*V$u zXtsFHil`=@tC10;d;2{4*%kk;AmuK>dpuuqPeB*VWvqWT`6w@T@i%(Vx~wlD;mzAG z&g}%US-5=D9B$in@M~LbFxND+RW^`%>o?J(pP;GdGUB}PBR7Yy>AY{90)F;f5b!02 zz<4505c6GCe?1>YlREm^oi zL`+EsO<=&!az2E#zX{`o=xNPBcG~rpd5w?DvYp?hj_10f!B^kwO@o0yuBV_;^I=^F zelaRe{l;rM8e}O)ji(Ll*9VDBO3IVO#6F-TR`KOEBfIKb}uB=!w)3C!i=6eZ>uB80cFXpLFJHb?E<2r+veiaz&G8X{05rad^6GaOk zO+2*(vs)^Fv!)2XaL>>$QiJ4`6t~%jpUdj7}Q98<@ zD}RL{GCgwVvrG7GYJ&E=AJe3vkMPmN?Z=J6vS(bUShaZa0tub3Z!d~&74Srk)aZ+< z8jlNpzdm`g(#KY}^=Wk&Ov)yt4HjQXqSeuQe)SmQ~BC9o*%=Q>{? zZTjqc)<%=#)Gv^m_PXa31@^C=LFb1oA0UEiK2{tF8Y)|uJ^C-iV*eFTuF>es0YC5! zC97Q7s-_(+0leEsD_y}MNS?v&@mui*7lw(FqIIh3ccD=W=6NVMp&VpnIbk^}Rlh-&+~iNZ@?lpJUg9sx}{+LHmmA;5VsCiic*o+%qCZyIL+W)deTiABE;}ymQbjQ7@q-fM-mXdn{rmFk-K= zs(}?e7aMXVIt@tVzR-Ly(O_cZQT8)H>dG#toP12tn4%N`ifLY8lcJBMBQ4a6v6${& z=o>S13PQ#Cj|9f@<^^$jySeD$m*8xFpEfeBpXu#Gs$wZ8<0jF)gGl#{`pCGm3uhX+ z*+H>f-&^~}JjG?uT7EY--T zrE<04XQw0uOV$5MIXi0wWyD@56@yq9wDpcw|0-*;n7hiF?E?>h8=DPHt+|#q6__+y zT~tMmUw-wwIVUnX`I%Sv4po8Dz8PtP7R8+-3mAiJ1t$#Pn<^E8S;>hmBEeQjJwP7I zTKdIJ+fg_g4^wtcrFH_b*}BqE+nOFW&ijT6<^)^$-?!KYE7sie_7a{Z#o(TgXoQ&0 zHJ^5blr;W*PO&_I46~<74=m|fE8v12A*DNk8O9a-cLr?QstYr zm+}N)`QW>}f`rR&dXRfuXMe&(VY_I_!UtUp6STV+3WgPwprbL7S=jfasNNA>vl7HD zrQ}|i*cDxw&Tz$6Y0t_Y&h@c%b2l>f)0j7$kPsEMz<@1ZbfI*^?0C)YC~}{dUCER; zXPshi8T8L&nv7>-zB#<@qS!*~V7jIO}t9!p1BHhSBD4QhhJhzZBRHtIIB{QP9R!eqr)QHzF;>fI<2px*cWr z6pr4JzKIor#884h&gId5w4XOR0kVL7d7~dNw-EJrz4S*f@?L&&2p>m@nrCjh7%3{nNNQQFVcGV0~OT3Xuz1LB2vPq$a{D%nsgR~9# zH43d^J&FL?!uwT=suIJ`c?_v6reWTQ)&$N&&d*ZlOK>a&j%p;1$pT1>FvcM&1?p=f zY9x{eX(mb#uZ{N}QlY-wC(A_Ys_`rV-^4$PyTIRf#4A{)NBuG7>aU58)9Z$ias z4>A3Nu{2o8?z_Q#+)@oj+$7Wb9IR>5QPr4CLw+Gc2(?YOemfulw$c?o0J(-P)h9nfNykdA@qN z!DlR0z9KiqAXIdby=Ih&!$O)7#^er28L|m7bBp~)-tVWq+ylL#B@Pg42zD`bFO&|= zkuZizEl}8fA^t3llg*S7M~|ynavc>4!GFz-q=Lj~Mw78p^1IKli~i!+g$}i-i$fw&M$fIQhJ?N@!S<|y#dHtx zyg<~Fembgu1QKVdxNaM_Wk{<+JBpnH%>PdVpX@%BGUOFHO2UU$uz@1 z#8sIlG99&B2#>$nzcaz8Puzt6cZ+{5oHbXvV&D@S*C+=y*(}c6m(Cu@?kyf+dA%sq zZ=ch}KrHZ;u+Z5V@Whe342#dBkhb~%K1xUZgA&fv;TH%+lu`V=#M_kg;DIh8vXFVBkFhK{K{bID=?zPC ziBfuXPzIjRmBN~3PbKtTm~VP8k%>RHq>HfXTChDMZ8aS6H%o3Vi|v_S85qr zbsVu>n&X6_SZXMdx!vXa{f6By#jI*8VVfIwRhD=J*VJ9FE*NxQIUj|7dzOLdfnZHD{c>6uWXI#l`)my({_P7js84{u2r!ng1C7+Qw8bxuXl4s*c z)}YY4$@mkF4DpfOj$^M~IjX*F;~CZ>ZESfhGb09)7^hypBxIP#%1bJ;{N!?~Uo zHDzb=ZCr9>JOBGF&i1uv_-_HnY2t8zKOsp%t^-4KFCaPm@2VtKGD#}~J1S(c1&e%~ zwi!}t(~4*vkk5Ta!!i5DB90PjUA2ch>&1nSzJN+Ffc(`^0%+Jg)^xE+vx+J zX(L%HU#sM>M7$MKll-K(`1DJzD++nn-)fXs8?Ag%6zRSE_gd(%xsW@Mf)|35YF){N zdI|lbG}P*!I9fsyqiFVUF;Si0n@A?r*DZg&LG0i(Bx(!aC{E>uQvGWE?7E5nE%aLh zj`1#)JE%Ewn~#xcgpKWt6r?lFWjNSOcZ$8|Da zaDI;&LcY@32OCk`VeytvjeEqD)C-d&%TcLln8gElxGO`Ld_wjl;!x*g3@B-|jjA}= zm*dybr{~iD(&aq65_3?WE)klWq3t$8G`zyCsE7DQi&}`!1TB@VesXHJ-^85Ah!Uh^ z>JR5QSHzR;mTVk-WJ%dIuH~fB3_JtOj9WD%M+^^^Ji&qJiY6|d{6vWTXkC_ z`aNVsU_Af^kcRT)7}zf*Iko}_VQUaNK?$sgE=G?}@j8L54^+}o#l>^%WZRJlGvtsT z?Z-#0mFgJ)%s^n%tD@^2s}TPmDS_2wCr2)3m^N((fh=XL1n#jAe5&T4@WUSNL;(_A zsiPwABTLvOK-W%`o*WZnMHyf{d&3l#=>{^0`#%x{|DiE}fpOPGZhrbG;O~pKN$+b4 zeWJWpqn?yn3q4niozSh^d`EzeWD$Oa*C38XKDxMNBO7MKb_MtV-G+gGaKF*3n|_%E zC`S&;eHR}`=LAy|E-w^TN)L2hh(A9{s&UcT7VslgDYe94p09G+&MYFM`AiJX0l}bd z(2C-2LVa#U<<|NOj2BFN^}jrBW5H7qu%8TG6akZHSI-A_gx53vDvPjvHBa?80KXFo zUw|R!K4F$bE7&ZloZ=Hi+Wc1e?eK=*vQ5AG=3;Y|i1k6bu=q6qV7~aaFY7w>#ZUN* zoK(%E<{TR#hFe0;vqJUHVLy+Nj#Cr@&%g7#YTQSOAkI5JekV1wSvwN2zsCP!AlgJK zSU~yABzT^FTP3HC-9qvh%z#|fJ~^bR*6IA8t%Hz)2M>uuz}$bKd6Iz zJ^DMKyNCmd{C!mo8m33xfw(MEY zKWMloE}@&9IT&mR5nwKdVED;S0BGeyTk{ea-3iO{G9-$~?P(13H;%ncYYqu>U0B(Wa^1uJ3-N zf$4x}@MnO&z4D;i(psu}0|-?^L#kD74}6+@0m-I?#dx z)X+6Zm!vR+lz^0U3?LQi61s2%_)C|9v0N z`@HYLC&dpQd#}CLbzSHAJD2x>KcZ;p;poMnEVz7BOF!~res*D*>m#HL@!HW8oHrc| ze(H|_yG(%^2^3}Y*jB?v#oEM$*yNOQ<0(cac(GKUY^c4Y5$qg`Du3kQ{|y_!ro8?T zoM*^52=z$tA*iPfIe7KqxyRT4>?P^+%w7oQ(@o2n?k?&tQciHxVO-_)vmqG<_SE)@ zr?$n**GeMk%odWnF1eSbu+W;!a7hG5(ItP(Icl;4FjQO0-{sae! zQmp;Q`V%{#cToNgc$I>wR1iEnDZku_;$HE%7SqhB>+g~YcF<4AazfHCbolV(qje)r zFk&fB;cTBbR2%=2P7Z3Y z`s>lPg4PgT`6zeZm?R&W5~BShVlz?sHrG)$a<&ukWL8)oL5opzp`d!Nga2GS7~%yT%>#0Ej5a5 zzL*-ylm**8T#{%CddCvD?I11r8Tk#N&VdmyLya5vu=51e zoc5IHd){ea$rS=f1;tlC9v8GRP+OhAKvoml@STa}@O~e+Z!!n&dhi+S3ye433zcxm>vVTW#2nz{ID5fR_~PWr8Mk<- zY{&I>+1|OU#+X5+3}`H@uoRp=(wTcasZn9`fjuo5iX|D}^Rcfi4wiVW#*ahu(Da*ZFpbbnc=sRuR>O zU(CYx=Pqpfty0UYwurgA#gTN!h+OX>Dswhizf{mMgv;?aV_Z`36mFTk;7f$_?Vv9O zSJF8Ux@Tk`ZXU3Y;pm(qgYCsjCHYI_Gq6l zjTH|JRLL5=>+fT%`Wo%Uf?r@Ir!f5hc`H;wFc?#JLbaO@WN&WeQ21=$~n~o+^S(4bu=15gvFrV^%PDjO6^Ck8?joF76V_lfdGD|DvqwWvi{cezw;|pHq zN~DEZ0m5ZvtB*e{=ZN7o{*L)`ZG``wa>?7JWR1MhpAtsbE@8|2_4aku8=IydHxxc{ z3JXdMuTU|jRmtVKOA)T=)xWb`@@z=fuay^fD{!p&f#6JS)=BoN=@*nU1FZaJT9ipZkzOPxtin3^nl~B zw$tcgOLd6N%y-S)<)mK@i6&@4`U9}OdUU^Vt1GbTi2#g?{q9{hvc5C8qF~mlec`R` zi&E819cnPHLy&-_`$3RxlO=BvwNZPYg4(gG7DzqvN>A%Ti|dIB>u)y4oDZ!6a}r0b zfJT3nd5t>%^@n4B%NGxeP&5z8?|A^Xk^W;%*Np`hX+B|NbE%LVt0yhwx~SSUZnIdn zsGH{?V91##bxInPXCc(my}WqOp^OmFg29L0kA`WwIb2K$pK;O6)8M0bS%+SU2qoC5 z7|GQD->X0BEZx~AGKFG|e%|cq{o4xVQZ@TC)r+zN>pZ`YRpMA76|R^-c0mWKk{1zQ zOM{B;A@`-b*WB9D@SNjEl|q7TF>B*qo^<4pWC^W)vV~_((3^lR@b()8nr2-xcz@{| zqi2zw14}Si5NpC`zR8^xFQ-TjZXY2Yq!y}aRuIbtWOXcau#lU^6U}?Tfy57w0~VCG z;8PCbf`pzX-cPp9g1_Ek@1`q{wG2x=RvvqB)${G_&&nTvE0Cu8WZIljpW6wh>~1e_ zSR?59K0%pmmBdpud}O41+&VjN5X@~AyH|tB+9|x~Q}S3cJ-+PHN$?4skdIDAk~QtZ zn(TpIkH_C1E^j)QGYJ;%1krf%psgurL+orexjOR25=#$0tm0-IfjXRP8}v~ou~oF_ zPmJzpS6pwWw<_*c>Q(+csXw2jU`kpKYe@IE)wFv_2g+}Wp2+Agj(bK$-eL`8P++}D zUqr+^mLI>&d;@{6u6vWN{>E2POa&q+H_w+GEZu19*IDOuXYgxue`SOGXBOUAH7jEN z+99ZWTU}2|&cK+~T{ z>jQDMK&iH)3rwPDIbul`88-;_#8ia?YI1_!k`Jw^M|gxd7zif+S@1OVpv~ht4G7*i zFO8vUi)q$IM)=dz$W@VZ^2KGTm%sF9DW)&Z*re$dB~#Xs*{;0lf;DbqWXJdlstEZt zA*{iWog$G|XJ!4{1Ts@Osp+~uL{lD*_33GS?dN!HSJXm}F%4f(EMQ4Bwz2vZbPj;= z6-)0{udh%lWqUv{QwOc3`2O<6r(PLiDA4)OPo@g9b)SzHYEm{{aLyW1EsldWKPR*!Slf7Z&9 z2;zPjPka;>#0lN$=P@F7i4NrR)$dFZ1NE)*`8t zG1`@#zfmM>BM@DC6%B1-n|?NU6OuPCdpTnD13d6Omaj!+IdUPlh%`X?bYR(qmK{kV%CN?;(yJu*3yB5?xe6FMKR#L7y7l?)OTxre8AnLH#m} zV^wb~o9@tJ;-0z2XPy1kexW?d^}OrTc2A;KI%yLO(&-Lwox3ioBiA)oaECeY*sfoGWU~Gg_6eVto{2+Khg}rH8d1P5`<+PkAYlJ5`cS zqlG4ph7^-F4u`_plwD3>l%Tk|;|vI`@71%Q<)pvBQky|e{PV-{%o34dFJIeS!afB|Hk0kRxIrQto${n zldW@o`o^s1%dsD6=m~Jut_dh*73f8fyEC#kW9iNU*{kKBLR*vH#wOmu_JTAu5+`R@Wab7--GLMA?M_B$ow1FadM6z`1dO%;?i!$9d z(MM$;6ST4dSK!VaxTdG6H!AO(z<>2=Ij9pOzXJHN;aPwmOO2Fel7Gm|D=8MLX{i|$0tg&EJ1W}G*j%CFm8qR}B!6X-m(|JQLt#0mfj>uo5oLT?t zue;b8%*zmMsH5};Pxsw-*@Q=h&Ce7 z)Ag0b2F7&sD5;!&h?sA<8Yi{ox$hb!f{S#+qcWZH^RynL8{$$F*m;dX|8z~gXs!3BO(yUzIFwJ~RhVGajqJM@(C zF(=<>JEo25u&P3-`TP5lp)E$(>WzJRGW%Ngr&B~}t4sp$luaW3l07>_=;OCHA|1J- zx#GJJT+ncHk9J4KBl>fSYj~*<{(EhK?ao-zroWDAy;ZjqhoIggH4^WK938||48a`~ z<4X#zITEWxr*tfoB1a*!KLuRV?uq_{9?*|`ivPP@aX&q3I1u|}$TKF5gahy=c=a>)%7;1iik2!&Cwu0inye8gBvO3$*t9vZR~1D&%(feS9YZ!WnW-#} z3TOY5mwm(`8z+jN9*9K|BZLSNJ9k~p&m-8Kktp=4aDo~E&-p;=a&VqJA95yP{C&~E z)OvW%gP%>uDZHOT=A4sJY=8>kU5)>zz)|n)tO&aScTItIQot)sGK_9_n`Ofb;f5zF z3UPHDld*WHcHSN))LVzlgCF-&_ zeN@e*76`ZVu4WlBskQ-`l#{Wah2UJYj%11{OTD~4^+hDH^z@sp1eQi`lk`yqv<}WB z4dHL-ij#N_Vr_S!+(X0H-S|5*0)bly9b!uW-TBdsVu|*OunHMG#O7?c2))0Q_l7{A zpxk5AcEQp`n1*2KhkYNFJ}K!-Yh?qT3(~RtqBn#43lwv2_=`J4!Ga`lts8s&;QN5ookVs8)nxEZH~XBLuwDs#%rD65P@G zFDJocc=$dZIz_`f#`Exd$1o%Hc;~#+Qoh9prslyp!5zh2fLK#nQw!|)UzkE+(Kw{f zL&5v&=m$2TAzeNJ%JpJ!v>22u1ph3-!c!pWGG3!zPNLd%-wFr=G;`pA0l$YA1X%^m z-5eDEChEU^1OY^EPSKHFdiZ0MUnxGsQw9*&O9tTNB*!sT$TAWYbH=n?d6$PPc~~=5 zGHFQ$#fjbAf>DS`PjN3>3ijz+-iiuv&n3}KX9ffV;+m!3VfirY4>sv~t5CKL19`we zzfl6a2hxMlj|zB5n@6=MGppAtBr&U1Rr~QmD>HwA4fvh$OZmB<$w=>}@o}l`ucC%t z1PVyDFmkQ7@NGxw%U@DRO{$lGdx}hZ*4_~v9idKp6sE-{p8d#^p@EIv$P(I|{8QPt zxz6}OaX}-ICVko?HUYKZZr+1H^9)nZ%2eJ*AJN{q98kxR^));h-5TAO{@n+&_)EKZ!Knp7!`n9o z?6;U;+PPDSLR{W3rpT(4bz_4WC$GHX$MhZB$v5FwKj+W&rmbF$QM-$!X(jmubZ#4K z1noXC1vRjlbnf<$+wO|dZlrpTQu#~pL|sGy`VYDU%vH%$h=M!USbeVmwV8vo3DkYb zNEI%X8MZaJE+84X#vSuie?X`e;sT@T5Bgd=g3fDY5bbSHSV<20Bo_{|p+)hwRP~ju z{!R~3-E03T6AgO!hD6v1f5^K^Dbc0#IGUk|{S9K>&gOy?(|o(ePe1=# z>op)Ga~JJs&eA!u?OG{UJ>q2@{HII=*UTK4$2KL3;4cyP!3!|pj6=Yg3qrd?Qi zWSODGs(EH4-8SRX$LF^K$qDu$U%i{VZHX)F#|X4}2Dx8)$31+FD&5z?n;Sx^Wpa3E zh)Wq@77^tsVo1>bMOZ5o55Gfo$BfNXNQ+43?h;TcnWfc`Gm{%TaEa?uu%p3G1+mY_ zZrUt0BfdNSCFGj*CgqhDe=}_-%BdDc4eP&{cdhx)%8PEF==10tkeoH?sQpc0qsW_x z_+Fcu{1L^W6-S7R^Q;##j9Tk|HX`m(ymdd}#p!8zDr`#&a-nDV+zZcUohdK&W$1CT ze$nK@=3go8bNQLd^keI3$4eVq?u{QWX6qL}I9+_N0!w!ti5%|NWo8QyyIr#O&9wT+ zb7-7`DJcgz5#P+-(ymr!j&--4%g*LR{7drm!Qzay%WfM?pxZo_FR) z!T0JM={qJphp5|m{k&xCi#Y1{;{C|+87Vw{LG4? zT_Ith$@6V?P!qGM+FM`G}-41p0Y zl2MnpDT_4f_niCh3Ye4ba>x6~da*^0ouY1laz6FaAIVmJs}~lOLFi_xR@@aDQ4+4C zzdt#kKTfr2S2XDd0$Vn-LrWn#Qirb;D$0AmTJCwP8I4|etoepH)3N+<;++m z4yRjo+YWSDp+x@^Y*R4J;hsP1NB<+wP-rrQOODgzwed{V-X0f(oa*ChdQHp9`=}-? z>-wG2(Ia(9AKP1+BNyooltQyMqBrBd6#QP6{n-0DZU($#4?)rsg%Z=!^c35J@!q=y{ zdeWfvvi{F{WArBCX7A`r&`?;h4-}!^vn=RFdy_J*%d~(Y75BCqgBPNuC(PQ&;`U09 z9B$g%0dM*r?90{z#$y}M=v5+qlu^Tzf<2lFRr7W&K>JikVB(4FYYq=%@mIP1$Ob1a2zNX47&UK%hKNb+}bAH$nr0bBI9IO5S z;Eey-DrauA2DAdDSfkc!ej}kI(g(@`Suj@5+7W;Bckpu>z-Iu~N<_VLdI65`T!>$0tD8N5_#PZrnU=%iuYb%~fv=G1$m&UAIS0NL4 z^KcW#*7TD=q~gC;_`(Hd)<%VTko|7lfFp-X4NEu4KSQvnKr9x7gIkBsh2!_j1-Cj4 zcUmt?QoNm%mydj~&jkHUly=WxMy>+X$b$QSC$mPe_0(QSk~AbV5XC*~9%#`B=Ur)IWxWv)%8!+ z{Z)2RhjoIMCU9#eA^d-~W;aaEs}nuGp2k7FxmUYAQrlDDn`)yNIunuSib_`fX2o~k z>5W8mY2ifm62f-YGA5;c_ebFkZr5R`m;!}*ZXOf-HnP55cIi&Cr8Kz;5i57opGmsc zxgmFDwu3&gWVe!?W1@u;bXy~b$-A>Kq8d-N7U(R6TgeC>SLL~uarYZv_>kT+0efdS zueSom@{tOb&Z+bXVZ1rv=Euda3Hrp18q?4;F0Bv34E=E@oNjopS-&p188FJ>*Ob>j za5(^@3urey@m@JurQU@iTd~Z?Cgs$Y(9vHP!5mL~xflV`>Fm~QwnpnQ&>DExWieM4$qTS*G&PwJ3oRwI-ct##WU`MQngP@N82~tH z6-x(>i|gN#q)%8W6B9G$yk?8yiQfn+=Y6dbmWabC49PLvZJmEHtvZ9a9>aoGyR9T1 z8eL2}0Wbj)wc_b)WA8BJ00lT=OreHR@cZiSreC|FF$-~^bRtMmr2#kXW9)eaoyrp< zKwI;NCUS@V{gzT{n$HFtQ?rz505X7e4r#hy$%IMF!KN6OQ%kj{_fX`miU$Wq(zT~z zRomF;Lbwrmmu7FWYyG;`V=x#8Vhs{e=1=XO<^?bK?L0;c5eq`z?}Y)XIp1(}31N$` z0Q4xuZ$O*0^pU&(LvQxP$A(`cWS?26xn;441R+rl2L&YcDQh7(JT{0{Ewq~|+-bK7 z8NdPjhtw$WCKW(o_7nJNyl;QkJj;yEFJ~_sHN7~q_&_TBJ!P?k4Hz%{f0t(9+vrUJ zXMMbhfV10yV8Qc1rkI>;dc_lj5rKCX%9>A=_8tT&{F;=FWOz+l$nq!>bP*&3PI2jZ zNL^E=X{777tEmD;gRKxu4s8HvFW}E(NVu-U8l21WM6pMWKYt6LjRCzbm;__EHbes@ z%5qD(|_1W*K_1<>Sr zT}?#0C%46@@Va%%_CWAcPJnbCwn=l@wAqlyNS-cH>3H&+mM`71TFcCorzn;xT?Ttu z3l|a-Ntq{(B=bq|Voc+DtneX~wTg5e=jk}B0X4x#D^i~p&n?+UIQ$wNpl($^3P&+l zF<=2CrCMhHoz3U#)rIY{`IIxhx}9fk%8u|98$Lo=7R-qj-)U;3^vs#dH7*o)-;$F! z4TOtSes=!n3X)4}brY&FxN&uSdZL!|f6>Q%Gl6yq=&4Mq}JQ zbT?lQ{u=7vhT6;SIY29g!?+fS;5vwK!)+B}55}1KY-U;>9sw-Pv%BwOTyOp*(QvcK zZlUEe$WcTVx0@qdEyYy|!2js<$@+_7*p`!aYFz||GP%H{+~_2_1q6M*Wn5`P64C${ zmYpCm8XT@%X!i8}ow*<7v(~xfzUEXcvl+ciovCR64$yMiBI7nlB0O2Xov3ICw+~w9J zlNci?!q1)v(_90NdYSgi5w69N<{iJXO#&Z)U**MT`mz7hKL;o;h+{CyqRD`6Yw@CR&7GOG=z_CaqSVG!3dS7 zhS`sYi_J*=;t;w~PMz}1amKC1JO^!j#Qx_v+KSIoS>qE+3c0ktnq*gH818VCBv)JB z<{0vl7-?RAjo&-ecw6T+G0uPAPyB|0qj}b0!Nk=!g>G+G3qf`-AmedFzk%)e<;C6& zJ_n>Y!!2J14l&=&ggEc1ZQF@GxlbH(Lhe30ORGUGGUQ#EYy+usUe%ecmD5tgV~o8$#J>9xIfz%bX)69+!mvH+`5nq zlORqQ$uj5+*NW08XOx{LN>h<#AX!V;LPP8H`l~Emhd}O^JBD#Am6pr=S>9wV-bFIP zxlilBc@sj)SEnYy#Hzsdust3sZ2KZi$=XEPr=hQmTo*~PGIsrNSp91c>iR{*T8lc6 z#$~!F=pKQ_x|*TYo`?Fe-eCPP(O3`CPOkF#iFz@Uo=U4Ct3E-h7tg2R=Knk&_e4FJ zM{42>SPM42{9ZDlikhFbWS4-+hstg*Qm-vpCdcNbEu^-(MbWWI)0urP)MW|(Z*4gq zcGuQk__?_XN5RtQ9r~1PP8o~5%DsIPw7-WDCKt!LJKdnV z_EKmhd-0EY9uB6Hg%i{)98Z)aX2iTqqzO;@P&UV)RZXbCR6(VkM47K&(kJT^!rllI zsU+^;NN6Y-a`=+{G)8JglGgZ+bJSETO+DxU*_lH9uxh8ro*Y)dg zSE-2x?)uZ0LKT7R#8#VvR&f?CPI{M$IHzv3Om!T1l>u@&c#WLfJsr*8GwNb_5H}Z^ znPsUClW7e99>ywWf;0py9koQpmi)#rhd@dX!MF30>MyWM$0R_>Kcw62jT15!rhCC~ zIp&PuiU@5!0Wa%izpWh$EZy5N3?1HCih#+5o2uzIZ2qQg+&Z_f5((JazM2S1XaNUB z6Jav1J8eR*_gZ~d^4xOL9UZ7#rH)Da1G;OzE>WU8S3~P_)a=EEHVfwzfYkFJ&;*gWPQ}C{bUy)D25ciGDxwQ_jr? zE1t|p)o9t+Rl8xY(3Pw`4#CM|i$P{mW=`)om(nuDVI~YF2+Dr}Tjcf$d-_yrx3LN; z4LRbx^{*mJCTnuSeyo_>Qgp!^PXcodE%>ZY%m$R?hHh4h1&rnRdt2Xqb)Xdc{4 zG|wVvGf2?0Y3zyr#-GHiwKqD3L55Q=p>~|YUw+jC(|$~Y8PWO0uP$uH7e8B|756B@ zQYG#k>(|6p-76P=hp~cU!e>^;lr{MmGgSwt5ech@@nG=1{OFbXZ%<=!dFD^z6hSZ9 z+Z7OK*>yUQmSPLuanAPw|1gh{!A}fHbhF9Z!BjfuRLHhIT!3l0#KaV>fe3$s5N~?Q z8&U~}^bfCD1tDQHUn-4Me>hi3)dnB4yjtpbLj{I@#k+?aQXx)~Np@OJ?1_Vb+igWa zyc@GHs^Ge>n!R|>sljpIg=tW#4o1B+J`W*56AAi!j}vf-iRHw?@w~pefc*Lrlq*Fj zH?I<)La8IG5!RkZ&5^dc=13{fuDx2&+#;*|_IRV-2kxsu@E?-6k8r?8>o4xmdCp!{tGidZ%yntAM!^qyV~~IT<2hQ4t@S031q~{&jBVx( zyBgcph5^0w)C$mYY#JI{a0Al71{pgI>8)7{m{~_@Z7Qkh7RUt) z%9_`I@cUW=M8jt|>V(ifAv9D37YX|8BO}FPiI=s^?v!&Bk5i`MiB@IRMdLeN5Vd9& zHdj|VTe*xCGU(b-g0<;v2w6>@V9B?P#)-&+C4%K^gqt_=XuXpIkMHZi z-2hM~Jug(ZeqLbJ9k;M#5Z&E}N>b$i>jg-k=zaJ)YoE23s~6ovhHkGB;z%ilxwTSM zHZ$nONXck30E~DNLC7SEU`b8T(uSCmsp10s)`2!Jm27*GdJf{m*9qm<*zRU7{dPw-@Jn;9htf04*K6e@mq7**N)r*V7I! zqUX0e}scaNpH&8K-R*g)OA1EDYt_Dsam)@ zFS`92&6xoDWljE;|P&X%F*})^Kq9FYY1-c#JWKObpix~fAk=5t>GU(D80k@ zGdRhsVXdfNk?cn;n4DzswarfU7GA@Kid#wIuS8*0TbbE7*#=XApxRIqy)wx+;eZc% z$mm(>V9@DaHZne5QoU&93vn>&Qn*c`J6VIRPY+#2nbY5AiuyYH@QKR+A#(k>2NFg}&(1P?8^xLDq zjdiTa-Y-*myJzp@NKGWjTcxlD%NzI1QkT^$XQrOI3P9-d-78F-I%T`zLik^6Oc0A zix@6Uu&@~{7B*G;E623C!e%~8ZU5k7YBu~MG;uKJzfj&BA5o)=l(1Eh6$j@%(Cx7n zIcVBMc0IDZ+FBk2{%YPXXi2JPHE#%|$|&gSfFZqO4Y#{bKCI?HeruxftAKCU-!#4i zuaW&m#o_hn6c-piAymhLp+_+YJz6gsK9u~f*8A%A7xu0qS0(z>c%7Y=g}(2%$x<* zr80D%pqZix!wqudoZHCRH|1FV^P>00A%c!+>hYOP^aL!eAqynr@RJbk951%0wfE|` zLAIQPNK$}48HRIKe=uu0m#aEeSTkVoj={E97=cx@P8X}dmBN50VxU?|EBRQi{D)4z$($BpzGzt zxovMMKQX@A?h#t@p0FahmO)o-XKCHr5rR2?xAWDnHmkZH7!!bhs2jF@)8ZwMYrq}1 z-q>K|y{Zyt`yu3Z!O(2zhI~xg${mc&wYrSk!1A%;TYi}D!~>9HxYbcEPnZl@y`&#^ z_asK5jx)<>nNB+KTtZ3`(UCZR0<+Pf6OXNBWb__-=+~K4sf^9{Ia*5e6Tfk z>im+4hg*>$wd4I)y@%MTZsw+R8#zx7T=&oR_Jykf&Q_&qAp znG>#fQ1m^zkJ>&TFjcMId?iBS$Ca4!Dn0lzKPk{A(wQn~^~x1}N$8Nl`D3uRAgiKQ zTF90~&=Wx#BoPAwqbh??v)2NF@o4W(Bt%2-fI+CxP;6frkmnoa6JOM?&VRqRj8+u< zdaA9O*OL+mPRYX8iC?9Yoc7if4V;c%35%LY>lgG?bZ|0iDs`x3ClbA29C^iT$B zfeI7!NfRR%|7Cg@++9-0DyaJ5%l)6F%rtohKBt;km-S-zz)GJ@5?!?P#xf%E zaCZ*JXNv=R?l}RRxzd7IT|BBZU7Xmq<$n{df-7VXM8>Aalb6)2tmC$dq>wAOo76#%wGKd#}n z(l}8}X_fd5WrRCICBGu)m~|1${rWxUr2UhciLZg!)=3Uya3qg?^o#a`N7;*X67qXr zTAULSf!V(^xHgQH@Hb0OY`yzXULBmC4&<|vdt8SGJj~VV>Y_OeJ{>Rkz>(>+<7HZqG z>0RK1p2i7B$8|Gv8HLJy#CR>`NI=cyc?)IW^&mqD6zYyHOE!_F$<+Y$SC1<{KMhAB!%& zeF%k$Ikx4`IyGjxsnxA*X;ELob->^)L{VfLLUUu142YNT=9ICMI4zM6>*ohzhf3w2 zh9%yydcmxdRdT?H#io#8so?xFR4P2a{%$X;SVAvp8CHH*#)YEa0q0~V?n=4Teeq=zxJKGPDWv@MPbV%R!&hMn29&#~whNkl;dYDHeQE$O)<#f8HEr)(6SrsXAVeGq~t>0|OW|G$eYb)siFY+nE zJVs$LXU~o@LyDu7+M_~va<~-asQ{-*%9Ph?*Q+UcyEST?r@ZtP5NdcDY+DWQTuOB} z6|c9wrRyVZ7b2Ek`uudg@s9w16<5_h!zNijeIAc;QmRBx+Y0ccp-Fq2M7J|+EF!%9 z9qNIi(fRuGIeuMJG*mEY3$PrA_dl_fe_ckooZFIOjN)(lxpXs~?)>KnRQK?O@rR2j z0ed1o)U7^`FBMOYj<0TYmj&gZX+A)QpSluzAC<`wFx5kf&WdqrQ9G_ zgen~>ZVp>`STjFed%gFXwn%tHS{{}TbO2db zaA~?PF?=UpHe0?iUhkz9DLK4;I^gCKO&)9iTXGaf3;J~BaiGE-Bqnt z+&9J>OBA9U#d>e)*1}`3q6p4DOzFPOqp3oQQlE@OD?2;@NXr!Wt9D5FTZic-EeF8J z8HY{sj~z70KUFyB!ns5MsD1mK;%+*TuX1lC%|%ymq_9v(=S$w3+#TO0+NAQv#-{O! zxXKukG>)uF<@+5SA(pS>SHb85fB~sT_^@%r2w;BW+?K24p_WpvkjpJEq;ALww!&4k z2vcZqiJzN+;RKft;o1%_WphE%E>fP3xD|G<4JiI3v~VjgoM8FpSqu4-^=E#n1OqdVCw8JyUhiJ)9*530e_1vce<~=U0Ii6!yz74p@5IeThi>pXlNky??<141yBL zY-$OXx&Fa6$Q*Fb&++lnU-x~{Bh`xT$V_g;|8w}x-kx>V!~lZli9}n7Intq;Go^a) z$QGtyD9_AaE&50j8j>Fx4y~b3;lFuk~BD<5lFP{1_T!yMZ z!SKv64JHJT0y$oIB7i8Uz;2Sxk|h_TxU>uSN=!a!Y|)KJyrK~!3QI||hC1jgePCPP z=jk2036d*a*OtE$#=Zfo885KJ2cJSANR-_`UBeey$8c#*zV@_l(z;-UyuQXdd8w7} zpfgm2=#%A;hhfTpnI;p1x7RO&^59{J}JMQ164M6FNsH%q+yen{T4c*2MQ_f& zw`GU4b)LMpILp2=a;;j+1eYh@~jm6!cA>(0cvggr!CEV9LgjhC$vMZ#shce98y)MFt zJIf^fbgw@qBE0`M```8gXaAA$GfwDyX9Z}f4htDNe=5;Sf?zNuKj}U!-Blnd#?Bu{ zE*g`z-%D{hBh6#hQ3uEH7FXaDGvQG+q=SOCXHEd1m|INBfS6#5~sNg4srOi8Z0#gEI*XisWb%^dMv&rN5?$k0v zd9W|XwL^o1Iz(_IMEr90Y>Z;{H--KiV-^wfXNJ@vD4dNqje_h&O`4nh)%P5OZLdan z3w}}SXP|yfq-rcUlom>!<5BbdJ&&qErR&va%$WA-Yj3B(RPy1Xf6vP!tKk&X2jb3l zK3;!$UCirkO^`sin7KcQxo2`<5_GtZP1G)LJbtgOjJE~yE5 zHW(c^E^pLuWC-3oZ~5J{m+;e3MW_)=+xPl3sFRQWi}KHP*boab%bQM`=Wh%@29IzG z$U9~V&EJYDn(Z?E+^yP`@*aQbCfv6*i^BI>CpD)C1%*@+v+;bM%cooQbGa)~`WuAj zqNP8uFsdGG@`tk3`i(lh%lBK6ns7|#@6VO%9NHDFtU!ixh+XsCL!preW?S`!$CVEE zEI_#Yp07yY|AfPsUq}rFa9#9NJ&3Tk_2un^8#LV#&O@63LNaLumu(yJLaJlPb=_(_ zy3(XHp$fJ74Gdlk3v!<>Jxs4wU2wd8C~WYfiz{za$IuiEy3hLOajWrMFLCFb;zpsD zUERqP6k(Hl4nCb3XDk|$p?aUYs+Pl_31u#H)eOA%qb^8EA1Wr8M>4YF~)=cH;PVm z4?1d3Dr{Dy5fD~}0WT}cm^FvLcXIe{IOb4}S&~#l=0^bRryc{(4ZhW|ymR7mp>g#`&UgTlnMD_Ufusre%w;&1r z6ivMZ^rW+@TsntaCSOzG+LlnfUsOB;^ZCT1*k_ij3ikONr6RCLAcD?oM79OI zgUpVyl8rmIq{l9i{~o!%!x(JwSb`Bsx6+9**Jcx_B`ELo2jinY{IK1raEJN(idzBN zfQ+R$q5J}88XLLQ4d(eg@c7@%AWtys<|txRg-n;bGSr4vst=={a*w@`?gxA0Lw7fNs+63sPuQC~iSb7i#IX3)8{_EnM|Vuy^}1`+ik(pQX!Kh{`5$Rz zt^Og6>!;`y1DGxfiKR$f%|mRwJ{~Vu%50%W&^{V01F1aO~YrlMK zvsB(q#x(o1{jkvcC?OkVYpQa_i=q_E;#8w$MeCbV6T`uAlc&DsE&H(AH9n0u&e z08J}9VBC{WPIYradxP`;5arnVT+B?s(xvCb*w?pS-k$#@lwG*iXA9l`lXa@G0D3mQWSB|gls8r?;90%->X%a3%#j+)+2qJG5ln=sobg*>C zP70cbT~}w?d}OzWR~;wZX8BdLqM=JEe9_T}+VhF|-P!PsZUo^1xh$X?3W#~6Fr zDj{Sm$VWuj8| zyv+5N!0-Bp87I@iv`2Xq+j{SstWTW%t!fm11?+>I3ve41BNdvn7XwO8C~}<#x%H`) zh7y7XPT96;izY74pW}``e9?WN3{zYncGQWJ))f_O8*k z48`oEG?e`eIBp)j0R14 z<>z&YRhpWCjF+z3{C*BJ!kO;bLkW2n zik^Dc&kBn+d85O0V9$;0I7WNI*>Ai~xPV34_fKrLQSprcR(KmKPi|bYe60Q|*p?|< z;K$t{@Oz_QY*P%kv8#^%J+FQlN|CNhXY{x44=sJU1vxzZw^6j*nTv~lj`PzC=3g?- z!CWzH7mvik#cV$=y55{+d}tHa`22jxTK=^0`Yyw7P&x=~=ld5u^L}N>{CPw98idjh z6w39pl}wTR_3z4~B>g?I{-&JLp&#ZM{zg*-OPvcw^fm5lclFKprg+|b%WZ>Xj8V6@ zeEr)@xNFQ1?XmdQ-MifJP$^znNN5C+5>ucwdzI<@8AQ z!bZ=Vo3g>92%ND@N>6LU!bxe9{5aj8iYY(=y57E9yiW}^#m1bLtlWD&C&Z)|x5taa z($%{)D=0nlb2uJ+`QxU{eCgf~=ig8xTu=6iM6#Kk8zmRzH(tu&E85EO-nMM|`2Lup z3I&Ym$yavmRuHN*ZLuM!jo;w`CFAwgl9CrYbyTSldt4bZ2EB(r4w}-|(9ZXM?Qq4l zevLgY5zS)UeX7x@x>(y(75!6qy#17(LsSb{C`|~)gpw6Gf`QIN-tRDKly6;IyU8BZ z*aasRvq*`$;#~@MuV-U>M4q*vsjj~wOb=#B)r1Un>VI`|xcH%6Lsu7nwIH)TTa@Lv z5QuebdYWOezjOwmRR55pKfj-h8=z9ym^&*6k6J^^aCm6nwa5UrHg)eVvWknSlUXQ2C)gSn&hXi;NS~ zsy-Mycg;siQD{gjM)0;|-1(e_5r3PH_GBu0u4u-%tPJD_sJ9le+on(UFQqU} zgJwRuW)ud0zxWNxFfD~0sXvF+c07!FmxZH}yV(PS&il_HGg0)KJ)XV?VST_3`FZvD z=6Cywr8x8X;)=8}mWUIM!Q$$P9ogk@vDR2p5;khSm@m{l6zhmVvQ)@|Lnm&2RPXW& zg>yk+Cav~&nJ3!gk{ZV+Z&J{)nf>3{^U($jlilE@rN>FY34vSaRluBMBVUo?=P@4z z_a^cOkLzaq3QwdemaauWrvDxNSaC^C*oc?p)2HP;fZX>MU~ryk^gIKE95bF*eh!$9 z6%S57mY+expcbW*8yKX0y;N!cpR$tjn*%v+3TZ!Qe%Lxk;%;{bS7ck1R8&wTv_zdp z!#23I3slkS_uy+i>JIpflXwJMI%KKR~1N(MX4Bb^MPH8F>_X@K1@6Loe zbYX@C0zx;&gk89EV**~Q4X3+#7!_Ws@PC!8YH<+xEXnYl>Tlzk)1;6+#eK3n;}a^Y zjx&lix3y}1=aNQ)%7mXUE>n51uZmS?oCr|hIoohwy}d2vy&F^>trPFeCruje{ZOzYJuUI>S9i+<^Ked~F69{l-b5VZ&#^tS>XUjvt z^65$40qM0?nk^5|#nzm!ke7>pD74PmL`k+mUyCwI6q7%_De-pwfIA`Ih?>4wGiH0% zr!dKN*7yqf6@0Pt5}i`Qix>GL-1LCMf#L&;Lb%yUbD0_=n10?S{y|ky@=f%o?`(Ph zR&{@=LA=}4U#@(7)p{*f2+JM+!&+72GsLDy1%h#hW4s$_G z?~PsPlSmoC(u42B*j@W5X6x$7B<(Gn_4VaICOl4OkK(3puk1Tz(Rdq|HnPpzW%o=K>C@QFT2gg79CVb?nz#(4}K?Ii{j5f{+2%d`702{eG6c=+j(du1s z_Rd**(4DLN{CZECQi`3?nsNR}nSTe@BgNuO59p-xf11d(Pdnxs*@)d^WB&~|H~B=V z%eY%K*mPq=P0!x4Fl3P-_vwrwtk8%Os0LrF%o|eP8Qr0gJ&(38YFZHv@XYsAyAWmO zr_O3htChWPqiS^7uZ=4V7u5go;9f=@`Z}@g{<`to(DOhI=vUg~WPv?g|yhtBBITyUaQieQ24b`LRz1{@A$kU{Dr1Vf&iQW~dw> zQ8Zh`4=bvgBEQCp*{+o=CKdNtvDuR1M1ILRbF_cAxGPx<)UGR@53B|R0_|yCBVpnJ88S6}@0SQ| zOWecWY%t=X)u`lpns%|pZL71MDu1g`K->W@>ehHq@Kj#tNeZILA2wWdCdPuSf5P^e z;$ik2g~eYhTN`ig)4jB5PXj6H40dHy2dCCewzo@pymbGi!T5~5}`o72b1;b zA5nJ-I)yUq7TS!;R?kS)_ad=DmKp8O#`+wlS`HXCO`6cV{CJOM1lp846uK8BFON1V8l6X+`>78(9bR zZaP$jKPW{-Yl@QLETM5H^hush^Wk@^oiah1{&WJn6>!j%tED2Zh#{&o(+Dq{n}?=f zyaJVZPNFn2W}~8E{Q1o2Gkcu#etB7uGY8|@PDynxci|FK!c+P7_qUebQ$2XuP`_gO zu(_#b{oqEK&fo?_rnKU-w{=fTX7e4AT%5S{m-m4~YD5n_*xCk$Lj30Kj#ZKVEc`-3 zF50vEk@FWH!mK6~9?>4=hi`;HN{6@K#9*`E{nq-Ww&a;$oAnrJG%4TzV38r@3|2ck zAnP7jSNQbyZqla6;@g92>2+Q6;w4{=7nhJ4@d+)i^L1-&(4D7?9;d`epqS%7ZUV5aSNdSrfBt^pj)d*j;!5V ze;(z5yLaR-MagelY6Q+4g_`kdLOZ;(_l(Is9#&PL!7BQ2J=;rs?{yaYJgLJ6cf{kh z%Scd7y3^tL_ORyYw`u;+PQc<^*fkbsXyMYcBCtW{cR!x!`X zbzoFcd`l$OP@ORIz|*3%Cun;sxCQe?)l$1w?NBM@5-rqqHh{^jB9!fSucgMHDzq_G z9$0#N)Wr|8ZPKAZ5y0_5_`G9aD|-IQ^g^6&vUH$OEIR*YrLT-#`@-ETB~My1-aYGj zbW7DZJgv6$bTeA`d-kj~OY#d}oy4E9oPBnldJYQuM$&$mH}@Cqz&a(vJ(?zg&HG34DGp(?!SF&Y%ZLL{mBu*}6enj;ZqU30F+l1;M5r zb(4YWr8rJF>di{5pTqXTAKL}R+XJZa_#PJ6e0DT8`Ogyp)mU3s^E@yysaYk_76;Bl zw+3Kl*lU6NJ;N_gHBiS@-Tm%`4v%I`sgM1S*y4;OR_aPtS@tD_9Y%_^M+&40&TPJU zlnIACH^<~};EyAG!?-BI99LJpg3M1edeBzm=%I)p#$vKoh-A`P@1 zmGZ!YtLcTvJ|+W|_xc^+E_YFxj>kYGHAuHq$TB>P&gqRnSbpb>%*@o zy-x;h`+`q3mDSPekQi!S-BAYfmup9Ox5`DTJn(>0 zSCZe=*3R%-l2M+U=Jnq(V(x`0o}i}i)zIcn0+N?4aKH{fnZ+U%ok-OLVKjFm;OTUN zz4nk$V`=;DsjR@dIIiZuq0AJE`i*cvyqU3>;cwl-hS-Z~kr7L9Dg3c!!)%-Ha|K{W zIPU%p9nhzboh8nhk#)3k?`y`)o`DB`B$;LVC3fVe>=i%uwdI$aboplL8#ZT~@_@Z+ ze0*hJ&h1}FBv!utXtMilyfU`}NBOF&cg!y&q!pU5Sx@>VO|vN1!Oa>IWJ?N)rXJ2~ z=O*Xj``z30?kaYT*x#^%TwhTbGs*+s8>CYp-qj@ce6S)4(J!&uG9}*3t`x3Wu zj!mY?p(Dcd1JQ?V<~o*xfue=59M(tCvBFljP0yfDhq_@u9tTA6>h8iaA)d&2$=eMu z`oj!^TGTp$gU`;xeiFJ%t&L-}y&4O*Nm`(xmFM7qDibn7S)WTm?nQcVvje*%2P&PR zmJLctkgI@xY&*aHWY>)c=%Tnh-zNsksop%F8DPW7>gV{8vVxQcp3$)hElKp8iGQzQ zPOd=1pa`wlbm8mb{NO#Y(WIeQc0nuX5e4NYkw5fzmv#;8nuepcqZor2YdDi8ql>} zs#u&0*7}3M6Ei6!ezAMNgz%w0lR;FUDYa=`MfxfGp&n2U#CGEKZE^Kb-Oww^-L=29 zIG8c1?hzXKPd9dXk|09{x+C4;4yI>_KU?)A2-IbqiZf53mXF}+@GisIow*Ly@;H)` zelPiUtl}&tUz08#$V62Y*mP~iW^H2ltt1WN>79iOv%&rU?lLrvAl$Oo692jqCI>Zw z+L=w;#JN98{F!XOz19TF$si6)8`wH>T5^(06Cw&7f0xURh>XtWZ2t2pV^{(fqGbJ-w-i&99Y zd=!R?+@n<~A@?&GJJuMF;Nzg@Z~B z8&GC`;3&{6F&Vzq_b~O??}2gN6UW%!cfpGYu-*wl{Nc#zeF5pKMeC)?_<#qpuIX7> z54XSN><#JsLebrKH|PvkG#urwEN8OP0c%N!h(92;y5EV!Tg;PeE+M;?OaTK_@%v^; zVxPTl-D}Y40uIFVK4LPxWh$Z@ucdVmn_wBJioT$A9>P z+`2hFH2%p`Xlk#bXPebWDdv#1tNqovlIjKYGJBcV$-_v=)EAPTxU7dNqJ7_JW8n)p z??r!cq#oAPd~fkK?z|l`2mG9)t|6|U87|x;>?B;WUt3stlp-Id{7`B^gTgr6T{uL? zO^ofb*(;8%nuM*c6Lo94v{@*6Z|6rI-o5rWTF3_cAr4zC;8x(~X0;}yuQ03$Q60W& z#}zB~*qDq6PENaWJTRb3f(skA!>@oY*#!n1tn*nzE3PFM^ICq9&hNCj6>pE|>=;Vk zOvk}x>~4R#wXtBGmd1;xTcnX_TJm-`%?dIh3iL_gDyyaC4_uDV|pL4a{o3PN+(hC zCmVNzCxh<8qfB8-VI{j8p_s08NOGD$k9-d67hPo1IxyW0+9OdJTPsUSyYr32WzeHs zSs>gZsDAypK=v-bs8o9DHqIah=sJ!XwP+jj<Z9G z$>gyQ+j%VQ@WgwTUiSgd$J&c-9cG2A?P9pQ-m_82X$OX-NV+XV5HE<^|jq%w2NExrMghHIBqGe``xeW7y@-KY_-zf-I?K)oZH+ZsI&w=_7S-N@& zq}2ielHb?CfLM686Y%0XHK-uCHnskm`I^RzV=9LU@q|UNb47~oP0vrhK5c=ZeACw! zk)zik98d5hwfzvdyZSID`o=jh4M|m)txp9ZRzcD5`XbO!jdgVa%#+;lbDGhyk;55(m!xGeG9Ha+HY zUZjqx#z;vTBtj&u1mfu@IU&~}=cflJaisHiL;NyDj{rJl`U8b{n>IA@rzl+?DdTS3 z(*&D7>z(Nc4AkdRZ(G)pVe;h)ku6?9`aGVUr@=z}NC`xRj9N=*>8bfngg++!H07x> z2cANx0bv8mJenR? z;f%~%X=vHtKZg}7%+EWMl9;ta6Ja;?)gd;KTwCF%ID~m`A$HRpIW1=snW?Hdp=93e zq*RL~R8@P#ro--IZ)2Fl&uP;AI!?S+A@r51hKiWtUDe6Mb**Reae?*UB|y1w7)dd_EF zE2M`|#Jh|+^V?EULX5*DmLTlpY?S~SW6D->=U{>>5xHK7@quQif9Y3m6G3BCYNZKJ zjG&fK-XS~9^@|ipN@V!{45sZQEcD4=sF;VQoW?F4 z0|kx@C=v!FiYAG?j)1|;f(M1~XDj9Y1@3W64yTpIM|tJOpL0CNEjX6jrZeUzsF!>= z2y#GD*qd0SPW*zBFT@}FK%`45p+fW>X*VnYb4Ckd>?9~Dx=0hm*((WjX*=n3F9?#R zwL*#42>Og%GKfSa(>`P-iFKC+t`&A&Py%Yv%He?FuuIl%LqS-unW6o-MEh1hY{T4T z=Tg$OH*NBWxYCyzQFJh%s2d&9A}KB5OpfHOl|(+YS>YyD#&7d~4y`v=DU>l_6*XY= zll=SWkO#%Wu*nYsJ-ee%5!MJA>@;0~?nty*c#%fiB^?Dpb`TV&C7TD{k-pvVlojJx zln}@fCyCDp7CbNWgZR55m6zHWB(LB9B{5QIPX?%z$v+>dPh!c_q9O(0Tk)FtJv3K1X#0&)JG^N1AYK{a4QGmSwa9VJMYcTpnR9}fa^rNCl@LS{TXQzdc{%Z7q# z5*+e>$JE*z+uhCAKS{Ru?7BHq7cB9Ip^~It;zdw2)sq7+^|)!zfymlf zHY{W4C!}5lr~G{8jiq!7MsY>)1q|A524ni#-XQEyftj&%Cs6~(g!nV>o$E#t=wLJs zuk|+_vrng=IY*)Y!!M2){#1Q&4UV6iHU)}pY{Xuz~RPCTLsKrY=6E)%64ak3JF;W3_!Yw z@1bnR3_k$WX1)ZANDpDdNkcS93L=LRD)I9h6!IPh6*rah*n6d06a8A3h%$-tVaY#k z^M@fAd;rX*I)_)sKDX{*0n@depUo6vi%~E8sBrtDO{pSm--7G>H&J*znzRO}89}pFu+aBa(Y`5s>Reakd_JqO4IL|CUFcWw> zv~uNua^Y`1DK|I!Hy%aqV0x9nIgVVYt0}qi$r1;NPeIhIHQE=)50fTnIK;qTXeTgl z9hW+22=>aW{{-d3qp9W-Zrmf%mM$!3!b{^k`vGShE+SQrqVW9=5=@W`+SVS@GR;Ol zE=91OhfTyIKwI5nl-vTlJUqt_*ILfKOwYw5fKEgOcu96)+k~T?Xi{wE1 zPG7eD(E-jU!RP&Qb9Q-n({I-XzFDMg(>M;ck(xHaf?Gagbyz*m`RM!CFty3s@oX=U zNe4nZFh}TUXGglZCxt{FTK3Kdaww&OK8Eu%^GLKNT`c_4Y2o1ae>rAevn7ux8uc$) zAc%uXpgVWsFPIMno+X((#>(v?42+nVzi0DMalI)CrAJVeqJ~H^gH0pqXi6H*Mv$Sk zB8SRT>pY}$B+60?ZDT6pDc_Qo^e$Cj3NS_)#2^LRfM(CP{RX6PX!fK zuf!4WB#fOlX2h+g!&|yh>XQw9-Bv5Z*euy?H*UJ6iF?z^hhEf;hLJf*rrT&Zt zzV(B^WzOfcZ&?MIhIe^JC@>~NdoWe?sSE%@PQnvyGvOrjIG^`Yf*^3leqv5o@U(Z! z_v8n>_7Lb2!p2zIPXYb4kN0IfhS{kQ-0d(EucMhx+Xf|OS+YYsYk7VOfOwfX@Z#fI z5SDdf>Cs<^>jHa0K!@@voQDGVFZ}`OPMoX(3=EC$t@*9>o|7)CH7ooJ?Fco>nR(O7 z|A49Oe)>cllP67@j{onk^vX|OttS@*>q=HfcUeOPlT}9Q9CKEY~_tfD1=xCz2ExE*FP;`td$6bC2PI8Z^%V$z&weRE$sUBbwONjgc4OhNqMg$x5bT%u_x7o2XIh|G5f^o8zV(aMjmB0EB+^Qvm<{PD_by4Nrk@$QAbg^YJ6?X;~tp zuuv=5EXVUso8*QGtn3n-;$2{bG_&mKFLII;Fk{*el6Lran9Ma_>V_K?5j0Bp3L%|K z*F_%%?`$#IM5D%P8YofuUI33j-#{<_z?pZ|*& zmofJEg+=wFd_IAYKb2f(cC5JUp#3r1rPT7KV?Dq@$!GKfIqOQ#SyEZ~CoZ-C%O=H9 zWW;yf(bvKp-U_zSiMx(2(jOj<3ch_t?{{@{FRG3C!c9we&BHUmzmLP)1UXsEi*hr} zkdD?K_I&oV> zvrCgS)wfFbfoLBkcUzFtFTGv$|1oIcsyhCcjxh=VGM|Ezao+wSDZl|(aNN+M)fs?L z?@bYnP5lAb;OzOlwkaSFHUk#<*f)sk2k*DE5MqDr;&l2UPV+m}t`ku^=I@#S|Gu_Y zf2t?kcqX|@do(^VE6hV1fzeGCfJ0t*Q3Wui?fg~M+F^a^#(cm{;$q^9Z>G1d0zIka zG>lx(m8g!l_rIP0Wznjqme;Xb-dxtstRw;5X#TSxy)ser0C6)>oy1051txK`u7`zD z(b6RA2~-2q$d~uxc@-}FYLj&xmy@iUPd=yYOQ^l<8gjIdwg((qCN>dHCmuAv{yQq} z?b6{~0!xE0;@Q^)vdy;~e}!!4P#6XnEMB!TS?76AV7@fu?3B`({vi&UamktE*mpo- z=_fFoT#R%P$4vYKl=Ad@1)4FKmYk5&I#csI?2ox*aaW(oJzXas?v31TuP&T6RB9zv zcHU`y`1E2<@UauY7Qq#|_P3xT-2L`@t6N~?>}2Y!_;z!!t*TKsu-v3J3tTE%X`ZW* z811{`nGP#?sCTGr!}gN{*=ndJDsa2*=RVPN@iS)ouN2D+2=jgq{=G)^^yO6>9tNe1 ziZyXhgq6VI!m7ZIP!MnWrz!OanyUiQhXGCA8*jfDPYnal7w(UHiL~Cv%@T^hX_mom-y!Gz^%@AKwu;J zZ0*`^R2MyVoeQ+Q^j2l$qKe#zArhZoMwG1b!RXaRB zur7;u^)=x`eRfJglXdB!L5v4-)&JkFc=Q*({Kz9ZKKqydA>cRsO}|tLQ$YvR9v#C( zq7D|U_;7`dbVUM+08{ADHBeVr3C{BfhIRf1yzS_hDk8x1E5M!$ap2(j4U9|UCJB|4 zLS1w|k2{yE1pU4W`P|N;#ybwvq#KCtz(N%`f2%67VRsSZP?0^@^j)|; zAppDSB-%!4N4-|4il-+bK~&w?Cgd@11XO+EFw=hJ%&#yHjTGC_l~jln5gLPPE-TYz-AAyRoa zUaDH+e|rHwY1qbIhg{;?(I|p2KfC2thnnv4-45wGS7{eU%>l8+C0^;`wqsZ>Od!!h z?=P}-knQhjD+Wd=bSU3By&#Glf*|@MU8~1L`eiNU`mZkPNh}}J?@0&o+CN3Ew1jA`58o&pyVWLh()gKZ6jET*|^nF+k0zA>MU9YR#}8yN zb;h2Dh?&#elfQ1SP%QMaN6p1MSDZKpLG(EGkvZ&0aN+d*%5zLdf~Ep_jAKz;>g0P2;&W`KE_EXF4C+MS+>Q83Vi}jT zKo$rX;1g)}E%N#`v$|;Xkm)32V7xCb%%KW5sCQu&BFqJkd6A!pR-Zzo??$p8?N;ZM zzM5mBxTPbiAn?*4>zwH+@==`n`^!OEugkFek4e$$C&LYw9SJ7_XR<4|+a zo|H@a5`g9!4l$eV&z+V4FuJ;noh9NZjt8Hf8bUA_xmgs_`3P>l#;+C}Serutg)!_r zn{wxuxoZQdew(t7WDBLHu7MqZcjDVr@EG<3?md~Z$|;OAR37??pxF`dNHJZT#7EMF zSOWf@#zicZ;j*YgYFowrWdJi_0=uh1k77t+MWM0Lzmry9*DXGq;R4Gp`YZl&I1WA8 z7w~8%sPO7fUr~v>XrKHrWQJt39!9+u6BKiRFtZ@{XeypxlLBt}B^KO<~w+b@JMzdk7JsI-j|G?ZAE(YghToXJ|63_W; zJ-9V*i})IrYDnU0({u~-s(ch5L6IjAW6p-cL&oWT?jSvUn46TOM6>c$(^>V^$w3 z+aU#a$J3S3(zPd1ex?bSWJ)w4p&sr?Kc|7JOhVWuMQg0sP6Q z=miPKWn6ZB84HJCpk|imFsK&hHwJuA>v7h~Mdfh~zGYsa<)fBY@;k9cjP!175UBxp z&&70gGrF`EO3Il*IEssPg{BG@S&3)U7_IwjY4xhy=dpAa^qG6DcW@!gEOY%T zQR0yIbcS}nYB^hId{`nq2^Jj{tVGowfDi**<3x08=1VIGXWjMBYN zW~pjj+9N|ojletO@L`Q%01*rCJTV5IW?lo;4?sEF6&ngfP-%a?4u~K-9sw-&QXB^Y z3N?hl#8+!sW`|Gef0&kd)h|_}C zr+H(JxVRW}B=hhb1C|lq2o5$l%8Z@%TF-@&aX?1D2mXVK;te#gostYGRz87JmF@}VNIcqZlWCf&4G$#<=A&;k9M{X8O z$59Avzcor{t&Pn?t79NLap3`=B|3ced-2I@lihJV3JUi`xsn1?D|;nL@agtT_tb*g zm^$Cj`+qg$qCdb(06W2a%8Yf#GWGl?i*)(~EH2sc#Qv_SWQZVxR|gajjTLo_f7gaE{=iu3W#VO+sIQgs(@V|~!mPK{pXu8khqhNvTk4Q=6H3WK;h!Iv zuEH)7;uC2>vvCya%}_#5NXt82w-1-TD4-xSVZV}dDCH^a2S2D1xi2sbLs>!1yJn@~^YR0BsS3?Y~>DoHbZNPwq#h&md616(K-CLg}C!qV^N1jdH)b>DTmK9x*|puZ5UxMLPgu=_cYAR7%f+ zoT~;EGrfU~f?m+^sWhM?@y&B769|d7s64v#yi|=r$+Sn2j8zu^p^yPN-AXIKxK7o> zj}%QL;2DUlrg1O{jDW{gRYq_IAS20{ogwYtMpST;l$R2DLNCuKl9Zy^+PG!GqBwxx z!D!Laj%d}kSPwcn84E^{5W!AbQIMBr)i^Cs$-pRb*{Y9YQeY#vg{sVToE<5be2=3O6jhGW5 zu0;`)2z*@;y!@C;TvV2@U3OzeTbfo#W)Cdv7DzVCulwZD4pnIj=l0;Fx(?9#@isC5 za9=7TCG>0K*@)EZ<{fNAN-(}7vh=(BY*0%e7O#PiL#>|bZ8U}5qLPjAYx4xDNA7o5 zq1RD|9QA$z{7ztF7TlNv@bkS=h#C1_snA9+4*({Ofp(WSR-X;zKXt;+AuMFc z&n?p;zjlMOi3T=Xj!QAP$ZuXm-bq>vSkHWDO`R)G1%vsk@Eg!&UY4bFc@NJ6>t5@v zG#LoL7s*gOIU?pLK>y9^9}RQi@nIRQzQEZ{{}qE}mSR5L_1fEt+t-~A*@rlEA?fx_Sn z*HS_hY)ZbGuv_xX>msgD_|QM+t>uD*xC4^3d*9@w3=N*H?Xn%jxXz;G5aEr+Tlz?!` z{jb=eM;H~StFnoM1yH_H;Hr3C#h_x(Hl{lCAC&=lJV*V*(rchE0+O9nHA^w@GoaN zINuN2d-wLc>JWXO2$8$6BjiVl!7rg8Ma|r@$T21p|hqZ z14^3p+gi(O2L)G0GK@E@SoG2?#jgI=yxe&u*J#AM`4 z%D1E2!Kus>+KRsA`33{a?qPBxIr#<+`czSRFUpgi+_LZ|y!UboaaxgcI=Yh|Ynb-L z%w>@>2IJCPx4RoVB$}h^n1gn0j3IvVm_fvxUbA?O%nEoTw`;oG);eSoE9yEa#?GPW z`pnDn!E#*;e4e`%QrIe9?syRJNoKjAcPQan!P#$o+mTP_SPX-Gs$_vZ%M<>io3nAt zZ?%U)^oDC0n~eSUt}ZW(Csxw3jg z92w)Gwmk1y;Mgsk|L4i)q2}BArdq4H)uXE*7`%__*iiFL{E^4BeF6`V%bhCce}*_Wj;FG~gO*Ln3( zEE|R-Tf9qk;}d>oiE?*$X-L~0GIPrId&G*e@JSrlK)Q~ehg~h>Lt1%R2wum&l2)+t zKNE85Q%R{v?c_+keAwWnJBY{E9)2L^s|MX1;*W2bTOsz~{vantEHM|WiK3zHpZfBL zGxU7oQ_Jc!&jq<|hd?ep>{rYATHq+imN|SQ?=|P%pT=vm>(TiX`+uk)_;TK+cl zeFSC4=vu!V-ys%;Nsa8=tI>P0t`9l$nbL3IP49n<%j-BdA%g4e)fTa9)oRcykJsPS zOOvxcP&=QcglOe@{_E5F(A`yiTCW~{Lp6`kx)3_wkTQ_;OhS0?r=a>N` z4qOq%Y)@eG0`qvF&+;20ex$bY!8V_8^Bw2qwUCc4 zC)(uEJ;d@m?UXsF*Z!)ANv*uj)*y~KD_-N>2LVyLiW$Tlj-*VAOiap^i zV?7ea_NI%~_w)C)uN4%fCKAea<851f@6s7*&v)0m#)n@v2I74WWjQOLZJ! z^fo|v=d5uqiz=~JWKba)s;Vv_m9$+dJ2_fuScZj5gu_ru?iDX6mEt>$NV{%ad&}2~ zfkE4?-2x%J$&N2;eoA=pd81nQ2br0F9kv*7{5r*sYS%a69{%Ie(}h(0cOi2e47a|$ zS-o<6vAS(R(M99d)ktN*emeSw_6jB1$nUq(tK1tto75;Y@@TnzH@6ioaMREjxjEwb z#&Qh+Vj>PN&|9r%x-2TlEWgaJ>o&{1#zXwksJsqbNYZI==-cZbh6d;{w&#eqfBBT| z_FL&v0VK*KOaguD7jkbyQf1!@emRMQ)AWa>|IbBY?wnCeq&ku@f0cXa%ZmaPWCmLqEijCg zP@ZcjZ%X2CxN*PwXWSqZwXa~|f0{jCwYw4EljQ9z^w1?OF#5}UE^D%V6;R4XLkQnV zc=Fht-}wS>>k_YpZ!!~~`10{eN>65x;3Nd`g^?nk&|1a2-J`UzxeM#JhdiZqsg8vK zJ%}#(`rR4OlQo}2#r5P&pH8FY*FLKps4mO2+Iwh>=uoqE{uf`_jda>tVYJ$rgk;k_ zxCQxAHVGa_n{EVo{agT|NtSLlz+oVU?v>~n1%R0X3S=&4uLSYx zDHBpJp9d5ZU0cO&CvjB0((fARUq}k%vtL!O?j{nhAqHHO>bJUh28Hzk0qw$;r?Zwp z%NVi1i%>RP5DRWsiO3c4hZM36*7UW9xpE`^cl= z*SDgrBt#4{xyCh-8#MMQ2D4@(@5M&a^UM35ymT1@{2nu+E(_`rSd4U(doSm@d^cZd zd#{0+6|DiFpyW6}z{M`@jsxBN^m`%=BJO`M)CLOoqtIcS6x3$0}U z2PNg>8Bvt!`fWcMI(h8$Xu!z)#8n@Ch;kVtIQ{4T;l|R?xGTJ{BV`cf5ZKchNt>I9 z4!f3jCsz1M6fR?+SVDwq`-Yxe-u^2+tXT`CTF0rtxxnup5i@hoC!*_->YJ~GT zNMS=3k|`VB3OXx)28AtcB3M*0!q&w6ZNG_X*Y=~*F*P6 z4XyakVNia+6~+JTt@m3gm? zM|$IIkY6#f9$9d}{DBUi_-!88l$3wrKbPNb{KrjoV=@S658T7E8)ssYtF zMVQL3iuQ1OYI(Yba2G%n3A^&;WorbjVUD3qLQw=Fv5ZCgO4BJYW5WI--v~fs|I<<; z6=CwT8$ie1F?1R}Fw6Vddh^+-j5Q|y@N_m-dYDMZ3JUI5s?f-7wcP??rJ6tk=oMt)$ZvTyQp5`C>#_##ngKrb40IG zfmwMa%!vhHcS)mknwDB3hS#H4Vk%_&w$qMEKAk=Mg056($koKIALx@g$nqpwnum|Jg4c952#5r=afe?+I9o==rJIux(Hdu~$-#m9 znwO>C&SksDKybd0=WH3Jx6T<0J{}qE&et!~Ycqi~BMj+ur6y`V@()@XhpWyeV|$LK zZVo*c)t?GVoBvFxyw>Ik$m;-LqyxXPuBN+MyV3L;#BE>F%cAy22AW`yrAR%?#y~8& zQDTbxYE!rHge|cA zy%9L51~?*GAQCYf#-PY8WqdHnGbVh?(mv<>Lf zd_ffJ%y!p9=Iu6dRNO2~2MoV#59-Fdg@=^VUjw|L|KPsEnt7GZ<%- zBAsWDsK64OLn&*&gdD5?hO!V|$aF!k#Xsj;-el?``?Uw!#bfhf_o1oPV|O!T7HbXD z#YyPO{8jO<&AaYSuyFsOW=B9tqE?64LIMfaGPKappCeQ(%21rJ$kk_TnY?j4pl)EP z3v_UI@qA|5icsjvH1}UFXb&uS&=_#Qd}4Jc^#+a)5GO1k^b!S7q^{?=Xh-@DfRhxNYr zVLmhSnb~{K-p})lO~@&a<;BTJOP?#jW2J^#0XB$@QJl}qfJ^{LC=Vt$({EOlJ6ypYK0*;0v8zP@|58k3{9t>%3kt6l3(=;`q+Ag_l{2FfzV196Uh^f z5CG!9CL(KBepr&hw7hU)a4tvCIwoO7XpeaECIKfSH6$6PG!rDL4nGSyquqP;l8>t{ z2a6~r{ZP#v6TZi^q4YB9+6c>8Sh_SMbo3eK%8&l1A&E#aQVb~t;v6meS~=Y#Ij%>w zG^16aMsRjcZsYDg)+m-Qvb!-Xvs3_}gfV_GnaADy^0ob~^Z{9+Wl!re<5zj9F^!{a z-@8}>8yrBg_z9GCuY!;&ghx{Bf7Lmu0qi@N-=(aw$}0%)I@!=au$Z7>lRn=?YY(C< zUwvN`CdBsmQ#76oxjBR+Xjwx)o0$o%o%l;|u_P8e`nx^-_)BIb3D{W5tAQGaX^9Ez zyJo}?+=y#XMTn4HObBo;K{2g&igK`)pf}^k9USwfYE$}dd%DI;;NVS0Oh1Vv6{LX; zKqRaSkTui(!p3=KI&=b%c49aLI#Md;eCqW4Tn_j5TmP&gj*#HwU`4sqdTKMFPET8 zYpB_GU)+w_mb*|0DOuY0cs7Cyd93ZT!5?nhG#*n77)J%ZWK#Lnz`w!lKR z?#EK6NkUYq?GoZi+Fg@QA+{^W-5wLE6W1arBk%>OYQGCYT^L8mNJW!seHA6Z{Sxt{yiXyy3Ve*IuM z8!~DpzEa0~mnDHiFC0RZ9Up}^(A54((MoY+gLtvtpKVn(K_c3;CT1dtl|=Tnrcu$) zwZhQtVvJ}`CG9p?EgmXQEQW<2N!sMSkB=3i^GE^0zFdb*ikJPIy=41zB8_xq+Q2%- z-9MJ45d#;Ey#y+bf*pT(JVa-B7RB8xm=5_g|NINvi#}fTFC81I(?@SE^2?%f(KN$% zAM46Sx(4;Twv2zYCga%um?))>kq2GE$i|95hng$F3$QF+e2ZjNf*znDn2|W79q&ag zXkUJHGGcs*9L13VU!Y=DWirHEU7r*88iY?3UH8%&bCy&P20H_m*bK)sP*9@~ih)qz zb6eG(^x15>JM>pwR8C*t;)QIGzAUJpS)_U)a`UCbiQxAl@Aph#Q9Bo@3*sVJ!_r}m zlE0{gf3fenURBWUWF{#?XnbSQC_XH@q$z0lM#Yj~)y2{Zhw<^by|*hf+&!5X)g9s+X}&NEAClx9IC-U2ol8wAgi6zj6D#?X|xDow+Sek^sCvRBbhnH&l5=LLJ zITd=gW;-yca>_|#8!!qa$XA#xvE048RO(^)Tlbe<8lnZ^XFqkLe;J-gi_xzn#6Gg3 zNw0ySiEACD8tG}gnjaVMoko~X%G~uzqB)%MVxZ1tNdjwy%!>}n0oIHDHvCdeejf=P%oO07YncVZ z)~Vn}A9`b1NnDg9%ngp8FsCl0LX8yI86ZK}c?2)QbSzF@J1DC|9_qHhzs9S#!(lB@ zHzY&`4+~GhyLpQ+f<@+aImHBf{MWtLStur|yFU^?LX`b%fyOkH4uRcH*tVd*#l@r) zP07o!N22juCK>{dpbFvqQ!?8=7b?#4Y~)1GijC zLLzDAGD2GrPoZ4FKU5z;>GIpt<<9&fyGbceGNi>HRyWedVw4%h6GSAWHc{W-e zpYZZn@q$#Tlog@gsxQ@dKcktUmFFVDs@Lonr2VGL>tp2M!UHdWYYFzjLSRN)W5Rjk z18AfL1s!8yC+YzY6C`99_i$cd{I7Io8jEZfk#KB7f0?Ki^jI;ao03uRo1RpzVBcR?LZw(ni=H*6zvsJ-)bM?zApmzHQbVYWcmV7(bp z*k;33)Dth){X2p*t>5j-cI$ib54#XZ2(voGD^Nyil|%tn>BcTy-J75Np!PA#tBIDzq`p>=hb=3rk5G=S1VF+yqQ9C*;XApaPF$IDN;fzp- zS1e8E69a5f=(AD#mk03f87$M^u&)rA5N8R0Cnr!0YlQzPhTRPjhB-nvB$LoQrJCX8 zA&ByJ)nyC}!W^90>nkU)Q-ky1Z=ctK81G+iO_*R|@{B%uT9vvj>)H{6`A*I#TcVqU z4GM+2?nIJ8U=ad)*J`jz2}(OW<2x{4MDdzVtgttDz%-#;AxBbDI?e&GqZd7hQ`{w7 zeFXPHCNlLm5(H~j*A6L1o*E@nL%e&HL$H5Q9AdYl?IzZ}2I3WsnaRXV?M!vn91&_0 zmx8Zb$+m;zWA-+vYx$tBl2|5cAh$n?hm|C3Y3O`^pSE0)vvoRmRe!;e21V{*$@OcX zq-2Wq^r{;3NeBn(FN1?0LhRh9N>TjwamQ!BKxx2q^;4N(4xxdT&S;8ZIRaMD!YvEg zgc%pC1ZM!&#^NCDtM3&<(UV_yu<@Q+)#6;`e(e}hP$p&sr=-B~>2|o{q3claZjM0Vy)U&FDt2dItHei;?(&Qdz{vA{V zKwAI-egmN-$^sDJZu-V3B#2zrZ_poBVPrEZ4OM@&m&KqN1aC?%6y^CXs3{4HvC;;@W9wIeo1^2rVaOejj z_hfzZNam-96*?|r4Ty3^EMbmvYUu}IUx+9d-kOF(+^4egY8Hyah{_pdd+p+<>fl9o zz3H`0Y;f+7it>5+2}0(-A-$ubfILEHHiF*`vTucNRZ_#sBaWzqO?bG+*3A=jbl>3= z7Ste0bdSyS2;AQTDzO+cmVV(To4gst4XIFP7wdTWP!Wn}Q9>-Q0aS8v6?o&nfs%y5 z03j3BHm1jmA!kY?pH=$CZil#>kJa#cMb&&fT>AN{lk{`aXN!@hnuQYfU*>sO$RlVl zh?DyGMvNpAJVAyCb300rV=QGC94UvMrrMFa@0m7^&V3lb)@&TqR9=~n6DLwJ>(O>L z+%>TW$Uy=XJz0#VE8y~Z-Fo$S z`_i=UZVUiUmjDEz&@2V<6NVbu1JJeP618bbSM zuV2Y5&)#@;!Naizn*NnEqtwlVFG8J4_Xm`@SNeoE2_oT@GI*;NH%z@nFJOoI!|>2*Z`z@@Ii~^5U!W8L(_gxRB&@KxIY(R zq!l362qjY$J6t%nwSoIH*6_)Yj@}R|7v}gNiqwfm!Son(eHB27GrzE*=rZL+ zxa;9r?rXy;#trU-1;8bG)dQ^cV6nknTK7@2wivXwW^f@aX0sqVtlH=me`UMs9aVSS zY-6Yz;DX!-cRlkAo8sJmD;_N{eOL7gW2quYQGm{%33NBe+A#DWbJ85WEWa?1@&LK` zWm&*XrWg?-*eRL|SBB0X0B|RFt4{$e`y~I z`bPgtk^|&Xs{6z*&t|&52;d5GttSW`PPlaVee7b0!ji<5{Gl3YaOz^JVLrUI^Zm+b z+n|hgRZPVAV{r1+VTcF(HaB?DyZASJ!}^R+I*40=YP##7hP=w=U*zMJWXlXZ8LOH} z_iG{7Q!hYPm0sb-l9AV9qNJ%OxaSSS0C|%b5sH+!2Y;sD0~d2jeb7Z#^!-mxhd1b+ zGndS5WsveM%XEZFbiqCvjO2@dO%)){dj~MuH+f7YU>hK; zu69Q>k`bZ3HBBbw#!B9v|BO2uj`1DIiC&`(2E2SS%R3Y2PAiYxo@^|_mm<|LV@5V5Sv-Ms%kSyWNX!S zzaqfZ&QA5L+o&Au_Yf~d${YP?8`4pvl?RrsImqJK#oVjZ`%oA#r#93iHNfp5-pgcx zO3{!vgiMCOndXa6JtKq=Y7G&>){ORS>*mkHno~0COiVP55L+OuP)fh9`{YZo1Q8lw zFy4Fe^P@HVHT^cahWYZhY=nipW*0Biw#!9`Ch&{`>d?hE&LCCK@V(!|Sl2~h%5#2Y zBvb+{`?I!Lb%lhkRopyM4U7T&mArBWwM!D#o!L-O0~BQ-K9?o%1eKrQS6D$&(g={- zfZYis`7EiP%i6X*qY%KlN574Yi?&K2TJ)HIYj2DdZI0U+ec2(c1S@!_Ou=oPLe4SCr z@jWoJyWG?GH;jN=8VC%$i7%C)xHg;+v61U`$*K8Fdtsp$D#l zJt;ye2dikYctGkk+#WhIA%!6axe>x=?CheH7Z9FQVS|sz zmQXiPk);XrWH4GFhX{n+CM{8@0J>)}@pJkx%i`gWBVy-3qxSafhu|SAQrj2W$Q=IGSwH3Vxa1V$cbY>w za=_7QAHW)FabYtN+Cbe3y3au~@K`MX$_>SYZH2Vut@W(Z{~nP@(2ji5U6-FuE@f!G+=9)}6GwhVS$lFYDv-w&)su(qi^P{OOGi7F2r zeW6Mhc{lVl)Sr~J^Z2?98WxsJJ}CHLTVlgi|0R2M(m=gYQ(r64nl1!YRN#MTMFdX6 z8d&mj^_dd|QJ;dfUKiZnD2b0=v8E>y^XHciM*$e`A*ebI1v5Fc65+b%_1i8oF1GS8x z$U%Z_O`>qGsAEAi>pK3l!Yk|8uk~EyE*x9mvl07gH0XlNu>J+{h#WKv;!`1{NRe1+ zBC}FFJ&gWQvDgm*$eoZEiEc)4L2T$XpwwiZK{&w)4l<5%LoH}XwJ^81a0pPDfEHRx)5RXZ8nrV z5&&g7Kj(?H>p2eT zaU_z`y3PzR_+;3K2yYT`C=;Z}bb>8J(21MZe}clv|E<%P8<*y_#8Nm6)TK8zNN9-n z1YQIDvXK&sd9h5foxJdemJ#2>B> zi!L`;+mQg-wi7EKum;BZ!YS&mLtUYaFn6frjuEU|g0&JT1C)GB-NKn54ru|$&aOKP z@w{eFXs(HxqqP(H$;L|tj#(F^OHBpV%S1B9iQEx1gp_49g^=+0$3Ol_xdaI!3`tA$ zE)D$_a>^9u5HHO{PXr+zj2x|6D{a7$j9y6hRrM$7@WusJn`1=`eIJgHeId|nWx-L)|odiuD6D~Kw-aGOyVXIA-Qh86Jf4I<+g5VaC z$`BWlcaDDg2}xBfE&q?(2eF@Gj1HL%jF-e=MDJPeiXdUcVEbg&dfR!zk5L)up16Al zdYU^}4!yQ5za7;{^LJu^5{>P#8`aCq#N|69Y#Ph;qf_t581NBK7Bf!_62l29cCO(- zy-2NI-py6_1Bp++o^T4Rmlz~0#F$(+@YmsR1~Zx!nK#>>NSZYE;?d6{#MT-?lYB>| zimz_9aiSXlFjPbcUnWy@1bs+EJXxUs;@s;CS~y1IJm6vzfqc!=cA8cKIIh&!Bq>cr zI(+m`D#4UDJf^$a(FO2#i5Ljka;GC?;@y?%#oAdaPH>0+CwwLCk8^?;M;DOSZKxw( zf<+??Cp2Gs*9jCd#!CNWYx9CUi_l|=vk+M(HYaLOhyFrHpqt5uNNq8OL(ZkqI@*Gy z!>dVh5WwG?-@k*_f?o3B9&t6D;+RP@ZCPx5*Ok&6fNSa;OY~Z48#i1}EaLu`tj#?F;C^o6 zSekT#AmTm^LaFJQp7663P6g_U5~x}iW6}2y5-CpM5;DpLqqFc^@*xniTY*QjARhqx z6+sfe5AucxD}+ly8Z+m^#9g5(ZI3IUmyI=f9XIf9_vBDW>rWaUnIL3IdV)HPi}n!O z&5+$j$xAuC+2V%Z_y83PmS*&L^I{AU0!8~D6PiCj%G$g%cI@5w(o@Dj);7UUSh*{V zKtN#>%CA!@#fmc@bBf9GQrQV5*aaA(wcFc&$TT*9iZ4?Y8$JF66)M9~VAJ;)aJ9!b zA11&Gu*_~C*U8#n7=VcOEGj^5gRe|p0a`hzYXo!kep38$J zzpa0)aJA(47{CI(Dc@;#m5#c406fi#4;GAU+d}ZwU+SQ^O7CfJ3iSSI;ZJiwCkCXS zLgQNmt^!j5RAB1kJ0XN>_R0Z+_aQJq7q<4U5_!F2;J=e9Klhhh{lTACN#x3b-sIBx zdrYBLxdiwhLV}!ze>d^zxdceq9cBpWO#5#?eH{AZ{3;S2jBL$JtybTS=`Y=_H75oe zheK1W?>`+}g|b$$w)Hsmd~MJ(7N3M&4Y&%%<8_8@Q#Zf$lJ9el%$F=z*}rDys@sGy zsI-&Z1ZwAGeP9H$^PwN@aQfd3n+k!kictM|95pv#o#T2}8||<8D>MglqrE*-i<18u zWCD-dIO|Wc{by=UfYL>dSm80vRkzMjTR-5p?_2Oq|L%`O49a|b!Wo`p2s$ z-&2C`ts^4n;`!q(0I@F_xt7?|IAu=xU0x1aWVcvFsf=i3W~2`}58aU7yr@_pKRIaF z?6^#h>f!qF;M9Fo!!q4F#Q)-$;_LJ?t@R0amr2o`iWRFg$JHnGwbMLJJQugl_jc8O zniie6dk{}}g;v`(nH^o$e$M#8A0W1{E)8Ov$tt}c2jkE3`rrD# zOO=}{I9^KCdzIOs^Of9$DS|YLYd}Vx{yT33^icFDkIu_Ch--OLN1nb}?|Tl?$mLwo zm}sp~xnG#ewZNypx!$!k2BoH8X_#=-FHFCBOktw4#yLW4XB^O@`qQ(6Z|E{-qY{hu z{PaiWg`o1%(acX2FU&5s$OpKTzxDwzyTqv7f_X1flLdp!#NW7tf1CyCMMLl+T3qPD zOZ4vS^oix?^pArtqp&sR9E!?{3+S4;29M7V#cf_J8rtUWU%oxH-!uWJ->vO^f$5cf z3VY)HGrL@(6pswAy)&dCXZ;09Nq%c`~W8(jP zR2X+KGM%{457qw*%7*a2S0`$4vZ&>xkmWnd0q2?NCRufE$G++Awh4`uJU)8G_G3-o z6mk6VTTsA7I%^xc%Ih(uqT&go`OlBEKC(LP&C(7zY;D1mdIdHcZJJN|R-N^6_gkE0 zpv<0U#ym&9tc%_o_*;1;jP>7X$P@Z)uH&$FrI{#&GJr;+2vqcGO(1Y z?w4*P{%605Lctaz{^qNc4%w@lxw-%Qt~zmSv(&hK`hwR{ht!&y_~ury`$$%gHyPAXywT z6cbicZWCL{bw+=DBF9T4HpBm ztXW5%&Lg9gdQkavbNA2@Z%0<$eQH;q*1OgIhiqih@}26(U-=#`XE)&3%-*_YGu6re z{h&l(;M`*`bE-F2trk{Gb4yhC4$~K=@654b!kb<)m#5PLDL_nxZ@O`}a8lLKdNUZz z2@ph&D;%lQTm6DtHgpS|-d5XH+V~!wjBrXO9F4DX21Q809gqUk{snq06T0dNg1Zy! zYsGK!GUh)KaN+irx)6bQ3`ry8XkY!Gp{$@xpZ5dfTy49^?|)$d_PQ4?LmG)7XmL|M z`M)xJO3`{Qn@?^nI4DGs_HZ=S_K6qScCCMVw*3~a*Fk@o#1vvwx~SSFx!u>YNt#X8 za&b~LJie3Zy)x~vJRbLXZBfxdm4ey-V$qV;ZQ?jP1N}`}p7_OV9GIcy1eh8!qrt9- zJ|OM=+pmVUYhOoxh}P_v)UcAIlXecT)tO-d-xacS#Yp*|qXoPF2$dViz+aRy%?wr@ z`dTwZUp+tJbozB~B|v;6>GX5>1gV~pbA=Fnh2<1Lh#aIj^_ix-P3in}&8?E6>^cf) zqO3j@nVS*4w>6-(H*xJ1ph(+QPwIcw{mGSfFt{i?}|NCsd>coaUG!69DkgM2uGc6P>n)|km6A%AmOz)sJ zbo31W&iex32rNy2BdGO?p1Rz61%Q-GNZ$0rVfT_(B4nVlx*#P-yJX_sRNAs)?{^fC zX)~7p2BOHQc7H?StH89#-AGcVw-e6c($Y8LCOs1E>)d|3YG9a!7~hE%UCAjw{WPG= zSz4NYi2sF$4KQz09R`%b-9!xqh+6av?W;>SnwmB_hQ_-JLK-enNiUHb|FWjQx3xN; zmbdnmx4g%J@`2_{Gev;6Kf*qPEUS)~`Py(mpCQ zI{&bHr8xAr2jxR$PH$4Hdt7BsQI8A}zo54Iw{`!f4qCTj&GVzZaibKZF~EoHebzL3`g+xKf8S%!`CN49 z^kbh;$!S}qtNnfADX;#=_qM@ujiHdU2K9T+rF3*S#N1M5!0-@L@59J;O4c-Ecz(Dqf6t6An_ zSE&)zPO15M8wgmxeD{(zp8tD0w*CfTiTT0S?id~h=kSyYKm%)EdRs*dPglIU)hOsC zbnk~)z(elFy_EWN-w(H%&%$0?RYwpBJ9?yhK49U!B)4vk`DtJC0p!GO&jGggrq5Df zvgtXnueQ@f!ZxErO&v?h)mFJf7xh7ObxTV7w60OHEB-I+shnf`1TD+OE-aqc(@aVF zdDFc!(wNH(-y2-^p&R-!Upj(0pV220XDf1gme;txUViz-+icF(+hvaSWZ_4@v|$Qo zbA*_eZ850H$#d53k*~US&px!u7N;lE<*yHgy0y%Vyj zoy6%hhT{F=dv+WR^8)@>HJF-Nm$k^BEpCEIt(0nCo>Z(=Kx<8+=9l zs7Qt1h~0PEcR#(#@fEf-5k7$ZVDT9&+lx0Ho8IaHtI?opv)K5-q%D0Po6i% ze{C4OWz(>J>!#@0%lI0z>?hR(vp0>nh3Eh-4Mf3Ni>ciCWNHl}Mh>6X1vowFVsX=G z4b~_9M;NPG&vsWfPCwbUKkksah>kj$f|9zDdIwSGsy9HHKZzcsRUe;{0HfTa^74lo zh}vCeChh)h5E0YhXw_b6?oLw3?)$iV>GInBo4|#=11zseKGoo|CO>aMdE*=`VV%bF zKKc6X6tVit?0}UM>dj&AwU2|jhvY0u<;<)NMrUr52M@Qn1Bf=Fi%O|)w6pI-QjI%Q zYP229oe7@i*aq`#ANvrm#neoVtWuvbwnjKgJ&FeDRm$eJ?S|jAi@%8w{h1vg?&A$7 zOiH~{Rr~7%rY;6-Xae#0Cry_Ju48Kn9j>3)!b9yrI(SRC!GOkRK-TOqCjZStBV*xB zW*UM7&}ulH*DXO_g*#pk4}+zrBD|K8<<&%ejWty9Wbpc;Vq+0+GDu5PnU!WNSO=%V z>HYYbc92ep-Jl9&x1Cf@58I~L^>$5EzCK5J$BLt6LNn&c``XMF@b%lZ{*R}+P)%6* zK*~Dm;1KGI&*jEgzRiyt!YOIub8%2ld_cm7+R-W0njT&MSvbuoZ^-Q|#vRk@^~R_` z%X^mh38lN#SR4-gCUCR7G+Tpba^}<&BDedjSc5Fgu=46EF~) z&6kozA8pFqh9By9#5ERQ*BO3B3xdSxTNkHp>X$u?*DB14$IXAIv8I zbBexl0{%cbF$Yh&>J zo*Z|t4P;N|vuwuWOu?FtV_lv4ovZVX>Z9z`c;{bjEa?a+mNh5tRVHn7H+PCT6M;w? zNyDRHpYxxO+=0rMga|S!{jLfB_*u15cf~SOIf{ehd^_&A|8!sPosOaP-00j|lY8yn z0@ljvwddkXOD1{ZPd;WJJ*q;zbql0WaQ+^>=Vdq!QHUYtko_1^U|cfdq1!TvYP)S}pNqU0gUYV4eUZ=L1cnE3#&gTJTQLwN+Tk zNQ)q_mX~OO4*)9nHGvoIW2!gBP7YNghaM^y&~e6iDR^&6TbH?Ojs(B-J~d%67SMe7 zj0A8j3O-sCbBh^2H2=_kp0$4b>r22?&vdiVUh}c) zs#C_j+3A4^7e!pR2QoEpOcLwUnSp}B9-#kIO+LLiA8y;vbYO0zEvmZ>%B>(A%;KH;~JcV4s>}{#W-m8BM|@xDaYnzRSRX-ia5ko~_~Z%KrzxzoWL1ca`g*+udu_g9nRx z1AiFp&1?Ruq$$q+aZLB}CfzkZyMJ*Ln2@diC56{6Jmb9*Tap08;%QrEjk(MqoHJ zrKV+ah5i(`2yy*xYCQpYHwJsG%7Z>%T(kC#7gh_TN=IW zt!cKrw2~*gu8$5d$bKOcV*l~yIMOp9 z`!Wb%QyLX(fCNGR@n>IuVsZ2R_Y4s`QDsbdoW_pw600resy4f7)^+)L>F|jL7I|5X zx%0R@MsFsrFi!r2U+FBzbmo+b+(la@?(yEPiZnPXsSDw(D&8cp4O$k$CXV~$9<9$) zmCD2zCf(!qTIUB;&UZ#SZ0^tDF2=w(Z;J;-3}7YP%Gx81XMpLX1iCITGwtmJ?UAP7@g=~T$np=T?m^$X zLTK}_m>5(%NuVo|xvi(ZmXs9+8yk~#X$=#T=Y6|JNT1E$zwc*K{Yu^)zr0V~p&D7c z|8o0$!L4SR!f9%I{%~xwuv8kzTF7$3M&ZZvSu^9%Y!z5@mRslH<>+ zv391ljyUgRS+biKN(so1pxBJ7oq1n+D(N^l*r&wC* z>B6cE$uF25zO3ITQ%L2B;sodCA`0xkDxZ$sF5oi?FhqLk$%vdAA%%+MXzKMI;b|Nz ziUd49=`bdi;}8iz^5V+$^6!RNzQ2=TYC;}YOyk&JXN0tSBRAm`fMisYOLISZ)4x}c zDM#ZWM~7D4bSfzpI{$o@WV4at!=CrC5Cu!-D>Z@a9J6_2hG7#sUu^6|4DCB2?j1+| zkG%XIX*kV&JFER&`NQ8hoRqP@r$~6TPYlq#1OLgmNw)l7*3W)|vT1h9fN=m5TFDwz+^c7N@Y5jeSr^6o2{XrLh{e8M5P2fWP$H@JvuDjdkJxxR7f4dq$=e3QSJiVKol;Zv z{>YWP&HOg~>DjTFcgJe#;t#!H6VbVKj~!WwxH0j$e7!Y2r9q)fkTU(S6Bt2aDc>t* z_{hL{sLL1q>%;R=@7$jwiX{g(5`{bY?(H3kwB~dNgMvpo&4;#|B(GE-iYF|u?7v>5ZI_gIX%y9;RdnJ`8Pva!>(qrvNJ?K3qd2sOrgyF)&^rGZC zhy53As`o^F^&Ipw{S8t`QN5+$BgycEY5X>^C=RI8ndI@kIE3($t$>lI<|8VeorAMA z;p1B|kBK9aEMxJeEAJ%CaQhDUPppv4i(Qfv;(RG~(XjoAQD!F5w3rp)F%_5ObrJz@ zka3Oz2O9HwDRGv1Wd4#<~LgG9{wX{5QOrDSjWT!)%hh0)fW zeg|kb7v9Q7zVDGIn7nJE{qa%0j9OU@lSkIDU_`czZ5oT=yT5nvH!K8-(~Q!4=5E}Q z0#mxI&JdY}YpoEtm8*~YWH6T`JoCC!2R32TVEXl=dTavb=8d~Er|eg@74>6}4FQBL zxOI)3Iw|j2ebcjlla187wTCu|r;gsnkUFCATtOM2GI{S&;qf zv$F62RY4S%f3BOoEE4OR|7ihLqY}{9$C{Cu)=X*;O1n zg~^olJCoJ4-2Ya`b@ePaEV)=3s`JysIJ1s0zx?NT(vidWm#VeVv7718r6bEePkQM5 zwV19i&tqsm_zl3c+k;waovjGW$N7o6&;8F&Iv?EqdYw!~yUF|UNIGxA@;uAfFSe}K z5iV2K?W#-+>c5B1`t1$2{+TnlN`lvBu#ocZ(+7=UDtIlr;wgbZaLrf$gI;?NCtR?2 zv*xjXjlV7{P^=X7nGZ}_PNwERd3M3arRE|Nm-F|>$dZV{-*Wuz;uMu3l3Egop+chI zmw7M2s@r;3KV|Xpkf7ITVL%1Li zgO)A+M9iA?`-?X((slnCyprjgujJ7`xac@zQGX{vh)5S$rzm)|=X!@;I?^J6PT`+v z9m3WOz!+Vnt2P0@D+JO+&NcpiV)=u_YWO;x z0FnarjGs1a-)}%YCoaP(HUIC?fAd8(@^urjS%_Lzr4p;BdD$|X8QgLIIGk@%81Lw- z4GY)!bwF3F6#ldWclXfz=T%s!X3|Zc(%(?es{AuMLTe` zUxkr2`812v|MSc>Jk)o{E*;lKtpWI-cEUy{75{k^8LBTHLCJpF5{N$1tEpWsUi&C z(79Gj;%JkzISPaEi=)rtp8&d-{FSPZ^}%jU^L~jw(6^rhn&eSH&6mBje)YZJP8Z|+ z3wgTaEN%cT);T!DBoc(7ko}$jm_7%%6cLfPQkJ96xxig6qZY4J<^Ve+CiC)aNwh)` zsC3MO%LrW3+=dMd441(51W8X`8z|AQ0lkk1py9!|QMZ(#4|L~&Yx-c2*}NU&VDZ`e zaMEL5Ui?Jkz#(}Z=$u3sWcmx)nv|@!T%J4l?xs#hx16s#kbO)a0U`(K+o#i)&Ao=h z6NhR6CtA;HXT!FE5P>}7`fVatP}#=41gi1<=AcR9K06QUC3C>ihyf}kxBQQLO#D9x ze-hkr$TfV@u+|i2yAHs;r*Dc|PA4~?#zt{eDC9aAc(efExwwmwV;gqM*6)p0zyr}m zU7GYMhMMA)3cmr0M8Ny?-VY=IZ(c`9Lby+ER~kMU_A>`<) zsh}t!6h0p>kj(7_;xKe9X^v6=MlUqhnuNYp+OUy=jV*q@qE?BxAQJu^PiQelS$y}X z0ccRoXNS|-2qt(gCh7%2&Bva+InNPYE2(+JzXcHJyFN5Z-{^4mwN&_Y92?=%VHVkn zjN@SLQbLJP4BWl75$?5Xm?~1&F@jJaR{#AXlPBS;gX%%BIb880$+P{k0K&#!Kr(;E z$i2pC@>%6q{xQCNaO$xzBR4DvBbBFh({@i^2e#4an0;QG)v{H{=b>b&}{;8Sj# z*i8Wawf88#Xv&jdJp6Je{9XcU?qc&l8_bULTUQ5vBED?Ww;P`T)1C$;dqXazZBHOX z6`?A!jWoe$evU4bx!Med>IAM#xTnn~iH(V=b(`b)Y zNAqOX)u>wrz+Fulp%iCvhbZ3D{E(hW3<;y01p@D~f<%cY>z1zOEfsHITt3N%ssjDmi5JTtp_APEyS6l zviFWb;ec^I)@&<~YoZD`>Y%T1H0`{h*Bh(ob}bPie*8sk4#?H?w_ksNr!N@La{Sd{ zuBPSO?t$?7$L}oxm(OMljoG$=HYyUuS<;UBMpTO1he^GuEbdqjaIteEEf;RpCLYw; zNEG=XA;cWs`I!Q8B0!P~ovm z6p7JRLapzywfhd>n;W{*oOlc#16%O|s15Ht8SNxG&Qc|xObUp>{PB;SBY0wiq1$S6{3X_TiG9N6|@g$x+ z@nTD9ECXyy$Cv-F9-*w)n+)DTH}6E-R>w zD|o6~3GYNAYj>-I*iuWoPjEh35Ll8*NoMp`<~K&9fRrNd3vOQcus5J=d7fpAb)E7V z;1`YA;;B9Y(!S3mri@u7b$Vvnf-BVqt#@B4b0uT5gR2#L-$Kvk=`Xw98ww7`1)R-4 z^Ts(}Y{Juhnq(GMd^=1cTPVRauy>8BoUD&!s00m-?4hEJr1o_VP)s!FB=EE7pa}=W zF&1j%-SeD=m^B>fzPp%SeW+cEx{!HGa#=EK7px{rzZ{$J`4Jm|Yy$Mpg&MgPrs2(Z zC!c~IuJI?Bw)R)`Rmnoi0VT)sHOkyo*o0S>8^>tF*<&8!UCu z0D488(cD%~MzDG$;}7^zy~EUkd*7rh5q#N5V9YbHi3wDr+*l~T-Gwf_3V7=W%_}Fd zP?waXw+SUBXrAU-yBMgo*O+`)dsWV3>a;C#h8qX20SyYU*( zE*-wQlhJH@Ol8_FbiGK1!=WQ2=%k4}iPSfU;zSSh-Tibf1SB)-KD|4DC%^{TiVMx* zXy!H~OLU)QDU9z4bBr*@CT7btxt}j`2Yd-C17sz}qT%d{(06J^EoT`qN`$3fQJ1>B zeHXyWZOW=K)vNa>HF6bVe2bT0Bp%8bsnb&l$UwfjEi=sx z!L0@r=rptFnZsH`ZE`TpGb8o{QybjR8JR55kKg#xwDJTEW{(EF%E5Ech&3P5tvrtT)(}i?@ZLan&_p>U3 zp5uY7-zQ5gxB-}d$%N7OiLt0du(d^@KY8*4`S8ja6Iz4S=Ek09Qbpf=l1I60E^$N2 zja3p&a_9kxD#=rIS_y27U|*ayU|;RYZO(sNiuVMO-o{zAOGNd+R>R2uc+mh``NKEn zA6|}3@#Y=)((S1a*PpIp>fp)>b_fw_Bg*;l$c_3RP`{gi@FsanEz3wqNp#9B;tr90 zOjHk=f8_dIc5M1~z}tGn!Sx#qMsEal!$|jk$|gxlbObm&h?(_+^c3Q>CC9AZoJzI* z%9(!UQ#YUH%TRG1{&QThvPDG{4Tf4lYQ9ttK4d*!{DhW%`lro8@0lNdZ!Kt?kR&D{q_X)~Lr~c&w9E+#o$F6PT8J4UdobxS zUHm14gC`bfw>MSSh2R?*}h z_2<&&rrZWTW{7L;ucQHKK$(;<{Q>OlvZN0_{Yn3+UKnZB&rWX=N^%{s#@Mw*aGg!x zZ8gX-0kij}?j$f)y$#e#3E!Pf{t1_>$*mU58XDAtUV4b3v+&H28R85Re4`ZnfP=e7;i?)QH-{}yiah}pXN4Z;zNdwVcJ*0#+prs$mZU|RyM+qAX1g%7iuJj-88m$+9_ zvMt5izOjuue`k?(Cm&3eLp0pT^gYq$=Rv%;j3nwqMG09iLv6#?BB8N1B<0RyXe1gkCmmbIYPJ<6^d!5TRI1WHuU3U`SQ?y_Ln`=8|VJ^Q#QOuh*OlX0dx&#$I>q6#s#d%Fcoq9vABo8%Jv;LEi_uLuySxBA(?^- zT~8$PZNP^2);i5ss9jLeRPtkL-Kicmk9r1|^Y7QjZRQLCsvj5w1)WxLpEitq=qmr=M?nYg|4N!V9@-O+9z0w z<0qw4w{A-yX}=M4x+7O|tQ1dMLPmEa1V zT{>;yZI0fkzjC;`5_J55@ z`H%(E!bj41SzEh{-BURmdG0qIs@Gn#)N#j=pUO4LEJ`I>`_#6q&5!ea6SL}f%Ec7t zPPKV9_q`Ck(0tH4ucpz2E@#EA5dw=J>E&cN7wr1B#gSS_AKl{>l)OO~+ zBUb9YHJd$)qpr%mp9CIPkh|Wx7d}EK;-N6%SE9A!Iz{2c1G5x{{C2M zGN)C0X4ivj#f;1P0$d-N=YP4g;hJ_ZXz=3FeC2*nPa8U5zX;sNpQ0GKS#x9hD~4c` zi2Db98`C%prnaqAh$;7ZTi~q?9%PvK?N5aXB4dk*0Xxcf4~dw?0zLL32s}1$h}#$L zONYkupgueI>S5IJ2gX{VbIn4~;D9?TcqHi8i_UG4h_2XKaZsTAk^9jH6mxjbwPc^a zl-HMcKR>-dsL@pcM%wPyU3tO4LAk~@$e4*#Qn@-JZ2bg4#&D*63uI)q@`en%Y+ff{ z4GK$0v<0{Who!dN0NJve6Ku=lz?MdvapADyYxV>ydD-W0^Ls6A|_Oz0jV$(7?4I@{D`@5m|3YnvrxuoU;(KjY%m%rqmhDW&jH&5gEpr$ z>P)HldC=MJH?VX`jeCwX{tU~z2f~Fw#m&e6B21e%^{F?wFaUw4tDnm{r-UW|&xXjf literal 0 HcmV?d00001 diff --git a/utilities/system_monitor/docs/images/class_hdd_monitor.png b/utilities/system_monitor/docs/images/class_hdd_monitor.png new file mode 100644 index 0000000000000000000000000000000000000000..3ae7f9bf0dccfb38757b806503687d4d940c77fd GIT binary patch literal 47011 zcmd42dHC~Woi~b#$}lgY0y5&p;=>~Fn59Wu5g}=kCT){6Ns}fK#5T>=W>4Ct5fmJK z5mZ!GLD7+6bpRJYL~t1yQ8tlX9F;)?1QbO<6j06`9zCO8zURE}ALqKxbM%+p}%oArJx`3^fjh@DYM;K?$@8 z-Vl6iyMdb9o}ajO^rw#axblNwvISwVtq|yHe;tOmpd`2&_|dWipJfX_3U3?$u81TF z?6E!V`$hdc+T4obb(20j;s;xh4!92dg$+KswzY`sCbMj^-s;ETaTwX!-im@-9WRSR z@DS62wnAIccB{D+##-Qu|6UW*+KN0s8)f25GXF0It5<6m6L;H6m)bxz5~SIgbz+O6 zTVoPyZ(HHY&T=1!=XqiMdFZ-vu}SQ0cW3s>x4=B=y9tm;zU_9izJt<0>@$DjW|I(n z9ZkT5pYN(ORKeeT9Qj3@ZENfQN$gf*VmYYYJ{ZO@``{*mAP2WC2M2#Pr|<-Bv|BA_ zTi;EsoLX3p)58WFEf&qiy5YLmkVWWd!ec|o?4^qUw|Q#NFFHy`T!_oX3J3wuC4OK{ z1)iQ{Rxp6NnJIUh5o+qtk|RS`9yY5`WD1Apz|&2F&o&V;ik)%KOpx`owZKME!1g;T zof_5_gp8A9u6x0%;ri)(8E(L>LMwxNxS(3Z>&YH)zI)Z7l3{mN`SE7)3yfc5MFUz#>@i;@nCnLuF7(~ z%5!ZjdYwjh!gD4Ko(!}WC3&ktDYT%#fwqw2E*e%=#3?=`LGvb!mqR(VX>vIe3t`@~ z>1I2b^%+c@+8ff!F`{1<j2LMYtqGsjkv?0 z1p*FdGH9(EaKjwnq2dmEselhe!C%`(UJjc~m?S2oSQW&VMn7qGniM?3I*XC(>Pg&_ zEdyJ5MmAjxiZEm+8qyVg%kLmO60W zWi&E|bFtrBr4g3P67TeIQq;L=%G-q{d%@COEOcyx$4waZ%;rQT2!>xaz^J&OHP$0w zR!L&qUwcsk^bsEtmaMJA!0^Vj#|wj)?RkzYpkcF=#uB#vl-BRfMtA@0OY@^_F@Su$HwMg$B;YHUJ2+syu$c zc$~hb6E`G%g$T*9oc0%G)0rkkv2r&#MNJ|lE9`bpYn$*ST@Ny32_`m@Wyte}pchgK zb8TahM17oNitUcn*%a-Grb5k=CB5{AMWa}EnjMbn0sRAe-H0O2m=pM@J1OUbHbHxm z93>)AEfu26ZJGmOW#KZ^ivcE(lG4&xZPa2!&(^w=#0A!y5x5Zr>$E+kpfG@MjFY!DXNF`IK&5q}Tm13cO(ZXB$M4g)jj6qW$ci=IY z5j0VaK^0-s%9`s9V+#6%axp1gcHE9M7oB0Sj@jH2fHql1!;L*>bc$WBg7!d>L)BN{ zWUZ)!8ffep-L?RoA^2JGR(89K*MXI{afwWeCQ)2&jnr3ZOKH%!vW zA#}A^gwUW!qh+z+$55L>p9fgG(TaJ*Dea|D!j`?k43zI8Q847;p=rXSIPG|;yO{7| zIq14hec~L08AvGA_S0HzI-zCiSbI7jgJaA>Vuoeyrqo;~*a((e@XYVvNUK&@FM;xm z9$D3DKyg!~VUU$a$3EpDR?P)?X{`mQEOgrA=13akwo!B&TvCtFwbBSxmU5bl>*a!G znjY(##AG_7bEPmtwG20`Jqu`{m)ng8Ks_YBt+8KY#}FRqVNKR?fO5+ZRj zWgL>Bi3K(x6ME=I?o_9h&fI9sfsr8BZkRPk-MGy#;S8BHR=PNsRy-h0Yk0=A1wSde zwE!{0%faZ(dX6@i-3C_MG1A{?Ge06Ydqm9Vfc`OoNZ^5GF;EK%ygZlVcsd|0o#&h& znQYdcx9D17z)QgbGD=FEG_f^k#Sb?`dt|oD)0D03~C94R%zb9gO~U=xsW2x}}5H3tp2Ojbt?ynQ*Mb zbhLp!p+>VphK z0XGIC{+S;C4Ojj%9nKDR%}lad#Pncwkxm0OA%G15OaBWt-ThlOjnYl6n5pf&!3-fd zoOEZd!?2B5W*075Ft8u0LN;Tdso|#rIK7z3N!tuqJKs38?yJMOt4}vlT4rF@S~ea6 z+paSO)MUC1QMBSPXl$spHLEQdF=q9Zl`ESHu7<7*r{i?2xd6FPE>F*w>&g+a=z%T3>P;j&sznW@K*8L>6td_CDdM_*sCc_KH&I zmhz&nD5Pf_Hs)tcaPkT6TC5wZ|t8gtsJl=5I672j4e z-0BlVPN+sk#72L`vM{xjmFc2CQkts842COHGpd$6E6$k2Tjyt#Av)WHDD7&}%kv)|2tts?7Ot*_f-9 z5OioS^M~a$hSYU4Fe;t&ye5&mt~Pi1#fA}O#7^9pEFFH`ABK7eSIS^9?a!vOUd;@$ zW}J>TS|B$eVP0^(u`O^jL>Vc@df>=|1sDn7AJJq+ogv|k*w%c2l^C+=0)j&)bPhZ_ znqUk`@dkdp&T?*|F|=K1t0h3D((AI8;P#NN(ecI_C+AAFE&z;3{#;Ebn>IRc^6T|n zL_O5p)Mqa;%Ek~%$Fl&Tv>7}%C-ElTbY~^352X?BDC7l+0f$+5^&vN6s(JdFmjZcnvn&Ds!&7P^ye8+Wo5mB2$`l7xI&eI$!U$M zLH1W|X(}R7w`S(xRg{_3G3Q|?a=Ie~fz;fy+4hFA7G@01X}G6#wJ9;uvVkM!6Khjz zt=DrV?qF!zeKueD>{4l@`2^DqyghCdSYFKQ9i2OcJ%~}wB9vi`0E?>jBALwabpR1$ z$orwCYpAWT)R4=4x+|_bE)5y|%rl3+M=X1dQO*&)S-e*5VLBIrMMswTEYg<&F|tW5 z-GqkJSLh+CPVKJRn)djn$D|Fd(No4vIc3@Tv{VQ)n|FtaHGw+Q-i!~%o`mZuX_$=G zr~5?QbHSucqajJdMW0o|t~e>3wy?>w&0-0Ufv&>+re@arR+L)iOl1@%Z6%QW7MkPP z0_jj~zJxTlA^GqCJf+2C?1cVmAnOAUz^u7S6D%jiq-TeFWEw&H%WliCNaO6k0=7w__!M z2{dG*-edtU5+&cTG(9f|42?mnIwV0r87hPD+j0$Kg18ZjayA{U3?*6jnyd(c2+d08 z%zzdWuB&3%vY*zxB!hSaQ>aw~;(@&e46L1F3uL%d$D=}$lW;X1Mpjj5ARGua=5m~- z;3*ODm@ynKB4#LfVLIkEeNqg7%aN=SZqPDY%XBaqrb4K8wS1%vV?m(>QkaOtfJYNO z=(jB>(x9>p9FsU*R@y=vwW&zKxB+06%%tmw#)4Ug5ac54B_o0XbI zlX%d9Wwl8P1)hz-#KocmHNsGo2k19*br|Sf1YqbR_JV2?+Wd_&-HPh{~EmjS8fWPjGP!0z`7%Dr+&`l5PrMv&d*6)+=wvLJd1zA1&qsan_3G z8rfRtwfam|3a@6F&dzFzK58s$djMXEGhU{Aee9N$GixF+wRUhA{OK$emJ`EnImnA; z8Z13493=$!Vm8bGi*HT)TEinO)=#S;u0g}W9GRkqnQ?6-(%Y~Q%qDOr)O^0hI;x0>;Namlf^n5gKI6)m^J+%8LAH2UGo8=Ru-j% z%Z)t+T{Pn<>bBE7P{;5ZX{2>1I<`eW=6FMDh;*zr6;B#8y!yQK{jQ%lHN)EIHs|6o zpQ`PRiR7-t4&khACfJn4JydVD*;XCl{oi4>)npu#_G0Kv=%&(*`@Bhl02?^5f5B{7 z3It*PGEQ7G+h{sn@(4YICPaI|6a~e!=IJmu;Q=%m30VeMS|@O2I`JipPG!qMoCsl= zemD&*X=y}~LwN35l-FW83Rw>kFothd)kLFZ-I(*;?tIOQQ+4VZq(M8f3<9;*63G`8 zl~aA-p$;;b1Q8L!F6DW?(lv(P#Q2-yXXbuG;+K|^6kZ8;|M$9r)`xWGPI+1#5omC)1Sq$rNp0jDp zQ3XV?$!45EYPlHIh7P=(VbE+X7dpF1-2k%qRJUDUwpL>_j)|=83G+S{=IV%ab3PwJ z9Wza)L8D;uM!%uu6wz#;zzPHyTYJyFxSisy4jGUWd}(E-r%IU6b+UOU-3*vc-W;#o zp5ShRQH|E*tfLya3UF<;iJ2J{&zI$<8|27(-KHs%YK?`om#-NYvHA=Q;??RTNmxI} zClu9-`&kE*M@diz3ws!CSmTip6!m$e;@lXG0?2SX9YutRu0AAXsB84-g;atitNl!- zTej)Ziz;R_q?hn|%U2Ud@LP*90_DDy4i-#M4j^KncZhKYH#(M8&t@@4eQG3maTnkNwSehG;0(KrIPNr>OWvA03x{_^i)Kt# zN~xaU1)ipu3Zb#h!KQ?BVzUT+AJ60w)FY}1+K`kuY}vj$g{$1y!2R5$OS?ra;a2P| zlmO?=N(3=zbtuf%RJ-qb9aZcPBMr7iu%3&qDMl`y1mBh$OU+8229LS<+v0M2YS#{;Ywa?Jj&=B3#Y|NdZI#5 zFVnqJ_JDgu%E7XP77{Vc?O`@|2425rWL&4*w7bn}hPI{ea8sZDYw5*_7JDVG#l@xU}{DOa#W$M5lfe2GM+_ zE7qp6ZdqeTccS7eGp@ReF}MQ}6K;&prv|*5^gU+E43@$o8P#Dcp+W}Mcz{jVf!tdQ z8@fBuhkbrRhmFGF3^gT}X*6&~rcilI?fbZd6%AJb;;L(7IE?KU>Ns9J!=up61)HX{ zoP$7&REacVwC3CX#8=x{&&icRnL9oRhrtRqmoX&u-3==eN?Ao(0_@SKKJG4sT2dSQ zZ?QaOYG@yd(@C#WVzxE~aKHe*#jH^qALD``%~x$^9?R}9UPqHQ7RER(mv}&0VJ+F3 z%yk2aVyncDiD8ea#e%8*h+Qwoz(8 z5q2J zfHe`5H=!wF8vS?!aDth5Ymn&C?0O$(^LV<%DyTMR1xvJn(T~g!T_uVW4y?Wfiy}9S z${2?rR9v!cxPH)^S4K7xyY-5qh0*B|1-byJ2C)9cjR4PK=5JjDG!quhVzI(a*c zGeA-P62=hd&+#3n3AZK01+jV}+OXcLvylM_sZ*za3v}wz^J}JK&YK;1#?Xst)*CL3 z7Rd#)VsOE@-wJ_pGpmKzg9W&R@=-hlKxeRYgXNNn0%V0`+qpOEWh;kNv${9$_GiABftp2Xax(toA$-pRKJ1+nP9l#h|k(2KYR)$lbCwI#|PlWsWvi z{gG4^L6boIrP?$$LprVo9Je71yEcJZV_x#hc4|;bIEScdP|3ce*AbS@KORcnI)F3sGvgpKF$a+R!PQ(KH{XJl=NAf&~JJ>e0c{L?R710Yh>hM<>VpjG67PoCg6a-Mz{rx!9B&xT>ZeBP5H7bd zRb+({iLKSG0uIZxaVN!xEmFx{x@wGvwUH2~6G5Z7yuTuoOmKQarZ z4chvIi?;|q%KPgyT`m#Po;{ypf+WnzptNtaW|APx*HQ}157X{*fDVIf6E&zoptFRv z?r=dxEwu{^KqQO<{=+FrG(e1})0HqUhvHsGB0J7dQ9`A{wM;8TwAb&(2(hV8z3AFD z1hj=*&J|7P!+*88; zNLpAeL$N7mOThiBp1B$IgFcUPN^{JU0x+UL|1^<>YAfc&nq1|z=|;MXd0G+57|xt- z60jpBZsS28lrN}uVM`Ofl`K~yxZNq_&9<_Eb)dz?ie77lnDz%C#lI2zjUJ%bWTRix zo1&aL;S$0Ho&~|jf}vI+Apu>{l0m}I0IgL7H&d~6l5kVG1Pp3cvbG?5LZhXOq2@Fe z0IZPe66xpn zb_RFE(L`#DsaccD5Vj<0mO)O;rIxrH!2*qFt-ES!%-7U#US(9Mp&5ojF&qe~K zY=$#xoXv(woarmoq10A3$kA6Q|a5T!Q2#ImDR)|5)yl|*G$?2T&eTg8b~cEMxI zKCV)9!wtuE6o;gI-}}EBR5l(pJDxUx_OfJk2bd!fO40 z1aE>}{I9T0Hymf#30Bjq!1qJXzNe)zvG+;$QwDv;wJ7UEWOEuMJ z%Pd%;@G8)jhQ~Sc1g=J0t!?1tLD8&eB+aQAx7WNvugt~}NH>ZWEziRzWdTIR^iN)bfH5gBaQB@Wm&)% zJ;$Q4mSzfG-x`NmW~kW!1Bu3=Li=T_5;Dau(|AMsGbd|-JO!w%;VZ>JS8kUn0uFNL zEawTbAua9DO+Ago`fW_?%!Xo)HtP~Arf()9;Boc3!qrlYYO{pSr~+Ss3o~d}2Kem2 zBi|Reb)mCiVT=k9iYj5+HAbjzG%3LJ$st6PaI0a&{k0Ba-n590S7a*pHWAtkmBAQ9 zQ@c(tOR;$oSPjpgfEWwSXp03RI2+0!6tmaucOA)^&?(>qtXvz-gvuIzueoylB*T&# zA4(1(M$NS9OnFk}+p!$#YzHv?bTKBi1_YS0o95Wuk48K=3?#cD$ZE<;!MIOiW#*9%^AIR1qK%D_RiRU0p8&?h}YiqUWNyHUk7QhQ&7`RiAWZ`i#z0pum z-C=ZP-)Jtg*+`1;T-7!j4{Ef=?VR?Ze9)V@ZagI+5U2A-=^8fb2u;K4Vxtwe5qg@m z#wmDZE-{8KfFP)j)K7JyQISNc|TP^;w5gHva%?+e8s80pp^}) z<71!-Y$8ZXKEjf?nmND|m^x4-xuH#WSIGjKwM0r$eGuW-=Yx12v}g}TC6^y|b+X@O zbR?ZN8-or%U1t+=o$*{MMLHkPSbZ5sEvIXa19Lg?76uElSCP}|N}4a2fNkaBPMw+u4y;jKT1HI?VIVg%-2NG1Pl$no` zIBA8Wo-WPAfDM451%*W8?z}J6#-!N?j*7e(N@msVPrHR~flviJH^%nFB$kR4gB14E z7%c>7KDFRdSz2k_A9pRGr_>NRFj|r{vf`+hs+$DlD@j&vtonxF#2PkNS>0NvGu~mj zqUUYU7&x+;p9Ludoc#vZSY|LjDC7yUX6zKxbl^RyQdgi!HLv6#@6ASf&btu`n;z?J3SwqC?r%nwVKb5e3il_F6D(VT4mfz*g8q zpQK5HCB~zH(4bqC<)tGKKA||Mxe+K(i?B>V`BJONmaR?)EQayMrY<`m7!cCDC1oNA zMvwxm+? z)h09q1vL!<)3Y8B;WV75Jt4WP!8?F^74%?~8N<%j> z$Xm?}ObRybM2fJP25E}|XFIkz#7#lSU3OULoJ1~_35tby5=Vr-GS_7u_Zxj~)l3GK z3i285SXevbIlK(pB^@e|Ih!TOpe(6{L-7fc&ZOQZVVh5ZmjF@|N!975HZp>$ZdSmQHEKN(tPXZZx#;UQyLv z4>IIiGs;67YSNo=cGwIWs>}G&MoBbRjxe9AMpeTb_bdTOzgLcwX+Pveg>PsCV$v?R z3d3|T3W_XAz3#xG^OBN_mBjjE*-!e-xkdiBRO zE$tP&2F#ntH5}Al^@q%aa#LqYb*1H?U>C};6s$s$9Mg}&elnYr!|sq-7o){QCxN1p zN#1W8tfq`pVz9CN1rn5#Y0{x9iH`+PKbN&Aoz01L2ZZ#4z%D1ocvAXMwF0Gj7{G;j z?)ODCw-*gAhlKGAA(*0}j1#}-l2blsDo~X>wmCEyDSRfWgHls9gWw?EhiRogs{yqx zgiz1LP=$i$gEln1T9d%%A$xRfuEI6W0*)yI*MaGQY!T{etUe`mna_y;q|~Qr&A63@ z+vSB}#CJ+1U4k3PTAAThppWDgLs+1EV7@BGWo+lL+-Q*6KuhRVPzAt$oI}C92}+I$ zmTX6g1DuoE;SyY)A&Xf&SBAw5YBejeRfQHha(yTA>N+8EFvd6~VMMY869CZ)BL&GD zI$d@tf$wnW5;E`=({cyJCt5~g(CINemau_dR)fq05*@g%ri!|xk zz%8XNPSrlZ!kdz^iMkV3vW6gSksB+KRL7({Tfs&mYNKdHt?0fa4|I$Olf0FJ6lcAI zjkJk2@FrR^bKP9DTV~0v6RoYUf526^Pv1x<%&7_`k>X5Zh;Hv*` z>9zk3JPxzivU7mte;?5rLNnn_PzFq!McQA|NIwDWU>l+((-9amf8IL_MjmSvnq@CR z8dE145)TYn#6;GW5NK_akwkB_(l+|JRk~YRtROU zU^A+LD=jX=LUx*G^_nJ@+GrLb3flqNSeSin;gwTjqk<4l7gl}TSZHmd)6`~prv{ag zyX?DjI#n1>wf&8lD^{P+C2U+yH7s6_BjBPDj79Unv0~(OrPQ0y8K`QynpTpv6i;VZ=&?AXo1!TD?x#A9t36S-g_W zgrjX?+L|E^X3>Yn!D68eGJ4&I{4odyX5JLktmWoBp(P+~MI$M}vMZvj=t1dHi*{$$ zmspZ62s|Ex!$u~vxRlL$@_A07`T^1p7W~)_)Q1IppK!U*qB`9-A2A_ zaU>|t2Mb`jgP9wRV-KPwGsCJ#YS6uTCPhn>1i#c7lawNXTAUF%S^~ROQ0yQeKv1iP z54xVrl*3s9f~zDOhZHD$P9cQP0=NvlbS4h6NVZJEuUtt{Kv7CBvHc#ji3Xqsj~7Fy z-v)Wfg`4NW94-^oo+wk#$a_ABi1}lwQ8v1MPX!C?CSHHJ$;PH-wtaZkTCMUvnzzFg zoMe!R^2`#zJ3-UKO6qm`QfFM(w1gTjpwimhA%hnl6L4>xPQENmov&jgb z!80Vv;kbU+n^8?21Om9T5e{w z5i3KcE8K8Zjz=0K8Zx-wS;nO?r{y`-O54(~RvIYHr%jZEY`1ASxd!eC5!GFJrarZb zanUK(V%wMk<^zJ+Q&7Z%D|sDIWo&muFl>OvQUJSse`qE#J2F5rRYO%!<^wVp({VH{ z1W-v&OH%Dqkg-hun|qD;BMa=8PsB)e;!Y5*d~7F#@hDy&+-sMT?lBEG~=d zayW4tK!M0emGWRY2Rk^Ky1mx2S#S;^6E-6WWxbzHXH=zx0*cHd2R9R8sEBz3=BB#T zrB?x?w?G-o`H z#OY1t+wW{o*qpmFG;*l-)PXIHXa&UJi-gD+&T zKH!)`a%(hgwn)EW^$0TVp{NDyRk0%=mLgP0ku=;DA_ zBWc98W0(+gVY~z!q&~glVBH}Mw6$1a8D}*`c~ZL2dg=&8K8p!d?6#Mv;{jM{8g32) zPpYFK&6X?VMW{*54LulhRXkRjGdLCPwqUZWWQ2t1tcyDkwKQZdCv>z0LWG#RRuY#N zz?j4kMB#?iP@trth>VR!OxsG$932vp3XxAXjYezEIBee-h&lM7LF~3*3DlTPK~o&#S^)*tz@wD7C3{l7%39ylFr;=s~HnrK*7fPilYOy-U!hDY7_uHCxf&x z1~=e=Hzq`LYJeZaJrC@Ks=Jw}iy1Y*2YP=5ehDZ>)PT|SvP~PaDQ`7U5d?`h5e%A> zJPtS|xpw|e`4IT}Pe0#9>EkZhW9xR??YSLC5u@@QKR^4$r>b{8_3bN9yu9}h=iIi_ ziT}dBNq*%kZ#&?Cy>4Th`)~QDW8Zu1x%(e^+lMb~?7#oN?ENqAJM6_Teu4k*&pjR7 zefD$KCwE8VFYgk6`U?HpYu4g1-#znPPd)Y6G2gxF(TBog{&-dKSoa@JI~C&Ibk(~b z2rew{e%jyuL&v@XdLi?T9scPB`@D1epJ2z$F8a;&N4|7?*B|z~1wHg9%kH6vtbg{w z<`(h1tMd(OUZ+xhcP-n^}kKX>>a>lf}j|H(5uy#2X9 z-+6wB4;}v2{oZ-bzMtCp^UGWQw;Lo~ihr)T?{_-B(!ctyQ9iTvE%2Eao*l!EWVlzXAEb#rgbjaR0wfI^nD{ zKYj5>FW>q6+kSlHRh25A|K-CDdiJKrulv=H4tws|eJ(;y|JY^UZr*U+Evxr$=HGlz zw=|0_pfCEi8{og`O9XxGanxeI_bai7gy89qTyWhh-g@-zXJ1e8#ch{=@h_GK)_V9& zulztN<^T0P$^Tt;?+(}A^470^P#EkxKj)P5PqY706z|-AdivoXI`OO<$CvglVGcd_ zt`FMh+P6P)Wj&YO&;Iz}4r)LCz#IQ&vkp4$pI(9OWIl1)58LRCPd?f_mpFUJ+b#-U zblx`}bASA`|MfuMc-<>7_&>Kicf}_zeEgR0T>9U-_x$A3_aFY96V6(k@!Us``p7Z+ zo_XTSK761x`$glgrNDgSrN@1A7wp?RA9U*M;S>9h90ZCpw&~V?>+;KY-r+y?kbd)@ z4_|ij)?a-6p&$J4qT;uAY`vFvgM zU;FkqKea{tEdTmv{{6MDe(K+kXg~YpPuTT+-@oPS>=o6KKmEin^5t)i6(9WE>CT5g z%Y5avN4ix#IO(J5PUg@15r3 z@7;B`_kCXYLuRg`PrZ5+zx((1zS@8KhQp03i=&4RyziD^;@*1V?K`4>z4$Nu&%;lp zZ~h_u=udC?&F=P(KlF<1>6?s)Z+*|jKmXBFXaD?Oyc_-ank`4Z>+1&}vU<;f>wAy6 z@P{thx9r^f~ul>Wrr`~in ze1vnev1RA;xxEg3>4$Fr)n(V;zWa?&-+YMu*c10v_4wEC{I1<^yx_pYPLZs)oxIbH z`(3!_o8+%t^z763|KLBVn~&>s&&xk|>mwIkmEIp;Z+!mzi}hb!`qP`wR?qq>!hY(Y zkG}maUz3lbZ@zDz{bqN5^9ygvuG#XBhkWq2ZR^E(W@XoIPCgA zj1JxnyW%xZee~%o-o*am5&Mes%Gq@%J+k$%KRkP5c+S4ZoV4SwzkcoFniJ28cYgiH zp1%2AH(q(jgMRzp?g~%)!Y&Vf=d-k>-f`-IDmDMAe%*mP0RepNgz1)7|COd6_x;|U z`%C})?FW9p`%$O8EPSN@z>c@P?}W2ZU)=q|OF!dXmCa5*<3D%$*wLFWa(Dms!_S_$2N>-V z<-0%l8`E;m8Ha!GoR_@f*WdWV^|eLbaThGu^?O%6qB_>=ePgK*%yA{^OwEzg7-bp z{Ofa-e(>;XcER?0*+D0t`*3jOWnad2y5x$#(dI|C|H)}}>kGy0Z~R-}eA5ed!w!q8 z2R{Ai_`BEL`L_36afpAz&wu?rE8HUex_kf8M_v4)zwYcCJ8aMV*K>zrr#<+R)33es z&ybNEzr$78#wAzRy&d=c z!Li57pK`1JcyM3yKc8Rf$M#NYwEjqY=e@sm(3^Ju#Dyp9h}~#yGjr?r9ecuAhrIXB z9kCZOd%ol!K7L{P(yyJc$GY|QgSSoX<=eer7wiRxf3XjG`hc?i;Epe&N9;TQ;eEjs ze**69z`gCayM8MGr9FjLK+^r+P0qY9J^r#gr`ra2!OJ0Om+jto^?!h=wdik9A3o$- z`<&}u_g(FS+Yog7!@oiC+kN!sudJEIu3)go{>K^rA57rf*3s8L_PLkcaQiLT$3AuB zSvP#(-(UC5>g4uOD)-UoAdP-7+3no|M1I? zUwO^&Yt*SXUjCuSPdOH>_qscQWIlPxtG2<<4#$FB*>2Bo-PhlHpZUx8H_*fOerD&_ zp1%3uUH!A}IAHe6hc5f+$Bw`Kvlnt_Kk|Zyf7Ls*{hMdn#x=oZuYFr~#M8xMug*)a z*<;`N%X`0g``xFknL?c(`t(OmTmSeu{f~cq#`)ek5B^NNVD`(q@8upo`Tdt4{Qe$( z`Z@1^!x>L8-N%0Q{ZBOG>kobEhp#)nd*@k?eFRMHJ?}f`p?3k|aqX?WZN%d^Z%@G0 z_So~fpX?20ryab4mS<-0Qq|U2t7?_mOMvvmdh0z3n&O+M?d@jQxX)?UN6F z^k0$pJjh;u=Ar)zjBjoAPkQYk7cF-^;E9ia>Bgh3+U zztFh-y<5Qa_4gk4KvUY~pZ2@@hHV_?2(YN@Ui=+cfB!!79S=KA{M5nkfG*y0$^~ye z{iU~`d(FYm-lW{|>~C&4EPL+STe#D2+WE#mhWQ`&neXr2@$oYsIl*W>%3uHS`}W!m zd)*K2I3?ZXA+R-{-2Y>%+DWq;MWiQ+ijog_MhB!uZthKd+VDoyWnM4^LM;)P=0RL1Aa7mpuM0rFZW&|LxJou;!QEbL4|J|I=Q} z`KhNodUwp;@ITH|lS|(5R)OYk*!8I!Kl7u1y!@*6j(2?YTyB>ezjn!G@h;fKH(&MU zV>ti#ckc0{&iOYT@yL}&P!m9caHP@pIvm@`a7lZw X`jv=|0Nk; z$u9fkVb7iMM&Xm}EBEW|f9E?&VUNpy_OItS51)85;{EQ8_k88upWXGqPabu`eK&KD zf8&@(UP0dR*3+9;U;JEg&AY$-l{3G-^~lqI`P+k@IAH#goj?84D}VUbtG@W1^LN|D zx^I8ulyg1-PT|k?-6P%n9gBCs%Z_@bD&2qaQ4jyY%wLUv{zvbjb~@xUhe{V8_sM4; zxcrlE`-<@H-#z{iB;~)ki}&wdo_p!XHqZUyQ`u8Tu8%)qk8dm2zU9mx+4JT~m)-xXkD9l?s6J-fv9~5CoN$(RtVjRJ;670s)I(ou zEe`nDE3lux`?~i&`=aAdx}lqEpMC1Zzx;>A+uyoA?CRw4lMm9rNWAQr_Y7XV^EbbJ z(Mv`C_g|#9gm+~p{`96VJo!cE55EPL`r?bO|KtH*jo`1A_w0LSYboh1^Itx-2mVs_ z)bl^S>rJ2T|M+#kKda_a*FNyVgPUJE>5MB5takYLg(tlJq(Amx>Hd#=^q6>?iNCZq z`+Gd{PZ#ZvoO7MO=OG_C^r-VM-1^g7e)qG^(_eU~jXm|_PaOU&@q#bybgp{Y9#4Pu zf(s{;_gsJCB~Se3;D6ii#!tR@aV@peV)Fg-F3xYc^()WZbM3=#IQ69P(MO#Zo_jdG z(?fS${#a}DwohH%>z!W8-~Z{J$OG4X=bid_&yV@C`QK6a*%?4kFTViHG3sHE_dv9BBd3=DGfq52bRnABc&eRE4`E58dWcT8MtI! z7X`kgH^!f))qxM-$o>Hwq(V_Q`Ha+byQHvB(liRyJpKDVVgCUQ;8>tgwBlF(zw{;- zo~JdhM&;*xE*un-I8zXZBg*`C43vszTr6hGJK*$3VW-Ld^gn$Sw7=MMI%hZC6x9rk2$LuZgX*V6W?-f7r9_Gp~WVPRRbXc>|| zl=eNTf_%TXJu9eAyshw63ZNY66i{3jp zp6p*@3!+ke{k?DhWUz#GU)-)O04_oF?M(8SlYk zEytN!dJ2J;i7^uA3drTh>KLv7&P;yBhM4n2TwtkHxS9>r%vDjUU&d9i{ixZAy#;4H*Qu?*d*_OSDiUXPA z91hdfBvaA132$zrW7^P~_?%h&s()8RH>Q;MFguf>$)x^m;qs3(9qq6BpWGj);al+= z`(7O-CvqFMSno#hQ()$rX`(Nd9?(sG52dk-BeCFx9^;_I*2GzyUW^HinPx@810lF!C7Qw4m zXKPvQow%!BYcR7*pd=l{`3Tw!NvUQ@eDw~bu-_Z|GgYNr$A9vneYf!>^FF)Qy5zxL z2(8c1Yk5=f(T1JT4>-O@kj0F7;q8?CdLxQ)IXe-l_0K-_^?owepX<$!VpoO<)3(a* z_kG-}VNWOyUJCUj(l`3Jt)962?da9E5tpxz5tcBfj7MK|6wlxJ>fK{O=#-rOiD(?T ziNY?wnQnh`u*!wP-gp});aVO|rw_J%xJh0zx#Rpy@^3Wg`#AS?S65uyxgYc+Vrow( z!W$rU=!i3r&xVF+=BpOodNos9R%tiEU94e}6U-lsN5L@fd($X(x)5lKwBR&<#HjsQ zHG`dmUF-RxUrVbgIPF5Q{cgrL3oW-v*x}7)>yLkOu{oN7vX0h!Kn_+F~ z!q3{b8}UBXuG{)oO;2NJ^k056tkc3`h*eNM)l1>G%9HX(D|cB_?TMuigs28V_E#wO zm~Fdb)SF+8vXDId9!`<~o`=2!HHnS)qvck8l@f4>g@OqrJCwUK&GkS$2b3cT_DKjj z+?&1)5>jRRQzQFHa{`lMPGrWOIk&@1t$Gk)PgcR6AT5#g(dN(5x_}mGL&>YdQT7}N zG&Ef`<8dJ@L)^0(k48*aj?;WHC1#8ew}X&I1rF(tejxgJiFExRH%VH-Yc~Q=?~`kO zt_HQNaOkWgxEC?2=fFp5uW@UPR?dtv4O4(@!L6rY{Ln<2_H#%~dMuEJib{W#dz3qi zPf%a(6li_b(%4@eU_i013{L`uAGTJOi^W1Kf9i1K*_=q+592CFzFJtIv>}S?@keLd z{dyv2vr38ykH0^lD3X%H{PfiCtp?E%8;(aBfYZw2O!#siAITHv z-fxc+ngm5ii!YFT@7c91zC5oy$1Cu#+ftk3k#gy4eZPerNF8|85k_pgZj6AbgX$-7 zMZkEE5L^ChK2exZ$SzVf*2cOwk*$hTc4U90kCEgvDGeS&czH(kl3vcuq8z?4nwU~$ z7QFjoBYEfY6U(^O{uIWm^CLipw#L8Wa-<2JlV8IaA#@RBJlblvu!*Fycz1}<$-80v z>Bw?$6N^i$2MUGMXB-prhdhk>l8=dgRkxO@X{NL}-`pHd4TlS(m^pv>BGJ0>Caho#OcOJF7|`2n|eplji}SB3{@!!r~v|3E|tNK1DXauF?M zujftOo1@f7--cww%(7hLTto4S7js#U)TZ1#HUCLs zzf3HI73x+r7SC5|HtCAW?KE9*vl)L2!rK{@$2_$CG=b7LFJa4YF_X`sdCy*Z+Is+k zI2IVFWAi_e!z+`(&0G+z^$ErF-Kg0W@3F?S;Ik`FCsi@4edE;6EZMcs`7VaS zAyNJ%A(C?#((P}SyR$K&!S1KaYGb9H0YQJ5*0zr>&kmrKAvHUy=8R}!6oitOr5=0` z3?@8l`29t*OnIhGhKWy#2`t5U2u7H8t>bjH!~R|u?NbVZY;!oVd-a3YWX5B3@>qnT zE~}B074Y};Em&obJq~RqU!uY2VWYb++l5v8dcU>Kvj@ZeWOT|&zPpmS@=@{L7sne_ zhg(-C^Akgr_3yTDGVgXM$!1bUIz_&NYkcg<%EvTYvR9C5AU8n3=7d}GJWqBWv&_U$ zICbFt9?%?HFv_`!K7A6q_+YxxvnHGp;SQ6$`~-eY(bMJcWH;WQ;|ORaIAbKQYjI>? za*t^Dq#5+rpMrZAN^2GoDU=iJPUzOb!H~p%x*gg{Io(T;zne%Jp zpho^{wVpVx+&^btNn@`@G)Xys(XkSI)l!R0AoZ?Sw{0AgG2Wffo~ruBm~!yqJrJx5 z8F1(|%R3T)>Uh)Cikn5#Yi!JI(!_q{QK`i<(6=3|a5c4Jbv$NPZg!x`rnCK`P^Sn{ zX=AAJ{YUcjNsoWV0n?KJjQFdtO^v)E3;w)a4u0GIXL=2<8^Tll8})k<1_k3Qta-Wv z^qjub=0@fF=zf|@nODtv55(S{j#m-OV?6nv#wyf$O8vLIB?Am%B3n@V0ucgpa7$L{C53gu!ua<9EF$!Q{|ZFPPse-Gsy04s+Rw<@7D3t7ZBlO8<9iDh4lfvKC706`SvmNe;ar5w!6Zb_ zHZ69eFB>J@mJ79?L+C-Ana=yqNquuL)c^^@`pK}^*y6{67*KR(G{mu>&AuO3@Pz#N zTJL)fDAjMsK;kYJy_OB_9NoQbs~-?!4vZfagAyF@={RKdbDBlhIpM_=Gl5&u2go;- z_P;dbWMJy;YcRb9DhYa9cJ1N<_bY%)*cCxZX`AXkilki%G)1+NoY05oPr7NacOl#K zc+q^b4Q?gJ@2kuX=@A8sF6RsVuLi5-ySxr3+%B$NQM48w;W-eBmzN0VV=rS?V%JQ(UWoGx4eZo@o!M?^iZi!LQ%-ip zU)f$XvYMC+jT`ukKmQgn*W7CA>f)hOi|pDTs0nEI&f&-7yh z${I?#iq&t4qfaM#fKK@3qxzZ#VtE zB@H8T+UJwz<0g_O|IPWZ3%05vk*x(IMtYPE1PCFqc*GP#IY?89dr2r5N2XILWw9~2 z?96r7V?r13yZBGoYkK?CO@NYK}Zj? zAfG|WDx3&X!AR%xW0n`B!P{(84yx(X)0COs%V`PUYaNxR@(y}k7KTnm<+b;njPgwo zvg2YQlu{7O6d#u%*>#w7(sKz;myHL9i0PrjL&Er&BJoS^-`pIIs=eDL$uw)=_iw=64TSHu;?OS(<{#l=aVJ4lBqn7Ie#)U7BkHmtkU5fNaL3c!dC^drLjM;~NE72!%ejI-Q?R z&a53HbotA>gVcSc2>s16dTaTGv(=N@o41+LSo*e!6@7 z!Ntnd?(|_pu4G2M{h3K3uw4|-Lq-ao+D-?*(m34cS_z?zQU1ni_eB&(xA9+DfC9EF zdwLS#&_YjQrXfT!w@KWvjA)jfYiYv z96LvIjri5s&D;@j=L(VWa?f2BTZVwB4NAVxImY_uE@ONt6`oYbZ95{!Q_kq8A5Hzr zchJxu3}T_(X;06n=3Us6GPN{!27gHiF=mMLiF{^#A|PGL8(f(D{R}8kO|FuR#gTH$ zgknfP?uC3w@}HS&V{~XXj1voATPysDB0fl&mhFTfMFc6O`dgX3F2sDFc0W(9xJa>x zt#A#_XhX6i?_uR;yr#D-@;cjRr{3$OBS@be`|8>8?yL>h=?Ky(^O+=lVG-x2TiMt2M=z`&O_c9#z@KPLLH{Gf*w;z2%E+9KM}Ld zJc#3m9ASBNhGxtcNb(=>)i%HE+Xm0)(tsiO1Bge=XlTW(Pg{&JVMGLzAi7G?R*&!fDvw@k;VGAduXb`=^nR1_OG zzi2xDO$;z9Ex+eACB;mQ%4GB_d#2}kZ#9iV+C9>x7zmOSwRII6fNA+U--KWta{I)NEXWb?dC}}>+4$hrT7At&Yr}YA>jB|F!+ zxgw180M&PdFx~bSV~D~&v_2&GzU=-D$Nbh(>TLIKbLrRxXhc|`T5g0+!C=?=Z*sEU zx`dOe+9BVXDVv;5t`Y4R9WLe8W=H*F&WNTAZTk%^x`kS99CL7*IQXa&OZxJp5K~{O$4Xv2iDx>ysi4LhJUGr!srZ13 zo7D2vCJ_2YDoFbwA#i<$%ZCQl_M3$acz9~Wb4&vTVG-EsffMl9j@nddcZtrQd=a({ zyUX5OUmU_?&Yq2Rbg4(Rdo$#5xR>V<9ZR)0`kb=0%?=_<>6nh4(sCQ%uLbeVOq6x( zlU#g_6Zd(AX3P1`PU0r(+&d`i z^Z8H0Sco ztTRj;3bGxVgh5P&fY2N9sveZK;C)qzON&6Fp2uY4;DowXtegs5Yp(u-743-kZ5 z{^+HF{O^puy}LN*sOr>wRlTFMYQINq6E)npMQr_3?B?>I+-8_zmS$4%Pfq869Z`nM z@2_9&2m2|Bs&$XwPl`vj6StS(nqSzG-iWTHV)S-QgT=XI))^Qh-%PhEF6HSYh>>n4 z5rf`t6;9xb|?is@>SAEorBz@$4VEj=R9}c2i_&z z6k%loz9(Urkqw4)fM4^4zJioX0BwaDL8V_&Tys0dyyL(~Zzmi^Rq zLr%tEb~?_vj&)H|mn;jrO{C49yT-dfB=34WH-Tb9^$BDK43e6~euLNL5qg=@RqyPU zo-`WVtm(T_^#SF@-dKdKvo2_NqFzOGxihMHC1{`79N{oW2}wKsuCL%$U{|M8;#0)FK*$FJ-YH(w(;>qVqpnbVak{oS*EL1o#WQ2`A(E z<}J01^zG2Af4fmho4yYYgYG%Ty%4!KAD9P8b^ z)=$c$@neNFvC_;`%EN6jeV)0VvbKg!a|n{^jJJ9G@{8ugP<2026+KX7?~Y8g`~E7o z+I%8KS9-)}j>$MDU{;#^P+fW;OR|J^DWyfAEo_JU2q>uU)g-U9nyExxi~szpc&Zj1 zqtvF^e%ya4%SkQnp{17ZCX0W>P|9ss`>`!Rt5}zB<7ZK_M=VM&L<_Eb`GazsFef;+ z+OY0Tki#y*{5y`gh|lO}6?R+X)Qs=VRSlGaun%axRZT!e*ra%r_p8FX=x(Ub=*_#W z@t~g@zkFp0w%K$`O?5?I#pD<4{rpydtPqo@)B0V6R8}{!HMhEtS}J{R$n-o;VBEDg;9iO~N)+{smW!bY0Gyof)~sN4r(Z^CyqV zI(>MbK0YGna`}v(;NQ;DThe?*{}15ZyjgQ~eHuk`5r>d`)s!v)yfhs)=E%4;|4e$m zCq|ojppZ&kc$_j)3qO%~8cnUy?BjjZ23HHE6nn&~c75TtdFFWvg|>bx+q(}%iRQb5 zGj%RiM)vog=P3|5um8vvGjgSAC!eqmCZJM5AdsXCghZwb;-4?D@HQ^O zX*}v&mt0Ap=pNOH)OT#VgCdeGr{MnOKBKDcP9ui+W(TacNCm_Cw=d=>$MvdrCV2!T z^tfYIey}(-%_-KOc20hdc1&srRQyZ=vPd%02Zpt1=>;BZz9o4j6}AK9?I z(#Rh|=imAdW1B8hcs&9A@!gYGj3D>5Q8NQdg>v9ylDs!T)_F?bts4jKgqVcosIAjy zV6_a^_%MgK@*wrp5-{I;?;9L$$QK@I5N^y@d`e_HtJEr*kn?bT#p2yigB9k!;mWEq zhVgU;@M-ik2)`IMBDAGlx?5*=uJMJKFxzMF04WOnYCsHX{FZ*BJO~Wo-c>~;?Pe6@l$C>Q+I}$CfGaHs{TRGiZs#guJ;sL(YPbiny zpc}jkpMqbu{Rb9f+M`$Tj`xO&^#q#jY;}3y!t`2%Jor=)NO{OwS8{$ZSNh(gvd=HO zq916KTPgw(yw@S8Q>P(->Rq1$#&03;t#%?yP_|)+ELXI8lhu(W32vW`FZYWrS9PbZ zvMe=4l;Tv4Kbp5b8q-H8Nt0}-Hm;?vnQgC5!q|SdDj86BwxSRhZM=t<}GJnNQthG23sF%-!ea zNqT-C8W^IsZ{V0|sAoAE9_F(qbqZC?ylj%ZOqlRsiQZUBFxlvJusm4vWYQa9nhM?$ za#YBHW3T+asXlc`FoL)P0LC!L2~n4^xo;pstpB~ut1S=c%S+(}dsP>DU`uW&c^XdX z&Kp_&M`Gw(5Yn#W1!;R6R+E!1Q{re(FIat|vzRhsXCO+c~-e43k z`RArcW(o`(86nMoH9fC?wu?QhM3dUn={}k3pp!i!_TK-EgTP%`xP0eED z(rtHJG$JTSrxs-rjQ5OvGuCc=!X}WEq%kPQ%t00%RbKE~4CWyf&(+ihc?q-5LI z%~B}qlCpZ8!-ec?0=np$VgSYo97^vwjz`bOGrNPT*`fcve++JfrpWz#oYf?7(i%KJ zTIRl5j(v#1FheCG_I06kUMpX?O-(Ay(!7K%!tV3LOHRqE0A{{EmE4~)(g&hrmV4zY z{I552N}VgE#G&vGW+lyMIIDx7vfsG7SVw8qsgpnlli7Y(W$N=J5t&@B@)+~HOFNF2 znAKOP(+ILchAL|C`Z~H>%TC08NOp7^0Z6!Gdy$q}65O(pQhyjxK73~f%7>T9Aq8HQ z+{vF%LHk23qoOux80iwRqx|Hr&s+^hZsXC1e@3(>mhzO&{DOCFU%G_@?WWC!F z(RY*d6ut@^DRb~fMY2d~3ku8*(8e*n#oXQ}a_;37>pv3ISdo7*)-tGb;k|dUmgQ@C zYA~wRQC3|D8@}XsHrXWAiGUog zLfuGEu5S6ouWK=1^|=R4_xR7R++1NZJ8ObvOQA<=k*UDS)^u}NvbMa}kW=>J2zZ(6&}m?! zaG_k(bm7<1ZsIQY+=ZOxs9kAPEjOdq^{X>nU1f0dj9SO7&!VKf=uqI9_MDvR9PmiN z$bhO=kWqlipeT*Z2B0+6?e^P|MDt%>aHI(SIH_-tGH_v)#YYPiumwi(*B{_Ft=mk# z1AUta#ZgQeqw3~BvPR@sy8>iS_F_@iIOfm)Y>gM%AfI_2|A}K!NnHnHYKoA1>0KIM zwAg^z9rSmSBi_$%bYzZE=!pJw5r+XgSeRd^{EZ*mbd%se4n=Vud z^YhY?*lPIJ?atru99B3}kvT7~FVFa4NK^5M;0k9J)%1sTE^Fh*aVLE|&53vv{N2DW zEHtJSgOc$WC%SG=73yFQJ_DBhVPu+=7}TC}q{>bQ0Pw<@`gh7H&tC>$VCTt4QSOgv zs$o+x(scr#kp-8OGuCsb?&)BC3a?o}p3-|I!UI`_Hwp#$`JDz00crRk|;KpWSZv7S%)jpmyU0 zrLBIT&o?;NGW`y27sXzYmZihg$XDf(2_bl)t_d(3g^**q@x|#VW&gN zJ4{t7avRk%0Tx5-Y9r(K7K8$XyIp|$;nDIkTRP}bB_0a^4@q1GER7yV_u#Z4c5f7H zz!$8VhbOA<06XT9A-C`KCA&VBRjwl(#b6SJ0@#5{HO_r*(}M+njA~u|xBeqxg!Pwp zQ`rDnIPwi#HV_j(&w4PE9W4IshZzI`ED9N@ClMnL4Ij-{>q{4L8MAr19t*trBFyVZ z3IVOLVxtD_J4Dze81q&D=qNpC(-Z)ilAbi7l4}biTf^N= z=e!~qj5_!y41X<)FS&PJY*?r9J(STFYlFcH|H%r|RGrhjg!|D?ogm(Zmp@WBbWk1{ zXpY8m_yJ5HBSHzLv)+ys>8OE}&exom;Hcsyyw6MdS=BO&f8(hK@=9YYzH8M)&pqCr zwhN`s`E33@e5Bk;`N!5}GMk%%i-1$k@_1qdC%NVcA?#YkPns zq(s3`)0SID(F;+nn(ZDm9R%1hI61*GQbeTi^mjWmddGbmypm3`gM6*r|c0Oe4%z0baf6Z#IjAhDzzw z_uNXOpu4)Y4FaeY|Mn0{y_@l=QI_Mwavb(i&sb zzh<<*nTTu=n4w~P{;|NuR%Gwd2D{IWL>`L*B|;7BekQ5(5J+}>p}`yvhpUm#kZ%^> zZ7uSv!5qZclFKm|JDt7)@!la-!TVB`!du?R+M%qiiIS};Ize1h2b?YA$yNt&ZO=un zzH+mKwEVtnsP^URVp$Bw$+&M@Agb3^d zmW9P#AweCfw?y@%J|`8SQ*vpX6#mbF0NI&A0g2D)WJwlH=mQzWY=xE`p4KRj(n|=` zUepU@kQOM-QSmrlv|(Ag$qW5QP{uhjiyW3Y!m@WmAhIZgJ=xA7Jk`2?Ahst_o1}}9 z;v%IEAy~&vq~c#gZ$5#Ra${jHj+&H`Lpw&|5V)3J=4g(Uy5@s=N8}nR!;ei{VTpf>1!pDw6+@sPtmWoxr#H87H zQg3beDeX}jPb{wR#~<_A_G5ZYUhd+FQHdZ=Q>axKkGMYH0*|%FRb)b$+s+IdY8qvR{5J-Y(^1~i?1N(-N%lz z(|qIO4h*qRZo6|Dl{V_lXSECCUkz-T+?D;qDOJO-f%#vB$bA~qJCrSB1)5yB+paN* z2)UWz!H6)qYA3BR?@j*&5%?N(8!36Wa>#^K)5cw}gv!*UM-B6Ms{h`nG=V}x$h->_8@ zj|um@&&5{{X>f-z!-!FmCiHqRT_iVH{P#yt`^!NIZjDg?q(pKC;`A%NHy2rvR6?rk zS_O0<`3w*Yzw?5W`*Pe<%drA=4N&MQcuoEKvm{Ln&Ot%w13dA?C6aJ2(CqF0vZDLh zO7c(75peF)9wd6|ODVtv7-4^joP>o_uBC!7qn)qM*$Nq|*B@t%B8pxVeU?-N!w88f z0@h#n+>SP1kU$TukqfPxb?)ogA(r6MZDvsZ6H%3jzF7{%`4ogpru6w)N~OIR6sz!) zaqoiaBOF%9UeBF&)9=s0+Oo$vr zB)NoFZ4-IvAS8Nx68$cL!rt%iKc&`G9Q@JlXkoo5)>Q{!BR6Liz%)E!C_F1JD+^{@ zi#Z&CCH-iDnf}ri^vq51R+}|X1X+XIu6A~Ufc1b4F_f6)SuD{0aOnkz!YJ95Ks?P@ z6HsT8*P*fCCIZ+%x$*%3&g!o_>0Qa+Vtr)Igh>O~_vw$Rh*j_XUu6~{2!NCMZHDMb z!b2Z)&|k@tKh6n$Z0d(>RXFUV8rB8UBv*rRqemS1E7Uc~@LOxQ12BnQ7uM?UCXfSn zOK7Gyj)&}1Z1&JxXG@?L-^kNl|HB~odqIexS>DGf0O#>=9&RqQ2I@-}X@4Da@e4s) zl>R^>9SAp@Ez;rXN#aUF;fwy-R!0B3Yk`H4m3Q>nO*J2WK-}#4 z!+r^EC87$3;zy%gul>1VCz*-^?&B%hsJr%f>+~|g>#XD(4@6xN4i6zjFd2U90ZzCP z{iD+iI9x*xOdbVQ)*}u^V@w3gD5JUsJnN)YcWDJ%{E@JgZnjH;- zDp8K2(i&up*eSi3pN>JIS2)kt&U+GAi%gNswpj0$E}|~^90#s zEyP0IlVu=R7BNQRW&h3tB&*O_ztN-0e!j^FfT>R=i*>JkVid-Pd`%FGPuEkJ85c-z zJANTC`NiE8LmQ*<9$uFz>c*|)z9jQGkYh_JQ^{pXMyHtY@0c00X(pu`OF$SU;XpFC zQ9MeYW<@~14;?@A52eJon~5&1LS3Q|#~}AMLph04kAce;IVN^}x`MK5nd zh$(5#4pDajkMOjs7URsF*Q?573mMsJC5^`b+GCdBWE(YK9jAqpJ{>Fd34+w!XVb6= zr4}s`$-(5438l1iP=L9b{-APbiirHHH6UHr)Ou~P-=VD*Vmo3^{#X8)s^Cl@J7#*h z^lD?ero{0bDzB{!bpCf1x5Y61fwZw^zQ;Q;kS3&dGgwcBfsPiC(SdvzL-T%r0;HiKx7Y6H=J%qnl04LFnDR_z-il)wDYG<1hIWT8~88Yyfpez5C zWK2P*F~EfmSOkx(PbvW0HJS*AI39sAJWuKUJWATB97p*yvxAeEN#9TZ zK!UrmcxYScC8$6+m`-B9;17`&@a5FAIS@__^oiSm7s)PfGjX zUn+yJz|5<&LwD*>t`cCi+Fvi0e09?1-Kr+X<_3U#G(p7UD!)US3h89D)+Kd3&UC(BO@5mhkJ} z)zt}Z2dh6oVlBQ~YvV}26QrA`_LpKLmFTwL;G_z_&OyeY=Zn7EWCD=uV49{gpuLie zOP>j9JBHOj)9Jiy{jsNFwrT%xYeLNj5c-=^)i{QrH=NHuN_~8Bj`-$rwAmXcgLsg6 zjUxdlEQ;R|j;N*!m!VJv=(KDgzMKFqmE78c<`9qY=nMS<0ld5$FgurRIRWk-Qw%gF zQ^Jy4Pu%M`AwJ}Zpl~1RtAEVtf#ddK`T5}9Qr8_K85-8c)87&7)S#shS*Zt}O5H~}bJFgOo+n8;auJvq$;S-( zU|65+Y=0%;4lZdywvy+D3mA*|1Ux!@?SgPhct2x|7y|%G!+SpxSYx6;HFqF@5E~T! z8`##t*h|kzpkVM|%zZpxjn0GUq$7pUlTk@g*cjA?HGxH|)Q?}hVTf~+TBxBG$b`VhVQg8yCA z%q1CtkmF2j2#tq=IK|-}(1cR|i&BNM*}|C+*r2T?msxauS>u4H;s4G79&7pA4Gj`9 z*yuw65a!&(cHb<_w?s9=PSbFyhP6yj%YU2wz+XdVrhaU|U~nFnD^vefzCbtVeS!UEEU}=%gGb-be4ll@YFy6g>tFXVLC^ zfSwdilz`EU{o`q;qI_P6+K>Je0jT6s5}$=USIBh~g@F9=?tIBoh@ZtXQf|YCKvvOk zQUY?%GEm@q&j5ZOsSZXt`N^YM;GuctyVsA>o>2Kp??w>Tw)~O$!u8K&wgb+}{cdlr z#4}l)d6h9)GDQwBx1D;~!Fz{6h;wGDYeW7%O)WRPzB{5kTZr!f*I(q}fSVO^3%*6!? zA9)`68t};=s-Y|xiva#ts_h~U zqLX&N&W1k57y;1l1^I{@##7Y`+Z%=LL5k%dQ`6x@BTer0leDB^e;Kl4u*_F%&L*hE-d%zUdCZPl3S|avBAAz}` zu?Ex)jHxfEnfgaqfaKS{KJJVW+9NMynroQ{jP=|XK}J5BiOq<^NKg`*0F(J4IS7R= zMr|Lg4Q^4v@Ju7^f#FtRA1O9hzhsr2NyI2$pdR{kA&AU)=!jG%7*D;OT0MbTnUsW^ zyk-EPliR^!nRna93zFfGw!j0BU-2Y?k|W7iX6xULih((|;c_HSo??Rhop|EUozpN` zbn_M>XeAKH5$7>SI0p{BCnq> zNTjw#`{m9uVLUuqIBTN{nlz)Kf2QCS-Gy1U&P8u)+O5`sW)_yXv{Be9gZ5PRKDKsg z|9g()30Fq3v&?fv4(;OS!J!JPL}>Tb(yiOtr5`dK^c^?_NF1D$gE1NsXsC1uiSeUV z!R)w5acZDb7kuaESzJfCx?9M_cJ_4Ni*2DJ(%*X1buRe>CK9ZRZ03$&G-{S(^!aI9 zChksTIf~o=V+<1OwkPb4(2ze8w?i{fCl7F7v#3Qb!RCv5(Bin3Evd==V0pnL9>gCQ4O&J@? z6_m7eut1T`*((K9KDlm6>?P`$*tJef^5sgZ7>GmXEmv9m-;qDCd0`o{7evm8S8HDz zDn8Kgoq?x5B0n7In(9|#oL zLM-*hr|Sdj@(;d5vlbZ8YO%;=*=Zi#GsoJ+pn=Gub^3tWAg%k!oO&8Tq%^oDpy1IB z=tc;*?HC??6rs8UiN<=0!G*2OD|_i~CzNdf6Q_RN^_T?ly!c1JolKs#IWb~}&><07 z4m4bU<+cO(NpLlT?ZafK1=HaC-nSu|E}8ELc<$dPrUP<-ZKhyDdqh{gC*PU^cZ;b{ zvCB?Jt1AiO&syK~R0vN!<`HMv_4T5wC)XE2@dZ-P*x*?~fxdzK3#&IsW+5-7m& zaa+T=A@^2QM6KxWL7?PGNcu&q)&xjgL91O**IhN-Iie1lOv-TsVa$i}qB)p6cx?ef zX9GLNbuunFrSEama|1|3V3|^1KTfv!h7P;cp<7Pf*;7-7HEz z2SMD2`9ai+P0Tp=icQn+vfI`Ys4FN?o0HN%5k-!*4F6J$IX8XciKt5RY3IwC9liWo z_yoeghNURmLC*m30$Hb=uw!Abb;%>puAR1}Puqv~_~Qq$r#lW-V2UbZm!fIly2#_1h?I4+9Lv!`Tj<%<}1ZrrhRI2lX$fx7IrhmY}|D9w*!qLqt&Hjky z1ZN=@I}2nj=^g_%jVU0{5P+?A*Zm9+J$?HlIuSIK1@X{O6oj;|B)1%Ssofc)Yy4ts zz%OK^3Y7FZrPyX(bZA3wuP2tpo}-xxce~XIbD0#r#X`RG=W)ngTp3dT1E9riP~wdz z(Y-PCTMOEb(~FV006(+!LRv3W7D0j435=63cU#i(gOP#=F4+8}11_dBK9B9B-z^!c z5~3Wm*RA!0a1MHl($*sB(4SqjzQuDSU422iW_aS_&v*|G$AkqQWQOXAJtIHi{XW{3 zN{L{pB%>*|+8YP|(}F2piU~}jmPQRHlMkfbBY2vgzYZYJmymA$Fp6bpl1VA{s{g?% z@z!UgHa)kvTvUlG5et?<8~2_weK?ZA!{Z!FvR!lSOwZXZv^GT)RP&iXdVg%I!cr%p zG~<*gJ4^U)iSQe4SC zmR<@4Y4OWZ`n0tpo@Lv|bgqotlI2sA_zKYv#JyxUp43<3mM$1=JbG&+-2-oi=L04+ zb7m)ID1Zg|&s`e8cS9kjk5MMhmtrmlomt;EU`)dBQH=!*-BY!P?>`j~(;edTXcz2y zVLoXnk@KdJW62Lo?H($(`zzl2{O#au=9d9WWD-L3(r^hP^UiZpW%(9-G&tJ5-cAJL zBd)Oo@S!QU|8s)&&mzf;6jk&8B4hi1@fBTyK7ZJMR=&~{pUudqnq+3LC*C5^ZEj8K zSWH-RG#)l8d2bC&08tF{X+V>W8%!d?C{I!hqENoQ#oyoVjK0|A&W2(>2E$;!yNv*G z==mChtdxsu`r?f??wa%1mlw)vO>42;>(A_k`jdL?d+c*q9{1?$$Ijjf4I$YKq$+P8zbJ4Z2M~*YPgel7(t6-h=*W?xbGE1I}8M8_GO97__+ND&3{N{u;x{K#ky#;ge1mp?vHOPXM)y$oYZKtl?6T<{PZFt{gh3S)FY^Y#vu*KxW>~^6kwuze*;GM?R2qfu>fX?g zK-MjKm~#n0Qy+-y9_q7RMiNgEX{2)w`X^HxcE1Bb+B6-MEzaaGwPVNktLan&tQ0)u zj~^!lb;SJ6-#UUfcS=tHoa3Az7mZ8rliBxBk2-@=J8#sKuy zvWYt_)+sS=3qyirtu+wf+Rnqfum{2J!iClMAlS{P*a9HXkPs>&do%Xi&dlaCqQ+^S z8^jgIk)gmXx1DVNyB1*uF4LbOszV92z5i+MwJGU4U6uxp(C-Mu?5Y&O_qA#uuY6cc8-anug zd1GVY6$Y}H@PfFet7C(sNu;PT4dNj&t18|Wgx+#YMfgJr{PeedG?1oju_zeA%858H z=TVu=B=Cg_CSS{{0KSdVH%36rtPyYc7~rKeusA^<#M>dcfA0$$^d-d=7Fz_Kd#*$*1DRoJvTkLlst?ZyV+q~%TYpeLm?!D%GI+>GyXNN z)29%&KiL&C#p+N?08oT>Z6IUxE?Yo0pj9)@V_Nj>KCchK$GWMiTNt0@O<4;&%kk+t*xI zdE#^DfhR%auJDOM&3w!K zS|LB4Jj=|abV8Www%b>M@jQh>z` zi5xnryKXb0b!un#pfe4%`5}ao?H7?X-@(+5$6(|83oGEyA7yq@Qc5h%jn_Dt9CdgB zg$WhF_x5q#eItuMcyDv2)GQE(4ujxC3Csci-~j5SdAt8_=G=b z#68v}Nn;qWCifFU8~~#qLvNJ<(nIFRF7FHxE0Auq(dR}Lp334;K2o?tgcdOST6ev7 zK$v_33k@SMzhLo4M$MgXuy?Rq=LchS>Bxdox+6dm;w623j*_vzQD~$LM0dU3^n#8C@o0uEfSZ_GeOkw;eX&P9gVOqUY)X-+PcDX}keq;6aTz;Uu-++IK*os~W}B zCf`RrHv%0Ht3w5C__awynz&odPZnD-*i%>fO^|#3Y)mv)@NRwR2?32*!KX4C67-B( z+YV{4x8leUo#q*$k?|4?hqe}=c4n+va}0s;{B96(IrJD$rxOOX*$LMW9e{U%hZA~U zeQ4TkkFY2#9z-rZ*td_Vxu)yJA>%G~;=%s9(AuA-LDQYs{#$=eK0ZtL0F;aZ)-c&; zBJ-kr%S2b$7`;z`tS0)F7-}pp9E-%n+Xm83A1D&gos@Y+L>QxFR+-$xY;B-l4VCgs6P!}aDV!L7 z*sc4_{AwhR9W%6!fX5cmXojaXR;o}1bWqAKD=BRyg?pE?2EJgFWLrw%sU@*77i{rp zKM8HcDu<=~aQl3n1?ZCtp`9!~@Q+~rc8O#SsbXx*tPo3AtE!I*1xSZW+1HnRw??wq z?tCnukEXQ9IAVdnF3Tlg04tk z#n_6eo^T>x#yseO@!m`Q-fB0{_S__s$oz|5F{S!xiV$$*>>1@Fhd$U3$e41e6>5BH zgU5|pwXskB@%x(d>;A{*+0yl)NkcWEfHG+zj_x|eTYEAbgh-uIL^u)Y`F|_iTm8k5 z$gQ3uJLRh^Psf6STEd&1JpaBmDD~l+m-M!Di`IY2+o!0;bW_PX>+5vSkH}lYfU5gXdUFsc6?S<9>KN< ztwm&Cj15T$LQSndO1VlN{FE4H0VyZt6z|KuE_G_7zLyv|ssQDvga6igiR{10cIF!5 zrrjx3PN}ewWWQ5pN6`=^Vl629DN^+PT{DFbG@`kB{Ahdre&UD#D!Ko&H=x2RO_&0X z?c4mS0w&UvrQ2aqVNp1f>fI9q)@5b0<1CB|QK)xFqx!EG1;`e6U*OtV2;X<^GzrN6AHbjgPhi;p8}C8SW*far&5(R8yzoE5L7eX-dURn@ zf5Sm`gg5JXudGmGVN`$pA9XB60A%$4wGWIzxrOFBj``&TD&#ti{ntbK_l04EH@E2i zwGa%IaQ*j^$lPodLamZeETJEH2=u^*$UfRSv)p&j@B~%~~2!csplI34|C`)`Xc)~V;Ikp1LyiL+&5sG&iXEi*`R{2zsV2{e@L|9)k{ z$TCB=L0Lj?2}6@@Y-21fLR3VS6dJN5G1g=-YAjhIYbbk`S0x!_8?wuUkbMbR#*&@? zJ@xy(=l6d9=luW9bLPxE&Y8KN=ed{9=en-Xbsr&S2xL%7MfmI@RevP_&FSfvzYhC! zftmac;5u;0g+OLxiJ#==W+dkSUm_h~p!59f-7ihwJ%@#yzG_bI&*m4s0y>|+z1MI; zy>#92z|@&tz`0&2w$?N&wF?)v13@WWp8HIudgsb}5Id(%ZsIIn_To=xg4yrO>x;bH zwy$b}m|C_Mt7YisQjBbfANIsSx;PcYgLO~Jfs%)=VA6Dddf{Lz6U7(EJ}@dHIs$Nq z`GK-tQFthjlt4FJPRq?Np{hXPfYz77a3Zj`OX8(Z+n{edGDA+`*oBl|4MkS@ZSQ5z zAK{gzcI$wo#jU}6!7}|1+ObZC=sa{hnEZnCY{7HLsHH7ME0BK)!fu%;! zMJiw_nFPwkXb|zz-KD%4(5fivyMTRvpm4pLpa-~Q|BX>5y1ZovP>r+V{Gi;8PDz5$ zL{dNL+*Jb>m#q$9+C^8Xcn;xp2P}Zh85N6^1BD=>AbBBs%ggQ{)izUORXm-!eGI^} z0|g&k>{9d;VXY5n9bnkieY#`|@F|lZ$Yw0}Udvm?NZoFEuAl1n%giq(GSD(phwVSq zPjkp3uaxOaigGOrL)!9^>7`^vqXAvZtw)j!K?tKKA}KOfYV)2T_qkn9gxjPh2JCI> zvN@C8EQWK9CGqp`dT#?Y)-rg`&A=+{c#mp7i#a689?wiBZZ&S;E!QamE_$VQZB!p^ zjG$7rF4Y;!x9<-?k`HqUVs`Gf5yf4_XcJ?hJ9DUSqedLcVx|DzW?ep zD<;V8wwi=ql*aU3pgr#1RUsl1ms(O@Za6aeYrguZw2WP zuWjxXq-YU8*)3dQa=!;St=aikU~hqw3#t#+I|+SYb+P0 zpU;t+B%@GT3yN=ztT~M!nKyq*(C+KBBVDM{^0LXfr56o) zV5a+MPjerm2JOkMOT&W5^q6ffU4}o)jShr zX^>7DBhRb4Qu0H1BjrYJesHznK2I1zD!}lo0yPZlz`HA7mxym9zmlrAi4atp0NSWi z&qWjK04o*?{M=?X-T;kvGzhvS`eAd-p3T})-V#$H7VyZ`$m-KxJ`$8z*tsgnQPfQ! z^M)aa#NX~vJX1XQ&4I}qlH@3Iv4%Brn)VUt3?A^}?(XIFR%}~}gwrHg0qNS(PY_=` zP8NbsdYVoJxfr)Rng7=%W^S}1-|j1**2>?gX{s;&=sNn?Kf*p(p^+eGlW>bLIU<)~avmFH7L8A5SwZMrCJD0UX69<3LxC z+mnN=_N+KoTTW0&$H5Ca%nvUpuBRXujjTmFf#S?U{L)KnJ(W~(2`^#9T63vY5Sat|1+dB-(Xyvd}=bp^s1wuJNLz~)l zjKZqTd`^7x|AB0K`E@ zF|_=7$>TCEme0c&kOP~Xl<$E3Btu4A0z1wVIz?j9byK2SVp(m#=`nXNWdxoF;FxxP zN+9iiPb`gpZN+m8NTL?92BpQZkcZsULQ2_YGFmrfyu7{hFk$KU1SV-%rSZV=qU;u$z(9I3J)7y(5J$(w9APCR$lXXC1FQ$UhF1y}%kk;f{n^N>N?}5UQUg zbd%)qxk3AN(Gamh?P8s?p)Y)7PqcE%h(I+72W~Hnt%)3;*I6A`6+!B>s+ewFARQk% ziJ4g<)dp6d*;7;9cXp5*gO-dF5m=>EosKGDP!V09IN+A-NDNCz$~ zt$)I1gEd3odVTC}8-$<5Jay;!x_`c!BA5b_nbaNi0}TZL*pFIyoZhWf{a?$>TJr`74Li{l&wY;4&B(0AzP_pN+9 zIZl~93vnZJAz|G7-0(px%){`kD+-WX5M9Gg4H7GaLI12F*sWfdivbDK53i5Z!?Nu# zLtVDpWf10;?9tV8<%t-p* zEmoMjsyn2F^6?0jYji1|R*0C$jQ5I&U=gAtbb3je`OYb$x|Or%sw}C@@$&X@*>&=D zBSnHq-j|16I^unm*(r z7QZ$4A*~~)B=_j`3<~8Sa{dOJ%KDR>a^LDdtVM$`@rF57jM}VHEja@{#PnOC(TX%3V+nYfiTgqSxge8wqrtT=^Eeh zx;Ppr{gbsdWw8=F0Oe;q%a9!U=z8Puq)XHG$cw%cI9WT36jN;66abwwYG1F$G|r$&QGN8WLs7br-@aQGZM0TGL%m*9P;ps1lrKI69to z%9dZkW*BNae)m~zyK!_@XVAW}EIBO|4^jXwpRXMhY`BkXG`}nB#DH_f8&xd_ zp3Dw*1>0|PT3@tM_d`^lk7wON6R<(8Y~x& z9HuIvSX&(n%d_~4@0N7E3lu&j_rUVESVYv*`f(?YA-v`n(UCWf0DP0s$)(o4co$M*vya9)nHu11^u0}iz{gukHq z(Wh&DK3z1v<6TB04UW5pB{tKd8N|PvHe{Od zEczq_V=ZwA{0P$nY#TaxB^JgU2o5Oy-v_TqLjz%^M+52Cbo1ZW)VJ7Zbr@+Mbn>Ew zc&g;!`>XtO`Dyz2jx0yYeE}1w@$>84**J{%iDi{~w}q_P*k;Ri!}75wr?2Iu+-+uU zc?P7HCizvbl}=oN+Qt>IYsGXM#T74^pd5|Mt=uidql4Se-@pF#^4BwOs)w^^`jyT< zjsaQFdULtlR-V$+sgHAoj$c=2QDGZBkt{as(W;l)%yjqiaqbOPd>LQb?iW1l%0r~F z`1-|ky!$KOiP!I2gX;RW1z*}BkGZ~pEPedE zn9`FB9ixMo_P#g<30!Qfo#Ls?xq>86^H7menR)hYv)zYN2mNvdGW#{do7o-Nr9EVC z3$ZIv)y2!g5ObKJ$S+@-Pn`D9H(gy95E$Na=V%V>Dx&`VcW+{;^MvSU_q;lzIQ%ua zigtYrR0tWpki5(pPFwOs1FooD;v=~XjnZ0~OWpc>TAOSlzc|(A8~|pOQ`7ZJ zmyjb?_{q43mPcq^R=UEpYq9acdaH}TEgI)~OuTO{KM08mwL@g8C7o{jro!HP!k4)T z{B|a{b>}+0fTuDbMa3W~=zNJsN(tvWB+nx}rn;g?-hFVuH}VY!lOyLf!jn1!q1Fpj zQkMvbTa+;Rw=c zMp*{SCbpo0WmD|B-$V2?WVBFl47Zq~-9QFRRb9^!pc&?s+ zJP+d7ZG5!mq|(o>ee{Ypt5SSOdeepkmb4D+P8}G}WOkd0EhtFfh+0h7mcPKT-2N2V zhkfF8``rfW_gHt@)<~wiw;#*`%w~Uxbh)>OGvb$+P<_!ptlr}hPkO7=m$K-(uj zfSFzAmA2rU&?F)I_-QwS)0A929Q=hacYpRYfXbdhcDwn8a4q5OZQ75eJ=g~ba5Cl* z8L+x8YIl>m@bqktD_94EtuI0 z@Azj9eF$~x?=rcOAkwJu_UWb8C5P2;LqJ2CoTVt!Y#UQc>R+hy&Hjw;P|Q$98UzHW5GG2W;TNHC9{dU*fxOt3_jfDuSaA26uE;I0Nmo-A$sDc zA(uL(<-p|mPG*Q`aCRMgCGu)tJ3u6Rw<3-(ya>e#aG@}-Nev#XgPf?^aK5rW=+*Ii zHpR1LE3UFVK%`PSg+FPu0&vU463J*Uj#g;k4Aq;l&`u%E8oxD@&4e#_8pVksn`^C{ zzTUL+BTY+>o~eA?{WV}dOr)-DkB)jDlWW@uoRgU2QwLawE~p zdR&17R@!7hu!SFB4)d9gdA(e-C8-!`y`_Gn*ZC#MiVBA%0t12%P@(xYg<+=*g7q=; zl8|bh7A{KA%IvPqprF2iY*Ob17J3(5qw3MLmm4X0tD%k+C(T5P;YBml!++h*k zePcx_GUwaE`p-%4GGbzjhn;*OeYG+b4%E*G;r+Bwn&8hU9^_qlo@D<6`D*)ps&V&z zQjL>Bg3W7W@;v8}KpPmB+FUry`bXSBQ%cE_JpL3NTpKcHJ~b4zti04i2Ljs^-)C8S7!*!zcDgLyvFLx+OTn@Qbvvus-XI!> zA)MBpjV@M_EcVTTy!;T^eCt{Uqi(q}qC4&RJ#d;!s3!qp1@3hdwE)fH^K-Agl zxfNS7@%+V^0Q$UhoWJLqPT+UbboU$wC93kTH~M`H9Y1da=4aT z$T=6#=6B<=1 zJ%&3bbC@j;?nk-OARbb6Yw+pIhVQCGsniC2$Cp?(qXsc*WQ-yy$802iQ~bw$Y@7I_ zRNau@;SnnrJp&L(w*<+G%aN8_vCGrTS8d)-;5)fced`9RC^&_J*+eCpYc{IsbF@adtf7)Wf>k9$$1?Ed9!n|k0&#+AZe34(RkeubuBZ5CWGx4J)tt(vL{#GL zElU&bd@d=LH=x3l(Z*yEM9)G=T29GDnW9%Dn~MDfT|G8h=emfImMeQ(kxzp0&bD1U zUe}ATwG9$1uJQ|sw6RKQ+_8WinuNp~b^RX+vUx1JD>u|5m*ZVy-05OHR9C*&fsmfy z-eBv`0$oHzZO00fgj~R~J+n?dd#KefO!Bdgsp%V~^w=IUE&NTS$1@i-0xKu5U-E(n z^Dlqkb9whyMu@@+s2^}1{~}|{TUd6NEj90oL%SSb>Kgg*8Vln|~v;s_O-}xR^nIRc&p2HOJy+%us zbSp*(PdgLTvMKFkN6@QdB+z`@q++`KMf@m!>yFz9+`+LKpSrtuf#U-lj6rTtA zEP=Hy*2ZBv1wIFEF5%#K%1gO(yS5Kjl$kfX0?HLwzkp$~&f_eOzNi)@TfvFilF7~? z8P#?Tdj*n0(`BYLqqhN8Yd%!(pE1?IYvpuIcGQLv8t(sb7{);+YCpcRxxk{{U6j5l zZZQ~>Gbt|S3&j?-Xp1&)ZNs^|#&k6}N%hgP)qBdpun8hq^HuJV6rtU9o;kx)j~zy5 z#7yGu|6&bSpqP4Ly)=5X*?4RR-Nep8C5EKuvRD*hsAUUM_XoG)Dlh)V9;VSR0mljs zTXKp%*45U_LbX-&Tvy@pzvjo+oSWN`xz;2fc9WZj&z!+DHb*I7&(~JizQrfZ-!hw+ zXjbLVyB|eNY%s84{GE=)bAZyUx)u?$RL{rhO?qeQT>Vxdhiz|0Jo!$`^FIf4GHLMy z%~pn63jOjw&mF0>(OB;H^2^!cH^N@(L&+FnAzqO_%v`08?IW=RB2u5jOG_ z*z2_|RXxQ%RP<^pqL<_*c|SN8{+!jnT$!M{_=E;uLOWoKs-T(^ zLj2~(=TZ^w7h9L3tR;0rg+)IVDBKzlTrq(g7V_u$UrWeTb#9s;w8r z8jb^lrt)MHzs)&u|AE(A-_WHzM)DlfXz@SY|4`u028Y&c2h!$4i;@x2(HL|{QMmGe zlb;pe7c4I=_Pxp>R-ap0?bS1BSSn0)x$WUM_JPrY3cg z)+CG7x-zp|9n5Q8m3URVN_g@uZuo)2B;oG23M?_{m5(KZjWzl_**MPlL6pyA{|tnP zSTQ|}=+O>0EIoAsxm(y>bo7E<6+X>Ns+(O$c-WC?e9fRJB4;yuV!7&1>hy*S=3a=d3mtF~@9m_4Ud>-}vVZz*89h>(o;Tm{IAEnTykZU@rRn`uh;Y{muB# zhd*z4^o29*y1L`rL;q>i?>AWLZMHwj_dl;viD1Ic$d*ar_;=HYIiC^#tDW@Lnw||L zCTbg4DIcffJpb!3ib4JB^C6L92Y?7YO|5#M_CJmMPXjX~9RJhq|2bvd1rf#ZsQS(L z{`)S19WHwQ-Fm{O4Cq-S_l4GgJW>4CtQ4k$LK}B{1 z6&yqsQB)8CWkelC5&keDZYb!ms30<;2&ka<1ZJ)<*Sq{b_x<#3^Gi?8@|@>9-|w^Z zn333f)-(2g#!fr!^empE$2;w`GY+nA+4ZU5{XKgedge|$z5d3MG0LcNgV5P&2ikq? zY6k-ONm1@V=^Y5dgpOV2NenK*{V16SZs5!x`woE+=pYC?2qGp3x&tNA7I?#mgIgWk zdaV7_bK?K%NJ#1+45vE~7C#sQUA@|X;TtGmfgD?KRCboSr^5|@osXNVs#|_r3)+wjnV=J8sapoDc1J88@3J>!aDG54m z+N_ewy;{%pp&uJbc6r7JC^)p8AlKoqhtv}dBgOmjON zLcQD?_gXP(8PJNSB5you)se)OuE2xVEmFw0F*!+Gy>F$+X4YQflQ`rCU6sj9dj~=# zX}U1{aE*CEwpc}5a4Q{yH@=%7w7}MK#)OdW7qUi;^C%u5gBd-FSiC*OCQ-`t@Og`M zQiJefHc7KyF(t5#ZLv>wMn{`oWy5x7U z-c;Z%2DA*dHZA+>QYp2tB!IS1dJm0iJLZ)DlA%S5A*#_ha~Nthmr8NbcbHZuoex-C znmJp_E^u;Cm3mUmMmjsJ$Ue|X%J2*zj=n8-4XmSgyD>jAHCNF#q?~kN24hA;Unm&~ zl0jn>qx96HEt?HV!!Sy08&?&+B>L?wmlC6T$s60=jPqJ_uU?GhmPz!misazF(>&d* zq2)8()pnEGX{8U`dMPHW0qJc5mF^f&IU4FZKFciz96foa1Vmg|kdTzWifk}={0Ff{FT5hHfevejCEHTpBR#%wpx zpvG08^41SggPHB(*aOEwR2EHYd7L58$S!&!ag~5dKhdLkU~_;Hd_US9kjO^XulvNbCHWiAdqT@-Q)wSx5;G#t>;^% zz}F6&S1vF~wn0RQ71sr7w?=qp)m?1xzLKFULFiEPNzE*5T?PWh+)Bb$ZX02%NuKhv zy3?DsmvKre>R9V_DYacji96_3+F0(dj5_3Odpn6tLP#6{5L8|J!jScOW5c9gLfdAbku59~D-$Go{9iAir-EruPE@#S%xN@TrK$R59K z4av1ljG=x4FoBYlw#I3bHY@p#)|;kY2XrFx6B;%cV?qzWJ_UBKBh>9azFCvQO_+PE z$Dov7jA+h5#(g4T%GPYqnmN#9p-cow3N6lNlo&P^Ayx-^r>*uQ)&u&d#sQ+R3^Z1~ zqAiPEdM&OPKg4{XWNtF=C1SQ0u#t~>m*Aw}>QQdFU;&Rpd=~Fm0?$+h@XhG4oL%UM~`@ zMNYQY$fiFOTh5fK^rRO$t!*sj&IEux%a+m1i6Vb8?X;x4SC-ozPpd+IT$F*+7nd{+ z@QrmdZ#>D{dCQq&5i>~o)(C3PTj@X|l5yhHD|$Nz&5Hh`GmblC0t1Y2rLNoWXK==` zt)Lp_axt_s9beEJL5w@RYwAX>EnSUwmPt!&!Ah`J+Y-CVdmA}uZO6lv2^JJ9%gida zy+9n#hyt%oDxTvy7R4%+K^;zC4A+W{24$OQ8&h>*l`sy?0>XuLFe7NHn!`HAXSKaB zFmnd_g9<6FJWlV#nupGD*uWir1wfms;?dSwum;Vo)?sI;j3YHr;B=#?!v<)aIn%KL zouMqfBNs$y;Tu$_V-xm?(HvdisJp1)$llOx!tK==)i%NcGfaze3kY2=mk~59vv^f5 z1s&?p=%WDZVC_Ue+{#&r6>K|O+(d;Q5{DxJ9$6MVNwTh=dCRFFRl}a=HYd(C*`bWm zogiz}rW@Iofp=yL9UNm0l5#xnwB*(%#V7E%4bOuvfwUWi^;4+GnTcJmhcrJ!Fq5i% zCJAUCu^TQR$Qvz0$6~jmw1w}L2w%2=0T8FGnFsgxOc zu{SdqrMob(1uzoS#*6aSq?dG9Hku<-Y;8yjc`X3aw1MYrM-0-k*9Z_d{Q`{6ZWd^3 z)x+?{j#0r@n+Gw;I}>uT0Hlx&C6Wkjn}ym?=oiH}NoGUJHU!=c)9H5O`^%mkg@PO| zA+w^TX$#+gr-ad#>`bgqwVLCy({S8+8v_==j#g6LAzOfTP!0s%Y;LHEOQ2*du)(fM zHbV~RY5+b^#O8d9oJaN8U9C|M(8fwmM3P(1`^}?(MHX#@;1eKMN&*k8MgeQDWeHqU z7_K?=2u%S?XIn(Ov!+LD6AcQ64~-6!y1mLJngwsDtwwR0icERVWxLwYn9`GZDe)2k zb=SZLi7N1;!YDxkd0+#+bHr@N5Y#L=+S~*uc1;&mbIGXn6p38DrGUk>Z zRkCmpsbW57p_v(EA~?Oc#mkQwuuidc86!|f3(uHs<*drVthHPp0o!h{CDdYjm?YUr z6k=O?W6v8)M(UigwhLuj!}Z7;!RsE15ro0Q72@nww83Pzs`DdYNPBGZx)62^K_#rkpvhG!e8ukcZGn&zW!Z{u(0 zmPbgPb+lY<#?oLGz|$6&=&tRymT`!SPIFY&DYh2pokn5m`5IxoG@1h8u%mp2bTO+h z^MEna0igrL2xx_B0XxtYl8ThTYT0HoULLZ zDpp-A$`{@U@_50wn@2l1&yO2JL9aTgw;in7<8B)Reik6A{jw5!)p$8j6v}r@2luzW zVkH`-wo;aKnN(!Ares$kRq+fG$6OIOlfcmlWDIYux{f!_61N94AD32E#n#?f#)*Ny zh$CJz+g%M(bsNsvv7^s`b+N%DD43(v7+FdQgS#D7&IB-zTIeV_VGl^MAXPIb6LYZU zIGA3ImDzGIQCh0a4o7QC69!Jd3#17)zU#;E47eafC=oN*p4H1hUb(y%%(b#No=NamEYrR(d#2Uv+L^`KQ5GdQvw)~gN2$+w;goR5;mKKg!-tpZO&e7R@ey2 z^m&NT+8kb3(`1`%d-Do5M)E{(mCZI}N4~$Lo$NG*Ja>uhOzX(iBtf%{rdn~@VOAG%U8wYQDd`h9om4M&zU;EHv? ztrRRPrnq4e9UUw2qFgjPx^PQpn4p?XDx(GgmUZJrvbh-;03xVJ2qN3iP)FhD5nlvM zPug@n1~Lb^Z;b+8x^zdVAkD+%03L!? zT0$jm6s(71W9S2zwbogR7nGFtEeeo_poZ4Uv{Gfczeej)>d2{L3+vh~I>NN?n?lhD zidalp ztzj3SFsnNVc<-(8io?NI;AKqUX3;qS_bj!lW|m@mq#915gfNLlT-={7;bp26TaIBC z)sSUyXx)S)NGM0gApEx4z_=)FrLvmOCTmkkH~khTK_Ei2Hh3#!#FX!;c)l8B4KK+d z0l^h|jX?si*MNa_3Vex-R;oTJ<#8IVXQSAzOAUkrA#5>DvJAA65TDiIXc@C3(T_5n z-wr4#1TIIqPWfTmYOk{4bd-sa+S7`OHcCW=5h-yhjY0uUjd0Mhp;&{e4scA8Y*lMZ zZPKA*1?Pu=S+dh!5SdGM6G5Oi$dprR83iSEVsPHZH8@E!6N90jH>>4e+x|Oa1}Hp89@ z8B2HO;Or6}b%neR<0UWCT~|x{P8d_pv?D3QveRBd@OG_c@iZBB;j!AH#FEG-VB%8Q zg|H}+#zT0X6U?e*7_&`^bhO5Tls=$T)hY+9Zgaad@fW^0G z0}b;@n+vjfL}<`xxIkv8Y2|zeiH!~{hVv=h3Fm6bYT>l8gj3Q2;~BZvbD+L41v|h? z$#l61xxO^wHM}ihi_JvUw}jTF%y}ya(~;_;y^RneYHia>wAwl|&_yemp#3el&T`~VnU>N^27*O_02?^5k7KqR4T3O_j}te{HlEE^0>X@- zDcM=FWl6K`MK&rdcnD1=Vx9w*)(yQelLj)*WMkV!+!*25K{N|(d1c13OZwhM8gHa( z5^+8v;;hiB>#4?!4Ray%dW(%9&D5D^QYPb$#~@H^uaII{(*->M9_lcMDG(7Mooc)& z)`rFk+k{v!37_h*A{I{9t_JBsh6jWB+%B2vwlz&yrHDkcN*1M_cP2UA2k*$bH}e8f zKnp08P;9)xfkYDlo3N`$9n_HP8)W8ZO;&-5#!}RT^V}`AKotcJ*Z|WCnrvYx zumT~@HQsYS>10H^ONG>wSlPMdt1>S3+mZC%Xz#fJ3|d%(gVUad~klnV-CO4I#hkazL%Bn_KjVIOBq zTc3zw*_=l@Da^?vgiNp7RV0|~86#>8^~^rAlq;}gb&!vlwqyCsvQD@h>8FCx4%Czt zgZ5HKpdzrd;gSvOA_JgamgQW;x2_bf^(0=GfwaLDFv^;zEypvR5F&?0m(+6@>)LiR zo8$j1|?Pu5cula(ZDJApTY>%!c^gTi7er%kWmcH%FUkPxg|0x@WHB+fTwWeD{7^(Dl+Ga9;xRnDs9`pyxJ_Wg( z&W30r7ogc3n3$Ey^BEisjj*M{^?14UX>(vM-8L^9sR}{;-0-Wh58Nwi9Ih&8DU+kZ z8RZLi=noo3#&@f2r`M`SxDSo`7Li7J-UkT*l+M7(r55Ofo~IBu=!`Qx4J{Ba=^IE= z;tbvIPev_3*(VFoZp88}&QSY}<|dd9ug2w+XaWu3JI$XGjfw2@^PsJn%(yKzwwLX< z(q6I(LcVCWjic67OYV$DWdyk3$}t9W2^dccodqozMDvxN)R@ZV$p$-mQ__`*@@skJcgLsT*@NN}M+8x_&Yz;>asRhoQBChd_)}i8XSv5jw#%P&;|w zEtFwZxB&=2S zfCYSu-JlMk6QU?D)*W_{jJ;8^iKiVrN(f?H5g}zqjbs}#*9&EutJ5GMM}4*t3$6}g zZi!K`qnc7rX-0&Y7Cc9k9CEyNNmXogtkAlU+(V5j~D zBziQb*~j@JnXT{|YRp;5ksV<4V=F?}sp3XMdtk$o#E;@CAs`5qR$K>e8v2Xc%qLQ> zSy8++yM3}mmjKluZn|#y-DbPNi;^FOxc_IA`+KfaaH1p!6y@hymCox1XahUr*~R(CvSndL0+k5*=z;zLF;`A{FUBcR;udMWi` z5w4(Ol8gY*nH+<0d|K0htWaF1@aO$}?NVyKa4OuB;z423^KA|}k_ojVHr}M$76?cI@ z7uCue&m#@E#%gfwsS8*PI-lWy&$G+Is~V$&V?I3Q8EZY5$aNXENF-RPEpt0!l6uJV zTheqI6R2T}N?3I=lTM=rM9;!{9LPo!Vc8B1A?uLxLW#1R8x49W3H;8Lxaf_gz81t) zh;I1x2DnK+GaUL$m$EC%E0xVq_thd>akW2M5Yd!3CX~w?kjr{qJ#I6tmFS2*Xfs4|vZMxi$?ZvXqr2x>-6>&vX`;yU^%l z>u!vE+iwiM=6RUGtTy;?0a1n4+S0UH;$CKSt9gH1rCACZp;p~!g9t9I!n4J#?+W8O zU5_nosW;BZ#*`wMTPL{Ok~6H)ZL8>M$jXLA5=oNzXo&`)5+pK&dMwq|UCM;ECNXKC z*+e9)Ka&R_gSsMm5x%5*BMC6FG`I9E%iDv@%v{prx0Z^mQ8IP3=Bbd!b4~AN#HdXv zg~!yGK5C4FG@FVV!xw`!m2NwVht-KPY>C}}L znjq4_V$+T|tytjAR-_(H(J@Mwi)JhIN(}@U+8EMCaw$e!uOg{6&R2l@*L`a{8H57? z<&~B$P$Dp*K>sv}gBmO5C)&6!8q6%=um5xhyYe7b%po&S|^Kua%6KlblJ!S zK-iwq6wSoIm0<%4S`icA;DC+>oryGAI4grUn`k{cFr6IkN|ULK>GZtC=LlDk4a=aW z)=En~p5%Z=v^PC9GZ!0rw5W4B($E~op#%=aOk@h!YfiL3%HbX|%p7S!q`;Z3ePckO zK86jgIFIM+zSvr7fMc$jW9$q7@!intT-ye8yH8~Dg3Ae3P4f9DO>$$cTD(5cLg4jr z&4Cq%3R!7GT&lWSZO`beQ_FO2C;p_-zIBqyRSz^<4G5KHFfY=ZC=SKs6S?4o5s&az zC&n$dg>(svGM2=AUI~+Et*wEhzLwT1Xw9x#;(GJH1#hBL{@-DnVY=?B6%EP52xB@8 zF?}`#0QMNRg(dJpDIQdfV6Y-0T4y;9x>C)ND>XCbt2|tx@H*61rq8>J6s{+Hqix{j zL-D-C($>sMIvYV@))qDb(v9O~+xLlSRRU45eU%8N6(hs(sI{3*IctF$a}$)^#8tXg z2xCEU18Uk^dK!~a@|u|NwOo^HL+n!NL}U7!@mM65eb;92wq}X`z}BNYH`RQIgGA#< zVS=h%i@D-dS+ZqJTvr8y}jD6Yj>&zzu! z*`fi{r$!K2!EMY;1{(v!ycr4A*Hkv{Z)3C-DMKAZQ+sYd&+tVV+L#|qL5ziAwdE2K z-7RgBiq-E8dai6wnGA3OZrm8nl+LlB-&%V?n&WAM4;7D)lU7!DX9A@Pon#ytTo*9? zY^hTk1_7q*Wd*(n;)wtb1I2Ags-6jQ55h1csFtE+jN1XJjP-=sS_z68!?8UKQFjPW zlLZLVCbbL7+S+Yq8uKNX1@Hn`7Vef5Rr>sx*=i`L?l61fz-+DZ`9zM1Le;jK0BW@K zPQe6FG3?JhFPTvgh|~F#Yy+E3ga)&F_+-s*#l9wQ2pV2nE1YG@u#_c$8$G&JapAmJ zWOP<}lQ8rL9;FCEF~}5uTY6}#=8tc@o_OHDJ$4?(&KNViS433{!K({6M`;7uEwXvG)pm#)F(p`W7@RsXA=-Up?Rpa z6=_h5u*yLBQoF@f?QRz=hV^yJ7`q@C5HW%+=Mo4;P$JEBa!_HY5}q~hD32zVf&8_p zftr~*2tfKCK!6y57&W_X^DQURSKJmM60DU>au9itv>4G;6b9Qvg?2~ma9hr71(vEV=7dDF4=CAnQlm4Y{lJ<+J-i5DS40ugbBgje?LJjg^>!f#xB|jmbZ<^==NukOrKZS@35`HO4MyTd-UlL_MT@M@JL+U* z^g(z!uj}<_w5pu$to92vZP0AXw?oC{x(!*u3=4<+_1wheaN9}c7@up9wk!#*>sTYg z62-#fMy0{a)JmD6ctoU0Od4xzQx(Yo8}RE^I`~FvM1!k=ynG=VG@88KP~H{NKZ}39wuL*iVb3WV;%xbFWq4 z2MI_aTP>gp{}{_8No7HRzLL4M2Cxhm8lr6Z!ZuK&LW*Y~g6MWSlQ{yyM6xQT!1aQ- zes@x|4ZoD?3pt;NJA&kxlf=y779Dk2yF7PhRqeXCjyLSsWG}0z*Hehiax#h7W_l@bn93QSI^?=PCR9Yx;)g5niH3P6I_TZM8rfU9`rtlp!RAoVyCp1xih*a zuZAVJR7RC(m$K|yK^zUz`GOktM(n1XET;wq6qQPgLC54YMbF6L)()0PSWRbXm#JkT z5kdW2-lh$%AU9nQ(hozYnwt8w3ZQxoO7(Dn3yUHcNNV9MF}{FAeU6Z9i79#-^gU`O z6l@Kua&?DC!-*o~vO26ZRWnH*5(1b}nzI_xn^KI7LW)!*RLH0CPW z5FFr`W8gZleUL3eJ&iMFlra_xG6X60S=KOa1@n4>IEsaCrDQ8`1KB8Zq7IG8c+HYF zC?8m?OT9{*0v=-+r46-|S%-B9{Ko|pE?S`EnB=HVthm5AX&f%m6IiO8Cktg%&Y^az zrrLF6qZ2Q1W51~rqJ}!oD=8~cZI}dzR+{M~Pl-}VL0+|&5<|t5OWf7;MI@~CHD*evIMi@`<--ZDub2$v(X*ti zFp979Zr~ZFod;#tT(3(Thg1e28P)5w69$xVC`5)!TXyXCo4a*aS2Cu{A`ud)VceQ6 zK)qNCcopjn(js9Wt47HRR^8Duoo~r7wkeC554}q65p?4NEd3cZwoq@%$@U1OEedlj zQL0XP^EGUyk~WFg^qLvSVzD zZ_{W*&dFLp$mM!%xOgb7K_a|>!=S&wySR~Y(J-+)vA#8-ycvHb(`(M~Qr&Uq5vZD8 zQ))TQMV}Kpc9L(X6-uPE)J}lITE`Vs75wxeKSA9um@ zsF68KlVQoTQHUD^+>_e^7RGBIh=QG$V%0CXoW=;H&F6T;&5FEP)6`b6RvDqN6QbDC z8fZ(unvq)-gm8MW8W84E>zLh^HZQsjs7$=oz*{hx!t$yUY^6f62SOp^dNtGVWTVHx zMI%|85rAXGj~sWj_3pCW??wZ?yBf}uwQQw4Ldzd3E zfg-UU8*(LsO>u~!pq4r8P1vlf4>6FZi<1ch%egg7x;dn?z?~c96Vk+$px@O-1QId< zX)n2j;Oheg$akW2rxHk1u^W6X;VmP!5R^j}^c;j9*b#8EI_^kL!;tg_qyd3CN~@1e zF&Ma)BY_WU4E&}8Vo}#rQCz3iMGq@hZJq+f`CtKTZ#eg2J@Fw%wsO3VWsK=Bayee1 z6!@i%PSJ`CYH=piWCiS2Npr)H1VODnG3@zcwi?Y-5L~6WB%(p#a|R(o9>P`RXLD(o z$79$6GpuBdzAOJJwq12xxdIPFsehkXUt*)1?zzJjxXuK?hYOD0Sbb?RZRxoUXVijD1 znwSAKxAHYoB4N}Z^rB1KP=xYbS|y5Jn$DR<>)q`}hRY#9yzZt^-EmB9%2@7@CI~Wh zD3F@P6K7fY{d|+7G(>8vIlVy?E1yn?IXp+=ZPXqNK#c|-biwmfyKh33&;xkX194oo zYh;L#&ZfddPF1b(z~-Z}L{m;%g?O=!9xZ)PlQ9XZU24lWx*TLzwJNUW0IE84-Y-$t z$$7S!8j4h56Kw#Ooen5Og+WmVsFs`C9mLL&*_tptl@}08QyHc zaU+4@JRPGlp(EhBHZU1)F52WA<%qGgsYX)|0}4dNs$7Jt1=zvq%V!m5#8H*K~jg>#fLR)bAX zfusUK@&gi@&IGUc0iG)QRn_FpIDdn4%*<195 zc-kIWlUyc;h&@seWzemR0bFaw!h`dTyW#MaIq88=?#4z-7%E*8Fw9XaFXU{yMN6M7 zfn%JrU@4Jt=wJ?Y|0lpZ6^#R8m8n-92R+|biyH8r-h%yV5C!HGSm?^Vu z+ye)gZ))rJK!PAoQb>~%1H{Z2#gK;N2FYTslfa}@i24d}kmmI2;igNPXnVQFbKY)A z<7wqVo0%(?#XKQVsn=Pdt`A_PWqJh+JgKgRwA!9nl#wR4w#-oH>qJ*tb2yWnj%ab~ zbb>_ayhpeYy)wsqK^kZqga~nOqokf7f-%Vvh{BENkx0uU3DHd~VH~AljxGhsr6i`|G{MllR2`fEC`q&GqcX|h&v_E?4wVyidM@K*X(BYoX-S6CEKEChc zy4&YT$}aEOcX4yM*Z$qVTz0~rFa2)t${$>H&&x0S>*cR}-{!U04}AYDTHfPk^lJ}1 zaXk<1x(k2Pfrnl4*1v8aGPDE#X~*W?TVHtAlfIfi{LO7=`}Wfx2p@R(QpCP~vHi=v zAK&e_KVrXnzA?Oc{gVCnSKfKxZ-{$Oc;AQ5{LasUot=B`IO^iR{X4(co6f%Q8RuM< z{G7k+jeFej@8A3W?(mG>t99iE_WbTyZ$0&Mx9)e|4R1Yl=l4nc_ukXF^LJlBZ~UBB zyy58O#dlnI(65fW=)_&0_ll3aqAT0a*h6~7Ef!<>GgKoinct zFL~$5&_(y}-Ddvnh9lmvm2Y0XXvaH<8%}H`xArf3#bKZR#n*25>mv^ycKRE?@ZsHF z{KoDNlUrZ)72^8iix*zRpLeEx=dW*NUUT&No;MzN?XNz3)1Tk;xqlxY{L;e?cvE=u zD?k3utFJlck--lBwp}hx?_xWLKXCB}_xd5veD7mN{ruXGU9hvT^LgjPA3F9`Cq8bI zk3aI;d+d7R`F}d%-{Nb|=zMnH_rI*Cedd;n-gerdN4@C$^G|QDj=AnF5C8N0nv<=k zT~*v5cZ%w$-5#pHeDc9(9=6a9+W+z+ZvWv~^9N4;>+f&-)&cx!7oPF6_GSE{b?=T# zFFfVc*Wus&^`&PWeyee=aL+;dMYo=O%bQ-JknjEdukTa#KlI$wKlZxI4}I!~KC*x3 zl24s>x7z>6(SmI6{e0<(%JJb>J$EjnpWh6EpCA6k{hs-eJAZl@^2-Y@IQyx$o{IkJ zqVJsZy<2|%qC>uM!*24<9N@!-KPpMBcTlZW>|s^3!n<%>sr|JJ{~|BO#v_@(b&@l5^BU*C7h z#lfY?Cw%3mU7qnmX}`xS%acC5-`n|{e)g5Wjc)tqai4nT{m+t~#eQXe=L_!p_*aLw zed|L9ndo^ZeBrPSv19RzOYgdI`LX?8^5(tpb3VD}K_?IPc*;W$-gL;C;;yw{#}%Sl&Vbngk$Gk1IN*T+nM^>^FysFAtudApu;_EVS1xi^?Q z{&3!NPCc}PeB?!U{q0S^`Sa;N_&s?Wb>cqioo{~Yw@-S)DL!(SLryyK+wVW)r<;2R zx6$`?PrmVyxAg9~>yuwO@sOV%`P}Gzr=0Y7UES&FKkk9U^viGG^1e@ve|vEL;N8!@ zYVzH$qNiSS@?O{CZ!zC~?GJwbx8q-X_xcBidvE*K`m@J8^$hI%-G96|^vn-`{*nW} z{VVS7vv1$m`pg|)w^|3h@(FU^eb+ZUnS22reffhY|H~sk$^qiMnd+bv_dB^p) z{N*TyfSR@4TP>@&hk@ZF1|CryOzx za?LsNEj#)rf9H%>yzU*RmdNt2dkc>odeMYDZ?xC?m+*rxdOh`btN^C^>*7A&IorME z>NmV+xB0a%{NTyox|X=M_w?KQpL@50J>1yJi|q%e<{RI2&Y57`Q}g>CvTk`l+P!!0 z-~Zu(D^7f4^o(mx{M>O5fBv2Cx!1Gbe+D>v+-bMoev|TtKmYMX{8<+s9UhAFh&Mb) zxOulzf7U_o{wnrd{Ir9Ae*FKs@No5x_5r)S{+SQFkl59j~% zxR1a5@jL(SU%V2WxZUo#WqkAIWuLv~$?l&XIPHVm#i!4Iw{d}f$;WQ`wAO#e8CQK% zzwPy3I`5p}efPcN>~oK}$j&f5B^_JAZW6Y5sm+{9@O<7Y=(OC||kDfgjlW{l~YzVDs^0gxzh|M!NApMUVd@9pxWH~d++vA)<9U#VRE z=ZAJYBfay2>5t9d-TLa!JdrmXa>|>Jr$2Pwv#$+MnG1l@lLEPkznfh@bx8mp|8U_|NzK0DkC?uXnHf;)(k%-*U_g4lqCRvS&W+ zab&3x%iE9p+TXT|*Bsc|JmrQbV01I!b6)Xg`F8T8uV3_d3IwiqIddmQ_{Hh>J>vyX2L_tDGjUpxdv@{Q-c`#HCL>Xbd7a`gK?`Mm8fN3UKSQoQZQ z2Q-8JuK(m}f9Ex~-F}Mwt4}mdU-ja8cpdWM+fEwDd))T^pFE~rN1A}Jx%_>A zuf6;8)RAXjedg(BpZ|sTp>KIi;~^5<+GXD}fmwL&xx0>T`Z4;}J@E%p_khP#W0VC}*eBLL{|AO~r(8GURr#*%+!{>hDeE3P%>@0Que69H>U$m%nTGKi&WHuRQS5Q%*ePr@y}HU4IIWx#PMsZ~bJQ^se%*GY^Wsa@@&>zvZe^ zUh$OTyAQneeRurvH?8p(!s&-+U%&pnF9v+~c>6a73TE=LpMWI+`5pOmAiVwd+5Tex zqucL)ap%O+SM~jlyZhXKy??J?9I(fEN4yGH-DlzQAMU;7^~d}ZJUjBHdw%`kDa*_5 zc<6J#`V{?zD^J|#h!nHEJ z_|S)cySe6+H+=HIGv3fZ_I?2Mc<-zXdDqo%-|L}2?za8?{ihE<`tNVK{;(_eyZxOn z900@UJaX(YC+?d)`A@%j;0<@(fokh}JFk$>rcVV7<~t8P@2xw;dyFIg_|S2`-GAq! zh0_36`_4UoS~`C_?us#V*m`^4ZKr&5ARqeOQxDu{=lasob51(_h?jMa&>Hx8mH5^Z zzj@4UgA32a&+&f6?*4LWmt)R4`<%(E74Eigf8d}$yx?=EVHccq&3BLb0 zJFfe@cyV^E^tyAm-+vl^(o@xa`I|5P{XIW<=3W2!ed^oazw(jM1^R`bIq>7JzwHh3 z9{6IT`!BA` zZZjV{paeJvUwBf!D>i-q-n$-k+#9a`?kC=O&<^(gU*GtSf8X3A zx%KVuoL~QqRs5Ty+E=dK!*{)I?+d^9fyPjrv;RM`1Tg)qL-zO$@!M11_nfo1`+xnt zed{lt|9j?JH+%|U^J^AAjDB{|KliRb@t@$c`ETy}ygPsUmCN>i_PYGfS9J1w?s>;E z?{3J$K|g)YcTT$MfxF&s@7Vt}cm5yjyk%6>@4GijGxX3y4-!%m!hj-33Me8H3aBtN zGJur8ND2%gC14<(N=OP4(jg(;h)9>@&<*DvfB*kJ&$IVF&wg>n(9PTT{z@k{#}yAeW1SMMULOY7n*+471R)B$|bJe=8vr=%B(kd_R0zH~UT5wA91( zcwKjhlI6PQi^@D1yc5`=WlHA-oL_ldR&B{+!*RhD?D*A^IK-56NXoL*5=COar z$J{x2mg!c|F+^6YUjxfn#Fh*WeA|KSMKBzSBqC`PZYO9kiTpIZGZeu&ep?<9TtWB_ z-aMYpll=gXC54se7c6S3$_sh(9@3Io>1Lo)RVnm*df#8y9KC^ z^9!2!or2uo!{=kPKKlfUpeVH?e|kD3=}I$3fC3&s`zbu{zb(wp3{;oZ4iRSa;dv3$M3wWr@gB7mW+Q^y2OeWd))O|>(UFvO6BKXcUzPJ z=(cF$=)|8N_H?l3Q*h>ycDntv5VAJ&)MY#1bO&1!oWh;^@~1DG9ZJ_XL0^sPkAU6i zrtX#{CNq9-2!36$3`5Lkuupl__PIw#lEhbXsnR{q>7i21f0`NtWj3yis6JHsi-@6e zxVs6-{QdP>7@6Srrru?dVuoP(N&{a<(05d^${Hll_`<$dXhcK!9-X5|FofAWfO%pL?%|aIVSPGqI(*E$HVg|O=zZr*VG?uL1MIj<=YH? zXfayoZ=+Ofr%THrGpfr^Cemo|#kDo@?Eg0?qf_`+_g>)H{GY(7HSWJXzb34KbZg*F z7(sI_s;lw3VOYX+R>wC02IO$pBVRiGE+be>%j=mazz>reFU7>{N_&<{5xzAE;EHx2 z*jm%xB=Fq+0VilO{JNTat=)y+4hzFOCnG{L!?Ne+bk2 zVj&0oi1I7&BM9tDZf^0!BR<@Bf*%gWOSRj-OY(2L@G=fpi>3R$j~>speFm6J?ltZM zU1a~C`M@1<+H3!UOPj+?3MTe~j|AfGat^B8)JoBR{rl|1f0s>G3usHi2OA1+=Tmv# zleh_MT%>gKp@sxJds0%PI$suLcXkZM&9DFRh?VfU!!lkU33|N12hWo!6b@#@Z;!+( z`8?{FzFDB0&+(Am6YQ$|lBLcmRs|C+@PuCw9X=_wx%W@Sn1G@|+Ym7-xs`D%Tqtto zf%m3;n??N9EPWll3`3J#!}8+Olg)aUKigFC@_q&6iM5ZdDSFzj+w>x1gc!qaFGl2A zj!tH}9FDQ%ZUM)m79BC+ht;^*{lqBNCsxDrIf}OkSsxQKx74v-eXy{2q!lZ!Gy#p5 zEX}a)_;F=>zC)7HoU0{b%LMs^gCgc$>3||Ynq&-x7fD@l_5b(Usj~j}+PTJ!$K!Wg z@!7I5mTLR-yJoy}dWDqZlLx)j%Z5?*fAouSRV{*bpucFu`#W1_hh%+6c=d_ZNJ|ugrK#uCaT){+B;_M^b;W7&SYx{lyNTV*rlY1@AgsA@r&ka*ay8CRT4;$8B|I zF%Io)Q9n9&D0nB2l++~sMfj*@!cd3hLQ_AEe#<-df6)>OE1Wvi9Qddu+Duw*&>w`8 zH(6vo%T+_6O0pFNVzng4$1hN#$XY>%>WH^Eu`=WJY=_L8m+g(|{=7k_SG4j8QiaId z)o-mqv3imDSel_Yv0TE^ZT*&I`ML z24h8xu4eDmzt~ZGFNPGQVwHl#+^o#o9Yy-Rd-N66;aGphKi3-hW@o9lvtr8E&P#y+ z<#c{}G>~@uv`dg9TGaI~bOv-p%lMwXX9c*S2uU0ZXCThD4K zg=gD&;C0r6H!B0*jI?gYUh}V%wZ^1=wKdTTqWTe}S+BXSR?BOgz~Ev(WsVaT@{iBe ztDK*`@idS4vKW%ATbllwa&_wActze7!BYJgAjRf|21E-!yjIcjibJ@e?(*%&4^!m5 zxX*kZw&=u-fzz{l7|Y69ws1;mA`lQl4`fdHw*K+%(ur%t0Ov6 zWj^E7=hk~B0>9ij^>rk3JTyCu%ls$mFEk!r;mn++_Nj4mF7>o|HdQ57x>yhszcbQa zps=B_mGJ_HMsRREu5F@eiH!RWAaJZE9%2__^{2Y;MT|1k%sSs+v6`%TfqP3|S#)+f z#p*RuZ~9n*KYu#G?yo<7#UL2_XD2y%`Dwm_*Z$oXEm3FZZLrQrqI3du?;C!tJOccM zRKN3><^Igo)II_0Tiq?M=oc0`;|8id90z}UA8aJ6M!@?29Jz-l^wn@_sq75U|CS%E zVbCn5NzC9Mi}|7~NksBGiI4u1$opJ+PfZ}5fm^@u>Zq1w>PuiPi$l1w9&P+8;`17L zuKNjfW3RoY&TqNalZNv;AF(FlUEzBDTQZ*Nj+i+ctLafm%L8roh40}8-$qDg$?aTE z>vQ0!=~^6cq!u&oS)r4(etx~gFBb=OnZ%}eJqqpP0D{(2(#x`UWw~A%h!e2oMeX7u z-k{!vuga#(GCt1D0ZLAOVbP!81+P-PHkuxEoEkao;SJ|K{6WKm8Qn(w%JQk`AHcB$ z&xVT{ZGpn5_;}J3`cvGtkZ?QLmQn4la$U0QPCyKR8gsx3h)bF$*>shn^XbLm*4)Ba zi3O0qDXL!Vd}1AkYG7OKe}8)*`+PYqfG~v_9e6KU_G259=o5kF5SqBrA|!6nTlQz% zBItj^r^)mJJMBN;n~HQ_8{=k^d8Qw;vob7vJ6ZN?SG=S;m3O8nEcu<#gMn{J?^q9P``G>}FG$-&iw0aY z_!GKCbSKKhot+#|U>?mh1r6(A=0J6L1Foubu{&|^QL|p4tOQa!MJ@(>{qhmGAJ-oQ zXSXgIT9)g#E`%QBJ!SjQ`>VoHGez!&<^I}F@F@o8Re5gF%x@`_qNAuC`V@@T&xZn`i_`_Y58mY#d-CVxBvAh78969M(gld zsPjk>61g!^m1#jJSsawT*dD|4gYkfKW5%)WNNszu`y}-Ql&)~uUg(Ds^Y3&>BvMd6 z=YHCTx?O#D%{Y8|qe@M;QRQU@Kl<92_lk5c4KjQV`dM9u^K7YX2lGF9+TVY|A*o6= z(rUU+#dJi&Dxp^^1~m26y}g9}cMG2@I)(=oG=4B}o$PgChv4?z*zIXJ5mk)}gf?*L zX~)EjP#HUgs@6!CtyLS%;BMQCa7657?bMDVi_afbKaSwsrWZ#C`10-x<5zCKsm*(C zZ)_0De>;aWmr$YS4MD2aoA7$$ILa!!oE$+NsUmXr&|HBSp4G3~sq%5o&D9zQQ5O`$ zhdV{}!+Mgg8>qb=MW=KVk2Zqq9CGq7vin1Zfq&K(6l@20_d*+%gFjTdt-dFZR*Pi4 zeX_rP#_Gn0y5H89uCmY+M6unk&XwCpV?nDX+45te%Jt)uDi#mCt@OYM;1XfVdx)Q{UT7oI`eyC`d%yHx#RNm)g|3M>(#LHr_Q1Q^_1cY5)Uqhuu zOK5sTEe}h zB~E$Yyzs-AWRb`3%VyWcIt_{@AL|9i+4eLcf4uu#F<(JHr3tJOgymh?y)$*nB9iX47v%JtDWog$^uO$LoiRB>A}jd=6A}LPz&eFC{v>5r?-x_ z+PH?VVI&OG6!94e1;pFUiYF_bRj7Wqz2@o+;quLCGgWO;A;=u*55>rkwoNB1Dk;o; z56^Z};&m7+=Du%+Iu}${O@EfTi4`$BJ-Yu6l z`qZ4Cbw1U|--j7A&0LcZNc2~`(Y(ue#Fy|a0-R|i@CaE_D0ynuHtR2_?+-O329`&j z^H@@6Naduk!j?e?tRmNYi%&?B)9xSb)JnEV5h?*;WPs?SGvTJ}x3o&FyWg^HNHCzM zi=UAlP!mxbejwA6WpRE#?CT)Q*WP_37D=P{!o5|JaKqTW5? zIsN^`(e^vbc4NI-slem1wyH{5rZ zbr=!Y#m1AFLd)J1WBE%DKA(#nQT+gAhWBx~y%1%iaM}s2iAE?>1dr8^x1JnLOcGO2 zMCE29$1LL|CbwzFwi8;Pp!*(opW`c$`coBU44?G>9(!@>^H(mW{YNh5Cxd4RkB~|b z$~|tb6*Zv{KVgv*fzn;35g8OQ8%rcHLxMQNd(sQJ_iqJb@06-N81|wU9JpX|FMLw1 z!n~1M?WA={71|Lk`f+z{LIe0|JE{A|uUM06KuACf>NL0L;K0RsNn}ku9^374)qLWK zaiCEl)&1x}3SvMo8P1{}bMO$tS93*{WBjyKt z4q0l7vx8-cPtpbx_TrC}!HAWKgSm*v$mO6MH{A7`+0}S!B(aBS4P%@AnIYEV&2di6 zdW2#Wa+08jCQ$|u_*rmJMZADeTx7J0Z-b_Pa)IZ>K&JGO(1M}qM-CTqoc7rQa;TyC z<$dvd4<)5fS9Y0|EkRcyzz+$KuxC>y*({5sZU7sWBrHsXg zOVOA_F9Ey zu10PHVe&5ElzQ6d$J%^M0^5i3Lb=5)57vIpT}Bn3s$B;x^bV&sNqzSFiUT*g7p+^-1f*iLr` zwOL(=XUH}Kxlz$@JUc_UOTXAI@mjKT09=U!syzJ)p@oDPlN3Yo<|H9v8+0 zD@~Z!V3Qhz=aEB|kMs!f$+*9me$#YJ*1C<71PH(D{uf{B zTaj+T`TjVi=M;2h!)lhK+S4s7HZ@V@n&LDrWOm7+TpEE2^(CUEhUhkBAIw=psOlIM zrD7;y{;ikSnr6`u23VS*2RAf0j5 zkiwH76+J&$I`o6Elv!CSNK(4wCo6ptM>9efNisQh0-_7PSas$(VGKxS8`^zI<~U7g z^K}A9n~nD+om7{Z#+6e`)QB!f2)poGXlt|~4w7_o4SgQ19gwO(MgJu-H&aSzDYU}y zGNwxH1H8r+@=hhx;CT0sn?2;#t{94asnc&?av~8*`+;p9w7v4@#=y&@7Z zRd`c(XzW(PIxz3h#5f!>$Q}#IPz(e=Af(|JdDCkkJ7lH^Vf-5hi5%(nbI8JpGe}J6 zF}%UUv)u<4hRLOA`!{$~?UdH_&^1vR{Bk`)ZK}W;Md4^)I!#Ah{bg8;;ZlGb4L&0V z!(xjm(4jm;VU)S0sM7C@H51uM6`%8!k&mcx&kLu;N?53MFD~Q*8F3`P6|U5lsxEBL;1Ql183GMCfQ9bF)u-G(Ye&0iVO zAfNB#pNiNa8-f6Az7+RJ_C7PojAd8?T(Q&%=#s?fOHKcs&~<&HeD;P#{PTU5Y_><# zr=GzZMOPh^9e-;BiHhZ_ACGgMSY(#HYGksmyxm5M>LH5kI)P{ko=8sR)FV^$d@>{fZbbrK&3g~32 z^>@orEc9}}Q9p z09oPmfdtMmf%c5xE<5~n*V+6cjot{vC5@7`Jh&H3T6?!%6!PbD$>G%4Xp0EF%@WIu z@z`q1-TM6UHh}%*=$#IpQ1n_EPLWx<&huT!^HwVT+k5&I%4pV+Hpv2 zleY;EH19NjW5k(cv0~ax6*GER4LP4<<<{5BmriJs-x6y|YXHt_*;U*#PX)|Hgh|`;E7xT~JrzO%0H)x|Fl@vy^#YDm#exF4RD#Gygwq zPQopWmO_cqQgmIxLMCQwV&nuw1apzqN%}$tszPyME4xwRl}w`1Dl%&z5>>wT>moeq z#$ z(4}Y)m?$;;cI_61kBMu9v9iHKmiQ^>yoNI*gp_|gScL1QzD};fn!}cKx5lF0rf^sRmE^ z;zW^g3Zl=PU(uNpHO&q+E)Y20N+0OXQqNYqy1&}9vJR6)l|Q*wr}kYboVwZadw`B^ zwWsZiy_K&mnkLHfN{>hG>HM`$8KDADGEijV=uhH+Yv*FEEyl%vg@66=a6h*6I>l&J zfsAL_Q6 z0AR;d={V`uu5KC@=U&?1YDnP(!or}>&0-|wzJz~H%jIg4P2BDfSxWR6-|6UT-D;<)a%@^*tNV9jET!s-w^^NpFDoN3)cfqhLTV7CSO z6rlJevz>eB*P8EyK28d*6`8l{1^O5`$?qFBo{Q#Oez85D@Q3o`M-6&QSrl29-vsqa zG(8>LBuSJqr`NF`52aFT9IwxAHLB0=mM!A<$7+Fhe#QIsWL-Z`*7Xi>@PApx5uQ$ztJctm9_M4IxD4y|cB5yj-EX6>-{zk6JdL8k&{(OJs@eoY?&MZ*kY@Z5U4gTslHCd#SWv>Pq z0V+ZB_)p8(HeLZEBssNJZ}GVk2JZQq@Cd z_ZW2_zz9{lE~k2DIDEX9{743g5pUv;fhkCf5%WM0p;s&wnh$~G_<2d?sZyw!q!y+U zkS~L?FVd^Plxva!E#GS~4i{0HDQ5&OPfHqgEVl>MUhDH`22-!qPtnfL9YT^b7D1AG z<yQO4KHXJN?d%_g0i%Dk`p6gtEZ4 zqKHYnfLgjR(;RYaf##oPX^h$sU#W2T#jkLR4dmR}+k0ox7WJoROGyxl0PUfko2l?g zRYvt7TL#IxvZ=i1u13&5LY2qn4w+HCNL&*F5*qDchubN#3l+AxYsp>SQ^_tfwpP08rn^IXrD;?E-dz|Qn_kd5NHM0(coZq?6@ zxnFy?O=qZb#o+$o7AqZ=3CA?Mq;Pnw*+CfOeJOo-3DL*9RbAWb*>)x)&&K$|ZD`(v z((;T8p^8UH|2GFdHr{pgFzBxbpC$aLDIiwZi-cROCzPr2EP1HHdJ|C0qmy(>XmNMH%11GU}nwjBG#rk_^iFhV*iWASIH&B~ck zop;qf#VdmCrQV`5Oxo2uAMd=A%EeP{{~pe41-vNFWuO%cjev(KOIk!#BP9Td3zS&` z?uQVn(4;oc%rT1i(o?|rW97Zv84aPg1!y?s?$3nOePdNn{?*5|%SL>r>c@U7^0Ti| zq8qR|XA*IEc1IJ~@k>s>a2`KGhFSEi(5r_1rl;EM_mlhIJnVCRwnqzg-vi_n3qLW6 zGntb*`Pp_`A@-ibYA!R`_xzm3SuabQlV?ZPILFD}WR5MzGf)T>UDoj6!ed=NuY;<1 z|C7OJk>$C^DlumXP9*lbI5QX(QEEB!+2j(`hgWx{3?Sb~6%*0mkT834?Wvh54~8;@ z2rWNtrqpf#JRyBK7+;wx)p&>jk(mpYK}iFa!itW>ZjliC1d01E2Vf7+Pd4|K!1D+p z&G-aD4nq6{KT;M&Pbp{YdDJ5M_EZg51G{f>Cr!L!4dvf$YfpJE<7nbAgKE}U)7l52Z>u9En1aj$@jVaRv@O(w$Yhg1w8>oYs3VlnI%x;26*wc z5~Q4~Kas2k!S6xyNX4k=pm0l?6fT1l)-0#sY%)6(HHR$k_b|pcK*FxU1zkGF^LJ2m zkSPH0*W!`?U};nMOR3%|#|aKoty|>tZwL6ciB*L6^|yMP+pgM<58$zB?mJ(y-FkrV zl5KhzkPKcnBCE&b91^K4WP^EVW_GhF>&|--+wdIccV}JoIZC0hSaQ?f6mlGD`=vm_ zcx>Jh$_;k>aIM3A5^8pVQk&lQ*PLgUGknl5qJt=jCz&!H zn){pIMIEo^`@6Tui6};zd9@Pszf;x72t-{X_2#ZA9?4epCs?6UsbrCpi8>j&w)%g5 z`a27b|D=kras=LmKP4~!=hyQ;ejuc^lk4O=eBDKH0T@HRe_{$EBmS}yVgEjK;R_zS zFjmJTx2Sj!-)zAV7nRQcj%fUiih?u-SfBLW|I-K7Hx{P8x!HA#>;o%0G-meaqwtGr zS+gcg0*i>lcv+)PG8}-sc~xmCi`NN$=SS+LYNiJ@Us2#5H3CbTZl_ z*<_?v<8_?YH-1;2?KhL%t;SCdFB?>omXbXCGR|3a*&nNj0|jys{q(IMf=E`{a1&5U z3>&Utej51Q$z>Z7GtQ#s{U1*2>4iZECda>_ffE5-wSk8qOJtR2NJfUaPOy<;XZB2y zbKES9l_nYH9uA&}JxI%xNIPzroCoJz_t;3vH!4-T6=-qYeeHwPvkAk40RK25WrC9u z1~HQ-{MsoZm$g&gGK-nC0}J*6tiYu9(ap16y}cpR=1$wePk&6V{I2$htMfVe#@=+QUA)`zK_YXXX7v1Yrx)jp zbR^%X@bsC^eQ|nNQsy{iQhNv6^?Yqi=b%zzF8AnQ%I_n<1z(>1mVE)d->XW=F+A$; zSB5|1d_1C8wD49yt9d>@EQr;Jx%9_GW-wbj4tSue)+x}~G2Wqmy}5kk$OZ|nG6ue^ zUV3y0vs!-L1R_5F%HN~|4+}R{4zj*(7iXy41%~mY z9W;Z46Jqh3Tn+|h^w^k)vFd!E+fSVyIJ>&~ndBT?rv8xquW~J7TJjpYYwv*p3#Wpl zBmlB~d$B8ik7nenq6Ui{3T`@5Xe`VoZQpl1ll+R7CwQN2H5k_{2}p>W=D;2iLg{AT zD^MnD(}9nfe-Hb}DIA*c`sQ)FBNa_lbFQo%~sF^)U9LjJ(obd?+N?g{*5%nq>LN8OB;URHmz|r-jOktb5I3FD{G`6q^Wj&?Z z?ER#bs2>5#AmKKKAOq8`k{`dAZ6UKAElh@Y72bZs@A-6Xti)xeiI@=q{O7vpY-i~IV@y_F_d zYUBgX5u$Q|tr!v#hy~AlRqTX{;o4FN4cE#G@#9SO*P=kg9*i#RgCej@+?00H4gM<} z{xT#ftocj+V@m$&K)6bLscZ?Jj(%;z?3-XaSdBKF4`P%+7-lM}L%X*SQ$;?_7U_CIq`+<&a^#C8>L@ z*$!V!OEFywiZHYZn8Qjp2nULb=VvH%2Jk`@&JQ!gBq2$_^m=lOis@Jd&+Io9hO!AeT^sP!rQ#Eb z+IFSPg z0<4%dJfgiICXu0Z%O~|Wz@KDA^B0@&R^E!NUbBhHAURW2#t&t(sHKq;h4p?mD0=Py zjU_g9ARnoP2mU%gJK0-;UB3E-n~2h=6?&DVh*4DwSX5TCEw5znd1R36rJLkSD97Sq z{vbe9;SDvMQZx-KiFTbfQ--l!t>msEP-RvgJ+)Dw$U!dCQ;?x=;MXyOt^H5*4XDaB z7(ArO2>-Z{LMUq%N8R&3v0tOGC|t%9!cXup)vj?U(g{g*ORF-~oH`nW81E5yzc9*l zc$YdCbui-Dgi9D|z|jyxpF(17u_nJOU@q4$>bf%c0yZ-62C2#)_%;fnirurVyA$xK zA&Hikyd(Z5=qG54kDs_2D7?OS4WLWN1er$Lt3!JcqTeMJAsa%GTD<|8Fe7K2a$8@P zq*mJ=9C+=SWu=5JhD1H_;Yvf(Bl~=hg&&NO^fKfF>6f|%_u~bOzdesmfZXm;T7im@ zdk{_3))aptNMvKBXm94g3nz4G>owo2Ny2IA_Lm!$66D))uI5@fqh+c8VJOFqa{Yow z4+h_YDd>iEw`((?oozalFJ4?43MWo!e-d~`7Cp&8tkC;b@C`X6i}tJLQ01yvg#21L z6>Z@6S~YxTOY)|Gku)&BF>jChg4V6PJiWHC2NGz1IJpnMz1D)pWT3k~NPIK8)OkTW z-I?k^2nJTrJh%&yyrV-8=>b*bO;P>%BM*P+0i#RR)Ve{Jnkn3kTS+Xl?OyAs>~A=cUH?3r95qh ztkEQChlDV$Q~yJMGt6!p2+xc%q>s5alqlAuAr0li*KQoL5ufnDSE(XI)~u;?N}cD_ z3g~~Lqk~9|0*hmQ&3C*(L|)#%)_?}#98nN)c$ce}z0zvmK0TPD!^3E3eH>0H=Qve2 zY_E#rBz+PpU8Y@FeSp)oR@Ift;cK1I{93H*T&h}6om)-lK!1r)R1_;Bqvu~PTt7T} zX~00tk~3Y>$RE+_%bRsvkM+OH_@15^7wH992L}w_F(CY>BRD?!czf^CD3{}+48e$f znBtG_hXs#pg>)d{z#m_ZGo0TS)6a>1Qs-@i{m2x29Rt<1G3O!%3w!Z7Wq8vbL?sZY zHi~76MBhP#q*$A@bXVyKxA7{_Hl##Ik!9Qoa2F?b!6)2#_fq6?Ge9;c+!g+eC1oXuh#hHi zsDalQK*K)f$eTtWh639hAusBCxuzDou(|Gm*QQM{^G}{v@Rk<*n#vIPZS^mf9T|xk zZU87ndcOs~atCzPVS0j@04Grkd5H9l)!)?>o-EL%<=w~s&H~)Cg2{;Y%`_gJ9ZV$y z-&mnIm(~5PT4PU74n+punZKe7^Cz&JKqW82fxLCs2$;l>Fs3Z~PzER?#L9Kk&dQCg zF4%jG;enBp;_l5B`ejdbI22UbF=VY#&cvVUq4&k-;Zg8Hs7bIqJseeBPgrLPCfH4c z9_9-Gzd0sdB_uD7B!mA!o<3*Wb!Y{hHdPxD_I_m2zTIzL+5oOz0!d;n3i!y(uz%dp zV+!Q?r0fp63>gObcR^GzAgGgke0+wT)RZ6(!1kC-Bo2k3Ri;0V)p}KsQ=M`V&sbx} z6w8J_8)yfG=>W`;bwftQyFn%Jz61ltndQP`G1tHG^|9$%Ccs&$tI8b9z5axx`bm{S z!8wgnP~_P2E54_PLZQ=D{)YhoQY*q(RuJSE@{t+1DwW0eMMnWZ+ef!}-coZ4L~vXZ z5I-ZfLl?t8;1UB>AWRb`pfdE5TY0{?guPPvWx8=FE9T`3RvRy0tDj-n^bIOsy%Pgh ztSIj^ZsIjb)P7C+tsgRDGbww7yGK2o@NrkQB#??~KuRNQmWc~KA z+}=n*C$LWUxU;HjXxuD{!G?Z7w#>O7NvgTYL$%!n9J52 zA7dL&ix6L=^$c<~$Tv*CXdP$5L=P7{HW;mK=$rxe>0>?MjWY?&d7^EKCok(}Y4~O= zPS$z}rS&n@C}7C}z|oj)yef<$7(}M2&j#M`*m!!CIG@=C4A;sS#$gaQp{~n`+^7br zvTLNX?`LvNG+x@F^0j1<=Oc$(xK7slx5m0E<7%umSkhl2@}C%@U+)REn+GGfqh_q1 zju;)X5K%Dw;TdEdc?=iqeGlB7#m@O%cr<9v}0f3!>oK z2%W-$Bb|8pHv-0^OucgUmx&+tzH{U8!5H zH0#wyUVgUUD zzq(f~`M-<@jLWoNni4smYBPEt4QA8mUF?lY*$CRniN&D%8A{R!COQZW(S%Qoikeh@ zMRRTMHj-fDFy`+-I0o@||5*IPw9g@M7Nu~eE6>Fe%$kE^X#UpQ7eKrgO8sTVKZc`GoGt9LnG?!}j>swuyV+OAXuB-X<; ztbY?o__DQ>2S$m~4(H9RqfBBZa`$%@^Bh6gI~K6@)hF?Pm{*Q*JRdMfmz5#Gvx73* zL0+JjY#;C02|g;zN$VjXCMP0!)t1c0-ivt6_LkJWUHFz(NU)LBiieGylk6BDZo>Fp z8kiB=?w%bq^MR$0_(=lueF%XXavE0;O#td0h3Z|PgrD_%e)Ki3p$}PX>R*ttxc;kx zPEa=s?}WmF-kcj3-z<*+ExcX>z->OzrN9{s;wcwLOI(a?IRUGiyd8i}lx%(798z>?_fHuVk=357VoLG^;5AxImIwUFak~Skd zwGW2aWuI%1P{QE9${pS$-|)!GG5U&nch$cy*QoSU(hZNEKbz5i*kl>BrFNcBeBTI4 z{8Wph<>WF4Vx-ChoS=L#+v%AHBge~ZjeUQI>U~ua-`KjP0HjFNM6;gj z*6c0Y;k);#UCgD9YDVszCj#A!~*AUF43+vKt|Vw6{Jr^r=#Dg*E( zC}vUUC@BAwz4+wnT&SH*l1q?L=isl7gSf zrc4C!B=6h-{v61lr=EhCGT7S;f&jw1d_UXY=~WPRoZtaE|H*5dJ1Finad60iM{z1D z?|1%W(HIUd_!MQdXy`aGq7mu z8Y#*1DE8~SOUr{m6dVd|iL-(EfT^1|fuuBf&PU&wkxvuF>2$D?5MtPX_%s}9`m}k@ zU-~{55gvv~wHs^=OTctc`naUFX#+pdi>C!&UjF2^I)WPFS)+DSX=r$3j!B*Alu-_t z&c&xMJ-Z3A++jDK1QN`_90D$5@ILsSZngQQutv~i;2|f?FteWGn6#JejrCi@9JAEH zLWhb&`Hw5^5f1={{J``QWxnbwx*wg%IsTzX^KZ1vu0(K%z$2`?K5$QY??h5^${DI; zz+q-%mo=gljkxV8mjWdhnU!fH{@Nw}q{mYkw&c6A~lQ+;`Y19|9pYT4D+ftob59Hd0W!%j>hTW8)Z84!z0z7_*hPSkF+ z@PP#lF|xocqEQ@^ji(^fRBH-pvU^!H040C~18Xgx`qVZ^O`W3!H-#OUB@ zK8dE@=@@@}%EDGpe%QBV;W{iR?MB2A5+q$Ts*$t-qn{1LoQ{fkw0*=FuS5vCSpWHAtFh!Un<$&d2c^5x?>0pOrenA|`oKAWm5I3O8; znVtJyoOzs8l@jO>(lDL3Ccr1^p_ZWSY(LhUL)9hku}v~Ya9Ak&n+7w}9PnLJj-EDg z7O6ClNd2I&ORD@E$^dyqr0%2+TLL$}r|S)Ckh4gtte-xU^p)8<37TS4*O|*hLfxT( zALy~on-Dp9Xb*NgtwGQ7wC-Ba$_(kDNwH19f6-Vd6(m8V8zuhDRN#_5rCL0#EC~}n!@lY1Xht0Z^ zdo+#r10~3n0(WT5346mcHD2}wNYFI1QGA@KQbKa0peuxgUw|tAh^t0LoB%xK++ZO& zlIZ~RQ!WxakT^B(wXg42_byO3I6Rwp0`mF6XX=^rlLI4J|7al^R9ZtOs!bihU zJf?(PW`G$3Jych*@*3;lwWw%`vR6(V-uUW=?=v-EQct4`2@~YK%E@_P9)L>5d0}$Q z3aH5ITIXPt{SAO?qq_Fl)GpUZ;J;$sB}~E3r}BS_i58bbh<~D@fnlhR$unV1&Fve+ z+Ds9)fHgY#YbpL5oCr#7eA+f~X^ouZ8WClSKL`}}W6ohe2jRT^b(uIFHB>iLzuC)w zRr~^CgmDT=fA(-lvDlwhc@~apY#a8zu_`mJ^1%#zRTm~zNq^=XHCa>T&QWhOy?kd# zv8J)vs*6pP!#A5<9#ME4uOHlx9{ebq`>;XX&G#!m?YE1morDwr=LlMSD#7We%1m-$Y za-4_7c;_27X*aZ<(1py5<(lvsJ??}X zK3qr0rJ(k0O#m)~3bXS$wl3{j7%PU;Oy>w#ibJ3K3LeWCYdjm#BjjO1w$g3~e(%BR zH^ACvcV4PeMHpFTD7PZK->HM65e^k7@9Z*DEO6Y4w2&6@?g++@+9SnM0_XtcfNDZk z1KL{b>&@;roy>j^XfV{X=#o<9Xv!|$AV#i5uGs*izk>DC;W2eH6Y-1|R`vTUdUc~_ z0qLgGX$OCJ!#8TotkQk6nM!c>954Pd4^vq)UWkVO%2;A)${m`SpszO}w^~@? zp+@Lu><7JI6+=`p$^KVHB)D_&M}+)YMpzmN!F!_g1yc7V$`rc%RdAjMVyfqu3je7k zOW-JE7OKovPYPK52(drMBFQ9cen&tyiODTYE-`~|aI}`?T|$b93qH;F`YDw?&Zz** zHC16jdb>&U)i?3il?vRk-1|=TiuNqFDFyOo%1bNL=)$0Tz0D6lgC=ZOH})7bVVb{9 zn2db$beiR*b1*}vSvo9!Y}&smfs|>72;MWj{<6=COco!ag>HD_Aj-NszFu{;MqzX< zeYuV?jP)P_O@h-hKk$P$XRD8&0!ulXSw%GYpZZl*sEN!M1-B6)f6#`tn5W>;>6!X4 z);NkN@tE4zz1p4E=;nN=iS{jgF#wJYKo8g#i{Z{GO2J9?pTujnRUptNRIyrfyRLQQ zTOWhw$AMT;3@>*$3kBJj5?)Fn7-&cBE9VcBb@J8R9F=nb6Yp{kYGYhr|B7qjPA3>t z_x;Zz$-fRin&$fpB>U%W{;NfQt}WcoWMLn+SV+-65fE`zLo@8Re~E3vT(I+bk$Nyk z%T0^8$+WjGzw8rzn?GzY`ruGtpXOii@ztqb9^VI}nX-)J^`uL~Nl}2TP zbS2#749Q1wH5Ep?GqE{d(qsN&N$lag=dF_1-Wu$qU9M7quw){J0k16bF1k~qZOY*L33br zlRWLZnHs}1I$SzntR3^7nadcvc9luQBC`#c%~jP>_uGu+rvy+0L9v(Lyi}(X-+8jr z9u-n@PiN>_ytqeVb)&^LVA^)~Jkg}s*+vqp!;Ij_;o|9kAQji_4QZ{g+lWu>oFL`oT^_^B;QCZ6mn{s-i4rbvP|^I+yNvq1z_ z{hrVKFB@+BYMiwbS;^wNk6ivBq@4@)R;BzICHo z>N4SeUZXlk+Y;L(A^QC+OA?3(IIwv|_32rx*Uf@ZPXZArkjkZgGans5m>jfLO>dk* z;L@i8oz~0B9*7&L)4 z|J4D;JBIF#&vE`vvBx9zIwb+S9ZK#sheIJr@iR;JhNh2R*?^d%w7!&Tgr81eH+QnU zddaGMN^R?>H!#MOy~F#M-;*UqvpvZ-5G^AmrZ%2(QxQ~rTRNm%LB;8pRQq1y6Y4Xh z`+8%V+F(g`7@p>8D(;}AtJ2afu8d1MV2q>)sCO8Ce97LgeQQXxEg+C){9D_9#=m|( zpU065HZgL_3*aTx$t*z;Alsl*1lebAC~Ruaj0$iyOUo1u4FbFxRY_1Ih;=tzvIR1! z+8OY!cRjslfL!%qBR^t?_8hMf2)qoUPYgM4dgmyFWRoIKalm{KoRLa7WEa75v|Dlm zVUlM^YJm=6KLJk>YB{FED&~ptnzoAgst85rWCPjhc)N9P>;=mWbn_cb07Lq0zemgS-*P;SJ;c#7wK$@oZ9!^{2`#JNWlH}FTG@nz$$qNXik+x3oUv zDn&`jPKdH(FUb}&vW75ZOQB>5B}v4W7EEfgwvcbg5`8V%-Pfn@{q_6Z&b{ZJd(J)Q z{&V~5(>WiXc`u)NzhCdy^YMC4;64em=T8*j#^0SB_|j0}4{ucPdL6WIuRb~LF8ltl zc(o5TzHhO+gU&uv#)omNsbaDk<_p)C1C>y`Kf?e0{PXa5S3yNffPef>A>A}%hoCsO zx54ubS?>@UA_<{>4%)07dN6EVC>j$}h_Dz?d@V~sz}v;sG_Dz50w$N2jUEZ7%st}q zHw!W2lN+G1^zT83k;Yc_>}q7j6gDWgcK?ar;!=F6sYNQ_rPO)JBiP`fgRK6*C})o& z6z*psiRE}}p`cuKtFG*{$>BNKc0guEihB0j zv%v-xQD_?|*Lz4L00HK8M0Q%Jh-+=+ir9eI_L!(O63f6;b_OVq+hfa9F}l|_2c$sl zqKtY&Mc3td;ViSM2V^LZ?vUo%sPp>#mzTGgfkFMxm}R$b+dK^(rH6La!Oo-bU}{3i47GRp05CO*SGC}Ddig0w|ehXSrWAF1z(ZR2N~R2jj#CJJh0L0_J?y! zW3kTzob*}s{Vf*hA$SflAL+SbBr(K=GYqqFSn6!Fz|O^wE{WgxZMXy>6-Km_QPCdS zVorF~6EH1+T3&76bBjvyJG4a$yA6gdM&y3d^0AB)1824Z|1l6MCo3+DSFuVUP}d1R08Xub~W z%zR=Mo`cH_o3&{d2T@b!735B)t;xIhU63l@w9hE_>4{X@Y+Co*tH=rLEFK*u=ZIAv4og^`*4Aez<0E9ElPy2GaKy~p$+$4390A4G=4I362uZWh& zB75bPc-bLtm!b98sr+FJ+ePut_FIKqZpzK8;5{3l^3w~7cj4rJ>Dq*B50s?r|I82w zDKz`rOiJZ{`vG+GXvSDn)XTRQo&UuH3(Vc4gVz7;fmOF0o+LL0uBB6`pW4z!Yrrb@ zzxsEJO!fmI#I<_--~ys`86#Sk6YU?651=Dp-dVSN=$HQ{Vr3=xj{>~EtuKQXGJaWq zB9&&pxp&V0rN%}tKv02gKR^992Ul5znXJ>^u8kefniPIt2zxzd482r#}5< z{)y;ZUw<<#C0_pJJBnZ&zgvgetjbA#=SPBVJ*4BmyO#bp9S1HG==$q`Nj&G22$JL$ zRZWJqE2GftPhfIQ>w*FiSC^vc4>$PL+%4}ZLz;Z@21q=|g-Nc-$4V@FCWpI9tdc-L zd6}W+@!m{yyam+ZyAE3*i%z-Ici(Q^I$S668v#&%1m}d?=aAhBvspoAJtt2x6k2>` zHphy}4>PkU-G2D(Bx_R-(xATCt1uo6q%ZJTTKSoFj zEyA&*nnz;a?6gq`dJuq*9l#7;cV=d7>w@Zq411Al@(qQ?43(l~*xh?uwbquU zVb|-@YBz#Js~M}mj)s*AE4HXIVyK=|0BqCTZs0_Ag~swj(e7Q(MlOSyNNd*KQ^XGy z&hdyJ&K>j85_`7O!|gZT6rWTM?Iyhh)kFpo&Y|ZNPqas^ivd$4OgcjFAff-rVK6jF z7KcJNCP&yMzid#2{v`8hFxitJ6eQv zCsW;9-=fkb*Ip86xcjyZ?1m`{DZyu;7SUx46cPl)ZAiUfp2aXPwLT*;H~FdbBMO28 zAo7Lodk*MKw1Ctm3kqj%Hr&0jZhVjdNsp5Vqzh<}S-8-aD^~@HMgZ)x=3Bbl!3k%! zKBxX}3KWuj?Yx%}*JZ*IdJQo<0g*p}bb2yegh&>Z=lYIs(G1AZ`JCZVXL5b3&?iJA z1a+-fwN`3`2_KcResN=?&^dd>sVlJQFIjv7PpZ7g?M>TiDeVFMW8>G|KW* zph?-<2Z2ziDuuLnhvFs?6>1A@pF_!!#UGPIU|fz5tY_;fI4l9KNHKFOaA06NA5|~` zZ_`VGVY_1N4{Tv|X#-HK9w0GQy0<>8SQ-RQS)o|+7}&PRKK7e1H3?thp4E*3aQFbv z7R`|s{H3N^k;3PeKo6jW3EXX@Cfg{Pt=z|zZfuK zbb_jL3Yw?0KV-eug?wik$K20Ka;i2LL<^w0zA0@|x`W_DkwSHfYOXA5??aDCgUNWU z)dZOQmryG7P8;Tjf#HlGerd}vkKJpj?AEzs^HvZZ>~XtMxom@&4N98=BHq_ah7a&M z2n@4}r`ydA|&7)Z{zPc%E7`i6f7l-^ z9fges+pDnqufXrY+Msl047+;5<=P$JAKTd^)Sitl85Q6>RCe3PiU0@^Tt+!=m(^Haive7eQ$Gw&4)* zd*K~uvVCfR?CL$e>^*sX!)N+Ls)JV+a|;*1sYvGKy$VpS4riM^Q!sfe*o0@NGh~x% zCROvNUZUJQmHfJ)t(7@)Jm&7{X5Bzs^h}y!RF;VSj~78t!v4#4ubx9kuJhxi?IKsN8s2DS%4%4;x&4~vrOJZ zM`_YR;@hEwdCk}=-D-=sojH}nL-{X;bsP^!ccZUA>h1|r!V<>M1`)FI4x{EvNZK>8 zRBi!+w?kGZgBh6TlyqLpLpq`Gj1@%^W}}`i<(XWF<0xAyu4d@I$o+U0GpK$+>}z0O zaZ&nOtK9?9*77&xc0c;9dQTcxcAGxhb0%^=Hh57Z{(y9t<2PcEvd&r%fG4ADDrq|Q$dyiV~E{1=Zh8y|@IPRkf| zpQ`x`;mmC*K2qM9!TJ!Z_p^-~A|9yboo~XK41OXXV>{J_SAX0Y6=?KiCODQRsZDzW zdYOClGQh!Sq65@l+p6R-Et?1MeOts92`*k;oQbmc16U$Ld69*99D|ueKFG>UGnk=o zfnW2WWE3>$!647O;kspA$*QJLAmgHT>#L`c9$|dmrrL7=i{CX3-|M@psyz12$XiJ{q{u6CJ|#Frb}f(MY~UL=!3C)S(GFrhXQMqvr1PFNrJR_ z&=)6Jq?LJ~$P^XcD{#qMOx=$XTf_c%S-Q=*M!0-GO865^rmaQMbpP3)gRGbfk|t$d zi|OJQ3#y79CtSbP{H$HmM0bRCkRIuBVrA4bJimX#0Xn_5f{J#@QtHaci7 zVK)_R*utlm?6mc>ecer%$-HzZ2S^_}Z8@Z9HCaefqQoxX=JqLz>>u$?FI;fD#2Ykv zmXDNeRPqBEZ(4mhA6davInHyau&?8~NJS4h($$@UC6{C#{%oM)lnPGY<2}bpZRKz9 z-TA0Ly1C$3#Fc3m!A#FY5#`dNa^*=zcJSgE{Fcm1#@$fGz>^>5wPo{@zJ(#5-iGU= zq-NtII35BiQ{DK+R&J@rU0;NH1BaUypHMmM>I3BqTifQzAM$uigJWzaxTAc`7t`x* zoib#a^2)Ti(?kZ%kE&#vJnNXGgtkWAEFIdPxCBw;?HYPKodLm|F;3~L-B47l*Qkdm zZ!JwP?9KNN(krdi4|-BPJLFBa8|lyEY1ZafDamb1(sENx@gXuoblEe((_>;0Ir@Ks z^H|ytElFi>(8Jh_oiu^OeLC+<+P~$}o71k+Xz1s+3mfbO{om6Lg&9`9suAWSV@acy zt#50+%IYY>{`YvFon8$r6QCH<(74Up(mN|hdY8M;e06r%)aUBjJlt`CKfTFaY)6?J zx9u)U8!!v<8(bgMrj7{u8nMKdZq8jDS2CH_V^kR;({MsQ6js<|-SXNIltE&WhFD`; zI-Wn%m!#m=((={$F(vlL)oY$KJ?(M*$59`giqyoYCZeStdsbq$66D4iye1S>K>WUZ zdJk#X^Ug%V^*=2-BzOuh8m5{KHkt^SlqE4wezCkjv~%3y_ffrb(L^ThD*yI^im!+B zZTY`!-|BDsY&j?7yT2<<6{q+^*jI7-=~3O+>TCya)m>ilMwD0NZ?3`m(HRW%Hos{f z<%7doe7l=T##*8T4?$kzlFB_im4%`m>c(1qPBzomG)`xVc@?*vVzC>X`nZrUJn*dkl#=QzaLu)LXqd1TIZM4ruX1T zl=ur3%pT)j3Fnne@4esZE|!R^bxf?ty3RE|di?i}!OnhZVGVbUnlM6B5es{^&3!QK z>&*nCw@C_4=BtHT7LV$8M5R)_j`|Q?CAkmE82Y%f_*c^FYW&pM@*>4s*tj!b-|Zn& z?E_0+l_ncCf6O~fxL&1YkTcwyJvdurF7LW8#d7khHj01^b&!9Zx+alm#BEx| zWVP_!|Ij|CbzMcu8pa*D0{WxZz0}nY#nLsBdxxc`)&xj#eC8vUAr@n*y&zT(XSpry za?f+p%6xnPc^rC&Bs`CuYK0F)7e{L|t5(vsn^Z`&e~|qdmbFTOn5ujQAZs`KoMjW6-OCmQyEbK;X8quSDAO-@B7~8*Qd=tJ?G?{``qWg zu6yZ;6Mpc5=k5NyU3S^!1uR2KyX^882)O>?bDjm>-?Q60&fH~}18yuRtq3dI3#?uC zhWk%l?cHvBCEYdqC{?pV=(4#dT^7Xx}4TAQD32-&`qICs6s~&m;+IbVW!jmMh zX4Ycl6-|4%yB~};T}I558}HrjgX_RsS>R(}nX9 zG@^U0{aX9MSg*Sug!I4{e_9jW+pqoPY~;B;&%8f-ShHHIm^)9cbk3)(t~=<)1Unb? ztUpBO$WtpUtt|I|c%Bs2e?7YCTx=8Tsk=+7^h_|1=57Kcl0S93+uVUEAoispD5sOE{?n+&YtS){ioQ?&fK(N3)>e$5NqFVyWQRwGi?<7*^Yf=tz@p9SU?|b1Z1x#kp)7;nUcj4UMF|S@c%OGzyqe zU!hXn+`CQ0N#bj6P<9+I_1EDR+)5XoB^v5PbeyDve2#WDg4^q;D8>e0oQ@o{8SrVDV`T!B?0`1%z;3&cGgiu~ z+LU>&&IGsL8O%A>pg_w&?UABe7IL8m1q!r;F_itoo!TA$O;|ywoHOf>J_VP2MfmOl7rfp#IBAG zIu*`9L#yfCtfA{t{q=T}m`ODo+4YK#*CX87cnXPWtzt5s&5%WAP%w){J`XMMC7Sx# zO!jzlH8M@vih7e7MNsy}n9*{{msp)IqLFSw8=4tNU@ile*72xqc~EOU=(n}VN{VjR z2WxZ}cHJ>;Pi>`Ig<7aplRbNey5Iy6Y+A^cx7?Z`#IGho#`hC!wh7RjH|GO%(uw;t zT(rUAOvb%U2kIDOG?bmmFy+y)z;P7HV>O0IWt56zoo%s5$?L(`k!St++!EC-0ngU+n$zl#ln5xc zNqIWeC%!NmmT83KlE~RZln^v_k#bgHN^Y=rRx1tJqH!03U86f!aGd7W9q?3?S38?2 zFslSU8*SVu0s4qea8oWzmGy%mKDP!PNY7g`TCI9?<>jW=+p3_wj|#e<@tVis3Px|T zkulh0q6XK?t(+sJMQ4=_Op>XgVcUr695%ZX1Y7t04KkEdc+GJbv7FYFZ_Y#@(2iXR zoweO-)73Of*hP&E=Dk&v;IbmAgFd13iZHfEgG!ae;aaN$#x%FnP)E7g0sukOwablZ zm(?~@;)H}J;~_DV($T8w+KZ$pN@tssn~n?X%<%=pWeYP86}akE7GUyz<8wPPw8K zB?4ZrWqiPHyJNgGQK>bI0VWWl+*28K+M@;6QU~+I!N4FqJ0&5F(x&7H?2~5>Fs|+m zkxhw@H$mpm4h0i#J|P*aEe+9_D!PkNcVV@rzC7hxLSQf^B}b6v2c6oRVLfFS(hkr+ zCGy%bO|>M&$$KK-Crf@!xk1MTN@mB)L8h#u(i;i@K?tKmjv3lm&cV8A4ryzfnuPsc z!EXFf8-aQ`S)rb*RY9AcF1XZFU7^eqn+GzZf%4EOM(Da2;jW0J2{3^)W=`Qwdq%dH z)FTiXa`@3S1qPQM`70wR$4d&Ve$4Spc4}5`0MTQV>*t{WEDyPDZ)I`QAI%%<(sQYx z_7^S;#Os8-;b(ZSY;T5RzH7~iY8DRytGkVa%$fqQr|BYGSYhZ+=U7+B21T(Qu%yBb zrM&R0A-^IKfN!*&I?^=jWnF9838_&$G$yUyvYU(qG?rqkUX$A;XqFG3oN-Ll3J7T}Jk*9}U`DOE zqL1qcS=6Slb@T-ouayf)NQYc>vV?sEw*49k%?;T@?LnOqJuS#Pnr;ww-h#{3 zDr}95G+GxcZq~v`_(_1ZI=z@{+m*HEE6B9Ahz@gub`(rFXkr-9G*0_&>a6CRP>lzU z-JCdEr^g~pVqV&)O+PdZ4Z#-v3>;&oC1gm3b;a%`L8g$@gO*+&ZTA|5b(2<}QB$)n z$0WOGcXXn5sn{dkw%Kq2PTZ&gEb)D8)}4yu+|r9dhfSI%49qlw<+YUN!e+gq=&s8+ z20mXbsa!6MP^rQ#V=V&;Xn7YcDvj=w<7nOB>PRrQ-hhz4Kz|p`o=~k~5xOpzc@nTGv8pql}GT&}o zcQr7>fD?mNORq>_-bFT`7dP4B*wnzP^%4=ShU3=T2(SQpvKDF#?*i6ASS|2oGGm2b z0VSh>4Yn1$dE|(!M&JW(n~ZDV%dnR0bqPCwHdbQHeRZtO z$?38XSOIPIOW=cq9mLm$fD033zV1p^&QpTNlz1t6ofcGs`^#W4Ds804Y4&CUxG{L* zf6?Rr#+Cnz4rlv1Mkbm)e6g>xN*95W;J}7}rT-b59{hJU4O3mUSSncFp(iaUoDY_c zO*5TXVpa}O(2y4@e72-p3*Ae3aC#Ag6`wL-SiZF>%~K}6qb;^#T4i9?YBrky+pf_? zt4j|$f?&pB(Akn3bJ+C`_;Jc9>+Q&KpsHRk=!MJ8XrVV}B}^kpbKOs~S+^%nm9_$rGal-= zTr=5Vy0lW<7AP6b>oL{XCb_aqWEH`SoSH4UgtA>d7D+)1P_6W=1+xl>ily37#N?he^{g4%mY}Us*U`pWA?9e|BEs6J z=-QD)1Rc446tb$`>#HqgWMKBP7%O7okCD~y~v%ux#1KJ>2Bmk;a0N2AdWbuHcVn~=Ch4i8~$Y7@s*kn`jne_ zlWGySlub9#YmIQ-E}lD%>O0(OOAAulN}QOeY;H4}gjxvI@_4lvEf>pS!wj-+oKClD zAaz^3U$DcO#k0${JeBp$*p|jC@FakLc$c2`C%8Lhdj1%xkoI-}2o9A{Iq>W#oYqCz z9eeR6%h|a~Q&yptYk*9ZJ77%S8MX&{-<_$fl*{#|05BqYzLL(j80>es&BhmC7dE!d z*^Bh5Gijx>WzZ(oCFC3Pc$;nq%L>va;*_)H%{HJXuIq27W8Lq>W(_1n02WD@_M&DZ z$tl}gYPM|$>|hcFn_|UJZF#9=M1jCct0Qhleg;%o-jpp|qDUF4VR>w@YNzfHqY@Jr zLOU8X%pAOmDiiyLANC`AFm1P6O72<=wk6G#5x0B_8ma?zflt+JYzz6^+%{V44(+)! zo*34M$xDw}%bhfzBbtt4vrd8Jh2QL`Zx_}$hE)@nCk+Cu>c)$tGu_hwL=Yk8g{G#$ zmdub7HutE3u<1KgOCM#fG4Wh{J?u<#79TF-jbcqwpAS}jN#e3dTL<{mBGhyn>f%VI zCa|)w21;)+^Vf;lU<3{EWCW$$3^%uh>7tCA{)lxz?Xmv!5@ObEe zNf~-a6ep_@BZmWFUfCGG&9m)l4b6bALZhx~H2YRmYGyAa7$Ph=5WOCpquHw6Co!&S zsZK}qpfPBr#zbs~UOASuu?t|~$uJ~8Ud_Ut(W}MuF)VSK3oYELW zJdg&`Vl2)EO3f`G*o|cizTUVcY)Eo*dD8AhGZ*dpU9$s@!GM?m zawFo*mT6TUi24wu#dbE}p>$+*1a;vvbq{TK)~4xq%#|&GGmpzSHS9FTbFRWIMA?c_ zpws308J>iANerl6J3cIg=u zt|EHEyJ0$Gw&XCPf|Wq25LT4CowNmJi*U}Nx;F07K|{n6{)QX z1CB|Yu4{FrPBAi)5q1oiB|RT_p}wLwVGE4b(#3?BH~}}GR|zrZEVH%t8jaz&?zq?P zhWb42Z3oe|XwS+3>MS&Cwl1_$dt*aN)`d04_ZV5hO@N<$V&1iLh)oBqo@QCEYbgYx z*FncpNj(@SEp25lEQDS`lRlT#L9}8;vTv)&&P#vXuIV$aqo*BrYwX)n8Nh}_sH1pc(wGQ$etpc?1JIt|vY8BP-% ze6gHlfW`L~Bemn=CgY{`1XWv;vEN?6x{bY)i@ciiT@jJ$!D*bT$lY8LCDF_$XX)@bLB z$V{LNGZJLMpf0R+F$P4*$^T!>ww}*o!dgx2In|X1@rW}B5MTo*_Rp9tLxLd8pT~(C zW*aRQYpzXAT5}v*(M3VhJwKh~1~hKXr+k(Hmevm(iAp>Xp;F1T+ji7u=ux-`OmVG8 zqK&)GMvyi_H4PcJ%_B6|t?Ri;Nt*6+gMq){goUzjbV8?WNdkddbKTBYHJOtm;GvE) zhyW20+^Qr$FEy3swlV5cF`LXHna{1hS&b53ghr#~(k!U?wmXk$IS+Zgiv41iVbhEp zg7*e>KkdY2s#Cw zcSapGC-H6v238`b0p?(Y2Wwt|B7*z|Q=Bx*gN~ygMtMA@6L1X@l0p zvajg50&uO|#`Kbm{dKh+1bKV2!6?!odow;A<{R2+nisn3$ajs9NK}&b~eOZ9;fi@we)<7RpE3pDgRz{gb^(@1sR&~r| z?P0=cJx@t!-s`Pq?N;uY>3Bs4b)EuHFN$KxBU@Vt%2^zhg(qwf89b$ANyBnJn36-@4O~?= zWL#ys<81}y_;wX~9-2wh))24fa7UEmuxEMB0;+R;3ypGvs;nNlhI+BPk^_`8Y5~Nc zl?lJxkl4s^`-(7{L@H#)&VVobMLZ^XA2UQ&ER%)0Y!o0}-4H1AQVJKl;O z8I6Xc)sSe}8*GC%kqgjl2~5mdVc8T4$6C-;pjujOT~Z(EE4#;vTB5XC!%TB4$p!8e zAqDHIwG#13ZcQ@Z9=oH4k+J=1iw(N<1aVuFp@AmhEE|G^08FOf-N~3jgdJsmWCUCOAY4QWW>#> zuv6HquB5~|jmGxW;A@v|d>;olqe&UG9c80WCb89nZQG5PXcRg*Z&9S0vn>!Kl_M3O zZaB=FdkU5f?OYyLx$S{)7$hUUgtSx7*)jqyS9PQ&z#dJThYN zWJot+L6lL%tU5$wDLPzmU1|W7q1$q;s1L$W`eY%Y@Td!s6bKPwFgYf1E05t;)|qOC z9x`@dg?!o!WUZDFzFMq$Oe!?MrvwXI1NSi<^>T5}*Qj7M+=iLwTOUk?u2Ii7RkQ;x zr|7Cp7Rb1mg|OllBE)C2bSd|AtgR>Y8UPT1PHhl7>BC!B0B$=Cc9k9@-L}CQtwr0= zNAVWm1U+{*Akm{*%|0&uc(F$6R%6Zz2FHNWkBks56WI>O=E#Huft^HEjJ8^^ux2o* zY3Ta3o=t^8v!ZCF_lI}^uK=pGn0eWC`^|QP7a=|gasTfq_orMZXN7SFD9WG1SiALK z@g2JhVPe|>v3fk(GH%)5N`Qnksnh=sbjsTG8m43T-M+M>snsGIPS$#lU;|3l*ll!ac$0Yn0vV3pZbRdF33iTPjUg?p6QjK#`qQz{PDpwLdb)Xt4Hm(8vsmR3 z0>b!#piYJ$7uC%g&m-}e#%eIVxeZthyj&oF&(o{isT!k$bX-VcDWe=s#kvT(c-vbm zU41*D;(E-oTU@sq6R39lid$o;P9~w>A{Rj|d7{=tShi!0OEFyZ37gegHtqChQIG1b zd5h<2gC1^{raDxo`ikTcuNwC0B~Ukz_8Q{kAgq&YR&2cCh;?+H>5*U}D^Xs-o0TOD zbj$D9zDmYhd!uFBVPo)B$LVO)dV`Gp7LlvnElKJH;-p%?S`MWuNfXcrHtI$jcyMXt zj>&Ibo0ICKlniw>Yn+jdE`$(M#)#Mz(@vw?Mm|v6YZKz}b{sD!E7%KUFBV&{Llga( zP3Wzyj!qkB*4sj7xDZDmgStisA+jO|69F)?Br|4Pnl(qMp4zy>ZVjbf!gyk-O|O7O zGIiEZ(MgYxbBC%svq@tlgvFd!DK;OKM6$(Xr&GuBoY|Aj`M^ZrImf%&1a5ew)r$TpGV1_b(RNF7X8WYkjz5D!E` z+u%Qx5_kv1c=`hoar0I@?2AO-p2%`2*QlDQl>iS%gSd@vn^P}1mem57vavcg?DO&^X zUk{D#bQFv@n3cOTj^Ke21^TB7OslbCZmddm-k9$8VCAPZF3+IM9wY%Xm17JIMxcB_ zu?kC^bG>9;P9dycNZY5%1~!2j7bUe(3n3kiL5hDXj52H0++tR6g@?E*ZKXlMGlU&M$r2`E z3xvNM#LR9h>orCRz`VbSs1U!gMZnX5_NV zW^Jaz82|$)G`doLYj9 zCcv4lU2R0bZl^OgqAXgLL%zFG0moc7$JiPH;=3WsOx=29Z-}O%&txdA#MyF^#F#|dXm6o;U) zshBg|gl)4179j@RZTC@w&{pVjS#i^_R7>EfmqMw4*7Ul|mz)19c;l_&|AcLtZrkf_ zIL41awfQ{g%ocM1U{7INPyjEKU_sSL2a@@=imfECFVqaaR#I)b&Vn@zm4Uj}UDoy! zsGhQowt<)1ik3wu=`M^I+i)^f8l4G{ZWOJ0u8YpA0*HzpDyTQFC=rS#-OXao7(T2m zbx?K_RmoOHHJ@Nc#C))FR4OIJ5}mTOSmUL}_labxQp1fT@#t!3n-tPh4c;A@voOna zB^x6k(KwMQuj}ua^Nr!%oZo=1t$(#ole`UR=l7|Jr9?qSxjw>7>2d6 zWR3&a9z*lk2VvT{wn152uSd-zwg9sLUI0x){emD0mzAik3WMqneIR*ycbzS#Vua?3 zx>Y$)qcy{F%4_B0;nH#91tnd9<2x{g<#R)CIgKa4QQ>MF1np@pIdCQIkCw& zHWed{iMa5I2~%@QV5s;7+O$B zG#mIMu`wpy5pYzb)kHMv!DulkG!uj>AYY$Za|2(?VhmE)3w^rcTmHg?DtT?D@n|+M z`JvoEC;?#_zVXABskgp^dsZ)-0-i}qoR~XIQq)X0b*kb5z;TSlws+R?63po27 zwzJM4bX-XD_J+1nMAd-zq=*BaB9y$Af_%7~YC$KkB92J4RS0G~;Atn+*KN^QDrT#X z`;#mh(X@%Uv1Tn$x)yBGGB^0roCq*z&siH@xA-Ya76DTub8Vg`9R{CG$9#wCk*1qY zLHLAZTiq>Bf?9-i3d)yyU8d^w`(QD&J2N!N2El-k;!H6UKrn*fNe0V6g`t8v#uAgC zOe_QWt8)$3Q)T3V^gVz8J_IppdfQ{WRybQT+cp|^y74pvkq1GI+NuIWV0(z5&y|y? zfxO@;N?*}}Wp72XdJ<59T_-SICOmjW_nXXgL-Hac>SIc;wdn~lwCREBP|-v*xxuq3 z17W7X#uPIHbccOc@85Xn#2*VmByyZ<56eCmfd7*Dj=WX%=nEx^PzQ!Ra7Xq zjO8+EkE@DY*(8^=)1^4vCQR1|q&|Qly22)Q&jp-|-fDON_i+6G4$G#%ZvD@GS}4TZ zwWKVaZjS8BwR6$v0#*2*u}lyY8U*MokttPxWx&v&Mc3uFo)YFlv;YxA8^fl{HV6}m z3ZDSitHlia)4Zp-c@6$q_y)6);o7duSgwG3Gl(W8IxOnO>uFE8-ja0Tj*<+QtQB^H zj^fasxRn#tks`!n>uKF_XG4<*(jQh+c`*t(LFPIt-Zm(QEyFM!PlF;$Qg<*msk|bk zq7)f#CV9!I>#H~qhnzf|0sBd`P)VK6`xAWPcj9%Q?2m7W0;*RUw5fTA+|nqbaE9 zb1F!Xf?j3-U<@f@kgRj2oVT8OtE_4z%UVY}JkRl}3A`93b}gf`s`^8tT8#p2L&msd zumLxkNY>m*G2P{71|xVXrw*2&By`0O+9Tje3X1K>=w>yYhIBK%1UO8^f=w*E97?Ft zmer`|&I7lfHiohT(JtX^^_WjoB%nd@3MY6V!RxF8vF|}uw6;oU1DH3St0<_w8cpaq z>7@389Ej_2!K~y-#hZmF+J+Z}qh#q5lfi`E6w}pQBY>h3Nj}1KMwMqNKHi$%svT7G zMbf8gk&AgyKbQ4Ljmhy%AB6OSz^dl@Y+iY-x&)3nP>d=Izj%P=1Qzt}>X9z1Nv_SMA93WburyzMlrRxF7bA1+Gw{*0m2aYr7 zv0A&zBW>8Xbz)&4BR8shL^kJYWy9Vy66k{C~* z=LFm4S78uno#n`B&u8O$+lHh$TF42=s}2%$EbC%{*y_v=xpG!^bOGkaDl%KUP|VKO zR0{IwXaWok|>_Wa9&@+yx;Surp^w za{|&9xn2r{G9#R23F(QTPNR}6sgWp+H3ScnyqAI$XS0Kyve(5q2v7OYn4IHNYB zmNx^zz|38Mnzh{U6G{ZqmQ{k}O{>PMni^LQxx)I(k;o8Kfur#Z95y0Z#+76=Pfi0I z&IDx8vA7jbB-)_^rl2}=q(u>}u09@2>9ju^cR-#lil-DLX2v+~XRR3x+__OU#dSpX zhJAH{wgbw;%@yNw?rbCj`A+5jTmXqGdV`b#($ylP4Kr<@T!PR8JppbOW>3T<2ykbF zYb{VmX$(8_4g}oG3CDVM2mGd^MZ>nPz{rd!^Fb$H_gDfH=Ys{%gYnXdX0h9%L?c7$ zNbFEUKNF)hOn_hN%m`8zK`qXdn681{DoAD=;2@|qM8^YHqN~X=0l`&*i9-?;KBuiV zmjzH2y6I9FXOUzYxK}%(EQ6wyVPbj1);1c08az%2?GXm@k}D_A10Sjq*qX}=SI>tY zh=_SJu~T&h-cSJx93<{&z0GEZX<#0-?3HCcf^#fP!AS<0DA%X}yyFx#sm0+S@3wo3 zg(4-rmDPiu@ zDIyWWbr5922#}gZVr!MV!)%kmWD8foYC0sug~{ z1W<*M*|30ZD`V+qYH+&>nrH*K#4u2Z3W1^yP%XDKv9_7D7bU7Y3d^-S1RT<+*I&n# z?o*Oa_EJooG)mJ-^FSPUR%_saR~~s)Zun6 zGeXg;DOT@7Q6quzGLc{rowdPrt#w4Cx#;0bm_a3BQ%&Yh2PhB`DPkV1eXxV`g){7} zy9I0G5^m8VUp4z__osD=%b>_SvQZ=9C$f-tAaVC2cC8`cjzHtl)c1)U(&ty5(pc=9z)v zGgQ+V0vW4Xlxb_U0?rgMYmbdZMDmb7<0S)KPFra)f_c5yo;x!=$}M%4NN7yMmdUJD zrVz4CS0DI8E}Hiy#xxW0aoe28ZF$tMv=LORn(si_#@;Z3~ zo+r%$kCH5WZZw#~1}Y1$iY>c^hgL0Fm9L>o6nr6p^#RAcCH1C@ZjbOf<`6f638CjO zi(56qP;+YAxCa(6-^A7(fCNDnCoNTsH4rnSWK9_3n|2y8SPbDp&d=6>gEXgi7Hs;s z4)<0ilCfr2kmi-s+AM6o$d@q=3j=Ho+b)2WuI}Uz@TB@`yW4a4ya-jXyQRi6wvK0V zcL}9}h4BVcCewBZF9)dIBG(htkO*qb7NDw7vGrD4For;AV2kHcZJEhxlU_H*2Y`ajw34L)rP&BDemM<*o)baZnSmS7*qz~mvCzQ};+_QdLeZQ| z(1eT}qhoC}1-}FoB63WtT7^;ia>1D$SO7udZ3Kbt1cw4nNo?%@p?nB@{hvSIg{gnO z@}~Fgvddn(up~aM4!>{5bFbuXe)Ng6hD-O551;g`<<6JAN&eQ$SoT{l_V#+{?Mvnx zZR(>Zedvwt7k%nGr&6z{j(bD@xS#KQ|C=7U=B|4m{n76>cRujy2M)aD>aYFbyj!ll z_wsx0yXv^#-M)G7o{P_N4!rlg2Y+zTZy)^ddw*n{_p$e%n%{b&`Rs-DrQJXCoD<&t zr`I{FUG@BM#|clL{q9Gvy==|h@)s}o>pLI5`3C*Nzm!e;%H4PVsV(Stj_uTT) zo$L*}o%e+k|7@HS4ypIqOZ@0vj`q{tp7D|w|F74v1%JrdZ`dJRc-%g_zILxay?(Ld z-6U6^HUEI{O!AOFy>7&gh2QL-^425b7o7I?@Bs9h)omBq=^He&C_nS03Bmf9!F>?MEE5#rMum8>zcYCz3G$-ZhhyWw+I)17Jemr(>Yh&%N+QM zrw#S8*Zuh9ov-d*^ugr-}mVEzIfj0_5tPn7ay?t;ziu*Gq?WXwu^2( z>-fLF^)K&nF4gl>Za?YfJ?{V6J(r&Woo2}SH@}P!;6L!3? z{P*KO9{uBT|2+=MPO`4~_g$~J+C6%YM}i{{NPZ<;@lUmU?T)v6=DHn^f5iIs$DrFj z$=vk%10>~*PnS0R^$Pnwe7VZs&<9;@gLv+k<Q~?8-}H-j zUUT0g-?jGpr{^DY)Ja$U=8@@T&*m1_Uhv@6m!0<8{cnHep2DTO?elo~+-LsHs)`q% zd+zq_bLW8W-(R|l_OwsE=x5vyE>}){+HpMLkZ-?)xoD^Nz4?cJd(7qUJMcf=iQMw& zqk9xz_~VbB2=4vFHLtnZz50otyzAA9?v_-u(1KI_>ZE zt+VZ4p7-^KAKml#;Pyk`d;dL0yimL4@UMkG{q)}^@ZOadd07gdk^}{pPl*eH_tl$eDinr+<(?F{O#9${p4Fm?>*p-FW+Ndc*<*@ zt$*R(=iUDAzrHv~uKA*Res=0VPF`M~;$P5RlTSO|AK7upN2u$L%xAY=|HDVaUmp72 z;O>w8q5Rg@U#VYq*XO_VtBawZI(Hm@?JalQ^y~ND3Eg+VL%;pTZK!kC^Y(b;H_tru zH(z1)Ibo>0>!zb0E5GNRZQuLwjvsvT(bhem{llXV9&_LAcfaV?J74`a{d-@%2yyCYzcK*Ts=HaIwoPTLI>?ag(FGUW{ez!9v-WqTUhu?cE(p&WZ@ziMVPCqPe*dXa?p%2v$-VE6 z=!^BGpF8fEmv8QP>$M;G-1{%u@u_pK<#)W~X~+BDUiadU@BGCNulnqz54`LyU+>XM^6AIT zsSkYhdg)oqJ;AtXFJiwd_d0#Y`UiS?_HpDhUUT^i@)Q5!jc@(8Ypx2? zPrPxj)?;t|Tj2%YyyfUGeeT+G9{%M+haL8wckg%L5!r9waYW~utJ;^W-f{N3Cui>d zz8!l%_`b7m|8oc;_qz0@%tv;z=fC&YkNoxyaJ2vZlSjPu!F_LE!k6Cg@kgGHV&8iy zvpJidJKsC}rTZW8G%daH6~`9)_zy=rEIoV69s2E;KmX=KpJr~D{f{m7_Fq<>@*jVN zJ10F2NsYaKOkQ`{wZ>yd-hJz_m+XJsmyUM6b@)H;ch%LOvc6qXr|o(2v;GW78%2Ea ztB-x+p_`^>?S9*<_a8oO8en14OP+D!Y17WDe|gf=w(NvM?tU&Xq-UOb{hz@4Nljv? zXTIK-zPH@@mZ#}>WBCBUSN8t>r$1q@m%rpgJ6YLeqKIqFYMV!C>!tPJa?u3s4x^T`p#TnoU#^3HG{`7`1d(-c~ zrl0>5mmv=UBx6@*e_$#0;=pu%?OgtP|FNH(r#`i@uia}eakpo@{xz=!kNEU+n45kN zANEq@@kIU46~5%fAKH21E+2UzI7y5Q7XR3(`<=M^F}=^d{K*YF_Bo&jxeI%ILx0}1 zE9f}>1o?r3&$#(1c^>ji(Brl5KBo^Jb>qvP0XlwqboMv)yxymt6w_Y2f*vn9fX#W%UZ47>{zZq?SG)$Rzw`6!tJ@y9z_|Vc_uc%x z@1GZb;-28ahqvX|fA(eK@5}G}{xuv9J8;_dk5cX7tw8 zDc^bE&V&A9pg-{y^S-bC)kU{G_~cJa#RqlV}?7zJ4YuM}Fap1A{50o$P{4Gze z@$mnBjcKKn;;iuTZ=ZOEOI`Quzf!TZIP$i;UvbSJ|7CpbXXVe_ci+V~ z@ZWjU{^$#KYqsS#|NFL_QxwlR`_qR!e&rW`aq{OwfIa75|3~HV*ZHs5_m8)3-+A@p z4jJzc$hmUHH3?8pA~>LH;_q$u~0bK7dp8don``-KM+y3{a@obltslGykj4GQ?|*T7 z;OUt2+54aHuiov|``-SdOMunC{XA^6W2b)6yRK3`d)v2<`oWh(Zl9WPKeX>Z{P85^bMN>DeKqtoWAitQgYVat z_oBfUj=ZBzU#6} zSK^NjKl*~v89V3P3y%7$;NXwcdv13gcNKE(5dn7*z52~fzt3L+&h~#d3cvXG7YjH2 z__<#>@*?w|gYLcc)5l)=;Qrs)`+2W=^x-Rhu=%cg?HSldcO3PD+sfbE#2#?;V}BQF z*jJAJ{jYC%CUxEKj(FRJr(b*UeSi0yZ~euy9`?dLx<|cwAOFoiaHG`^!Y^KP^kMfh z58QdxkACyYD{k0U26FyS$?IU@vf?N6<3ISZET;f;G;z4OF#?z;NG z)AY0c=DHid_k912A8riJ-%0=RO<-7Vm>^Htu-ESfOu=&3Q|WV``!ZzDV}A3#kAL>D zFMWJpT~CBA3ZjD4fl&fqZ9VH`DfegwvW90-rZh?0ObB|ec%B%9`uec z-c>&Mhr1p=3cKOV?E@e9$1_j+_@3b<2b|l@=K=EIerGMk-F_tRcJ5uB_JO~&+l|eB z!-wYQet74vkH6S>ibI_6ZeV1e`Jo%X_qWHMecb#d*T3)CfA^l9pM2SuK6{Gt+2nH{ ze*TX?aM@j#{_)_)7WrqcS$^)8qaV2PfVW=$;O#$o$?2E<`|B?I^s~giYn*@l{(I;* zqZicQG>TWfY9IfU3x5AEZ~oC8H|~DZm#;nlp1=JeeC8Q%J9vjT_~74sP`jyGGc#UOqZF@0c52@tG5MzxB!kw-=0FeBtItf_lz(Z$|&)wujZ9Jbd~GzW(@! zk2~w@@&Cizdqzc-ZtuQ=gd#}+5{n#FvPjMuM3N{ugP>$YpvVG6P9h3O6i@-lS)j;C zBncupNX}4XB%Zh2|L(JI-@QNFd&jureCW~b7+BPL*IF|?&u`9d@;v@TGMcKptbFl+ z9>nnOHhyDnQo%XMn$N%T_$)e+gc=fo+T=t*288_Y|7YctH7IBt?=oq-2#L?nQ(mj!Bo$n9GZnl8e#=c}kdf)&EBX0Sf_3-N9}1EyGiF`MZvpDR zkC9&v-1xePkv3^De=#GF+7C&-`}Jjt{{75`lYkpDs9s5bIk@{{9Q_O9UT)i8_D1}b zpJk%aZ<d$G46 zyD=VsXpj#0c;WGjxW~uK$zH#tPV&N9ypCshhToo<%lz1A&za};Wv7^vA&c?Qo?s3|45S+8EO8)bACJk*KwCZvks>Dvb zt)pcB=xX~%?2Yqcm8^oaynOw}57Q=9X%}ZZO-FsP4MH~O4jc};JXBV+1N@VXQ_qfd zd7Tvr%p7}kok|ZgovLu{bj#n7Wmcfm8E4dtm7Z}%PhF+Gb->j{9Fezw+QmT+#^mvm zM7_w0qOEm5Gx;B-r7bK@j44r2ZTZJ3>3Y4u(6h%Wx4@l>Xg$mf{x7#82-^IW;ddvY zkNps?$L5Kd(0s`D$YT82)F7Up=K>LSy7}73t~P9{#L>8@Mi<^L zmICF{VVOYD)hm9F5d&L;vqWOhbha%>2%=SxL^_=Di9<8}Vzu(gf&ovrt>zqqdW^*1 z$OlJX9Zr2J}*^I6XCDJ z2~P7HRHPhFLuJzH9o#i`h_Zf4ww%T^P7y>FMo$9&A>%1-w zM<;)^1k+tF*_>&Z#J_pV+*mx~c9q@F=lgV#R`*TgBB<54=waK96j2ZQ+mqSs`mrAW zq)u$EBQn~|_b(YABF`Lq;>A;D6F2SL2OF(cb6cs@n)RBq?8K)iNTz%t+irJ5nc_@9~NB(KX%+pz3$k(cc}Z(hO)TeIj*AWc)i({n5XLT;WHm8rXOxhHKpmhrzH*Fr|G>* zQ=WW91rYz%nq{l}6na$5n=(7&wP3*M;U`BQqvVR=tp8NA`m%~i|-M2WSt`VZm z5ZUz2gqX>~up z%62-vTbI+7T@rc2$JqUAlKKVDX_XM8!v;}>?zv1OpS(47g_}W%lr{6+4LRH1s+q0ExQ;V68*t_LdvB=%kBprvd!=rpxFQ&r z*f9U$$IUik>B?HS6|s1?`F6bec=F`? zds(69iz+?wEMY(Mb-M8CPBKzv{m=U7y%tG?{iC;I>BJ4|J+_P=!-oV2%0<8BFM`!W@X3uCbc>DG;Lo?g zsc!e%#wOcJY`*2x^Kb({u2f)9@rg-y#(RU?bK7&)k5br-Z$*57fJ|c;QAba`B2O%7 z4Z>3e4AyHNmAjmvDdlQhd-NsL%Sc<1wKC(BpZbT_VIU9hxjf>IV122V?Y_dqv-o*@fmlDPvnstSlyqHObGTF}v`Uz3 zZ%4r8&3>cAbXA0S)8&HZ`0%?ZhtWh)kH?KY^WMu|b`Ya|q=aw8`xbG9aH@fDWw3 zZLOo9rOKmQgwwBw=;*Mb7i3Vlk1B@?RA#u&v=Lg9|uk@)FGihr`0SM1J(Xk10u6!5=3n=SX&2fBAnhu84`dNYoW0J?30-DGeV`v1+M~aNP z1ZnOMYbjq{UThVVG?uIJ)V5QfQ$@P9>VGh(tO0M>`^I_HD=;7us7RNE-?@1_8?X~S z&>R%LAmG2;pFSCrdJ1ak{&aEi9Y|1Q-6~n{<;emurD2B%R1y4a(?auast&)iBlkIv zBvbGFs;7gk&zF1G2z@T&sHg<(-dy}%$@JJLs-ZEBVNs6#GC;v?xY)QeQB_b-p_L`4 z0bzc1%k;$Hv}QW{_SnE_V=Gw+2*hX}A5RIs^~68|KFc@9vId$>VZr zX9NFlr|GKEo|vhf_AZ6Ot?a1ZpJsjIR=w8qbJNV_386Vv|WcqRw?1D_`o{$Yx37< zXAW)Hh(EFjJZZ^^fCh~ho77Js6}=^ujzb7ie3EAr*5;koOnQH~{dlS_)<5bR`Pe{enJI_)~A-RG*WHci~I`0=2Lp&FXT9EK!Zm_8SCL+&2^;T<`eTu zTyC@4X_opx+~nzPO?1&L3OPh|-Rf{zB=V?nnodiWjmAoJ$;M%!%6VIE-A!ssYe|^M zV=@tefsZ4KvoX`)lb+?X`khJq>U@9NlPVsr!e@6qMg=MA8|E1#CtYDXu)QwF>W6B< zjlkE5(j*~KoHm`^<>J3Q$;RQupl3VPl(qhDMrhS9Ypwn1!8=P$>5CU>c?L+htMN2) zunW}%3%vGD(x-YKOACq-jkiG0|1vO|qm6*~>~Pc!G_i2Er;{7fOm5*rAH41OzVCcl zxWVz@c7ylfb7ov7l4!C4f_5sokRX{3SjbDz9ml|gJ*K{N-h%(quW7FeZVpsrwXlm1 zPeBwbYZ~8;o$rXMmtveqc2?*sv+7D4h4@RKqk>`AGb)-lTtV*WPY8h?G803UqJ!<3 zCN}u%n)b%TjX>8Un)Ig|#*@9Ki8uF{rSn0}=eKI&B~g0w0iHnYx=gtBtD%;&a6~>m zeNcK&k^T$EW+Hx!Lr*oG?*8^(e_OflPn;EXFCZ5QT^=?%(e9_Dq@&=n7YWoooz{zgM2_d^qiRl;CTcY+y%{V}undn#hk*lnOwk$@g zYd$S^mJ^T1vvfHepfZXBDx~#o$hst~e%J&&b)zh-)>UVyJgq7)Snj=|%$9|lmhQaB z`Y3@8I?Ig1Z4AzsSr*s?6fbZDL%q&PHHJ$&gF-fM?ra?%to<-~O6)w{Ajga;L7imc z@owLe5ps*FA9B034Kqe1S~0f%WIk$Py;(fSHe><3dGI%eLre;XlM6H{x@m&lg6uEXRA?ULIn&(&TuD|k&U)Wzx*RR;_P>a3D zbDXH`rtA4)>a!(CnW9_cWYV_(QeX9}PVjC_S*%uMC1QV=(E*9TI*6+6h@y-pdywI~ zrz*?=w@Y?zC!FWe8vbQsd7g11`)ZDEveY7&Oc1`0@<(uXM3TGF$DeJVneD;8fyikk zJmnHh7K*yR>fKHd@zjD=&&2($cwDLCGEBS8o!GOTlQ~iBgc>e6q=)b}&nCd4!-SPs zR*qVIDcd;v0jiD@H^qO+NeU`2UlltTRItJ;364*_J%h#vP^FBlLM7?*<%lw2A`7#f zJ`*S00BLKzr5>vo*z^igcqMJWDJ1=eZNMtUw)2%;O}cxc0kAj56SiOmzy>O_n0sQ$&;{N3bT_No2hUr$;Df^$P%?qXp}8z=|!$CZZj+DWin zO?%E>5Wkd(fAvU=DhI+@;y+VK=0t8b{L6yzX7nM?&AX0+W{9tQOFcvw$`-wa&LAA4 zhD#|zwYc$T2ne6HZXhv*TR-w0k=)0Npg~|b_NNLDq=$+i1P*aIA>^lF!r^iO1_Fpt zd|9`%ts2;z$4w;nu<{oZJ`K2y3XaTEdec~r40vlq=t*|yz;1c7u)pl^l>4a3_LR#< z5b||FqWL2ATw=fLoKYX-0f@H3%>_p5xFFB)ODIlPn$y&m!I-yI7ST+Nd2?=^zf67v z`l-im@K22$Uab9*bD96C2hgq0?R<1mDn(V-X=X}YJ&QghqB??*DnLRvBgr}E6^J&7 z`5?Oz=EC%=+)si0suDWTy=d+B!uk`~x02&I}N7m6sRN{E5ngHol?nhW^tudh9h zr#$W*3v`Q&nXe(R7dQ~l4ps;IH{?h$oNt&%#K+(USEC-zZS9Q=fA>V*Dz)@S zRStG(Ss1grGM2Th|12>1O5RGg6U*#Aup^hkP z^}agyjY8kwdm7P9%)LpD>wy^HmbeBm#4yb*Z5BwI*mvzlTao0aS$j`wo*S=7(* z|Db-#(4ylNPpCO@z>I^{BI$fbkpGNE#fd~#5K|arj*8HWVx81zeOsfAY6#gl7tMxHF5!!QqIO`r!}5G=0$lT z2pzq~2PA^issya@+X`foVM^lra$j|Setw+p(#{zyf-29nm|7sWh#{qqb{QY|rLs!l zIA}W(jtZdS!wqLaY9gw=@aXvtf?fCIwxPG+8F|6{j5Z`Sg=Ch+cx3J3%6YU*rlY1l zMKD-a_^zV*FW-&<|IVt2aC3hZv6kPZ?K;7$5O>Mv4JsLVmnB` zl;B%lTS#%Repbe)f=c<=-kICo!8uaWwK$(lu`Zf$Tvf^E-*kFQdx7#<6$@~y$k4)5 z>axIZR984F7KB)~ki0c+Z)IRd;xQs{?pbSUJG~(IEIU*R^mVeX8kbqzGxz@26FUN4 zW@>hsLknI&0d&krL~MvHtNZEhg4pH5OXB4#WWa&B*Wf`*WM(?LV*BEN) z$&Wfbh9U3K&>&cx%*IJR(F{lZTDPU97}t6{(SC#FY|-Y*CDjr=I|Ris48a0 zp@=S=#6rDKl)E%-(Y~eBA32iaU*#YPROI9=Gf_O?aq2yfm*}n)%QkIX-eY^l876%- zbSIJbnW&rbQ??%A@}Zg;^O74IDS4rq84~14N@Cg^>~rQ3DXcPT%R1ovu7Cbd!re-; z-IJ3IokG7+3!x`dG8>@Fxj6aZ{I7;skF(2Sa42r8JJ+nbr0JqRl9JPbtn;Ae0kweP z46|pK>-ztQV_Ht4dymWOKffu9rXFyIc_wnZ=QK!sh!T7{^y6srV(?VzXYbar+;8gz zp^dQ%ugQZB;Y4x08}>&h*PWzk%Dc5R55;>7(K_arh#jL#`{GjI;Ript zE{~4{Bi^W%E+A1nM`95l%m%A-_Z1l>$snF)Y6DisZVse^{zI|x)e`(NRMe^JM+|p6 zb&G!YRy!wKtl0KgVn@w7lRNW1yY5|6-DPxG73F4Xy>CNUGuru}B6ixWl<8v9psmhx zd?{%O|2|<{J1EJveh1Py^wsqpjeH>9Jk9>SRckvjnV{KZ4L9(gZfK9CJL|!p((l}tj(J*VkkaAm{jB#?DShww`-({>0B3nyNrALxF0;C zyc3r9PS7_0Ctx2A*N+g7?*v5sEF2xIbNB7_mKqmPDsF#6{RybvQ*DyxU~h$;tq_d0 z0rkaof!PW5Ae@F`Dier?)sB-wH3N8x+3fST2LsWse(Ut8C1wzD@SD6{jOT@dbJS~a zyY-*Nb~_JJor$Ffdu$p6hW$@}zck7%H$UP81P?U~2)g#uUf~y&R`ErXr5)QvlY?IO zTSGFLl=x1XPT-&Cif$QwEOUQ0`ZZK)a>gqRl)+YJj%iEn!(@&bWzU?6s>P1=$^a8p zz3Ig{0i^YMDJ{*TC?1!fs34WEua_hyD{c0kWiNlS9G&>>_00%~h$biFV>Pn`Mmt{b z?v8I4T}{?XJi_bPXl{`XuHOGv%CQ9~AAKO)j;qOwO`<8js6Abm3|1gdb!C=6tDu;S zXV4ShdC<`1JvOo>?$A^BY_9IZP7azNz?KjoI7S^S5T&ZjGg&14Zf^Y)xw+7iK@T$X z^E2O4Gs3fEM!PYe(2zZc)vuTLK-=VT_7ic3wkzBHC=HJbZkGXcs+w*Nm~(l7pRe|Q z2c_AU2HCGtou;?0;}E*|WNGPF4)}{~3WLdWtdy1fIT4|q_8jBd=TBDBEd$=FNCC*bDL7htaY`RpHB{jVK84E1BRje_WUB4+i z)g9O|YpF6{&J0iK8v=3?@^<6gdn<1S1YV#G`?8?pg#u>}qgmOU^mxA`1KY`N9S)+n z&d|4Hn_&zA>TmLD0o8Qo(hr#ge9*L3T?W}b2u!XR;w+Eq^>vQ0ckT;wHUv6pt>{<1 z%1|^oS?#rTlfw?_eG=;~fHp&c0*SQ<#d~jgL+6X3=Dy`qH>v1fO$dl~_x5k}b zw#{jaYD>?|uZrwi7XDVb0n0o~V;=Qg>+s2B5+)f4HH^zUBgJEDLR9;EfgUdh)fh{z z!+5z9VL0t&oJdc)cnu7<9?4=i2Dus7ZWHfdqk2MF|5e9KL_0XV_I$6$#AwvmEoRb} z#G;)&K032c%>tn%?+||xy*pZjXGHKyKWOlfHCeSa{bg&>Fip$SW@x#~oSZPd0uhrVP#q)Hb|gHvjceS_%b)b5<+a$mwE%&93>ICG)TT(f@~b(zDB<*wM~)}pL0RM!QwJ-g}^O$pUDI?O`U)I zt@n@e9~Ngq?vxDYX}7VF%OHG#94+L34nO|Mk?A|%PLmz_T@)z%q3r>X&%it2g(iozSfZXFUv z!%WM1=mL`e=Y62sG5fX-)*X9wJR##umdUSD9q&SRk5EExFM{s1gSTbjAKAUSDfY`!BT;3aLwi_}CohgWffOO1$ zy6{93NZB9krL~3;>u58)LXpw$57Ok%_7`dPKVI^`dPf@$ZzNM;T!dLa0^LJ(5=if# z%HG9z$W!y|M<-g8RKVya)Ng7_fl*wr7$0qpFN}1T9914zMPmzua{`4aN_h!*x&r{b`K!Gn;%IM$Tqjhla|Uk=!@R!hGzRK{R^pM zx`7Ac?7hfG{RrJMzD&OS`)}|3X10@iA|1tR2O(j}zqVnDdI29F@V_|J11wDi5uMoZ zmZSXIbbU<>wLm8i5+zsjl!2Gn;Oi~8k^Y7}PKA9*!${0KR;)P*K~}tG`4_*MG3w_d zInz{ROH1k5LCvf&^{XKZE0Xqv8L7XaQ}^Q83K7c`;eh%tDZ!Rg^6A122NIQ8bl?8Y z>@S8bkP1M7WYY>8a}0FSX!zjODP*;Ac_8g?AgCRJZZX*niLX{q)*R5FgR;!AV8F7% zKO3amyC~Zxsv#bZM?ms|CDDu4#sB$veYRJm$5r~)+}dPO6~+9ZLrCLC;|Ezk|G)DI zpb!H-(DvP^Cw(bDkv9hht4^9KcpFbFlc)=20x`R_)8i-J5s7w(E^le?gD72J=y?9% z0TU-p{^wcvLd^Tz3lMBQwrf`=fRt-8B2eP84b+&0qc+tC^>}n@6VG^IhO8Hn)spGF zm}`OPLcp8K%8n{nLESDH`%o6371Mt}i96_uQ2c?NZS=_}_0$Pa5@y?@t}^}D6^Jl{ zCGAoK?UxM!ES8x6kd67(G6Ydy^05}<B(9wKd*7c-!z4_!w(Ha*dk&FQ!cIZH5Tg4d3E4 z{!+TZu!6Qi592gz7pt$ToTewd-lBTZ8rYUASw!wKFaoPI(#6JsO=g>` zk^cNao`8HPp~uz5@noOytOKi(O!U$~=B!OG=n>M~Vkb9j7Qed0ybqW_AeM_&B@rG=+;;p!*%bL zAZ(3jW6x>#>VPYMTNh!w;jh%cO_?O{NlHPUv14qEt`PZz16_gp0lJ ze&7&N{Q?#1>EYH}JyX}N8J9L94TN>~Yqr(z#0*jnYDqj*;9jxcvI`}owoKsAtd6D@ zsC!i_qYX+@`ug2Y*cRHPV{*<>j;jU|`2-Mg(q1;hsvO4eia%cre+zQ<*YBa%*2c44{*!xuHo_*x`G zP8^<(Qem?D_Lh@!bon~5g!%D|PYFoDW#=hfIaIGQHwVc#)EKn4ue32gaxse1P@- ziy#CvmN#5cc(CQfLZzbf1E|&d8N0M>i6Ewg1NO2#;YlDQO)>MbhZ5m*`1ItU&w9zs1rgo&o)vsn44&z2S_PskyF&Nc zwNI%U*Xg=bXeL5&9m(pH#ls7=vO^E0!etdmum?ylB6;nC4ms-zWNo8lP8rdx+CI>* z{smqC#j45g?mrY+sA^VA(0WRi9qP{R8&`u-LTF)Ln1grF`@QF>q~ILTQ+YCI@UtA@ z=K3{3GUGMQnQC`s?q0{jn4u-bEi|qjDtf|%*ZP`G4IJXHDc3GK;IDjVz-X_7AqXwt z@Divx_>AV@I+dW8%HfOG+&4zteS^I0oNAXS3iQje9jEJlK41E_gp}ipMSo?2xqN2K zG7Xsl?118H|CZX&_#GKtGy{_s+z=w`16=&{u)r$jT>>28P_YeJ)SX{NEdnjx@rx9K zbLE-Xku;~Oau^CxH8Z$z1Ph|B^9UoDLix3kPo>)-gn(Twbj=jdxLZzwsg%es*NHM@ zvICie-eT{%4MiXAeo)83IdeLyq(vp|m{ zf08SiO`VfKYYh$IOk?Vklc=a+wMruOby}7~XE66F?+Hnt(!^#m_-Vnwmt%gF2H-+9 zjg*#+*WjIS8`J%26U-C5-!esExwZ+YjxVe+xLdeD?*}Gkv!SUi>JmsZFr_$1AVUN0~Q=>|?3;TO$}QEl#Yc;^`|@6WDnaZ~5H7 zqG)dgpa4S>`x{AIQc}SKw^jrmPn5>ex3^m%l%_5Q?wDutsRvOH6zoTf-NmhS>O8jW zKt68h2@lSbeTuyyOxum$PERE6x&4AUg04tXlPGBUe^8ye3l8YR=qBLlcV^&Kih``a z(w7~FT27-8v=bTmb2_BnaM$$bG5ek^f)ALklheb5EDnxXRJ;9i6RQtVn%n|e{(w4V zr35(V>nQ70Z&o|f7HVS5PVp<1hVe!}A6u=8u4}i2f%v%mFoKy27)?tv?XM@BfE-Y5 z)pcV*og4Ov389kSErlOW^Uw_^G}Bee;wjut1ZOY^^6fQSRGH>=i)Wyi06dhNm~8Vg zghT-&dtt)95jf&9cgB<(!8{9Y zmU%S=vb)F9TRkzW=$d}MW)YZ_?-w%A^%5xy1vba~@qY&eyDi z&hj<5*ToHf+}KndtaF+c>)Lr|o8byu*N%&Xe7G0b95y;t>oz?L;T0KkX3dgInF4>T zPr3mfd(E}&T=<#yN$$zbyzAhp?tUP1TxE?z^Fb^kMZu+$%B;*XWS_b8w&7&8V>*+@ zvx&-lf(eYvDkAd~B_84;fP{oo5V|2E^&nA}D>m)8^fYoEw-7~M zO}P8R&=e&)Z8CdnAib)i6+s8Gm1-F z<#Y2C3Wqi;m@!4fHCsA>9}Gh=Lk0JSSugGmwn?vTzW9Wu$XVY5(t4j+I|0%U;0-j5 z2O#;juMlt&Io%RdNzR8K!uM~1x-x5I z7(Qn^<68p2@eSsIdBg3c!Nm?oxCf;D+@wfe9)=#s* zh8{U7^#~J`a>>bzCdTLzqanqGPV9pM^8PUEJk3a!ZN|$Hz#Z!U-`hoYk~9_)LBt1O z3!;18nxkL`i_I-kDkr6imev6%<$&}RvZu1Mj+{4&ieL{s**ixmEjlD-!_Yc%t}_E) zZMPGY1*N}|kf3vBO5k-|u>suicMxvs{YdM-SO9c}-zx9nakK2&AP&MW3(U)!^4;%q z;wFl~1`3V&QH9HehRX1(M;K)aRJ2(hg=K4#H6`gHuC1WNT2Y|fxB+6BE5?SF8RXWP z!HeYo!d!zV9!M5P`2digl<;k6IO-o+y)%gB=$T(dLMol$=?!A8YIoMPPd6hK)KAm& zV!&`AV+aJ{!=gOKy0PU{zg2y6-D2HIh_-2X+UHOMJ@Iy_hHk5i@&8%AaQpvvMjs^g zx(JG<|K6Cd&XG?mM4A0}ME}qDK?m=DpA+~~na)%GcX0q+l0V&z`tM@`=$fYTMDahF zgW$x#tO6)v*bUFK|HG637$gJ&#h)tf|A%8p2%dGUnYICdVYmQLD7D4XB4zU-p+;Zi*$1RBrL)}$@^QQvR|;^O8~l38rQ2H-^85BCN5mq5!=&TUlve*sAiZX2(ppf!@Fn`1SACz#4ZW?+O~eI45mC!sYWT5I1N@e%PE5 z2zNiwvPf*yqkqT01IYvd)1L(@ogTm=JFTR9W)wsXMBTh?d3L;016o;u?(F52%z)}B z-o~+hu??=C1dh0ilZ7}EGZGHXj7orwcTwj7T_8!|ghY?h*d>rj2?|q;qHsU#_?%}@ z9={eA0QrQrw3d@Z0cwM}4Gj}({ERa6H*Mb`zibwj{9({%x= ze8yFlbsA_L8Ycx<9MEn*_48~FXhOCUrQQK$tQ{EsQ%Qcg%{yp99gpJFdfyx%aXqkz z*^Wlo$$=_2oCKljt1SQodk#~LG!YAQ%N#=|K7vX^D;OTAU$UH!KffUp^3~1NphGjm zXR7anoiiH1o$r^C@<0DVM)o6Dv&R48RCJ*4W0I*|j#5l{YY2gOT=#Nc>a;7`#R>`+ zp3*b*`d9$dR0kEtR>Sd(8?!a2CyGnp(xB|5MtLnn=acA%%LKUpvTqVn#=bF7)V;ubxn0S zB-An*181w@7I32S;>A{uLe z+E&tvKL4`eIrYW$YIhiGBMCS1_sa#gBx6g@Dc3N24%_~;?G1q2cJ(>xm-73{u!1>( z&IAYfq&!ujH=k9|@wpd-%I!Ph2s74fo3F2!guM2wdy@Hc1p2Ql648@La8nIIuv)A6 zGWh-Zarh}f$(@Z!62!k6;%xDr4D)flha-n&G3#ftFHCJCG^58C_YX z&Cy2dv1WgATj`ILz5w^SrXXsUR>Y+lF9bxCX0Oy$SaxXbdp{&Aqy`NuyS6cD4Fm0m z?P=2&e3HUm-1$9ps&#MWFqR#5p|vC-X-Ceh?*qk?Y0NilUD$Ga)GWX~D7lR6TgMdR z2NKaNU=i%D&otEgov!5;^VZCG7mzK1L-(8^T{l6(%LrC{KN61dGVbScU83D!M$}6%|W?1@`Nl=0flPKC&weh=8u@+s7Ng^UF$GjVe6S~ z34#)M^x+UxA?OPFsOtg$S?S#PyYqrUyA9^o-zJi)MLcWqm8=ud(gpMQBc@q=69q+4 zv|qGs>ja;Cwes zoIH+#{x;%fr`XJ0=YIZQyT(AZz%noOXWB#wwa{qd&%~6l-8kUs?{a8v%1?_Iebd z=-H(Lv)usdoy6bU2L4j-R8AD<^IP64O`(<*^wGcw+StHr^=f4wj-WGRFc$>qWSl=DdZIAZ564vnQEZ+`rEWf=&+>Y#65Juy#E0! zHn48@J=Q`9F22x#c&V1OBNK?{2qe>ez6lcELN|*o;-GL=+?(rr{w0Q0pEu%?BrrM; z*Z@xJN-)CPPSA?g5;}@+p>#sOHLs5M82myvIGR1Q4?bjdQMiSbx}#fUh`lAe-g76e^X07i~A=v>+>E4z)?t5-LTs4&+^r!wS8tblZ80zfMv+ zIGIU-NItF==Al3|L(!-fowq9?7|yj*Bt(a5CYM3eetp9MdbiLmi%0G?>d~vv8lYPCLp$WjR>#qnzfn@W*2%lDL=-EM zZ#crW=gL5$e~cP7ALv>Z8dgPujL#)P;v)0ASYA>xQI&v>j-Ef-UTz7hiI9mGN)=>i zkq|U34`x$K6ybqjQ{>|UXMG1L@U%%qMkep3Tla6OgVEtBQg z^AW%R_jK(+rN5T;CoH=>N9}{o@&_lCNjTvE+1!)9)~^bW7!^e516z&!v50UQIPCIp zgJ0JyLC7LO+s`piB$1`XrD5A5iNk15j;Z*7PdnH(ZY2!Gf|R71X1ytc*bP7uQlSFp z42DBi0^O+)SzZyCm}fowaAVXP^Iyz%m=!=_VtQOC+){yfzo0IaX|-wP%i_=XGeo{T6~U6-y!orgyt1lXItR zy+dmIw9|Bqei`Ys$5jWa>|V-j+6hRB$Eo1mjwVCD+XOP_q+P^q6d==0J|wlwU6Q(QA#D z--RVKOy$BpjJ|0c7zU%`zu*4Tte8)N`)`W3dBa-2K2m7r#oXLzZ&Wh9*!U<@}(-%F+ksx~7Up9ZnUik{<(vs zYJRZW*F?EarlEZA5W?HmCro{}ytcco+hRNB?tei3Qa#FUE>xadA2~(~&Y+r$wXs|1 z>ff~XW$xgo&KbKVP^*@AW@MiDdC^Jl5WSs1p0Nr{tW#HA6{!qkS!fil0@uo=(*|o! z)^4zwu87Po`bENG7l$9~8tFJwvKvx;oK!6AO#+&txJ{ApFq>TP;N8s+AE?;aZsp(S z#~P~%>{~#lmxE5m*G&yz11 zuX&P^c&6%A%#1(=N|R>OK2iY`^(tQnlzJKi&aMHJT! zv}$`GWyVf^jqG@C{hp~tTzuCCm~)QnBjr!j#Nnv-Jr9D-%>@dZh26Ner;uJ1`wpe4 z_lQN1ROl8$Jwsyr!m5oI-+exxX+YYUxLYg;H!SUZv!WTtDx7h`ss#H83eg>ldP#fa z5E=@7Hrv?H)27MLoikty(zgdJnP20S%s~QfHWp1V*Aeu1Z$4o(QxWl@x6rhqZbLXV zW=_>>t7>#g$qvHzd}p5ydxzY;R8z)00ztV6H2#H?gwF|6r+1it38M`^7J9rUmt$Lx zfR&CL1gqoMLt?ncQ-gh|Lwxv~D)4OOjt4RW$OgSmr{V%gSjb~2w!+G&) z7Cn+tKIF$6&3lUpnstEwT~wVj?UUj}tL2js=?!vYz420nRD8`1!+6N1UD{u!-y}tx zXOP8?M?)4(P_zJ1sml2J%y5F%V12zxL7h~QXy!GTeya;`C=X@)rA|+5B!t&?JutBU z#y8)vxmc04(UMFbDjcbHD2c;FDC2xqk9=GhAF)LA3#`BzpAs7H=26wzCKnJC6INC+$uCY+ zVb4!|c<1rwFGT(DJOQb_v5H+PcUQvs*jAnqU?o>)D@N5-^Q#m$98J8>X1~e1&T&sO zBW2h55tn=9DE}nU^*g+OmTQX?Ure$OCe=!v?q+I!|z=TZEeZ( zG{6>(zU`+7e8UPlWp1{!B-4q+JiKI8dMP?_j~AJxZ9L*j5Bbhhg&e&n(pcqz zw*s?20nqaZ^n_mqb`MaUao>woz&#>dKkV$i(Xx4`PyVetUxw$cQt6h?U`DGXEBXV3 z4~ox*8;Tj{4cZ{7W7P6F=nluw!+abOtx_1i40i_nJ|Ka6)>CwQD^?!pQ_DP5P3^!w zo?9piz+`{!n`nCdvT-3pV8KhBtP2d;^0F?oa9OtcY z{GDTP@v!PLSBiP|(snZ)vJ;=u-S1LNFhmAh^{<~nl%^%-Y!6MrPKl2t3kj*{j7$;( zdfMX^w9o^n3KLtoh!pc)Wt8h%k$Cg(jK#^5@ z(3NZR$0HYyM@1&l@O!KU!Z6sZEj!s-|_Tv<<-F zrip)X1eE$>ip*VJrWgQbR%E) z#|k6_GaRqTXc7^ejl-gn6s-AJ1X$kDc9T+XN_{(}-ew7m!2G)Y1@JpHPW<{u0?r3p z6IE_E5YoLk>I7e7zxvo~RGGPo-)lT_SB?g$75!n@^;3U~K%3EnyE$OhjyL0< zH9g6OC%f5UKJ4_4ydMQ_A9(HV0ry*3SOrbRL3OYm_V{r(par2Nfd@etck|%DwVS|ia3zSuU9BhVWwIZ11iFi>zygS>w@W&w>Nb{ClmUS_ayqj?hm(z$S!;& zm}>)QTei_c_McCQV0x9ZZ6C4bX($f15Eb<$pK=2K;WHjO!XJeHAE^2B-?lp{+;LX+ zpIj%lK=1Jbr&_*@?BAQ75dYMfmKF?v!2i8W378=^Ozes=(og?d7-$JDEmPl8%oLa@ zRb=RmM$~9t;NP}z(O>@Wje%gF(LeVM9-!j>-d2d-X7rC;hwsAzuwK0g2ZePCGrDO0 z=fXkBbC$o?6{0s8{bSkT>Kw!0s}j)#@Qc3-VBnU64PC@n5XQfDOM#2~=e9#IKlS&n zMD#kRe{5R(-X{I`o<{Vgul+x}^wvM1q!TX^6@*45>HSYEQbk-Xv8qxW$ICmm>o$16 zju112t}yXcH1_0f3S5g^I&Xkyp#$AkhR=4yneXxTwC;Nuj5DCWw?0nYoFxW!M$B(O zD%1d}cl7R)Z;KOOfqnm$+i1l5c-s*z@SUN-sUzTWOu(Fx@tYSa_d^!C;%a~$(wmMy zaC*2=FG{SN9EWBV0XPXZIVE`fe5{9F^Rd-0zVjj%YlQN%bUb~M*8eK+Jj0q=zBNu$ z5{d}~B=pb`X*n3BNeNY@iXy$p(I^N3qy!XcL4tya9*;;bN;x8e2mwL|2^N}kL|PQ2 z69aG0f4BbVJIIPSf>hlS;0zPD zf#C|ReVthn;sBPfhcPpWnM{_EHUSn*pQTUaWZFcPuQLT0JG=m!8Qjw)fFacQsO?Sk zfnoSDwUY=?JBxej+Ni`E>dtsBIae>9khZ4RDw6%nTuX`#cn$H294iBKhE{aX>#KGE zv3D`fziVO}D@D5Rwa8p3@-73rkuLuokm}Ar-JE%Xy9P4vz!*eJCw#4l77kDrdR ztUo|Q!uWZkFmE7|Ol_52?i87|G_dGN2H@c*CQG?R2l^J+AN_QR{65p^Q#Uf3k*v4X z0qQ960Ewe$km!m`rhl-+Q3JQbsJgMaI@QH))chO>XHpCO#ScaCIYsmwka6zT+gUYo z26jzXv(l{fezrMPUAxK&lL*324_t5$Rz8x52MF!oM=z)j9Uq5pF}}Z7(>b&z)S7zy z3HSJ_BuJ4DYyfpot5q=I&SOO+tRWuPn`e^wZQ7;V?qSc)S%uxUqj3Z}7o)3=UZr2A zr+YqG_dAJk$fGHAakv-2SF>$qlK~LfI+Lu~11TLVFx^#y7)EvA*V98onL44hs=#7^ znv|laapAAR>|3L^w&oNRZo=<_xUy_E>qggl1Q2+jfz-YqbA{R3Rbo^Jz75E^QXftF z$@Os{cbEFj=nSuy2hdCvO5jRN-3*YKTDGn0rn{tazt6QJV6QAjeW3Tp%PdU_@K(w6 zuUo46G=1-hPH3qpY$*DIUme|46jb&wAo4-H{w_dK_?KG`f>>95zfgXCf?{U`1D4^f z%0)1y@{MAS5h!CtwlY2-dJwAzE+ylBwR7?SIj+~}0WsTG zBKy=Ckh}_NmzYfitUgqL$Y!c6Wdz|(Jj&z2L%{l}cc|~6L(ubt_g4D4O!t#($chY6 z)g2xgc)mZlRLW&wA!lU9T$e zd*v?1@;p+sZ4thMoPhAPQ+$S0aXlAxI)tyDIyn2x5DtvEknKcC&rJZ; zkDw=Y?omn4vXPlE%t_hnjU4KzgQK~Bir8(1AW*UH`xHZA3^}? z%n^oaS06@CANg(Q!k;k#03S;Eb=RP8J|c$U~EE$2O~>Wh}S$Q zzk;#Vn{vmJKXAH9Iq>b>X1SCBJGpir2smS%=ph-V7__j7Qmw8^UGW&J*#pma#lb!B zt(+B6YP2Rx_{22AGsb|n6=ewW>alK;{jC9sjc)bf0g?KNLI?Zfi!SrH8KTeBNS4x&(l(gwths+`HD?&Joxv~z8_h`tg1=zIb&wcO@3I5aSwnjw) zUQ?PpF4p~UKVks44#1hJJjy<Lfw;Pk|Z9ablT? zw6~`Gu&#aa**BfS`;)f~lg(e)vT$>wSqZ@9{Ma6Rym zQ2_pmq%@u7>Q<=u>6dQx8H$GLoD{t)qJ}LK4?~wwE;R);2cg?}lUJu#*t!oNXuju}{d&NP7Vu+&DjiE!Hq`HNhRuh78YQ z{U%H$W|v!iZP;GEt8>6G?nE0yd-4S{Ym*Vs@hP0gzKxgGO3L^6OWFd$`y9w3j8wwi zFVGF?I%q&FTCBQSq?>bh#wGF0c!wQO3V5vQxRHHC&9J&=?b`Y$)Rq}fG|ss(4hfHenx=gcD|K~5-IBY6HCs9JH$(46!=CXvvzhyz*&MuXr0 z8G$O3g!N`!c-(abNl+fFaVN9ZYTSS^n7%G6fW1nvOXj2=6{9*|$6Lm2Xi1>3k?N|@ zM_Bc;s<>LT75suJu`u3HmwI@swKTYC{ur>$K8zRkp-ot82 z(g7qnWe7yJg;tH$j57O#7Q&Rcdq1Sg5f=SmYe9W+ zVbW6DRB^!JpA?UFrBl zt8ov+{MU7H!#MvYyI6F*ZT#bdQn8+QJUh}u6CE0;cG2oh1T!1-@vZpYq@n2hl3U%Q zqC6ixrf~h1)q+!wC7jY9x)7MPY>Y`3`i}n>ojQX=PNQrLOgRutm6Xr53I2Hn=bzhm zv6~W*v{>HVrwv3x6L&c&M>c{CIJibIKM}curM>A7q;B$&Zgx4z8asMKkf4MX7;A!u zu`=I`5J4;f?jZ9Wc!}2n&{+NCrhGqshOIZI5SDvd2{)QEndGTVFkX#n6T*~1+Qt1y zmK=z2)lyNlXm)`1t0q1SXpLUrR`V)bpzT+NZglvLu^?}cP;933g#5G9i`OjzDNi?8 zA7nlA!MSy!Dr6r1@kNTyFl_jZ<8llv$Mt3#j9Zo37(a^5myIKto=bb+nC=&}RJ|0` z*KI1S`l47kGP#m!Di0j+xLthM9TRP?>t$#2I8_YX;NDHrhGI@M4m7++aA8(nIYlV4 zaX=Q2_^b3Ed)IsMr>Vlc;@~N9@z&Yw*9Nw@dW=$pj$Vj9<*;{nWWH=LNtAW&)3?%I za;If|G5bi7<^HX!8x>ev&pdpmnW7TMT2@!@vGNAY%hr+6dj)dA*Yfp)4Jh_~&zxv> zW;J|q4R2poIL*G=IGm_-W}5&Ru>Yu}?wS)wD0;WWKmE ziXMJ?P0{X2suk3xF5@20le-7{i{Ck#=`QGn<{#Gjp`G<|&OPEse0+RiZ<=;rQoq3M z=PLo9vF74y@A|g>(lg6fNh)>yhl-9X-w=q>!7n@r4;~-&pGB_wixtnM`Ygwd6%-39 zFRYU73q2;joz8yAG68YQCBMQPDDO@2S)%AU6Ayz&~rxtALmK9dr2aO*W@M}stRg}X_&53EVB~`Hi?( zKWB;@X^TprHI%y4m*8p;aWhswsoQDu*!z>wzo z|4&1jT+xrzk2o3mMDrsU7<|}hvXyFG=zeRr&dl?K>NA^)fUifinfHa+WiZmhhc@|w z|NWkMu&gr5rXqO#i0;46!6qI5b?)z9Y8qt2b`A~{uKuSD4hRG@%KS_DpGKXzAsFWi z*)53Q*I*t;^>UEoTUB)&&fIG zb3W(uet(u8Hx~NO-fO?TcH3>YXLBqy*=@JoF>w8(XFdbGzkS~~etfsx4!fbCwIZx+ zFR*sof%Kld+R=jCI4^b})Q(n*4lJ|C;s{)V`(eEFY|mOg`CSWYK?g(V!4N)eAv+KP z>3}y3I|PSt=AU>|WAeirHG1wsxc+@L37~X-9;A-SWWd%N~4*q5w{X1|) zBuQYY)?(-tO?#w$2!c0VhU}Cd?P&GDb>OWm@X@!-Rorx0X7kM={-(>?^oI^c^xt%>Oz(t2Vx^4y+h-k%NDtkx>#&XX(cuTeYhqc*0( z)>{))jGIq+Bo>Ly@2O1 z+U<1gC!gI`s)dQ=I6X$;XtipuHmKuZW41*{a~>N*#vokpWLf(e0uAInNn1Xc;ISN^;kQTqr?-18pJIJ`&bu#K|5cL4KRYtMMeYXtG?2 zh2Re?y4_8dLk1HU)|NDLj2Kph8dr<4%8V*v0CbYn91VzLU`jm=?W(G8W2lV07S`Q5UqnOQgf|S^pMbgaIYuXwbs;Q2x;x0HrB$pPlzLc(v*y z<8s=DPMnbRWFjQhNjh9rZF`Xv#oF2C6g7|JtgyNRrE9?RbTi6YC79TBGJ#xo44y(t zVXkaVl4y=|OtJmxY`H)Nq9Id$QqrY2F3@7rYxg*60Q3*+H5x^n?i2X5Kd<~zm!Mr~ z5+x#0mom}kw(SwIHt`8Ghyf;$lH5^PW!hmx*HZfP#OZ>E2;7u{HCmfeL$FVt+3)go zXMkE>gKwOW$_9@9m8F>Eg^XzI&T9ufnCHEB75H9tUWPwjSQgOG86 z{>>t~~rztSF%+OyM!Fsf$!Rkl6u;iv@VZ5bk?oSU?jAyIa#T3Kd{={NX)D$0DFch!i5!v?sVR5i&?)YwtbG8 z@qq$!l*X zqf!S8isV&lK)jAn1F%=D?8JR*|R`o|~*+jgegLky~%r^=cgBBic!z!2& zG@t3CI>HvU>1(LI0MCPRF{vC@?M8}&EHPNaEUpBgO;*u(Yx#^uvE@4Gj^s%=^JF;L z$g@!cG}e;tnt;xbhT4^KJTR~g!q<@wyZCsC_!wgQH5{57s)O78Iwd<=kfWMzkai9s z>(wfRMnxKx#fn#Y+uol{h`IcQ-rBK19wZ(LV@3*30%)?{DfTwZVb5mzE=f!H& zckJfG**Y_l5UT5?joS1=)6lT)!dJmDW+5@dvTj>yZxU<@Pdf0@>*1|Vqp)rQ-C7@7A;gKYnP5a%59kq7vQCh5+Dlnm*v7~dkFv3|CZdq#?&_K)Ecu{Fgj~Yc~gR4W)*m`|RPFqtOFJ`kUWx!qVOrg`( zXPQW{kUOD-6tYWjf22q4cGu!Z(8yoMuG3{FSwC$HV;E^cV9R1-k_&4iFf^xxNSsU= zn`CHWh0V!?9y^h<&}g~m>!=Tm1i5j-tUc|=U4{vltvR~ZL|_z1CJ+fcFii&PK!Ka*lQ>?CNK@lEJ4oi+ zjq9%ZW*G2Nu!8i866bAf1A6h}EzzAC-Ktz-lGSkBdK&>2z>G_=?hTAAT5)14PqJA6T4g^4xo*d6bl5qS`M17fJNq=7S6>$uA~S$ zlw*%E*OCaXNfc8oYK$a+r88~3(_K^JwT^f>%>`PQPV9bV#;#y>KREO9oo#UMhgoiy55sqyg*ZTbtIr+1Piq#a2qI49r@|)G@H_ z8dE@RrjLrE8HWM7r8efWv1EkGYHKr>w>4akoe7+(sj4_FJR-5qWEv^+ejl_N@`1uE z8xMu#T<|9JCLKoSXm=)zQhru$hmHeRb-7>`F0V3TXUnT!)kDGt>ehSmq=kmq`8Pq)l^ z?y=a!;pcs&9+G+4L&MB>#*oADuGw_$VjMSV3lOSQ1oJFmb7}J>Dok=MV=27!qIm68% zLFB|t&xlwbu2~kQ%89&K4X1K@W-_Dk+EDnRHRu6pf{pLF5xf8{2p)*|0yY=*%9Bc) zbG)Te^e4+H2AHQ)h>D;WxzjT@{EWxi8@W-qm29w>BaP?{o7kJVx-o0RAD5^x#K9l!>_iCIB8jl6O)zAZ-(Pg3*lNGtro-OVmWA-LDr7b z=~f9QZAkD7ZlGEMw`|E%S>KH8$!G;e0{BO?nQ3oKxKp;{kFW}BZTo=W&)xNJ{p@fkPr!2Bx%}< znu{jRy0xX%Z7bmV<0#k^D`9HO%UMPi7&3!UX*={Ypvv-Q4G|NXlHnSWM+T>$HA)WG zU1=ev+c2&YE&{cTYR*Yufib~1s#RP##OAaKjgXDO&YW1it zUqOn4N*+7{t(2II?a*6~CfdjaFl(&S1j|V=85krW4_*ze<#{!eq`?}g3$ZIDvdOP& zJMZ%IfvfX*BP>Glz+x+@=Zl6RrE%2ou)H=|mJ&v*d4oGdd+vp8n4OJSCpTdwuC^vW zYm6ZgO!||>NK*T=nqPAKY7JMM2~IkL%Z;t$HkK{=dgGRGA;r(-ajO%lF5dRrCJK&0 zpBw{nBN6PDg(?q3eMrjU&QNH3k)uXtz4S{(m0i|Sl6h0K*x0L$~9B;7E3Q&!DLS!`$N&1QY10$cjK%`)*&lW zZc?RcBT;KVeWCFr(O5E3xG= zDjcpNW-Pd2s&d;QDF(phNY)8A>KL6e9nHt75YGBaK2^rCAkzXV%*AoQBZ(FayCxJV zP}K#FNt~9ovQnm9Dv~j71ehf=?|Y%XVm2WJo(AbsLXMq)pUN!9l+>9v(&QChOLba&$2e6IljlrGr|P;*(2v|JBPWn&*^EFb=ua9 z#Pm8qErrs9{tVJq_QJxL6+G_oSsg?xPNI6Yk_@aMBCUB>lt)Fkvx4C5dX`4>c+`U@ zvoj$DD$7MAY9*XX+MLI;6gAdqFau*+_rG2d!CcQgT>stp#{Q zJ6<48H_d~Y3U69y+JvHGOY~xn*CkY><5^pFr4i~j=Vj>iy~J)9)>gAP2aox5*4-Md z+>zKZoOO)^Td=r`XzeZwqU6;7D`s2I)tIzaV|z}w<$gTm4H5*{z={1cX3J6_2=nK0 z;)dBqi$%$|=rJ@Wx+|tAD5m45z?smACt-9tG3}NewOD2tE&@|3 z^+>V_*V%}ZjaW@X)@=zG!?){tuFw-r_xXO`-|*sMws3S(r|roE1ZvH)m9J_lr-r~o z9c3^HA|ixUP5gYVDGa}jai5O4M2%!2w|ZtZOneC*4wp-_py%86JZ9uP6!a?g3pMLb zGim_dTkHP9@dO^pp+H2?$p!-wjd^s+l;LbxL$<3Cshc)g1u~q7VH3`?x2TWEAc{@4 z;|!Wrt7&8Cz{?&7?M}JU*lp?rkjbZ-<#-cwts-$uWL;PAhgg`;rlgbe`55XMX|f2= zg2~Y#s^k>WMiF2I0*r0E=Rw>}@lKBn$T?n`nc>bPOz7L0-%Gb6rkA(XwKEW$Z7^-n znq2l~dOicVw%*3fl8XJZ+V+FIwb^uO%Ah)`kPh+<oWzA8B<>*!b z5hJZfs2Pm*OtYEI%11nED!FkV-~+XS=~ZBl`;4ge(00k2zP++}TQq6LV5O8A2yWmi zvLO=++a7HzI48EN(DU$YGKB_2Jx5SUj>C@SISaVX^({Qi4Z5;AR0(%tcO?fnZ`2}) zLC?m*azk~8j@z4w!*Qg*X6*EZb+3p=lpuy#ysTE*B(;~c&=9lseB0v3GioyL(5XAx zN*)yr2gB8XgzQasgEx^2&}<1zOgZDY6b?sP(4N8dWVLlEeWqI<2In|Qy;V&GhCb1W`jm^V^oF9NioNpKm+(rap!nrA_v^k z>nJ)s>4=T(Wd`k}AD3Rh<;}LSnfU+#;Iscd>S z*wLTQ@U;=w{gn#tK*XF=aetx1>-o@S7R;y=R>`ypTM2b*WU3=<&W0vP`3qJvD^dWg6edA7I=Nucl#+80h>^;X zLQFS&*PDB@ZZ@!Uc~s@L2f|^njQJC+m3q#W6$!bjBP9X$XxbciheAxL3;uUlo-!0< z2*v4q(5o;@SpYa-0N-LZh=r@TAV~hY%lPrc8ONJw-o?Tg$0rpYkY?COwjp! z@nT{;U>dPtvth)pP%^S+I#Td$x(}404Y^j-17RqAyqMs~unki*2oZJ>YD5uM9wShO zPBlXhSv#;oA#EOHt(Fn7TC6&3DmK733l_Ep?ss+E%cZ$cll@l}f|uu-9g$jmJySjg0LDR=a4OHb+&01$~!Z4f)@AzN1jZaV{Zl^J2}mcbj) zqGjmAcnffXnY$a1=uxa@AD4c-D6tx9%vr$_U10PhBShATY=3P6r6(Zn{~qQ3l3;>fS?PKW(=q&ZZ?a_Q)gl{=OT9yK0WIrX zpbk4BP;O?u5(lsVS5Q8U#{lSbmPT1FsVP8KNVc21%R#ob$yw%G73PT1FxRQ&HiIlt zhdLn>ZIW#pgejOUB7jICDWr*z*4z}|3RbY4tu|ydn%N+CFuHMr%R#rX#VHP|OhYbn~#=Uj(Dg zVwFc22;&E$G9G|jR6A=tkHljetHE~WHefNxa)ALp&#ZE%YK#tsy6}XfjrDLU)kV-I zT3$J8>)SCM*CUSG61vrxKn3+HzU-ztm4rS-ErNRDNm>(O*^V?m?GlnNhiS%+hkb+q zerGB8{fRhGyr>G04Y%F^H_4?(BX?z!W@R{qycwzPEKf_ecE>&*&N*#L+MEX2jMG!2 z4&5#VOWn7(*vN;-TxoA9N-r=c)q2%(FsYI>0gVu&ZnQxF zmqzZG!q&C=Nu2FT|7zuGP7ZjSyhifv~c4Y^xV|mVQl*;kEsZlUp(AOgzyhHF& zKHQ{fS++!L`9z8dk}x}i(xKj2N`l~Tq!gGRraR;S9R}GZYSe&0uY{HUctu5>SsxaF zNEjRZhf|V3L5!!@moPVn;z3U$d-hnCL%GJ4OsPa5inR)6KEH6g2TX7`hToyu_+4~C$8 zVP+MUH0L`>xt_w^UNPA|SvIfJA_;RvMox8e{T0E$hb!-n1z)xr)-2p4!3 z1Ro2AT8D%LbVW%<2}1+4p0#iz6)QUlx3xpSpk^iO3KLgAJF*J37qI|fg`AbxfU8v^ z_ee|9=Odd5Z2*Lw1w~SH1WZ1|x5mC#&$=urBKT$&4P%I1Ar%o4%49p~7XnM#5u7X$ z3b8==%fTFNFbS!8KQ{O5zPH&?1$WXU3xF=5M5~@rB~tRA+#vlFw#1GmEq3IEgcD zJu^6Us06_4W19mjjAWuxMwnRjl-gWSX}6ZB%#7V>qkZc*k*YpuRu1tQMWarrHc=ds z&Zbh%@?);W8Qlmon0Bj&8>F_vm&=NuhHGUF9QC!ho`Kd(*%sED|1EeEtm6L)+ce#_ z%XT;--i&MWd4Q^mIRLOHu`MWo7fN!VY6OL4p`~2K2GWh9RmXMlc~t;WF@qWI%_~}hqj7t)n6rkD zXiFWG-9%Ngm2u4{* uN;L=NokEwxmv1;wI=k)WUA1E&153rtATCOSVu7gcWA0% zmg%!>gn>lkSf;(IQwy1FRcXAXy``OXK%N3r*6_8gBWtJ66afc0KFhhnM3+h{bW&F# zv0)bzd&{wyBW(;=HD+ieBH(e&y25oSMvYlQmQ;bS!G#fYYaM*{;Hl>c+@{dju+XQ4 z2t~E9=<8EN)7una`s5fQD!7B{@o=Mom^UpV>Y7X^gKdPgLwTfvXlmacWGUtsfr+}_ z9K={?Mp>;|g1x15LN*5dVc(X_Ih_Jdz)l*YnNS((4ccqROEN5J@S);b#I&8(y#-Is z_-;H2HMR$se!5ag1%&`pcG4X4y=cmV!$7iIf~*(3)Q3>Chi>eoCd4GYtZF=#Vnc=fhM6iI=!-OypI;3>7V7SEdR9A&H3xGSZxh4mu&LjkJL`$w5)vCXk>;rHp)<#7QTd4m4>g25bNf zEhr>X`~FaBj7fV49F@sxEE#owxab#}2|^XHudCMFAWB(^K?-}JPgeruFHE?SOEZm! zYTpzFas!bgy(39eGmZx7Y@2|5CCN_E^-ve=Si$@mtC^d0$=fVf4BRae14mZzvLJI*bE%j-#y50+CcKm#k{$y8f~V77gMaYDUpNyc(! zLOsGCXVH*hOw5fnYk@PhXj7KCA(rM?L_mAq+6cNOOmV6R*czK_^E5$OLY~9;5Aent{lJs6;JghQMHZ$e_os z$58`$!IPA}VnoZ{N>cR%paQ#2c6FKbkQLKwGSdyoi;Sq(opqp1M~vZ32ULejCZ@>^ zo=sV}Yl>V|nl?OGX>0!vBnAqBvtffWDI0wF0mV7#h52yZqLhg}E3lKm^h5cBji0 z2op&&Apx!z#14AXyra2!4gOigrfXw^(yq){u7G>fkH#iGDC)-RX^r{Ll5!DrmJF7h z6}AI(<}jYLl@rC8M3~3b(;9Wvfhhp#52~rW7>2wk^Qc0!4BFw=VVI7lL6Ie?+aH;9 zUQv@`EwP?D@seTNR|o+Kd3m4$`$pfdr+oWQHL5%m*OT zr{Rn3XbndgVIwxasI6(&5}ObX)o`Me$(L(n+6%`V)tg4G^}M^u7ISE#RUzG7K%kIN zV`#YO@d`+gf?j3-U<@l_kgRj2yjM=WRaQaCvet1_5O_f`ffqB2UCTgMRc~Nat6`vR zsF;`-T)+><6Kn3IUELK_gB3l6SNcm(61o!lts(Fv#hLBM_+~YohD%a^^wg_<)R$GwTgwKfpq|_H_!?GQ%k;(L{xmf%Kf zBQNnf(590$Lztj^z+V??6HzqUJ{0(EP;yMLWH*v+;G8rLm*DUW zSuA5;9v4ff)2_)*9h%70@$ATL>V(LVig9wnh-3#Q0HPIo3X(T;TJ|Y{?{P>8>G+!I zJ5ImDX{{=cv_a3-$%TOp-Kg%6*_^LuQ%-;#kV>~e4s^L*(p1Y|03m@q_0|ZL;S5tJ z6V?-%ImxwzRTu;sx*R&KxjL%1EqF4=3poLK)qaAHWL+vSTT%UxU#n|W7ZG8kU~1{Y zF{hSv3i9Y_TvRB@)mhJTG~LX+qNlIdg^58k8Xy_j?{;DulyS&-iiulh;tra-bx)O3 zy2rG_RyYfy_QD7CVr}46tT(MT0lR25j!SrEk5|cZO9YWg8uW7HR8k+O8XsWgF35?2 zICEAq#~^Ky>uZsmsid=9!+Ihr(`Zet>7g_kX&4bEc_#%a&SnSEw2h#68>tvyGgjS> zQE{6@>CP+=;kO%O)N6Iw)>1MMP-xO^bD;Wt++{sBmx?ab7z@Re6RKe=Yh|ayeN5?mLnxLW5ucrjwvd38(3j>sn z!VJW9hzS*vT0}_OBpeex(2F6&w==n1;iBsl%f|w040gm}MbUgM!T{6qh?(hK1}R&zd#O z%^BJ*LIkz~1YH?JW#v{2VmkvNoIX7BaDAn8^PKW>3UI1X2}ylLvbz74YeNak2p2y0Vbvm zC~Q!{5ja27p_kz-2vkX13lt^I$BqO#08>bMHU-!=Ii8f`iM@2jIM?+tYuoY60Pndq ztAouYOABppK?i*lOW^k~4UCw{806~hRcFu(hib1JE#tLhBphuCi_WrzGOHn^2CJ1a z%IM7y@>CEE%-jX2S<4MSp(P+~Ss^LGv}&TN=~3lSt8Q;Olvt832s~E7VIz}eTuqE- z31&z)zh$f-7KI%`Iw5N_xkf)2{DGf`RF^YQ`q%y#r8)j2N z$7FBNQ^t5JpgqD|u|DsrLm9|-D);6hNK`Q!Y%OAKEizgN+w!R;2t6=k;AVC0v6KV> z;S3240(F$e0G*>Sa4*L^=hZ0qO$Wpvwmw5Jm0ah2G%q_G35xT<0+{}2=|pPmLbPOL zSRF|yJ@7LrDiIR=Qb#2zSpu~V%tsGIFEmq$N0kj0R0sIbUt%L63^D zsonNQ9Z;--iBJ~3T#uUJc|S>(bffk5b|b;X2q0c>)2Qww zA~!`ObqO5=nYtuM&0?{&%H2V>$q))6lyXUJTC$PNr}z?HwxVs=84f{>2IloZf3h>s zp^EPVJnDluF4NP}mX<8${8UP2O5=eo$3=l8tWpM8z7C%#eVD})0#v)yhO6~h$gJv_ zP%Z&fb*XGnAhwlpOfxm4RRvA70bF*wpb!-XMIE48ZfSN~X4YD)aow45d6xLs=sy(ZDAH_(JMA$S6=|;1A^HLP{f1F zc@t1&EN4nEY=Fd406Rl(Y$P!|)j={P)ScqQsYyQu|<#8pb$$L zZ09m77M+^r^fnwd5*RI$2_oTY3tZP4Dq+n8;LNM#T;& zMwd`=O=n4Lq-as5m3Rf5DN=2Xj73BVu&)Xe17A*|v=}0S-f7JpRgZE@QIiQCGl*rf zrNS0swrT5qf51oc&e)h{5;1C-W4R>{dzChXYen-NINR787Ay5>AB1u@CQ`sqVe5cl zj@wx-rQ0o1xI_UQ9uz>j{w{9OK2(mbV6e-p~%#4;baYSrdX~cG8m=JS8Edd8A(`GFiS%qi9u^)|U(3L=h1LiMJ69x|2K(I3>BU|A+D+@bw>mzKhVW z-T#fZ?zYuz|> ziD#U!5BVAN0Dixbcc#ScPQPg19T)5~c=_Y!Kl1O7Kl0dV=N)zJ;g39c+k>|s^}72W z`bBx^z4u@K&PQ(D{PNxlPInH!?}YR5+aLMmCw4#mh|5kuzVNfpee#(5-+$6i{8L|k zz|;Tq`oJglJoUs~gTt(Q_var!xHj*6*5Tj#-dEpx;e*e8wQ-bi`#-6>KmTdZea?Tr zj{T?6k3abheuv-s%^s`ZPmckQ{J`~lvNtXN?L{~LmU_b;e|jD8j(tC{^V>h(_uQWx z_qJ!g`#)cAU=BJ!`tbFRcGtfD`EYP??6ZU)|HE-7?}goFTz=^DKP$ffBY*vq8$W!{ ztsi{-`;F7~yZf`&qksG01&>^OOt9nl7p8wW{qVQ`1Aok~u~WL6@$dfsD~{o$X> zXmiR#zgRmbi^uNs7iV@SvseDvY7cn&LGS&_p3ler$-n-xgYG}|g6js)!9MZw9Y@`9 z_4+Npy!s!$x_9lq{m75L`mEBs^IzWg;;wI?p0?qu{EpSk)^as@K}@tON{K5>S9)dhRs`si)1zvz-Xe`x>3Z{EDP@@0pf zdhX7TA;)~_?#o|s$=#QCE-CN3<)-s4z1Tf@_Ydvl@-xpK|JnY$VGm)yWA{D8KjfNI zzWJ&jJn)u>?z?08&G$X_;d6KX`sSNXWnaDzcF>2;`^5{MvPo~*bB~w%%DI34g9k5< z&%Nl&kJ-na{FZyw&pvg7-+9n;-o5kK#fhgJX8h>n_TZ-FZ-;~3pZ8y$b1Ee5dp|U} z`Q)!%H@Rxqf6ssF2e^2{YxaHjVbZR9e{%W*m;UIS2X1J6-Q2$EruI|h_?%;3x#z!} zw)2MF@CpwmBQo__h2 z&^Io>^Re%@mGeFElI!oe{*%Z2@Vh5{M7!^>h)WOupm4zb_rK?}^8LTr%Y03K@nxQI z$*Z2C<6!rhGarEdd7snrc z0RQ1-o3CiMeerj_!ydXx4!`@Wqt1Qf&wq+LkGGC`^tABe&7F^2?A<4vbjO#RlWu$O z_b%`sIn>THcgS+z)Bnc(%VQqZ%>&opkj>h|dUT|F z{uQ6Um3jTI-+uY;{(X;w-aSww>&~}caeqg;;I2=;_WqAQZk~G9J?CHf_{Fatpcm4+ zUV6!bKID>{U-Gigedq@-`22$}Ii)M@`r&z(UtB%jIVk(u^Z)U*PyG)2L=>-Qq`CV08F@JNi8J2$2l)rr@~{2UT`xTNNawDD zu3Wz7p2L4a@t@lN{0lz)UZ2|I%bRzpEKls*hCtr2&zZ(}Y*k{vsoPFL|)$*$MK4`xA=!dRJ&p1&0 z#K{jo;0(Wh{K!Y7N@tpM~`yO`w<)1%Lmv-%X{2j_e9}ymY{5Iss122605Afs@?mzz3k$(8)XI=2> z_q^b9M_qcy2hZIp-J+lSrtB9dJ>^uLdGOQjJmVS9%^vLj@ct8IfqM@2ioL#g)}4QI zQs-@7BOl-E?!gzSr+wllpy!JJZ1*iL0F*x1#UG#1H-0M#K z_k*6&^5{L69qE&wL#{mOAFh4jQv~vF^Z{VsFF))B+Re9Lz5d7*hx8s&o?1A9k4_s=KzwCA$jryY0l3CN8v zddlGcAKM>W9rU?-Pdj$~uV1NkDwHz&U6j(XPw!;@X3+zdL@tlLfTwU(x z9f0cpMuPQx^kW~|x#v4CFrHk~yWjpcihte*igyG3|MJTZkoNsie+|&N@EBv?r`i+hNA81tHBnyu zq+q1yd|>BsPyf(ggP~Y;576;rhX9D`ob&uAz~k6gf*#bfXZFBQH#{FK;w_&Zo^jycT_A^nI`BUVXtA?9b2MbI_M}UH+lJyU|m2zTtKI z-*Rts=_k2x*DvmU^zQTj=@S3MIC~z3>R*&cJn+zt)n~(Vo}qm4d!Jfg^`f(m_|gsEIBn-=-uU?w z_I>U#zyI}Fhqrf?kN)&KZ@u^@*Ldq&y|cdj%jX_;b^%`cIoSW28h>*XW#O*t8Y&(IvhLD+W(s`J?!E4-*^7tsso!{{r%v-@9NKg z{~YnAH|7sL|KVSs_2yfhUmkqnWhebi_|;8+f5iiL|HE_N_o7GM{?M2Hu;&q%z2(&J zpRHW`)(20!^L*#k`*$xq<?D7Vq;wQ`1^0Yc<~p|H7;Hx+g#5JG*YW@WJ1{?SWe#yJ+>v;xp&mf7&IV zJ|cVQ=5v*+{`$qgz2@=X-TSg59=`gi@TMZ&zzV0*Khty0I~Of z`{tv5_AP03^b!0yN97@=L`3KHhBKkCw^|nU!7i@ap0rdd%t*vwAYbGonu{7e>yzk z_4jq8uitv=1-qsf9`ejj!*30*-gW*fj(F|M@B7Y6&OhyE9~lBD z0l_c*k6iM5^+!J?zw^GwcD+Bm_{QJu-TnOAcM|C3zq#sFhgHAY z9JcGb-(B1HAm_g6v{TOg-H#pt)ZywgW)FYm>mLptJN`4u!|(j*d52!sz4x@EE)MU6 zZaePebB=%hh0j0#eVaQ!AKmjv?_Cevb?~nLMFFao25E)BE1|yV2Q? zUJuUZaUVJ1%DZ0S|NhrE{_si58 z9B15wo~wStK+n1B1-HKNTgM#t{8wjR+COz4`{v_a`^X1ha`(;O`d^1%eEMni)t}k( zjH`Ct^f}?vfEqk}@9F)6kGkS&<>y!3cmI2TcNbuV|4ZaAeCVowML%=I9|vT14*o|Q z_KFu^@A^Y$anhTQyzYuW%&*+{pzGgx`ad4H*E8vTjAPz=w)L7H-2MIAfAIPT-!vbp zmwosE|1u0a>By76x#Pv!Z*Lu((kThDV_f+0{XVq&@^x39d*UnKbjwR$_Wkc1_v)K} zK^+kvdb&`){*T7;9lclhH|%!C*-wHXyFXAg@9XeKR@`g+f4%REj(x=YuP|?T<4r%_ z^K9*$)4u+B``gP?4v+P>@0=g}EdA;Sf8M^zdi|xZyzVbny|;>sI{Ny56^Wr_VCYU!KtiO4 zPDMaKq(MSJ8j)dWfuTzTK}iV-rMp`YDG{V=0O^$Ov&UaN&;NIx|LcEoF3!0)H@>_W zhME1{d#|-VpZ8j*?HB2!Zmck!UFc+%W71;gU`R?VM+imUeU@O)c!7FW%{YN&oh-0m zq7OhgJok4`OPX*!|F2iCG*R|i{`YqcqxFLohBW`zuLUpoUw-ZXyD!Kl_3zu>tXOxl z^)PY}D@(V)Tt1wPs}6}veG5%zySX=noyU+~4!g8x9#^tGUM?U&zi_B;)}WJEh#Z<0 z_%iBHDNCYOvdQFY1?po9#iE+t;OW^xTV1|HrN#>)B=y`m$kc(Mn^O)CLcCEc(f3K~F_ponXxpY|d8=HR+OgFom^h<1O<;Qk7 zWm9ih(sv3~eIR&j&iY+d4j?uwyN9U6&C0>KSU^UPpX^d0R5!z)7O40d)>@S});|vs z0@udU0J7td>G&7#T|~L@OBdet>BgXogVEW;ovfjaGp3`-QKn|InE3M1lqJbcCntfa9k-XZFzN`-73m82g`nRaz0+qCgN(%1TO1GYzvHaXL^WUGR9ptyyp9P*(yLQ=6AC~$w z*%j*)YfY4;yZ5_D_Qw{7@6F9oBndAFaXX)I9RA$P+6WIgnR4Ol^=%K!l=NyYm&4hc z*l9IRS;@pyGQ@O3(j#RizYnQ)Yirtx6c%aHfMt*es^9g`Ulj$D@-#6r{S1=p&X>-6tYx z1kZ)2mp1nLB?hFSBaTpi8&O{R#sZbVCLiL&^FK3P56Zgz^I6R8@IzMATc zq_JS~J1>{`T}zXgJ2a|r#^foVyNn-FLIqTZ zQy`x|3+iLhiTK$Z5&KNc7&LbCes}e+bn^M)R#P8q{9Yng@wA^%dVMS>7A738A$9iM z(Qa^nfa06A;Yfc8ruy~ZYkuJ+?b+^O-cUC8tGWQxWt**M68edU)#J}~XUzSse0sxf zqaJ|^cyr3NjAQ(WkZ`1=JtSuA!e>&PPd%Bpy+D6~R@iP0;^q3Q{%N6!wcSKs@bq+M z8cf8gxx5e2ATfIH`FBg4;up_8sTx0T$3;{OYQUX(W<0yXl2|S#^}7k&$1X3LCmLvC zL|v4bj(qCIJghN+N-e3X<(9hPv$Lj?RxX{IekGz+^XE>t8F%X~(d(~a4`nhtnPwIl zFRN#L>-$o~hG>E|Co0Qd4CS2I@%N4oh9(`&cn#nZQ9n~n;0dcE>5673A5xdNySC8I zKy6#VB;`G}E4rMrVA^@?$WB2qCpi$u83TjFoBE!7?T7C@I@-33w^8h~h>^7NyFAG~ z*q)VMbG+OekVdTK=LSnk*=V}nEAGn6_`2%fJv};4u9`$*n0c!&_H&yJ1irJwPItCQ zn^8T@?27LZ%~?Vq28&dK%%wmF*a*(>#aqvadj3H3zj!rCnV}NkxBZ<^;i_g*d-oWGzx_uMqJZ0V|f5r*<8lHuwaThoIyh$$# zc1&Uw1^3gjOvQ+lZ(^SNdB(mczlEQFC%2yS0v6avq2cH+iX!-4ub{Bg3|!ZA{?AT3 z$s`IN#-kifkC=3*7L!dJ)7}FQ&9Eoo?)0%ho!8;Ui|KlIcOA44wX|=;@9*z=CaRsB z*pwpq;dmPGU6jLY)3nQYrClOSWp8<)T9vPH_;7pHDOKF<-f6!N>17}u3BtmDC?~4W zw0Q<<`@1L6J&m==@Ao_10=-i6D&(%Yd(m=!hWgSvxFo8-zvHf75VY>6Pr$kObGN!i`2E0k^VLjI{g!w#+@mbj_jHvq8WylVj(%?q-_ZH;)Xf#yNn@?o=y^a?`e({@pw_kdbnOf3BtUG|!{q&o`~@KR!WV&9JOS6-6F{%bZ(mG_lNJe4${|mhcu+!_99z)6YeI1d#fLO&cw|1 z!CBMt{zC}6yD2Qcf(3~8!t^?-1o(6BR({&W6V}@L>B_Go-Px8)GZaqyVL}B_W}Czj z=OK~rR~q<^jvN;Hoe-lw80~TL0{sP{-xNXSx#VFBG2Cl_dxw2&l~4$!PRshB9U_rI zVE`4T~op@vJ~*_jIICUc1K? zebUcX2@2MyOQ&BphX#)H&~J$`MQuhrOf)oqNbvc~Wk&JykSH48n1i*$=EqS^&1c;n zwzt$%w;Kc@ylZM(_2lXyH#OuzW_tN7*y~vO@_3=2EnqO}{aCeAI*j?QK}89#aUJ`8 z+6TjryGqR3H{vv;N(p&uT4>IxBdGgA-{ouP8uTRzr8>*ZJu9*5OZvszbZkCZY7qkC zLN%MMc+THwPw+JprMzn}JW^!5PGm?l0&b^C{9?{@@1Km`JF=W5d2Cv(?=O~;ol z@MW>dz7k4*(fSl_?6p~WxK+PxFw@`><;;b8%s!yPuGxM9Q6n!1%hH=tW;s&hUXhC>FNFc0qv>UAI`h{hdNfmaJo;s# zoipApcN-5z4AqYxzl8~*iafys6Q5>Ch5d2eOYZ8MAqS!v9Kb@^$k*RHd|IE6 z@S+ncs84lw6dt7-&|V1o%wp@J|@wakb`ppe{{lWu= zYHAjD)Y#_nN<_)*s+`0LCcEyF%?^=Px)aRiRB{Fc%nl-R_6l}RTmAq6gF8-5Cpm&Q z1#o-f?<{m&!wIAhblaY3?Ei7GSv|Y4Q9gi}HB*>pY0V=RV%=TZVVJ=uxadujtp7q7 zyMMY~oO}DxT>(V}ayKuZuJVp!SOjeYHZp!i8YfoPPaskZFIMq`q*v9n-_-?vrq#)x z-}r8ON=)rcPS{wM=(eDKn2ano|E)-`j%&F0(unvPK#}VEP-}RuFTaq$?z1|714B~)Ho#c>j^aosAx&( ztw(ohHRFa4R>D*}H8U0PNAVQs_M-Am7Gk7RMj^hlzGsDWH`2;~th)@PN%qGDK@V6- zph}T}cCFh7E8E5J%l-r)eD(jMjAMniXv-mg9e4BTgPJvE^ecB*^B2>joGW$$dgwhZoZe`-Q|Q<{o+G{Y+7M5>(U+?F2UDx_ z>FS4+Z!G#PKzB1Zxi?Bbx}XB$s`@WOak1E+YthLLW8b=q7#l?WE#?|)iQ|hhp5qt{5WtzuX8(eF5)?CwNX^rbc?S~6_pCvJsB#qJZXj! zx9zq0%h5>C2T!{kHGWXDB_N-LF*m-Pk*FJ2|s^!!3QPb+4B@&lm>%shIsP zuQ<49Bt0t}Cad}wdTP>qPhU_ajbuN7weP*wd+=R5a5t(n`f+#_`*ObQ7!n_Ug~~O8 zijSW2{r>7uS08>F?Gl|pU=1OK5HgXvnbQ|)iR=QwXG4K_2HwEb{ciqighY(W#p#u* zulxzv$Qx^4iV~$FrgY zSU^{~7b=;-f$8a$-#8#+X9q_`K5zw|joe6|HAOlBtIvjkdo8bT@^-(jjt*wWOZAkp z-*%ia8!u1aZ0p}z^{yv$i0ELMa@RB;G2?uL$&zZ&j7cRA#Q((tTvES6x$Z8}29htN z^3%id3SR6I$lv$V=c|wjXVc6!in@XIYl|!)n}2c1r4VjL+Uj;=9+;a{*U=b>K}irQ1l~Z z{qnT%9yWcDKzS2~m}X#Za3w#=R&&SXnGDQinWBc2H>fn`@xzD1%tSVOQ6e+Wxhyx) zk1o&zazU49;>;hWBSh#*xgSsR9=AfOv*sK!q}n#yT-pTX?_HDI+j$9g%}7{qM`rNA zZdr?ni|p|5XPutZWTSlJ`YMpB+|7ugA2=6~h9o$TvdNK?eiem`XU#EWN~2l@at*5; z-7KCvP+O?**dC_{AV*)>m=4W*K62bRy+ncl-D*VoZ?)eASPPxAU=s7O*PRqno`yok zdzRn)Xf1qh1WN{BlLoNVdmgM|Yqp=>Ad-WVQ0Ji3N|jJXUIwXoJjlF|{un+(D!!S}BM>XP1?7##e0iJzjg`Hrj z(!5q}1wT@6$X&SvD6AkB?I3MJP?r5GU%RWYSVevK)z;KF2bPQ;zpvc;TWU#*4ZQ56 zJ4@FRsK=4~HiUc>GrUe}#6DdSSlml^8gxF9iLA-d9haRc)ei-1MR@q z3ZcEJ5~BwsR!D3!1tzEvI8#P^p~A?r9IJ)SsHdgoikzKLu}G3ZIfR;mFw@t!u8ZwcMXH;=RnX(yfpkF*0K2rMb5?ei_YdmNq>-zDqQV1*t6B z)FwD>Q~VPjsN||_hx5=VHWQi-|HKQT1;%2CUHr~7cJTjbl;a?!k5v@pD&)HBYtgnd z1)Jo=x$E-M^qhQ)H~j;a!^Ej?m{Yp+h_fsu@yj;2qP~;PyM3k5ttll9f3G);>erp$ zur^8#g)D_+!%|38;X`uq;I#_qk-##oEHn-^pfGwh$I zJSV7Z>6>*CZxnNRndDZbjIqe9oeVe*_r#|EB8!sSH=8$#x=3nqso2$%a5nGHDTm0D%r4Dp;VaULTxY1``AK( z3=0*)JVSt1#vvegPUC88*}0EaGml9E?Ds zAAsf2lRUrphqhj-EOS)(Y)Rqo`u)CwiSG0iC)CRjCyPC=5psMilv8_tcxGl;XC7#* zQ}CLicK+VF?V$8reWa!$=`M(M^KDKQ*QVBK6B!54o5C)>p1AC(RtxOsV6?`AtW z7EH25A3F{t@A|zl71tg4ff^s<&X~>Z!%`YS$6y#sai32wZ*S^Q)7ho<`iy%;>4RIz z_9KNJS(4(Jxv5_2!h35UBpp!1Gy;PRla=x?FPq2Kx{1sACocy?gnyr0ZOW;iEQA~! z_O#BvEp(q+krG~M#Xme%jhT#kepNjyGhcSmJ`kxUs(f?Psz=wcf|#z_@Yh3;v5i$W z`f`5f|b2z-~fs|>FVkseR!jAmFbd+Tv0Ez3cmuw1HCSM6Z!mqTj+4zFa1?zc>(rONC> zG5k^8pMvE|DDs|Ig7Nk-xWH~5^H1IK$2TW^4{ z#TFy^trU2~4u zyP>u0pM>4^a2_rfwwuxN@;Z6Kty_oGGfz{_1b~)0YRdQMLcL_lZTW7(a@$@ii?pST zm)A2HuP?xha5$UO_F4)%+ZZ(^(N8pC+w9MAOJV-A#zG$*B@hyoWN$axY|Z3wY06X0 zX=`x5*rJjSQJtlH_0oKy&MsmCz%-nO+d{ggW(-@lHh`^K#5U6U3e%u6jqmA{{5d&e zP(GfPc7HU@<6LUp*}XmV!q0JOeWY&T#>iz+@W|ZKLyTCt`K57ITvIzw#)SLH{L?R> zs3m5a`nt7t{yI4Z*vBz(+`EfJ+F;8b0mUo3mZMTInfR>Q*d)Xl5pV#d>BZlAh@keE~!AODiMAbq0 z1~7{^6K+YSE(h-jYCJ(UH~&+Jq7yF3B3`5N?Xuc#@Zf`+N3H3WCK1=snuN_Z8C&T0 z!-x96>31dx7dVpKT*D}Qb0e+r3ma(>ieKyQRc>@M)$Oy*4zOHa=S%_(wIL;;jjy#4 zoBdUR_N@_Fg*NE(uEP8~p!R1t+0&r%tpc*G<}V4i^Jn$z{hp+J*ENP;*$;iY1s85P z^w|qE*2<1{+aBw!bGM}|WjGbz`@{i&zK0UqQ{@gT?Qt9aA)I2G@{N%W-EEwOR=>)G z(c>N?pGI$=`HtShn54T1eOzG^U{K`6c^!LY2CK2}zA5SPwlULIJluVz5mRY5TIVA* z#ux1K2r9H8*)HcH{L0cVDTt7&?!uOpBHCh5+^Zi&2^Yd>Ta$}%Q6l5NKz?vC7f3QS z!)(c9!55Ei52ST64( zIIDlG0g7ek;nJ^?Oc~JwL&EM_Q8e#UGJ%VD;P+ z_Fvqxqw(5rjZ)9NB|73VM3%V(z!`_HU#|8b%(xJeGi1+sNv2ib+wP|sM)(#2mlPbd z1~KY=o4cBgZTI#R`arc)S5kxl7~cM-+c?@DsdFte)@!xZ;j^0-zhC~)ZDKN%#n@h^ zxPHq0?j%VSl~uEuwBJEOpK-|)&83NC+Dej;8_L-5JRJO*gStY^U-fHI4-i9999d*S zBr~(!TicVJrQ#AAip!r~%+x&XKqSq&r5E~oePK9pX|%KWS%EW>(FNhOeOf#@kFB1- z^I>yXTfNfaioTppIeKDAh)+}_?t2&zpB7^5YC@zx^d#`;&qumwk!?>_52#CQ-mea` zOyo5tqvd!m$f5^i!#c3EJq|@-d9uCCwqtILvh9wW)SD-J%kEgrS{cT|b_(9W0nJj1 zdPyh9iVb102vi)<9%}S*=Oh5y`XcrXuf=$7-TtWSvF%r+*0rw7h=pf~?h3?o{;Y4t zc;5E$;9r?jd910b4>Ox%O7WSVhy##L$!^30Uu+Z;bxbi5cO*wX-V-%vv>v})pGZ5RP?_VGdtwUuDEdt4uN26F|k?k z&&w0ydI33LbFMXT%K{EVDvb>?WcdQ==nzzCb=#d$bk>Gd_AU}#xjA$BERurKq=cs4 zyFrtwGcciwh?diXQPb3tkMVa6M^2Bnx8W+FFhpPlm%Uom5@A#zW^n*VM_pyR!Df)P z+Vva=jH!98cCP(m%k-nq;XIi9fAivS(#es8_IrVTc?w>ri{K?tQ#mVW#C;WRUfcna zft>WJ24)$Hhj)g=SfP9%)d~3U0#g8X>2Sv?^d*0psRTr$;g?CLs-~lg3L&TFWjM#D zhvemWcy7REXqcnicQUwWIO8!28_||W(%RWdjqTQ|dCyCop>uEWwqDCHL1l3ialXyX zk?X5+B<|ab3$9gwfa@!)Ze}=~cI21B+Ew{Lqy1)`q~)f;>>3&Kt8KxFL+^`Jm=F%% zfE`Y;!?Ryp)6dwS&yD%aUfM*Mcuw83mSQU^>So5{274F*RG&6~hDAaOE|4DyxthH1 zzyUSd(t2?-!ZheI4XGA2DO0p$%5vEEziQy<=#X`Bpd45C!{vG(grA#!(K{Ta*K z+juwWo!erXlxU?h9QH$ewO2SV06GzS`rB#5tqNjkkEyhJi!u7z!smA?nM*&=(gj+Z zHxIk5O%1lU?(&S{h^6GQOpa&2AdK4fa;qN#et|e^d3-2sS%};EUMNhJdM|2Cr&N;! z;r`*P7OQPeAM#h-5sihIYl@xWXyeLTTm{2oCQVrW)qaM7jEOu>fi$|3=;tx z8D#!>O5*Xe@H*EM=JY5AmtvhS-ttDqF|s62L9E+#Ch;S(m;1KEK6lX4F86Kp_4OMm z$er)qWI`1&x+s1zxFQ4}l*pqi!`d2d#@WRXm;zPX0yv+DbQo_)2%hFpm4hMYt+(IP z5{!;%(Dp#)cU}+ETW_~YhvWj`B{S?2IX(m=@!u09|MRl^dPt3xmZw*3A3pg;TM_%G z1b}M%1gTfi+n=1RI6WI!3Su4@siX43DsnmrrT0!{?_Jm8b>E!$<+;CtR=D0xq}SY@ zL`QkSW^}kQzA(~Va>$`uWaOwuIJ?Jyc4-eLc12sEV%3uFcXQy|OxL-U+1cvxp+s4p zknj=XLm=brd$4Y8c>-&=T0#DJjZ2nJf!<)wqYp1r{>R&;;OSdZp_wGgZT`d89^U5# z>;rX+nMNa3I)Sgg?(gmjZYBmcbB-^comG@R`k=0=yP#>^j*+F@-9VWKqgCXxmiwaj zUgQ0fcU(GHe~U8?N+DEe?334Sd`R(z4QuI({kZ4dZ@((VFm4`JWe_pK$8Kq)*)OMg z6&Y5)TcZdFENt`L-YOE{t`U959chWM(1NI z71ZGUb)7s|tj=wiI!*q||6}qYb*jBtKIA5E`Ix?S>T{EDYrngf+Z({0nthJTtyl8Q z;E8oM!b)DfEW^WV`20@~AFmyqw6@l_aHY>{*6BXN8!v!}Ta7V`s@%6t5)XR0Q|dwC ziMnvs`st|E^%gPF6HKYrd|s8ir^w6(RoQAvAnl|kv;dG&kp5#PfRo%K!t7t|4^!>w z746xG&QPb(qEryK`b-0_t~Ovmo~Pc>9BT6M8Vv`n5Rcw*k@~+LXEO_3N;K)bazz)Gbw8(#w|5kFh z16Jj8h5#n!KeC)G5S=GKC7P_kh3t`HzURnlUDaZf#*L=4tq9TgK)W1sP=6p9Mwmu> z7;I)rbNb!newbn(u;MJi>bZFhmQeL~gux0`Vp)s)QqDjSF$9TJp=I~m{`J7zCE&P} z0~<%Qm@Mss<8)oEq$5bW&VfUZ*ls+U0M?@U)%jkGg~(TsSrXEb{^x ze=LlTD6v^FG-V}5pKf43rGKO>W=T4!e|Iw}8igkr ze-R%als-)NK3($%sB18rvr+>6(~mzeroCH>rV2xpg z4LZ`h7|Iv~(W`rv4-=-|@j2ZW5KdH>D)HdVFbaiq$N+=K;dlqFK78M9q&Lm`&ja_3 zU%IB73M#-lX}@`au@|dnJbS=(pO~FTBV-#7;!97z=mHVdJt{6+aNSsp8o5R}OjL9S zHDE3naBY~=i8#K(!g3l0;dt{$hWyhidwn)}I;?E#fwWGgG(ayjOg<}rlCQ;EL3FD- zD82D;!fvG5&rkliwDwjq>LxXROH}fkduzr`-nE2@+$Ie*u)Cq#U$7mhg%)E+GyhZ=!mX4_W${E9$l*HsRJ@%GHicO_Ct^WM(aW@JKrG-Oh z>L}pUq2Wxv$E{WaX`7J<)XnEpH7@-vep|K6DS7%;_8(vhU>c!o+>`~*Dj?)u9LZ16JXNz$fDS5JQQru@e zcr7CXR%|9J@}p=3JHwIybz+bP_aIwK0VXrdI+PYg$_gn4=Ze}5gs7lzEVkhKcn-vW zw`I>}Hr!n!wREXzpJ;1*%@08KTBn*}q#zA-$MWRGcE$PcAQ%QOdnM{i{j)#-Y(=_P{Fq=`03? zr@*W9Wa?nf3=Oaj^98{PgotAC2U;D-R9OBXp?bJxK$ zcGoU8ulv}wfHeFy1p6=HSaR`4RTUt@sY+3_9AeDE-R$0v{_@vv+2)R#5{xcRFa1Ci zGGBbi%)q%j&Vy}SY92JHlcYBAGZU%rQs=(Cg&0007`G1{T;d$}Z!j*6VUSq5xA6E| z$-<^ls+g9WiT*F&Yo!iajFN~6f9gL>LC0>@lj_(!S@Ov$j>1;HZsW{y~n|((O1Ic0^Mm}TV zIpgy_ng-KF(H|fCQyx4Je~j%7g;>YCPM0Y|oQ}q^W68fZP(LeIcy|Rv-mEXO00+$? z{o!->J*$=NhBAEJo!>N#@$pX9tKk(j61*VwBj+<5DD173ig-wK6XwF z3n5QJ3VwT9j@UFv>Gu2$$#2KGfB^c zFM9WSz`P54|jusiKLrX($)Ej%HC1IkxaUtpR zl3Rg~wNl2tw*cUP;DG`Su;@`M&-!E19cAYHkkPSHi|L}xhSzfwxo`XlVu+LZJ|6L?lpka@PsG}_{=FU3t0mBx*pZk#hv7Qj!a zj%7y;XN2A}|0%H8bh1QOoroo&)lL+gZ7>ZA0@ccgw%XXN=6I!T$52#SUIuYz^iHcN zQ5Q|=Hxr`azBB@GblLqMXL*BNqh7KT5O|^VmJ2E7y4=5MB0gMXEb*lF zT0Ag*NB{|X@;Wg5|#Z{2^VlXoZhP829t+hwa7^Gflgxzw?98@{MqwR)* z<+i`LMs+(V)5x9FqC!}bb_B5rz$G@Yi}cS+hl<0w`DGQ*ZmjUAE7zN6%yYjp2gp0{ zXVESm=pZV4pj!09mzOwB5YDSKcHMnt=#Af#(r&i8`^_XSy~)EJU30e3s6S{ z!boBt=H;P9;hfYL7y%?UZsvhK&tB1s}5cP2n zB5ld4DY$I)n&oWhAK*ix*d&rTZJ~mwJTyz@+_=AhQ`reG2c}y=pHd^KjQx}(F$ zIHu;!qEjW@i_WCi9l--pLPeS*NUhx~bX)z&!E#3P;u-hTf|YwgXf$xJ zAzcKC7d)kTW{vo0YfEiR*s6gd*g0h0KZa|{9}3>fh=tBs?FW|siv?I2%u3)hl}hA! zeQ;wil=dz5+zCrP%?#rh*S@+uu{(UH$O+{sctr!Ki}D?eHR zfM5wAyF`#*+|dc_2V|$u`ED1Yn*c`Jx4PLQi;rmotbgaV7bB9N3SQv|{3~Zx9px9RTFI z!%aX{VB^xU>GHzGG{O*hhZ+e=@FI7U=Nip5Y&h><M!N&lnDv zum<7hR6Kgmi0OohR7o@g{Y9PUWb9^}8YOrQH1_~?I}W5pdr&c|52t`SB!OF(_iQCA zW}_E$xw-9nfY1rJV4p*v+U6Jxp99Dk0n)e0JGm+59)A`~x0}v**SP0Fet~JG6uVLR zw9ue`PT43G$lbxzvi9WMPkVn+6=!0=3}Kre%%Jl8fZ-(jsnbQAOv)ljh4>nF0^aeN z&RF%Qd~o(|2v3@*w3CPibaHt(1-E!KrZ-?AK&9??f?>*zF1`kH(pl2+2`8p2h$``l zP+17WYpBV9@>*Bv{y709&oR@0jLnzOr26fqNq%)wHb`7YrWGauXrPz$9Oi94f0=ym zc{p0E7DV>V7XKSh>t4O!v_IacnsfvKf2}q>9&E+-G{C-DGc$?3><9}>H1X^XzR9o# z7ojpiW~ilz4u+H8nTOv3dWL(~U+;=_#@W&wU&G#fji9P;n!h;S z?P5xOLo4N7BS>HEIK9>xBpde8p!Ve_v;db;P06&^c4N_2`GC}9W03OkUE{ia>CB~c zzspiU!PZ}D6*XUaT4%Eci#FMf7OC@~^Jzhk#@@@h{0HGwa$ufD9}q6=?;2LUviNk7 zCg~;a^s~xgGDQFsJ0g={AvY(Tnkz8`uI)&{DpKGtlKW?=&klszS2NXr{WWuYB=wGY zYd|fAPPAYA7Tay|(MSZ@kOnpbwoChijLch8-pXr7PR$oq#&xesL8;yKYoI}J0EEV! z`vP4?octYxxP(QG|I(90Ogg;%v2dm;yWya3q+Qso4ZA0nEu`KzS1tLFNkgs1*W=@R z5>XT9Rvg5Tnn*3;&;Kpt--*%g%n(T~Q5jfXfEl{*I-bIR}-ku4rtPzmZ%Y7~S*WB3Pd+x0-| zz;{x+Rt-R_sj}$0c@#`9iyAZqnvt$M$V-h?DBR2~S$p}T%PqUjF+CEn>li`XoM%{D z(Cg6NYcW=NYOLIYm?ZH#O+Ol`$Yu+6-0$O|ZE)B9 z{Ph(HaQkgk8#roP4Ql(un(anEq)fOi;x=Z3_lAsv)qkw!>7IiidE!8Y!VaF@1PmLalG8xJ<}W@xmTn@NXSmX##HSP zO??mnMcIJVS?>jtW;>lvf4gYzW0G03Z?H~OYZo2jdyUINirIIu2Vu04K9SaK6Z|H3 zsQ0NW8vMK7e`=;K1~)6hX+_}8olshAGHDt?Bd8)W0d#m$S5bdy^g2Q;KP%7@frEe% zSF-et?nbb1h9MfsA`WFo4F*wm_S2W-1Yfpv!^lH%mSEdZ785)Y##g!XgKcaNB=ep<6IUa&8aHx#)d_eGDLb+)tXraKauP;y;3%ZSgq-*FNR#lD zshy*|Mj2hBa&Kc4#$p!v;F^Pbp;`*CQE5Nr^NaY~nr%f*r?#V1#~4xZmtEWWw7}1< zaUfg?YW#PO5HwE07>Ju~;6l{Hp>#9n7Q+^gJTt9&-wX76k=ce?=3c-=Q}n-B1)6IuMHD6wn#Q+dvRQ;?!l``ySoY=DKi^7N6I;9v~ZIwvF-Y z#M?;$S{w93kRU@kl$^3cTTYRwR1YlBR8Edp zM8i>d9Q1tf$0ZrF89}En2sHyC%!|aD0fW&12(}&BP&qx!CgZYw-!AU9R$~`pDGcuDYDo1 zzOjQW^d{WVC?=HlR9Pim7dSB+V=T7MLLiw;M((|^wEL&wdH#lzRSwhnGus8@r~5-1 zu(wA1qsS|eemh?TFrdSXiXk-cx95^9Hpj_-PQTX)UEVr7++5#|k-m}6(C2ga28nb@ z2B3I?4T!?Qc9}m1g|89=lAS+Z;Gu_I z%;07iZ3hvHEwv~4ObMIqPSuX_Lxm^+A6t4jZF-c)>?Q%}cR}GA+5t)07DfvfOHs|E zv(upFV+|GANV^{HuRhJ+%C`7Cq@4~WLZm@#lJ4A)i7zexWY7c%DfCQBBrebg!_PK` znE1SC(>P8kxoq>ejhd;C1P9;?M9!U2x7#NDKkl}DZZpmY-P;y5jyqf~#6P6u*rvSM zc-jts+va6OS5ws{N`_c^fHE&aR=qH@Dpan6_0hV<9VVZJP9)Qmhc%=w6N|Il zr|tyVRHNXAe!c8%8mAI`7~6fK8#nm|fQS@DWMLvom7!jMBl`{dGstWetORaBAWP7F zp9KeD!tT)meb*H0;3oFp`Lghmeq5GzajG>|c6<$-7f3(^uMug&f%qB4*L2)g*rURA z-Yc()Br~C2>!|sC#lvX55lOt;Qlr=2J^`8eHiSEKV`g}Pv?T%>t$QErIOkXk zd|v^e&WFElGIszV191{l(AzldM0v`FBz+3`;Cpde3l&p%`qIvJr>W)jWBvwZCfB|LK*0iiIy0_BSV0UcywW_B8%5DJ!@VC=X_$62Fw4Mf zk%rld7SZrAO|TVv3^AjtES>)<@^ck)%Z2&qTwVS;C`}q?TTfC@Y*?O5s52ZZsQMg2 zOXR6B{Fnrn!>Nb#7P-bSRK0@^DVL#_(jVYOBs0Q=3V-jMiMzl!K!R3AdhypixcwTk zaD}AdpObGd&m$bTvCa>X-y_389VS}r)Xd#!ZBZOXSxGN=%YD{!3b4kP?Mn8R>Kf}h zRyu$7BY1%#Dvza}RxX_975J-p&e6HSP$?ob5MuSD1E>gG@HIvf-rV-zlRLuLPtnhb zsCPdIS|i+8F5h#uRY9?x&C+0r0KwkYXC63b3*V^#hh62u>MpfIJGrL(h{$0(TKu8< zaErgdo8y2ta?~w1NyA0>^LGS0V?y5Y3y-;~vDDQR$^U)#Q&gzsmYxL;Uk7WL5H!fL zbHOQOJ&|9PudlpWLZ%ZgaTmZxagQdV!JGjHkI%vwvy~GQ=LluawK_@KDftMTCUvxw zt|1`Y?}lM565ZkqWY&2o&W~pX{JJ53yLiC-6`2$$5Q1kFB22#@m!<_PU?E)^`ee1A z%6l_LbrBa+XJ~WfbIPpHF>>-{$gkObAG2Nqedhl)WaOX9e#P;p6sEKOl9^!sdlaOQ z@M~w{rNyy{-{EUj6D zLb$~}rPAwG28k+1)jxQ2UQ8FQfq`O>V3`77ZqvB!6sioP%+w2PKz^k$7Rd}(xl3D@ z<)#%C>-hHkI6H>jm{kJXHM;taq1N)7moHmhU+4X5ZX0f@DW4Ah>U6lKR>0fOciucjjxA3noEkCkUOGxZm^(6E;tc~Prb4obRz3zDw`0SZr!4DBvo~D~*dpTZpBNYk-MLiE=Foj>z&qv?vM?A`*V$jW2Ax#!@&3VV8|MS8mSDnEQ z2%xHFJ(3Y#6i4ene&%X09hnD3!S76c8Mpoou1pt+(sEr$ve?fM3^|x6o^d3Sc4JDl z7H_#Pd9u60+CQuA&S@)*pF-`Dh0J~kN)hej+f`2p%@V3cM=28vqi@B3rqBWMebz^4^S@x z$JDXPby?k=sLTALHkG+Q!)tuqmgIoyK!#k8GQ#ZhPVeZ13}MLREJUMl&NGH1>)et=ZVHvAVVmdY4oa} zy@NCmO&{3#2(<-{x?e4S5I_!QFCN)vvt5JS$U+sp=mypX>;_OkPGa&}<>hT~a5RA| z4osMPHEdzg)$5S>K?6j>@6e;w8XWR^j7CJb|(|G}MBgeq#s?UviByt6qap zP|ASh`$X|j294noT+;2DqqiZ6w)Q1=G#9q(evY#`-@}|7i4PY&w;jN^1Q|{F(CZ{J zBgxRtplh<&pA?1xGV-Hg3e@cV9vEz&gj8`wUW?UkI8W283&!$HnSGfvA~ zTq*%`6*wU>(Ns}+XvR(#a`+ERrN!USw3iAuv4VEWoil^a7>;I!LuuPyck6{w1t;pD z(pla>`H-WHi#SM2J!zF@AO^3{GSc_w?!1h2w)n5-0Q8)R?hR9=7lxTj*x|H{2?cbr zJeJ?%yYCut+`XNl-=XbAQmT?hO8K5lDfY>+eocsgnLXfTD-PC2>-q6U{yh2oyTSKe zmwFw~xxh+6Fc+OCNYa7KpCy7}a{6Pu=)14)a4C}s&8V-2wGY(jq8;$7bAkusP(jcN zGLDBeXK=on<47T)8+bQgrBOE=Vj9%VBhGS<;LMXW4rC*d*W~8jJW&MQTW+7q73VC; zLYJBl_s$YEClc}={C=cF=iAvHS1E#GWwz1dk9p0!pbs+4!1T&{4>$+_Bm9lGlTKzr z_Hn5*qnUPwT+o7&YMu5BS<_A%;g-Lu+>Luj3S|1=yG`~2R`XO@>jvZTprv%gu=L2S zSOkR?$ZyTLtaWq4WY)m5d*_Kr`9OJIBOT&tt2Z_$~hhC@vHyTh2}!%-|_#zh7vJ^;lIjr!jdr zXgb1C#uz8r_ykBaKRNv?YKlJ%#Ntib0VK^Mw?^nK&YMrYh85}a1ieNh_vC0B9!Cxj zyJYsa3bq?Qx|fw7Dx<`V$)fZlDSR7N&}m`Hld7wa2z*Q$raYEYFLCoRV`b*UWeTQ7 z?}@((OQKFUBO`kAAnMgeO9Swie_f6`TTA0JAV4yosi1y0)wl5wib{Ex8%IH8!2$1Q?-hho2sFz zPSfnnb_spWXmVNPuQwl39Sps1QU{ef$FKuJyj;NLW_?43Rr<CHFS9{kP)x@^%1qDNsfCvE& z5ETUlA)pw*&_c6ZI&x5oC<+J?f*6Pj(nF%ug9Ryx6a|znNQ5X5Fjy!eB^*UeXp!Dg zqlCA|ch;K%uQPgvNYc^kpSi zLmEUXP$|gOT`$)YdytOw2V9CIX>`o=^R|aZs{}Z&AX4 zLTPu8>OEH#h+YA?1Rnvikhwqr;MUAdtqQ}rr#ZNWHz^On-WuX(9#7=~Rm0*uSm_gn zPS@jRrzQu=bG!hGJ^+wA*Z!QLV?d7|#`Yd*+9|*(p>dZ0D1PrYQQ3C@;_an?><@Bb*qemUWO-d3 zzhh$tM?q8-VP>#Lu@_*1wdgOAy^2rBR6s@zf?`(X9bi5*9@^2;N2fu7!-C|!mQ}e| zC+^Rkp?`qnr5jKdNe#e;6LwxYn@W}{*L6-RG|?$F_KsdBXq1`$oH_Vy6*TsD4pQDT25cLfO?zO{sPVyHZFK9t12}J|QN^f48#(1KFca@91(W}P*O<`F0=Z2DI2di5tw*jX5 z5y;PRV5H@achkNomQagH&z^;R!BsMrZtehC91zx>U=`5Pnoz{CfW8T1Edh-8w{c#0;vc4lcP9%#|3AM$K8*=W>l8K( zbexecY}P*e(7u*`=iSWLrsbz9#MNB-Tc0QN27tVJ@>U-K88XZ27*yO!((~kYD+_>n z!=u9)~T*dVdHNv0CN+bnh1saK#L2C z1{EL1%Jsa`V?C##P2VPy4nreGjI0KiRF=sxmJdQdkGv{u>VNWQeP<5(NJe`ExN~Z3 z)uQ^Mq$8#{m^M@Iw4#bT;12#9r2ou9LZ5RHfSRkIk+T6$(O~RW=^ebzUpC?JZRD>q>n$!9QmpfD#GI`a65n^rLOyIP8+#%kipxs+3Nz7hZ3D_S zj5(KYXSlON#w=b`ss^%qU%dcFuBdTu1++X!l5W3jva_HP2(dMU;iwKVwsIJ=u7#oN z)zBxVyhVN3z)E6N_3)*vpv^mDH(9rZMI|-58Qyg~I*}37qm`^6I4k#)RX@#Tx( zC{=%zP)4^}>`&5h$~=xYwu3s{3OOqV0;#LqL|Rkoml#eq9SeS#TBIxL5o*&uvT&Pp z$ZNe^RK-4`!om;|i9#(_Ici)0L~B=OOi6PV>wWPraK&_LVZM@1%YaEgQYlH5W=IgX z!(IQlNB1c@XE^!>6uK}cX7fb3!ARS78-|dsTUpk0qe4Xj>H(OBzK@0$h%O2hLkn^p z0O)d;p~4&el`Ic9IyApaIb8f-L|=O|6lsy+xFEmir#io*fV8Tu8iF}WglBEF8V8c- zysRQ5W)QEyF+2V z1ApmxrycP&P3Tb$VaTkVKC3FD{!8jATSoZiG(yJix*X%euLDS|W|<4~ll=a0*)v~Y zdsuCeyKl=Fl4ZAuhw;kaSv&wyYhU_#6s0Z?1~HWBZb)hh26>oGO@1p%;HeaR$)L#J z^=B%~O4fk5g*a_jBA;&oreHz$YnTT!D8@xBu| z0>5s@iu72BX#{>%6V)8v=g^0=fg2}pE>z&!4k~W6-+~982h9E7b@3&!dH1Sf7c}Q1 zQuA@lRn3l0z(fyKA4|y`g=A_^@XPSGS?NX?{{)F$u6iAo(-LS?1Ykhv6M$P-bq4Z; zD}LobSsGu`bxF@|o^i^aO|k^<}0=kf4Gb1D=^1pAp}3 zGbuJ*MbecSPW;(@O|}y0_ga*t93;NefN_8CA?-syPnDFkz*r?079#^JIu?w0=LVP8 zaoYGAGu4ju5odilOY$mbEnds6FANVRt!1oA z0d_0YT5UHVHr<(Nuzdwzs3jJdmDx}1RT}eLgrprHCG^Z^91YXzc2JA==7OY-R=!d< z!sfhB*;7^Z(oossfHcVL!*Cv2W>vc-1u?b2g89k_#j)Z&pP8atT~g{%Um=mXG%yK& zc~rBYo<$1B@{(@&w(a&rDEqR0np?zxB48bNU)O5BwU#2zu@cyrx7jbbFE%llth!|7L05I34iW@qBguYnXLsxUa5PmQm0iN zBzM82rKn1Rz4QuA;(1QXmr9L5#O7f|0adfAP?eHBinHbK`QJ?4-xW6)>n(8dSm~m( z;r5BvPr=OdvI@yo14EqHX7Vez^)F5e7?-Hyr)V)~5s<4V!;Cy#7dS4dpKLvF9JvYg z7R&DAC~~tvPEe1cfML;&m~bCH>Py~L>u%X>tTybIwA}#FP-f=Sf@W!vra>54UPe3O z>sG>U9hgA@4G_hP$qKCsmbB4KakEx9kH|m}UmV52vp*>MDv$p440T*g2#c(F3Cl?6 zp=5OO;rz++QgBA_%ZQ(4r52vD`nI&Q^0-{G8|Gxk$*MspYTx7pBdgsEJ+NY)z@J5hwp(&LB`#*|KI2f~#W ztUJ;ZgfhBvIh0XjTOWM63p$MH8MciZO!jVrtLl7Q{7Vwt4sf0P=*xFe6dYg8{-szG+v0CgXbXxHo$NC zoaa~MCOC6FBKZ?bhIBS7W&gdoFrjZoS=->qp8h`d7t-k~I$lSJirQF2fqqSMwcz`y z=9mMz&!2WDhx0}|v=g&8T!M`igtx#X73lJT*;Hr$rY_>N#+1)tyNS~BR9BiPTK~hy z+~}k~8*4Y;bNfEiR%OHV{v4v57NBIW!mY>0Z(b3V~Smk}smqebR>D9M>+h7L&((%(l zE|0t8Y3TJAbxMhKr7N@1`7DN*$J!DK($%InQiN5VKkB`^4~doP1Om)qFb z$Zq0JUI7iReIQ?6KbK#pS8iDij(9yO`z5h1$>h+B?lof}b{+di`ODKKr|#6K34y^l zNjCuw+@h*C!XR z|HKc)HVMAZuKeh2Pc)guf?iP+o*#}jTwht%Jt%&JejD4#dFyfoY6lYZ8EB}zM!t>K zKkt7xqBh3yU;|%{3T^ynuY4Qj|L*bsdp%;qN`5SVJJS>?SjiCm_mvjj!V+U#-{7vG YZFUCQXwxNt>l2*rwUq>`Bu!An54m zxF9=>ARw}cATWZo;-~H53=)G>|x9q&rPCLDhWk`9aonD6Sw9`uuc-1SwncI&4#=Cdg>3~~uO3#DR z_IzunEpYe6qb<#b8)f+xnB3BAQod#8X%vD(a6X9Up6yxl7r$#ZnvJauWNQN(HQ_BV z4tKyCgzVpHG$${%pE_3fryKE6<@x?}OOr<@!e zT{n#a(1>m~_HXPDciOG}A+!y?_^&b1?fsiOdZSG3Y3lvO!|Ksm`P6xFq%x!{RL|@| z675b87Zz#gEMFX9VWpV|rf0`w{rS=L#rY<-UOYRu3eN=nsL#e=MzR-Ax9T%61*U!O zO`UWafUm-}lkO=N1?u+`ZLp{TXB)oeDmc1#-sf3{}O z6hb=fw*BJ0TWUEo(F~)82ox@tt>qeV9CXMusc_1p!^WhaEPc%4$pM#lm9DrHSIYuS z0+vbqz?=y@HBC)_(CDQTxz`HeiQZVTMBvE7RuzbJZu2Z?-NN~F6XK)D*7}pUxt_I` z=qU6Vt~;g@!`#v&qBvgYu3sRImn>Gn2Aqmz@WytdCdt#4lu&*{b2CXLXG4u1lz1Q5B%wPxn2x?Fb#}n}QD-L(o-k9v@jeI!JG<23uD46Yp3jvzp zb1Ye;n&JuOk~2-k3fn`CA}D)3(P*U*icXcyLe4OuHO=&7(3c)d8+h2XJg714b(?x< z#d)i>0AqA#c7>R>r#2G3#4OCJ$hNIvF4#c?o8*e+%{OKM3Cp3F3f;J)t$i#L%xMoB zB2kxy^CsAw@u0m%AY?MY0>v5j69F5Dg15GetQ@xJAdV*u#jF~9X>f6?+ajS6+Fgzu zM~|bvY#M0c8tH5~$b*2Hs?DD0nO?WaHzTI6Hk~d(!nU#`osze@w%5U;Dw%O@3SRJR zI#D@UGbKF(o0u4|IjgIo?ZabXvK&Czz}jkB@p=`I zG66+4sfta;c*mENVfpJ84bFI8O5`1UwZJ zRAfB@Zk50_ZtaFKut#i&n@Ulr?85KkQ>%wSM%GZUa@nR!FEhRNMg{E`m}o3gLHBrk z+@aSgH|ecYNr$WXM#<2^qSMj_F3Hrfpg9Sv3^rRsw6p3i)@WZz;1$nzi210Z7N#bF z2}SHuL{@gYNtdHEW@lBWH*GJ&7+1!!+UpYIb{<4F*DF<7>aX<5XH0W53Ji>oEC3Kh zRk{3tc3FK*#ZEwY3LX%eoN&vsWzXU~FPu$AlG9L0bF0%=I}>P{tOsdx1v)m8<%a7H z!CeR`$kdHV;PrNnNTxR$&u4I7oG9cXUQsJ=m?QbR+v>7pAJ`vQYa|R=V}WC%-n3i{ zIymJ@au|zvwNmgNyJ-#Z!o=i8KLVIQNJ?8})KQxjT}$mvW2XadBCsP8(kXpJa$uc2 zv)AFPb{}0A_+ag)4((7d;budUv6^xpi>SOc<61MTF~9=;O@*c!^4Q7RlF%g!VMVz<;sPVHqj@hKufoFXizw*W1R)0uJ(*9zxM?13 z>g$Sx7ww!~FSsTOwKKBBJXbIMCOw+*iKn_^k;S$E=8Oi$Lt`DnFr*N7B{YeF3#2>d z2u7M3*KM)>8Qo70B93sINVqZS|^!R;dcg# z9E?2$ir30`Py>xMr#dE}GsHyeNEzl&&^63gp#izra1Jj}*j`jnV6MqFX7{RuXzPB4 z=*EPwvj$u&mqBBYC*dkz@>-)q!aD%gLfR4Ev`cFxl#pp{Py^nSQqNAPJLIc~FX^1JBc3M(v9it;iZbNggi#6M| z!MbrHOR14r6$6r;H4%fTTq^QNw`tZ~fS1;)56eQgqqRoTAhV3Thp=(|gr1p%u(Fbq zOkA&)6y0(eXM#^>b1GBvNiZ&h4P(uH3Rrmy%S)Z^l7nzn<0>akHeQcZlIF<9^6|J# zXmA$XQ)su0u`ZHK!<9)PY1k`peqe;HR>$H8jlrUbT&KgxX)kFBLkMm*z>-B1ITMPB zKhd34gTRP{wh5ZTm*|v;si6}(Go4bp3jw9jdsI#vrLYn z*?=&0p0)jWx>>vKvS$W9FZs)cQIg`cg|5L>{BVPJMw3ptnxm3cbKGhZ0v13IS7Oz{ zTYz;CRs+15%wQ}mfsxU`2is%3ek4bh9Qc5nCgV=9p8%rq?aArC0*Ovko znYEi38-aNxL~y}s=+R~&iQt$(P}L%ba12;F-NM?Pf*ckG>}3?|>m4e#d!>!l16~sw zm0;9ybILL{-BkzrlpM`-krlBtq|7(!KF;;pnrC zl$0sxwVG-};M;XNZ?xzhB8p}d_{fG_oAcU};ToeCW~OW^s2VyllxT^jI!!Dj(6&4Z z)oHH>T5-Iu((^h(Ay^l@30=8O8!Y9Hg+aoPR~yc8pt4%c=$XrFwAh}qaz`ggbJa~! zt<{!B$FOG;J}FW}9|v8TzPT)mx>AkwTbv zYJ;ifMU!&kUx9;py5;0L;VRN^8SEnRoU38VyTRBM_t z`YVoSyIR+<%xdZ}sO<35o?3B4w(255x^RXKhvi+fzO;j~tXw+^a@C2Q4Yz8`-8KT^ zEI?HIc`5WtdC4gX;aY};x*J!SL@F_E#WZeHu|RJO(JXzUWT|EtGMQ(MJWIoxGPIdg zRk*g6sL9P-R9sC;x^iR*#W;5n2CQndyJ};snNUj0mNo<4#RQ!oAch!+&7~MosNES$ z2@m>F@f{__Ob*90d~Bq6WN-z;K;%kRW=n3Qw8kbq7#0(i=d6Ag%qCd)t{Xx#5Q1R7 zh|M5#RxLegWwVYqSM#1cAEAJGI=QF{MxHrcbIp%=w6#`hgIg*S26dzXwPs>_J=NA` zHCYT-$YNXxewT7nZ&=Qv#(3TGjY=n6w}oepqb?kNxuHe5X~j-Nls3QShJhYHl`>e) zxcO|}ubDyGijvVr_2pJWSmbP9vjleDR7Q%i9@z3=37!P-4{y<Gl{?aQe-j(RDSIl{2MU=Kw||Z!u1$ zn-08a@$2x&K9okht*kdbJ#^j0W;8Gs zNMu%Eh6unS3DcfcY$!WLb3vDJ$!ufy)%B zKozVECaj872*DK{X(l$qUd_zGD=$;2J6QzX(C&?z&Bi!$EvB;}&E+I&EGVe2_S6|Z zQqzGgW>a%hTdmu-r_NwFu{b6xJZ7aJNj61w1M6r=j%N9yUeSe}TZ0HzOrf4YOWn!PbMaLl8D%WqpGWJlHB1(QzwF8~ zpN9I%$43^SCY!*JIE5O*AnOAc!0e<*Vl*SfxIZBPdGM-6p-juM zB=rlp%EgWpD<)r5cGlsieb?Z#da`iI1A{H4?n0bQq$CP!9+p)m!;r#YIjwOAZ%w_R z1u^3R<76hJM&-uj$F(!WeYq#k29nkrSNxpimjzU^CfMmTrqsTUU0b%eFzT>`4M={f z44dsxbFtQTJPOZLEo`Oml&lOIrkc z9#?RxkJQd{s=^I)ypcj*t!5~cbInX21JXEB(8$oqtWQN$UE+tkBfj2NjEMNt)5Y9Za3@-vH=Ryn$-mFy#g&66nq6<`Ut8AodR%A;z?Qe zQfLpyx)mutgu?+7_NPl|87tX_p{PYUpeeLb)RF|=NMRYsZ>u$g3gSl0%lT|n7)reE zw-~Vj6q-V3Cq5;_Y;TOFD=w*dN!s9>s6rMPZ<4%(CUDj7_Ni4cr?YBo}bk)Til zAxy=g&%?3qa~-o0s*SP(0+T3NRq9e5b;wXb*#Tgd^t9&%#*$tK4RE)HA;rYd@%ibr zjEMnnnT?fKTMW;)2JL1mFs4y^(+f9wQ!9K3ndz3c%5|=}wxMy_f^}!%G0GS>0e*Ig zY0J(aHtDfOlBVsJH6~D_@)1iV4Zk;T=u3NMq4W|OcKNjO!zC+`U0aR&mLC$i`lDmLXm8%r6 z2Xd}kWk;-79v-(~DhqUgQ3QzY_^^jY5H-cbH4up8`l_@|yDO?CfW;!hrC5)=6A3l! z^gK9U48(amTBt;Osn_N+8QX zQW#bYdgUO?SBbxJ&0rMc;EVY%1uVWj<5a}OO~y;AA*MElgGF-&8vi!u+L9Tr=BnHe2ycYS@_Koh6;;B;8&l!)yW#8q<-Grhuh&eMhEZ zPeQ3gHtnVzHW``=X1*z{j8L+1*IA45S}aEa<2D79=37-YRVi6F7JRR_So7j+JaY`f zpln$NLan)KX3L7qNDf4(gA^iwB7$3`yvPb&rTI;SEvSf%wNMcRth*q*dFv@6=YiVbcl6~;rEP6A?6L>gl_#%wRYZT0A#3Lhm6^yy6VY@n>xJjK= zAOcwoYB|r|APZOlDmKxI(#E)4j%r5-UiQ#$wO31>*(8qNF!@Bc98We24UQr_?YP2% zLxXHQBAkrRhK=qdiDy2N(;31cYDVHM1O{HfN0~Z$?nj*jYj+8sm|`n4ow#EO6?%5M z=q8&1-OXBB;q(P(mwOH6kDZ|u8f}hv>k&H59H1ZpU)9orEg!l9zAvbzP zpIS;K81k4)WvXpWTxwZGOxoHg5(RC`b7oML85@Yp zCRAy)$raR&+@<1U{G<|r20b1M^EKJw9Jf0bxnZb6X5{pQqMJtpQV@eQnwLvmPV6}) z)Wobc-8A{(n3Sh&DscxJ$s?TR%4b;pkSc;tua)|%Z*DK zoUydqtfa@|Mx&qVZYjGUydq?ORW_CqKFq9Py08Z>S2HrUTW&hNRy9Q3#;`xZ;y_FL zARz#g3D~*B0v?g`xWRB8IniQ&0`!u;-i&gTBK!T(umvdlXaU*{X|~1a<9=YP$UZyw+NwdxZL#*fbiWn%qLt^fS-orwQ4lSuGaTjt;DRel=jI}C zo)dWHwIHD8D?PDxmGzZ1cJ!uWte8YqZ>fPZ4SdRK*kWct#gudD89i7D%Xn1FRzlSr znA!lHG6T847B*CGst-ASN(D%6v&J|fR!KOpM-!oP={ojta5Eehe$yGRjo~n|+OTcA z(Hsi{Clf4+R5P{#G*Ts0@zI*^cvElON&9xD49d**fE)%X=t4%DiRWw>5m(A8RAbwlED71Zh!p=tU$u!)P5&J7^GL zm|S8$VFvZg)?}{dOC(dpUW5<(bUiKTmhRhD{Z6GG~#Ln0EoawHqcJG z@WvHE*iM60r3YxMIpHUbS#x4=(FWiIJ$2V0(W6@RI?fl-Y=u^h+MVSL-T_WOoCI(Y zD|Rq2ITI2^b{Lis)@Z=uis?XgLw8Xb=}7F=BMO&Bw~y!W5};axnHDX#TQ4_w5z-Eb z`+rBd|H^gpRuH9tqWmR{H5-4{ckC9_k(v(B>hW;HxJ7p(0}@iFPX9a5jaRN$Go8tz z)s^QowVb8>;mT+etWPNh>uX#)0LD!hOR*0LP}#^v(GUQg!B7ap#uW+33c++TcivA6 zn;54Ht3(|!A z7vtqj&O4R6Xim&k&lSm8?icJ-FEpCckO{Ovz2P(mLWW~Bo6uldfR!WINuL&1@uWE; zx}$;Ej7gdUSGrly>CODXdbZ3$6v+6#s1Exe7u8DZ$RqZc+G{ZFsSQ{RJfER}&(q7y zDQl;LA}%De)TH1>QkDBHyy>mREn_pJqH4gh8{DvJ7pNkOl3#TagN%bkgPi%5>`8j9 zuxti8pLB3(p#(|F47nbRgSc}gEPAroSG}!=|0C7PhI@O0WdJn$Z3A+*JGO$XJpB>XrR2JqP9n(q4U>>;+Yv zYWdphbF5DLZlbsR*eR%>*yXb_p&+K{A? zqfVlC%Xwce<0J-+;7L_mg8&XEnPUnY*XHFaF64>2)aqblZHNKH6cH-5qy(vLdy@6k z=E{TwyctFF;S%(T25?5NA_CrPz!sh0?CI3H%*I!RWmrfAJ~q?j5KYNw5aGum@W5Eg4G0q%$Ha4ew1 zAlpO^Y7pqIAhkDKl3{z?g9I=ovRG&1c7(~<_!Y>8{Z6qaE!U(`#X zm1B>G8f#r#i#9GPK#G4O za!4OgYy#nGdXtwkJ6JU^foFjDnA2nt;1aMEH6Fw?1<-oj#3qSY+HtU{92^2QD``iN zT>)t;TB9|K1OO|`RWb@aX*kkxvz3~^Q8LDCotI7M23y>Qm4R{e$m zixIhsQg1{t6FFoigSn=0OM8KJK!-rL%w}l`tuSl^R8ubCm2LtGT4Ey*;D8%(osl?N zSSy`1YPBBb3@e4Y;%F)%8aZ#VX_G1Onq?5v$x4kK7H5D(wAa0HVl39=a8adXpu#DN zHX_Iu5`oGfr{2--Fok-}L1KvuEC#`JJ2Ll6ueXis91K@%AAo&r;^CjjNDOe zeMJ;YWe+r4aoCuo5GT-T6^EeGk(4p~kZrP)PKZwERwSE;{(p~6>JhRfQE7^+5WZEfJ?Ho|$1#I4yR>a2N%DkjJf%x)Mi+pddE z%N$G<-5+D#w4@{`9Jbc8DKlBX`rH6zH(?oX6ii zM=I4{%d&ti`?g7;ZFM5JoT&wAYK+qX3KES&h4RXFC8UZ~CeeoS=62c!c?wWj!&iy{ z7fz4PeYW8&7}gbJLt0sZlej8@avfCc&WBs)7o+!*CzBdmm3<hF(INrUCx#8YgxZJ^acdoD-joPy1(C@8 zO$fIFWuO5ywP*L!1YP95iMZYrXe<=1E|*Qg-jD{aO!_^pXG`XkN&qKd65IwjUA&n8l+^U<8qS5erudlSu{tfubLU_kaNwA(#Nl}Cfg zI8H>@2k9m-yKTIUk%cP9MI8im3JIsla2~k|nF}z1%O1!`vnJAS2aG<@`<|SEqPVp$ zHENTZWTQBW+rg->OLNg@eBfw7A(7Twa8m6|S{w*eaR2YsiXEN_7I}*!a{?(}t8_AgSK>8j)fDizUn%=b8mKA6#X4AwX zq!o=)pgf3b*i^?b1eS;JyL>SWYsm9or1T{%TJ}bg${m0T{5sJw6vBg-bhpk-*Ca2T zgx$`#-B`E92wJy6b*N;bx>DoWh=Dq$$VL>S0lG!Z3Bp~s`$R=ln}y_|3Xr?V-kjLX z88j4gRgr2J8i0Zt1V{C>52kPyERsHJjYliJ59H~zs*2%oRa)Iyy|3AaB5%638bDS24(Pkx&=T0j_xAM(QnzVo^{Lfe>ienlG^rgfUD!?+} zXt2EH@*8g)WMVi23ZmWVjOI-s6G>ws2BBAj>32t2TX(Yx{Il?N$42`ryEG%E1mR6D z9GX}^uj;6$Ipo`O(uI+6+@G^n(DIS7LwnLjiB(4qQID-g72;}rQvkEyFGtFZ3wTlC z5fyJvD2FYAAQ_DOJdG2#H!!KJB;~x27*CVEm}@OmTz~^!>1)7$5)DjNN7L?*qGY%u zgZwDHgohzWP)_DF2a?ac4>El^HroseC`54^wy{}djXIWCOE_fBi4r=S7x1VX3|X=} z3Y*2WvrcEzhOCzX)tNOwA)!uFP~PQLkRSzDnLdCqG><^C&KdFEYUC}`vJuZK149IX z7gQ5OG2_U!Cdjhv_9x|%^Yt|u;qrv_d2T3MQzz*duAogA(NlS~HwPu5OQF}~KqM)S zZAZb@%h4#H>+Z!MV9IA~Y~e*;#>P!W4cqS2ce_dLC=rNu31?$OLad@b4T@KI(E|xy zXXQ&>4=TfzRX}UNyzxxMKREDKs=8|MjyfEP6`GOeshV(ig zEvGsG43&s8u46E&q9yoXV|vS`UruLnm#QQ_5HEG_P7Q5ZdX1_8 zrFtm9g+=CZ;yAOG2%9woZQjJ`98t8`>pR4Z&*%zNz& zrQWMPxz2?^&%|Kd@OOwd6jiJV5c3dys&-ew8e;&*ltJh~_d&J@c2q{65xUH0xDQh5 zv!rI+3gYy5VHon=Qb|_eM02govC7v+azW!JC?8l9xmHG22FVCQr~@^o3cvC}{J3cN zixwz3#u=g$DmDmC>VQjdc$&!P(Lx#K^G3T>5$!54;gRFnpVI|BL%+8!mEaX6?D&WdTmy3mRYFxyS72hCMf5IRhvksd^H}i0_1>Hx&?Be z^I}es&BY8%63A0;CV|S0QB9T^Po$>=+Z2|8@9W5%bDC3aP;Hu!JjHS)26@$9j13e+ z%28X@76D&q1!9P>Fi=r#)1H*P+^b)T?d!RfY3u++Qh*SpW_wZ#Fs^(+o&%VAQ7HHzSm!% zT~tq)U=W#|P}>-dw0{0dA`3=$V$HJW0jQcTh;cqm1(y*zW|Xdp6^zBC*p9JyNUX4$ zov$QWfq7UTDGHNllTJ2YhU+HhC~e>ZySllmSzdJmFSUlZyd6coEU!*$6x{+Yz1lBbPC9 z)wEV1jj7{^7Ia%aU#zH#>j#j7n3jV0ebffsBZkH-js`hP2R^D}P)};}h#wX%m@fts~!vWO`O%(kKuq+nVVURKngbjW3= zJLe>ZpmH3GG_cu-cpjDVq<(VZ<8UgXJ;dUdz>sK%_L-bQrf7pA8ZBec8_`Ku8z3N0 z7e*rrlG4c_>ZT2i2H_l+j&K82yna_5Vojg&aC6Blcvs^TFux`_ z(uA4jf}8{CfgXY|t78wP*!OXV!}SKJqnz}SDFT7;a>%n@g@E65G-%j1#xSZ8Mb<;I zRhuP1aXuIT-5boEP>b9KB~4Pa3MGWKI`69ptFd`=ooKJ}q8aFe+>NJH72;9liOiUNvK`myEp8=G(dYVde5 zu(=M%OD>%(^A}JV!`4)pxklFafFkB;5>g^PuRjI@?8Pp(+N9dVoOC>B-Y$xagR@SM zfSn97QSPJ!@Qzc|u#)<{tkrDKW@9;SFV%L3gBKvU(g~-XE-=81*+%TnBCQ5hnUz5q z`K0S4E3gA;y&*3%zT7DNE*YUCyX6hqpjZVJ8?|OY%qMBl%$t5tBlMz6nvDQvyW|+l zdT~6bYOA+5YYEB+0P(u(+H~cRSm&YC!3`iXbqJ7}MI&pOx&3sV!ej$iS95aRR3_8_qM^>{YrM^Zdi>j-Q<%yT$q)Rm8B zMX;mvVI0XgsCKC)uHI!DW?7Ae)f_-ohfMo9Y+ETy*Ik2~rC+NJ;IPvHg{TlH>HyVp zbF=o`r zpP9Lqck{K_F=l}I05N+8ig++3s|8isaz;4K_;4ioki&VyNgOdF10+*bcnr#XK;~km zg|l1$mGqP()iDJTS=68ag;;8TGgTNdZ&ws+w4kt_fx$eMVF}Zk;JDHe39S#>_#9?1 zSzMRHse=FmBEqqh`Ktw3!RgHDw^yy4wQ(7@Xh|sR^|ZUAD!~;{WFFesBo>B>m?025 z)1@9&82Fqv$DsOhto8X-J$v1_UY;0AVM1SV>z>jOvt~1`5w{PZXw&Gh@N_oYFrY4P zW5casP+^^1XxFM|yQ#MdZWUzdq=RdiZZHHoQ1vj?S6B&xDMD)wCbN(fpoJ#L6KpAGd~7JWXPwuh5ZD&d2sIaHbo*DZAps#Ja9 zKI$1E#3?3R6{R(u8 z7KOE(f{j3Tm8F_?_>dCE8$PFHzKwdGtoa@#TljQRV-D-9EWFG&>;~>zm28y@9h+m| z3mJ?L1m+F7J({)Jgol`YeBuuYBZFDos!)cSQkyzFuz>p}Hf|3j2+}BSs8XZ@&5TlX zae%LzNyu~}2p2O!TLBJI?_SMccX0!5FAFqf&6X%nOQ*4(*+QPpBODfcofT}m09IOt zlR+So>Z;9F+Yz!nP^H#}8fa`4X-aDjC8E_4CQK2JngKlTVRnOD88VyUI@|^lA?mD^ z*x?26OneAbxFI#0gN}XZ572!QV!8E;KDSuoq1h{`O@`0Tb zeu8M=1T=6pT%61d@PoJ=z@CqFClz%uB?s6*=SJX{fMQ4vXjLyelrf+2CIX8*gcKop#z|CzixVayW9RHQ$zH;sxt~=?t&1Zjf`9FU4O-+Zn{=l1_Jnl!MolpLecgXx5r#*k^_Frwk z>xJY>=U=wpb>9`+FL|!o+;^t)AJ1OC{lh=54qiU?jpx_1BaS`#lEa?C|GIzG0c`(@ z)pJJ@yIpe3t#53+eDD(GU;q5^k9X{R*XjFS`p3tA_G#_;>z*5(S{^jK>EGUd=le#f zcG?*q`uF9_(EnTe#>;x{zvxt(9Zw# z(m#J3a-jCFU)<|V@t?VG>-{QuSZ#cO|i=tmj+#>0<( zZtM1Q_urp-&B1#;bkwsSyyeT>*4>Z#$p~iHr7s-xO(AM#_biOB`zQYB%%_E6>zKzr_S(hlh*v!N{GWUGr@kJtZJ#%6 z89sU29rtoK?D8?|Kd;l6R>@y-*E{Pf9NzP#M^D~Fx;)z`ia14ZON-FoW&A3Ryy>zb{d z%biaj_pVo<|LcSscESGJ{2qGoAwL{uPd(#3{N&T+btnDyox5%O);I3o|Bsh#JMt@6 z6W8s2^dI->yhc6sfhX@d^}u88lRvTb5A4}5J+^<*Ug#F>>|Z_c@JSz?zSBSW%=hnk z@jY*Q&*_>l+G*csMjz~a-8u6>udjacbFcc8Kiu`5S3LTm|1zH!*YLKT$+s*{ICr0SZu!gurygQxOcdz%BFZk)#XJ0y(KT+Q0ZSUI`J^YaicOpLUo$8{`o`Gne`1W(37+rKL`<)kN z_&>EDKj!zN^M9<4eZ_~5@g;-ibpir?zjoxJDeNOG7-m%Z1^Z)g_w;%Mtul`~8*`r4ld%n0rAN|=I z|D{D0*NyxS#jm{fyVA`&qn~xI{q?2iDK~9jxyL?m-CpN>a&pg$_cg{`E?fo%HNi_J@jtuR8uk4{%7l^S|7E)aTx~?XOz-_IEt+ zG@D$S-VX2R;g__ReC)Je-gd_&VeKjonZGH%>bWoc?28XRcw6?wBfs5xNpTiceC?;3 z9ozK#tCzoa@$)~tcJcz)>wA1>-wzFcaoOh&TE!o|>-2Aa{M;kYz3hg{z8m_}e!1Xl z=!@RxfHyTRcy)T%Q3qv*-FisRdG@iV!YitWzdEljTj%%u`z67PF6s>|xc9sE`NA3Y zj(#Bfz2UuQ+s~c%h|UrI8TP*C9P^fgIr`YMwtn)OL;rTl9(%?!?1kHYwa4L) z|I^m_;Mx4w`+EB0KX}#Q*WUZ;)}?2hc+RuuGq->FlibheyPfmYodxu#<+wlsK5&tL z{h}SV`i9$f{{9Cp@NRzo?GN93(LZe4{NA|j(eti6^YG7n z=d@S6Z{PpC?qyGI`Du5{)<@s7FZGS(4p;ex9{|rue(j4z=f%lnK3cv8z5H*!dh)&R zJ?xau?yoxqc5dQMz2}_yz1qFkKmXX}wR1Y9b=5Wd9kBh#J=b?7pM34^|8ZFVjW_On z`9qi9Jo@pMg%|d{YWv$y`do1M$zb#De75tzMPDC@{KNel?|p-Gm%>_)&WH)@^TV z=c7BJRM^7dQ5`OCfkVdn$)eQdH#y`XdC{U^QoH-D8L ziGp6;fBiRZ-GPGt_;RrDGyJJ`dc%F^y#JIRf1Ccq@1DNrT=v{UzVn4A?)lm0gBhc!#sS){Lv%szWGxVs z{pRS`Ty)-#<-@i=P*#fr&;G>G*~K5b>Y-o#_699F`D-UWc>NQbJ>Rsr{=naTeA|W6 z&5vJrx$iv9c{}X+uG;Q?{iE?<`?imsw%6+}WG{K!=O1|Viq|xYTMoQp`#ne8|C>`k z^WCSPdEaw?c=qvY(8>2-_qq$N*gSH|o8SDx?2#|udET3r??3gzZ``|$Ica$IgHN2i zysWyr`1bSXbaub_OAlRidvIb@{P%K32`~I8vUc7tT)rVg5nQfQ+_N!MPdhr)N{h6M~{_*?bw{ZT-x7~F8O`p`B z{rG9oF7G)0&SS3pRhhD|g$DF=pzrXpce8E14pMSx&3nsTe^jBxTaE0<~N-t-MQLrueV~4-+sa8uD|L1TlRd#>bU#2?|ti&J@KEm z?s@HxM+clcy6*3r$w<8Jxc49Pw$9V%eBFQHbN;=*`^LHK8N~bl_U7@v<7c*?*}eCy z{dXUH;o{-Rdu!@$ov)vG;P~o~REPaDf6B#w7=-uyv3utJ(jj{t`|zF*zoQy{FZSXBAf4}7$I9agD`(sx7ySOQKT`W_pK-r`;z<$Rb@KE} zZ$sXA%qQ_*-2U8_=-2)e_UYA2&fe=ik3Ra9`%ZY~{Wlc$HK)DkZ|kk`^Y6ar2g2^( z``BsggP$R5h&biP8}Xo%G-_7jm~sEG?RUyaf8d{G?gNRs$9@jUzkIk#pa0{Q z&$rAAKKpEZ=6m$ZaN+1{d6a--@M?dM-NsnIrNIX4!{Px{^5>`A9oET z`}p5o)%ptJ-lHA<>z7K0@E5=3P4nBYMxS{8xX<14_4~LJwjMtI_T#VI^`VdB{8t`2 z?GKN>_nU9}#eT+nu6gQ_dk+1>>p%Z@X9dp^yFB*!FYo&EkDqnhrB7Zxy6_$$xWKse z71!wto1^ZC``0D>QAtH#~m!D_(WqG1tEE{Pt@a7rawCe9O+i zdFU%&`)62t;V}K79UkXZ0P^1QfxrFE8{;p&Vvl{E8@;oWJ^lB8|FXkQRz9iz@Vn=| z^|oK`{kHGie9`!+hkp8`cI$_?m~?*I4Ntu5%?I3n=cQ-ea1mcEU;U|jkG|{N;zwt` zcb8wGm%sl6{3U1q=jpF|;Ebb!H_o4U<5%{{zWn;*2fOWl%P&t{y!WKz?PD&yX#L4= zAA}s({@}BpJ>inKKmXj-%-L6`51sMCC$4!3dg<+#ocpuY9Uoj@f86trZL`07`cuS> zPw$MrSKar4Z(XzN`S1D3Z}0ocJD+;~#Lj-J*S_ZcyX|#FW?d18{C)E89{BegPk+n9 zf6ct|p({TZe)FaLOAg=p``iV|v-ydSJ$mPPm(Qk7c-B6ToV8<*ervxE4bA=D^@eTb zQM(|YecLVUq;&-Kwqw6{{+o7vQ-wu$?`@qK?e(!geDjoFzx}NbdzYe*?790*lXqTo z#((UA9`@K*@3UGz4zGF)nBMx{Gnl`=`*+d1-i7`C#OqFGj{nvx#1pn(d*p>bHBQ{? zie8mhAKZ1PL$5q?eA+kOdck3D|LeEk_t+j^IEH!iD;GOIc*N*^+pEL>@H=<^J?Wc{ zJLvR-PkE|ymU6*;@X^nmaruWXCT?^tI(S>$y7pEiyM7P;pMLiFcmM0IiDKJX`RyCC`OQP*}~@|z=nbM&h}ef@WSLKMG#p1$OdPkesc@-EK)@dvg( zB!HAM;{@}UEH~;>d z+i&PT@$^rwyDWd;f79`nVNrE&yzmTNBPlT;Atg!*LpMl>v`UDC^nd~)-7QLoNDUw@ zNJvX}rz0gPN=Uc#S)8jJ*lQ?GvZR_AH8@K*R7poY*Z;q{7^h&unmYiG2fDHY#PI>P;N0 z<_&%3W9f%&Z|s%AQ(VdaqKRjZ0W^F6O@eopr$GvVx;PGnOPfa%Rc&)bY_M1lJ=Gd9 zC50{81Q$IjoiOOh>$*(kc#dcD44TQ}7cTzt@VCohrTzCh6KdY?w*)z0F?>gU`Q1K$ z>(Sk-q#xR4Ykf!O8k7+LRJDspB-ys zdhlmzuRqy2Mcd_fZPT9VNBp1l?VLhry9pF_+|5oOLvDsu(|w<_7pxX@9}eL!-bt;u zrwA?N(qxQY+*SYH1WNE9oy*HJCayh2###IUUsKJ3H9^M)5_++x3JWU63+~9;rshi} z93+P6Y>Jake5OCE_Wf{ilp7?cetz~eyo9`yu;9eZ{H@=Mr!q`W;T@AM+v>4T$CjU) zO$|MJ;PfA=)-D2F5B=L#?=J&q{z&zjQp?$~^Ul@J5+R9?UG@|IL&CT>G5s;eq9Xnu z;Bf^z^x^5V`hfp-#T$bSng((r+W{~Ck&2=3&y}7_{>O|*^T3ZQRqbg05>aM0@MHP7 zVU7Q2sfr2!plmr))#WJwy&LI(EAbA#JN)*K;WIzRAihT@o6CPM_UB99Pz2A{<{&1kN>W~hEB9y`nPK#M70-cUqj*y zlKveCIquA*H=uH{mZl>A9U6fWW*vBfcoJQhtqk~6;Qu{i7@UmLx2gC4ewB^6ieOY9 za`xZJSp2&Rp~sue|1nYkjJ`JuWh2vEZ~WcVA1VLV(ouEY^5X9eF*DvFTUD#@*k9h; zs^9KwJf6E#+I0GH;JpB=A=-T*0RLyILlY<_zLP75SLgeh$x>d`=psEn!_$TB4<^1R zxee!g{d?`CGCezs?Z3V|G$)eEobz{`kM)l)fO^up+9WA{be!l(7sLyzo*G}F&# znQr)<{G##rU6}u&I5k@8=sgLeq&~uNdUvUt-Ro$hZ8}_~=<%nNp&FSR=FU<|7Tm7( zGmn@@_Qk4|t+Xh=3z{B_{Ns28y38X^5CH5E?IiTA$}R<9BtzVj_YjKHndfiQ|1Lj*BzB z-F(G+JmVaF86HW^jcx$Q_~rhx`r7!XCnK}x02=>_lGxhu@CLaz`;zX=dllGAl~@6& z;c_X_pp;1zw7&VjcPcn*c_d5WvuP{V+Em5L^WU43b zSpZwfhEGE%=H7oR(o;(neoiI2)35+LJzXz7tXTV+-`^5|{VQ7LGUh?@-QI2{KW1n=5O$A~B|SdF{|r^}i{H^JDW2H-))mdfx4%62 zb={-JZO%ivE0Ug*OE)he1z~r4#KQ~ed$uX!u~{|o>YR4=hWM)(*Ujm*+#Ptt4T;BN zIjXFKDTsKvAUr};P%Nu*-{r;Gqa;@4s9Vf~88Rk!t%tZ*hBK1h@jM~&>GsFJeRi;x zZEinPTWBstF2^z106FG0ELtSXbM>IG)#wCQuULcRD?=#f>>VTvuBk|I}Wx zMT)Fdy1KmhRlnU7k1o_LYK<;`JxWpxj`1GK=g0sTAA%o*upP^ZV^P2pb6oHbBwBQ! z{c_FQbaIT3qHo#)*)25ahUa zV=M#e44(UMPR>#e1#6S#*`CUf+a>ohMmBzQzJ(ihiu!*@GWJw;S@4ed;d^mvTRW>j zD#gZQSQ+!MP^ZvrxH%wzkdmV(S1svhFJ}f-16;4v_*=#&g9;^??Xldq#)9Cuhyo!L zgM>17o>Ui8-O`c;PYFAnpcPeHA%w*bMee87enNW)Xz)W>F5`yUN{4x4qU*PR>gI!M z{=R^)EXR~XvSexY)tgTkR@X+e!?5W2WhZIK@EFDmv=!unoH$kE6cMh=Z>uWJ+VOCi z44Dgds~7_+46Bf9hR`zq^_%zJ+){)hWQXV-8nSl8otGbYtbeMZdKO@2E%nl`65_jK zgC%d{x-lt`USm389@AXys*i=~X#o!^VgIS!%&&0IeQcj4JQLl+tGAmdArfqPZB2}W zplzl7RC%~QQRMVmK)+aDAOs4>6T@3C)XhhaGe|ai~cPZKgc7)~*tiAEmVqYDLkDVgWd#=n+r3 zD}MrAWr19z+14zU9L$S* zvPZ*t&UiRoLQlcVeSJ%af_$M@B}2N=QviYm4;5s-=l(vQJiNTeiB$TJ=_Fz&YQbQ! zcJq5pKWBzFg{?Z_b=I_=itUzk5j2D~I4oVt>v5z(TOWj9zBr0e3jXc^gb&Bz^oAzv zi@o^eKHd_&`3)_i zYTP|EL|8)}>$G#`N9TSnWy-6q8G{uZP1rtc0OE$y3UUkImDs_KS-kPR!a7xB?q zS~0=8Buy7#h^W|Ro6!$f1wRN0V-rctsmflK45zxbeQLA;f0^|<5j3!iz2R=tkV$-&s7WyJs&1?hv{-PYrv_(pplQwBwv3f_MaQ9hAx{@+`7oV%9eh^O!VWVXg({_4R00!DiTAtVcAsR!VNzrgGYipPS& zC(&)on`CWkqLc68*Wdj@X55kL9ibJWCQG1@2Kz-j+|bLJK;(dBOnPLngU7hj7LQ|8 zKANUg@|rfb=?D#Br>)!wH_MhGYo+&eC}`DH^n*&vzKvlw4V1duu-UC9_pTDuW8-5z zoWPXFpA2npLRtcMDcgjcekdM(iBW7x#;)w>=?ZFX+|gOwe0hW(acj6`(|NvNn;m`G zR;%(u_F2%UCpE~P>kHw>tpRWfoU$<7o?Mdy+)bY~oES%#EP>P%c5qm@7+VCalfKQg*^K-t{%22w_ z$A?@Y0?c8%P#(8gmn3jGg#=X=+_EM4*1T}v$j!Ljhk)j} zi1UpYmojZjZs17sXRRMVJoW7>hYC zqsz(Ptilke{a@)95mkhW{4#9m3*MC-y4bJ&Jc%xLgS;+>zGNU}#(E5c3u$R_E(TE^ z^}su_m+Kho@U%!51eGm(moCW-qP4H+U+6{jV>r#PsfwomOrnkgtkIL)aB{){Q!37m zWdl82+Ll@ldIKYS2%&MsuCV`3`Ia`bc(c%~sp9A15FgS-gnV0?P@DG6yoq}RAvc90wb+sG%ansI z_{zUc(%|1xZaF0Xj#rxXg`bbrA6EsV=I2oc2-}1k~kIm0XXs5>G+^Ha?Pv3Z8mY7^cuj zK1PXc10eO%tvOYnxR<~B3f^PeYnkLb_o7@PCd$45nI zT2A&|z({@#No=EU#(^q!tzLpFm9W*Y+CCXm^$m?E3!qm1@Q*{-LJ#e_ZHD96-(vYU zclmIQ6L`BT492i1RPwVj%M#GxQs2;2uXo*~BJw=m`qUyDnMT2Wf0fps;S!dXtDgF} zTQ1QpGgLkkLeY7X%S!bR&7+@n#>@rKXLl`nGLQRG5Jl7`I1#rfdjD`4zftmsm)$!O z>@q2O%p=7(g4J;=PxW;wC;HF29+i6YQw)1HD)yI)e9PJW<*&8p&$Ymd!GgR`zdV#8 zfM69y2hc^h4~MpbVyjx`zWd>lb{Gdme*23#x)h+`ciaXaG9uxK`$t=|MTtwSUw6q>Cp$vX;-^Wo?Wdm)LOkM`!Mnnis$24C`LzVv#&Q{QXUwF*7u#+Nkbj zNUoc4lXu3iI^w05W1EYQpJukWfT(?$Gthtmcy%My|mB&+Z+# zO1%>0kI-NL(9Eaa5;cnx5zN>uEvwt<`g_NH)Um`?Ilswhl z9^RO$s4`(Ax@A~da73B;((qSbBBBsNwg-4lf2Hl$gY4OQw>!m9MDWmJRjZl;tI;)w zA(WIC6*B6EM4p)g3Pv#9;8F3jKS>ixtn%S$t)pCPbkixlOxE**FyF7M|GSMUTyqg1 zS_IJQ0*KU=bL~<|oJ-S%@DfL2?62Cvd|kBCr2wO2^<;1IJK%Z)=x$0WAIb?W#b>0J zZ~Ef4U9z)KIT;Awiq;F}7n8i_AG}o9YWJ%9hMNt|+8tA@S5U^c)I4Jul)PbK_yvGy zg|{iXPkqG-$sivRwi#ib)$A~4dgFto5s-;z^Fc=As1m%9>lad4T_(-;?4Vl9o`bYX zSBSH{)>4~lId3x7t|DlYBOGJ%NqO;Y$@dT36(*UMWa8!p2C)C z)*cEyMwgioh_XB+<%1Ct5KOi2FAeJ|5LrvAZxl||Ip-(besrHh6Xi{hd9-aRURYxm zX{3c&WQE25y-3i%v$S(wa#X&FJPB4!1RX*tv&-a2(4l}uF(Lje{qJ@lv+g2JI zAYY*{`n;;=Ha@2Zv8wSLs+hL?Roa;GbIj;Yb=gE1i4~?X3d9F9$K;2yLET>uWytUW znWs#isHM&K{j0Sxu9=0#ED!l>r&z`thg^?~-+Q(bh_pK|8RU2AHOr^ENPGv!`Xdm? zeY|PxL2w$4H!i(YuQ@?;3>J^WZW6lb;m5Q z?kx2;plK=4r>FnT3&_qqYS|pN25YRZrmz@3_IA>Gli<5qU7r8Isaf*rhs+3uY1O;d z5Ark8rQGB^kC^VL>Ai@ZA2LaZpc}j2XqcFzx6<|UcsBgt{os>h)$N+@-b;sT{g|Lr z^s=|&=`oTe@pi&%;pfd4m$jI1&%x&0gHsm=>gUJh#N8;&f^3=o>2@gw8*^UU*Eu_# zZQRa}H}ILfwFHAKhfz|uc{y`j^O!lOM$+I2plj4yJzv^>E%fDKM?D z{KnQu-OX@*RM4PbnDEm>=&k+CXJyw-DdulQ35h3yp?xRBNo>w2nxBg#wmG`>r+Yx} z>XTs2>npV$?vI`?iNV*EBI6OHCBUfrEOnR8 zj+uPwW7p!R=~$colLSXz{PD9^#z#YF(FL~S8}l@@cnIygkNz4Rui5{$^1>%(HHd=n zO*)l@FS^v}&R&Svo*O=T#NIHxCxcQ5$h8Z@yZh%;wb^eegJr~& z-vWM}lWS^3vZ(U(EBI|G@kUnFDwQAKR$=q%;yE0tbmo6Sf%Fb(F zKNT`oY!^BF3S-UBk)Qey_aorUAvHN6x$h%Be(4CBPL2J^c$nqZ0ZW{q7l+i=lEEFS zHyWtZdoL}9Z-I+HUi}c6A!!2K%p4b{IU57zFGqCOmkY&SZYbMMUEY{#TDMb;7Z35~ z|4=lCF9ocyTdG^C+@;?Nxp`6>xPgN=x_)xT9l*z_M>3zuQE5wXkh>;3n57VA(He+L z1VcRsV#D6FU8yY(Z3CM>&Y^x^0v9XL{t_mfhV3hLwb7P=p-nXcet1il|U02~b?eD%3J>)1r0YKUM^{HlV%uop3mdtM!D0#Y? zJuNeI0VG&<^DbcYYq1=jE)>=Q>80|;tYPDQcdO~@=S7GYfxGA(iq%1p`Gn55H2w2_ zSD#WG2kW=Ks2O{%v3vXo=M3&3Xwk2>pRxb~DX=!(ke^bWmbz5I!mHkMGONaFX=+B6 z`i4})H|#Mlb^Kr1c2*A~+XmoxUZs0A#WFfX#==tF)J|U&<{Gpo<(#Y|er8n`cFbFA z{4sdjg`l#xnZF^;f>?J;WSF|!J2z~lGC1+2ui@VMFLc)R-{DTvf$a1-T}4kVWJ}+T zeKAn?VB3DX2M8mVBJ^(Ved;)nFd%kQV(c^4E_qtd0`ei+d>X)n&pqnDZn>Nw_u2O= zFPBMfB1ms&8<(2gTU_41VbUA$)ETYcgKAEp;yHhRustOo8kxpxC%mCmu=f2^A(iJB zRGN&R>hd7%M@MBQO<_`z@*}PV)+s^w z3+twT08kElfiQg?iJU0m0XS&f9Hb7NLSjIFJ7pLFQm;jOC`>2!exhTRRZk4dT>xw9 z&bI0i7DJRs4U{C;$^J?b01|dR-#fx7EkV2a?7X6ZOVFSVM8t$5z0&&tNrjL+hp2>I zyAdpp`kJpfft4CUOfx=mSBQ|xxBAtZ4p8J%A-)Y3St>R_#dVnpPH>v7vYSBG8UX=^ z%8vRn zIXl7CzHo!e_e{jqHfE@{Px^wV#`-dn#n7vTxfKOw)XMF zE3b+yMz7U+^SFE!^+QOb(I=z#jQ$fFxOO>*sR}vj`+7e&=dL_6Y%ZnWUKnV+mja2m z=W`br!4sPTI3ls&al1WW(RWZ6&wcPyTr2yXA!_Ds^AI7G3LFZr4 z`3rpo0Pm9Fa%VSmWB9D;BI@Hb8kL~_- z#-wq-ME=`#B+BDU8P+xa#MP4egPEdEdWTmsS1&cB5R`cXdfOx|oi5lu z)MtWej$WX5P0yU2jdk?vlp0I*#)@TC`4pZ}7HFKyK%c4g(|aKKLzr@D##+QcDIdZ2#UH z5NaX>q!*i1GSk=;KB5g+6P>hot^8n<&l%g(FMgDHBOK}}Kxjillw`?_X(SOg=sb0L zSS&UY<+UY-0n(_Ib0*pjXT`v!GXYFj>&OU0&IoXAa6(Nn z9(NM2$v5?L3r;Ud2iM)hsX@SzzU#K9c4M)x_l=t8{|YOmR-G2&LRb`?&<6=YTgqzY zM_MUlj8A?YeFo;{2}q!Uu=Kpe^31or$HU8JbYE52v<{N-zL17ph@u9W(C%KyYVRh^ z`+7(Yh0~gN{5a09O`<3`=R;UQ;gfwa+_eAYDC(c~QT1N8!XvrRY9HNFd-o7N?xjso z$J(*gl9eqj*Kv0;n>rB_W&LIOEc<~n7ja)=%Q^b~d=P5Z8)qxC{AD1I+@f83M0 zmVE_wBzE5SOkLp%MsuMi5B-*}$#fXC5ZMYsAdIGAp~|=gSp>IC<$4Uxjy4Y~G}6V_ z#AIPv$PE`Rt<09^^7s|`pzF7uTwS z#E{5f*VSQXX4ljB!2IByk09@Nzw>1$di{sc_VCBYycZdYP)wK-=_3AdRA#Gj>$eA& zPF|C@^Umvs9!&|J`occd%8gvG-%ZS4yN4v>3=}mEL@Q?BTOjGv<{?zzw3u^ll0>j} z-__v{y)$BF{cLH`N~XOXOJ!qTTCE~jJ2kYdw6kBNH)Ni#pEY@`cm1&F!fUopn=?+uCxf~2%Go#Lk5-06+SFcfq@uu+6*SU)Y zN;)C$H(RZ16ODBobdE=(F+Vdc!`v+X3!cDT$D1BKg+1TT4=Np=k*FZdw+1v|u&R_# zT|RTCk}MF|qg03dWqKX;W{&0s6-+p#SaWbm$_<)uWC3Bq#Q-I8m6H(HpW3>al#!;( zd3~H`mR|8Q^h1MWuj*B4~i-WE0inR1}Gb$yJSL9!o(=WIid`CI$FdR*WiXUvDBpeh3 zono~-SxJm1R~b%ns76`9vI+76VG8T7|M4k*F2_`?Ea{BwCmL#N46{Vv4>5X_90t%& zzY06eT{GB~u0%~vfy-h--6*2qQ}3u32pICi6SH~@Jz={A+Jb!QmKKORP#`Dkb-@}P z@fBkqv~?H%jhDn|Q4t)TFwBb6p%rV|Tzx>XQqlTLKxhAd2q+BsV{7^|3d1#tG4b)| zIy0BKbknPUu_K_eCI96pW~(fv+zPQk^l~D?Dks$UqdU}~-YNflw>x9cyEBe=vz%aR zmT~apwY{OhXq8XIog0GSVtH6TwmNnIJ^7p0ahp+X6|n}K76YsZ(MY(%dEHW!UqwLEZWsOCXC1EzRMp7!b#j$m2bEW? zT+8lI5gd3&ZEC>L9Y-V`@n^a-V;-Vi@htZ|X_cch-uamL-oX&MLLH8zw%p%p<(y1O zq@ix%BZ#Zh_3g5QujJwa6!`RLMR_5neDG%HS!VJLesNhxBCW^hM4nGS%+pBs{0<8W zi81w}+c^CA_|wM_*|*p4P;cZqNbo*X5Z4ibEwYWN==M~Az9479-mo1GV4#gU z;_JxE({(-`VYof93$M5BQV|mfHlROzhG2131l+6?_dF;dVGz|4wx47M6;`*0<%Vdd z#R=v8>}7JVHek?PU+WLXM__Ocz?=Ob=22?fC6(Gdd~=piLO|&{=FUflf}I8bhBs*D z{m_35_LPzq@4k|ipp&pg88y7RXDIApfOllee%36;O%=5ZT!n{#ej;;-mgOniLw$MRGQ zk8`77q{tH8LU}^fC%dCJv=>;a1f7Ij=CtAxMTQ7V5;2Auw`BP zNz;3yT1SIs^f));l5>dYzM$Q2<~0DN&iB?G#_~???740~hMqP1O!(T)c>15apX#lR zzp*?j>?o#}@-r(>@&F+mt4$??Y2el@+PJVCPp(54I6Bjw`& zWlRJzs0pkTgh=`TzDLXEgu?D|*lvSKBkCHEmB`Ht!%O2A@~L7`2(@7uA)&k5Q)bp) zS-{?T3j|Awo4YZAkhWxu%|*SK^M}1l(&48VBlgJGn68nWWnvdgT21%vGu@M{Fh-rA zZ(QfS<+SZ4y=;5omAx!w-t-~`(Kk&|;dV{Ac&9i-#X$4_7{s1HjSbF2w z<3af4HghI1!luBvy{_q1o-pY>rNW>fJaejuXA(RqJ=<+lX)XW3t@*R6^EFzk9!9+b{?Z)^@>NnID>dLzf80Q@Z=1 zjQ4DJCP%e(OXsm$g!3DfD4&{C65742fwUS!X%mTiktZ`DCXdap28B!SPmP6O29|W1 z?%yeVl>MQ>xcN=n;EF_39CrP3&&4r&y#2|?`vKl!xemuxW7+exxQV*+yh(sqtAGsk zE#^d?M~ax)nx_&%5B*hRcj>sU9%!#kX9WzT)EH*1^$*J=X81|v-xI|LV;0x@s1s2a z-5>%qK?Oheow6>yrB^x^Lmo8UU!8vTD_awUO97V~fjX$H7;h6BzjN-M=s#Q+VfVU3 z#_cXv61nv2Jx?U%7>X@iI=$cS$%m{Rud)-#(M#gMq(3V`ZX@YV-vC$8iy-(ycv~jb zfj5wF0C#)iKhfy4^bTEkQvA^Oh|6QKF5l-`cXCEt=boMR@TCGrul4t)7zMB8lg42? zm)mN91@`9l>$ymRn6Hi~4u3!ju9|SL1e26R^VW}VzfmQ002t8#$)4>`h7 zGei25(({Yc!(5m3aWj#_;1s~udch0zt72F>9`NmtvG)r|$O3oYXh*YzIh~9@aVV6- z=T5w(Eq|qvD*VZqDQJ!f?dVM6MsiOQp_at^h!jtWFGe;?twA&x<}~wXcj=qT1qf15 z<=wJhlZ7oD0=udYxDhUCO;N}Bcg3AFGY2Z5R8$3?zV>Hl?sf1e54i)wStl@`_~=dBUVR& zUe2Pxc!7`Q&$3Lx>{7YA)eVH8>tz1RKxj|}gOjgNw!s-8_y~r6c&=j+Hp0KGv|P{^ zLQG0J4Qd6LlqkqF-@`@t3qpu3uw?6;SH|ZN{%oK%y!_EYShwADMr8&kWCMbv+%G_vI!m5aMwjPSp}_1V+55aK5D~8Bp;QRH+(IP3^ha8iD*#| zGO#?lll0D<(>D$~EQ$cn12cCz6j=50FzM6p^uljt^}a{nstw|9n$vl(IeV@hSt;P6 z!1Uvo*XFdBtQoZQ8e@VEJ8@s5YCH}DEx-JH)11JQoyQ5cuD-lN>X~2$EIlPoNl|R` zn@=(wM{))s$@`x2+uhGl<7!M@T|{oq*0b>y86Ecx_eQ}d=f{Q|6r}m!M;OE=@M)9UA*S8R@Whpv=bm; z$XoaFmyWtEoS8w0xF2a+AzK!@sSh^>o)Ih31Ksy1&dcQBL6(l_* zZUCr>{9P6cl-ANLsibVNU}ldO-y6PyMMn2Fe^ZPiS-yYPO3R>0EGt)=CsVNK-0;+& zGxE^?-GJBW!P@mdJF?_hD?-e;4&<`Hf8z+@-o}f#>u|0yknDWs_8I`0il)u9Rm@=Z zDI#j;1_?4Sen23lrZ^?1>wJ-wvpr&wI@0bI8jQX?km9SfzAd7+-9701{qV|NYGx5!Auo; z9<3O&UUy&SGcLWDt$y)_%I|K*k%%s;Z%=mb%;M_EfCw?<@+ZOvqz#SZ9gc^Ni4hKs zf&vRJ&MSR4>60`GL{;Yq2{A)e#@@L>o^P8Zyk}N?z#KvrKfXQI+e$FUK};;OFTw4D~tJtAvmtkj_UZDnrB2SkYNU=;~B|TmuUI;7)qztBt z6zz7WI;?Cqf`^P%kVVO#ivFAqs2l{nZCb8v{k6O@-D*|V!;HA3BrXeG6&~=d%U5_R zf6^{Ag(M#b^9e+QBpm5?$gp)&*YC#st`nKewnRZG`Tu1BQXr3QAv7_>3=qoiH4aId z(kF`G4wV+(iFG^QV>OBtBgH`!(+#_{F+3{(^wnBM->rp*QK~@*m*|{6P<JNTYA^LH*%vR}eH9@BQrwLGJit zCE6@PVg(sX0&4I`7eK1p=X(>EU&cMF=ikKyvVmtdu*#5CPm9LkOfnbp1G*VTKAozy zj85>$3fY>1@Pg|#PpT>GAEE6}yfYF?&<{cn95_kYG&u(6X>*K&lZ?HUFjHRR4s$$@ zGWd8fb4gRgi zZ3HrHD!hi3Hk0a&QV2{Q5FRZw*M&{3_KrIi_~k`4f&BE$_(9YlE*2OYL9V*=T&BxS zF%xf?Bz1K+Vu26|G&AE2FE8QKASb`A8L>lY(}lewMhEhkRz?PsZe?KsVo0a^j{YD} z^`s0AqGNb{w`Tc`t%p&c7VU-FKG708tfZ6Okwh%64KRe%^k(pLcD;5osUyKRR=0xs>N}QZhh;>&5lr*URFILmJpeBB(^|;S9B1LZGd@56%qW<>T1ap8Qo)Ao zNShV^ePTr4xrF9zoO$fD;=A~Kj_##FL#SIsQzW$7zw9AgC2wymy==QXC4tufB%yM(W%N_L`Gc`o|XNt#f> zabW1n&9mQ64vlAAR?_1dWf8qs`Wl!SX~@0*{$P`~-3pVNo*ALoA`e*e`TO|2UK;e-mg%xgrm<=r6iXMTj#?((mA5c212 z?3IqFx&D4v>fi~c5D~a7!UXv{lwKTZKm=%eH|U^N{M8WFwoe3fOOa9;<(jPODMFst zCP;7)E!4+tf4WvV&hc3jVpvFYwt7FGW{o| zEOiE@Az{qtj6NnbM2}(kEtYJI2Yv&D1`^`&%zNPa{-C#5IM&WMq{_XM;1TNvti}A3 zyRdJKHvnI{0DN%)@b&Ee8o> zzVD=;B5fx=S6A8|y)l;7FEHDe@(PzuZq&J-$jt@@nBR=Juo5HKcy=cI8eXu8m~O*V zX?Fs1AH*89V_ys^JKo_mW3mK{`TXp3tb@6&tgR>YuH_p~V*bDjxk&3H!Er>_ZHIV) zYrSoXwKS<~0=MgU&GaB-I|1aH?zBoAEYE^tPV8uRX!C-nOlc`Dv1v`Uo(WN6g~_Q9 z&^k^3aZtrl6G8C}n3{On%*77sPF)jqO(}#(~AU1`zH>`tevzVMCYC>K5yzOVd zJX-O-JU{vEqNrB_cs%O+=L~4%2G_Gjaj!IaFN(>j7nmutkcwwolruS^S`{vX7PBJ` zgCKx{g^9Q6v-&Ax=B6q~r>1uAK{N5*@8aN!L=IMPkhN%Z-CgKO;Uas3QTLwQU(vD> zL1nDpn4_WzJ^OXJZ8^H9zUX>b_zV|(|KqAFq&wv3th0abaxxkG>*9fJj%pCn$&8k; zBpQIlQf>g;|pd0)3u6z-}a{e|3u@E}o6x_E+UTH-X{NdkVSJuD_Nf{Ad zd3DJQ3VLG(kn7>7RDHRg#BoM4DMMjwp4||CO{{Vh-%Z#|dZUw|l>9c8vA(gRUUfDD z?xcgF`_q2`P1wPU5O~|ILcR`T)_kqo#_+b^K>y6TwJ^R?A;=MwqGdHP^ly?)4HKAo z7ySQ9wG^*l%r^PIswx#2MGF-c|6h=%=--N++@2f!4Qz(|l~K6@K=cNx;6r-%y%-lt zp+4JdnBy#=nZ)SQb1Qjzx{t@*gXaa2ij!=G{e&{C zYV?QKmJ(?1WPT|PuVHfkazQIru zMy}pS`upupm|cZjY6^mOf$CY#Xg)?j>y791fyY~XG;DA$AIAnhYc4$RAiz2OW;7LH z?l$`RRQ2;z@WGJYIAqJ`(ezW^hJgH|2cTwDE)(KCckc#zS;tC;&)H^;;WiHTWQ8^Z zRiuiB?9!lj-h<@I*KFT@rXuX}E;Qb8Co?Kg^TH9D??s3#@8X@lt!Z&?aQ{KOjZwd- z;FfcRAqwSczeh$gfWL2Nc0d35WSQJ8$zCbdsx&^6CdY11pn!bZ4ZJoWw)BD2{RZUq z-yyKJ^UubANHmqfoYz4UdVkTHjW|<<-Ngn(NOMy63+)uMmxIJz@C%kq)D=PhMcW4dZ{_#wn=x3kFrl zMAMk%!Bjn%q5M;S;t0unC<`tTl~!i!Yu7hqTXT(1VBgE9QM2+jBWa(8+JrHS~k6lDXj z5iQVA3B1pxO9IS3hy`rZmV#q@kQ__^)^f;oj!s9DTF0yyo%bT^Gc-ZhH@V(;fI%!C ztlsmD=_)mtk?&Ars*vr=@9qKEUG0+~ben?-h6`n7vWH3>TNyd83_W_E)h4yXSsAfx zS4_JHWZ=hA`Z8d4@1d62WiPFgnNCX}qRmI3R^YrhG*ml!T-Fr4GOr{DI5S%iG(3hm zW>1TyT2enG&tUI>F+UqDpwNj>EGXqzA@uHBUk}p z3%`%@g0Po`w9D)3)%k5B5hmlbF{TUo;r|1I&lsnx>G$O7rd2yPs580o$USkPU7Z| zFN;NGk-a(JY$7GXsgb4?^TqSXRsZg!MwnS3?grkaxAr+-DCZPm^i{kFtn%b>G+3g43NvdKE_Ph z5uLBD6_bOA2NQ(1YjgHJlcZ0}U9vuL=M`#)NoP21@$Ney;B?iPwUH(?GcHJMd{Q4&Diy{2m&=pgNxt2s1Eej8r zuF}cwb>@R+wtaVD_J^VEhw{h+gIjxC2%rB@7ns1&S`EYIbZ6U%BNK0T0i#PLKDme6 z^CpcCAi6-|`DO=IJVDNBwd)i5u_oYeylYhp24Z#a;Dlf%Sn6ah(7?JKIsO+vJnR@IFUYlantp;o%Nr7N$EUMLO zMq?w;9p-c55z8pa_3~hm$CC6Y@WGPfNl1GO;ky4i#LS(Ve<6TyD^gA!+jQp|^sSKm z?vB6coUHXl882klG!t*ZMg9w|;1VkX2zp4KL3ae2&tELeLS)mHiIMu8?gPMs1Zm34 zu4`J^se<`wVG|>OMm{+Ag~|&pM9`1{OY^Hs|2FH~eMyr6`t{c?Z}BN^Kp#QIE1*X< zZ}f<^Z=-IGGh&*h!Gx>EpTGGL%UT~Dqg%-!B+QQ+_^<`VCr9*aiQnYZjB3xS+O#zg zX-~nZs6vgGzMq$-hDVIhSfyr>n2X%0FwG3DnZa=MP{~nuiD+`wd4ITk6oeU$$8*7c zj%R+YG`@M+_NRG^^NpkUgojxx{(gejk z0Z!Vn7QC|8ZXuUuuU`6W;|&a;q@GMJY|_?4ZY~<3LM8k==sgBK&Y^pMx0Vs^aXkVk@64LR(GeDRnccK1l-!=JfbTN0#fwZRM?v9m8+ugzm^Iu9iXCj511@PC>k%kI{!}!05g_%$JEkz`e0W;ZfjpJq8Z}6uj7&G1iR)as+ z^6QglGK3eFPZyjB@sKKH5PQg0M6w5aZ&1GQ+{I3spgcu@)lr7y4b1|xl0O%w%@odE zPAIPQi^y~-p$17v8AK<_QrcS%)~w)vBc|;!#kv%NcS#-N z68xRW3_E=;5L>vbi{xhWRE#42gerUJ(8gPHD7eYQVX+&l8bV0p0P38-U(c!Ho9k&Zdg% z6u|d0n(5HB=IQ!;m{1Su*1}O((|60L;nPL-|3ln&MK#q%QPK%L0fbNlLPr!rZ=n|{ zQX;6RbWo}k0S&!{9*Sb2cLfxwqKHTd5I`xSk)lXdiXa53g1~&yf97Fk)|$szi??5Y zFWrM6 zemz_KXNg&*^Scc^Q&*N4DQH#)8ERqId-7kO@Pg#fyrAIO$++_f=db9^VD|4HU>^;A zK0>x&Q3T#2iIIwI+TY&gMIy{Rxc|xqg|7VPbaLhKR~at=K^QKOulZLk*&7ZK=Lq39 zJAQtBe)NwhGsEd&FIyXqoaY-$|58j4v({JUn{085LBu0uqK5I;N`kVgPrJDyUNfip zh>(>bUTtnR0ar!V@&`^4`ADZr3F22LzuE|kyIQzi3HrgGb2P5DVHu-irGJJllK%4I z=+RRhp~G|k>>tm?jHCZ4DaJ2zAHR~8GK^vS5KgXMR-l>g+Sv;^cSKv~PgWwD#EZL+ z`#bcT92gyeNKAQE@q^@f|I^BR1c9ovG13`WvHHDQ=#A1iTZkY<|e9C}0WZydvVL5#K7QYA6%-Wc98IwgvL7^fn6e zZJ}cPVgfUd+jyOG?r=f)E~sxm6`qfae%sQ)78NbXERxbdDPK~ZPel%Vgg9RrZUo^0Tm(fx=INJ@018mZoezxEJaeRm&LX#!DK_dRr*_f6j>EH zrtLZ(9v$r+a1Nlsh$BD&b-+C6<1{F{B7gXZQQnmfbjcP^U3gNd+`(D+9FT(yoj#41 zFqp@X1or>PSQTNXDI+U9Kqjv*iKM3eR(%LieY@g~Lhz9SW>n>Ws?C`DCUQ!@8a5M6 zTi{#p(TPU)F=2mT3-a-87rcY>#hm%+6Y>52fdHw^nx9Ef6Ec`ReaeMeiF552bLw0; z&K;%1PyL)i7pRIpt%~RXF1Y^l1{oxNF`CAKSts#*1IX82pYz{sOWsrp`Q>)zar{Hk zsG~nuob&4CE^2)Ns;2>9HR8-fBA2jaRoOHui-)!>ZO%UWB#&KX<+*0~p<2Kk_WG|J zS;WT58zj}4fzT27&46Eu{kQd{lV z?(lR{0EMwSYuq%C3i$=`+ot69Vpl!TrAYAo+EVo}#{X1rbEi&kTwLcmlb7)(#3@sx z@I~mh*Bh=250=@YIe}>enF8yAlG_r@;F#h$CE@t$rr|U{H4;*JJtzUZ)Ol2^`67ucNS+|dm%^7+B6d5)1 zIIt8y0%}FZQx;F{UNy9CeK2Db#CSkXl)+vs{F&w^LURe*0EmP|@2iq2EA7RsbT*%WyL z&mG(yPwXp)W`Bfy1tB$Xvd~__A;~B1Ur=NR#ioJY^ChjGv2wdNp%-Kv+p1qKK9fpl zbZ4UTqF_ZqFs`J~_m!|bNyK>jzhft8L- zs7OF6M8_I6!>^DCJn!Fu9=UB)v^0KhNpRNbXoqeF;ZnpZ@C4A|vB47u;Q2XE+giQ3 zifw|msCc|D27m;mBv+zf)zykd4TCPEG36$a=6v7r;{S!8IB3lg({zHFSm!A)-v)X| zEk)P}A)nma_*PIz;zCe-{2IU^;85kj*I2!ykh_>F8!5H4*Rrir+KypqKX|np>zw!3voyHmN z1Q7q?1d~txGfe$+{$Ec9103cfWO|CQ{IHdh7CX6d#4t&hV$72FQV@)RtP#*5iL(1()d$pF8PA?T1PYhCqIM74!fkEEf9cSa>~VorXtSLju2g z_X+4R(wu#KhpK4nH>b|RK5*i~4O|PF7H4o6Pt5_6_QCW0Q)U&w2*|j0cpB!(h9X6; zxtB+^eFo&s=jD|B{-~?K1to~Byd9SfTW0F- zwLnRoLEy}z$aD=zRJNJ{`q;lLDnag^>6rr+krU8H$T+xfq1vl0daPO{x1lItp zh?EE>u^g3Z{r;61Mhg}dVm6gkHdS|j*p?bFm|w)Ei;9&}nsCDC|2*r7qKysF>V3=z zL@8BmU;m0-3;w-alGB#Rr`DJ59f5W_gJ3*blfxSW>*(h5GJeU@nmK!CAf32~54;Ol zgJ&X5Bjh>~iau3ewtiw$RT{W>GFE1J}8!qwC4`UxMwF;KMr7x#r<*!Vb2SSe^ zJNP|{6H;3naG>utn+o4Ff1@n59m2%6_srqVzP6P^55UPAi#gDAOlT$`9W9r|>z9Q#z;QXdKQ%kWzm%%-O>fd6Re2*$2jD;Vp zs05SxJWM0hYKB`ChJmL6Nl~u1nnSUhDS@k6^T)jAMmLALgHz$YZ?*Ztox9L^LR!{6 zDeE8m1?s^+qEJe0``;lw;l-|i&Z_2x7#(6X{qB({Q9pI1l7hiRT?p4%1bIaApzdE&Ap&?h1HQ@Lep#vWhiNst-q?xPt%rb~(V10_^E#an6$ z*TOzUaAKlq~Vn%k$n3f*Fnc}r3pR^ zbap2=D=iaVCbv;44bblPno%{Q;dudNaT3JL&(oLMZ5Jt|H!1BNgJPmKSu2Lusw<#F z7~0)B2RJ}*dzqv

        )Bl+7X?;Rr z{*(@+cH~4q)Dl^S_2>ajn!TtS0I(tI5em9tc>ok6b^A9uC`_1^K9#;?Cb&@jEs+TOOSD}d0PE%V1pG?S`83vP5#Y4)CFA5% z#s6QN-z{$*04>|yW8O@ONK27j|94_HnH#YpdINv@? zT|gZmW1Ls);^&W;Agn+9x3G|FF=YVT?mO)tf%W?&>1sHWUdR;AN#f_@{;p4I5jF^5}&I?`M)^3IoI++6sg?$nEyUFKVka6{t8#W*2(`<_5RH! z>E=vb@!c(EAuwgy7iP{cYF}6){`XC^gz}4bm@Qi!RR2A{C9z7{%Wo=YO+L zctV%tw~WM(=HIYOZ(T%vM}nO;`rQ3137Fd{V3o+5%K?Fnk!sf{*t-vMe8R4 z>GutRfzW(dHFH8~!T*1J{^=jjaCkNA7c)?o##dx0zS3-JAhiEe#at|;`n?3{_c_!4 zw?FzfqyO%`M*j)>uk^d<4=Y`>65ImC$4B z1IF*NCjX7<&qID_{mg0B`o)p|>XB{Bjrjj(iTdXkUkHGrLM^gs`&5410QLXAVDADq zmVRR*ZR!3J++TCh5kF8Jsz;)}m}}+>?Vo-Y5%6_T6QbY0CI9?5{&?3Q5VXH&k%Y72 z@{xHm5?1YKN_0v-@&6yMA3O8?p^LE=sg)0W{@F{ld|9<`LLL~?{5ZD%fA@6vAC>W|p!2`?%!1Gz{Cs?V@V_H%Ijcc?N!#Ep^!?cu z0{bwpxg87)_`n3pX?_TwZ()&@2CuKkNVRPQb}CwZfm3~j%dEU}>R134>< zznaI`!rAP9%)$rT`S~R%{IDcn44x#z2D75}q{!0VP_VbAA zSX#e{{g=|#FF0;_H2b3UVo~`TzrC7UzH&PouRl%`{}ReqmBSm=-|g#|9cH0ae$o21 zKe8D&*DRfQo-xeZ;e434QYK02>31e)Y@5y&65?{pH};KjyPB-%$UXDV2E;x5kd#^r)?$6w2RwQpELX?9C28BW~XrkF|t5 zryCJcL*=Uk)qi#WcMSfWvmy5DYx_eA2!yGM7vWctGVt zB9yPE?q#a{nOm8<>aSHlt5uV%#_;+WqOV$o>lgIpo{)B?A8l$xoZsb`YD^j+iD- z=I@W=v%{vyL80m+kRLsCJ|KCu8V1JblVPuh^7C`BKS8>F@WG}h z$&eWF^JOT$J0L3nnhoeJupbkV{G8~q2J~_}5;)Y5pKpNVN47rzPIl={?yRH!6+Zvk zOc@G0TMQuC(x#f{7selYod|>m#l1kY|%(CShc*d?J3)}bP z?~m&sv>Kvj^1ssQw$r@d=|9tKs7aebU4(iOxss zTb$QXIJ?)KIBlZm3rLXt`0;2dx4Byq8*@V3eq^2NbCDx*NmNgIz9`=Rn{lX2HAcRV z8TW;*pSZvA##zlc;&O?|wwh7-MfGXb>iYAaDF+4q8Q%Yp$c94P(9xv+JDUH-`9Jrj z&X82E54m?dg#W%ce)qM$x_`C9NP&NL6Uk@ao8e&mY8uL9 zqmX=-$UPzB$N+LKeVOL|!uVc{wYt7BWQ0IIwUK<@=->e7`t>4@7;2y5_(qQb!Jxlv zIC*uJu5UR=KA%+j!nKEkiQc-w{Qa?fem&?9X*Z0>DOfz2Er5%fCjXHa>{ub8Ti8#0LeDzO$%*EJ6AIQcq84a$o?FTojkj zUu+)SUmZc_*mURbFG2g8em&d>CQT-j?#MG|I0|ONf{AmCMt+cdS{*3mn!ZhA|E7t{=WW|El}=?!o$KG2$@TIl zSDa@phji4~r$YO(Z)LUWxZUwO*T{`w-t@T z;MJlDWPknj{P)d3>z~C87YJ=Mlx+T3pZ~sCzJkuI1;@{0h;NBCKOe_GK3K@Xc_tCa zR}?y5a9S%n=yI_?F?c$NpO5{w^IQ;&xFjX#GpKyUBl)^Gz!wrPj3y=<>3l3-Z>9vo z=p)9YZML|4UHIh+UrmM)gLUHa_3~E`*nE+ajU#FP2-}aR&ig_q<1ys-svn~Awd_(b z#Kkehw~*S8c>T+}cn020T2HJSSn=n4Vxn)NjXF9 zZ|vV$TKPeY*I07glg1Zuf0;%b&H!ni0wAE-*&`O`bzX`H0>#q$^?;o2=+&5GCGC}Lt_RZc*I*wa83RX*^iSxsq1HVP9jV7#N{VH{}jwP7fbA&+VSs) zR$za^n2ZUd@pX_1?YjaqJGj|&JV~&j_Ln89&s`fRhs})^lgPJ}{}P$LApU!K{VFIl zm60VE+Vc0eMEp;334osl3k3X^p#0V2%ph3YY7zOJ-GMcpxhMM{-zF%(+ekkGCVsFWIVl?XK=xZf*KBxs zYo}oSkR$u-a*!9SA2^$|>ln*lANx!U{s?mlqCi`^lKjd#$j`_2 zS^4P#F0N}TJNk%tes`OlD~!HAjih%xq`AMaK6BfQQtn%;%XRYK;r$2h!;*Wf>$x$a z{J+&JQ$4dNWa{eAyJdhbH`eC|(Vu0?^N;J#pX%1A`g&cf(?6POruP44&LZJbf7O5g z2is@HOG9DyTU&B|5M4h?(D@f<)aO5KT0c)6zj5T}1G3Mow%fot{i$mGL;H_o{tYs0 zfoVUDSgh~Q&&Tlv`7%3L8#seBe^2#SJmTB>gAZ(3y_6`=PT{}59@6gzuE-&@lQq$H zGSFOKsNa)3h>pz-Y^I(xHg*D@Xi(s|bK?Z_P>Hx3@I(Dg|e ze@kg!%3U6Dm;E_LT)$8G_<`$U`GQTmB+mExvIvA!M+H8U$?VpDA z`=5=~D#ySFb?Wzams)Vk`!-??EORvV|HAtB*Udd)-a9L@YuGxT54?YE;)fMreqjz- z6)>M4mm$8V7OVRUM$IE;b7*~F3DWNybnRfv#zo|FW2)bckbZaWv=+XeT1Be0hiL9E z?0*zp<_qx=tH{oB%C`*ZZ>4WADD$1jjN&f*e4JlRUKI%UFFTN+5nA;5k$(Q8jxU7% zTSIh*Q~w(4XV0HOkU7JN6wJLx`DTTDo2~PKXCqgV?3v z&Yw1QSPoAcFC?db&*1rRMSNc#xe^R6o0HJh1Nd=lpAQJO1f32`iM6U3KaT6iTBdlz z=iV;F=pof#C8$2e@NN*e&GaEUZ|d{&C5TT`_YfFv>Q5SL`Lh4%pAr=RxfGBMS!**$ zfIW?$;r(yL$JFQZ7>A{Qj%{ZZP8H zYO>#j+80QAKG)`#J6ZB1iUjXwO}cbSr`Ad1&$1$Mx^Uw@SDzv&z{CTH<_{ zZh6nSCx2rtw~yBFDYVZsc1rU5wQeX|VlK|_Y~yN`!L#>u`mg<(>2dFWw_!`Jo!8Vq z3-$AC8}yr+U3Vw@AAfRWKMcQep8HvSh279noKKffPtb3?mXI?k zbUxCr=1GS@?`#Iqjd7#$h4{P~vkT(3ClkL<;(R{6Qo_y3`o!LDD9-23g!kOs+Y*_5 zsyLro+jKeo5$#!%#ngU~ApdZo`uy3%*Wc=lUwZCq$u-O9%$9uo&GRXd2>Cpo;0^bW zhLRIIseZ-wLzT5ZoSPIu?ktq^-yiGO(;IAHQoJi^mq6`f%;$!0Zt%UAoDf5rKf?Pr zr4E*0IdqLc|Kj?P4@UkF*)M_=AEbO@{p+DVpU-qzm@xj1^l$b8XXvpofD|otrT-W4 zxq8@6&Mh&S-JBxM=UYEd_!t^O5);Dde8lIC183mI>;m#?1jBzH+<)3OIR|uC6_Rtw zl;2dOUvH@O<8Vi{e(1WJzrGQwKVPu>Jh!C!4r~7=SX93bnVAAp$DAcPBdPwx^&5{* zlyGMz{AIU%UZl~V!v1uvgPU-bKAqTsme+Z{asBz~d1b2gvwqYWzi7Lp8Fw$MD_f#( zLG2HTaQ&aVr&?vWydJ4*f7{-xt++d{d$Dq(Hj4k`7xUTB$_GB(jUrR#Z{WW#<}=sU z4-BI>kkGbt{~L~9G+bj1Lrc~Ytt!f2BC>B!s{7j<2w6w2XHoqsNAbJNgU-;tB#ijA z>(1XF$0r)jb%lYq!%4#8$^8G5qx}TD61QEl*?T+l%wfW(0zPV>Fp_ zF_NE;>j$^1_XqYI5-F&kkfZvgu19iVX230?`G!6n>qU2R#^6>+|2wR_K5_%)TKj2G9hxqVN9 z^NMTaS+Nea4W(}I!(EGDOzQ-n4saC&fp!T1=HUCGrf2d<&D=y4> zfRJyrzwLOS1(b9SCcUQ9{TC7xzjN*50)DpZ$uv_Z)qnD#H=&^*es*@04Hzs5C3#Y+ zfAx@kko?ROj0&R3_egQRCl{ezoGGaDLzvqXIBNX~)l zjr%0DU0443*gp2p@l8<(c={Vwhzf_XHG_AAj z<1c+Wj_ix6Ve0y!sHS!5?^oN~a4)-$U}cL&it6thzf8eke=srnLj4;YpR2cZ4X}qd zkqw2b`R{9j{I{KN+~IP0EIECa#wQYye(qFc1`n5qk@&wl{CvDWd3u~9_&7zAF)t~9 za#pBcXTFp}f1TaLBCZiXANz0e(XLQ5c{ADGS)9MuSv$B+r_Qj)$BFYtIx3-Ev)5!q z&UF6z2B<&t*T5iX*&v=YQfy)WlW)x5u$Dex=DStke`%xrJG!6pxg#Imvj+N20Yf`Y{m>^m$aVAKOf$IVErf^$~HeDmf8jyK85zf`Ii;k z-L$qc9b<9+()PYo?akLAW$XMk`ctT1dm2mfv(ERBwP_&ke?6^%EglS zG#X!!Bm3c}Y&FC<#S)7%H2+tE`0VLn525cilbBa@{lAFxYhX7g7%1DKt{-SfzdzES zJy)yuXJjRk$a|D;ynoWPsTITx+ek7!99iCeLh;?*mv?aOe<|7L%fu{ypTP`;n^+C}YyL}VZQnx(_lgbrXkssj1>GL#>`aXA1go+J?SY8oHI_08^W z(qV?OlvqY=*6=ITuWg-hj}Qf9fukns5Q}_3MahQDa-^O2Gg4XXV9ZzxTLqD)>_D5>gH(~ss_xK=~cqW;=38(c* zcz@SvHGiu=4rMLwQ~o4~Kad82S#~n{5t7E=KNjiNEx*!0I{Y;;D{s#8m5BJ-YE;QJ zzF;8xy;q#Cr6J9@v0YiVYwyP*#eHOXH zx84Vcbu(Ijf#a)#yVyd3%TAIon6BR$NI$m8UIXiX?eeNnlNH_SbrOtyK8+n;P7S9p`UpEMau<6F3X??;m$i0OTV z99&D|v)I0LTIKKIw;aZEE`nBTplI1Z+JYKZmY7@jXc@vVeoM}R!2AljoF^W!Cm z-|Gey+}_{4Wh2r@YUE28Umf286KA^6TJJ)+Z`6;9JHI6@N8M?!uzbV9C zMg4o6zY6={1*4B0sk8oO<9j)TbUZ1aQ4uKWgS!A&t55GnB-wl>iAlPe`wQ*UKN}L^(cjl(%D#G<`NIBY6|1^( zZX;H*`?P5OM}q3#a*Wz=y{DS8=O%>n*T?bKI7zi?S#v{D*Z%XY3P&)6!{pl}>};MvrF zH9+>~-Lvkn=Ik+2{gm=8NBP+mnLZG-JcB@S8~*ul{59^W2c*OtC$j6c{SAciDMelg z7=FtkdtGS$OM?9OocJXW^ice@yj2FIWd0`6 zJLvzDA^TGMX$Y7ao+Vl~lwTZwy4Nio3?BX<)g#3DEl}_Kd0CZ16dNhO*nc|ukiKzaJ*U7t?8dK#5EkU)rPI-|-?mi##Yd z1)|bY?&x z9J_v&Oln5gZ){&)`Mn69c1$2e_I509U$VmfF;fE_AUonH$+4pRNDx1>)%A(38#Q8k zOr-h~`!}as`oj0zQ)FBtnm?5x`!Xu(1hj~+$42E*`xg*@U$WKxQzj}&{%mpna%KT{ zxt^X(67H{AKZW_z@aj)8NK~dhD^KRDa_2z4PV@?o;3>*})0od@kwNlG`?H1>3i{HvTD$kKVajt$HIJ zTIc#-IJZ4#k#En&>N@i4zXbU|&o^1YI-xrJ#IzTO14e$Th00`v_Iz$`Nugvm?^urTHHT>GPzoHdg`b;{d3>I z_T0@eu4+DAD4!^Q8rr}N*uh811Enqh{c(Krf|m^#^*TwK@1*f1J;dkMD}K=D{(17f z$tr$6jxWi6t$-cN(upL$7e9{qoD&uZN3@HGVarkcxCE{5S3j! zAIJVx!reyP?(U1(pS$Ae`=R~yDQi5StV%(ew%)_fk3#XM5JfgbPioG-N`FK7M)l>f zYWp+lS7SCRu$kulh4$x`YvtVMZsY6pk8=N5K||wHr0iR)=J|y2(YEf*Ie&k9_DN$q z&G!-N*WPLB{zomOb?VpB<0~L;eipfD@5o>O0b2hTEK>VV{mzhK1D5mS28hqL%iO@Z zj3Y4%7xUvdf9mkX0v4XjBo@ni^5fXQnzJkbPW--1!gr3)%oncz%iF8t|F%k^|BS}p z@%le+g%wQC$tFt%iu2d4#uMH@D!ut0`(yvB&lywh z!HW~@oTpP|)IJjW{{vc|gMTKS*tD@3{Cquhe$LRBsn8}zmz`DBQ1g9-e3wefxyTk% zWIg_k(AY0R{o8qPbI$s*Gy6GvB|l$|@}~yo)vCpl$Jc4U-VJwx64&!&^u!RJpH#%J z$pd?6KOczwQ)_-a5%KG(wh#12oFlH*efV+A=kk^g@O3#yuHWy(k6R-BX<)qyo{v+K zmb;g*|9wBaKDQX;4o}HN;*?dX`Tj!w);{uupyV(=uzW!(7Wb2*?1;{pD#n}cN^<7VAQb-ds=pcf4?ZiPto@yaNNEno1rIeUq)Yk z$C>t?DJywG`N93)_HOyhRZKLOT{IA1zwNkc)dFq`Nq85i`M$#Z`=IHrp!5C;d7K%} z|6g1`^7o%JXkWifp3PswkK_1J#>bTq{Vre7f4~Uk*AFhRg`>fopuW@<`9CxL9l-x- z5jhy#nZG`cpG!ZuK_9bg&IKFP` z6$s;2-zQ_H(E45+zg+h_i5tGUnM`+$IA6M|Q*ifKCpKM^e>On*?^DwwA$I30!gwXK zR6h#ilU7@gL&r^R*sJbze?cO$58Vv1!FOU;cG9Ip{{P7lKaJZRhS9rPvG#s{dHW0d zCp$~tac2TeWYt>Y@yDjBX56*2e(adN;`JL2C#qGd2Q%yB=ZC&4K+{`-{l6wi|4h8* z4)uNRke_!w`2QzI`bV+b9-c0~OkPyf=6{9xm%gkWd^EU3$YokTkL^33i#Bk%Q4#sz z-*R6vAaAndH^6JbTjr$BNW^!c!UoAf#i z{Fyi8yKOrEd|1D2T#*TeWd`i!*$MRfAU^G;9R}l^cC4P2gdfNK$i@E)vB3yP3l}95Bzfi-&=Qx;Y+$cV*g{NdVQ!~dY_~p zcjdpI4Dq=dRzXmk>qKcVl^@6PoiXXFL0WiIkiWtC!Is5qVE49S;wtM-{|{O}`#88k z<@5XG+z}d|!}eX$RdXiMs zXr0lCHAxY-&$?V`&UJeg&K|r`Lit4eb-(wAGwbUtbINb8vEPLLh0TL1)zg!U>hzDF z?{a|U7w-|h1X_QI`Rnp|4Ro)5DA-?z`I}kp0v9emCVqz(@%*@=^|j*cYKZ%CmjoRg z&W{_R^;J*l01oB%h+m&B{5a0vB!{~|$JLKX8%vrW#QZH;Y7TSfUanI=?i%9(^Ity` z#MfXo9qWobm zmk{vT|DMcBOQ-q=?LRWlvWCJXH^>Y_4WB5#)9_>_=iuB&wzz$S=Kl)w-z_eL0qA@r z^3nsE=NGQuUUtAan~sqA*#>Cl3*(ci`Re+_MDBPssi#nx8R3>-*3hPEhmosh~a$=V#ul^UM8CejxD@C!RkXUo={61xxhr zkV%{S@Z)%W|I%SKd=7a;v>Q_Y1IHJS*Ixs^Q=gGB3ut^C+lQrl*FwuR<>bNnzZ(4} z^gr6PoC9ivNqh?B6R+RL>v_ZEk8enZaS=Zs5TB#e^+^*QpOUYo7ObN3f@f8jMB z$(Z`b`S~S?&sGO*Ve!a&WK51YpC5K*a=%v$kgd}b=X3GsTnI8B%D!6vOY?q0{xYf@ z!HaoH7FHyS^4ECIGtM$%nM}EEA~c!<~#f zKu*7yK))}lZ{MQsKjZoBE0LdSM4u0>&$FJ-h6a}kh{JBmAJ&i8x~>Ilk1BHU$5r}$ z5r1LMYrwwZCGjO;{Qa?iJXT#Fx23@ka_$Y)j}la0xh%~RCM~#6{Pu3pJio9$ZOptg z@G@g4J4Qm~5655rH4lO41>ecUo{9YY612WIY?KEcrlVM=p;Z1P5+R?qk6fT?&Ktr0 zHwp5e;~Sg>`}$+p^jP}*a-<)hOnk=K_OO&WZ5QYF-ncTZ^B4!&gnQ!r&hP$KHR!7u zsjEMkqsbo*VuEGo;>7i5Ttv0X&Sw>=ycDF7KcRm;^_DgKX!V?2ZRO7Yf9zlX9_S3` z;>w9hF4d2g$o{-FekC;BSW13Rr2HD7_5XbGAjd(_!!&}n( zqy23y6xI;-_ZeB*Xd?graQ%k8$4W3(loF$+^#56+{t*i<&Vt587m4;*%C7|FUydfP zg^L5elDx?@euDL<$>KHOfA*b#U+n+f+!F#bpZ+5O4^C+K7se0m?Di^TP3_a@J{X=J6$ z(n*}Zgd1JK7EY^zibz;Q->Vq8X)Q?`$7TosyEv%${k?8)) zMJw#UtMfZD$FG2Nd3xZcb z_@@$*+Nn1`j`=%yYK1z#SV{)R(fCaw;!jeu3VNoM5yN`*`1uBiuNnt$u+RD~+`oqG z%Uhq5xy9k!XKZW`;uge*@=roS~{;DJYenu!hRL?~n|C&}w{At8z9AD`dulb!;LIu8=We`Kis?1qgubTRl#6iM0q{qgy2;~%}{Y>#-#E*=!; zbC&lz)%n!bq^|x}UEBQOQsW|I@loRZ+I6c|%{uK`C%<0?H0ORk+{Vho577OWD8D^r zh8?`_@j<{Zwm-G+I>Cr~pGl8=2mbxA{!|!Qf%WmXB)u!$AA$8}?^V`N|4SLM4d}|LxcSf$i{0_zsivRG;`!B7#<{Lqx5O~6`#MY zYH<#B&Yi-hzBtKWUxMO8r)D39d*6n##VfQl_ZQ|*h6j4Uvdt1U=DDW^E-t9H2+n+@#HRSsfZ~p$+e$6kkg=YP0$Qx6-|3Vk- zU%PI+68@yt2;%E9wEj<;z7n>dsS(s~N|675qk|Rf8T6hcWm5YU@Bb-hY(QIHMScyS z{K`@O`@6b-^W$-qBz1ia|NfZYOb1g~y|a|OGFhnMOUSQmwlAz1P@mPi{F|ST`ISrM zkhZH4D>He@kC!0(w*OaWP>uXeQZmH(y>M|cv}*m5Oc)x)-yg64nN89mZpv7;AeP2A zWJv!`oOc?!$tJLQnVSAoW`sm*SpE+B4_VuaNT0m9sQpQ{K1G1v z$dTssk?nh=pedX`eOhstyNL$>n3NC9*^{ph;|g@(|er-(fsjV{L46+ zdw($gpR%`^W~*<*{oI84Y=2Sq{mV>At9*XVRG`iO?L{J~qadH5s*c3v_&0GvJXyT`z$s+y_CB@xc?_8PeSSsbw|l&EIvyB`f9w~iM*fnQ>;+U`~w2^uQlp> zkQ;ygiO;uT^-IX7-9>k@X~RG9M`=6m_aUDh4w{h%wQt3v2QmGG^{1k)Hl)1yli0D` zL(T`kfAhF$ILS>_LjIM^{=)v?t}m=emz!FF``~M1HJ6DmE#Bcr#IuWNzx-RQu^3gu8(}a-kE0+w?zg>6smEC z`Okd)dw$89gbw;9UUO~>cYlztC-a-B{^0F+3lipQ)9VK5#Efw9jv=9f`ZrK^KEuj| z2a)7@EXNnzUlyk5Kz^t+iIv1H@j3te$SxNgiB|V!v2jP%{{!<+>uy<-#4+E*6Aw({ z?jPE3|5`g@Quwpg{-90qZsbX08??BVosSFipL4r-keAomBE?DVx$DF8X6$NTP%o{Yoj>b-yJdg#OLqJ+4aOLr8}C{#Oj9_ z*za^FH_~*!4I1_%R6d{IAC&ewpY-at2+b*-%H2QAkBYKP$+{jN#p@iR<@5RRRp$GA zQmeJ7RsT~*DU8hYQ9;99Psr!<>qj*O$H+m;ImkICPOg9a{g1VNPiV&DP^@h&9N$NG z$Rd7O2#NI12>PG*RbESHRfLFJJKyn;PBVSdkcc-K2=iNZqd{t=8`Ubm=4uM`Nt;86 zRA51VpRBMak<1%F>r(Xq`q*L%ER{=R3F zEs5GELXkyr-2Fp+bv)FKzPgi%(z@Houg|Z4E;-OB&0D=$Jmxj~ei8I9M=e@T#%^eb zTE35`3G8#H%XXyRz71;GUjgIyaW5Q6v_U)6c@vA@VgBAH)`etu?uc6U=R*H+V@*C; zx6%wnx6k7KAIv|sFIrB{osnJNi=7_>`78RljQscYyEvsnSU-UrM$%CyBRyiRae~^E*B5FzFvX8)<5@{2R>gzd0I8!v5=xp5JHu z!uq{}-eD5kX*NneM>sw(;MaU&7)jlsj!q>D>+foZ9P;|S3A&rj>X)@3zi-%_OAISa z(T172?D`;nnjP?pT7Qeh1KJAnJ+=KCss8pzv7UJhHy`r7T&tP>xVHy4*$M0K(CCU!j9!vl>q;7dah*D-_9uilp|Yz zApe?}=0Y6PJENBV6J6k+HuiQQ6^lEgmh+|4fPdQgix+7ds(?<;(&VlW>sL{^4&>Lr z_NXPkhxym++=b*!`Dd|T!BUQ2xIc4^q8CyB)(zRNdd59pCE!0?-{L`Tcj|`JtXFaK zVSRP(b8q6;vpZ58P{7^~(C6WeUZf^O0gYGL#?6QQ!9A87Cgrb;kY<61`+v}X-6A_* zJJhicYS|x5Kz%A;b{5%_HW#V%WA*{|KZOR#_}`&{^p%DA-M`=zd8}cDDu1TR@1O5K z^!b%bzT{aV-#Esv1n{f1FPF?Pl#Pdt;QF87`C=cw)=Tfq-YnK#%ls3_Z``lnw0ZAd z{J>P0-<TjQey&Mv=3)`69q?_q8r$QSWZ(quN+*Tmtxw)mTBa_jN&~i&VLB zsNXqloyftDosr`q7XQQkzN5bv66cH`;@T=; z-^}{^A^&}Phm)Zj2BK=qlk)rL`_Hk3r%3fvJ9K&BKKB2Ce)l)cB~$y^qO#wk<>P$+ zq`y%v`Ke%wH1pa1c6h$-z?iqv+s1L?*3OUKcPEED4z@uJnkCcO^X2;|4K)qY=f4uf zwH<{0lZ78Cb=VSszx~`{<&(D%&Ze;s!Mf3sPm%kt2KmYI`Gma>sAIXgWG*I7N zDEq$oNGBDZe#7|h>r+QkU)vR3+$`aKUj+JNZYrK6I#aBWuGtvw|Lq3+FCCUna@FRe zh*1sP{XxD5o?lP$fAvLKtM+r(hkTb@%O)`~CTQ?X*1rS!Uj8|U6yJ3~#)aMWJx#UrrBg&P1BSwf%b-hNZXH#OU z{2Of8HAfGH0kal-7Zkz!9MKkP4{DW>t_v0_kFGHXmTqppk(@O=o^0k$M! za(9$(%=FC{@b^>JKh-f?3HkoU+a;*{7YY;Z)2ajkuq^_)RMnX1NQZ6&Pt*>v@hy>@iq7VC4j$|bC!`3pDw6)pc}^z zjDIXrSCiqF`lGY6So};t{IkT%iiBW~m$S*b zq4wx#%lZ4D{@FJE6nXmI12vF3`TOJ7KlivEBV*gTqL;QTzYqKGuItrMgAU2K?K5Hi zG$!vSOPiLV`PCx1{_)S3QL}kL=f6q8!_#yH^HYHq&!yI~?@!HAV)aXCU&r;xCGD1b zBcuER&b~rE*T}xFHarM{b(m=)oJ8-`b z`4cz05%1|5$l&TjLH<6(EG5@obVa_Qu7dns$@3#~wrin`nzQox{Qjse2{xpiR2ki% zo8p4g#(~Lh6 zu)onU{-mmO2zu1^5;tE2^lx~89ocrQ7jiCO@iWYSzEC+r!s=X6SF6k1d;;v}ZG&S( zJ8~sYzaU==+t<*!A5(C`3t|15Sy4wVoAzVxMZ)}a{ryzx9GfKmYPg2|e_%f|X62H= zgZ}7&S02X?0sM&jH%hUs?0lX;SbDWgl_d${|?Drjk{adGTjO;R9$=lzp3G&zfz8)p>*RDp+PnbRt zpij3&HPrjuKD?=&us#jZeokNLq~ng)g!#GIhO-uh7zdxPBh6whZx& zEOx#ctgk5VSw=)TJ&{QPJ3j^H=iK+YlcXE6=kLkhzXaH?15Yf7DV6QdyvzJ24E*!e z&pe6As==t%UY~ouu)nwO2Y1rgX%KQ=&-zoKew-NLM$VnnLJwBAW7F&?^8Tm+(%j#~tuGApA=V{>-0$R$vTB(9g!zNov}~e3&HoEVr@Yz*VL{;QfcRH>012tK*3I!u>PNSO8Psk_9ED_rIOpU+3Y*I)GExI(-zLrreq`1!9- zPaC9fE@ri=FE6ZY$>}xykZFYn_k3Xd7p&+?;^GFON3)%{ab3XAuTdB1z1{Ix)8L2! zi;vWJ=kNCjuqGpw`=Y)5Cd;qS-`^dy!I>nvYV-2HkgshDmh??kKOCjS@;f3?AKvwy zv)su2!oj@$2iRYeH$IdU&(=pNQxv%0hx+nNcD_aR`k~1FC(A!b!1-wZt&b-9L565( zXI5W;{WTXtmy;TOO*G(@Jii66ZlP*Yowu=!S{? zuk=|IABDNjk!PXDv^LbdG&?kZ0aNYfT^6T^Y zJZt({T6yQFc*p%HIp6&FQL@{SXgF&lo$S@ze7Jw%&}a{`g6QD zco3@XG?N>L{*krE3bK2{U^G9M<=uZ8+()5e}81ZtvPy&0d-e{z0zh)kZc3T>Os_=NRitxOZ5)m9xn8yAh(`sU{^ z)cU0p)y>{WA)M`>f%bKX*-_$qF&H(^xz4>`2{<3BS;>t4Ufv%M2o=`XhlgAOq}~cSYKyfs-wlVM_RSNx6af^8{6z_)&A-v{GztiXYl7(VSO$6 z(0Lyo-DLGO&|mu&S&_Yy2BN6V&Kw`GKceUSGTLFsRxH+H z_7nPdeqY>4p3*4vU=QOT+IO2Vu4Jx^zl6T?1^Hi6=tN4bhoYfXto{J`cWHJY6$=I< z=ab6Zd|i+q`Et~fHaTnKFKdMPx7p}UHW!UVen~8Th5c#6h6fVwE|XAYXbZo5`+t0* zH>rsnjq;x{{$c#kqfHdC*gP8%8|ELt{#@};ds0@fjcyGU=6_=KAyS&`$KziD^2f19 zOv#gqzUX5m;~)0_I8II{vj+R3xS?!+2kbAeo1IOr&RdJ_PGa#5% zh57F*%fD2O3q`dZ;^q3t&o2+3Zb9Fx55{+|9Om8+tWSKftfTd7kK_C>Vg2sy{#4pY zbdVRnh=6{7di#^UPOQLjBZc`7{qtEGax+(~vzzr-K>u`LYIizT^*(a^T*mPa`yagx0--_M@85q;g!XwJ{}-0wsG<5S8yVwN}! zUEbHSe))Wt7DN!|uX9lIC{~|<`mG#kPpD`pnl+p83-f=!2U(MhL)ysRZ8H+mXVa;N z$fW83wD&jbZ^EEHT;r8ZGOISCrXP$?5s079>^G&~duih=b74LsgKyGxf70+`3m>`v z$>;Or0ZTeAWEf5hIl?_35$J!Yo?J(FR-MGJHwp83UA^3hw+(ejO_eOLmggz8~V?E6qgf=Wg}6``AAT|muFhg$z?l{ZJB ze&v6-=MVWlel0{+KbnEO@38y>^sk>JdXxT(CLrGTfq;L#r81JJ1}#9geVBej{$p;< zCvDpFL6#GP(Es=r0sp$E?tZ#-LIBpd5W(>W>n~4w9U`lHuSNYXF#aWg|6ARUk;^0u zB`sn8Gu)qUHo}b3%E4H%TA2UkA}Q@@pN#!hS_<;-{>Xw}T|NT$CfVHkgZ$?nR-!4o z&ynuNk8-~G{qN>m>!kn2Ws4gkS^gXHPfL1G*Wy~Fo8GcM`2O{h$j?%}y#?aV!-e(P zHlRB#(tg6zXW0K!_n#Z7Uoajy-V#2)CSGd=xhENeHZ5cMP008DKCm|eR1+#3KPFD_CUM6np=s?`b9}=3&ZCYI z#Pieww4s{$$B^%h)$_>xPz`kPN+9DK^hc!IWf0>#n~?hrd42`)_h;HyT9P!gp=fR| zrvGW6{^NA~5K%m{krzKg{jYA$COwqHk-M1XKcIio^u?4uP#cD8&I$9cc)NnC7VO3o zErt1S45^^K*X+h&Lng@AC%^wEHNTe5Y{xAg7YYAcM{< z{)G9F#bL7j8E+=?`hSc;{8@6$mh>I3gTl@;zF~efd-e)4K{Ae~-_So9=iopp?Z%*% z^Bds)W8(q~dQ?fLRleKY^djE2`sj85i!Wh+=b}#=Nz8w95c$)I=@ZDm75R9Ri#7V_ z>~LYeYwJSE`@IX0Q3tmFh=BZ@PSHH#{k>nSd{=86lJ&<*kU;{=-@^E_aG?e1Q#TBK z$&KOGM=jvH&@7A8^a)4lmMnh^_5HT489mc=BtEJz4>SA0?_ay!MoRZ7r(*4LVSXQ( zD$^93cSs-Ua?c0)*Tv_1(9t*FpjyKEzhVE{);6!D8&yw6 zZ2#VYpmAvMQKsLJ?**GIXrJX{uxPrle&18^AwQlO@aj{#VE;&L^Llc6vJt9&CXYWs zenn^HN>XoWfXtJH`L6Q|C$IV~Mdv%P{*qe2_uAh^grpBZ*&BuR`^Z8|5;t%Z>e7zs zGtBS3d6r3*ABf=fFGGG~%!74?|z;*CS92CMZrC2=X>v3 z^-n@pHcIvN%Uk7Jd8ZPWvS2pAWfhPu}*QfKL8d#qkaEgXxP2wG7#h&l@oP zgM1&(^dZWVF{;V(_9dJO+YGF*#0NT_w|wX#3OM$ zIy+H`yFLN+{U(14dg8BctNJ}qxKh5eKJoqdQ=0Yc8tg!#2y5>6H>nj*(@ z4a~m;=bwytI+vUspowbQF@E9xrwhxnh*R5WwZLK@0tC9{Y^7H zUQ0!lh2om6v2uOo=cntI%J@|Oh|Xi?Kg0OZyho$-OS!bw{N6z|C7R^)36Znx``j>o zR5EZPLyqbrOTR$w{VRd`KWdQDiScPz<*~5-u6nzk)J%yz(|z&O3oiY|M6p{4_R_y272Gl4{`Px z2jqp3{u9knVScIn{qp_e^pfLrqgMj{Z$y|}|M>l%N_~n+r*FH^-VQAOg!;PRiy1xb zI35rFPgq}rn#$;vS!q~po$RFWkpEYhg8AvragXTnH6^X;>$Z7H^nk(_q*}`2Kge%G z>1*kM)RI>Be=PVZrJZl3<2K)`x%UV8eej_{>O22ztNdCvD$<2#8&HF3n{xL2ReAL_ z`^omC=*HyM_b?vrqi`6rHFSUqfvC}+ZeJ*!;M2#PxX|?~a--jjiq1JeO(v10!@cVHl z>t9L3d!A|4KVI_v2eo&;hXqd>ZQ4u|%%_{QPtKN6IwySTnCb z82S&Elg+8uq^VdXlf7Ta=L&<@(sn)-t)72&q+E$cmoy>knQVU%%s>3@-6(ZzxFjx| zE1Z8AuiAsotNMXRw@!lk>oUoLlt0r$mZ~c_KA``guzxvO^#`Gr^P?OApQVu=)Eu^zSqOsuuJIj{oOMHs{SkE$2r=eXUlrphJI6#olJZ`g-fJ zC$aBkgf1>-{x=5k*^>-6k~V8Lsw!vuL*V&Plkb_+lhUcUcd;;^L!PW7*ZP>F>^BeO z`poZNP2TEGRx8axR-YN4u>S3z97axQIiQr$XXO0w{RiEfc_ij|3i7|p>!)93hgXziyb?8bN4R-{XP3`y3np$7vUw7 zO1W{^-{T%Nz_yX!*&fHg0jpnnh^7U;j10l{&*4SZ@t;RQChw2 zIxqhU`I_~-jE1-$!9Cw>k>5X`uZ^o^`ybTANbd;iZ-9IiN7<3D=M2$}JIww<{hPI0 zw!iV-d^GqA<4Xzf_3M@kS#B^-w*Qay??b-!Te_0$f_W(A2O zU*`I5WJJjPR_*haU4i6)g(cFv#`?=@L4GRD%$)k~MR@I2VZQ912a!FYR!DsUJAX$4 z_}Zqimv(s`i?^Q$XYmQ(>)q)*GVRxX^tCHnKT4oKQgd=XG4?%xGA@7O_=WvtuCEBi zUOD(fqOIKjUt?|@1O8&4%l!ZNrD#r{>FoJ{ z`qqed?j-QxVwB;dDIe$ihy6;;sr0}M9Bm`a-@GGEWc#3bsM(qE1^q+q@YTdB&m6sM z$Kq?~A4W*b>2R+Z*!rq4e^-lxh{(Z~#~%j#4eGs@{=2ai8=M#BFH$+5c!VG1osTO5 z_1WK>Wc}@nPvONAh535+NQoYmw8zgojbqOj^cT1u??GR=x5F*?P-$Z$I^18l~-g?}*Jiw|u{WZ$BrCRcU>CC+v96o8t@izdY?| zNn&3bBDEwJcK^VBO7B>ced}kT4<}8yabMuy6<+ovzosuk-kVLiaj0)kk9(7=e@sz* zh?pCP`nLUzH|aIe4C#&)Lmj{#eb%BPGIo&0g$G+Tukh?Ig=jLcUUpSCj48 zRw%nhn6DS3&FR4dv+&(aVZLrU#Z$xQ;dqon%lFs${$0j|t5wC0CyvL&>Ar z`8^oe-+wmtw9D1SxOTv4`Fy_q`G(2(ebND^DYE)7AI z0}WYyAKKq39~z}Q4pfUPEm?jZ>Ys_f?0lwii;$5@5O;sRfWKdUcBI629@fe_Q>-w!EA^j|of+IV>DGkIIMcsW!@Lx+*`g0h2KA`_9^pH8- zzin=-{k4V(?&QnEWvJ!*ACNzR)!u;)i7(%)p z^*~0}EPo00?bp6ks@`Eco-PsQYlY!yB5pd=Dqr2SOX>BL6L>>tFsCnRp#N&`x-&%i zzmrJi7(1T^^3|}*lD<=2h@Yn)W6uxhUx(Bl)U2{2{`p-vzo@(Wl{De%^;Y$7UA;1W z_PaA~yNkuIFu%A~@3Zvv`G;bSDa<}YzRI31C&bhkRrd?#?ynf|g#uhiX4x_{)Q9OG z)VIC;+(_hNGgPI$gqsh)|J#)6N&M0*QQ$LHU&ny2HL~+r${*RFliI941N%eHHk;Fw zZS(P|{lfZI|Jsvme`AR>qq}jx5A%atmidyB?)J#mgvAHYf9tPmPS2m3*Q)(|qrRRD zp6iZcLLRgD0@%+jeyhk3eLGZti|HGTU&Gd=(r&$2S;~{?w zcG*&;D<(Li>OA*+q5X|>w-7Jg^`DYTy_f0ocA(@x{B$AtOnX;w_mY{*6XpA^b}pC3PL%21*=9lBxD0Ac^m zdjCsluF-8?d;s~mtFJ~QZYtp!>vqcDKi_|wq5V}_=2|CCPhtJl62$l4lC5lM?I1Ip zy@&Aw>wCTZEXabK1w8)^=8uO;oXACgb6)>4?4MBV?@tu>yP<7cS^fm(Kk7}KNy0Qs zq|?aqA5h;;eRm}tZdfCwYXca6fUl7u=JffhCD<`en6D%qKeD*g1=Y^$#m$HIv%?TS z(swHiTdb7S8e)?VBp91V>mvCb`S#crmI5>ct5A!2==%qAl?Ok4e1o9WLdI?=CT7aFO zYRl*I`K$Q#McVZHMXUUoCu4&|;7zh8cP`3kcB zqZN92w57h$k*7~K6IT&~T`uUsJ6mo(0pEA|HDCqVcH9aT+O@1dzP@$JbtIGKSRnn` zYTSHBz~734=Co1G1V1_~%-@a8tBLPRH))f z`_W7B&Vj=G>E)~@rd`}o_0Wmrb+ARXx{NOg@ZT=Ia3&iS?Rn>8 zK>L}t-kg32GHsQw|4d~173hT&Uo(A!_VeknRb=8Vcb@+y0r|HpkIbmc{bks#r!ZgL z#D1iYlNTEB zhjicPi8Qyyu=NGvhigAviAJRp3Ul<}#?wH2y6CJIxsvXNl3%d+RTspki~lVrzc0%C z>p`sk1>@7=V_xKUtQ(rzhWT%>KSm)^mjCZ;fk%}J>)RuDe`4a`i=JL%`2`WEe~G@W zBr1SCVvNb(?)DFMhb&~M~?5o?4 zCG?lhGHm_bpN)(7{e_Dz*GY$bekk4+!uD4}{o8;S(>q>E@t9KPAHe#no#GGaz@krL z^?k{L{OyXerD~lVu|~i}ZXEKLd1Ey>@zNI!*%8a#AJo4M%bdvY?#t1_lgs7feEXWL z>q&I_c%YW=_c{XpRQy+vpoubmcQOAC@>jRPi%eSS$>R^!AI=(@)5m+QaNASD{2d(` zK*~)0k$!s(?*8EZ<9?%8lJH^PsBC&mexKi;_4c0`U1w#5OMHa+Gaa>>Y@P1Qv#%1s zU-0Y{I!9q2KGnebuVDRu7(PNx9FJq&bYcE3t}3Bn4P|&kjj;Yn##K-yrSn+xjI}&} z!nePlH$9+f^Pl1Q8p7vuth)D@PLw{!e`k)C>o1=_gT4=>Q-W@b6@p#l{P6n+Ef0R7 zhnD}wTW+e#=kxtL>uEowUy8qoMdCg3`TY1|Otv4{m*|hWhsDYH;qQMOY`>foop3_O z7dmp|u)ffH#!B+I*$25kwdTg5zWr%*B3G9<^XjLNub@zO;;by=ONIHTO2B{XWNl9E z#J1SyiZEXT#X;n?$y(I$9m_9>!2b5nvhSPgEm(tEzF#H+`X;S4qgBKP-}D#eYh|~U zWY&2f)FhR%=Lh(59+E=;RP4v^KM3UJ&{D}DV z_a8%ji027Elwis78_++yvE7U=`EG|D%!T=hIPODcPFaI)9FqIDfS*n`_s~oFY1lAd zn4gqu*>v)|94zq@)~8XSCDg}*;_u7X%GW>t{5;3S<@9sLC7kx!N34 ztUgXypI$s$NW0Cmz^V^danB$6XI=N-lA8EciC>m35ah?a<_qm!C^FQWDeRvm{cu(`M+z9ctDXbUs^$H$Uc?z=;}u1 ze@PIZuL;qz{MnnpR_mWZo6YFq0LNDC-;$#%Nso{INc9fop1%n2b-jEK^=LYXlcmCZ zh3?I!T}n^kT4!Ot_D?9G8Vk?isRJ2bus(1qyqs=#yNWeknLa`POJ%|X8rks;PBIhb z>%hu|^u`t|tYj?b3*=`98(x>L^}HcIK69!dU%_@?>A!t#4X54|=Ifr=gWyGLkizEe z-21Hs{YBlgf=H7?C>pnyjYI!xm%Af*b=w1_gfV@B@nu4e4{1MWEqdLV@r6PDVwvoG zn6*>aAk8TTf_za~e~0-vUv%T*KyF+D`ro%Vo6(uqR^W_#!hEU3`w{>78&Omu>z{}A zZ_p7x;^DdxslI3ZzqP>r>6)6+V`?jKy1TG`b(-Ks&bS1i{8ugYMSlLQF;d3Y^+WhW zwlH57%d=@oSsq?xEX>!X-X(O)kqg*+9ODb-{~abTqX*1Z;6B+^-1C8a_56IFUNC)& z^`;8*^=phwzY1)yleU~M;NNS#yDY75S1IJ>UX&edymm-swTsuLwlp*IEBl1BfpTJG&6uHLFp}`9cz4 zKXHyL=__7?Vv6+z`8r$RLZZg{p{4dTN`-wb;#EbVnzq5x#C4N!hBiQdy<{EgOKqd#uxP8Bi#4UrqIk*`9cG- zY5Twed}*98Usdf&=%g!`@acKNeEsz*qY-DW;~fi`eM|%OC6&tiREfOD7sbMSsc6im z5f0|K;uMR&pnY7j`KnZ{dzDyen64mS*Oq^w#sAtH2Ac`^E4|eJ#96xR|_9VmJtwrb3BRM|m0bikK9BJt>e;kZ=%lkum@$$2io!61L3z2AO zTogAS)}I!KSX2LdEAg>@ablK#=kKrYlpIbRFU28$t#EF>FNi;{%kpbhKh~g+vsnEK z`ggxeR+5*8HzLK|tbZNqVtio}a$LjCH-Yu3ksoFI7w@>^ zSpyppyMO-oh56iSeqGwD^q#mj)=SPG|NP^2{KX!h9}DETf6{Z)4mj zte=y&+^7Bn8u4j+VLlBbFG+2(Z;6fKOxXP+KA-OD^Xbch%W*|l)?W2Bpq9H zOFVes5czyQpYc0BQ~$C~hNc~b`8=HFM*6%;oj z8}C43L!;34al-!Nl>!HX+xYYRM;M>n!`5{5tTouQJ=0H-h|i}|&N|{UWHb7h@5jA= z*uQCX*OeUnw;qLEVDSs&^X+dN`ejl8c2Hw{VqpJ&$-d9q_oNTj9CZM({x$yjmV3MS zk)rt#Xm1_!FCm|ce)^G;st9y?sz{K}d? z#j3*;_dSC@)Q8C9SAKm$JExd-S$hLdT_?=v^&Mq&^Y^=0NsH+xwC`Qk-ltoGzhI?x z!hDLiotOS|s}ct*%#q(epHB_P`E+Z+3S9e)@d^8f`}V&mwb!{V)=eEKpU>y>@K9I! zCnXf?w4290KbSw>GTohQRFrXKT`dQw~ zl?*$z5!t^I)=&HWHne$W5YBFlfKp=7xFj9HGtfVjz$q?Odr!g ze6!gxfNYD1MpfNC<(APV$$gwF5$4Y#bS}01>x6Aiq{!btzdlx?eoku8`<6I+E|%XvpTEgVXVbUq z9dUbGR{w>GUp!=8Zk&>x-X1_E2ym{`Vv(+n4Dh zgECLx z+seZHDP7K@IgSSSU5yrPTg-7~lG-CV{WjGrf5Fr^DW_~Qv<@5=u_KmQj$<33d` z|A~(t7S_Kbp=YIErMJblHe&hvpRgkZ# zk6lUf$go!Vx@ftSUj5?RDqr@U*N{0=H=|LzSbh-pKMkyr)n`Y^uAj-?Ka4N(t!4TB zPm$=6$0+Xk5MUoax%!dAH8JRGpO*c1{QRBWCLiLyI|_Xm%=V8!{aOBRHAzW}LH%NG z$e$1Y{VVm`O%pfe;Nks+-~WQTEIKxg;Hw$J@88s>n3}!1i_aewe*f8D%VhnJHTdZg z8}9i-`gq1cm#0$@iCeT4S^9RAuU~$BwBUIxjqQ5~ z@7y7*FUKo)(YdOp@SRU=e>1FqCRk=s%Ry&x_Loia^~v|IPLD69l`8jnd_ntm{8bq} z*7g}zl%4az`HvufQu(o({#W}4TNViORjhbUI!*0?_``%5az6NcJ?mpcS6X^u{mZPs z0`isbL!|3}-4$mCc9qZP^VRvmA{so*54Uw5Ea#JN-%7RI$Y=dX^g>;jFOkAhn*JpK zH+&VgZ&|~9iP4TNsBEEd{j~q#FrwOT7h181T_5I;tKT}%#w+32;A51S`QLp1e{Yd2 z|Fb<3RR)=H_YdZ=T^?9YcNEs)G5;8UP~Uu>R8wpuGQ9gxn7^@Sh}8A)eQ`{(zMLOE ze{)TYXrYb|*51ba3&`IZi*r(o%a6ncX1(R}`TU)D_lZgt^e~)QFYI4AIJ(LFqbOc| zLJ7p5L92}Eg4aR#C<57N{jhPQtP^3_(~ovd0Gjn;J-!d)No<&zme930}2qc-aghJ5w! zwU%u0*^aWBIt%jE-ZqwoDQDpd**;~KpX1xl|EzaW4ZnOGa#onH-ile&S?OY{`WF19 zh?<8##u`_I`I-?}M%9&G;BE7T`O+?|rYk+#7&<={=4*X?xzyp=J@H=6QF1=`e0{n0 zfI1#;Yp7GCBiB!U|Ht>R^U@%rr>*)|Nl!k}VF#5AQ`)J@=kxW=|Evqi*NjGS{g{1( z`Hc=+me5tB*J35{N$&n&eq*(h2kCFJ8Cl!0{BQdi{Qi*72_a-dc`}-Gl<6PjYi^S% zZF@EZduYXrh4ig(iz|7wCmN}YH09nu)VF&(J&CHq79?6{DCdh`pG{dI`~FK&46+Uv z<}b0zjAl7WaCW$Ge&fz4e{$+UJbLZV@^6sOQ7?l@VcrfNpAw*dU%wYor2|iJ)Ram1 zfB!EHoF8>~ZY*uH?J(}PP?+EKBX-dZ9}945jxfK5b(z$({1VoGCajMQPl{-z`0=ON*m7xP{(W)q$dQ8lmQ9~Q@9*@& z7mZnc6zb!vw0qJnd%m^WztpYTl3q^@$F}w?{}1=qOg!d7bY=OAmihaWaHF_uh?~zcGGc{ zfYB%`s;3o+Ek{r0ejmmsi$6J$dE;YHejck&=mPuQchVBN^Xo=zY0UV9_Pfe`Es^w0 zMi-9l>#H5#V!poh4oMB?4xCjt9g zJ6>8w*P?K|W)I7cU=Y8wD>SAv%|h|vA&1%f2mQlu^~$6Us*lAAM#C6Cpneh5b_N~1 z*cYGNDy)z7-=4|N4{L|w4B7sD3E;2SfRA+8cvVB+;llpoC)xKIn!ZILv}H4Qe~y5^ z*X5L|=kQSl})c5Gc&w&4t!_=|tK7y~VF_%AP)m`G386 z_37(go}{hwHe@_nSYP*;l+bnluW?msl6<~8Z~pQqOX{T;h3mh``2+Eh^|xZ$Ui2Cp zk{WJ4#{Bw7+T>NVr&AJcKP*OWKl%9~&4yyS>DMc4ZmfdY{cG@k|5f)Ok~B9N*>CT} z{eO{&uix*Ji>d0CSNNia9ycHAx52Y5wEODgt@_6wW%2vO?yvBSA=dKw{PPLME>5Pq zi%YSQSa^MDYFg5S?~(ZF33c}W!2Y**u{nKkB?6z^z}6QA>uaD-DLvZ%9rp9K;^vFM z`VucKrPF`C#UB?bvLPXVR?E9gtoT zTVH8leVs0|pw~J_W2g8@?D>Q9gW_fVr*9v{qB)kVeht^x;PWMP{@k~CnlAGnBw&Bs zy<&gTWnMCRP{`sl=zsJ~ETL{)-s1cS`TGa!Ym}_+m1VxKRsCO@XiJ~;+JX)C$8h=& z*H=okEBViCYpeN#M^j2@?e6+k*VpS`^JrG#1{_~5*MG$Kzg=$@)BP&-_)aieUul@X zzVt6x(mgrRIBAxAK3HEPFU!_PmwG(0TzGwHj9o=v-P(y4%@ST;HhIO=@Y5Uob{1P- zGE>4^UqgI?h{4}osQnz_`0|cNv21_I8(i9(t*=_(zdOWkq0Pl7aCR5DJ|KSl`EzhF zJu&SKevO3Jm$H5`UFuhc_sF$5e@&29b|rO!P+V4J*q^7{kvtBwn?=&%jt z#j*GmuD`w;{K?46yINgeo;^$H$Y~#N@UE8k&#!Nyx1q!+{vgV9W$P36Hw|(!r!TXj zan+oyg8r5JI9HN)Y#Y)vGUM(a+OPW;=g~J)Lt0%w2FomI<%<}6K!dFh4Aw_bn^n}@ zY8O^oEX@D)w!tK`Qwn-Fql^6c^X-S0y9Ir>C7W9E@3~ui`hK+;o zk4-pfPMz*YV{d71`8Yp6{K3J3<`~6bjnl&X4P9DJwOl^q`A?Yt2lZdgXFl!OKNO#K zWcbi<5V^+W*nVT4rCoHe*t4FX%r-uMH)m z?b1>2n~d)?;6GI*n$fbkF*y06oIlXNwCSn~(c2%7&eya2i3Irfv!)y*x5i#W$&WMG z{{#O0vs4SJn!FkRER^dT;BRY`1$BtojL$0j$=^TUzsc-nL9d|AIP5yBZ$tmy;+<^& z^`Onzf2y26(4VCK%$yeW+l+OTh4n4zQ6_ycP}-pD-T4(|7N$1yuT9eXHk( z6lRsvp?=@6{w{m&{$YGM<&-52yBLe})}7*>4?O=e@ppk#?fGM|zmcLKf5q>_RJD5` z{`rX2hoJvaYg;ER(CUiDJYwgEK>nthxX{(V6LHk71?>HZ`20OHaUteU5_t6qU*O+Y zhpZ+~F78HWmoon(2IPP5uC=01jpDG<6uJKn`a3iqg%YRK4CH;9=^w0*{n9a|TK8k{ zi@a@u{>ABF+4mjyZbxHW&AI!B`d5C%h@SQh#dBx0=o{aE$m?c7lk>OW&cVX`=?}D| zX>PGtanKt1`{VOB>83fIvvmvhlkdNS{G~pS=~vJ!7r8hj8FiVqOa6ZO{p~M8W%bphJ-qrm>@O;%;iT?ZHX>-Jd_KRwW2-PP!?>Bc8_Fp~nT!{6?9X$UP)?XhutsG~t+R|HQyp{4Y(u{}|}o zDVcuVQHaBTJ28Dr1NpV%{Vb@vavW|pW%*MH;@j7epUr9Hw^-az$oPWaXLfyYh`Kc0 z!-E4ia_?UR;-~$eGUyWP`#7Xnn6EqY3uv#Z5BSF0Ao+ZL{!FcN8O6VT;Ny3M^Jh=H z%%Oh0!m#C|RK|yh@88)66i7vm&&0+i-39sjFLxPzD|>z)riaPr^Xn6}x^>d4nF_7) zHR_oeP2L`djmAu5^Fe&|b*(cw(<71Bf0+&RZH?<1lHa%&#e}x#6Tkj2OD%%9c%apu(cavbhISXiH?4z-}8 zJh$R%2gVQF-*rYkgwB3?81HCkxjvtt+0xBa&#?fvuaWZ!;)_QwlW6>)^LXrG)}IUO z_d^p8QSF`g@%T}~d|fKYpbBaa@#JH|d~JE0PhSRq#3>tu`T8a*r|vI)iRaKRr~qhPczzQz_wQTte&xwO7mp<-=9Zw`T_auT(pVaS$+gdo(l6h z(`hs9d%X}}+$YTEwDKfc_U}Tge7ag5qNCy-;?F&V`P`YELHjR$+^T&Q<>gbQiw(Fe zMwriEs}1RYnW1=(O*!}cV0>%3(TJwGN8vjL2e@%~KHN9Md}*TDbMg7LT?F-SPu_ic zcB-=B?J8kD&D`sxFHZE}@hJiEh0a79YN(iqt7cA@-yh$g7w*+6;4E{J_%i1#PnGe)Mq8LBS_Aglj!vwrjHU3UyM!Dq{5-)!w67lo1_XZ@An8>pz-k!xb zu)eS-*^H7I@i?=+u)e0(dDB?Y0onN%1RCt5c7G&kon{ySTk z-#&xOsH@9A>{-s@V;G+VI~dWe8>6xE5;?!Xe&57-(!KAWi}eq75ajo3?tMCHor>Y6 zzry@>EPF21zoU%S)$b70*J-(yG;!|^yf9@7TR$K^S-HfQe3zZi-ERofe+jVP<8S&C zg|Kw=cYPu^AI2vq3c^XixSUq)w~6Hns$IJWm$nTPJFAU>jza&~S_X>7DBy9gxe=nmNZt+;(Y7l1i1%Cdp z@2zxd`K$($Bf|XRn|btXm#-LS2g>>8`0jpC|E-%&l9k!-(f`qP z=5aMWfBe5lwvaZJA|c^}>}$;&yO5}4Z6PhPgbLZNN+q;M+9XL-C?ugfV@dXqv?vM5 zmMtOM@BV(@GuL_l9;d(0|0cX|B%!TteXuX!}mJp!+IE3Tg*F$-yz zNzvFtiN&X|K5Op1fVymn!Z|Aye1iIH;g=wKV)g}W6)ryiubC1>w?Ds$%j3lPG_SRy zRcT?^+g+T`jmMJd>JwGX@|k+@H2qJh5f4fh=hJ=kB|7^-_L)*$8<%OK7i(7#u%D+@CJ^5kOGybEtnHki+rY^u)cZCa2Kg;dlC7(X8sc9AAcqHpjWDv2>dC=LVtST z>=b%yaWGy{$@CNIYo?(!-Fzbw?~t!!=jT_zZ%3W2bW`vtJUdOC&ylV{)ZbCQe#cyK zKH#&{%SbxP_inR%Ub<~X`|gcwmd{F)WI83P2IKYO^ZVun^XNj`XzUrl_=NSrfYujj z=Kv+H^bq3{&hI^APRL4CUYcce)K|P;A)jL=KcWkkYjG(pY}xYx_4_3ir)7H5cV;Ti z9Teva_4R$VB@M}qz>cq2{0sBv7q-d!V|r;en?L_l{)T2}^x*>P)cF60{e$aHtsyUZ z9zkO_F@Fm6b$o*by}KwJ>zSS5uMfso0q4Akk@GRsn`8M)sIPNO{K%joX9fNh_Ghj5 zwuBD)6^G3N8NV>T`u#YFBoDoWz8w@QQj-|7sO%Ntaee z;tz%5{O)~RCA*}dCD2!xA9%C>4Yldmm-Bfk&Tp&Q)ntP~YP0@eaNC(QHzf?uFUl0< zxA2Z9NuPfljXcEs0nE?af0#peJc+^{L8DlG64Zxwbo3?3Q_rG)6WRIDKLp_=H12ae zj;UjOLw(-(XBT;rM389#>%WEh`+bM^lk*0}=*!6%Hot)SF_fe9~2%--P~K=(={NafFjNzo~Bn=`3xE_o|5VTfQ)ou3d8<2h0@b*L|rKJ@hiV zS$$rz=@2c9m-k;^5a)Z9rF?(z-}~|0N8)_{FvV15`!0MwjODi^z~8QL%am1QyfSlY z|8IS-knep3#q|3#ZLaZ)xc}YMQoeu4HeJprS==9F>Q%}DOtl34QyAp81}>XRXGZVC z{m%~J-yhUpHLKNR=;Wh<{1%MAc6ORc*C<8cou)o8hjW4PGl!G$8*!j?3?AvQcw=X(~r)B$_{ZId(K0iDbNOr5qP*`u4 zUx5DNr^OW7HwdD~hh4#j9^!l-?;A-uy@z-RC(iebZ&vhj?tVN+ zzc*&rC(JJtX&<8dN58`F7K!t%IXs(gefbxEFY{8&&%*pdTQ!c(9J?ET`;o8UN2uS? zH`8UYqhFb2DE(VMD&$+|QZe1Ar^^`_iTjTt`TDQWv~HY3mN?%_hgZqyByD7}iTPg% z;CtAYIn+bC9}_EazKe8MlMkEI1boB%ZRD7l^z6JytY*g6Z$Z9)b@d|kVVUU8B5{AQ z`i41eH6sEi>0Z6a_!RP8Y3fUIXf7Jpk)2OKe)o^99S!nJ67UW6+3kKHxm8J!EKZ#7 zCtoI0z3U-Z>A8YmP+u)hwx;Vm58zgN6~}=;o_pF_{`?N$jR(Z}_TyI2KmQ%W&NIaI z+dXnK?RM=fR<;%AyW_n;T4Q?^4;d@Ycf-;cGNrK;mCRIE@Fo1d>Z=eddN(}=JN*`q z{~{hI(c7{*JpMm%zDMrKqG>xN+~qFfe5>w~uWu-5$0>U_@ccu6?PGaNW_SLj*{PrZ z;x{4Rb>79a+@>4np)Jn$vU7{*&n`*WB9zsqpnvxLww(Ovl7bA@BrEP;xIS_C@;UVL zwisM|$Amu)>;EmzuO^NTB zTb%DfN}H*D`*Zk7KXJZ$1qISmGoX7SC)T+e5czUleLr7nMr@O zQT)D;Z~NiJ)aIxjSEDY@_xj5vRB2ClE~#K{JOlzM(&H+G9&! z?n=Z?KgIKJsYlk3(vl2xB$MSgAm5i>ThYm-akxJHvf}!M`HfEU{lm(apK6wGpTkpW zkt_m}hufHb1AjgDmXuf;=Am0n%pVs4{q8w4ki=cPf}F=QeTMnBQ2S`|>rg3r*N5d# zAin_xbLjO6v3OmvIKQ_{+-O34I?kwP`$NI{@Y8G``XV|PFX$uA=R)^Dy4v?Tp4n5J z&+aZUWND8|WZY7N=LduS(f}>FzZe(Stp2w3IY5eXs?e{83O+&qjBc+i+9|yym)${J ze>>0OXvE}DEKlDm_!at#t_P0E9PHni_5Sm({ww6u;lV>{oTJa>JQMfN_hL$@{*4|S z=^@T%^?4`q!#EXg-vYzyH&Jy@%sK3<ruDU3KH}v@HsLfW98M>q>jw&cKsP7@rc5 zAFeU-p_!M@76~8a! z&o$(sJU`!^YhNtR-`%wf>D#r3apoWPeF!-J9}QeaiZW8s#+W4j`Uv1}+|fGvoetu< z2a4w(jE}4$$umzh%b#Vw6|HefZ1(#-gJZnNPV+P9SCK-WK>y6B&GPS44T{4CZTpGl zA2g$PkQO`h(YbOKzkLMy$n^>$#mtBY#@T^{oZ- zU$B4hkE#_lt4YA7rsDH=)%k<8Pt*sT=Io=GABB9L|8a_LyQ#z_%lAQJ_a~gchpo4w zB<3J)H@#fJuTURbj!KiYT>j2XwMj{o&u`if>9Y?#xTH{VK8;tGP`c5Ot8y3D#|g5f zWJ}ahw7j)ApFexl(R=R)bJmvPe0GjqMIJvoi3TrW`CX`wH_~QNn;~)7+43yAey~2P z&A|;M!t)%Wk^}7i0iQ?gX484w;&F9Ie^Ea7kMt$kLnyKx&-jM(cjcTwV$fKKbbc~@ zg!A{7`3J~o#~0|ND!YEDk8zXrspgH9IDZ44TmSw$a4%K_$xVJCJ`qus>nKFv^c-fRR^hR!zUd4OPt@xvDVac*C9MLyF&5*LO#E8X|gu!>&>d0{`J2I z_0ya_paWX>TH~dO}eu2 z3*)EQ8>@(hR~E9p!`|=z$LHBuG+|dfZfX$clT-5|Jv*Ee=qFr1=rYrn%=vN|IUHjA zRRettHw`AWJ@26*x-35c`?vf`_LF|UpQ8(nOdlbCEBotH?}XL(;a0{U0sOV`oJ0Lx z590Zz;{554SWfFhPRRE+Vtm2=gOLk1(P=I6o1MR%ZKFwraW$GWWRT+h3;VY!JYvcC zpRdpq4;}tE?2jGoYDEp|lCXWQIDa_$AicTg3vOQ^&fnXrlXUDPWp4f`Pf`6`BJXd= zKbMSMA{d`ike^KoPLWNz|HkZl*=t4pK*;B?RS&4+P(!Y8wm6@izTA{8H&90o-=SRElP-$;6ZR)YU0q2E z&9YIKcH;a_G@3%R z(Eo0u>;1*+W1*d6h|1zxbSN@T@&1MR*ZdMaO2&HNgw>2+4ERlRXhnMzPs1e{nu_}u z?%%v4@e29zOat4WJH!7z^q(u+ZK8C&45xo#e8c{(DDP;}!nOvPJ!bsE?{nDt9U%5` zb!f#ark_%vpJBZY(n{s8*mZ_Dp9hAWq*|YpxuITceT)RGzqV7hrq}zY;8$IqD8`Ra zKe?x=vP74UX15z93ciGVX0(1l!^igGI_Ze>*)6C*_N`VG#T<0w&zE3fefRL#g|xQC zG2C>KX6^$ulU)K&byFh1&+ zn@C+;8}Yu!|Mnje`p=yUt?8yONAU7m#vkm@o=}t`TebXySzXl!QGNXO>^@CR?#%_8 zit`sct3c-0MNPmT2K+77?L`OLZo_8%*#4fdf2+W7898}Ro`3ga{FwlKd^UYH^=UkW z%^bw%cf(2UBzoi-l&2!zztws8Od1k&5Sz7O{RNP}A7kYEqjkE7o)g9&jL-3~9i(AZ z0h+vy@dy3o$eLjCI`a|w(#Yn2OVFQfWW1kzZt)szIW0cFFaD)Rf1dHgHpxsMB|snP zG)p=_mW)@u7SA79kCyKrz2gKnSS!w7>&gvu+iQv+MTzq#`4LG*|9OrUqW>6Qpg;R~ z{sA&e^F4~!6rbPS0}`p0)Awfis~>%mR@t`WdiN2ZzpHy(pbmf3Ib~f(UjJeKa{RL+ zGTnh+%udz)>t7Y>qrtNKbUYUZK-!;`U?15_sNi6H7tI?@w7cf3jGz%-*=@eiNVzzG%=d#3+#Uh z%$!Nz&OC&>=PTxKB+PHl?d?rkugpifwX8l5^)aWV3f=p35mtWN&y0^RL4I@WBPl_V z*9G+{xIV@T`4X=OH_)YXLHzv@!0)O_mbB0)1us)){t~W_Zy0P(_exIT0WsqIy_>#) zj_Y#;XSj&-x8G|wIpbN1hOYa^m(XASDBe$|>b*lsyEXaigZazk*@?8@s3zPf*gsIH zfAL`_XoymKPSs6(ekLdKXlSVhr*zFhl)r6SM`YKYe=#e3{#8^Te|#>YZ8D9TT|YV| z;)?9jLN%nJ!oL5U1o-1RPow#75^>%#Z^if%=GPsm6B*et8+9*Y{7C_SvUCgDYGeww zQ+&S`#y?{-SCUrCbJ2>{EWZxx|J>%8bf{M{b}nN4!Tzg(v%SfoZUmjT6pzm>LOak6 zpBCc@Px~|eu&_Ql^5kZ+)$J;}{FcSvuzs{iJ(#p;QHop*n0}f7{lTZ^HhzTl|NH8` zYU1<%-}+3dd$>K<>GV3DZ|F~#YF(fS zv$VM4M5e#hAbz_1CrM`A>w_7&dQX)9BPWaK{k*>1mSl1LT^xK_wl-M}`43yf>mvdD zpWF3_Hl_^V_Kh%6T%VACVz->Es6CC=UP$4ePY~e$ zbI=82I@8Ga;QahBibu|U+7=+ds@*8osQwLE5!LuO--O3y8Xr)!^Qa?YjJ`G{O-WT z91z#{%NOMPUpaK;tUbl~?lw0?7M0s*7F7L7lHB{_0 zPn7RN$&YB<)PY=nlsMmkAx^}t>I||oW_&|^SG{3NC5|WXiWtP6A6Wmj?!7xnsmc@N zx1hi1ce5wec9*ZuKghm+B9RFFMazBb$s=7V$PYmOJLhscYIJr9c1;<~^d0cM=%o*F z>U15Moo9R}f&5op*Bzws_ia?VL!9rpo)JX{#c5H z^?_Skq{OMkZ4}hmnm-@**M=J!)41qBJoi~B64Ups);mbN!yPnl0plO$$M#9Rsphil z_>6}*|G#y^sQUcZ_({z+UcX@eYkTEf8fbsKS-x93CQ#L{f11^A$+#2r>d=ndq!Mwy z=WffRFE(g%N^2P3&_6f6OqSJcZZyj+c`3^Gsr-BN@tc0!`0nC-8z#y3cTZJEdp270 zd_(`T-OEU;sI$mxp}2qP9b!wDW}L(^DdK#)*RCK(5-tex zUs8}?2%pr7_WEFriI;_g>OgOFUWQ9%7&E?sfAQPu zLy}h%qF)CY-_XCjw)Z8pu z{EJIoH`-cvt04ai;f8#sDXfiAH12Ve7;&W9_=-&fQhtdVd-{4Ea5); zvh{IreNVY>CRMxFk$cxdod1!N^60H_oo4x;wJu5acSl3B{>5mk4NY8k65nWlR&jsA z{W)4h$YjpS8c334$@4D-{>AO%RJwL-3YK)*s5oEfUyPKT$X@BWX7ydy`#EjO9LFur zR#o^PVf?ts&Yc+Tza-Fi=wD36wxVUn=V2UctLPsP@?U*L{(bP^s{;Q5^*v(MCNgQ< z4K&~bTmK04d*^{|WT)R9H0qB(e}6H+pY(VcNiHRRK(#~J__752rfYYj%0su|A(l+P zVg9$Ml|NZK_Yq25J%Rsy0{FXoeJ|O$?IoJI!A$Xdh5U^y3?s@L-k_#Aefi^%zaD;} zwCB8cc=b|o{>C4Sr@vaa;A$Mi`CGFola6lc#O0Zb^VjObc{+WyE;k&B>+j(H_o!y? z|2WG(){6N-$d~h*OES%Tb=3Cdbe=B^_&Sv}mA*4Qf(!p_P~5+euaZT}N%GJ0C{~^) z;o}3~k85w)QfWpuZYsu#^M!n=%D?|=6`$X1eqszYpedLAvGF{%{s{Vq>nZC3U!{2njsO-Bq2!p;_p z5c3a0|FN@JN~Z0=??;R~w?xHzB`9&z(q_$^}%A z%J_x(wXm~z97j2R#ktS^WD*VReBzlL-t&h=s6$AbBd&g<3_ zBlGLXZve}$!T9c#x(^Ajyp3A7W_-f+WpmX!Q}60k*nco(e1iRDhD2>Ad$!(3UuLlH zH^BIAV2(Pymgyzr6VxYi2SyRqf-lIsAGGOmj9HXJ&6XcJbrv{Q`npLQM zwj0kE^atFJaPnF8Bl1;Z$D#j~_4g-F%1RNQ`%hnm`a5lPB>B((Gty9H^)<-vkIEP_ zChaGR>7&Shfcjd`s~L1_0d-eI3#Hc3n{ag7b63;C8gGdO22pHi+>B;;#qJ-lT5*t!BTU z@L^PEnxN~^tbP{k+(O2u6rsQ0{P_EK0Q#ACEsC7G+lVGFWBET5ppU(W>rhjFDMnZ4 zAu)a2$V@RT=0NDUm_9ahds11Xv45BoL(z&{=UcO(!Fiv}OJg_76Ncx|O7kdx%~PWb?BJ;L9?zGhIp73G@%0u6s%U*tf{@{AR`T6V_)#hRmnd^6!7EJYoDneS2%`M{a&Dmw(^X zi17vZ`&hJxj5U0Va&Grv#{qwDqeJKq?lbl%XZvfx_`hs-91R$z#5r8rpqT%J{8cxk z(;cJLnw_8LXh+Mozj|Xfdc|o){4Us@K%)8k94&vMFW7$r#{cUItmv%nXYr36XB5vz z=s#=qt%+<(7W(eO>aUQ`dFnQFfN2iinIz8V?%B&os$D*+EM@u_2K?uo8QRq5$qrnY zk;D7}$X`XIyO9HBR|M-@V0`n1>q+yXcVX*;Z2d5tzaP>yWTo~E!S@rOe!9KcM10Eb zqeo}i{OtkqQ|%)CNz0}xL4QBw^KnmAy8fteeujMN8HW<>QJ>JWF04Nr&d>G{y=jHV z9^7vyo1dj%e*P75ki5U7jH#l&f`NZ*JRl{SJxfu{MDhAVq{a^7+E9w-7c+e%fZwE> zA>>E&N2Hy{<~Ikx@5q@^WVw118eY?d@r{J}SL$wU;h>Qbh3RQ?(OQtt`B_wBQMyB)Q-tU z=^YrqQs6)P>@KDQ8%J^Zk>dXItaK@{8zU3wE1chtzt*AJ*8Vso;@|#n!uToSg$o&7 zcLkmN$l?dcuk*p~^pJZHF22IPPY3yZr{h72+ucITwOD>1)^}T;Z%=1UT#Z)@6VFf8 z4cSN$(lb;&~VcwOn(61Ir8s+w9m`KP8w|fhWfnmWeDkc@iS6& zVE#Y~_kr)2BX4+(*|+xgS%`Xs{s?DgNG zWX?0|%~W@s73J6b&pEnnrU93;LY&|8M*4J{UJza}gz*da=bWEtMW#ob7U(Yl{J#33 zM<;&`#AEYVd?-aifAG-Fk+`SG1o>6SugVc?x->l(ODF!zp9uN&Z{^mZdI zESD+#tuVg-RP9G{hde_;(ac{!eg65hGi~u($S2(YP&#c7>GbLYy4#-Zp9J~z>^qN2 zf1k%ugV_2~$Y1faon+V1=P15A>yL5Zgz?Xn#t_mmrU8|{5a-kEN*rmky)~ZO$xxwR zLVc}^jit8H%3LRPaecLr=+mc7f%sHawkV%Fu0_f^kE=J!?UXLc=S6+__o=V<wX>w9~sZi2mTFGTU-%)df?UGk_0l^ogKY<=sw&noh! z{uZk5CeH8oXB&yy-$y7ip6MU-uf6W5P>XCY{LA>VD4(X9{^axK=K}u#^>g9sJ~Smd zOrW2T&u%9|$W)U?WNs|(A4>ZhQu8x=an!Aah|lkV`d4px{yu796{<>D$Ui?5PUwFl z_XZG^(pPBDotgY`$oJuoTgefxa+GvYk3U`w{6o!#z2v+~16ul;@eA{-mmVJ^iKgxG zui$q4`BEhGx1Apyr$;+!aTa-N75-PKuMTOkvi1FbnT;OYAj)rT@j3c4!;qU&F3#_g zwetPLoGxIU_#FQK;r_CjN34m->~n(n3-a5tP?z@a6NIhXGyeqpW1kOjB=ikB{Js0hThg9-DuSg5aGm${Le{2M4}0pl0O|N92H6W@8a1m8z21?yjqnd{K8 z^6$^|{`{WTR|%+3IYfDpNm0dUZW+@zsIR6z+liG!C8|6%4IrEC+NW;-K@-;c?y5rfD`s_Ut3sAA0?V{b(@DO#*a{6xxEe~A?S)={)c=% z-PVl;ecXkAO}Q${XT8js6l&dQ*1ulM>rP`z_TaD~EPsl@`Yq*lE6KixchE`2{0{wr zOB*kOpFcvkQ^onDK@!?!&oaEV;uh0a;7xVSQEk<91?m{3#0hW6QrE4D{8J+eB0{ z%aBpTQ2ux|;JZ!rda|Ru7?nIzRlHxJe|T~@gpB<510}jKzD7xPMr(K1z1A+gG#i`_GB$@4i3Qbi%KE zyh-B)|ND^d^Qq~wV!zJFvui(|FDVlC=f+#irKdwK;>eSV@dfly4VMj~_=A z&qv6=Y=Q&1^YE&GZ|EOBz0;vViM#NYyE0L}9paXgnQ1qWqpEm(*7}ng9Xs0(d!!dA z?q66xEg#@UGOKT+j|I#h!1}=TpITJ2F#sDcXkz*d^0VV-Y#^-;mo-~I7^f?tx=~IT ztKH`L$AJH1ef-E`lUFEfE8{;5?Y3+d_`MqS^VVz^!tWycdBw_FCHAa0EzjB zLV5iou3ri2{%tb<{2c(_d8fTd+0ar{+h-7e9P%CE=}C5|Jr?MFv^BJi*YOzkld2Hm{ja5+=w{i^Mek zIMi?TTPoB_x)t9JQ)1_X{_^dCjwCSnI?7UK{5ydBS$IJe?QCeyc^>Yp(0`%7kh(1= znd-NY`+wqm?_ScCo^}Yr8+HEqDWy-x^%PoZfvmo8P7M2 z?@ZTjBJJl?qMy?v`1=b3`L&a0wW&tzE1tesSpbdJ;ac6m8kZ@@EEs|8>D$B@~O5*r^V2V?a{Jpx0{+B z9~Qnj)H=(ED_F?7*TI$K{=JKib8LL1f$@=Hu|aCrb+LU1oHalTKMuOpvcm!kGM19-kn0N=g+y~+E@PtfP(Z2bj{52rs}NBY&5qTE!r zKMc$-@0%1z?pl0CMW6E6`vLx2|BEi2nYjnw-j>D2FW~on_kFUgJHO3>BJV2Rk5J!V ztNgDZ$}-2-Ibh2`I1e~xk7M&exj6nS-J z`U~~j(6kao2c$;r@&*H9g3^FOSg+pN;JKOc3s$|Lt8%`bBw-K)<0sA8NCT zIJ-SU=2z$Q=Z69PzS2RTeo76+y-zZJVgLHi8V_QeU5b|8Gv?3tfcy?wPj){n7w9we zC(@|(WXWLp{y4ur@Xy~8=ySU6ZW2HECu$hflK*|o3G;VuMe_b0?hCSbc3$!Rg!-Jg zIgP&ks>^L`?V;d97+-cajF#1Z`rWKPy9Au29p)HwrAcgmFR0HxH`8R5Q@fyF*B+vhy z`^@_j3Gm-8hc=Lg}^1_bn_d$N|{kIJy_-8c=s&3-n5A^57_oO8B$7?ja zTRDFm`jaimG4!2lNA9Alw}NjW|6?Yl(O2KPalswL`LF1;Pd4k71Wlt4MD<--dWPEn zGUhh65a-_@GEJ5-T&-FD!%tYy`ppCz)%}}ag!;byn>ER)rf6|F^A}Lx2W)ysT`x@L zROX2DUmCuI6nwdXynnFzBh>d8wJK_KVm4RXM!Y{`-YRGEbK(O*{TuSH(X}g0v)F^R z&3-7JkI=tg%WxyMmXDANW%_Li{7LIu8%de;IokD%9Vft_jO?OJzol)&4qFP$Sbk4f zf2oLAO_sebLq5N~d4BYOzOOW0Me5T^kw?k`{y2<3??rc`*#TjA%?-vstbd0FyOIV} zj8fZ*^Phf4pJv8IV9WpZA{M_2{kh?R6=d+B5;U}JPyYXdfd037=1ab%e?WN!jDM)_ z?k)Vt?Ya*rqxB1(Zz<4s9lIEMm+QoBnI+D*eb+Qv)JmVb+e@79XIG+RYl0=Hx%hO? z@iTNqhyL8Z?~_7(U%U9IOr?h!8s0&dzdj87x8AM3bawXyZ1zkM|A77fb=+*o+cQ^C zUREmqd?4S2%OBFtI#aoM0pffo9A8XYgx^Hprit@?P*amGT)i7lc)<2|fc~W-XE`b8 z{!p-f1M)qzVg(uZ^D&AZ$?7vu->=TxK+5xAM|k{*_(=y+VYY7`Gr8={gU))@s3EmWH94fA`$Z4eT5sbNGw66_x|-C z3FA-yG4k)%={-Tp*BRf?pXYVmKyvmxM`RJx_iB(oU;Iu=?9aVNxqm7|`LDXVlf12N zLrpv-j6j3{TKQh$-W4gR^1=7`Bqs9{Sx~3%Wh}rR=oku^1oAd zRMs;=9sT?M1?0cQb_*IY^a{?k6Zh{?<@3n+eFf;+Mfp7O|GuvP`QI7dm)_J%#7TB6 zeuDL%#WR+W@42^8&K&Xj<%@MH^u`o_?DSvmj;6yfrJVa)` zto{h&S5HrM>iH!Y_erop{PlzJQ(5dxUf+Er7(cmS{2aXEN^t69l)I3P59oioj$1|c zzp6mm$5{Sc0`fB-OV^W$Bjo)r2`oPY+f;1(1$AexSQu z^Z4VizEraFD7{wPotyGSe0((Cjg)QK(gJyWk%^9v$7b^HZ+82S`#wP2|9H@&vaX35 zXiKN={Qpb9{9qJZNS}ryt~O2F|KGKQB~I52@ap>DjQ=#i|Fp+Wqr0myCv{1 zy*s;+Wy{J?Os=xx{RrzvnKkQ4*tO@V$f<#U|B&AokL3MV#SLht$4mZr5a8FsDu4_M z_=z6aT@dBBSLdU2jaLs&H9(x-@4usD4H>OabNQLCZO+ip=>xgZoH)OJ7mv$cW^1FM zZiD#$hxMb-5rwqk7Ul{Lit~GKf(=0u`TmZ(7{5^8zdG2H?S=CEuOfd4{dxG&u2fYc z9FKKm-yeqi|BhTO@BcsjfBQqk^XpTC45;g|19;`Z!Tj}`a6*4RNY$MLXjBTmF97o| zKRdUhi@y8foOz1%Q6PSOw|^6PZSYpG|Edz$|2Jh&D_R}ygL5YpnlZkG{{7EJS7IGm zj#T4U^ZdZ|sj&x?Xx?mL{S@Zcbv`_Zhxzp*fu7{xxLRbH z*Qj{@!u6*o<@K{b*KcT2*em`x)bFVSb`qyKKhY$@{0&@x`fYY9ZL4g+rnjnpM?2I)0peDGL7SE zMvC))bdn7*54eGxUo!roez)&pPine66z~u0OU4725)YjcG&U)g|9{wDH74JXw)q*4 zHLi~1pC1AKWY=R?a%umQX1_1%KWHPFw(Bi2sABoYkHEiQ+uDVu{U?ua%`fu&LjMtI zD#%GM-?>`Lq z3%}vsWI_CEwAf}Ce;o4pa+-_0f4Tx$&Th>ghkRb08cI0tw%C_2e;x+(cUk9DdhNFX zmzpll*Jl(Vn_krtHP?R{+i;r3o*K+esSxK&XX`9-bNm(5$u5JxKIosX{4JnfOD1q0 zH|Fqs!}?9e=y^o{&Mg!_kL3p;U(vTTsg89x9yF#K|NC(Le`3fIa_P^5X7|sUHBya+ z745|yhckJ;p#I+b>qy=&c#I}p6zB8Ml%90PzIgn?X9PPR=x^_LE~MVL5_NjQ@*mJY ztK_KB$Fo9k`wmJxe^M;;&yE*;h$Q|4>K?R@zdy)tlS?P6r5TKqPvwj9>zU(DHda?7 zXG<^se8}&qoTX%P$5N!5JcB=;2I5O;mlfpL#HVPnzNzB4P(RNXI1`h0PmpRG#vk;z zKc)VpF7~&4&vgy{eCQ8i`v#C&cL`3(`^rB*nE&W@K8j2@+X+WWn7^n7^_#dWM`+Ep zo*WKj{3e0@FO%;^$<#fRo6YZyDmzX6ewuK~-NfrRVUDxN(vw%wgha-#6!=@xvNv_! zm4r+`8GHe~qS+h}$Zi~k_MV=f!g@RlnXDKws14>to&>sYZi7 zvHS>JA8`MyD&6F@7f<=xj`0h=zxBx5hxnjRg8hk40sWm(q(O`Q!m;kK^Xz=kf6{91 zO0ss+b3y(O_76^d+nG+5*Y9Ev=%D}2U#B?X`s#Ff|IPbDPnyl2V4oGF$GT@oRnecG z2K3jcqX!9Ts71ri4&dJ}tiK!88q-B~M{w_;D)Q3*#uO#1&y+CtEa{T$QzHd5q zC0SbV0u?`G{ev)m{O;jG@>*64;zwBjRGG4kw7b-ZBCOl;zn=^Ew>Ywch5O6>ToonrZfMi2{#%?mO_$gVwjsRndFXc0a}}& z@W+7f+%^TY&6&wuLyEY6ncTyM+#7Wdsq2XI9TxsT{(YLcT$KI@g})c_-GmpAPKzI+ zdxlB;^MUJYW|>sb*w+g=-*@8uS=X%`$k6rW^7Ykh{WR47<(HfZmHPvdD(+7vF4;sn z@A)G5zJUkO@1qhmdR`WWhYw}^5}@DR++E1CkY~svcnyF3F#o;wTsyjQZID2}(*VEQ z&N`DvrPTU1|8{eK@p9oL`UF6=VQ;A;^C~e{Jc#oIHq`S%NtV~fq_5Q~q5`mWx_nf&cnE%4uv?}6stM03MOH2>-!o==Sl!uZgwLQ3-A z{6y1^J>!oG*C{l^xg(3=Mp?_aoo{kW(Kn)7Hem$pN^zWLDEo~&tK zfv(PG{6l?z(ZZQHoqdK3#xwrIK>hOWW>tCqE(~8i*VgQR@85wF`tzqwK4iu8MwH{v z)`!FTewTs{w0z@ktTK|Ve}vy(oPeFl{DxFrUaQd^nGx8e;wXPU^hde!`kcSpvu4Lnmitvj6ysmm-!gW-BUzhVh2nFW|A+O@wdvY4A>jaip`yy45A)kq z4$DZz>1veyiLGCN{(nTyCbHM<8>%18_=okK`$yZ+kqd%x&KJb`Q=_Bh-*+{+!1$J6;rwtR+L?qjK1X>^SpFQ& z4;}qINN(qPw53GxeKFvF+RFDw{kTbjlls*1?+4}&JM@jFGs?9%?*pC+{S@}UsN6`Q z`7$GJLJfIoAtIT}O{+^S>~^{wTnK z+z5P%zOLQN|Nkj4e>9xhNQ`HE7sS7?f8flUHDXx-+}YP)M_p2_#*~e)QS72p26x=EhHKnHZlFjK>sHX zbRo|3Ymr?F>wi%N{^><`HCmz*g{@P>$H&kQD@fm=ZxF6m;h!JO9}PUchAh(ffZpBy zq~KrZpDLoalfp%Rk>#$Z{Bf8+>KGnH9anYb3_q+_@GBf2<{l|@YF1ya{F3#K?!&kI_(%fdN9;bcP3wae4Gh2C*NFdB12O}`~b#B$E9VI?K zj@_I~B()FF;R2RlhxMf!+yg2xn9mhxk5t^BFn-wl-G<~1EJ0gK*!Y0?qd$SV^wRAF z{9?~t(ebfmlLMKjBwzn7W%CF0Pl?(~$cMm6G-WQ^p9RLhY92bYEbe>gt6bYD*@u)KaahQ+^yV15W(=}5Z&eTG6tF#U&oe>2vgH^%J8 z(NE?f{{JPy{+La@-N?7EuTha1tB=C|$G9#U^iS7oKxSbgze~F+#k5OwH#k zol`ZAQ`QsrPa~9V2resWc79Mgu0?JB#^Uex?EAhj|DQYAj{NnmMx}vleh35kp$%gf zlQ;9K(BIp;`0Gyt`rqN57X3Xj4i6tu>Ok^7~r`dXn#^-vr;chWyv7w4*_f_uxa< znSYXi_VEl0SgCoIHUZ9Zi ztbStx=8ubGy3oV6(Rk1z@$qwH?s9VV)+@9ziuo%zek}T}Cu;^bqEknI^8Ca2p?;b# z$?C0yO^V*~$6@@PrSDJlRFrXZ>qqAL9H#yH_T!Sju2SePsLwh^$?kq^e*B~wY0R39l#L*Z2Z9W zC)q&`&R8Y%e@)e8G3viQUR)F;Y*`Vpgt%GlDF_4i0Y{;I{W!_;1>Kj-mWeEftfN6L)c zI|}l*aQ;c|aheW%HjbO%w^T9yg!^-54l*Z(Q|>l9egf}n(2#C%I3#>Adw!rkF{jXy z%o+O#4fAC44;(+=MrqK?n__XzMm_#~SikGrc^=t)qa3CFV(~j1KS{^bsCr2ZUOGd( zKW(ki64Gr#4NCp_uYRB;7@rGkmkl=Hlx;%$L3$r@v~C?{$PCGKd6aFX81NczbKn7C#l!pplU4}_IyBn zxzf&#Oy2z*#ac7|C1CytU8YWd95{fzrZE2D{LyKIBUu_$i~Kd&{NVuRk6>RTI!Pwy zUroF|ciCV$sXF!s{pu~=-{Vrfn&1x&g7vd-{#f~98`<`%C3Z4l`CC=M|IlndQs~$Q zTV7!LhynjrjmflMd4JBXQk?%&QIWFgTAdNmtGL9^zaai_YbWo&7;VaZejv{OgU9CN z=$;~!-aV7?4d)N*E7acKqS^REN5zt~RWE6Fe}poL25q$}4(kOm{^9)b?t?9vx4ug7 zeLWa|*qtw>ea0>4esvVj-%bu+M83|dK||A7ehKymeU|h0X}TYlw4Hd7`4eG$K3sJX z`Ed0aI=P?uvqIp{Vs|%?)_PK0f5gI!j}L%9+b&y4Om{aR+?mDq(4QHGuOSO|eM3Qu zng3D({r#aTtB6Wv1ImkF`>z-P{=KX0$oP9N(Ug=SiuWVzuQ+;LjrtkH;%nW-`OhzM zBrQJHp;}M&{9*m={Pktzr#!wWdCKa`P~YR{tRtpgO~~`VU%dZ;@rC{&A5wp~1(v)o z<&VSoV&|*?l0B#cZrFE?KMwozu#Q6@bzf2>XXLH`2#N+G44YP^ky%NFx%uwH#yWFRTp4f3U z<>K*m;96T!Zv9lSJ_UpQ6XtCzr3cqIbHnw;`M!|3i1e>`juvzi*Y{BMMZ|ODb9D5T zIKLj1Ylz0mALzDa7|##%KgW)(AyxzDiif+^0*_|?jrLyu)c7tmjUhSa14*E2t{ms3hM{6W;l}HZ^lV^UNqtlimJKI^9lXQ&awzPs;wRu zA&(Q-_!s7f!uuuDAx{5sFKos6?XNDcuU%C~MeCb*eU<=zdzNI=Ax98**;bt2{>A2G z*V>0@>QlzA3DD;`Jv8X6+ysF?f$PJ223e5CRgck_7vlRjWuW`C%+Z1SPj!^y{)GPC zcd|7(8dr&|x-fqN`E7Xhm^$xqX|}$6dDJ3OtoagI{AKzK{k>VB9nndxL+>clPpH4f zV?Pt4R4Fc)GsoT`;b<6rUd zC)rDRe9m2^A8Lusx3KJ4h|%Hmt-@3&81Mm~9e5afR>!ThizdJQ>y>laFy#`d>K0(`%& zUrVxW|Dv>H#y9lu#*bRl_=TbPVjWwb1N$o;eQZrV?ZU8i`Z~rJ_F5@oxi0gZ8{#>H{whBeH z70=)Fo3)r^*}g`N72^4s#RGp6vjsu8S}TX~ClUJVR(Z?F?6sfJ>@1eQhy3+g?@kP> zexM!3O#h)jshQn{Y8Av|&nVXaDUk@*kLZ7KCzsrsP}RL{{PTtR{}#%vC>gxBS^e%X zXCpcLr4=^Yw}C$&^4BY0k6M@=!zPI3HyyzGzeAoYNtCE(_Fsg2Tl|S7pZE2_1uIn8^?~>_ebsc* zb3zHaX2$f@68IDM#jR-;3ByWjNAu?=f&5A8HVg9SK}ECiBl=QAcV;+oSvyDC`dk8@!g>_$I-(npl5PF7Pj|BjoE}w}j#; zTd%V70spo+t4ZCczes(UFaLbu`qx{7ThP<}h5gSkKbc^@f!NJe!jpD+^XEhUy)(7x z+#g4<$Dsx2fBdQf{x?*5kW)7$IHGYje||N{Pkxv0@AL zRHYanp#C-e$Z8V3QG)mTu<-%wUm;Qn4O%W7A27c4lCQu1G`|%d>9v->e+>M|%dl=V zVcv24U*kgbzwuEG^7j^0n@YzX#Ytv+`QtD@Unj4Rs|UVE#VJhxVSRW_I|KS;+DV+H zm902msQ>Zxj%0cDXQXA!>RXWiznZJa3b{VSycW;T*EFpr^+zT6pZ=SG{NzdfSW?hv zgq1Qn@b?e%^EZ1;AZNzjM_xMF{BaoH5{GPh_U&XY@s^Wf{0RA8)z7Lj8YO=RsbcY>EH%HxvT>?=`m-y&DzQEZ+h1-AKl#U&wX%7XJF7zs@LaL3KWc z2>cJ!|D4I5BsEkCmsc?TfqW}J`%79E?ZE|Bvym9zkF2(nqTKd4D$Irdf0&=2YpF$l z$&O&DRsQ+4-PtoLZh` zJgYC3#(75-$uk}A%~3+DAvA`!;7D+@5$+x0%Wc#O>taQtYPX49{#Q@MP} zas}VQ@#B7M8ae#2OpxD%^TWF;8U1hZJZ|5c+5Gu1ewZ(@AcN|kHrqd8|GphP{3!{zwgI&&-1*`^E}VE!qB}*nM6OL`QdJ_$Kvr( zs_>;Kh20vKRHK=SDhL-%0TbyXj)>Hky-R~&O>{=<& z@8byn@8~}SpZ}hTCE+(f^vxLa0-=jbFU2xv<@US(elN^i@mN07es|6Lk=BP695^IA6X%l|8~0Rd zzhT~~k6Q`!gzd z{}ulhWGrT_oJIwWaYJU+h86U=I!KjhSDd+FYt)lSJol5z{Si73_()mvnEzAYI?c2e1gYy5kj@b~j^!qL^8_fSN z>BN3D4D5ybSMs3{Z_EGs9~nsh-#6Dr;9$oJd8}}U*(c4v7Uzz}LlaeCNbyOf_FZ^w zG0y3319$vh^5dlbZSuRh_`IVreEGD19jEotKe_`p2)ZqAcA5Xbp|A_Yg zSULZ(+1(p6^`FW2r|)6!&zQu|v%2dF*M@F@sc(9++(wee8&!UoYsGS zZmTQQ_uBwbHSs&GKe#XUpZzv^FXrF*d>m^3R(I|QKP<=BI^X-n`%qkd>5HU)fa?35 zFB=J)_H2RbZoEF0@~35;gYm?XPx1wg7qk1P__?V%2GeZS!16k`f69-#boh?l#r^Bj zw_SAmYag_KpmfeiTv|^B7R1ix?}y~KQqnbr9^KbU{@;`zdE3uKm3?}!rjqNIv4sC8 z+RB90kHr4WEamtr)C$L$1{Ly5>vrt=6klm--|_9hC6IqAUe4`Xst>LE8G#QytK>~0 zxxP>J&2M%V!mt-va4Ax`K6EuP5_=R^$;)1lS(H*&_VLrcqf-fJ#eBtfZ-iopr%JJnpvo|hp^;~`fIlgHAEU9rn z)QuMVFKXrw()eOQw;RF}pD~K`7M*JNmo&cUEcWj#&wDTLutj-%G3DwVL3Po8il|r0 z`!BnzhND+PrDXm$#m~I9`ht4$Ch!?_p(cMQ)mM#f1mTc_W%B3x96yx*w96lZ&HJgt zzxjkTKeoEs1;GNFNuxcr{e>z`q z+R{k$8dEJ_uz>3m)c(in)DyPd$_JYb%jMkur1oz#Bph2;RLZv}@%o)u5+59uSqmN7 z=fbtf-8Ji_@$rnw5$MqBt6aNSjom+ukH4O*CrsH|0RG0x?SE)~IPUPOl4o`0{)Nsb z>@|Bdw$M|P*gxe@>4J@L+I0`~?DCvlpW44y^(Miryq)3(D9?Y{MaZ$V(Or4rFy;Q` z+aoPus8}C8cmJ%K^GoA{JHEZK;g&+VnhIY}?f=&=FH}4#l6!pO^=s6BXnwyg2q(rW zO#3Rgf7inSXl_zg>wM)&0e1xNvlA4yH6w4|3F&;b z759H&e)r|@W*whjMf-1TW2WHA=epoNp6AE1NdEzD7U#zY=1KeujSreP7=cYqRAEg) zH2Z$Z1Yai{$Kbdx>hN=*H#;6j_}Rxb-!S&;QZRnN{RizoIQu#br;GNVI+){!`j0x> z?1gC#2cX~{*O#cidfGP}JLi6tJHAzA*QfDygRk`j%{Kes?JSO;IJwk+OzRqn!wbL3 zv)=IfAP3?<4hW+#VWk>)M)LTB)>pTQu@(v|cEgLtPucZpecawfahNmC7%n`E{d2A^E|5JWuwoXgXpS}Uy)0N{VWkqk)ob*z@MNp2P8Lc!0zq{*Twu!vv z{Yd9G4;<-@0j4FA{xyoPtGhIWecjf9%#!pp@`Q4HP0tyDt9z(H(jU&>Xnt?5 zN+m}1BKj?<&$t{v0p~8$k>r=-2)>FR{Kj9uQlKz{`!5;k|9LxmIBr>^3a0fv+4rUW z&z-Zsq2JGCkW|j`NA=x4qW=iL`c2aROy_e2mPO*)5kDpM)zm*-xos!>7;^yTPPrrJ z|1T-NJ|7B0*W7A((ZSp7`vJk%{P0nD9n@>ZSJuurytu*y{>=xa`jyMRI8@tg0!c1& zmEvotx*R*@-mf+ONt~i71a{m2ny;qU;8*IORQ!9R`4N$Sy-<#?FD{xwhm!S>y`ST& zkmL^^ZTCjq&u`_sZ|-F0r})~sE&v;ME|-^$-o}no{OoLgTY%G(6#K?0$B$xG5IT;l zl=Sz|_`mm`CW6QE)6mOBIerdkhoHUKzw@vElg2j}b~Y4RWS<1*e%%;;=>CbvW)8v) z%Vf~UA(7ob&3|kS9EGk8HQ--;Ddlh3m0$7OSE>F>{m<@!!?4vAvHs#qBtJiBOZ3qO z*M6bppcODOz6Kv8ztP+#0x$jgA(@YkB>&f>LpZLf_%6|RX@0v)awJ|T_$9G_>RGZACiUca+~T49g^%+1rF)!)@Kt>S=q68P??0W? zhrIsO3%h0%N&FAZuP;v%>r(Au;f{N8f@3kqrcvaeMDhP17y zb^c<9kGF(dm6H|K@yhX`u{;!u6TVC07mANrQ`ChESJy$@^?1hLsD7K#E*L-JS9wk; z=T8?%{-ko&5Db{B3NVz%Cp7-Qqb(B@sjDDS&gZMs`aUhAp}6|KDr~wijlCbr&l=VL zhCT_>{cmafe}3b1Or2{4SwrL5dg?zEv&8*3rmux|jsxWU|19l)`%(~v$9l?O`sS`| zJrMrplvs_!nbV*P{9JpX=OkZ{@>UqwgI3%?C5Ty8G*_-Rj#J|{W?~j@FKgth1QI4-i;TnS1 zyAAN}3FmJ}^yT{M0T`WKDGytu-2apfQx_c0t%pGiSJeDJr1Lojp9{yV2fyVFZPJ8gTvPAa^sY~=RWK9SVVT2)75${Q89K9KttB>Hsm z=K6wd$Z^Ou+R4^aeC-kEceQuYfPeK@RG5KRC1UEWchnLR5}MchB3-I@J0>!tY773ZG&%Vn_7^9lQYG`<;ny&Q*!EQ7Qa*V%d*Nd3>< zPGbJnMN`7hsD7}@d?tPjF@bg+3fTE6e$0Dl2tTiEfMb_y_&te#`Zn!`=Q1A3pUqSr z|Ad-r3d>J#garp@F#DnPCzl`g!hXx%i1YC|eyD!n-0_ewYIKOgC9MWOWWLj-3~zih z{-ZoZgX4$tv&+-`QG0Eb#Q#u!w#zjFqvpt9!guBNKl!biu(ss}D9esx{-u!AzaEYY z#ppA?KA+N)ez2jZ-mN^ z>)HKN{}Yth32zJc z{X$MqkYajcPwsyRezs2YM*pXu zRn>(KL1~a~mB8>v^|`HM!?EPG z491OL!QLO$=X^hZz|;dvp!$11H_o4=^)Wq~h2w`~BL1T|{%HK8=%^xm{*ww%ckueJ zbdo=vrx%Sr#%hq4!t?LcKgo)!ag*mtcz0DfzHSGFVU+lPKbO>j-9Oc@^S8 zeD6&3X?6c9{Bt}77FuxpQ2+CLbQnJCBZJ-RIe$nc{O$QC8{x^FgW%qU^EV*)N&Xgv zOEuI$J&xxuDSx}Wc_cn%B>AtU(kakCVXllDPG z^f-2YIzR1`t~bKdGP%7I#|Mpn^jlmPvVKfeT&dGVDLxuHiu1$MzsrN)as8X-KR2v! z5WZhN2@_4fvgfDs3x>Ky;oy;Kus|=f#y+I=V^Ajw!~3g&Z3^!Xp!P2$e#9|VOChAY zm)l?ar~3omZ9fdJsA@sdQm(&M6MptR`YRTBt%M#PJpW1c>As&Ma6-B&xC|f9?k|=2 zC*RM1@XF*=i9Q`m<_FGS6N7sn>%z73W7v8m{;6k^P<#_8YQ|k$Yo1@)pXwfOD5U+_ z2^MX5e`+C_4`nCTKdQ}Bfq(nsQ2fkj^%d{5TnRaIIDV);eM8KjHJz*i|N2*{|5{dyQNw~RqQ!-e#+lw-(7^~#yW!8rS0rE#aDtwhs=ep z-}gf7o@VU)w7$UUlRsW;_EX-fA+JxM{O)axnNT^b0FLGJ`Z_v)t#3>e?w_a*r}lDu z(fCJuaulXdSBJ1+YuNQEzsvm4KGdDdl&%@5KE_HtN92G|msrh(28sX({;q z+z+LH@)$lTzGh7f!Gt?9Xi_nfU7zy59)`bg?PV$d^C9?}v2+Al4b_2j+lRCDg#=#? zT|>~bKn6Y|+q2`;|JX!*73)t{K})N-^1t?-PVjZoBMehMs=$&HygrBG>(#ml3<*{P zk7e35=a=r^Ga=hjcoT2{W<28Y3*~Pruc9$DNCUcV=kq_0;F^}G@%-QZ zArwEE%SNJ~ims&onAQ)(nomQg*gDW`=N^U+nL=8B-(+JKJU8>He6^MG_$IhIN6;KM zP?2#}IX+Ui^}_w5K1lFE=Xb7rv`@Hb5~c`vs2m@rPrcA`#TR+6B<1*sNUA41OFaRq z!90GABl^IMcz<+p{3So5r5qpM9-9j1lk#DS_C@~uq<(U}do=2x2Dqwo|3&NT|Ns7^ zU=*h4)N?cYzEpo3FCf0p*2ScQuFLq}|c6xS^^_A8BlF7_Aa zs|2WlU2h)$#1a11PBj{Lr)og25Wc@v6w%kT#J=&D^$jHT#nk?>{Y1?5GXecW+&>r- z``_|=y|8|AS4Gr!QAhZTFB1P>KhzmlK6@%x@!|EAG=3ScnIpL64pda!Rz9C?iA^uu z;{Q?J{WRxi6d&I;_X%g`hbh)OE5}FUDgAKv#|nAnan8?-$$Z-i9b4hH#tA6h)rr{$ z&40c~@JGe{-}14uI6mS?e^=f`ec`8K7mUi?$MGSP#xK*v`AKrQ2F&`jm7Sl)FIoEr zVN9YH=q}*;3FT*BRn9S&Q>SKWMz74TfC+&}oZe8t6e*TD6z-2UT; ze~`tD!mOV9ux}}^PfG`B{pOP_72!YzJZr{?~o{$s%E za-8vUCCs-!z}FN0HS3o6e36=9{9HLcv=0{uFW-eIHr*L1a=`x!?1_HXynG}M{G|ul z9eMonKl;FoN%+vb4p=#4Gy9ie_b(&(S<$^K-c!7g)HhT7SXAs1 zj{NdftZ1v;zf?K&!pibb@?G6I|DyOAci&pDN;w8@rqkH<-(XEv5FRGt8 zINJ-M&Zl8eCq>PAX?~~EVSnsDR0bbfX0hXxe|_FpPuLqGfb3@(dq1>3Up+MfH@>PJ zKk6Ms{#B$29sz6F`DuPr1I7NmJ8K}IxU(Doe$x1Ua%v=wovR6JH*x*hitw))rC-o& z@+yd%SW}-*;`#EmKoCxltHMlyHM|a>_|MYR1>Nb^w@f5;$J>ZDaY|wR)M|;#}}=?G0TX;kBzk8!C>Y5 ztf*OmV3QZBc(+nHz5+srVR(Tq+;QafIaHs1)3iW%u{%^DOi!%Ar&NDy*5W_hre+EW zQCvTu{B7{>eBsB`P{owyX>2`!okYKTW?3LCP7PIj3d^fGZZA3BWp!8F(&&|Z-MxJF zekeZcX}rOMn#Vwqw4lO4IX>staTMxVT!7@CJ(+)_^Hq9!MPaA=S`fRB z=VvHBPc|&W5eHX-<8(eh5ePn83qcstKn<>~;_(sfPt!4FBlg{-xFJ(-WV|5O;}W@tcBeI7r>5`0z-j>Ms!T5!yV>kBkKN;;J<#BU8# zn9Wj-zZloyc&d@UM8Bi_F#3AFFmG>|!ez2@{9Qe-xzvI6cOss1-8E*v}j)P%?l9G_I5`1z+mc(Wr?QMT$IzmVcHMLQfd z^EF}qy;bb~9+3Kn@oM#i6vNX1E9WzO()u9tIYV)SOdq~<=J{W$4~91QhE4(NAtsQ= zXB3|XDPn!#D>aFJLFXUEOqU5w+%`-6ClG#GZXJnTe`$f+GtN(e;P>UH-+1ENM$owG z!|_A<+sv|p@cCyoaDK!2E6rcs9ybWh%ypq;Ycu}+2tIWOgocIc6woRO;2*Ka`r8FBF%DE0(7y$6w<*<8YAZ z|0>>WR*FBXclm-t-w4H?jmq&i_M@7RwQ?)Wvfsd-uaNN5In(n6S!xfZab5|G4^H0FKF4gOX3&KT>|WeWaG)|0@d;J+`s;NB3vjq8X0b z3$(y*4#yvj?{>{I6O0xehO{;f*m|mev^5UHn0K16+Lhz4gy66F+YflO-709-w3nMQ z{<>>p7-DxV_;7y#dp>Q#UmG>}imkQR!*eZO-%9cKq+kg8M(D%u`Mke~@>eadaD0@n z1sS7)*!d|xt-IwHrq$mBfoU9HbpC)>Y7m||tPZ9_mFx4z{KWa?LD~@3s3AK)&Hp-R z$%NZGH^Z;-JpL;r^%EHbL$J%3Cn2{BZi_9J zYgH@vPdUCe!mx&?V3ENVww})4#)h6KoGh34C(0jnt*)a-YCOalmDbp=6hFq7y>PP2 zPkFP}x$OKDKV6<^3X_KIgj4r9ehLYGZU*>bpt~y6rmqiO7mk=QgungkX7`TGM>f4aYwCtmQXtW_Uhd*Tu9ey|7} zjWyZ(q50XMATP{r^-Dg~Sh;<7GSCt%^0Oh}GUsR1KP=quhq+~HknOsYouBG|_)JsC zoRkgs>Tv&%PW15+V*T;VXq{T^|MnG4;b25II1f6)?Vr>SS=dHl^DcUD*oW(b)c&jc z>kHdP=fl3rN~Q5r(1LKRUa15A^SQp!g7}B|mxp52Q$u*)XD)lbJd&SPuZ+ajj(Tt> zB7z;K`ro&;Vt%x58u-rWFK7Q(!mqY92*-zhI`D7*1-gIjyXn7hxluZ-?U2CMM=7NJ zcX9F%jGv(e-#r}I^(j8?i2Z+U6( zUtA2y_j&v%Bl_Rh9bTC3^hbX74abj+=;zw*4#K%sS0HZ$kDua*f2g66!kds?B7TlB{G=27teX~w_NW79 zFIKbfPxbXgqYxbBq77b?=dPz|?sDCN$C*o^`9z0R&UUPra`i1$8eqiX5&2a3>Jo#UIB@=vXc^8NsZfZhp{n-O{ z|HjgrTO|C+nAFc*auoHEN=;ZYS)E;<)^Gd%&==}O?S-)T3+(!|{zuI(9J9T2A;?g< zzA$F`NVKyvg+|-2aQ;E+fBy3thp(TQgX;0E?077}$C5Vl(DjfLG}*kC9S6dn1`qCx zgT(zYj<4kWiTW4gE(XHjvVBlexRgB~tuM{|;epy;t0eVt6d&C(yl`Qx4DJu&`Kv-u zl{m0Z4Q+(wxo5#JzB7M+#QtBl_d}0h4S2VV`wzN5?#sqiIAzpEhhm6Mf9)rh>~HnRF&KL!X@g32 z0$We}vnOZ%Lh#6dGeNw*jn2Qc)EkPu6~-V8Qtm&7e~LuaFZwX`tn&P6b^kB;wRAlc zCwR;M-XGPsLz0K!>CZ;6pp6&1zjVT{Vh&bg+d7-!ZUo0i9KpxLgdogppbcwY^ZJ8W z62Ff-_YN=Ut^tc5>)7>ad@nT2rV?$9} zTNg@W3fcFi^>GD{MxsY#9mrb5_cx>dW0vCtTsz1bHciQ4>nT1|rzBubd}BCdw~-yE z{$o<(&gdTYPNIKNdN||4B(jhO!j`LKHd96IWG7h z%^yXP{88J6QRx1~0Ag=NvGtUn3D#q&aRfgqX+LrHnhdZDNRa=%f6Bk! zZ4N}QA=(h-$ng_J@Uzk-039c5!N2}&9}<60-KHnZ|FIX2UgG$m^*hHJi~c=d7rgdx ze8>pD>NtNGHnlN@fDg*^tD2oAA?~RQ1uOH}_oMN5Wo!a&k81+Y3OPRFi2qnz*a@}M z-b?Z~6dx&QDU{isgQ|)so1>dNF!;bXdH5^NuL?>2Moa5CI`)Xzbun}Iay8xX>@ca(NN67$R>=v&HapRTaN@p{#!mjnb?1?j}h3-!4OpL@%V%Cr!Gg{Ve{&>Fr;2@X8$yQlX@@+ z8|v$VZn$!OrMppAnDBHjd>MDRX1#^Pzs^$)!_n>a!8C3XyML+=Ul~({L$*uxVI=zS zouUZTu`!g??*P$Oj=_Ec08ytX_6SSd3;PDCdFTL062_;SULxPHO{#9B(6jd_x;NN^T zik}l6!?5FLQ}{O@pVlWd>@yCHo?5|@c;)py-8#?5!}-l1b(iw^-fed$9KWHo*7)Sv ztNXY#cnN&>teDCqFJ6_fNE`RLK@k9C7xXI7(!JcI3ddh%(|Nn{ahk1$fLsjAA z6kdNv{maH*1JPGSt5$q0Uiub&R8k=^X#o3wP<^-C!$ADnUKgTHas1Hww(m|+7`?{` z;%fFE%_96O^2b}e*gF+ME^vILlm0goF@C%jSO?VitYFWVMe3`MdxT>C6n%&gCbHvH zpEc zL%0yg;}hyXnwx#b9o1=){vIIuR-h~x3#xU&GoU`Ze_G#@Q0|ZaRf_cw8@c^c|DpI^ zj)5;Xf&Iio?EWafT6`!J>z>h<#2++1H_IK4`8&*@U?h(}d`SH9ENL7reP9jA7j`K1 zA48@+!LrEZaOlifcK>vK=1GH2_`TnUTH}w2uW#Z#&qa{9umxLBH~npClh85 z#ONhjVByF82i3P)cdRcYXxstAu{=Jc_y`UR#QA4*CH{rtL*3j;82R!%^fGW~@0aF3 z0>%EyCu@ws{yonx#S#2Gne!e$^jr`7z?1n0ntyB`J_Pee)sf7X$|Lw`J=j<%-gz8M zAMIu9Y5pS$Loh(wK+>N>@ik*cIks6X^)GaOfxl}oZdKKX7WV`A_a*o$TpNWe-WtQq zm|pBSjbElZRNz@v@t=UaK2ApPGj>oA7EjUx7j2FoTEFw#s|uqhZh_%rHp&0;w^$P2 z51SHz7hCJXzxiuaKlWHziQ3=NAu0MWTTk)zwpj?8Zqo;|b}!iX1H#W<7LCAHF&1#l z`35^4Mex9ESqGr96pT*mBNB15-YxOUEdOyd@wkx4p$GB#_6kpvey>On`pRvk>6`oV_e=QK;ogxL|IN5o|DvcU#WZ;u zOup$}W8c#Hwxj_=aA1HL9CYUXC6VBx__kQz|Jy*quc-YmPYp!HT|IC;?#JH`vF~;Z zKVpT~M#yQw<99kgcDPm;-nwiEF8dU0eIkiJoR0b9)it^Rx%Jp_B=w)hUq9f6(loen zVT1gyeLEBTJ`)yz%~kclr$5iX)B5MDhbwT#_$~0kmD@MXk2F{ujPo50B=JWSv2Ts` zqp-S%6|`%|=dV%!fngQcyRCTsXP?;p$z;;{vn@A9qjj*gr2d8Kzn2}K;_aLin4K`5 zJwJ`#ZQgdkxhFnK>OX0G($cdSAMQU{Wb+)`$rGBUrzzuX69uG%1s$YR&0{^M$=N_-$>Kzj2yzMkYq2Gk40CZYO} z?9JnITEF5d#@F42O^}|D&*Bpx_^=Z58%wf{!AEaByFTS#+m4i?wcbWJGfp`^QdWdw zdWaG1y}F34r}%h0*Gzb{<}5hx+QaY_N9xNQ2Zo|oYa?jVatd3YO7bU5&ws#=C#Cu@ z$t&(_oU{n&>Om?r8QOB!%|QGM)3ax~5yR0mE(_GRm7{;_;oAWmGT z4~tEH>&F~lRR3!A%^&xzk>ZQ`k3GH>Xw^6a)VpzfQUB4!B@jD} z)Q3{xG5h`$Us_YYVCOgKV48bd{ukeIa_M}6RojMQg@XlbI(3Pyr~25^4l$^|#73eY z`w;)qIXe!IoM-|o)~sUdseatKxC1r{DUZ zCm%Ffs|}XrJJ|Ut{tiy4!~pe7NQ#SR>yhA3(>eeb`~{ZM>$>G%OBkKY7QmK+-$Jzl&2+bdyA$VUH2%;0F6wKq4PaOS&%e?5|HSw& zsP$tD9NWa>AF7{ebO^@yqlVD+2j^!LU%l;K;BWaFaBX@?{uf_#{)fHp5ZrBK0hgNc z`8kxo#fkHEcLdahx#c`RL-YTW8q7!M^42iyKF@y_68^UTjVlgVR3`72Si_%4{(qDH zVmw^G6UZL_%YR7u+xkFv++!qzfBipHAMkrpj_E(Pg6wun_I;4(&(q_3WB1SMVB*2` zHOk)-57`Na?e2lBVIQ_$M&hFuOZsC|BOP!*q#R!!NdfrgmI3U};QouoKhu}JM;qTw zAZr=J@I&ic)}=&Xbl*BK)*+2upVnUn&v}QT>o-E_VGp;z-w%m?pufo<%i9=0=NyiY zbb_yRkN0@qVH0S)RNlWZ#VHzn_03`V`*?PJApYxR_9t|4*ix&$uz6t+erst2lh^Y4 zFp95$`vEvw%Mfn$@50Vc^@Hhme_{Xg*>EUwzWnd=QT<@(5I^h^rVs5FaDGVpM`IoY zU{h^Fh}*9`Khq6A;mKB8K!5W=c7BSVnG-^BS#uNcJ6yv4j}C^LsAKJsQZ(P5o`1w-qij6Bj zOXg2e{x{ujG5YrC3_l;tVArSln++=NxM*qZ_}OUr24k9}L6r)Bzf@n#UDzA__iKRD zN#*!)55It|Z5D#5D)&!RUsyM_Kh8a`1M$Yn`C+PQ04DV_gl!8reklL@InzqezjzHw z+j#NklS%8B6W531#>sUg@e$2`&JB8tNA_-n2Szpe0m;vJREMH!kSW;ASj_B``lszz z-{YM@nzexnM>+tq6mH#Pb$MDD>Eecq5i3NP%ti8Yz(9Fd49%$#8x!`cg!OP}(Hy1t*>KMv$2l2F>Sri^{I~g`!q)(tn=6l>6w5;} zBgzDZjCsS}Kdp}}y!-;kElh>48kadfWK#ZS_%#~$Ot65terMTw%HR4t9gaz}Z6GF@ z=VvH?8y}sBYZ6>Rd-h(wUM}7L!@$%Phqn15|E~x4FBBhr$`|9~#I8_1g7Y7W51r!* zJkdY}{^f7dN&e=7!!bNlF&iqL^82Uw2piWMtHx`>_`00GQT^@XxmVcZ`g$;JcA4Kl z@h|?9`(x@lvA=l%#|N#CIb3vJod3EIaO+uC-$MIyJOcf2VU+>c{^t29n%^mkevAL* zi2g^rty2EB>2NUa&M|>kxR%*J&F}14Q-a~5{}_}}gCChxU)bszj-F;_@NfT2s=pO) zdXMA9{x!1z?tf_fWalvwI}EmkTSJoA^%Dtx>brixran^tL+fi4dH>;`7mhH`mixb0 zf}c2ej}cXy;n|mdHTaO~+tv|*xI^CNAcy+%^%HH8^X&fdv<>mKiyLN@#{51 zcp_8oe{!FG#-#a~VDO#uw{+5fIyyEOJ54u%ytLQMK4^V_+nY$N{AdnSmkR87D$&;l zjvs=W#@1qg9j}j}`0?qtN?0D+S8;61aOC_?il1KV+G9fVa=Dt5a{RRTZ!tcw=?33V z{EOeE{H$?yH=GszTe5#Fo$v8xYcI^cqAAI5Qhc24`U*#h^RLtOI6kQVSoYBy$2QZe zRbS9AJC9+Bi7>+WqEdX!zT%6Piw(i#CC3N#FI8fG#;9pJfc9Xe__#YQ6lKrrz_*56 zU!eK_Rbw=T=&(cJ@<`2%yX!95)&3%fc5~6AKJgx zeYe>E;BEt9FH#x4XnfPtd>#hRX#+X>8SFUK=c2vaqxaB?TK$jTaC2eaf@?6c71w{M z|EYT26-`wB$e%~#vgfDx@iIP&$0x=?Qe*Ca=>BO7?8W&yL0Ygrp7S$`uQK0yg890K zQ23xXKR@w5!yEO-51?ObeRKDp=kVtRasOF&<^D&vsV}xRG=kqdmE-GS%R{*J#Y{*% zTgK{>WrV+FiT!J3JuN`%F^_*}{-;I964X#h2k%)uIKD{yvJ}pl_Xlw+Ip(l*c#qjQivLZ~Bt@PMZHo|IZgE8yZXUKh*!+EP9JSO*0_w>O7_TKZ-Uj!eI$3$Vyxjeuv`Y+PC*OZc**{$XNCk$KBfkS+A7yui)wctX^m;=?|d%D@BYy z&KQ{2YX7Q>-(ag4Q4@d6>uczI&|IG&ESy#ces9ySd4JORATAE?acNlwIIlb)|Lec0 zKA?Ft5RV(zk<4d{CHN`*^Z{MoWy0@Yx7d0h^Fb8GL-5g&y3ny7ukWP(r|I%R=$&H& z0lsUPeNy~58qUSFZZ6>6IK9SxrToomYrl^TV9KDWvt!d7%R_!o^tPUub;ekaz&6te6E(?|Aca3hhu}enV{V*ZOY7G< zTnNM8$(As~Esm|H`r6fYn!<&+qZ0o@^F#aU55pEM?O<|$UjIhx*E+QiMjKsoNqr98 z|GfO$J8boID`cLGm-G9R_SZbL4@9*TasPmc4QuXCI)CT*^dNL!U=c_*wJJ zcep5hYpwWsJUb9u-KhgbmOQ?p`m}cVaIC9u4>NV{GyA6cGyI9h$50n;*>ZdU$?wSW z;<5Ch3v@om`|DAJo6> za=wUbge8z=@QK}j9MPW}Eboco19hN%XXX09^C(*(+VlyGJ;M1JjellM^2WNI4dLX) zo$UM2{7x&+6Zr0T0tD?}%JAbr@N=ru0I`0{7R%L*!RYbR9DW~| z&Yq9@mp*Ub;&JuNTJd2WJ_7SH9pI4;Umr)}|NW*PvBmf8VCc}l#{Q-8|4Gdt4AL?O zTWxoCeP^Pt-P`aMbFXfNyhP>r8Kduq!`hlk>f0zk^S|{2!!QpH*=Mlp$C3Kah(19$ zx`R1rp6B?Y{b}z1m7v}Cj9TZvPaPeE72f7hF`4Vvl;7Q3{vI2&*#?iBaR20>km_?M zeh$L6w`^;j|F+e75T0}vkGE8=FZgeW$DT*q!o5K5pJWQDe^Rw=hrJh9OY%RI-{t>j zE^JP^4d?6g|1-tkm58pG(n_^f|5W$G1#CERDcH{7_@nyVz{@@He2BO|cuoBd&9A;6 zV<&_U5%<(<+n;@Z8S!7^$M(l*H;v%O++FNA)#tw68Gv;cnbfMkP5u*(ox0gTJ@^+N zN&QdtuAlgQY5}y%vgQ7R;47jsT&%CKk<16B{R8RN=0a<|+i-Rg#~0NPWXD5s$Yv`^ z{~DeD=GZ~B@1;_FQGIQVR|F25XalPXN3iFo_*%E~9UfS-4e};=GyA6TO-fM!{%C9t z!(Kwo`;+#!O=$5Jbrxj8iNzdWH2*VOUF`oDWD4pr4s1Qu-!8!$?AK^3SasRJu21V1 zo(2WsKo<+hnqkP+Q+&Bpy+O0At+nFIAur~c`V z+h>$V>;mI_XO15d|Mc^Sz-Pni!nR>4Y(0&Cg2njWT0092!!NM)R3E7NAod@`+JJth z^89GN$ZsAluzU$B~t#DYc2YhDhqgbn%jRC;cp&#B{=g$CN$Sl9{&`63c}4I ze~q##W%fn++vd1(boreF$NSxv|K*p?#J?Q0J%>R7h_@Vw~d_-IPux2$JKxT9#a_1R z&{4tlZ_4kcI$ppbJC{M~W{wXT<#&yHir-I9Qh$x4KlH@>{dl%zJX~4N`wM9Oj!~!n zI9b&Hi+wnLD8I8?avXpBS^(AcQ$^Tq*F%q^mx+>v+)Ia4n55Ny|EuiE3P_~}>r-5w) zaAKkb40Khn<5XWr*ieF#T5pGDnacgo%{Tri3=sWChem8Y^*@~(2clCaOYk(}_@etK zlwB&p>jSof=Q@rrs$V}4>$}g@vjW*Yu1`^X8T9##GpFUi;(_<%f8U=m!B_0hXtXf3 z2di^jU!eI_OTE!}VoO6vFUsNePyElyqqA^#^R_U#!Md8`QvSB6+y%p;en|8=8A#wO z+c$YCMhtX@nYUZ;^#otHtGc514|TYw!u?k|$*&&na{zBnmU(H?>c-S)bk4R1 zy%VdMeNp_h9{C#G&SgTMZkOHue*ZY4U!Ttl!iA!~7kheUjeSbE1bblYC1%5c+ z$pSj(^Zbx8(XZ!R7w2Qn-wroQIDez{aR!;ec=VYy{BC5*u21!cX8I-gCVxBNMCJHO zu?WVTDc0bT_mSBL)$jCTKH}>UfbfP_sFxkY8I}?64XNn8<^7|>#Cn&yboFCvoaW?7ph5Y|T`P~SW zuDH30My>vg;eJXq=IwQWz^=SMJCFFEO|SmSnti$c>O=H})sKA9VVeaw4pxqj8{+!$ z;`(Y06L$YJzw`3N8|;<41Hv{dxBnhjL(u1VUAQr%f_*>gU!De*;rJK1&?JQW7i#|r zxr1?t+z}Gr^8N=}-{#SBB(Ce(2yDLd`PQ`lpzDx$G%@TX*}un_*uQVfwz%N&Z%O|( zwg0AhWl|4TY|Kf10GoFxXNa7pH-^v>n;9jkGc(7?ddw!}9WR&;7m7WH* z@;8_Ddr-rBHYB=rVe1bO`(NkYA1$2B;7}>If9hZK&4cjlHXB&>kn49;zy7BF1??K- zLD@7Y zp67QcKCX{^i>{Y;!o?-Z>j!Q(4aJ1_woo#qihW-i-)rc7z(rGXVD>@oA1MFQvmb<= z4IClQ=N4N}@o`J6pZ4z1R5G6+mhi9s9cJUHv##L$F^#RK^`F(|B0lQM;NSdAijQyO zrsAMwZDH!QHf((y!N;?(&Nx3_iVr0GOBW|&ML!on=TXf5Xnb?LR}b8_!2oW2;raoM zZxT&+BP^H&C1=~S>z5IHWUT6smU45@d%*Q`ACmv+TrUWZudE9=G`q$=r2Oi7u#R9f z>LL{C8?y6Le6-9B#U35);8-@-*GdRJPM$2sgA)osJ+`qMk58res9HA^o33sMH^Mit z>(l+++{XH&^%`p^)tSbQ)A}@%V^w%Gd!Hmeq4PPuSoz}bN0yK_h2w|Tr#YJxVf@YQ zux&lZ4-otW?VaEarG>SG-zyv1wRvtj2&<@jlr8Hkmg>O$cd&abF{$sO|ngHPu|amTyz zzwe*=m$hf2(c!owI4tG(q4jOCS)*{8e^Y2-k;lG2#m}LhGteWuJ$Og+`kgpZA9|&m z3ziL#!N2)X6hCWoI^nHn8WMe(;-j%`5BxO3P~sobNqlenbq_94jR%;{`OyVp|1Z@0 zW83TIu;mE1e<1dMN1U(Hv8!#Z_HXZV7-#=l2*=WIv-pDAf8*jnJQ`~Y=QWh`qa3GD zEO}xFX)0X*T0rX0s+L#a<1YI^uOE-k(@A{sRji-$h_;4nS0^jA{}$nvg7&WG68ldl z^=GfI55zv1R^V}y+dt(`mcs(k#>5t$eBu14gz%$fr+=f?qoc4id?B|VV*lUA4#fAN zR$$eY^CxQm`(i&}_`BWkJ!KPLPwfAj;EP6Lf9A1pZvV8uZH^FtZPwHUzabx({Zaq$ zuyPt-2uWBXR~z*%m= z{7(sq4-Sg_>FJVs;5hqV{zd8^oX+YAY8lr-W?;{*Pw`@p{-=Ad$ z;NdB@@O>i3m%6)@e|^#TgRNYT!?0x>UsPXqt?!36t3>^KZDV$Q%D>)w_+zheb-~-& zh#jZ=YyPD7s6KDEr2o2*)IYbI5r}84>cP*rGWPwb|Hw-z#ee|Ltz#R)$7x)jrt$mkIUlj= zRX!NIwqp39^9lP02c!E8d+2GG%-%oE-*}H4h$&q~eeF4~k8vjW+Aq$Z@$6_18Rv$v z^@m9Ol73MpX!{_9-0@@f6-W42BUgW%7h(&;ZhF+Lm*Pjm`Z;!$Z-?g{nb($_qw z@;<_@j|5+)Hv_O$N=7XD)cYp&Ix) z@8i!;@Rw$ojAJ?mz=bN_KScF`@m`%UQ%4(aAh&U zj+#em$DileY+UO%8$2#FXX|PFley0uU-*dgBYyMi8x#JQV09QR2P8q^riBbY$pnAZ zhXe6b3wv=sehz#7D1yI5ZtpQ@LY@SF)c>6m_y4)Q(GH9jbAD*-F0DUkF(L$yyVi%8 z0?rR_5dU^A`ZYTJ-UaE~E;4*ZDWvsniV#0+lx8c@4`}}8>$(zr9=luO-<-+(!i60I z@x(0eo-dW)Q?02#Ms=zOU8iyVnf50Poct8WRBr?C*S!CY>IXeL1!A4cc5v-} zOLl%*pR>Bl3(>!1LHSKyKT7Kdeys|^8Mp1>mcpE^r~GiD#RqKrC?94|;P|8UqoW!H z;jlUO;Jl-P*@rQyAN?=yBYrj63w>Mj{3-QsjlYQXgH8<~Y9H^9q4=9MY792t)f&9L zkFfKn6aKhEbuK192Dqfh^KN&^t_^^X9%v;0lpXvwo((^HP;(RzZxj(yqZQ{S;UwPxmq1I6E3iqEf zf}ir|2XS`SBp8tx&+tR_SXQ7MKR#1~(Cml<+&!|1J-_){ z|7iw;*ZgF>_FGLIlDfP z{EWrXLM)oSQ-Ti}@lQ`%_~XfTcD3r$^KN~{)hiCbrqW|_p1+drzwuyYAbRRKNc3q3 zf{&!t#TfN17iJz-9$$rv{XILrHI(QFwEo6q$QZnR)ERC?9A);EO7Ic!d@kxlbO*-~ zoPRkG{wE*T218e5jG}{)!{|Ti~J`Ebl&7 z%ujQCrW5>V%H7dE-niEK(Jx7R@xYFSVAec@Js;Jl6K9I?*Lx{`3PD<*Gsxr+K6P9y z)@RIT_yOX7+&=|kZ|C}OYckijssB;ESBjZO_CndIc5FS8`hxt5K%CO9KD12d_@eQb zMdTMe_46ROT01fP0IA=xYaM~Ae;Pv67M|as^9>4aL}33Jji6I(BD3E-!v98$FUJel z4@vMx^$DBe0PH`+0e(jgW$URvw|U)jG+MF~qU0QZRG+)=7J!2Hj=rss9Q1JPOmU zw}vye2ifsNg0I+M7c8<6=QrEzXZKJ2OZ%7(=%lU#ziZ|TP<)Ja*@Y*y=7Li^*C&z* zK6-CeV5d@J$oa|jHQK+E+%q4mk1c?ra9)3tO7sbhA>P>FvJG5NX5VoHA9XzfF!hxK`08^1Li0N@SBi0F(>%a0r7XTmC-}(w7>0B78$scjOm=F~k|%z+ z;;OwQKSby2RN__42}(fv)m zuKHr|4?FN1V9cK1hv3WF=Q+BG`?EC5;rOEb&TwV`78}+F?ZR?q|5U#i;988{`}auV zE2)n<0^S^G6eSV$JIZvPk}? zQOY~K-*O+!yjYVTl}qzKvj&U(K}pR($CT%Pknp<+hL3Txbr!5jxytZE^>M?lk+|ha z6S#DD5wjmUzy0LT02~`D<~RBcufdm8znk{)D|TLU0@l0w%K!eq(~17jXO$m@B|AXD zdY(U}_(*C03|lPAhDob9KB#|DZ1ctT_v|J7E{^cK5h>5G;BGd2N#Xba!tX*vekr%9 z4@C{?u=}U}rx2duk2TrQb|l9K^*;-}0?_46eM$TiOZeTI&&4=9G#?yqbNzwhW4YEK zysOh(%%44B_DB8CXl$sH1mIX)5zJ`O!|#r{2Xp`Qbf zPpJR-;H^OO38oT!(D+4mI|mz8jKVB zwS+q{FW7n?Qa{#c=_tH++669UAFi=)Ly5pV*eV|5d-s4QpLf@+m)2)$`MaXESf6iG z$oUVo-$(IVvCfK_5RlLNcPM{4uvmdfW9q=RC3)=qP<^@L+b&e8On|t}-PrXD34ekY zUf3tp7RojG|DWnxS9Izu({Z|Izj3 zaW#G4`xhZeGH2#3q)-}YP_5ITK}hqgfyz)aPthe5LcGmmrj!gJWM0QSk5Qq7kSUqT z^gG|zd++->>-W0-eO|kByLUbNdDgSmUYqEn9m#%Z`>_kyww=SjAEJ-WUcZmurT)Wp zYg^m1_))Zy{eJe(gYf!@?l8(Gfvu`x=rztbP0hBS!55uRXl} z4K z$4AxdVfd!L5nQ`jpZ$MS|Lo`*iI(kpL4xjM7C*E;^JnL1sej)b?l(Qjo>P5uwCOku zDzyZSR!iCQe6oL6)sp558aIUhoo@k>U-z=vhFkW`1dnR<@vpPa9_w6bDx04{+55+k{r%Ybf!J$sJDI;r_0P4xS=e)AGKBBo^E1oH{LPQ`{jfS+A2jOl z_^11ORGVj*F?l~^*j!}zq4NWWm;__uP6IHm=J^AipHVmSG44CM7dB<^`L|^xzt;Z{ zj9$y{|`T&q<&eZ3Sf zz)Y&|p3VjP;XMB7e1K1nrTR$!u27cTO0`}-A7EO-13bQF7c?KpVg&X zd=yTYgtMmFLeVnb|3c3{{~fRsdl$}u{E6Iu20>n*tbNlQZJRd)m&aURQ2cyaupPT* zDdEH&-k+v$kk8L(|Jx47nl_Wo&rp*7nA?MQ;^>k&kluvXM{)^&v8^i%KhOKe z==m4N*g#z6XdvsKr1`;#mxXAtDI3;z;rv1S^D}=*{h#l;gWckJEIvF5K7IvD=XbVr zgL<<^tKv_dA4CX6xc_-J9O%pOLGPcfboItl5nUi*l`C6M{oj)pAEM)--SBfN*H5~{ z|6P>ng;4enjGD^vL+kr{2Ry|9sXp6gJ;zT5$q&Ao_@U0huCU35L+7bIVPcPBww~q( z`Y(s0Z@e_W=_s#1DoK9OJa7t%T>xMRuOHIzmv0)`r=jS=foapZdE|B?EC>nAG2u z$n_WXugd3a$JN86{GwL>*EVW%(ZT6UA+gZj62`>QZ_ z>M0oCs*@elKcs)=X`KLU)!qQs=lsj!lh#kx)Gxwj(*3)uAMpIzlkm&QXFeFVzH5#1 zX)io2!iV8GGW~_5zOqv~e|)TO_ZsmPmQsXit#YLPE{-qCKiQK1{a9PVf5K1|KIQfQ z4W}QV+vD93?a%Q=_1PeIFWfV)i;SPBzw7p`99uRy1ba_!WcWaWuYu8i7yG@nt%;)~W# zEbGRi*(Y;wUzg9G)A~u#mw0SC*Bbovm$2tbqR-atn}QB!9l-O5D|@aW{mGt6bF@y? zmi1p!{>ePC6|*lWVO0U|7(?}+vG*hxB{{lEKfknm5_kK3{F(m7B*u?u@Ytx z^uU!{J3{b0-rti!>LVW-ZO1qFCHxc^GyKr=VZ}>)FfO*6Ouy0mrRZB3wyAv(Ap02O zpEANfZMFO`eO-6>bd#UIr1|@-QGwF=AVb;turlIL9clIu&%$0%>R+?_4}Y{iU;ZQx zCl*^nofPhGWfA@{cc{d1Cr--n(~00GVx=^ntk?iT% z`s{}GLo~M83m%I&J`@W1{F#&sLvdmceHlKee_I;<7}p-%51&8q^I=MYj{$XjG4_J= z{!cC0`)U8#=D;$HnsWebA01}#?{~qy*LoTQJS}0* zDL&$=xoQllY&SY%lenv;^ZTTt89%7;!iU2Nb75*+KG zUNR^K)MxQa<6r-h51L8w>-CKD2c3VuEB_^aT5%LieEabFiM`yv9cUDcZLai$jZQmN zzn{E6U%beIv(p40lpg;HOfo@fA>TZgdcwEyH;#88}4s1I{4aQ#I0_w-qhan*|h5Y>z8 zCwl*~qK`jzTiOFYzi7k$K8@c?w;!XC;XzsaBI)lc?&XiG(|SNRO}_tMBKe1=bib&} zE)y`R&G+|k;y)#1jm5ojwvc-EfBhwL|7q{oX}C1Z8G7gaZ+^Mlf9m4A1Jk|c!ilRN z89p+|{{G`%b9A!Mf!Af+U#0O~`Yjt%4N|4~Z(N_z{e5u zdq34h+)$b>d-_@`DaixwC%<9JDm+GHRy$Ug{$sU-si0hwJqJOs53&DU#06@>urv^N_1rXyEJ~S`efn$`6&?cj_=Pjey!`;WBbfj0M1;W)BL#gtxb4- zdlF3S(~!NN#_z@ycN`?uU)uIkAHN5}cH+6>`Jni`NtNHq=jZvp_CeFFJ>ZfV=Lb(x zUmGX};D*aRp~Jczs^4E8zfZ#pv4M2HPlej1FZ{k% z>W`>4X7BeT_$ZBgj31xpf&E;*|10g~{k`k$e6UN49^g>L^JjX#J*`y<&Zs_6<9wF& z)_yqZu%T@K&mj2G_Zx;w`nvG}9 z2Z(-Y9y$s8#5#jdB-i&!vi~QqG?Vh1#*@Z#|M4!om@M_*u5QTm z2@rqQ?m*I=v@3QWmKl<0{1ueR8fA$v9|JKuk@nT&Q*?e$%|5&qEh1ersjvoc7-+dkL zgCqMH%JSnZ!VhgF{+iIN7j!u2%i^2XpVK6Nw872&viT24{H3rql0Vg^2UOnZ!`7z~ zd>oD_#XQ|Z@O7wqe7vjh!G~)M;o6qgY(3?d`#nl=(bGJrzI@pJzx|2oqagIfJMKm@ zd{BS(efcmf&M|{)Y0p&gBcD%HuX!x4jkku7^i!(%li!I(8!9UIWs^VWh->d!O zLX5kW3)c;J|AvC(#}0Ac7%<6D<{v3Zf79{QGVG?24|e_X8Ggb^e*C4(7yBml1Z5S^ zFO-B|M(2cM#S{yudcf!7QUA4rb~GkdS=HEoTktj>>v##W`}wH<+IhA)cFbr3|GOWY z@<-Rg?dW8d0xh#L89u1LdU!y8bm*ifyI+su!}R2KT-rVb6880C>x&3~+?(%)b1k~m z$RC;Kcc56E0-Y`{XZt^`Pdv!>MqNpNzerKfAASdlvF%8SKZaVU@(+1_tfvuxT0X{5 zZz1Q8aMIsl7JM76#_onC-kd)a#DD!(7=mX)&0ySVe*UA1;KTo0G2Y#J5IXd^%J4?1a z1zew{lKP*;Zy&6<+7mvG=K75G*ZS`-#sRShq1#uk&uD#Px2qp^d(sO^b1YS#Uyh&t z$Gvb`g`rG;(fM6z(T}D5D_@$=aD?GQm*68_@?YEEGKMyRb=lvi_3wgh!B{uM6kN~n z`!DHyh@Cs4@ol;dJb26N-&w>z8rOd!?yejloBvJgd-d(iQQ_7UbdtHgq4+p5WCy+< znJPPFnGK=PBR?@Dpi^L!|q`-I_x_RqG~48SANCh)Zf_m61(PUs$h z@0BJn-(n5>eJDS)Ee*iyZTi5}x;(!QC;3PIgAo{`*&p6rPGRe*Kjc300q)g11TzbH z{L=oWF1lX$E!+q+dkkjlb;0`B8#X_3~kZlE*L2zsn5+@K3S{cueQ5CI4VCFOz*?evV$sfeG+we=BR4{kt^H&l`eXV1FIX*CJ z204xg+5bo5`{lcxsEkQuIZ%0aw7mqF?Si`#6+!-i6PM)zjx z>HeRW#$OJ@SudU}4gMV&y*wK0W}xxD`g$^Nfz z{{Tn*It2IAuCVn~AMJOM&TpJEfsrp$+4m0wALS7xC~lLVuLvjggC(WIG0CYvJP73Y zq30`n*5AXvjSs-NtGxb3@e?}M8>b}qlGWc3OJiGcR!pn<@>*q^hZtl=!Ium z_kt@A&3XI~{7h}-gGZb6hRIXfvgb6vNIUTW7eyb214cZ*p!k_0`O{S%rqFjxeYT$Z zS4k715SrLP&m$jLe9`@1f}dI`l7H2wIYj9H@BFMh|6W~x2YMe{Af4~z=PS%fe}_X4E41&T2PJoQ zv;U9cr+aEP_FuXfazD7U&qw*;*;*I$j?=Hve~p~76Z>9Y1j^<7d_*|mhi;)>XuGNx z{5Z|^lPLp~hN;r&l*h(9}{Yao6PHUl$nu8$H3K30|&x?(oAU3V%f?(;{|Au%*`+JIaQOLN5O&Fv{r~j-2mh9LQR`hUc#PxcV=2Ehv+%}R zgL}*J3+i9pK3IV7Jr2Om(`)Vj+n=a^b^Cxf);-!A)~)CGq30(Koh-)uRfpkLrF#Fj z_LyKiHP8YyJsa})BKgG-^AXr|vn`y6_{QR^jMOip!pGqLqmn;0^aguQ{of9@LouUy?;7>h-&K|PW6EX7y}40seXdsj09?Gr494iI$JfT)Z&4_?2(j1N+OhZ` z`08-p7gr|sflABO?Dqx2KR=}YjrHY+A^r&GA0@$8${T;&?QJHjf6((uZ%<3>FVu`L z?adK5Xp0TJw4cY`Pxaf%Zg=s{PsyK1;QXT``08xtjicO*W%Ut?uX>~JVszgFpjXWC zl|lHYxv@8XbT*dhw{XHgKaSi*M``|l)iU+?YSPFDKh!Y+ENjO;Kjo*$2E~|I_Xte6 z&+!GMJ~-Ds7zg$33%3e5zG(iQ`#2b@5A~Jxr_=gM>xnVgXEVU~`P?54C;7?6Z4+@+ z#X#_yyo1FryZ1o$etQ05fwc=3w(3@+ezP&$iPkoY0X%;*{f5Nf`Z-F%Pib$^c*OaK z)=%6%JVVWuA|&`aGyKr|ht7ltU`UBMN< ze^kHqzjp_niw?lyB#s}-PvJQ}xFM$xd<^3LmkG $&nVm+cP2y=Pp%QGR-qHxwN^ z7{hB%3swBf^Y?%B@8D5;2|s-}eyIPIGDMocmt+FUH5@;*f9i(SJ$&^t4_4Xb+5fkH zQTz;(=HHtKSU{(+2CDbV`$J~83dO5$Ey3i~a~6LTKVF_A@%jWunA`XYd)|rQXS`GNB;e?aq_)t}1IZ}C~M+q#ggr}dG$Gd(dw$5^`Go#TVn$1U^9 zF~RRFz*!%T57Pe>F5S=Oe$N6v&f2B=e&zb@#9wb5qi0&9KC6B30Y1n%20`vzpV9dX zpN9J42wO9-|I72245H8O>)u7Z#`5`%^nOR@HDRbXzy|t^OlF_Ygy^%d;@jw6>mayC z@c5_vaZEZtcf-^SCVB;^{y%yCQvSObzv>)=iW{@-dHl)ii(>Rpj4m>U+MCtKe`wHc zbouuH%xTHvpX#$aPkr&}F*7&;omKCb`vcvb1JOIXFO;TgvFEgYIQvLAX0?<0Lp=C= zu3VzO3_Bmg$Vr>P@Vk<&F9UgfM5A5`-V7fO>1o^_NGJLKtExpf*ef0mujJ?RfYc8U zh4sS&{o2%+e_-zcXwj*Ajr!=AZy9>#A>j5oYU6iMS5GXuVJ!1!Y5eAW+KQ|CE&@M0 zZ9ArKNdHn}1Alz@+5&>lso&p+9r3{#SIl7MExv#MfBw_dV$9Az1`9Xy_@(`?8@~DA zl-lO-uJ;1={r-RbOI9H`%hy`AKX)SWxy337<5ye4=kAegJ@ro~ERg0imiK`Rq1+#( z`eb;;P23)J05VUnvFHE4yng*5J`k_J=m+7GyR*MvDjcJ}va{d&3AChYY*112V_$Q+;zKv*8qdr+x;EWXqyVs~c zTGTGZr~6LBEuC3v`wF9EJJLe18om^|iezURb}t6#jIwV*kIA=yP%4O^m#D04n#ZkAG3(hkntv z(6^}xTdzyve~h~yj_cUB#`AG4o&@1+eQQ~NQv%svcU@1wk%5E2^>C>wKIQxC(_Qni zXFxQZ+sEq*w7=AN$|kJ1oC+=5^8P1XlAjKC>5C;F+rZMvTt86%e{}yG)YDo4x!Z=Z z_v;eQ$4>9WXL+Zz^n13P-V0|{z*Hk|&>o3hG)G>i+-n_q#`lF?J?{Q1W zEhxKri07w7KXjevhlxS`;Ad~HAE-b2)2$fyZa4v7H}+@oPwQifb-w7es4u*G%Kgz) zlApT&{))yI@5}CwR+9LS{~`4!{I&pni-juu)R*bA>$(c@PeG|H{%L)z;OH>SpKK4? z8u0lWH2$|VmF{o7ix7E{$3N8<4Uz)!&<`sp*unSrbfT|M<`rUgzvIwu3y*&V$xj=X zc%x4p3wYG4Kl}W2|34WOjK{azKw`C#+W77v_0Q_`vaE6cUOFZa<6l`p{`3F&oAUmO z4UgxcrhPQTUg76=%7{N>W4HzXYNx@kIow~N{SP4?ebMbxTQD@{{yvT02VZuf?THoO zv^t!{ZzmGJmle)<{g(m6>+$*m)xQ-bk8tEqtZ{!Hw|fZg9&ZZ4MZAB5`jd;FzQmq* zMY>;RA&Xzy|350i4=aaTfL1++g_S~c6E^@R78fc_@eu_ox6tk^2AHH{$;T}*B^3yeC3oE78zN< z8b=$pp7s~{-w(xMwd^5(E8m}K|AVG>IKKJ{F!yImww~&bkn@2!E?Uwbs{T_T`}5H~ zBe7cP1{*wXv-qO*uid_Lv8;NyG@qEyccJ~KoxWtEU#;b!dA1&VzpI1%d}g}wHXOfw z31nW}%l`f)vVUuD?u&*U+ShpgQqwvUQ-YSs{CV0R*DS;d--Y(5QJ+MNd5GzkB>o*Y zoxNX4{1Ll?!I*Z?6wG6J{40n*-=?wz^EJ*wCtp6l1<3w=^ph_JHL`-&H`K@f_fDTN z<>q}*9M)j*OV2L{&IrJBgKc1y_a^rJT_XGUm3x12n*9^FGvyFluOR#PN$GxyuKqTV zuf3G5r~ZBIWNE(Rt6Q@8r}`yjL^NJL>;i{&^794Mzi%*Iy#cPwD*C?4N*zC~!6p17#2p0KUgDf|EMLFXF&LYIyRXp*w46Htes$pIn~}tSh{Z@;W$6y>l6m~o`c>(S zxwvvcG=zM-&*H~~;bC3FQ0#0zm+34w(9|p3V3|d{e8|G5A5046jtw4uRoOk`r?H!`@Hz zMbY;$hgvq#g~$tuMaT`#VOeUo$a@?^|b!FPk4uKDsRK)m{UAH74rG2=3k}$ zwy*N|r2RK87lN^Nq&+wnbN%c|^s{%_dmQIl0Qs3dEIxqf=WD0^utS+Oc*iCr-1iF9fya@k#xO1`C34va=m* zx9_F;e&zne(~2nkzGna^ezj-M>HZv}8G*xFJ3;PjUjL;13D7!O)IB*;7}aMqi!VB# zc-;0#{I<{;DxaQZ@k8^+KlM^^$bfh#-^=^kJW2d&A6bH5&dmV*ylA!_h(D)$-U1i) z?;z{1q49hF=XUh0UIwXJZfrf(CkvDgxa?>T7=J{4{F=K;{(+$gC&o`^>lLJaS}}VN z=I%6umd*KkxHP*1uipM|AFY)Yqd@sBM*V&}L!vi+I*ceh^n;}%U@c(P`$ zZ!}reQM6vHBfK=;V9)n2xjvaH`8WF`tsyo?P{ps@zh0@(6Fm>r7v6T{_@Mi@iESV* zv9*H@9eS$P%kg2+DF{bs*~2Q0ChWO^gWR94wfL64(mA)nu?Ao1^AV1co{JHoiOe1BDt{X0$D zL%ejLpD^Vk&mWcK{_UB04(L{5Sff8}azg4KH@gU52c@w1r}^dS+(Fpvo;gH+=J8(! z^7-{$eI8&J^RtjXO-HRieRGu$rnjz}sU`kf`3=4&-e;drX)pH&wOytDjC>oI z_*RRpzeV~39+ZaSqGU(V@Z|GNOo%?w@R}_?wiziLn>$i%d@or#95=3XgZZy`eTM3n zSKH=ebZR^l+~@I6^-I6}RP@i80Ohl|{>UKl-|xBw8Z_!8n;%Exzs)fnG5>->m{mHE z{eSfSdFLMjCL0*RJa>){s$XusyN@l+M7T6$9E*Pi(dW%A2cn5ozn?pnJ#cOK@iO=<|YsANTX+CImhz%69 zoWa)9{a@MeGTu$egAD;3A9VjeCe8PqmDyjm|ECgvWpvlt;+55};Z#1??^GYvdlrE2 zbV2G*bZ76U{>qpYbH(IY3Boc{EtUS2`|I}|ebBAg2J{+rW9!q2zc}%612J>|cNu;Z zr2fBjwLeaMY6sIl=&a!rLgq?9c23c(1v8}6*vm=3%Nf}^;MVi^RaNzIMBG! zpZ$F$!PoGAE%4Q~PO|wa6ki{%>=j=f-YlG1(ii#uC(jT1Y!xu3)JQh}f#R!O+d?#- zdj>RvC$jfbez}(Hj`4NPA)%jod>QYR?#~+AA548Xf6)5>mlrS5^!;tv)sg29)SoPA z6pUKtjxzkv{{7ZxyNQ?9w-Qperg8j`{K3R86i0bD!(|;_fBH`9pZS-5;K0DAGW|sP z<==b0IC7*NJTOwPpUmIfz=4Y65b{;MellC>gWis|GW;kBe)22-pnkKLFlS+!y*mA5 zXD|${z7GKHOn&~1=D*4#$>Obm1i|H21GV@$JI@EZTi614@%%S|;HT4=6gS zo`0f>1Mpcd0YVmVeMQfY-N{H6dl@GPrxtps@X<~d-|dqla8qYDNEoPK_{$*t)F3!X zTv8b;SZb-qS7MJj*tO+Im@}y%TTkn&#>UCwlCZHton-a+`aW?sp1KkP*T(bwoSxsD zWj-JG*B=jOHf~|@P5Te_%$Seni^jv}VYaIHm-iopEVIDKo1JCzCzSTJW&i(=+Kt5v z8MTEQ>v;dW(q4|g!*2mK2lcFx-<$(pqWkGPP(GU1-xLb@`R2eb1JU(_g{(i6^4sO^ zmH41RF-*<5qSk-yljehC`>FohI#W-KjBF@$s2E}YAHFER`55|OgJyPMS6jXQ`y|a5_sDdS;V+Bm zyA3Djh;F(GLSC?X{5`Jl!&)0aRzINl^MD3o>y6crw1wl3_TMc35rsSUctEV!cPnJ_;WCxjkaPel-=d{qxHEV$L8TF<#=%DpdNqgcFxDO zRuf^x9ANmP{P%3X1-jq=2bOH%`3=S20q0-XVAxBjNYH2hzd|9$-wkR0ulkA*_mgCi{dZxR1t+2Glz$Q=zq zbC$E`^!(7>W%KdNyh$+J(t$lMBl=N)pas?*+XcLk$1lZC!_ND}pD(uxuD31mzwe*s zXW{;KIPIB{YzZ}!_tkZf`)|jl)DkCDSIY21_2aCm{-`_55jG^L_owgltHy@+UVzq!02ber zpNX%=5VfZW9n64gQS5cZ@w$%}Qv^-StDfizxW!4rq8h-%0 z_3H7Z*+laH8av4FMft14SWPkc?@#Eufa6O^@~@+(0#QH78U74x!QM~vul-%8i;o;) z1&{g8DtyTC)xB3N&id&E<<4CH(ep#CzD^S(TE+@ZXN^#;m*dN->jX@<2?gCN|GS?; zo}Yycoh{DolOUY9svds_%4Xow;Ul2H;v&OO7Qx>P?b*0${TK); znUGNy$krpl-@(HcxZ}D$oNdbM?-YMS3pK^=PJf{1L4kdL6o3CV?~gYw8^W{wT)!#F zd?)7?EyS+dwS*;$`Tj=zk;O;dvF;K}nB%G*e_aoGVe7^Kn&ljSR3Ap43&F3+Zm{fU z7W;fOKl}G?ZPES9NAQo|$M8k<-;b-qaggp%NL;ant*8B|iO^2;i)bR(e+v10@o4h^ z{AuM31vlri^^~6$PV>V(YaJmZGL}83{)NHCUzoh{HJBdY_@VyA@ITUg!j?{8cY^a1 z^)LE`)Dl;iRY7F=UVFYj%K2%-TR$wS>jZDJdb9U?lKiXonfl@t>t9gIT0MSFrTXKh zHBK<=Yg4wK)_>e{r-^O)jTAz5bNtZxmaP{@qw=s9O#Q+6iTWG;R!kKe_ly-Bz6@83 zAMFMcuyA}BG;i{S#jghOHx7+Ziano?6;`^b$Iom*iQn6ghAQ(rY(3R~&nC{r5AGA; zf*U{IN6$x$xu1r=bmu_0LmXRA`K$7>If_^Hp+^vpUy2_M+iI*H{|a&=RQiwj>rVgJ z;K?h75LHV(ep2nKapc5T5Z>z&dq2&;4%kZmM-!_W@$)d`C2rYJ2;cQ`S^kBj{x6t& zVex7?zQPH=wP;v@&O#APU8rlv;)~>8N!!D)GQb1woXTPGLF=pSbAIE6+_#Wte2}jv z_5Xx4DgS!x1&yk=vh@i>ABNqjCEELal<^y_FU|Gy$6Mo^!DzC2{59Qj7mt5E2c1d= z+yD3ZDZfpv^uw8ro#D0dDE5BpkKAnk3%#t~fc`#?PwKyWe3#A#N&e7WeK)qA`XhB* zYKf(TKS1lIoZkTC_|$AC&4=qb07Crxu=UiRx4Kqe%-r%DV%Kwg()?`fmk?Yby2Idk zZP|Ky{@ZCi{K6eI0 zVeu7D$T-ULE9yTQv`Z3KO8MD{oAcQFslFWWJrTFo8VMJ=Tx0P~{Sp0aCH9j1|DgN- zvghH1-@12B!!Aa1V1wgm_FO^wb7BseW1ci0`_Cu!_zcr&C9ZF#BMk4)_h*`)S@pHX zua$=28PEAAgYcW}%qC*dB~76la(|cdn{7LH)X=tuyaN7ysxM#ld5$gb-v^VNOtt>V zh;%O;+QI>#!CvSH?feewPnCrCXO!#;mF@h=~5o*};66DMp)x^Dj;zLliEa(rKDK4PXL z#NT&i>uG;P*AEKuZrhKL(^5S?GcQD-+agcsu$=23UBaJW^7=Lsd~PhPB|Z-RBF87uujf7mqEWazjPy)p z-)}hSUn+x8xc2*Bxb;gt{=9$t;_;OO;Hf3YpOWD3 zM!b&bd9o%=7`xlU%>j{4dOSqWHCOtgx`7di-exjmM-T5wiLm zo$qKAJYDSnElzmpIhWxFNquhJt!ZfdFcwxV;QB9vqDvinURtd~BZM*P^!Q;6?P zK0|9S_4xUCEgU5Kl#lSzJB2T37v2K*h)_v z`9fDHFx2Gyqmc7g*S=BsaFh=?UDag&e?H+a_r&qyxMMNGnL&|!J;?d%sY5ir4)h17 z+9fQ0^NIhTK5V-9$#bl*I)mef>dW8VW+DuW1CuAW*m_#uempD@r)$PTS?&_{ocbqW ztLNdTkVKff<$wKw^7`AXDq?n%LK zsy;IPLj1|&F0S}ulMQU%pq`(!Cq2VJjbgx?I~hM^kp98lD~Dp$W+&+WgX4?#&-R=h zghzxyuwl;%=(=miJeU+7gBj?T3P0VrSLom-i2rUTG^n?AtIw1SvyJC})Sn#wb|zY1Nq|SYIX_YT_hxyHSlB63NSmo1KU+i_bQohIyT4OO z^xdM5)mX3g2l#b@<6BAavo6mC>uUF}(cf>mPO5L4ltQlUd4`{Kf*;3Up4h0Fvy7i; z{j6>FYpiYf1Ptb>KObRR5RA#2hk*YF6@Lx^ye_oM#f-mb&3-VuM; zGJ^Nt()-&sp1p=gnxB)+Z>0Xl&TKz?xyBuKwHd354|#v#y>3%Pv&Zqm_I20nIlkoh z_?0G|FPl6Ndaw0j>nT2}Y<}Wsw-1oDY7bja@$t{2P;^==#|N#CMJ9C+^|$B=XN;;; z@0a7_>DVy*Yv2VMwRruR>bGkp+M@sT`oeZsuHR_>bYMv&wm0&V)yJrQtC%rX+&wZz zIQA`EEk2%}AAuDE17+twY5o*5Yl=8r%AdZ!NoMOQ|0ti&#FVoMkZQ}%A89+t=Z9tA zo`(4yrT+HNG`0NG<3cjNSv&&*X7l=4ILVJ1TjhxTj${fOwyDR@h1WK?cv&A=e+R{n z_8Y0cBEJkQlXmm>6Z~A)bHSmr`@`bl>iK8xhUb`=SOVcWCm4S634YSwd!l>i0T4fn z^B>iB_acAb-hwLl{_YafcSXcs%+3kM4O={6>sVEONANRy$~!z}^c*xNbN@m~{Ka-& z(*3XP1HfbHb{4<1zav9mM;w;eK*mq>d{L{oNE~hJ54H}x|B>pues6uTXYGM->OwsG z`?Nnjs`n((&oy4iczab9-*S8zO!C8jQU}7@y+hf0I$zRcX|*&zt!8{ps0_pwm4iX| zCO+Ah3x&bKGwuM3@h4t!?k%FU$p+bptOxR>U|60!G87pQ@VZx zP7Mlz4gNap^V9Qrr9a}t4>mDEygSF2(q7I#)uY34iiPv^p!IBMkt@H1S={(dU)4+BpoWI4bN9))l_N zh($}-dYWH7ogRvA$Gjo0%`mpUi1b%&+ZBNJzXyZC9X_Aq|MUM&*A>^atSziFjL z`t#IJVOXn|FI24I^`CI!Kg5)^7ENEa5QYYEd{O?=42;A&^8jTZZSw7;VyZ;WU# zE=H(+G>q{N#n&!qIl;*ykM%O9$y*@XQI+=0(?&{WbsS= zznl)!FlImkliq4pJ6J) z7v-;i=G7I$R@WBVRrC3^6ki!S1F-%v+Zy$s)8G=!sVD@^oOFh-PK3Y2o@AE)F>9Q2_A;#>RM|A$|SpI^~I_^xCq{8>Fs z6<>0Fc>B+9taSPg=Q33Iq4`t)P%O#ufv1N#erSKP?InY@X?>^qE{AhExs1dXhg7UCI0NDSv4Rt;OM;S_-g9Uu{o%x)c;h)*%n6AR5(lWqS6QF`n~&oI>8Eb6_@?~jI$!cP zlH!Hx)pJyzU*3P;ZNyA`G zL-qc}&!}W<5S;{<0$o&}PwrnFeQAvK9~#uyzqssyhG>elg~JWGe?ZR$4zF{qeuP;|{{F46t)X$M99ts9a)&2Ha#2-9n6^hFg zelW9gDT^N^;jh^{-lEIm3K(|XkHtU5pT@!foa8$cR(MQd>uLYu+2??JYnp8xGJW1MLDHC{kbJ-*I_hT!Mofi&4*QAzdEHc7xf#?2JOv**yl?i{5JEIF+RP~qsIP_=BF(&F3S|!U(02` z9}<6~)v#nVAEAV@CCiw8qyGBD+Ro_q!LCMsaQpigIN+ah=ydBI<2Ty>aXoP`J|61| z7o&K7M)_^Us_)qL_7~9Yj_myzgx?ld2BGoGn(|yw#{I*Rx|8%n; z1ni%2exv8hE_KlsJ73b0r3KX3U7E4Kx+_*W?8 z{$ayHKPwCoy|DY#$r1SZjxkNvntW`%;Y^^1X za^m1HPoPhaZA)q_A5nEqG_|MffRxD@{BWQdHRg2FbFG6r;nIE)k z$^Acy&*yq$#hI_-gtu9<)$-r!rn9iB%~a4e=l;Hu@ZX-EPGa-d4g!8rkI#9NXJBs0 zWVru_=XahYzx&&B994>P3sWE1^3J}JMQ zx7HCG>}n*m3)5xaAI0aHX-*h2&0dC2BU-oR$|G%mO{mZl?;EhzoU_7Bo?QHLW`dqf0qcqb$<04 zgGRlQ=WnEbe6v#|ItGM-e}8^{n);I&MfJqrR`rB64~Mb%RgnIUn0o&BLGt%-`(*b0 z(f(q))<5x6{ttLPR)s&(-*G_G55sy41xp8xKP31wE{GG8rTS`r6Ae}T%KNVd-wef! zKLOy=n(NOjg1-e*8;FIannI&f9Df-kzw34?1Sh@mhv~m~ewR-2yPm7!#D+)Xgmx_* zRq-#ck2(5;;8mqRB$#sjso@}>&lT+wBMuLX5wv%!$DhlBP;8MO0QyaMe+R8Eo0i3i z8|uUhbEDPcFYf6SeCRMic0SF7;Ll#qN&NoSQ81V^S@r$N_2>DNX_)9f86M>D{w$jR zJvuuV3+)nqMW||Ero`OY!$*#eDqLavtQD>|*#xC-cMJZR(3Z=9t1j z6OIqcp9`JpiQ|UX6E3;)^M4edNp+pDOG~J+K7GHc9G~nihg-I{+5445e{QK7gs%U% zLs$pCKTv=3*|G|(9aI5tgZ?o7r1QhHvjTCyq#tj^a{SWsYxb>LiZ@2L6vi2@Qp=x< zHKQpq`vK>4vU)fXS$9SRO3IsRz=R~|k_+)yCludI$Le&qOT|1%W3MFv4)*Z}tVf#A<5 zR7=cTs3kONUCQDFK897EYDTx!F*He$buJ=aar|1~i z`|>d3Cr?rzm~+oj^f==rXr5D#zoFZv;n9mzYV6-d{_e}n|vLWaL^ zQeWt_Ef5#?_J^&l`TjxY_f>4FEw+lUBlv{vQp=w)29dZ_^4_XVIR5DQ?t#sv{)cPf z&@p)pi|=rvPj`>1FJAW46k0Cj_@nvZneWp1v_xOXJ2{=Lr~c-r{=c#Dp+BG(v6SHh z2tN*U@W=QwJ}@dJNcDbset56EmbfUlwoqiRUZ0M13c{j0{!r@1^MC5kbPm=M-G?+3 z(v<4)850_a^I!VG)>9mxWrQCSRMf5Z%$XdnLrxSf@5jF>R#moVNa~`U{FZXBu z2t6^Zxgls3@c5+oOlgyh7Y&lZz-tNPCm`nwy1ui(d4J3xTy=js)vrZ+9Wbz&AoEA5 zK5hDL5Z+(s0cLwSzREy8A3pTeC(OJ56)G-WWcZ@_VMu|*Z#M&AhB4n?Xn%=*Y&G6U z`YrW8^Yc0XpFSNGfj3r#%kV|(3-#tV63r4D*O(t#4;h9|@nK*ZvXaF=?Jqf!Sx;=2 zpeZB`SC79>5Bzb|Wj`48Y=&C=`AYNs%q0IXe@!rZokr0FdZPVv!y5HxcDUr9TFnK`Nh{Uj>+B&5JYHxHT2?&1DZaWtc!u9k zzJ#h({Qsl;*L;{gw!LWwZWlR!((?h&@?T*2!PgMm`nBr)^7%ln(SvY@%ODy5=@R}M zyz2wz|Na8Ioo_IF0`YHd7Y5?t_Cc`t2mk!xB!8SU;X9uG{R^fJ$+hG0E3f~3@Q%PC z_amUFkn|z--9Q}V83-CZ!&U3${AjViwz%A| zuCQ!zp6dN_{4ULj#PgO>Fe{wb@9F)et3EUk7wpg$q7;wWda7UF904 zBEpX^enpGRGsZ~z095=U&mTKTpa1ZXK-dj+*?J|x@43Vg;?U-!g~Joo`>P&CA^0mf z1WdGfeUIXIRcVYExgbu^xs{}r9|zTr#+kdKL8tzHhA&!wzjV}5Ob1uNboEr#=a=*2 zhW1l%W6CrLP;!5j=8x-Q=ir@^WLU9bDEs@=U$s4Egv%q0;7J^hU&@bl_GpOB%jyd& zcDS(bho0|Aa!H{Ui`)jCv-PE}X1J-|m1eZGuze<8%!|Q<!Krlx?{|!W zu#-Ihr2S>-W(~wf%d~}?%hmJeF^dqKw=EPr%M94xr~YZdrRL)E<$A)}be=y_ecF9f z0J^*mgco5PfAoASYz`MqO=5&GKZ8{9FW0C0CI(~dLkWMIIe*gne3@6Y=-4_=@O&{# zE&gKlM&PXCXn5_Es}_F^${oe*7&pOu&@|Qi<@g(%JQi(wPJl6s`TR!epAIsgja|ki zgUJl8Pig*WVPb@yFKWi$!1w0ZtVv&RTc*M%sc$44d4fqDD!}Oy??0pbc&dvv)=RPh z_ZI5$)u{VdEF1e9cK0#j_$2;}>j@83JRc0#VmZF3eq9#&3+H~RC1mvG{V^0@KQ0B} z&B?*gw5NJ}IVh^}+EImYaD3AG#v9W>^m!f(y5U^kQhZ)?4ig)jMhi~T9p1dZLC%jmD*dtXzdoC!*TeNULL*me+|NCNroIkLM4Z#+6!({V^E)jieZ9GDJ91|zx&R365)E$As zfLJiS%=wY#j|-^W(u3w+yK(wzn1m-^D_@emCeEA+94EhfE{u<*yB>cC=SDHU> z83L=r_vDw3&MTYa0`RS|>)p*Jl6g&z8?uF-&MC>i*KJQNM--O8vih24mT7(J<%0vPhZW} zQ~i4TmLFDS1WEfF@4unvThY0$__3pwuxc^SKb55ZSadKHLmosx=|B(m{&eEM`bhrp ztS#Dt;#P_3{qp{slX`(Tt!^k-ckjm5)Bfz_yP@K0jTm9>0gg|~pT_e8@Z{(asIJS; zFJuw@TK`h0xafPdPK&jX@2E&wfxy+;dp#uJPpb;(ph}d{PSA064yv)C;FRm{-pP(*l8K! zlD$14z=Y$E>erJ_$=IrE3dHW^^}!5M|5&ih47Z->TjTtrT|XO$)^8dMr^0mj??d{# z=jm7>r1Y1cbo+*H4l9JXiR$s^6&``%&0-+? z4#yv@|NrO}io141!Yb8#=6vFxmOT84e@yELb5HU7kn-R4Uef#$&k$(i#qmY!i_d0i zia`N7g8NtX`qRt67Z>&pf&nWy|51E>Tv%7!Z_`j1+%})#gW@Yvx_=-%ClWfX;P|5Y zG_xcCz4XGs{5r=E<+r#0Mu_u*#t8aH>{Rh5=eN$S{qeeW2>kiN^(Q?aK6z%C7^yc> zIQ34w{@kM*g6pS7$j;YMertU-LOi`jki9`1B0Qy?0E(0uNh_316v*I3CXL}^IMsD z3jS=K1{D|YGXI3uFNU8oMa8qe@OcMcPxNiDHcdrcv&2k+me{cB@uSz)_WTbOrJ zy*}O6vbJa+s3|BLg|pAEB=;BQ_IF3i+e6^_RL)-%U-`;!cx-bmA$H3Swft8m-5)oy zy`&EfxW1+Q=T!b4Zy5cA`hO4D{ikoJzpDH*49~udh7P|tf7AZbP$|AO>uAgQkIZ-I zay$rs42^)v%ej9;>x&Dk{cxk7lph}F_@nj1cR%ZkCF^vA`Y$>DD8E?@@P6PSYBV8WT+#&Si|)t^hEuzS^QCbSQys>cWd^paenMK>HNdY z@rxn-dK_SQA>1t)^;Kn%|vFvc@z4VBRX;A5HJa z$aqv+Jo&4E5PL30Eq+=abi?H{JR$90_4sk?>yHB}!k~9B$A>53CzsrhxP0ed=+$(; zT6~nY2*WLQ(XeB(ECnWx5-&_8;Ds32S zHlL%4UwQxawcc9dnCnf1a9{QMuhwrr?35D*WtLH@_452|UD9{Vd{8{hRNy=8N|PI>mMdYrHmG? zgxIR$U(R1G7YATJzi`=n1&SXl%`oxCkkLYZ7ROHp$^;lKGcZ|CJX`z_;bIWc54hj~xFa)fco7H`~=?iV@%j9+MdU|3UsY*srQj;rnm(Ixn4UHJi>yC?)lJ&qqB z=kF%(3&pijUx0b;Nd)8wz(CJ!I?Y{TpHJ{qX?9;ecvCCW(|^}C_*A*Dk@ZaSLUfS4^k;bQAlO3REj1fGnr?SDf2q!A#>&^B=eLI z!tXrKXYczx>-XII_j%Sm=iIwrcdhkaYp>nxcQA2Fk*|N8&uu2`&uT@d_Tv5t&o4O_ z767;N$B`&Y-rs43`pZ_W86zb05c8u)oG-k8D7Dfb-YSoi^k3upK=F$)!ugpoG~tSj zFSI}JyEq@LsOKaSKJJi=59$6_|DW-YbSs(M9JPvFFGl*tjSh3bu5UU?vKh**WB;|d zS7+Ez+C!oK@1rj2V_lok_!WNa`^WRo?~d&S`!?DW+rK>i!~QFHlmlejQZjRTb4`7YS!X8a{POV6*#nk~*3KO92-Y8_zD zuY~x!t@#;D&i*6Q56kDT_H7W%*d9sxUEux;*Uukp^M}pt!-;AZ=gS@CS2=lV!lq?S zsp~M#SF*FTe>%94A4~`cBV;eT+G^N4-E66((kJLnB#o{l9Cs^#-jY#StO z)Q_RpYx>L0uhiQ3!;PGAq{3U9-MV6C&TCB z1(N>D705r$PVWS#HF_%4A2hD13DpPmXy*uCU%~Y=gETAXa^0RR%#_d1r~-S~oKH!l z3+KlSoln_sx|rYWR-xJJW%JcheiTDL+NG zykVqQsDz&?q9)PLFW7&DJ!2cwbJ<*k~l z^)ELsHKD{xk8U2%`N95a^%g(4K0chh`;*4j7v`t>RUowc5=o{$iz`QPE8V6f98+sTm)v^5?2{2c1HOAho7th{mq#ad zf2>cacKQhcD^%(9-QQ*Rm&SL2fqr1#BAjfs4usxEu$G7{*r%xIDa~G)DB`x#RN*GpJBc_E&2{+?^LLpj(olv1`mSIM-=nr zWhKsUe65(DL4P%b0dJa9Q-^giT($)Ks**!$!8k(Pf0!O3?5**jw; zyPk~vPr?9SxY8q>w5FU7tRK8^Ru(>P)S(%%+`r)X?a*Cu|6kV$uAvD3HO};dwH+Xq2nazwPy|qN$2`q z9OCD8+$>Nk$&l2K2fIl5c|6ksjy5RvKW)El5n%Bly4%4SxPB!)Kf`TqPl$QxAkptI zKl4vG3BDgk(V74Ie?|KD$Yplmdc{Rye0R-ILkN1O zG6qgeh#^(?R)~mM8YLF;`8(C!AH0u7isz>`W%tMY z74-2FQa?vi{R6x{h4ZI*bpbGN&jb?kmFp8L5PxpReTCYnXgV>I_cvnxQe&eb^Xe?J z=D{_#{;7we=fYY$RYj;*{RtoFGSI7T_ zXOG4Gm&f_{kM+L?+CAa^w7v@c*UZmfz_(sm)W56P^JD$O{COX^Y2qr053zosa&Le@ zzxvU-{oVQRkK)7kUkAXg^PUp@9LI-y-u;A&p&HcQXg-e*QUCv@eV(wnE{x20$n`-S zA7jEj9=y6vdGJp*+6D{52Z*2GoQ8O7_ncA$`NM&=1a!jUw(t zc>Ngj8M(_F8d*e;u8rmUziz=ALdahO+84NffzJ186Ns}s?e{5^v4X2lclalt_|K%fnFt(u{ zGR6Lp-B$I^{Qq4VKhB;io)2#yMJ&2<{;)py(9Bl|X%<5(eC6|J|IH8fUWy`qi=MOf zSB&`cF!mADKTf2&1$=)E=5OV)2yi`>K%Nic@namyzs@$D3QLvdld}5NGCuVr`9X@5+vlFua#S{k=^^18f%eKj-goW$Pd3Uz>*afHyn)O6E&q{}=54 z8C=ShX_5t>|AP7RxYh?=w{asI-}3c~`J0|p2N&9?(Sxsf{HUZP?cWGrF#y~bdr9;~ zK>GtO{rU}|!7Vt4i$QH^LETa(wm#5&hNh1K z;n}E3WWfyn{CK|Cue8^oUnk`c_b(2+5DY?I9LYPjj(xw|QT#dHwXv{At0{fmOum0y zSL+2&H%1Vv58OZE`tqANZy`24ntuOvhOKYRrFA=-V6Hok z)b8f|JwWNS3H^Eb6{Ke(1Kfjkg6f4IKo@XJe>)hL?wXe*z; z2}8mlBr%>iMV?^%^+U&V9pT*wYjP!( z*N<@jMQ!{CP}f$b2VHw|{?PuKTbH}TfK}0hzhOmf6Kd7vCwo53U)Iq+U_595 zd9`;B|9qs6#1(yo_4B0s;rg-5LpPXh;4RsogZXnd{Rd~>Yt!O(L%9D#@#n!~qoLQD zaB|*PK7U(>zlFzx8qx9)`Ss)H;{qV2$0YJ+Bk$k9{x8D&74&oZC-Hyy{En&-p>XXdQ^^Nj4u~Shj-|`&rS&tm_Whi>8fZ`^xx|@;UsKH~3pdN#-}` zA$@;y4=S$WmL_VKW|M)`v+==ADYOYUWeZT!yPhn!?XgYZzpTB_p<2wIPc=02i z^ibn`;`lWA{zR}yN+wVD%I}YAKQIw~PG3NZE(~UTV10k-dUL4%)=QzjAK|7f?6}{I zMlJMY-yimm{X2Gt%ZvJvLnHRF>)1b5cl!Wk1iR07m6I6v7VnCBOmGu8_ed79?`b!V!_$*vu zewd{F8jhDJ(QovC6StS@FDs|{gI4GyveA|EiS_>z`(DD3lT!bP`TSfl7TPTr^|L7( z`1gnWqvHb~h@Co-1llfO*KvJ~zn}JvLT7pWUHIn>Kjuy#@nd6{y*uLXv7jW>t2Ct} zA0Ls~OZj^!o^M?JDw61r9?I-7e>t;%gZTz6n&`~+O@j2zeJ^}q)Vzr#uAcLU{o}5S z-y!?A22CBr{Uh#Qd@B11 zT%W=5>6O`|g?C>jQgd_pE3U=?q8kPpIoVu&tI2g@8OuG3auOV zST28yV(j2^@L+OVHXj1-k4vzxgyWh&Nl33o%pUtk;}Tc6>Ea`aPceTRZYvAL5zT2; zi^q&VTz@<1 z5k7EZQZ&&`oy_i!^_lq1|DfknUD|mn=MT>h>mT6{D{fCF*WdF0UtC{!`Jonu?pCLB z-rbS$EA1Z^j{3mQvS?CP#p5e{KI50u-^BTYnpDq{^M~u(N)FyI!+0VopRUWEAL}!= z5$eLTxR$i9l99~+O8Ki1=dUF^oApp<7M{J{t?wj;`s`$ ziA3Lo*XOYRYo|8>wkV~L;GW$7VgBINGzjdrfOuVTVfP25&vbC>0LyZ%$<10BKj?h# zx2?qetLyqJ%>VlBcn_wPDm4EVpPz=~&t0GUz@o2%$>Zo^_WfbL?7q0b*EK$p`Wucf zv%e_|v%(B$mD5GJ{CE|+!)}-H3iPa*9lb3Sl=VEmHbuqIGP(tk*heqwu1 z>|aby6#K6?vFFG9tX9(&3>TZy^3+JS{xClm7JI>*Jrhachzw?r^S9P#>mYWPCS9$+ znAzj}?eIsjKF~6n6#eG@3+pQn6aIpFqo!142jt{G>`oOi}L&zl?`TVRB{(;>pJ(_$jp1q$Qn(sBDuM312 z`YO~fjZ!P&+rS25-}NQ0AE5pa_Yb3B*!l4a^^+UMkD<2j4-znd&qv4lWvd!L2-ccH z!p(U88G`EDZHG31;W}M~{MFnY1Gyy$#Bm*u53zo^qVy|tIjl+D(q#KzP<>(6E-%<( z6GKAV%J*N^(;EpxC+O2S58fY)>w8lpeL%x%GPzv+goJaC}&v=mp93(PZZ|&KEvkQDv2u@JX!={hcK{{|3z$YB|>jehisR zD*EfQ=fnN^qjKDYyN+Y2uF43;S2F5vEM4vc?vdj80Lrh}`oZ<@WhX;nMAuowDEh4I zy0pJ)UaN^PT5rB&J`h3mxwzp8FvxJB!c*RSg{!%lKhRSJa#QoL^b{(&OwUg6e%;YRde<5D~Np58W&DEeY?fHCHCDi|`9pwk9y{D127JJ$HjYIxrf72i^n371k_Tc^l?;mNI_Z8aq z(4yO4b3SnVmU%i5h=FK-BaeMP&VSx#Y6yqjOz7l0E1h|MD%JmPwf2F5*>S|raGK0s z+FzC4MN_EwXF|*Ffy`bSzm;AV&qwSYN5+rgzd!abW52%xjZ13O>kyCMije+Lt>+20 zYLg`K8=n86=_l$J#ZBq*$iMvlNS_Y`FL?HIGC8xQ8GC;0U$z#x30o>c>HAJ2xqoq% z#&6>seW25UIP!V%8^#CrFH^>*>&7Mb;}?I?8?%~l@V*$^(rE*f8A*t z3(89tkcJkHGJ9$NN0DDU(8#b=7{9G8auvLF!|0Ei%k2FyUp?%*i1XK+6zU6!1$SY6 z>u)5Wp6^e?`H$yD8^|pmLIVHs^@;scO+q7KcfA4aVa)ZtWYquR`qUAAg16*+Ud)%x zibvq~^%v1Q`-SW8s6WxBb_Dp$j#3!E9kJ07=51-Ou>Q4ltS_`onnqkNa=x*?F!}y3 zSnZ-GiQfR_Piw1#V4T={n($G+{_gwuGc2Fdgq|78`AbIrsU7%3YsUnVGLQQwoIfr9 zS_l2hwQ05H625-Xe7Z_?AK3nC3Mm;8&wpQ}|HaPz0U@Kr{U?VHaeJh{J5+f?!qF)b z{}qS)SO3)?;ZHkFx^^$uAM~g+fBH9QGJu=m6KIi=gcnEOM?@@?|{Tjn(vL3eBzEgfsa zzF(}b|7zk0tNwYD!AJS}$NbF*cnFs7ME;!W7=Kt_zcFkCK$8gy`HL{{70x-?_pSlRlP_SgSg=mXwW z(@58sQ-Fh*5tWS8RYX}jB zZD`|l>M}m0^{o?kykPs2DWvp#b7o(K>d*5}dBe%iQ%U?A&JWhl8@jj%tBXSE8J`KV z&zI_V&5ne@-exJp-K&hPPlD>ptLQ{n>XbpsHu3%r%vXPnNkE@1Aht&Rm_3dkFBF-9 z(ed6SdKb@MaDCbLgRU@tfd!qaKaag1u3v4iumtrBiupSIfC>oC${`TZi{x9jEl zx8lm-@chXHqCVvS|NT(^{SJ#q;5zsZF)2IZ^j~~dh2lrE89uP6`*bqIhx3Q?uNy4` zVAhlw>wCbU}y zuODN+9@_fCsU`_TujdT*epo;M2p=KqViS6Az5M=0lTBiOb+33b6TD^i(*2jSZQnzO zL7Mb@5AMH;5MP@#y&+@vG}7(5Ewjh{RSVCF=O;9DpqCnH$>KjLU-rX%p>@XuGBm`9 z*%u+cMro)D7oWDGM+@ca=SrggHJuSpW;glB)<5QtG!S9y{7~w3F-k6f`v-)BdTFZU z{7}r_u$YN(*?9pOT(*{dKIYH7PYeW($|P2y^7+dgXD05y=|jkX{p|fPe;?XYp}E~S z`ofO;H>?kyjOz^P4n&f_5wyQqd9-*m!{l+au+L)l`M5tnf2lPba2`%hw&eT+n*V=Q ziwYZCkE896bN;Y@>tf^pX1_hjXal}KAJ2FE^ZFj-b^J{Z#>x0Y{T<^~hr`>+6BYJ% z{40I{sV;v=Xs1%S{22}OfdwlP$X^5Qp8@4>T@F2f>4W}A{2#6#_iYjYRBskB@5lWg z?(g_e;S1)ol1TI&`TWi6SPN5*>Cp7L#m<~xY5sQdtv7V)mOyU0C9&@x^H(+K9emuT zNyn${XZEJ#Gw=Wn;`orNiPL#bP;eEyF4kA-=AlSyjlOUyn5`M=q7BjA~Ox6n$HpNf(Q=n z!s*aR&L561<8JkWJClb?{2%5|FXI(hS!js!)ot1HWBy*{*}=TQ;`x|I`TRD_-`(!R zV6#|1`rrOc+`kyry9yRuR;Jl8ygvhrxuo#%X10DXUk?OdxV2{n891KnBiO$c=X=56%IPHLWdgG=Liv}8;TteF(4==N zi=F@DFB!#$0hK;*aD5WFm(A-dI6i!uR|o0uo6?>Q^7}8=ulItMU#63iIepmuF+ZBt zDnk6}*7WlXRkr>K($`m~`a+~QKj!VDR?Pk;@?RBE>H-wBrSoUBmdj6?ix=pMXR9Tx z{lI>ItS>go70*vvqD~8UwPNg!B<@ReQLv;Z1(`kng|xtQ-m+ z9%BE3g8ttPz7OEarhmjOkH?2tU)(Rw{~a#Q=Bod}{X0SaseknYu(wc>=pVTMw`)ic z-1A5#+Ob>N_lNn3^7sK>5&CptWQa45Po?pr^$0&W4YSDSLp=V*`I+PKH!#n+3ElWL zkJ;n>F@lB{%-)zlQf+vChWUH=_Z=9D`-j|S@%RxCf4|CoA=hda$(+yUQzaw)qon5- zXgH!vx6i)M?w^eOmw~qzsQ*nMJ3H91_s8|EhQKvA>sVt{)@KfePN;LERs8b z`!CGjfjR1eYoQr6{LJ~o`(qmVc)_QK2_)Hr`!C#oaekkZu=8>l^_t54S2CI}P`6tu1jmn-#UXI&)O<;QFy_y1SsZNf$ssYC^853fbZY~yHg*dAm);W#P~T4_ z`Uj2=^{@U09nBW>Qa?@h{bK(V9cl$HyN{6Q`$Z@|T-CGzCR(?k#~f4m{}bYCaaViz zUEo8ky?B2g_D{Q&D?sCMW2!y#p4|NG(S{-Lb$hhJ{V%H~`9c%-*+jhs&)=*NU)S#4 zft&Y#OX5FV|7!I$2-?m`A@dt^|B3aFeP_QzGo|MAeJbY**S~hG3V`GK;+p-llzo3# z-}mV99;U9+rtjYJ{0#H;Yq2N1+LowL|L8rS1~zMHQW7ZhZ_ZME|KlNl2yQly)Qk$_ zzaQeO?&W7VJiRHczb~J!)2+S0c4QJ!)3#^!*uUMG*jQ+o)0(z;#LuU~{TbQs{Gr9@ zd8Bxg8MDWHb-At~e7EU9(-;14|C=;EoSEwd#SfB5_V8M^esF&FVuq&Rq-;({23yPZ zZ(qgvUbiihCHtpWApbUWawu&4n?@@3EM}jN`T9I$8l>OLBXvv1^7V`2!yOH#pxVM- zq5kM|>?hnUHl#c4J=pu>{Osps3wZ16BAK6q`HOG)3qsx)(t(3Dm_5$VRNnQ3`4uB1 z`XlylYsXi^k&_y9xQ{h|ezgD0XSyBiQSl`U9pv*@l=B2eE>od5S6=1(q5P~~eK5Q< zk0!x8x&OlRJ>IWq^%&~|R(Z3@_HEpM;rP+P^b;sMHx>Is74S9G6H0H1@#kCl{%c*Zvf#Vi zl%`g5|AphnKud9cX|0s6ODKN)+E$!@@yU$Fu9WY;61IE70@oQNyYdTLA9#O@bNOq~ zo~%XN8_W1qlE#n9KmEZoQOXzIU)Fp<7|e~yAU^Y!vCqf#>vPrduw~O?QfC&$u7@DL zT)a#n#@k-u{Hf08>*4J;L;AM~=PMcQZ}GX+5vCt-k@R<9z8qCWzK*t_YkG43Mv(sa z!L27Ob{Z+^|G<0=>}v;izx$F~r{wcfANmST`fAb7Wh>?K6IJd8+m=R2&ObCm^Kq7r zxCSwIzmv@UC!Dx`AnlJo9ODC3dUHwBEu1eU#Md&@hY++uI-ffk7(v`4-dW5r3x?xqKb)dIsCK zsM8yjoG+|zn0@etu{GlUsMDd$9`luG@c`nRi1SYzuQ;>(&RJR?n>fM~_K3673Jo2Y zJ&q4u9>0R?Vt>8n#&66X$A^EyePF8kTvET-l-Xl_!?{R9Fn?oCZ`sN3|M=kI4L!Ha zCMMeTa`}4U{2FMb7A>*ieBt~o^Q5oXUpkN2KjrgyBrC%NehXK=|=YXn6Gt( z@zB|42|3YrBD;>~_s$M50S9WY@O-B7$O};N_!HTEM4i1q_Fp|0bc7xYToumWCjE8` zqqp3qr6bIN|2|TEfBLl^koSJ1LVe@C?KT0D%IJA?~nUGj_wrq_x4C3>K+Bm9_L?yK0Z*8EdKtNli79LAGr3M zH_W>>m+1HA^RsdPxr~wV!GNL313)*VkO% z#`=0pp*j4^aaEWf?Ygi_uo`oRCZ)(<-}Se>WcJK%4o=Ps+^Yw3r*1u!N#)83{HuPKuU;j!de$yT53-?V^ zNUt4B+4^xu{egK=HLxO1o0eE{|AOt6){K1`Si$CtJVL z{Aht#U+%4)LUwi@$Lz6x`ElkgM7L{7-`d<`_5|q<+1q?!gKr8kzv05{aea9G+ZQmX zrU|w9{FUDy>F3XXdBd)eqJHDhmf2%|v|p+S=A+uvnP+(XriA)yTiEzO)Rbg$aLZq| zzVZIYKvBQXUD%QC^^~6<6;+QB=WC`DH>RirkJl)-WMVD+*dNSwHAASTt80x*a7-naaE|FH}if2j~X|n zgRg#O_s9A~PVerZJ$e)w-xk<}~Z>wgX9 z10khLtU~@u9z26@fl~ee@z-9}3kq`;^EaobFI1iq>-)0!4D+QuqlwVYv8`Zh~fcbKoc@I2>Dbs&TxPMYYe6_Fffgy`iNbMfZ z7w&Izyz(5Hiu=>mH*>ylf0NNve~7i1PfBKXWbcpXZ=CO{E-YzmK}&jY|AgmTZ@%pZ z{%2Fk#H-3Odue~uRzX`h{IwhP8f-7q=cW0PZpT14VJr6U%K9^gqw{e;G#L-UcNP(+ zDVx~(3qk!)jfPBttB;ltgMpFkdKHoOAO6#64PBl)DD3amzHtFguBapVk@ER^AKd{` z{M;1k>*EdHz^0>3X}&$zUvPhK^@(n9?(ZnEjg0e!^CO4t&tc~wEqbXJudm_#jjLwc zK<8LLvg_v#_Wff0&!g-G42{vInQ5!#=1-<=2g0}$iutSG{TFQen$mwoYn|lfPfxr( zp;NnL5;~pxPpnTgSk%Iq2t$egQ$qPu-hE$4tW71oMsfcag8X0oWFukS>i+cRsA-%J zC8_?N_A3ywGt)`x@Kx;n^O65k)>0GJtm#OL-*7&0esw@R|F@HV8aY3Z@BhO4kBtjN z{iSm%F*qE~J|FX^C+ah;f>KHKPgmLfrSsj^eAE`6JM^G6pexhYr2QAyMg2tBkwWrK z+A(`PA92+>72$Jv2Rgxv&kv|V{wt&?0NNF&k;5Z-eu3*(tv6{4iI2O}f)dUbLHhan zLNWfdOeMK}`Th~yUszci0f%;Flm4x?Fn<1@|0-+&u8F;g^R^@G`IDU+N&1i8w2g!B z`b$Z-=<#y-8+N-Dz?HrVotTYA1tX^ zSQqwun7@`|yMfj-cZK;==7m=<^KMgWe{K|ee$1a+y$u*m2_RiI%hxYHop}TrVt%f- z@r>N~bF%#asI`bw*dH}_!Dxt@rkF2y9RNN@(}_^Q?~nOO395lzUv%k*Xx_hz{<| zjB8w-0E z7#x0TP`?|;)HCl{7vZm0_;!fNb)!Azk&>X zVUFm({tV{)C8Pe07cG1tzIhs1m>$JGKN<1Wb4xkA%~7Epo^!r%{FwUO7e*JPk>PYO zv&Vcroc989>vZU9ZTWm1brH{ZxRpkfNGF-Sj>JDK9HuIK+iyW<-{JZl_HPy`esHut zjnw9;F?(FU+C8a>;Mc1=y*JHH=3k}p;{%NlIDR6F*nWS)))&_QhRtmNwF{=S&nHJ7 ze=14O$1GV84x!;Wq<^e@{>~=p!$}WovbC{%{?bjN;a0(7vc@ui-QNu5cM}4Qq1dpW zq`s^~8cV((=ZY%0*HVYhY{mOyaDT_n4dM=rbpsUUcOf>_U}4{s&Yu6C^M&;JFu$%~ z(BMH1{+1tqey@80(Rxj3w{wGJ_R{>W%UT<#NDU$y)$;Yjq1#;{=~JA-{*JJg9&l47 zMG`+^zW)6v2g3}-`pNdk{t&b>gE)=j_a`WRd^ti>2tLz|{<4jB=6p-z$3fo%q4(zn zq~hKhw!T78{FvgPDwO4Sq9Mc9Fni3Ou{dA+u38%Lfiz~1^SiO}mtps~2BNuSE4N4e z8$%}g!Z59L;x}(1vv)^)`ncVK$}Y;(W$0yQkNJ!f`@7D$q?1QOhcJ8G|9iW)57Z7! zBQ8!nf5ZBS&U6*wV4(%QH(Ne`k30IozSMNFzn#aI+mXJwyL%JCxw1PgJiz(G@#U^A zV<6>VCMmuDfUTcoq`x2ZR}uyVwWHz|Y`OgT4~r1@C+3nq!ggk#kMg^`WBL%h$A+9A z$MX;D|6p7+Ok24`qOaimZ}cl82wm1slK)};h7D~8!J`K%tbe(fZ4=7Bm($uo9awyd z^^*;2yFeS)(GvfM^Sk3~w+bbr%ITk#RqXe}{fBSgTSHAv5DB@=*EiNT$M1Imhn7=_ z9q|7jtY6v>zYYzmjj8?y-rq}*eljr49c&{~6xP4S4ZaEPqQ3CI^V_k0+0e=#ZdEJh zFGvv2udKGBgMP)x)~}Sm2m6Ddd9N%oWhS4$i2dJRaX!*Or3|tndI9@>uz!1S=MsEq z@`vtFx z48CgEknHEYKLPVKW_2{|*|d~wHxFa>1nDc*y^Y}5y?&DT67x0NdNC+}JWNQ>+5G>( zSvo&zSF{oYL*W6we2=?oUU#{Jn141(fcOCc7%-`?q6NTZET8%ITp< z`TX@WvxbPiV@R_C&L56Hr>^?}t>a8-NXi`W89hjO*B7P&*vE&H*89)DUUyKe}`(dFJyeqAaiZH zF#AlzU+k1X7}Yn6G`Xh3u4Dgp+^`D957MRW&vCw#Q2usdSSZB)%O)|EHEjK2zEazT z!Nee&gcK%n6I*96JhZ$#eDg0Z3zPh^jFB&wwku!@MECD z_;AedI#8!3bn72&_Wrm(DrA@?Sebh&?2qcPwHmgW=u?wfynhn+|1L5S{nz4P@?$>F zkMR68(w%_ewK(D>+nmfd>o|i-9OLe;P757g#{_7*wC(<8ek%=mv z%svG1QR&x6n76DW)$PmoFXQ_2@?rk)Z%-z9y1qNJ$9x=%R1=4-^TdC`bH;TJ!o}TvHw}y zwk5pVt$6*n$jt@2J%>p05UMibk@-&unc>i5dWY9Xh+37y@ZzaQp6;YSukH@!{fyrp(Kal?3q_-dRIGahbI_zb?KhB>5OK-qicU4-f?C1O+ zKUlwL7A5Lmi?T?`+_kdxBdw23FRFlj;{L6mxIAXBg!cdc*ct?%wl5+Fs&kqB1H?}k zTYs26A&czY#reSg<7>~`uh1>36 z=#6?x}^?~xE$jS(?T)%{L9=BgEALfO6km%K0VgA$j`vR!$y_Zb%Jj(3x{t{)Y z7SMQae{wpJuP+>*?RuIErv@G&X0P~sCW81m9@hr^QU{S?R@@%PXIFx1A?dA&{>pOY%lFED>8i+o^L zekS?ZjekDw59~3a3S2uhqh(=SAH@D?PB%Yr*_cJj3^`voKD+a7tTkP%OCdN zT1YOu=l%!xZ~Xdn1=7U%>3hG_aC>KI{YyjJ558wh`NH+(s&s#NlD3dsU!=>P57)P5 zYz~6E`Pn2Y{~22!SYK#bFdm9NFD2~{9c0(Be<^6z6f#3?iIZghyR?3FQanH0r0-s$ z;Z@4)&C&cpux$aYuQ^KQQ)7OTM}L8l=B6}bh%bA7T)!Hn+6ESw4pykI)0=w23l&FN z9X^=bD@pbBs%4$P`J|V^{3dy74Yc@SNXyobW6!UI`u}XUTY>-K5RxmKZ-M#Qdc*;? z?usD`2+uF95FgjoG=!hgz37?SIZoU^NcHn$6NZD!?o@^OO=*I8d)+f$y zRBnerWruuH^OpA)79+kQ#q&|y=Pn{UwUXHH6Nlor!XG!m@rpWaQOErgj^A#6^o8hw z3rSKb@4v?V8DHwJz`VQ4^h4Gw_I%hsg$MY;jOr|6<<0$5G0tzq^K=Ak!^~a<@$AR-Xz%=bt=va{%4=Nn~WUe7?HY4}+Z@=1cTB>|gZes0k+~NcqA08%>;jpy68< zQQNs!_WNr{;zPGj4`BXN9XhrkkgqS)|Kz42?%%qWLtHF2F?-C<{%LohvTqaGc}xzo zPe$=wlZJ5+VX&0wX|81USRb$+@e;l?Z$TTqIV7`}_CFc@_J_>4Y+`+K2D8U}{TdPg z)tj?PQ5XLIiuv&p`$Hub*s3e9Y(<0IsXEiQma)?DO3bA8*nFVMRg?DLNpZ zkIcgH@OSqzViLstLmbkl;js=BRoaqI?d0=uuqF*Q_1r_+_#R;E+ZOR*-p3Hy?st;x z-@tsl+iwE4`v#L|`tswi6+d&pbHq_nmAsOze;j}5Mp!__M#bxYK=nbea{EA%*SX5< zrS+d~Nj>2qgc5syzP|AKzwy2v8g$I5(&(=Jc>G`}S$}U&IKan*STapEe-`_f`2NGd za-!n(e|C$Skh-mxLjR#Hc){CqS>)Me?mx^>eW-c#T?q8orokry*!siqm)EL5Nb=1k zo$~nlFGl)UTf+x%#7vj2(~_Ux#H|c>ZCA z`0$C>fe!J#75b0wJLkiWRlCW@4aIW($JbT{aA2I1lf!Qvny-Brq+mFQBr2_kNNpn+z~=md=%DqLeAH~jw&PSK5H_&KcM_Y zJ-r9iRfQ_dUwQ}JhEA4R)NHuG{0Ht|@72Q|${tT9zF*|~k6|{Kp`WrUt!m8cKOs~a zpM{1Eh4k(773v4Y-JU`3HmHA3silP9zlTSICCwsthI4%!$7g5Z30%6RPtywJ$7kOA z#QmkKb4mA^oG`ya=4&lTh6eD?d`{qutFEBNbTObhoM zasKcBhft}1SuXBhf4DW9bX&vu!}@};&Lgn&)}zraQ!Yt8jZ16|t}BNq^ly(7Uct10RN$_fKDe zouAYs`4i@|z}_FKa&yVHxtvd|PuSlU&j(x4ijE2_b^h=Dtq`9{>Eisi_fsMi$&ZV*Ssw%LDk-NRO5V)G>R^=eAjXVAeF3 zbRN#j+@gDs9MfugZ{8q3# zX9y{qC*MC-uX_XAj+#)7Ga52`X@1or+8iRkN%_P5e;4h<@jOnAXi?pDx%}<&iz z!X)!OF@Fmd*umvGDPK5#e7f)=++Czfn>6MA5APqzdodVV4pGdP^{7AaR@@(=sQ+Qd zV=u6tlufRGmd}@i&s`8c=+fr%cz%_P@~g!g{o%J5AO7jX`6@#3Wv9!2(AqeUxKwd| zus$BV`~_THZ$#tH$?8j}|DojuUpOwtcTbnh;=d2#XI4*tI2fEq;&lVrbsRqiZK!}_ zFPhWHw0dXeKT-eeGY?;QY@ADU57{z%tUu%)d<0nq`m}5ppMQ(@hpg&62GaGHkc7Rh zm_6pFzwa36Z@q+UzQpIl;QEnjkBhK(xGL>y$o2PRXKDZ5{iov~HE}sXc>IR^TZ*kd9PjH)rpWe3;rLVCu@xM&8>%qA zOnvhjX0|e=xi#|n`E;ZM4D0Euu)d^aeGat$D%0X!Z{_l{YHK%W7Ac;us>%7SLg%v{ zxo`~<7m4RnjwzGtze+3ZKuMTNZbor?tdEcRdjY<_Ql$sKACc?7bae+q@{}}%`gs40 zXV6&3NFiUby}V%Wscd4e&huv+U$&oLF3u-uO8+KtzLXGOE4v0j&%60#ZSfYizHoiF zRj(`XvZV%v{qp0>h?)NIH!zz?y}{1hSmeCW(LxZa|O?0U@YKco7sQojl?pKL%E+?3DXB}-o@xsXe4Z{_|8&+km! z76`u|i1Q)V8nfpEl)n+Rv7pnbfcQ1}&ek{PtDv(MG#u?i?lt1yKjtIpaSB*_?InJG zygv0A@nLwd8MHm&OnUd_`UK`fr^iRoI^2$yjSphamyG<6^Cn}sxJ@xXAkOz**r+`% z@@U5Far|du*8yhT^HrFijWvD+OYfP`!Paxw`zNFPY}e1O(CVd>AMAe)^s_IT>eHuAlet`czsD4}UvH~n`DbBwv-+O|0Tn@=R z#(y6i-(5I(3yMs2>6J(F^$m|v{t(}Bv4juof3B5W0gYjrbd^cA^MC6X$9LP4#Qvja zdBnfRV)p!1NFUc%eFh7+8PQ>Z^8Hgk>oL&r_EK{BJnx^y{M`8b1e#^Fpn-etv-{)t z?o3exY*@dNd^F(oD<#yQmoo1$oP1lgo+ZD{0hAXT;73x*OMQTJp zZ}4UQ$qMP`K3R5f+Iu?r*1-A0`BjRC03O?w>H8e{{5hW)2=jWUOZdb3dZ%HYuRXWWGLR=RZJY0ejp@6uO@^H-kclZt~pz5^8BjoN$_60bL*Eq8Oil+gYv z-Cq7M_~&BM=EG99zHoo}nEg-T-oKV~>7GN358VIy#CI&*?^j4>o#6d>n6GsD7#6KF zl=vrt{F7(PP&hngIk8_kNw&VF{jbMEGz67heW{DFKH~%LAAaYE_%Po5J`6ptPkROP{#hj@>Hd$sjf0@^ho!{+ zmVEug*W)@o+^$W-EiBpd6C#Ztx8x;5pCfz8ZH-2xPlUZ#+K3 z`emShIovtbj1Kpf^_MtH^E3Ts?cx4cKZX4lcD?R`v$sCYT<^@DAMbzMB6NX%dJziw zwe)%g`|8_JGXJaG{@Cs(`@od5(VE;EQud+{mXw)C9DoIrg7oiKe{9R z`=j{PC_#XViQ@jq1o`|46Wm~=Q#zS{y@dTfm_NhaH({Eg^!y>LPrmHw0kJl@3iq4;z}j|zzG zWJC}9aQ~@?_&X%-ukUfYfIPY{KR#{r_c1I{HKHb+9Q&8f#yng2xn?JgN{@Uz=yGI?|h_Wk1h$-0e1{d=uA-@=RYtAzZg z{<>sXtF)gC&*1elTpv$+t0C48>=pV?NL>JJjvpg_6K}BfkLOQ$1vG^rgQ-IOWzCyK zknjbFIa$E$@q8Q;wU%(H^>Bsp?+@3FLSEGi`c|upTz)TIFa!TeDZg0XbhG>e7sITm z{Q_RU#QA041WOpzZoICPc{R)AW-Q1+xBkJfGKp=zYlCAx?fhSj}Skf{co&p6~i->Kh+?K2JOZY!QY;{L0?n}cEE z@)cxf^^gYnN=nJW@_$HUXi03W9TziDV{$aJo8-;fl ztLeho^7$(nUQ6tz?oW{atS;;fsolmatiS)Xw}sbx6G+G5 zoIf0&_W$ez>b0rlbtJFv5i0G!zvg)!UYr*7laIa`gVnDDL7LeL;;}80*%QRqmDqdm=!GGDx$Q1{zhuPM2J3h@cVatv;lGI4s~~-* zU9*RL}+c8Tq$vljp;gc1OruN4`JA3h{Nh zxrR6&&VgvU@ZT5fJ74S4VfM*mq#*hlTc5=!KU_Or7moIIAwT{2`onz9t2KlZjYbf= zwesW71G&X8zu*U{`Ig7|L;L^t#I%Kd3j-ADqb&wD5{CQqp=X}+{1xYaY3DmZRKj?L z^|^-e0%YG(r}iyBvG^0u4;?qh26kB|O8CP2zh<;|gsHPriEm@xUxNLc(wdP_^*xs) z4CUW1_Fn_Pdc!T-0%CMhK0iD4LSd8n8sgVx1N;3;QG7VpCIU*0)|1OW7PISmX#KzJ zat~6rw4mWl?>V#h9 z3Go>%vzPjpBdT{`(Rc&u@5K4Q@n3{~C{%V_L*6gs`yVkMT79O&xCJ|jR}VAx`T1!5 zcYU7Tg`KE*<8@9VbZxughKEf4}O$h+8g_{0pyd z=beUdxJI#mufnz53g_i^_^ho zp-7UE%lX3k|BOZd;GK7Gnta5D>zhi_{>F_t;{M_2L=vpT`NjU@vGPNx*u+Q~7^R;|)*Rf)ejn^#md?KiS01)h=wI4*8wpEu^T^km^7;7K`voNbG^01C zhByGrsv*j{->G@n;NmQT)gn`|+wd9JWC%bVJ$+ybb-n7|`%Y&KLGS%}?Bdf{6ySv4ed7GVa_o zSiWQ@DP7Z+eZCQzUwGm971%bnDecp-3ya^Zs8oNnS(ymeg7%VP<6nGzBK~$1seyC2 z1BprD`Xi3t+Mh^+HiM6o%@6tcmN3^+nvD)oQZ^ z^xG3Dsc&OGGp8yEkr8$@IeoZXK7-p?!{H%G3iGQuTkga2rN%Trk@Km9`mkA8$ zQc0Tz`F!So_znH9+erCD{gbCIj(}V3@=2_330ohyes}cl75MC~M;Bh=^#vs~|F9z4 z8{qUZa$wjFW?zNs3)g}!g3omwYHY^iL!5sF+XsWA${LdKb3L=ieD=&81AVeqlLV7& zc0CUHze7*N_^n54np^bH`M>`Ug8bi{L(@PhXBWA=E{ECU_%GYB9CA%t(&i=d{of_6 zQ0Uck9eG{M{a+QzuLiVM5*%Okp$XCd>;I7UN9rz_3ZswhB)Z{)*!}ZSd{`>#7rMFz z)cPRTC-MCFHIM`WVt-@9%udW6?~hqndkwzj>(lsy-Q?z9HwPxb>r|27*q@AFtbZJC zt_G9OE9N(jrbA4>lf>NY7PH6theN71v~A}~b~kYUg!$E)X#fUCM=H#(Tq++x_SDwY z=-of|`M7>wpK1zGPXiUkhwoG@z|T2KVSi+kw12QX&yFf34Ux;=!;D@~@+V26KjQf{ z_uKS?l{4m({h>Vm!~W0l?R^*qtrYTQ{&+a-3&|&{l=EeV`u`ubyaekUn^K=HoG-k; zS^uk8-+i@`7_H|1I}`DB>djebZKF+xx@EKVkNG+#?jIZXY8`3wg!eb+qxiCILn)Ly ztI+?=hayPd7`|r=#I9XKCUxcf;QHN2RWbe?YfPsc;Q9vkk4x>Qz}oVi#L0#8i}lAA zMvaAw-}=&7A3Ms{uauvf_pzW|y@L$=;>OlLjvtk3%V3CDe>0Ec^R+QQNrPrU>yl#f zJl~Spm!kNxv;8&jtk}qSLK`NOyDH4DTAytWFZ4$#^l#grn}A7Nki>uC`A(`UilOZ9ACjE0 zl&$|Fq(6Ka(h(+}R?N@G`aAIAwbZbHi20&p^+!TJ*-pMT{@pe^R+-93-l4B-eDev-O4R zYbryJ!1)?w>S4Z>*#qM1e5VLFV6lnNi_4fj_HVa4oQATkn)G$A%gi48w^m70U}4wY zWceJ<=L(eHrTHF%&K<=5?o-vw9_t$yE+oJX-D09NV zvssx0gTwce`VBmO#q*);o?V5s-}p97Pw@chAN4b}K&9SQ zqVHq>)>f}M%xXVMVg0Sw)%|cTTZz^lT*LTRLi)#cKNHZuu9#mFt77PN;x7qtTqg5h z(*19h56!{CYl1@kzGbI7kYQp>Z#GL}{3@aIzpR^y`>!8J`31!9)9XJdnG9u&F9Go85!Am@9jE&U$@tF&ULQW{XCxgh0dlsV8d<3 zrv}l#E?;ipvmP1(K52Zvd&wMh|F9qGX0!i~*8hh^T*r(9>YQqlZ2em%oldsL;uzTc zWd0-Ve><@2B3^%>#QmG!M)PlHKe-`lo`Su8EPhGjk8@LfQEh!P7)HzHZ+686+%aCN zuP)U*f7JgwF?ls|)6${ob{NlJ74iS>Y|TTkYR~QO#rUK3%eUtR;0EJ!@N&}>em$KZ zwbs5KpPw4UeamPD%8Pq}I6C`0+%O%;uc!K$bZ{kxYNSFz8uOp%{B8T|N;qb= znIQf`_0Q}4T5Q=S6MDBme*aUxe5SO*47IVM@%yGy%bX4qqPW@l@A&(p{W;&~XrcD% zsiN`6(Lq)@uO(4jL_FI+)c^Cn*cm@LEEL3NsQ;&Pd^g zwCXN?xX@0ZpEUnHP0ki$vvShi#Namt^`+zWUpPl>B_XZlF_o9E<#w$_R8>KB_2XGi=$ozGWs z$KY0+rS4rT7C#d9r;dOCTxOR7LtnD^DUHvljL5(ZUlh5o8PECkR3Dw@twxjG8BmW2Qy&(D%PJz{lCAVYUrXmRy2MyT*ESFZsva`+Ns3t*J1n`lKPdH!rR`Da?c?X94O+mDY0n+&Eu)V`e&z8?!MYoPr2J*Izh!uhD@erce5H#=~0YTn*IXz%ztQ5z5A1Y%6lZA3>;oEKZI{&(OLII$?c11bndm-9g^TBY@%An4 zf33Sa7#kL?7Wk)>U;VKKm>t}ibMcZLU!A;k6i$|&e>x|CJs*0$OhU)IxP7*;zD17s zrw(!xP@&sSf&Cj#_%%Fv6Mz5JD%KY=A_Vb)v1swdxOf-M8#Wn<;c4vX%Gj=`> zwVx;Jt77h{v4Z|4%CE_ZT{wU069|uG{qc1Em(CFl%%~IB-;gW1_%X#nU?0=?(pj6I zcqGV-Tc6MFkLEAcihH1EgQsYIL}PI#etVJE$@nr~P*bCTFtsRUn)%Irf@-&crm1 z>*9Z$-~T}Lb9avg7_#vwcr~8j|9_g_m^nWcpDk44_Qjs$*E zwq8iX(ay@8^WYo&dK!Oya&8sYcDx9yIx_#2o}W9@J_S9C6}T5Wo;BaUa6ZfT!K?7f zg$wYpgz=|B_|uQRgU?@Rb3K+f^GD`Gls)vrsfnqOo;;oZ{dE51kBt@B^H*=q!JXN^ zRA28tT81tzDG)WR55Jz)2h=#8LfxZZA-jm_E0Fq___+-d^Q?hj7Q^0uR9_R)12H1- zBIGKx`!VRKku>zXFke;k+E$5)AqgC+5+p(hYql2m% zIK_6FsQo*up(Ex$bP(0gIo|2G>uL)w@^rCG`?hpS544N+677#r>70pEwyJVbeOY}r z)z96t^)b0t; z`T^jC^=Z3f$KjmrI|cOv)c!5&b`v-Hw&R}kW%e(PA9a}^JzuoVVHjO4o8JnpCs^pv zi<>Rk!|#6@-z{7)AIsl}>*xN#skm2FnY;Q-Hov7o?r2&g%|8xc`AtXSzYbfTihszdEz}0GeNU{uoIBzQ-$jD_3ymKs-?)H&9;#fN(|evz zs*jfs=wX(kw_A7xPHO;pB`Pu;rfi7g8BifuX&GdVq{}`4$m<@X@2we zaC=-i`mm_JI=__9IlW*ES3l(h&nL}qZd7o9!EWm+XkX z+RpXF;$>%HtI;ujJ+*JwwMxUtm=@fgo3izF*Xxz2t)2-1UQAzUd}+y`G<=`ff^(fv z!{0v=KI39SaBA->pf+nWe|o z!7{9E*PDZ3{ba^}Z|_=)lj~C8>f7G@`ds3_9y(kn`OtL$G%RJ$hw`iQQX2pENC!J( zd44_hPs1O|q4qp;$cSg}f2yDQ)vGbAJR9y#yv_4V`x9fmTcUo%IMMooJm<~0cJ%`o zxMLr`zKZnk8@+0S168Ms>TCZqqjD?`Z{t#@vHPQZ@2Ts6%W4;i+P_;KaXC+(@8YV| zm-D}$@;#-a9_og8i~6sjTn4WBrNTw+{VkJk=T3ug^wJP8IM42n`mb+}zQk$Y4Y;TQ zviWxYI~>PXL_p0%#y9Pc>NGDG!>Ile|25lXEYABN{nZ~)*HM#8 zS-s7Q#b<@}dGqft#QKXTVOkC2m)gfGjZ(4gu@)R2ImNH{CH#(3@x->ZfJX#e2?*q`3Z|9`Z9KUZNj9yiPe*S8V;=S?I(bLjpqe6+3- z^1eUk?~mqZLhgIxRO|ELR6UtrPx~)Cm2cwOuG-wmu`Iqs^P_fwOY!Rsp}x}kA338~ z)G??AwbraYFpd+(e}}JrDftuMAKG%V{Zp@b%kaR8bU}WH@>{t=4kvZ75X`5c{GRq- zjrE0B1pSSa-}YBp;Ns$OP*?FUJ|sL}E_y~RcKTQY*Os#WNZMb#pj#UZ9y?t$zjJT; zA)I`t5jtvn^8C~M>YQO6P=BtYD8GMyS>-HSvy1aJTE_oBl;4KA-O;T{$ZtHEUvtU) zBBlhk;(C8<;Q6KY^Dm2m_@^X9G=BUuMLj3K)m(0Olq;{#G=BWlbvSy=js%PU7{5s7 zb3B(^!GRlu{f#vKl;Hu82p!h4}o5r6qHO`@KFJ-QUpKSa2=iMc!9(EeK z&1CcEY5pfjCj~1Tl)0BTW!uj#4J&ZYwo9O}g4xfs{>V%J7D`k*a65l|Zsu3$|32>< zg!!$rVbV;-e<|TVzvCVZRI7#uYPIb5bHe(iw+p>-ai3Ip`Ed%rzi9p64E-nA7}1yO zmdN~H8lQT9*$ZDKoQLsUn0-z2v%mCrV#$UI*ep@y_1%u}|IPT7#B#wv2pull{@xVt zgIT>ZMD@G6>9558tc9rm+fcs-KiVRE_LN;;@2K7a|Ms?l-V(O|XnZPZw>l=*i0kuu z(}Q^IawD`iaF@w<>UJHR_|j1{|MQefN3|}}`BD+@c>9~immddr!%MJKkpH24|M`(2 zoe$fJ3uyJ8=Ua~0-}PYw@O8jiQGKqN^cH7Tm9UviUx6EdYHR#QEMBvJ&gZU54tG;r#bg|F`Q456tsF4^@vQ@t@QB3Aey9 zH0>!pAFqP(N#j$iqdal$*YlvD#Q4l7_Vc%2JMei|vVE4c;(MD_Xj ztfe^8AOp1S$TdG7;rtKfD}N-b9t!mtNdKgqLI_R@%7K*Be4Za#e}6wh86ASf`CPnl zCr+%Y0yT+*U!P0n4+MW}jm~{$h}J(H?|uNC7B>QHbdkxgVwpDPv|lXhKc6VSfEPct z=DHkF=GRkwuKd{*-F*w>U_x!e75UG7?e{>GE|Rnxso()qz{xgLMgEt!2PtWP|& zd>A@x73VW7;40?SX$knG^%YqF*!|%S7~8s_|Z&=lD8~F7diGQoKem8#pTLW|M zGX3-=`l(Rjf!mj*LhoTrKPjIb8%weE*?ydZ7R&EYKA%LoqnpQh$XwTpzrG6TfAKGj z!D!P;a7|3vTJk=;9n%0E zdoSksqV*NyJ8GlKgvEmRGmUR`FHFVv$JIDrUD@%i)M;H&ZLE(dpL>$i@kPhhoa4(z zUSE;u>jjPeIL&;WfM4qWdbP_zU1|TXzLV_uvzfHN^V+dULHwE8&uVW0x0&w}%ul89 z<-M;ELs6Tn^JDfg68*dvYlj{OjtJ^2Xnx4z&wm&epv0NmGX1O~`Jr;VS1&FqL0V=hL}7-;J4n zUw~5PUn}(9`m7e^1TL08%^LE^_y#m^p%I4P~r$%!8{y>Pgzn#c|^0ACx>i_mytc2f(jTg0l zBeZv5^y=qeIhN@wlK9nv##U%;GE=nv-y$y#Z(nJE-G+`b`OR6=9xWd%7VV!Ivm+DT zx@vI4jEedDCC#+w~g+aj?ueXa|ahO|5uL8$1C;ehstl(3F;fE{-$4g ziP!HA<2Hrv=Jl8Qzh~AM;l3-8U=YRPU-88M9XeiuWBf_|1?g|oA7Fu{BX>X_Irjdg z_VJakQ}M!pc(C{;+rM4WItdTtDssLx;r#y8;Dqt3{q}QkS^g6EBXRgJ2u5Zz{z3`AwuK(pt|UWHA4T&= zd94~G;kL%`UtzpVel??3;hqCIg8p#I@7uqM=v_KqG=J2%Xb&1lUPH<;W?xf&eLA*6 zqoFfJ<5$K{+hMG+lYmdEuiXx%V@8=e*JR&<@k#0zyI$*zUd2A5^%W(r`r?b3p)gA4 zpMTjxP@i@6`%ug>*bJNB%H~UPcNRt-7TUMe|7MpN(u0N*wc^(t-qqIIkuNBizL&9IXNa=h$lLR$L@ zl)t$%SKv<-34FN9@~^ahBBymU9#E--zDia6{WTH&+%nY-V;-kL|29lN<4OPMoKHLP zVdV?B+4P5Bug3}X^YSQH^!t(u$y*qIG=3Bty$#DOE8tX?3h$pf68;{yt&v>v(}(td zW%Kt);*J)BF9`Uf^-VQb-%36$GlrGB+4H6P`7t68tF^9y?{*eHqV-KnM=4@?gSdWP z>9QSXj(85^YO{GhLWzI6Gh8|!^XyDf|8%0+ZhRZ?8fv>vVSJJP9EEM|@S@2QcYql;?~IpjEfe$yQ2%tFbUytzzrkE+!(nzlm6fo+?xD25 zRcTeIU_K?)&!%qa_`|skr=G~p@1XkGR(B}gaFU*n+gyJ^_0!PI3{P&^0U@Vk^PAwB zg>U`Zajmpj{D{uKJJ@v!9=;;3pEbsbIQ_n~K2VSGYe)F4RiBNs-X#d)!<66nq-5!Q z0qK17=KK%spIg1q1)KcSAZ7!zpQ-)3#OVxvZc^cX^}WgSLH*mgM}6>1T^3j!V)6xipaK1wO(jihU`G0YE;&A0#U75Mu@ z4s^6(^Mz=ARM|NNZ0|Bb)W6ls*@Jz98^HH{G0*2PYhnGd`Day39Aqz=-`#s&3$^T* z2;#$(U$fI^F}_}ni*%~v`2`U62i)4!36qq3Mg3QQt`DwD7w5Crcti9%F3z8=^!$UV zdc6hlBYOU5%~eyp*>$Jj{9dZB7MP9h_BvdrQOrN3^-nuhCgbzQc+vRo*Mvk2Q*Xfq z>|lIS`?eu)HjY@51a>D_e3{0d#%G7)r(Q*%@^mM^zp1`f9(2GKgU`X6$t?b4NA$Hz zoAbE+X=_e0E0cWWURT z_!FI9Dd)NsN2iv9-Co9LJmK?He^=~3F$3yPG5a=?=&#X~ZD@bz85kV?&R<`H@cCoA z7dHNP34Xv3i7Yp?LM6neGySFUr$US863Ljs@Sc;+=fF=MIBD-Cn6ycW|9+ak z^(uWWF`6(;)c#%Nxf1(ayDpgTK=t=XO9kBX-vm+rHR|UUToY0OCtjxVd?ph89XwqX z?YE2b`8$6rCYDt~_V+&g`YNKo&|V9VmM(!@W7+x}_)r?(=-Y~O*Jb=t|20XXiw^UB z1@%=_e@|~t#uw83(AO6VmjC;IX#RH4ncg_JLl~?c^6&aW`+0X(DsCUpmYcY|S$|3W zZpUO1m`TJ!}xF<#uhUOdede_YuqdVXZ*-ji^l%~8?%#!}NH9Oc=P zJJKeS-=8%8)FXEmcKDJ6^~y~DssB22P&lqWUIc?{8Q)dJe*T`f0P`!(LZ1~Ze?#?m zWWrh8Til9^A9H)+%Amvb&-{8I{4PH%jUR_)!m54x{CZk{ zv1#;n3Q|{YmZTerADqFZ(8(a4q8bq53*{kvwjFHvt^tS^k0MUt30Q#=EiQP}M3$Cclez zsNhDl7xiBa4(vkho(+(@W){Dm#*Y;{Y2uITO9b&_1SNt0xuK&j?x_{mSN*bH=sGS; z;J;G)clI6wEYR5k<(HZNO5?k`{FQTTHqH^~EA6jaSTG7zr|p6TcI^33eO+jgfm;o< zxWd8Af0ZNgU+iX!%A1ag>g#&b1l(|@1$Qx?>8mfXe-{PVqow?R0)3_YHCAjwyPd^Q ztGSEqPr{$?I!9ctl?E@)9Ow5ZjUV+Mybas$ss{bMbIt38{jqvOeXz*xDs+ux{RPzi zZB@S?qx*b^4Z!%)Bld5T_EMbVeg%>jGd`*PYpxrLF1q(2?OyZwm4wefpIxwio3uZn zbOwL_)W41I?}0B2vOvGdfd4#>*teNSBQdVaQ~0delJ{S$2!C1!t0g`68iI2x+5L4J zd%9z^Z`771;$Li?o;9ko7R~kRcE0M!{+(c3SjB6tCeqlNM zdT>rAf2V3%V(<%l(frL=ZXfoq{04@{{+%z|PQcf$s~XrL+*#EA9paUYzpl07I!3(a z?caD}|Grt-5!1#k7udfv{=2NACoVA!6Xa(opEEX}L&I5ZxOscn`COqyAJ?@qK(m!w zMD=l^;sxAtPP{+XZ^0<6eXt9Bk?~9OtNz(pI6SrkSK!U;V_JVazukD${CWfw-?8_H z9_f$$-FO1$?^fmpw~@_n@^O27Kj1VBelJ@;PY>USc3q_Q@oJ`@p@iRaI*T#ua5^ko z#Qayv@5HBDabC7GKQNB*OZD?kf)~D; zmu^7fPZqzW{jqV8a=4|Ft!RJU+WZ)NweBr=H!=Q! ze3}#wWwFeDmLq&dMQ^}b|02lVw36RnG(P;-*B;OJO@=QGEdS$6=AWew+lYpdQhj~I z_yoe|kL8O{cU3w(&1U`=jr#N-^TB6dcI{(-L+Wp`95g8V)`0G_#AT51&fYc0_)6K{CXN+ zx)8Dli^hF|HD?rg{iO916Y@MTx7`)+`()J2S6hL;bRQmpnGsJRx}gQXK9R(i%rc)z z9JU*RQ;!6GJ&i9t=;@8ery^Juv~K=>VSUr!kuM~l2ABXhQ+9l5?DGKhJ9--&&zA7| zN%i-q&0k6F4{`ks<96VXLTUX&&&SMuCH|}7lNOk(K3g=tl&G^0jXwN<-rd9a^>Un0 zfA2cAMbp_XqWT;2?nKU27gg(HiLLQ}{wLMn%$6N6te2laf2sefI{OjoZrA7Jy14V_ z8`1Msy6)_OJ8HuO=aW%=R(I9MkDrD58%px4(=F04d4W)WDc=WdN1#^w-J5J-7uwr&mMR9L6`*-`+7^SWzee9RpUM zOyg5&bC+Vxj2y^}XYpZLKU|?1f}v|3fVV;+|NAJvZf#s}jZ+qk**Tl%gZi&k$$M~` z=@&4wR^s`SBmV29mo6C7;WE@cWA-!6|0s;zh_iJ{;hv>3zdo1n+vaJNb3E~|0m2_G#%~;n59?g1k*JI?5!K&oDr@n{?R*#(-`LEbrr`ae^5mCf{E~@~ z>doHY)PGHW8;KRc&tdrFi_QEA<*L@h8)Wl4wyzEbLv6HK?@kA#9i_oBwZ%TybGhHfUX%&#$NU zb%kdLW?AQha{XKW`qaK|@y7`#{JaGJ*|GQ)t)FVUD-=7qKZXz`rvFOT!v3MyiIo!R zghu%Kn(4P32=J8qyk9yWPg?@(->CBUN8?x3MzxY-*N2169#-EHO6rs2r2Rw3>K{T( z$XlL2J5vAHdBHcy8D$&T`jq+alz**_%6Q?zY|;E~Wv@19H`f&krn3D*?Q6LSDHvX^ z#hnOl-^{--|6@_3jT-CxVQnSzFRA`IR;6H*R3Clw9?G=8@3zpx;<-Y8k<=fXwMxOR ziCWyS%jrD7)c#J08Hk@JZWYA0s6KnYOTlapA-|!df6v>0I9_tx1AChLFGI=vi@(lS zP~%ru?$^bI&HG02%0QFh7d&xp=d*zu`*`m_Jf)zP`}DHk?=^(H$@X95ZC|xpZDIww#_18pjx)w0~f{ z`a8+uVH_Aw__toz-=|x(8TAxiLf`eQzA=;7*D1!zcyaq2$e7IZg`OY!d`T+4+^5Zb zo>##0N#o0%7ptRUgsZ51U0`)Q=TxSewN`+-O#9mENqh8|=r5Wdx@2=6trFUEVo{1Fh6uX+XUNZ?E%mG z?DA9E=0ewi{QOoHoqfUZ$|65S~!`&_|@Qq@o8s! zPgFQ@4VE}DerbGqy8T}4{^u9OzGLy}7{YH?&J{=Zmk8<`k@W9XY;eZb$ycC#-vvA$ zR9|~l`Qw*6cVVg7EB^T+nIEP4atV&@a|OoTl+AC!)^%u=QwS3$Gksl8^tJx;Q;E8P z5p+sm&xi8cqqQ5(8kGakpV`+)?CYSQYKh665pYiX7=Qm%U!R(6z*Q#Ykb9fum#T=q zI>gpXnpOi`|H__kC^K{*J z`bzSW?D|w+ia3s6G#yavlSv z{R98zXVCmpmCrDYOxXhs<7D&wJn0vn+%bzwxVM7wEhp6H@DYH+A0L6M8qNL@(Pv+! zbvUJ@2%c9puP6SqyunN?{gVRuml@x3gm2fwVYqdbkZ;;wWWQwr-Wif9;MfB#gUZGXGrO_ghKVg$3VsXoiU-+`^Reu035N9^|#z8?>E#U8;3!%f2Z z{ZH*{TfJbkJN5_$b!G2|I1(SrP;{1_A9@vvr!jq|{kaBN()jS$dvL~%@n1#wuaA)S zCmUadYjQ^X_38YK^UDJfXFP;%H{^KzP9ggJW=Of@l9MsGd|~!2)^pY zHa}92@W1DgB6evK=YM+bHgs)#2mQazZ01)OAG_11HD)`yiPm@gIll)d`uv8Jpq^Lw z_z%fXJ&0^3{~48nqSt+m!4nXH;fxKkImPR zBl#=0f&FoF{Z?pk;vc_4{dW14fu1LY=Y!Dr+2{ge+#nwd=>KoMaK5W`$2bhSE616Z z+gY*SFXaE+TPw_56%V^IW%GaR{#xu>Q4E|R({~yl&w?4adFXktO_a^QV?h|cZT%Ep z>|pkJ4AJ-cBMb1}q)XtR!uGEQ;s1!&M!dQ88Tj;P{8N3;Uhj#=rrw11Wz2qzB>AiQ z%5eOVTLU`JWXH$PdAp#~YlJOMjQ?Ds?+FpB@cXhypnZ?o=T(INLB-BE)D59}k|WOt zwa)ATQH?S1x%X`Mc3r z)PAp4@xT)+Z^DIRn*8_E`mP;Qo=g1uje<~}h2R_&uQsR)sF-`IeIt@_ln}E7a6=hnEp4{Pn5- z-K%joe);elJ&_drHw@gKCGqR2ey?2S zjmcSeAo*Yi{&N~1_kC9-(Ni&nt|jdGQGS0ujmFfEpCQw$SMz#deB34QwPf}Naemtk zjlxf3-b2$Q=08*W{rw(k{q@7SqWy(x7uB%4rn{(roi$bq7fxRRLy~0k>EbW#FZXWG zZTyfg)BZjNq%bm2qQd`91DLh$mZ{PW-LZK$aBlz%I0sG znFSuOkB8EPWd8Zm`RHBRuE7C5CGfs0f(p|Lfq2 zDFbi7qY<0=-$(u5pj835)<_k zRP+86=7*za`(b+B190ri>|Z(J|F#V*lQ`xLgRKW;^JA9oi@kn6fU3XU`0uCn9g)MT zB*)McHqB7qi8?d%ME&0nuMN@QXsjT=MB`hY`FqfQqdaFqG=$9enx0KkwPaki<62t*<1PRQ@(RDm!r*dp?*^T*C)me4eM^fICU?6y(8hf-BVB8k$(sBjb8Bg zpGfk{dVa1r_U%pZG_>H?)APHQ?)JujS@)nr%`bjEjbG<0mr6RO4TC}*+5GGJ&BezF z(*BQy^8ELwkoebF^=Fc9pG?7Pglzuxm%Nf}T3`(tGi2Mh(Qcb?eAFwbDq-g@zbAZ` z&XGr(6Z1svUuE|lIH>j)xZhgM{96*=T5O|=W2NWorT=95MD5=x0Y`FlwbZRgo@v9! zr;+%#T4@>>^I?Uk{d?HrF82Rv$c1{gkXiqsS=$NYRW?HQ_<#1duz#VeW*_|0ew(2F zlJa{rO=`cklAiCePnZAyKsuV71GJZn|zsmil;=RyRnDsD~-yf7;N82C_{$2ttJ2QT%{%*fI50^j8 zhCT`G`m}$ci%AF?20VowIsfs$9|*tsUhbIClnZ!_?LQj7D(D%8ExtU1%wIS7^^{-Z zZf>ZUe;X=RM)CJg^Gp5-E3i1b5QfSZ^XqAUaMubqyb+WOZ9w)k)bMaCPTznsr zPrl;UBjGpQ++BM9SuV6V$?@xbNqu$5UoR}}n+KEZnEgxZL&hkUNTPm<^P9QT2m9qc zgm^2azf~a2KYdTElw>|O1C=KB{HT5hS4itqyOzTH0Cs+DE{R`xHNB9Wb+8tVUx)c_ z!lWLrA!|kR`68r$u=0o;KF$@_@2YqeX??keD8GJZ59gRoQMb-JFPq=DFWO>V_m!gh zZ2JBTw#o0vC4Rgp(|`R>wG-<1+9(>IaxPEC!P4{Boxh*A{GYzi__V{w-Z%`liTbaP zqhqm6jiP{W8lMjMV}O~pvGAmr+4oeR9S-fr$9)vIgdei?xx&g64}Ob>I(OOj_0fAP z@S}Axqz_>6X_`N-8a@S;i-r13?dxl&0&!@43AFgRgWuoOza27lJ~~EUg{o-gUsHW< zo3#eD1IyvC8q;SQpNiS%hF;NkAo~m3pVYrq8yzg2@A?GfB{}@{Y5qw|dVWg#HFx0P z`)xd5wEpYb=U`m){0Th2TE?%Z`D0%bcWl(X3p#Cl`SnzveOr3q^P;<87$RGrt-rgW zX6+rwZL;RqQ@(#(_Qbsl@}T8N#y1lGHsEWq#IMJ2I6u1CzM}OXpTe-#sTTAvF#S&? z`n>R6g(Sqo9A?j9_3hNZRZZHAs^dOFr*~bOf1l95-821#WUA(9C|WLCzq==g;fm)q zu*xr;*IzrL-|1F=B{#h1K~z7se`$U>dvFBW-*15N(PNo?PU<%w>!{$^GajPxY4trj z@q)fQXV}_|k6+0V{q|ei7E6@^q2xNdKFv=xeaORpIVN0aKfL@uerf&os3E%2^RG6F z=9j;ZKZE1UbOrXgoSbleUGn~3xG{d4AiqrYJzak{em|ff;GgRI1SbPLH*2q`eSR`f z+J7h6pUURD=eWuEXt>5^4;%9AYPqT2G!G;e)|&p zdt~DroO}8TtdjqC{Z@hkC3UI){p^Iaf8K@hP4iF6(Qar^dKcE{vG^C|J9*^_RCFwX z^~%We8AmEKBe*`$@_VIdere*mdzf>=gp>2!Ba`3Z+dJaWC~^HR>U0ki zCYW#^UH0+%P4i2(IX%(n-ZoMH`by9)ERvqzBW9nEx;Yrba`%G%7Uq9Y{f3JdP(QCH zH$Bn8>VNMaB>jzduZ+YEmyg1ONB{T|`q!)VR^aBfLcVE!X;sHbczt}DXntAm;!3o8 zR|Z$z8Q)aDM|7KusvRYezoz;BCH}QuuVBnltpLA2%s!|3-TkQ>?pl!t`Da;ug)i~1 z@6Ynb)z6Ay#x4o}`+W)D=KcK`%`GQLX*-yb8xv8zcVOfe4S*HisY{_BaxQy)T-$zT5Z zld*xfBi7F1&*=s z6t&MgpFfzR=hMbIk88{O*HuKH-?wjrTw|bUedp3ix!Aq^Fivh`xv4CDet4+^KDZ^$ z_q*Ts@R$DxZeihGnS9Gt^uQOY(V~2xySfvhuh2fH`W$*fA3N9V6|EoX=AVY?Eqie0 zcNg;egZkf-a!24vjbo7elJRXv{O|a40eB>%OprgO_IYJ*TO5`nuHVlN2I3&6azXzx z^}hq0W~0&jt6=_wU7z~jR+3e?%1g*M%|AJ}amUy}58&!#7C#CleCru3!{RfApl@=O z|NYee=7#!W?EWH9{kf0li}pW0_w~c|i6yX0j`5vI;^XgZLUHEyT3B=`hF@<-^t)Tr zQrx%mF`Sz8mcM>$YvFvZG&djI+VmJS0$6^S)?fETDZk%Gf=v~BK9t|+=OGyLpay(< zneo>L%5UIP$zpR$;DTi9v+1Kq^#A<@e)a0Xuh%2`Y|~gHv2HmI2ABP-FHsQKS6?P= zz<{E+(EAIk4^bihwZ{IRk|~eoL*6=O|5AN+IldVkLcf7rkQ3vZSas4v z+-_pd$+cts7u5bfk*9}$yGM)GhrNBe1Kp;H^Zn=CAiUNmPLyx&x*w>dhLdv^?RB`THm$zK3wn4{BNq?-nB&%H$zj{Wx$>v<$u?m z5Imy(0?tM;{igo+MUAJDs2`SaLzme8~$=@HX4_oA1BN>%44y^4nD3*MAw0CB4!`?e_)G)3N)8-kgtf2EYI1 zNdI)&hgq1WlLNXh+4ZTuKiU_Bwu7bf8z-~;HsychfF-!hH4j$#GyTdX`abK8R6oa; zK%5ohpT^(9r19rb--;nn!sa8;_}k$-%W#}DKiHw1#n&~gh3B^%e;k7EbzZ=_7{))% ze`n}Aqwd)Iu)WJm{`cn+`~CBY4S2q+0USy~cz!7VyAxb-!?A~;e&P?mp3djH^0-Ly zDZmUW*D(JLNc=5bS|8B%gIIi% z^1V4P94GmF0ryJAH?1EzdF{KT`s)JG`Vr&ln=zp052$)C`}~%Ia3$P7%1bo=y-w>u zPRi4^)*nqZ`1gYxC#?Uz_Occ3{UOfx`!V;=$EbiUuBp94^Pi#Xrf$IhZ%d3SEX zPuYBj6c0z0h!fB)ob3+{V!uag`lH49a`>Vg$nP&8^F`Rx7d zkDoSHfJ$ek??CvTnl%frjlKqYEmQdYNBOR)T8Wn}s{nFNv+I-mS=4c7j5B`-?|hj3 zPW8P*Hy^ZbS1QnVYQIOF@ZwUNL6L_JI#M@-4Kj1$7-PL zK{S8=l<(DXUO44a5!@J5&)XE`EjGH%oZ?n4T|@p423nv2mej{}%pM z#MoC}qVcy5G5d4cd1zR7JRzI!paHEgb5W3}eslh}ux!x?PVPgR%=nv4VtahFU!3m& z4?m*1>SAtVtQXHWt#6qb-VIHkMGNxdwEk?X;TLomyF|b@t?yoJH~>f0#EI62&OWmh zwFk>_o3~8m_ZRigJE#oDZy!%Uo11KZ(D~TPy)NKU_5R%B$N%^g&Zk$X8i$8(i1WQ8 zdKUg&dmToYp6B-m&5yP3B+Vb6E`=)BME?G&2*3T}7onqK9_Wo^`-j%AtoHQAs1~I# z%tp38e{b}~v@zw7md^SQsC|CxtT&z;R|@i5m_F0`&%+y5qTl-GaNZ+|zkkZ_^$;gq znEn8!oM-w><7;(;)}!6JMkqYR^qJ1jU1jWs*?Nz`FM`#t(fXAHg+fV?uQ|jjG{66d zKL61S!_GY#VS(3p{{CqHhD}QbM8E5T)G)g;NHqR7GE6P!L}(cI;3u1}LjCheZ`)y; z%1xs6-SZZl!HO?>T;03VGWFZ#a#x($ce`l(t?}l0bm&R+o7BJT7}X!G+wBwe&--1H z&X?^i&z&ik&3D0{VTk=sf>sLS8$lRfchFsm*`uC-N(%GOseV6tIu`9aX9()osD3|r zZI8WeZ@|5B*?e2gT!v_04s9MJ@q8x|zH>J@;ntD)u(5#YGmW3yhj`(SH0k>xKsMha zcPvBi?d7odB;z}i)OQ!g`C#CQrx3A{`QMc9z0-Wrd29vb{E6WAKaH>bT;_-etR4vL zZ(84?x5^hwJt`osdJ(^#>a%*G8#-DP3Hmc=efP`51rncVbI6jg|A*=`cXAyj?reZA z3e5hd^=Y@L*ZN8lu_I;o8BP!fMD zNH#{50Vl!0hV7qt!gtFoFSLji=i4H4jC4MSkZ+nFU$NZ>QzukF?Rl0zOC6M6mD=B`74Yaf_f!3DANWY}>9RRYI?Vnb%J;?CP;C3(dzjOX+26GOe9OgR z$w1*y@2UARd~LselIkvl9*LY1mge}-=O;at|kcYoqi4Rd6#%ToJo8w zd;e!iae#wpeQHcV7?#iY2s0N^JayM)~9+IoJJ*+9$a$YWJ^9iNBS>s zx9oyPg zq;kp2O^W=}zWNS!e8byI4BkJ%PVI)pz4|j;K7d0NM^Y z&F^no|29`Te;_ES1WKKlzE=@_9|m5yQm+Co=*!mkGu}S9VQ3Zf$#}wFpVqgQ=Xl}O zLlpq?nSD>^lUA%-go!sF!6fB6em(Wy)us78)2wQMA#VKrzbE|9X>9{zDHx<32>v#v1xr~bQp`(jCT!Dxs-$m(OMeV@NC5Kkw)fmpS+{QZ@Z z{CZefrKJ1(Nuaw~Hvc_FhhW;E_mJ267SC@esekjj|3R|po`b0WexvU?G*$QrDes!= zTZw(&YP}pDiCZeF|7Ec)@ynvsqW-yWxN^?oxuKlKpOx(Xh`zUar-3tXhl89G(>FR_ zWrBMWW~cSwV)bO}``XA(IH+3;)J$aSDc@1yw^2^sN|f(bDZP>VD{jB%?v2Fvx8%81 z_nG}JN9=d)FNWCnose&8zh5`sg6ka>xe;|6`29)s-C0-K-<_EXtL0h#%aF`h`PJ1G z2PTwB^H+@Tc*1wvi_j4nlv&@cW<6 zFa0A~h~^s}iQ4xMf2_ie^7UXaZzaDT2;U8Q4!Gs{BSHSmko1@KGkPFV3lQh~rO!Hi z^!XD^cbUR}zc0z3l}|2~EOi+RpDmL4&ne&f=Kh!?UkA5Fw_^84{P#hw6_SiOlik{Q3A>bu>dzmje7OGW1^ z4a#bP+TN>0?e`Qd4ZKq!)Mx5{&lsDC$J2Xoqo*-`Y5z%0fG#SwjS;PX8NECKU)Boy zL#h9L=3OuBGGo8!e3X;Ak@&<=fqU>mHoxv~hu~z5Q($ByTc2;4Zo$fNO5EmQ8?FB5 zUr>JYs?2cw?em~8ll}jc-=0C9xZL|0to+LSZ_2Nw+%ybXbqnHeGkuOH_POa?7qoGE z0ufUfzcIxBe$dqc_fLBa7RMRC)IQfgxdgjrmqPXt#_xN=Z=JHVfAeQ0^ax`86STj~ zr~eXs!v78Hjcy;n?@Yb{B@6X*@*k5L%RV>lU z7zf|ivif1lulo{DjM9D%`?VDK_3=cXkH=I>?su39BijDcccFbQ?Jh*H_yB9JGkvD{ z@p~)ZNy=_567|n7tq;N|#rN>*zPU_()rS6&Xif7G)#uUG$~ZoAwP=56lyv^MpG5>% zul}c>!v4=*Id8CRzqEerxQ8X%|HA$e{dFC2zIlx3{L!~Y>v6#KAMmgKoaVp&JKq!c zP2LY@6&Zijzg`t_5l5*Qaf>f6;rXNbJFw#rOx$`()V~g0dKTZc8o z)};#0=b-!+HM!xF)JoWYgz-!5>r>yQ=hMpHhU&Iy{Qd|f{3>sAMx*IZ!F{W2e#c#2 zfFJighT}VB^Q-#D6|F8;KttOc{`WT#e%pL>!vV>aqVY5Dqf2m~#}k2njU;~N(SJDx z-FOA%+Dw0`f33H{0sqV|g2blR{Pk&nNkY;JY&oJHuB}_a|9(5dZ_2ENxY)Q5)Kpl0 zEROKo!vCJcFwz1tireD|c3N_7uxyKBE_{7g;G0EZkt zC5V4h|M<(hDD2#*!g>DO#P2`qAMcAa#SiV$V5$rI|A5%fDz+{-GPVNj1~YygiTxb4 za0>RicMGO0W%>(*-!BzTct`&!q|amgQv12xi23NWZ3mscRz`$KPT1 zPxu|X*c}TKs-Vke*8f2D_i2M8?zJj|&@iUIH2&>wxeWgceg!|*ZRhz&A^JOStRuFM zD}_Ei>iO$a{Y{>{0!u<0V0xE8emy{`Uq{04rqV*mrP1Tzk3=@VMQgoq=bRVP`NA#u`x`^}T~_@}a@lSM zlsNrcFXZ>HX8@YnG(uiqHecA6_{T&2>m~9p7Kxr;H+4+}_VH2To?MpAZ`Y$gC4)OG z6U4{p{DuyJ^=P!ogG*hm#@~M^;aBdM58qAB5&G$lS{K?<< z8C*?dd{ce?@^mt~p1BQ*!({98py5t9MZFw$?`3?)6Z<;l!92`4UI?BYlKKCS#=mSF zm*CYA6_66h`ak6e-&PhL((@B)VB+oL{Cdjw&PfhBT&h$B-=(A572XwD3fh>Dge@5%e1ETLp z&MvYPwXf5p`nVhd-VER?^qUQ8fPbb?OgE&!}ah`Rl%4 z-r`#Hc{3^vM`|tbTCfJ@4xfgY5Z&GwQ$^iPJBMgY;QfhGy8z({Qo6q0&(P=Ptdvb zB&+|~|MYykgg1k5>bp~5slxsr$~Wh69h07NT;V3hcc_)H{wzXgBvzZGL1H=Mi|Y4~ z;m$bi!ZXl6!T63L`n`PpB#eD<8w!3i{igQ!>Qo2Z)b|PW|4(*&`)lkx{4HM$*Qc}h z3ypsj)j44o*Gi~-&G-fop6{+>>W0Nw4NaPiZ(6_dHDw{*>sba3YD~YW|D2!ai!tu? z5V@7{P2*pC4d!81ToDWidd)xoIFjG$k>G=aEZ@MEAYYz8TAwDb?Sz3b6`&i-=8IGN zyZg*s$+K;iqWZmDdb&r>sLv4FZxa9g(pat_KhmbWKr)$|0ItCPf6BMps-@_X_XZpe zx8~R96aTr(%}U9(`S!3|^Pm4I)bFVc-q^4cHMY>>3m>w_10MaAVN?dPWAV+MHz;# zoy!%BT+8!I?d#S9wQ;KE4pIO4?xafGa?C+AejVf29Vc%*Alkoe8@vro*SF^O-kibj zpHLFN{-!+$Z_Z8-wZFT6MNBOK>HL_3{CaACHys**k?qpKIgRl{{pWTzOR&ke3iNL< zeyRQ4P2Cnh72Jk(&F6bj``g@cKCbmB70pktA36`8o0Ndvf@Xao_V+v`N4zb~KV`LN z{OS>XUYqWUTkC7!&}YUkjb9I*xByLNmqAKXA^ZI#etq3idVb%w*Z+^NGmq=(iTZdY zl}ai}LegT%^0Q^h(oD)$QfareQAs8HP6*i&*@a{$WS4DDb_qrHb|NAq`}TaFmpi%V zd41>kyVrE@_uhHm&pDrSW`-2ZPn702j=!%S_JN!G^2peg<xQ+EcEp(SFAse zl*T6_eO}oj3VKd|P4tTR`R_RXo_qTm^IB>z>@TeL34deq9YB!L3&XS+wq?#1H1T z*R^tXd`OUx--?B=75jrn()XXoNzVuS*ZaPGW__NF6RrKhFI7iVz59&(ev3`3E zP=gIu#Qc|ezko5j!s&8H<@}e~>p(5Tcv*cK^Z%ps6KLCQIKAGlCjLhIub56Tf>HBU z3HwXO$Hl>eiDLck;$Q}Ymu?ou=ljk+ghhw_Xx7?^()`2zSr5heB4_sO5!R=>uE>WU zTSwB9-SLbRT8{_*pjZ9eHQq@we}Cll4!2qnE%bq zBVYr0MPj!{N#pVPK14SZUKo^-u9NurnH`XSR=VaY+dR!)*q?THRt)T?AIR2+{iOeo z`%g>8HbYCsVyh{}cbl%lY4s^pdH} z2olz(POH3vwhtreZeQhme>DBf945vH^Xrr4@PA$Sf4)M z_!ZRt7)i6YwNa|?OV?_{)ShC#zpSqhi{e%ZbB}BAStO=XI`@aCK z-+G-h0M3uRF4X6F?fhV4&&R~?B_F>5<o{;eS zo^1a^?2mPb9S`4Ks)*rGgR8Xn(c{WU1R0Cu(dQll}edHjv^_uCmmD9BnR zT%UP=(R5H>|5N5~16tqFc6AdlQ%@GI?^rl|9E{PdB4)FlB|Zs?zpc8q0;48-h5EZk zGapo)g6K4Z{nB{Mcdzrd@TK)h@_I3U|9E}J)GI4M^GiKCr5)$f9OcjTlKaDxGuKJt z37$XW_w{NMSQnirPx2T%Lj5SYn?Pdas63sqX!JK&Li0i zUrNsp*RPsv84nXiRul6!b8E)S_a~3`y39sd5Fy{ctH;6&xA!D)oTD@z`(F$9-eSIG z1BL#V>B%v$>+@S;`a(|{kNdxEr$1&_`+5uY^_SH&IAr*XxFkH5^eYAV+d56l7?~I> zTz@$t>^8i}@T4|_`S%Ier|k7VvRie>3+v17$89scmz|??za>lekNM72Re`AFIl}tX z1@D&-krz!{E%{HW{yzSq1v!V~h4riEar2@7fZFu@lq;NX1r2uZt1iy^l7AqCv^R{?B0nQE>O>2Xb_za=zQPZV5ildu91`F{wlHBaH zTbdtq);4pFa>&?-64?yoLIHE_fo?Uin7!_4)Z7*#GX6 z_lz~z9xSX+H)~YIG!Bdxo?m_R+HZD2Yp$^WtMRNd_&qzC=8bEol;72zwcy4rar`_y zYaT?6txfOFQqJ$X76vf7*J@$^cB_UnLA^@MuiaHs_z;*Z%#X9f75jrMswUG4IlnkR z4jR`2EDr1y_Lt;5e+()8f@#-Y%Juo@?9QMceUjYk!TANWe?q4}%b>d={?;<&{9=FX zT7(mXd)$!qhhcs0UT+wjZ(dAh1lHu|=zQC7#rfFRmy7w0{}c#|{9X{JhdjRCfcT7y z^#?D-`CJ>HKa{=?xc)q2*f?-s^ofiln`-8-ygpUEXednV_=uF(eJzd0^{H1Qqrg4- zBiXuu$JfQk|FWfN72QCbl*EGvN5USzHWcU;IkkZ0|^X zY(nvONNgzsgAk!UTdaA{Dl{et`8;0#7u(@FSE#RvUrXTP@kkmM*h0EKK0n@mlqSro zw?wF~wmtPhWs;b`qM`}l<|yy~NJ08};dvu)JT2DGv3nxHes47ye3$cwZ9S^FdY3dmv3}0|-4|>p z-5}#u3G}nX8`>=@ASyOoKLPQ#@wF!m9`}^|vOdD+7mAPJdXQQOCuxtKDVxq2GKh3*(!qUS}$gb@b()DqC zyt`ctRD^ydX(scf`!{!x$H$48K5%|wAxY5Y^`+CupW0Rh?Bg9G^ry-;hr-6M@5s(Y z4$}X}=U)w)nZ-J*I}81(-@QhG*0{Iit`6rDub)ck|9}j z{>zyXA6P##ElOBm-w>gGHfYc}bJwTy)Vb{&>HbyF`iZp4O14gOf-rvGXwf;diTVW^ z`*@2q9{X38kAJY(Cv%1Q@ypjm@U3SgHMzy>%eX#elcE6=dyDygq8$qpw$`Se+qwRx zp!j+7lzLEgbhXf*zHc@GP7V_1$Eyq)!PW1{!v5@pu@Ue@SFu0bcFsT6-=5J{P+_@G zsK0(s9>9S3V7kyqIscQQI)ZN9Q=~AEe?M@3e5f)WoGj|mN$oiQ*q`=)K%oD!Yos!V zkH_`plA~TgiVBEv2hKmu&p3X*mmUGXysJsZ9L_(kPwg}r3hj&)=Xaju{HLJ$ za(27Pa4PW+xqN-GG(T~FSelm~%)C@Wnz*PFsXqYm?@+PequA!{&7#Ng?eo z{eP^_W8Pe6Q`MY>`SaB3PFO5?FU=eN#d$(BCC_<5b%SQw%Ch0N%hCGr0V z<MfN78=lcz+l{{#dm4 zcXr+;R@h$>*s2I#4v&)QJLbRFrP}Z)M$SJ$`y(XHng$KGsnOIv*Zcf^f0+LpF?!J9 z_G+O&=JzxPLezfA{4tzAAL(fV(*m{#&;NPU*Ah(n?-Tl8^@BRVkEl~Ze=9H97vNDT z(K^fPOE`YMy_>>DgDjzc?QnM}G&@*8T)y%865c$ve za()w$eh)JU1efQpNyn9YrTKy5Yh8VBa5E_;u#@wP{jIPO5%6B+Gch~8Q5qkQ>PwRg z-5_rE6Y@fr^NaP{`ol!dOSxm#Q5`gHEd|^3#;_i}(NEbMzjwHS;CD9eDnY z_50?i$#D9iDh=QNOyU>!XImvJ`b)lvJN{ z7p^aW3ocPKVXtz2mu~vX>NJTJo)2(%b`ks;K90^(Z7bbB=C@qCHiT`K^NaoMo{IB> zNvm3P$-8S3zr{$u+uyAVy{(gk{#X2x`(U?RzQ3pnir?o?Zm8(b-a;a7{nJ1B`P0YK zPQ%gvoap?X5%zz-A1W&H{?CU)Eg(EC4xiILk)9Tu zZ|q;|nz+IDmQP7PAI>+fA6qUT4~ypgA+_6Zea3t@7~%tOf0vTS37l{2Z-peCXU^-X zFg|a(Yb-Ra`-3dEaF_VN^{dG%uPXX0oypC)Jb%V~Yn~nrr&m^!LkEnc@mi>UWoUPo z<#+KF_K)Z|i~~)zKP23p``cD1e|9U*XHkVA!unOum`q6Wa--&sz4-mx%l9`a`}vyf z^q45juj8kEVa?}?^*3lwA++?2q1mSGC4O;!eYS@>_}mopd)0C>%*jxrZsWNA62xyG z=elqxBZ*Wz{`dWppC9iXX$%cAwg~$-6MBS$lj|4K&%{NVe>lGWF|9dd-4(~z*0GDA zUsgTpe`T>WJ`kO+SJ}2b7@j*Nt1n}IZKioZlbJ=tCT>;DcvG2yI-#Tw1ZifGrq6qH&Gk72>GP#}BjH!u zH;VoZzCT9}im!7G#z5nqUrDO%W@-N5`1xv?E1X~TRMvluL!pIw39(7$`7`d%?0ESc8)E4ojGw!`4~K)5--uhiA=3X(LHfIN^A#5I+*wv% z#(a{Cq0n&g7m{7oP#TZ(=Z#HrS<+fxVSnao#raLf!_=wzx;N7N2Vy9DzgG40+53Z| zNb|A$`;PbbKN^+^_aC{_LqqubOq@UO%6-LdJe(-&-^BXc@yh~esINz-_1?qRN1*sQ z?ZPLf8yhS1$KqGif{gl0iD>;}`?v}4)?SUa{lxi(|-Fo&H*V*SkSz7WbM)T5yZoKH8z=lalg(9r(0OkV-{&uT;6 z;L_DXGNCKy6YJ{`yIyd8({)+?n}XIy)r}YmbN(wOdDFQ6jP*6{!w~2^tdK0Yubj`$ zgNDH7RE7T5tWS=$m-km^7!C)+^A)5)EZ0|DA2$2#21^$dk+bl?{%`!@hV<3GUIh5I z`9UJ~a(@NK&*QS)Aj74IsJ(tGjmP_Q&)YE$R_v3<&#@?e-kd)KnmZPfWPdd&|HbQ* zyT+bno7y`F>;ud#ubSqEJgS^kUpEp8nIi(7ppcI^zM@qws6 z(;(&!+vwvfTt88@`3VcTI7;YmX{#-Ozf>nA>cy5nIrxL~zZ=s(wOsROF5D{1)N*;m8Kzu-7Xl{Eju>pM6;)m!Ke&90OXHv644J`wpx zU51W^J=ebw$G5z{A_npEsgDcHQ0(uus4riCg!QlV_!*Y|&_P(=8TV!^JWf)fu#o#N z`bht-`CeiL3tfcyXX}=?*?{e0KAc-UW-C9968b-jf6RkzI(qbYd(KBJ${)9>zGO$I zPm<{u<|9n8KHhYo9)&x*B>lqsXZ=}M#k9`E%Fd@LM(4Lz-u%g~jbB6>wCC|lG4gkY zoSy@BW;%3+`o%tfzmJJjzJ7mWfHq9ePm=k&n6KxT>w{;=R-u2hvtTFOGPk8y`}6hr zn6G8YW?->oKQYCS{8du9I0wuw!l&4&F# z|5QtR1|+SiLoZeG{cH45d^n-9HF&0D)Lt=!ZFb`K~L=5J-cCP4Pa+BAIjed+qRf8S`YFD#k- zmTVi!`NZpMgB|+8f!VQV09I#XJ}krNPHc5e2Dj#Yh`|#&8*v3xW8nJ+;Gr(rb1(5 zxW3`~$ZFM0cA@oPS$!18hm-3ELvW+-#5}H%bbq>tPt9)GY{MHrVSTjq<_O4qsY;X2 z7b(r}zTJAjzJDK0md5k%JI?P+noNeVrJ7W)c(F9zoXY)|33s2dui2A?{li8}Cc)VR z#rpC~MAFAZDnH-l?6`NVR;_vDr6u>DF#p51ePC7zkfGz{#nPA9zL z{wdx+GHZ(#=ny&IIKS)tJRj5^PL=VE&u6Ol%m9Af66@!nIziy~`m4;J!TNb~RufoJ zv|rf&&}jZN*q>X67FKh<%@N-Pm93yaJ42?gnD45Rx!|U*M{BL#A)k21ehK)SEnh#rfZ*;{H(RluwrFaQ(%6cZpE!f3xie(aPt1*ezBQ8>OX@LL=-)I^3kLPNKS}BQ#uDGxQU2F&WfrT-@*~=LoKIXo>3TB^ruZuA zCztajJ_+(~ZW!KY2Kl3f@$dV|r7W(;WTAiR_w@}+-x*7M8y%GH5A(TV(>u1l<$R(M z%J~Gu=b)XDkY=tl^lBvP86*gwr()fnz|IUtO0Tke<&8Zp{*zs16u@$&v&-BQKD?%o-){1Wq-v1}e( zQZt~X19-}ngUml{a}p-8ouR88Z2;`5cp zhn{5rwQwZo_VMoNw`DaK*&U!^M5KW-(B z?|}HsYJG#nJoY0C)+y)n(~Wyzuxz+!SgX8)VC-9e&F>vyV{qqyp+kp_<3|JLZ!$zxeyXd{WIwn0Z5;UOmnA6Z1JrR}*4xtdaSnIKK=} z$%Vz|qhyNGV^r1zUZNmIB_t!D-o$5mC_|@=<>W^i~rto!)n9r5kE#dHu4D#nb zfBu-i&c3#=z%xsJei`DceXk%G*64d@3A7^1neTDVKBk7?q z^Ozd_PI>-`{hQ>6=UHQKSF$;lzaJdm?in{4LKXS3=~&JeK41LDjO)zgoWC%>{bCjc zxf3*Kxzl?||5T9vtsirjjU5syT)*lu;{;s1I)r|I)=hdoxPI~SR}p(>F-7Q)mgl@; z+BaiK;0@*cO>gyUDj6vTx+i-D`)WU8;)Op zbjX2k<#PUTei~n*2d?_tg#Gj0PM1LQNdQf3FiD!fSRY%jYy@Qf0b%^w-aHP>9E_=N z_7Z74USEFhsWsewm_f$X_(zz}=F=BI)Z7Mi`YqnS6KgN8FK+qT8DGz|M-M+KU0)y77j0hjgKWQIVf{k)R0O=#sZEdd=J97N+8-t($P4b-eIToT z9FXP*K7TM>#R+~}7LwD4`FPCli$)<}n5;riw&DH+=J(g|0kBiAlr*2j^V4D?KR-Oc zJ{n3)H7UtTl&+8K7da{eVfC$2k~o^zA94Tg`{T#hDRW0*{F>%F3|#EKlXZ7_|BM^* zU(5HLWuK-FCbOFH{0#G3D=ieZU9Lq_!&^!B=Z5q#{`FNxj`<7yqw6!rzyihkk@(RS zO8K2&k;|-4i1o9@s6_ZxZcS%3d|5MIo}aFdDP&uGrpWwTTz?E0SkCgR#r%dDykT40 zEg)Nh`TN8Crg*4iZY*CzJI$=ElwZ4!wPDdOasFATsRx4sw+Yv$8J{%)qmKt<=L2H@ z^>F+GaJpqozrW}F;q|3zC#>L7?K8sowC%Y?V3%l0{V#KW74z5pbtl+$DvSIsRnDK6 zYY6ydsZ!tioIk9ews)Lhbwx3m+e*29z8L2TPa9W}wAK9kiT&Br%PF*Zt*9@wuRAGG@bZZ!eRoc|{zVS&51toFNh_+HpIN0x*@bJ4WN>`C z^#5^ud2aAoHZ;?f%&+NB#(Zp3xx!5B{mJ;o{Q2ShZN)Kvc(&w+?EDWE6?y&L^}`)D z+BQtMzT|D%6bSdxqh>mrl+OPK+4*c_%oJgM*K^bh*7Id7$sEa_KaL+;-+0Y-&s#u7 z9a293_t`&$-o0nion73O&i^t8b(qj>t#JKUw~gwVTWvSX;z#Vi?5a~2#x2|?T%SF9 zz*TUt45M9cPO+EtlgRtmGEOvvNj7OhewrA}hiErrdU3yUej;{Tf|1)9nSRA0e>I{0 zeHgZX8uh*LOu9byS2a94!jrfxGSh>&2yI{ScaDn zwY5CHj6wCm)w?6XC`^kU^j|IU5s3WL$`pma^Zq#rsG~f-yx8RkOO9|9*4M}E3x>kg zwP<(m5z_z1{%N1w4CZ#+Rp_72>^L6us4g`e)JqzV{S^zROKij+KeA~a*Eh`PufeyO zUHdR${MgZc64Wx%qmQ<1kod#(b?r@0nV!K^Vf?tM;ba)NR*#w-*d+O*xPRR6&~tWE zp-(ZbmGh}NXG3ONJ6ng@0gt5L*Tq3zA8Bs)ni)975&O%j(%-Rusa#WodK=b|nYaG^ zetCadZA)F)a8;~Ni$`X`sj4WtV(fJLzx-kUQ+)uM{Kyb7x>W`>5|EtltMuiH1%$bf}^IB4Vo72+&2gKi(kG)|-^8#W~&fk9^;%{HGVW4lRLdUG<{tMpUv)LFAcz0E-j}=#X zL$lZUkmnB5%4x#QNJCZ z#QyS+^)dWqFQ{Ail=L>``|Ec={5^Yrh!an9NT^$(L+`fc`~{-?ZFb*N%=)*h zu>Rn(cQo8su1RCHI!O1Iiujv27g%~1e=^wmpFXI`zHf13vAb;d+)60{iCS9 znC4Kzw*HP)oUf*w&$Tzp8C$iGlrQD)7xU@Av6_XQTTZsV<^C!5U#7nYbk|j<;$Gn2s(`Rv%K6)*;R;j3sz`a{ zHR<{(NdK~?xI@1+pUJy-{Q5XPHJw7?sP!|_wT$a$IpS|fml04Ip+=Ln`1cd@=RL$8 z%Hxa4^T0RK_2W@|T6`oNo{g$QKegigxuN*C8i7l~MBmTO_WigYk;llpV-0E>K{hc1wzqnCp{5m&NasF+`spR+% z{{9F$|6RRF3{26iM{`Vg{MrHWm%5^em3@yTojf^zfcoEzv&X^m2YU4VvqqBs#i0J4 zPL0dii>`}E?`Xb$HU-rem%poGi4T{PYxkA&8U8aGCMfdbf9KZ}qyC*z*E;aaE=A~% zuD@0vTIe1mT2J`z$Nr1E`DJ)y8A*#jACTq`)<=8V400Nt73$-M&;WRKOP!9c%l8k` zNBl0n&=xjsx=FT7;n&CcV^VbhthcI7e^_z-#QsacYQ_0hnFYkN4xc|*Kd&E9?7w|T z%qUkKgB{SVBq+F}ATa-WfU)(@rMkK@-V$NfP?Q9pZ}&;0|;Z+xTPFlk#6 z30+?l3FtG1+nBmoy&t&ly&vG3~uhq?Q%Gf9&7% zHW>?PE$h;Rb5qz~{)&mbK6v}naTd8&%~9WeKg#9s%*@8B=j*{1&C!u&IKXgKtkphFjZUZIrVyYKVZ?Rrzmie>-ikGkyp zX2ulfi--R&zsZt*;{A1-UMyfOzQqzdb>;lFY@z7C(XL11ZYt+jweSUt*|3Q8yT|#( z`Wl%M4d7LehPc+mzo@^pzM}spz2^#IVaw+a*55nZqhRA{Ip6wJe*WwJ?pkn)rVyvM zeE#F}srCg%K}ez=eRYoOb20LdKCUu^Mp_4j`dnmX2D{zGeD4|(0GCT@(0>e9B@c%~o??B@KYhmQGh!=yfXcQ4(qgT0ecrC^0vg{x61PgO&#_3KwX%kQ z-=?qR&=}r-5R2ANsXICWORgY`k3W_8!ulNbZWs*9u0=1Y@b~M6{G$?g3OCQcAhW~X zOXG3ta3;xY7d3<~}G!&Y}>Cn7D z<$UiNdyUGSvdh}TDs&njacEf$l8aeRL` z%y-3?C^%rJPluml()bkA|6{-A9n-X5A&jrjKZt~ti|WbrI|b=?>}pL=FHaG!pHyuU z3DmG24J=g7x7K0<*zI~y=ugdCs_-{`6yqZoN%J=ro$u^#+7!NLoE7?0>6v4o$>zE= zzg4O5!?&@D_`dYGG#>N+!LA1^zf?#}6ZrgdL;3O1HqNl6 z$tP0cdtDl@g7~*Bc7+yazLD;|kFvk-Hy-gn#;7-#t$apC?&9%zENLp!5Br|}aQIy< zYWb1pPndtdkB(qC;w|}HS}k24=f~zgqoMkVHVw{D&i~I#U19B!r(~b)A8C9#%8$eP z>}Oi1orL`f_b<(Y*dwMiTqi;LeOTW&?>)*~2D*{K=Ku6jRrdSt+=zt_C!5mt%|=P% zW01bT?skst8Z=zEKgr7>qhZSz9lCb_kI%6`RVVN&d#*D^7@v>69|Bc%bSSJ{cH!^) z!TdLDcb7rIRN48jnEwMCgW-5zZK^WEmFqiNUpd|7DRbI4Pv&3Y_}pw^Fl2YtrdFeE zB!2P!208|1Eac{55*fBfdOkQlZ!mAH;{Dd6C9S!>6Rhtlm27O7oc|Q$Z$18Y3N&kn z$oR+gp{g(qu!R(1|NXh)W1;!wdepMPP-*^P|7-mMeaIRw)_0%x5nvcA=Ks~b#-O(6 ztS~=c;TZ|%0`zICv%EhS?@va$vkZQ;PLhs#PkENzs4ZG50Bi(w43)6=HDkK%z&aX zrnFAv3TghSApgtN;|TlN!AdBr+kJ>XAaDfw7=U;6zi$loISe8IL(ZMrvx$4?y)U-6dx zz%aFnB-($K#;ZHX`-99AgTY|1jx2u0{_?S+o{+J#j2s=$`NI9}XBO;b^h!Tc9I8A& z-Wo9#eDfO7n?B2HexE!)R-2Q~dRMy%`yZ-$&H>l*ph+pP%MsF#jpTh5pv? zfwREqeG{5@skwChV#HVLO_x|BzcIr6*u6s#%-N|!9hdO>4(;X`5C-%3741dBJcU~Y{zk>BMu-izud!Y`sDsC(3XDsr!Dz}%i!!zPZ zFB9G$isR?B5hI|ma~*mhgYWN`j`S0f-mt`b2_z_s*M~5_-HxgQblWcMpLi1I566Nv zX;$(OX@13`{P)03J!sVA5UEw;-(vqOG{zrxd1=zY8VjWH#V9^Lai$S8FgPdFN3*4h z^(U2TbkP*&Tz3uQ;Dw{e><~8L*!HjqeEZr#&7Lu>bv*d_2j|kHPzU&409; z^toePA@dAjsyZh{p5 z62$L`%3Ewzl2{*SKNtygpbky+@{{;ANB;DIo{w4F$_29hu`$01<-=i=jyBZ@<@{oQ zdUsX{n`^LyxR!E$as2CaV;C&(s6#Uu=eHd3Yjm-Kji0%ayiVcu4a{$+ueHEp>vmy& z+wH0^xGMNvvx4)B{i`<%>O$ztgR=FdDQN$C!%!bcpQ}L=w$GR5Cm??J-!TE_@#lp7 zgW07D(dH;40! z^V_T@9*}KPi&_NcNaJJB`j*ndf$(FknD4=eO~Q?_4Ku=y0_*)$YyX zC(L)`i>`|ONuH4%pLqQV$G?-t2f`V5UD~hFI%)o6ecnqufm_D{Qkcr~TXhF{{ppC+ zZuX){e_{Vcq3$F&Hpr9?ny;Mi`G*d&j2Ghg_tW4hFfy|-jXc5otMLAP{-r0`xyQqW z{?^>&DKMZQ>#1U;eAltfW+#_SBh!ce z`@YHJ-zE1(z~}t`<(vCkc>e{*%!jPyEh5Mx6hxu;l><_nA)uFKmIp4*I?}4vgvpQW8iOWjvkHn(<)?pB2NT>nABXL0^<{n=8t zObSQy>zgC}uF@L-+EacI=SNu*|A73hqWJ@0mF`dSvpv^$K>EI>Z8uoHq>SVmK9t5| z{38o3 z{S@by{*?JsI6mJozANlXc|qo{=KSg-{qFbL1J-@6O_yqLepOI@eX_JO?CJN6I3D2o zjnAL4-5Uab-s;mQ>RY7wjrmQ~`40xa%O~cwxqkOT`rT#O4mO&K`PFKz=%1KlO4|%p z&hP1Q2bgubyU?H388iX*zi3R)*mC`jMfr7-!*TY`Z-h|4+2_d+>?!9L$LGVHFR;;D z#QeT8n+tn`tmuH*e1A_Ipa1r{!4BI_7xMcqu1%)NreZp@kn!&a@~53A=doSY3uODl zVEyjauT5sh{>5}!PnVkU^8V+gVFhepp`3r5UuUl=XKr*A>3Bss-}|3MVP%_CVSMhWLl@3Bj?bI+Zvbge z&&kfG!F&hXyD9qf73-_kB};r^e{5wd3m8~>OSrzS#cX$I*h7PwmUF&wemzIKqe6d5 z$dl9j`y7k-HtOaM*R?fdd?zBlQ=*(ecivBOQU93q{xIKF(YCN-_)9YVDd(G@`qOvS zpryJBAik$5jXb@K&rj@6o9<`DYuttY^f%LqaP@Fgs?j`18jt;HmVcD3 zB_o9E7e<;-f>$HVsBxJ^&GqH$i!SJ&XZs(C`Svn6^8iobT1M?lIlrV*P%gZ<9HEQZa4OS~=gdx)iYJ`%4K_^ZGUB zyRw;0=Ct@?YO?vVl>g)U^Qp3ztgLz!S$%A`^n9?s&+T~#vWw*PC+vUkFi?Ra(^R3q zR^227CTi8E?cekI6Xri}Z5=p$UCuxD*G$`afCgyN)6Y5o1m)*NeT?A3&vRsO3;z5u z|6NrF!8BJjdV8<(_`oj1gTB!v#L4U5 z_2ui60zBPe*MFLHSm`}!Jm$aC$-WS4_mf49@0V91 zVL+8B-9J^iejirf$84=Ug!(-uI2z7sHlf-lhfDYOfB3F_l)Y7)&Luh@c3tQMa5`&7 zqlxnPyE5u58&Mu1^v9Rfn-7zA+tBMCZ{qYck;e)0J>_xCh|Pc3f?^XtKu?ZIY82}yHQ z&gWyVkua>60Zqs(kmi3Z(&yiG93VRUCrOA<&S%3m{bAG|RXW7Iyk@+-Kg2G;9R|i} z(e+RH_Zi3Ek6-kFo>M*$qlTYr#>?wl3ta+XLV_VRF68_c6Z!rXTB$9;=-DIU(Ef)s z-VNo?MQj^$3+zwSYR-4V{h#p;W1%~3OtaEBzqo$9E`1NPYvCd6->z#P35(t|riBKa zUz|VRJC@G21dbG*FXujGJors%M$?0=*x&D~Ir7i;`JZ85ri~S@|Gj%P7V-jZXk6KA zrTlhvyv*_{rV$Gtp8sKf>qq9W>f>?bPJKQsOj8hL9R2=I`v%0Z@9Z7Oi&Y`LPPxzv)A)87v+t z=C75HBlLWtLXDice!8Lh)V8d)V4Yb)W?24v{&M~FdNL4}uUDr(|0wsjJJq9bpZpTm zuPVk5gwt;7bd7IC4Igqo`?hccy#g)z&F+9S|1h6DhjxY8>6N7Ww~x~J(P zW~>wI>(cH~Fj&)!u09qhjZZ}Ras4ZY+3Xep!u{1;K1D-zw`O$ta^?DZwfZzmJ|pJS zfBalfoo7Syjw|Q$>yV4gdFeFrQsL7}^*^+}0#xrXgU@lqY#^T>v8cbJ``t>|;kKQc z_}@~>r=e>;%hFFE$DZ-=#fZ;k+uwptYzlR>zps=}^9Ik^hma(4cYty}zc{~xUpuzT z@?+eewRquob_G&}`{Q?SHxibesZVFr_LSxqLH^gK`5N#$;;^hg6Z_XE;(XzOqQ9)m zyM=r_ijP|r>qAVkm~Uf)09fH|M2A@Isu?d|KYT2#Da2eB$H%GRZJ^T!#rerK{&)(? zf5#Jhc--Wd%%6@&`Z^=Z9^(9ek)e6Y^)<3#A84`Y2N~u0Ou9c@f9^HY6%PH-qJHf- zzc@Zljq3t_5tU@aM$T_M;x{G0AAUA7pluDgKdq1Wtz}{ZPFBU_ksIeX2J!oS(-yYO zY=E%;vbkb?1!$O2b)!Tkeg9GZdvxqBwxGg;gc3eK@%|ZW^2fs51T#72@R2mzbtCVlIYfsp8 z&jixLnD_6bAih_+7sKAH4b&mNR-eDmAMYj7xKLw zzOr=f9YX&rb$xBcM;q`QUMh=^F~7~!`oOvizsQ%`H>LZ-_2nsfc3|fJ zjkql2@82BtPd;sL2W0YBvdybR8jtHsg&SRAilRSKWjO!-WB;m$duQnJwUV5^&H0T* z`$L)K4g<$&^{MHaZPNS#6d(VxXbJfig=Bpm_pjm+zom-0)XSX%g#H!l9}er6Hl_V+ zR!aXL$H%n_cd!E)9zy@>%*wGaKCc;#=*auO_9FfDHao~1w~O`n{-+3NJf@j2zg^bz zBrEZW6!wp78N3B;38iT$a?LnA?TggL!h;%hH`pH<}bV^d#s7UZJaSIoDQmp#P)P@%(rX4hO_zJG`Qitf;L-dAE9%K7Yo z_#U#lFSxv~Mcsp6OXEAB`qR?aE^u{{HVt&;&F>n zD%1{YO=G8*Db;6{g%?=U&(nqZuiA`k&|kiSPFm4bx_`{K*~=R&^kq*F1IB^RRZCi>#reeg9R0Ep?4ELm6kg!h$LpIrT6BZPNnc4Ta#*^5 z>_2<2X$iZJmJ0LdGsgCCzC@MwyLhW+yqxban{Kdo>sRu#|35zE{h#%Q+QKQ#&*a#; zB56FXKUG+`z-c`l8r+J1|8f58o9Y8;R`uzCwcNkL`Ehut6%_O+BsZ2R=ht!CCKhKs zP`G}%`L!@O^rso6Emt#T@pbO}?d+b_P@z5-{5KZ*jJ2Ryo5x7wF~1(}``P_n0Yd+I zXM-`&@~t@?wcT18kNqq4^~ab&j#!@;8cv3r<66@uCd&DZ-F=?jF_|f>FYQ(A4?DWo zLYcpe`3!Y_z}o4oBynq$$HzDSD+HSaxBU`j zeB%6f$&%Gt_9@Fa=w26_NO*o-oWmp3=sOq z8&8gcwVuuBrC&V1?SS&z^PVY8XPQ_)O>d3{Fg2%Vj)X|RAM>}wQnCKYBv81&_@K;C z=y=ndwyMMV!~Gj~8Xsk|K1K@t<1Tv1@Tk!+diy$&uCIdPo~lKeZL5$C5Ljy!@xY8z=@j=IwP^z{Bx_PpOlQvV`<{{;0-6v%_tn<{NeiS_;4L4 z+%1lO&kkz{s@KKwt#ip}*lVNsriR~C%9lp1=HRilfMkB>{+vGQkIeGw0w3MJ5%-cJqQpJ&fq( z9Oe8Owr>ua`32-<3Fi;zr}0J`m~En1|9-v-f`t#{@vAxFZ-|2Xdn%qnf2m>GXgHG4 zoSIz>mF7RL-#jYW!{$Z@lKv-ne1g|EbX_qT{H8UhUv*kY<1v4S74@Ir9ixQ&88q1h zdq(-w;X~||^0zGa4Eu3^rm%mCx?N!g3&i?o{OvCD9=(!WImq8%Eb@o?j(-Ttk~Yfx zA*_FQ9u>2p+pQ2Yq^E~cywLj1NTSiw9RLjV1Jq2L@~M9=Ky@g??`a&~uup#I;;<<^{E ztdDkAY+y~%TXLlT6Y2UfDE}<#J`hsB%K63l=l*9FaC>Sg(dx_j#s2UBLr?I&YecUv z;`t}m&v6>-*|hwD!u1L7bArI8n>kIrwu;Yh#OJTvEv)#uI6mF8=N0hzj-sT4xF-P zq%iQ`_g7mMU(U`S1{#HpY0Brl(s;ao*4Gjv=xCH9?2kC}tUsI|P?y>`oRh{A)ZgUn zXaR4wJ(J~^v4~%*Z5?5^yZ)Mhh( zf0)md?vvpwKHjRv&tHsySF^|gj|X5~cv3E$t9p#J0*%hs~)@dJhR zo1C;jIQqz(ri|zLCDvEJIms;a>QLeOf;W#tp!h#asyO6^{f+PO`rjumyO>d?IKB;h z5d@c5b9(Nl^7!_G?jhD=w^(08=dOkFWFLCb(N4NPj&E~aPP3%US;GBuyyFhT)lai2 zj5n0VV}4DKUu45{7Rl65z-${gGp8TDEn9uBjmQbxYpXaMS*H2tut(DpjKJ2MWqZ9e_#rfyb zL+0QR^o(e3P|j!kGFB6^@7tHaJb<^*K}9Tr(e!VwxV>FaDN;9y}7V| z*+yDffuE!)kaevd~CAZn<28qP5Er0(6#m}$z zWr2(D8oFpm14&+$X_q$V8_@_8iX6}#7Sr%->@2aSSP zwXNxCCx83D^BYk7oOkCtTUP6cP=5#eyF#dkt&!ovAt{Y}2&1s{8u zQk}aze#YyE0uv0O$8@p&I#e`+ResOO)SCS*vA%wrZVgwqydhqzGNt>&=f|EY`wvQ+ z{v>B=`eOjC@0(!N63k5Ak?R{d-?1n@j=$^##U6U}$U@$KK~R1h-KH7z>h(;fzj%FL z+c)l@KcXQW{CtNr|8RZA4J_fV?rRy}?-AeKS|qV{@5K5$myCdaP1y00ZJ#36 z*P@2OpwifyZs?_)-=^!nvbLSY{CdB2fqR`A(C?Euzqo&*>CM`ZK7$F@?`~=64y`>+ zX#35(?f-s1@cN)@9tP0mPL8nt`g@Hx_)Ka-f9GH0<5B#4WrP_#8}nS&UxE1!8Da%r zeBTng+sgU28r2@Y&HX7m-vsmRchL$i)~+PYa(R4>^WWoojt~^DM?a(}=iAHM4PIVs zNQ0bqO7jcz`*Tz)STXA((J;{@f1l4@#P8^wRqWX9fkJ;cD0~=Lu4_(dF6S5bFE+N? z$YS4!^?9=ONcg%>9zQ1{eKrf&&U%dr68giQJ4OKQZ%Nk~DCgJX&_1?VJzBUvpsw0# zIJDoFc70c)&noiswemHNvkxa{3-`}y`ZE`H7bMe&A3jR?ouqz&?H(tNpZhku1w-0x zq^Dc*{1@x9X49MO`AD%oZ`FRp7Ps3Z^N+Fq?kmrQXSb7u`g<~?j8!Ly^|x<&ARJh4 zP3w*1{9^y=(e`Tgq~I{wF`fH2xPFuHKpi&aiQ{L_LN^$*z7h3wRIabyM*47}RIIPR z+&#cwvH#)J5m%M+Sz+E3>Kqow&!MK4uw1bMMZb*mse<|!E8n+;)U==EfiI8mFrU>Q zEuj0tw+kRhW}tHT1&JH`M!NrW)W6tVu|M_o$VRkV zI$ytq`396N66e1@2i7yA z9I^g>`{561&n&3J;V^0b#~^+O1gEgKHo?TV!@u}YP3CWCEglX*hE{ZtduwSt_OJS^ z*vtAJju!Sm#aeBJd*h>MsNFDWJl0?J{YTmK_H$(Cw`2WX*ggkB^taGQ#=g>ctiROn z9D6-~5t-8d-}96AKk0Yy$(+B}(qW^?acO)!+F#@Iv>U9~szl=Hq&&Vp)aee49g<8p zto$L>XL0`fX21hBDR`62zruW9>5&7fjkXB+K3nmO^}N4R*uR)mG7=1nt*Kpva=wF` zeqgR24iU`?-oH_d_Sf0f_$rL>T}#tyU9|tJA1TP+Qa@G;Le)W-KU-e&g76n+bk5-Y z(s+XQw<~_22U*6sLVs)N*~U=)NUpyr$iLb+r#VC)d`nar=i3eOZ8@S1^t<(wB-gB; zNkQ?o_S)uf@6KCtGm`Tih~n!JM--{c1#x`MMw-FlXXUc<+j0H2j+!etSDDbzBfF&e zgZXZkY62}96_dD$ynh0(&-Gogl1&O9BwSyRG1~_!9yF&a=eR!O{jp|FU&pRA^Ah$y zUEk#oBL-N}wwoiQ`@{O&y!|$IV`DHWiBit@*tB7=yS_C|{9#k``{eO;ti>K?{aVcT zq-}9<$Zr7kIAku3$9$I+rnB)sXAAwUq?NnD;@K=(dZwN<9`ha1=QKW=-C-JyxH`Y+C(jXPRq>bCe!9dEVZOvk%y|{@u_W1XG zke^ScO`pU2j^g}T^*{-8zO++V|Fv3Q$sSxfL|R5E=l5a%4e;q&C~erE>n}dvc5JE| z#Jhv+d7Ex8=#Y;59W@=zo3M=mA=KX4LaCuW#Z0#tQ+a5N=Q= zjISdXm_zvLN^;JSe}C}$+okVY!_U^gg!=8I*dO3|(+{M&_fz}7-!B|rr=|CSeLMB& zVH4%?^^_@QkU6@76pwf(jmP>utf>ne(`rO5HY(@){sUu3+E65`52vH}yWX<|wkyV2 zcs^(SOFrO!!jdL8;^#+TzSr2UWjRB|eBXBTfi)hM)b1$Fjiw z&u03$$Wt1R`F=VggRysuWa|&Ge{In;OVMAvnFiY&m-xi>r)Kt7*!>=fWafYT`-b_R z+Q2F^&-6E49@rh)z?)S<{qB6Sh%Ku4fA}sq1J+wsQj6<=KTA9%J;84x7iKco0?JmqnvNN|JA2&CeX*OOxV9X@TD2Fo?A%{zTx_f`8En| z1>1ao3H`C!@9h-(*VX+Wy3RW;$M65+cgjj>P()U;_X>&5$%>3@*-1r`QW*)AC=DYm zqC%xYvLn3TK9apfc1W_R5E;Mw@%Y}S`#QhJb^h*gx~}`W&hvV`_o1)*vHJ_);$Ky? z1^(0dOjhQy`s9Y({Mov1M&atdO)0&TUcJAi@$E-vjIc+iB66&wygoPI7zy#+?S%aY zCB>7_<78`U`kC3^$erKttzs)YA32GqXZNMR;C+jQ@$G>_0@1B(7&ZUUOtqfpcb;Pw6#o(P zOMG`>3ap@i*Va?5=j)S+(+P0dzFsolj_3D}N2_z~tbWrJYp?3-OY_G=PoIaKQ^oui zT)c#DOA=^fXT>09ze@Xet*76HI*k)ZlX3F;e1GaQXgW1jcs}7^_k7II-cIM<4YmH? z|L60^754Ao>18pW&5dI4cV8Fk^13>HWi9O=+IgfB4z@l;e!XS>VM{8_A2&HU4qte* zqy}Y7pZWM#yj?x)eeyOr5X$)A>ys}GQ`QInu1nV!C?-@LfStRY*-5Qj%Sgn*_o=}&+BXcHpHsZ zSlaIv(^tNJvV-XtSl{dz+1!%VHxzN_Z<`;r!M=5k>6p9})%E%Mt;IdHF|yVjp?%$E zz;Mh?F`;vQ=c(4mbN%__wisi(Gp~jD<;NeD{e?xJ$#NHV|9pRM%-%Nm;-Xl8dtGmf z7Zd)GT`sRw*DoT?B=MiloqD6EvVW+eobk!)^OqB5*tp40;x)TcwO+yT9lFL28`Nt? zEl05L1Mfc{Tx*Pr_P!?dO*B;T?Fg?k*g$GJk(^^^v)$66_ zD_wCu3d?GSNaj=W`h4gqLWTYoVg1&jnfcgbz)sqI0^^&Hf8~Z;hk_vq#G{qG{w`eg z2=*RJ74{!QjNFD#3%uya48|{SAJ@)!4U3Ouk@;To{2o7j2BU_@(sjMr{^#xE!37`T z-$*IH$nm=*QaRte(uj^pVf-d@@vWsrb;LUvUVl>?o8v9xze4}`h_b%(uyQ`m*;y}C>v?{+_U?(p7iiO- zyXEfbq-6zkKhEKuynPbabXXzo+WzW19<4iN>`m)%E%Kc4+tph-zUc z%ulTyG#*R7wV{=cj9)&#Y%*dqj5C=mjDHPyIuU;~YEPrDd#U#S|I_Epc(`!ZiKIrT z^-CJxrt6oZbIYN0p4EKSdgS!EN2_Ege!Wvq3M zz7gY>um1`<)*a`jYty5J^8DhQR#<=9Z_>r~m+JZR=bLT&ZHtTCn^V2N`&G}6*I(ng zrueUK1-YHc&UfJB*V9&n!e=4Uc7F)1GnK`^czyl4HxcY!E*8$uc;%W7w(rIKy_%4KMLqp!;V*gq zHZD8_V`qm5^Gly%&p=nlE##J=njdNX^Y&QqzSS{2`g^O8-?3Kr z!2NkDnKD!TeCtS_|8Vbp82mY$dN!2T*F(9_AaZ*a*_p)jf%k7eB}d}x!7g-ffV{r$ zH7^BIkK<(2k7U*Jr4csT{*?@=j$h5;{8w8&100!FA~`>SaQWYM z%NydL@gK+)OSJyq{!HfLPlLC&z%CE|3hS@_x-`N*y}pwAPLEXUwQQvRYsjuH=xcR9NKpWG<)bN%n$W8^TEA|!|9{ZEIt*$ z@f)}<71FE%gz>3|z2mX9m7m1^<@xnc&V4nA6x+X}o1B8P!CQ!35qm#8ze_#x;mxxI zN&c3v&uH(EjbTpW{7#>vci>y+G@<=_x;zu(9!F4pXT~RAf7SKp6IgOBi^Lz5=kvAs zW~_bKoqByvSM48OUxQk|fi06xkcQt_{XWlU`ARzk|2A~?yaTHBeEqXqg(j9f6x+Wa z9vb8Im@+b-?o+Mj=R>|YtB1do{Ho{I@cg>BXn>ED{8qGP{PO*Sn}#&Uk=p-+{4OS@ z7`nHL_{}e3zn`n$$UW8>qf_hA2jAuST{x;S{?q(MPF$~0t>^XkV}s!sb-5MowTIbf z$iW@diyv}srCuZO9@g>J?VX(?`61gx)o=>ac3$S7tp>Ee0pS-?i z&DaV_W9E_OW7Ydt%IAaw+u_9tPoe)A)z=pxek4_7wF1@mljE=Xw>>a_K!C8ms^9%M z{MOB%nnmiU*7Nxt--r7lAYZJXKUOIFm-dMH3(U@gkN>3n@%hyp?<|}@T+H9?Znr^m zdm72mXU~T}-!ncx10Rl!r0dr+{`mOOY>&rqYve()yeHc~$kj(}xw0Am8{kPTtg7=b zT>d8b;cM_}l|yb{-Cg~BrTH7bTw8qb*qj=b?N{wTK7VsLzXootbyw(r?l&{SoX%w= zREzOPIQ=YKUmwZ$5=s1*=dXRCA#NM-i5yk1{43Aj(Ho{%yT?CC{3w~LpGv9U1edS> zMeZa$SKU8fUtxQ>69$jgp-n%q_z$1o>9ouU8=fvxo`1~d!}0prC1WUFC1&(Mdsd&3 z%<(tktRWt0_DOR7E`R>moTY2QD%+0a6fpal5Q%xDfXicW=kHE*RBEE?{qTIAJGTM) zubwQ-?-&NUpw|?l>>p)(^7=V<#}NS=jTWDue%Lg zb3BFq>4JQ39F}WGm$YkLegD$>=0n?eLts<@`3Y?Q^YLF_MGW>B=0}_BYOB`s`nlSC z9|V<%`Sni9lvyi44Fzp&O#2soTZ2K`doA5!}^ zYfl=^8Wus{8!~=*|1==x5p++?Cc5|4`%gL_YDTT&c*}1az1twqn)x@<{OiN>#b7r5 zBfp@yB^+|&$r5$%cn*(Bg`%a6)S*rr*(j^lwMp zy9N!y(}exK`(H$0=i45%`A1*X{^jlGo9!OK9h1XkYYwxok~#g(N(sg8%UmV#V+B{= zyfyF@yy|m`EHz41Jzt*xU+aeA*K=*?+R^g%^Zn5Z?CX737@vw--2l^1SCH)w)!z^4 z{3*>^I@ssp8{(~uL$L3YbiR7RUR{hxQ1<85kmrBkeiLl(^N$2}Qm>ctf2Ug`q~=wm zYp%S0-@Miy4;Jds89ws-$HwYor^BDgs?%Ro&;JtV|28k9xM!~!?du@V|2Dh2m{;!= zIa$Q&tN8rSo%ldF^jsXj`fsQm-pcGu-McaSn)iRFO$~w4ipeBXukWjjmHh*e|Huek^?E7a%LW-?%gw*Yjv#*my>Ou z%T&LgKR=<{TWc&lVn%QFmgjqS^SXG@?lnmn#Ppr#TQ4903~WXV>#tIS?QrD7u5|bh z7Qf)_^K66l(5v+nA>U-8BO3R#p{ey){T6SZHxG=2UlZm@=CAX7C!bw}PJKqx!{dBq z`F`FY20YGt3G1(hy0~I^^l+N@p=tGcseRt;!%k>_DnOXuU1qJEFOU&H>jca5Z~k8@ zL>>qs8wbhruifhm`ut9joPWaef9=2_SVE$N`KOf=0f!f*(e~rz=Q~$SIs+@>#QeLj z3Bv`oJSF_|=MUagT!vR)(uDPuUF&ba8Os*YW7bUH`T8sa<$T(~jgOMb#>~Ir`SMBTitpijBiIO?f=moKNI^p%s=PrJ6c5n{^(u7>2yQNsF;7xs2ovbZ}Ptc*kb&;H^0zi}iOVxCSW!=E$z zj?YgSeVT(A*9X%j=U9CR&%gJPaOgMRi5LuF{P6ti4V{Hc7g9Q^<*e%cA&qaJ+q@MF z0=$I&xlS(^oV?zaPVB(q+sRyfE&k39aH|(cw4Sj2%lqfuYi`AVPn7)U$@4$YB?bHn zLL~FIc>RwnJ_v_eMG5`$J9jqVw?SUC`=BK%eOD-?_0j#d#y`6y zeDm`IV!L02B^rB$@$X;xA!r%Bh$i>1=9`=U0k;aEpXpKI{GK)L12D0t8C{$duG-%U zh17q4Yxx{-Sc_KWY4}POKGL3~Ws;5*Xin{pFDJKjFx@d!%J;_4|?bKlqN|L{?>Tqoes_Ysg8ftm)O6SN%fJMR**sm#y79;bvs+(z-MN3 zfxbN7w^C}Nf6Zc&(dVD)`h5O5VERh%Od3Vn{!sHJxxC`f5Igko>`CXWV&7k$?}h$r z!M*Ji;`mRVZ_WO5(B5MxwO+>Z*L-|@dR!Rf)}BYqL4AE`{OyVFOq}u2hPFRDN3}nA z`+feaEzrQmi}c;8Uau+n0SlvD(bZ%Wz2#}9TF>*n#WDe=HVzcV-$MIt#x=Xv&{4*E zs`Y&QEhS?&*eLma)0$nM=i7eTdDQBdMQ3Q0vidCUe6xq4SxWmjN?6~8Mxl88l_#|_ z@n-yU{`0)PDMJ3WT`oY^aeK+V>hqiU`1|i!d(rNC zG`-h)z4iaT?|l6I)Q-C_px061`72$X_s6(>W>o83HUFIdZbzQNmCvWiz5?eS^XV__&vXs^|(n=Qr^6Uy;LBz}}{#h4o)!nvGP> z@9afa9a6s^>HM!zj|1W5fyu)B*pac*P-DCe9k*BAA1RIBb<*1afv=p%gSm_!Uf*l% znTzu(M$j4h9;*F~T>WP3*3Ix>zZa=js9rDS-+$m-w2K=-!$vn(t>^h)wssph)(I5a z_oIv#Vw0oe=&ep{eiw4}C-wg%LyK2p|GrsgPkc0UGVNYvbB6IF?T^X|-w$p5qlEeG zz40etMB)y~d=Z{+y&s8~Q?OCUx4px8=;6FqSf7pBX{a?JhC15G^R1nE8;-7%+V6aP zZsjKn++Ea)dN|ATz5e23u)21JtT~%r{rsi+-ey@}te9yg>5t;=_u4}$z>(Y&=GUHu z*2k*MpQPVxdA@ZA*F@h8G2c&=@w-TaZ)9`gdDZugukZ92Z-`sQi1{{rT@PdKR*)>8 z$Ex+bzB_DeiHaGz)YL(qZ=H2ISXKFrJeXRcTJOol=QQ&B;?OiRI(Upc-$7$)VCBG9 zq}f>c_?+M2r7+W0%=bL)5%}>$Z~CiSM)muV^8Nc!0CW!$>pR|=jx*X1qqjdYeJ|qb zQ;xh3foI9{gz>p{2c5B}{a9+*Y`Ns{m-jK^?IrQ zey3GD9GfY&-*e+UFfC>Z&6|r%pEovTO5M;m5e2XOKEoOusn$2Te8$km4iH0X~r zUbmrNN|}Ehz}1K5ocs#=Nqr}8zjxT6gT0M@ zlAxs*RKJhc?`hHc2zCl8iqGlp)yA@zZzM0D@y*w7FLG**Kbq;%?Z=q?&g=IWqK)kz zR1lNJOus8RzKyo^!QGi=^i(tT`<3dq!DJ2WFrt|JsbqZf`M2JWePHL4(Zc%C!vlw* zev97pPj~hASIYOo(Q9DoJ~7`ucc)^fsG;MhRIR^K`+e-ixj6gX z7}~SmG8Lb^{T>w?2{sR;_Pc^e^}FQfY`knciq`+ps(QVY?@N7RL7^2$j#jDPzm~-Q zAGtUZ`(6p8_|;IgUcvF*utg$7d4)>)n|b?v%%o_XG9;81Pj+J82hM)iADaR3Wn%kX zfq^(-&mwB^ceyOzZi9}(CySlJ{CnvAAe^4HSi(1dK9j`_fVT$eWSpCtPig)=ZPRLH z|Ka@3W(%yo-9hH2(1Iq84O6X0&VFBKTnI~_oh8Fg ztMx;w?`;ou$J7@sXwT^xs`dI@e6COb&oC)YtnZiG>!3!LDst@_<6obP&zZW`z&nq` z{`>S{_3*~ppX7Tq<3E6_KMm@lhg$9ms_uX0?f1q1>SAfLAH-u5^WXXS+-Y}HG<>2% z8yPbG`TYC9tlIeZd>N^F&GPT@9RE+B^}ri{Thd$O)ci>K?@tvt;7&2QO6C3cg1=rc zZsllUd~US&Q0(v4hn~t)zaJ_8hnug0$a+(S^)n~U9B^e*TRQbof{GvH^xbIhI(WX; zS<)ZP+wXRDl;?Am%%C;jgsRr_`S<)T5pb&1i(Fg7em~EDzZs6o_{dl#f9+K31GxBH z>C0$n&_7T(AKzy3TAbkEO|4%2Q}IhU{_CXgfEU|BCG$Ob{LTgLe3{C6607<`>}3j4E6Zk&N{4bqAKKsBFIz9Z6-&}maN zef(5jzb&?3g->0Mkyq~O^-{i{HtUKyHZADrfsAi{zGvn52g>=aNMM0_e@pp(bg>^! zo7;g_Tw?JxzCWw$&ks=VnONVgPio_pQB~x4KI5D3&uVL?fmX(Eh4nSvzt+L5cRxs< z99ADx$nm}YzAi3H5Zmt^?P_7IS7nm<`MkdCk7|kooOJ2KTkQAq`o6}g77j2dCj+V& z-F20|AjUGAa;nD|IGV!abd=967W9X z`hW2i-hWS-t%J+*6tv7$y?>&t&%hdH(;aSO!{krwa3Lb80B(ADyrk6bbwy7JSByNc$KF9OlIBNz@>~2qUMlyXT9RFw2wm{nkfh00q{r;rXE zC6gU#Ki`6CeU{eO`7GK7LwAY&ck4WNbh|y9=A4XW{B!>MCz})~ZMRjJe-D4X23NZ- zq1r2}^K%^kzO@fRgG8~uhxqtoh@RBG=g(KZ)$tU}@f6$lt|OMArnVccJzJjtp8GF? z-=<^aVXQp=z1Mfd#l9`5wI$=9x9`u*z7M*E=gHy(_WT1l|9<1JQrK!$AgrIA7tskj z`n06oeJ`o_;`x5`>^CT^-wN~Vox9Y-^$HF8&h4^lJt5NbRh|E8W5c@&s-6$b+wW;@ zw9tNP1$nbuo^K}`6Ql?0Q^#D!58>t;<(O*Ww_z3J*Cxhy5qEyFbwFq3{G?X2Y$mf` z`TE(mB|qW)^b(?7N1kts4{oqpcZ@Lp9_=w0EgD+VEgRVL=lQPp)(4zkP9Z;6tM6Z0 zKle*HA97^o2zuCTC;adG$j9eihXg|SEoaI3tGxZbEPXy&o}5LebPcOsFU_xCzaIi6 z1C|K&{o6kWoMLBBXZ2)!2Utt}_m@VSLDx#G?;d$^@Zzdiznj>)D0m$#xJMe z^QY~Gb$z!A<8Kq^uE1X17fbAOe*Q_Hjt9W#i8%gdxpoD{*o*n?{rm*jxTF)qc542l z`aRV(0e$br(3bt>ObwGoZo9s4a@ea)_ZdP`H_*Yp_yp`37^OIA3vWg^g=BR%>7NiG-dkD`{zdw{e<;B z-U`pR>ef~pOR_a+SQX=2!SQ{5c3q7ADCYaj1T9?t{s)POXa0E(mtXh)*a%Ii9z7qT z=2NQQ+qc%h-YcYh6V84wSl$tBgT#E3Q$OKL|F`6iA)9ZM!`bhSlNP`+y|JXog}pyQ zr1txaQ8qY!lKDlveQv9<3KMVm(%u!i)%q^A&kG8YVZp|&ByN^Eekz^M(CnHoE==;E zM;|i#oag&==Y0T5zD4swQ%FIzr^e);~Tm8DFzGQ!_(JK$>MXnRqwwgcRuVY-I_SV|2JvBnc3&b9N$^b zYh&H|8bbR#dqxfH+u{e=S&Q*)&+*;F(io#=i20tSuYo5+E66E7rr!Y^-zm!a`IFCE z(VCL_6RCf$X`eDy*MrP`(_8Jn*3r?%FE;`TSbm+eDbST5O-^FZaRL<2|X{x}~c48_)l@Q5lf( zOU(c3o}Rc)!(9@8=k0TkCP!h=%XE?(pypSq@8Rp>ad~bmt?w_d@5y7%!EB4;#b2<$V>&I{Zv^eZtKrY`U=_2CUJePBCnM^7i?VCx4+xY2Q~_GQRov+p%+Pv4xUv z|BdSPQoipLe+H|8uZhnk#y4O8TIDnkG-{6(&JUh-d=Q@RU`0RNmgn17#{*iw67wBW z#}4nFv88jiu=u)yn@?zT-VgqJD)zrWe0RdlJ?7G5`jM*V%jeIhtXKZ;Ja) zn3=j&*x!;qY%yLvvxts5>L<(Z$k4se;DE>h0- zTSz0WG5?y+kCQ0?bA}!#7YpS1{X5Yd?FO`>%TF#bpwElIQ(tnMbte_X%7~jbp-)T|BP&)hxnV2QdHzX^t z!{(nPr+R*A5vSjdC0e-IT!X65@8J19ShE4TZW8M=eyM`LW);Htc~aXpINHFBzBuuxct}(mo4DiYJ;%;Mel$ z(e^cD`F7uw07LhP{co>Jo@g*{3H|a|zP`1`-&7d6C{bA7T2sRl3u3$^eDnP)4s)|% zQs)d}9;fD0s?XoXI^lWWd34xY&uYG;^M!kNIRgz{rF;{v{-r9y93Mosrv0}v`_Us??0x0ynUYQz6gK6^Psm!-&b8fz*<`0ItL!ZZms*m_*(mr8t6GoLE~pJ zzIpq+Q;Bl^o1;{}^*Q_eVCFwC?N~*w?qm6J@YJr;(>a-RKK%VR)X#6 za&q~VmTJBl?|=W^IU8Qui}l-LswL_;ThY-M<@wL~Iv>t9bP(3JkBuFLKC8#lb2_a5 zg^#bb-{K1&?Zo_FS~UmzOqxe;-`=R=m#=TtZW;(rLcN9l_rq56vDGAZs%0`xmj5lU zLSg;8Kwmc#Z6$&Z;x+R71BulLCmlE5c-{H2jjU3Zz%fNR zvHC5~f7FClnAXcoXum5~|ALH1m89QIHs3Ux^UwSCnhD8M#|rD?!sqtG>HDqdqTllT zw@z{ar%7V{w@Vy}3l#RWk00Y-dDer({)qUy1T?(G{GZaCfy2G#QuoJ9|9Sqq{a6iI zt-VP^JNEtK?f1oVL!f<`xc)6%nVM=a(wT+{S&s3D&i2y^j*R6-G8$JpRWyq~K_2TSVLr24*l+*f!zu#7yLA{=l(x-zjx`Q_A<@ zKu>6^=PK+^pS^Axdg#xiJ*d3Cch&R@Z!!NZJX&MNg7$Py z9;tmWWxd%;c?+fE|v_loRv{umWf7thf=ij^8Qz)u@PA>gs{3mn#kNNlq>LzPY z_55SrKVM*>gD0Qq(O0w7{7LyOb^8pf)5^(=9<08Nx6l1!n_)BM{3ucUyifabIJ@r$ z3G2)F<@LGI`l;~8z+RXiJ9e!XzN@sNI<@8bwV3Y+Q_(?KzuM#HV6@&ghHeUG_7AVm zmD3l&>wK|3Z@N7hUzj=33l=QC#@DYm4_yJTwS9#4`Qa|p(dLyaZL&e0UmM+E=4&3X zaFb|Zeak_6XB_o;2~E_I=hyS@PAJt$B%A!y{7CtA=sXXPW=rjJp5FrBbhx@l?4R3H zWqdQ+lWI(2{POc<>hC@ZFWyM~b3T7o_Oltfb#FthYRmIGIPx4c`JE>@UlTd~USfM2 zDq7wb$JcuOgwMAW^s%SBJ|EG449%_-5r-q{`E=6$^5azL|E~Q| zQqFxNgBP&*<$QhW=Esv@M!Hyk51;RWb!!cz*T1swJFmYF#?OZ7Cez5(>iTa!|JCOv z#d|qYe);%#yRUB0>7AJ0rb8yti+!r~*<5`~&&D@Fcierlkg)Z9eanyw-=Oa*1wGM9p6|Xl z9>VTcFUiP%Y(7;0r@vckR)T)6hOj=(zi}BH`S6?A$Fckua{lw~4t4RVm6-1hzdykD z5kDmTWuYA3`XwfK1V z9A`RFc@D|{_BYSBQ;|2^Z0RHHFEQ4gf<-eH(EKTOs`b2mJ#9c~1pAWAHfhA|e_O+te2^*YTMvwN;Q}M0f>et+13#>mBO_I;E?;681 zPjW6$R1CFZ`BmwBnBD=~;n2!N$@%qs{rSPk*YNeXBB6bK-!%nxZ_1F=ukn1>dp;K} zVwTb<-|F*6xcc+FRoU>j!3kmg+DC;w)?MjHoBWgKJ1^%n+&-5_`c?P$7jgRhps5K) z8JSay$C)a=`S~yb+m-Vv*WD*8$E)|RG(WbY<2Ug9szIZ>WUJN_E`FAN=K(kyydt^} z*!&aTzMdGYi`$wvq9-%i{HB(if1TFk8^o20^WU#(>*B(##) zFt3s7`h5S%j&bWD>ztH0?f82biG^Jlz$40F0juU3! zgp?)p)9Q@s^-_HgI&uoq23;TyqZz+E|CRy9c-*TsUA>6$&)2U`EWZqE!o>D_qH{T{ z&#ytVfbkz-EuHWBIlTZ@-g!l8uG*`5zdZk1PwL_A*^TI>Ta14`e!j=B3`W$dL5Ie$ z`{(`dhmEz-c#aWmeX&yY`+5GI&)3AGzWQ{?S+#yk{d3D}rQi|rlPt}tP_0*R_35WH zjB&tAG5^ZxEpR)tjLfdf_>bq}=LJ4vAVBG#i~7$#)^3M*tsgz{-#*pz;q~7nbqXBb zBi8@27lUxkz=?E?Gkdt^ZT0p-?k5t`1um5XJ{o$EX|3&?07nghBq1Ef?EaS%2>!tR6ZdNdCdoSky zLiY`r)^y*KGpu`^}lcCMQB+ij<5At zc^9m=7L&hb>8kg~^F95wF4lh8lpd=4QuY6NeZTtY6EtsFLs;L|Zdh$RKe!=X)WD=hGE$x2WC^AAifJx#R}-I)c1YQ)z_Eymwj<}$GKMP>D*Wo)%AIOulFwqww8v?^=}@{GvWP?6TY`{*KCZ}r~l^-_KR_~aP8 zA9sOVGGx!6=X*+SL;TsiEls&E&$oWZ3vj;61L6F)gvqy|m(y#q`61hXynjAtkS-=T zHltQ^Ua9Vn=etAUd+_QY<~x6S4WtM3Y4KHgej_yh!o%}AbcF`vw>!sgi;jj^+Ct3l z$3c(5v-}HbPnmx{hvT=$q!G}lxxKKyt;RkxyrhGcGjTg5_Ga6oUOw@jYjM>R%a z)7oydrKh}oo_yCAuDb>a`$M0HxM8JH2%R^%sfyoZ&Oh%oKM(>NhY9mvuWqlyx7pii zVn&Kep98r3x4wTEq!)_${aT!bCnsH{ihR3VIeriPh=QfXV*mV2;~n67G($3fndfuI z_NiF@WjQS|U9Q@{{Ct-&*?S?)uU9SDWB2fjzFw3zjY*! z?Qh=x-u%7+?%LLlUQODsTF>jRdB%V6dG-Tgf63@&I(YO#b9(J9%TM$3*G~?=2~WqB zkO_w}RPT@HH%{q4$9T4&*Q{Twt{=ep-+QN&LIXt&;e03G^R=)*t1+G6U!_`4IDLK` ztHAQ3;`p2Ci7L3bT&mAJ-wnIyV^GJ|!upkC?hnCZQW*(2CC~SnnZse=t*xu2d#@-sETF=|xE`HuH^^Vy8&i&|tc8TG%YjB(D z>r3tL`@7b_rsiS7`qg!Rf^qee1lq4+FXNk=?-cVa6!QOw>s#98-Ndo!-{^;tnruC1 ze_J=+0SbxF{ms{(FSb7fuA8L#%k$m1r6K-zr5z1AAkX*X(Fm!V9ti7G|Bk4Q3okaIqptm@ zx_&YjUn`5c0ilOWiJQ_-_}}-Dx4(nCYhvriM$}uu`oH-4^QML`;9==sQt*>~ACQ~B zI%sum>{P2MJy^i{JM=lee<{z0=<-r*e+idoW0Grs`rrrSo7e9e%SS^K{prH|*;}y0I%(7C zgfYy%LT-LjjaE}3uikv()s+36=i4mC7T>IPrw;mzZ^G&Khn;gF_qLC)e#I(Hx&Jg5 z)7^>VRqt29&3AB~Zil9j}ePtD4b$SJ`|f{`|vR zPp`uVv-hM)b$=Gm|JAb^sMX(?Rt#bMCv*AnFvDlC@A+S{=9)bJeHv=v4t*1PY~^p& z{ded1@Al*u#QzZU-~C@Dv@Fo0CB>|Mh39|JE*(tuYb~sQ3H7vr2C??S_&GIhhIKkv z(r@?K_mAg$N=-Yc+g;4}!0r7p$Z00s(Vpdp0yw^VZjvR)y3>MM%e)4=z zxiTA$7y1b6PxbeYzzYMt=)4<~RD3EF(*BdyOBTVY$6~%G6uDxX;o)@qY;)Cmp6_r? zKQK=UBR3nc{mIw2bk7MvyAylp%L$<3n~$IUh*<|y`^Au^TiEmA^Ji{0X;^c~WvUqF zD$DozyOD6yMa=i*tW5k~dPB(f%!pX{-8oY-f0fsFi-HZ9H6e{|zaOsJpM3nxdc!Wz zMX~)JFmwo>-r`2D8!^85`m~kG^IaRAx&t+BRZ*^ZNdv)?=8E z|Ci`*mgn1KLlrz*)_}%+|E9V=A3xWR`T@_i421r<{+u$Ha8s9NtYrGG&*^*5i`p0y z)>_zqwrYO`T(i`pI-w0!`SSoy-$$&lhVCQmh52($&!*V0%>bo+!`=_if9Yjg2&tM* zTqN}g()lg}NA^Yc=Cf#NfqH*S>r+cS$HRms^Ck0}czti0F&Jy@T|`&CmgoO&`n13tfKj!5E75 z6gBpIc>X74u14$U2{h4M-hRJvY%O@&i}_F1OvT>amHv6hlvC{frTO!Q2g4y{LXt4P zW>Yf-uYI{JE)Td{qAbx|!mcD^OeTO-f^@@F}atzSs~zGVFJ^)WwEHSyWd zW;E2F={wK=*S448U(g51`3gM$b;JI`nEXcc)mD~2Bb@)9dEfzT#J}X!TzUR=9{vJ_ zuMz!jCZ9i>U|0dqdKu8X3budv{&7W*FJO^ZpU&53`p)y8dAJUm>=ei6UakEKRq=W> z?W{ci8`}(oBo{IN`I}Af-TDEv!5nsfJpZQ*hbi-uV*lM@Pj75gYZldymFIs%xIK{O z3yAhT_WpSOOBPa`V(&qVU1F>GmHO|yt~tQ`w?4xBS$gR-9N`>7r*;UeUN7ap!qOFH zYOWR5&uAZY#DJ4Z|6Pmm&&TJ^8F<5-jbXz6v$@Lt*x5cYWLBp7_e^xf`G^H82|r(WqWp=Q1$e$LzPmsZuo{J0L(a^(S)KI(JzZ)YQpgV~ru;rU4k zwY1Q)VN2R^W4>xVZ@&*)nh(#SKS<6;p_s_(l@lpW~tV*9>ufi?CzvzY!)jH~8T%J-(6$#7QBSIGBQUkAK@HkA4p zudQA$<@?rWCwSIK%=cB@nRvr6TsfbzwQ4lT+z)2YJ5Z^R|Q5 z_Y;!&%e;Sns^LIfdcvI^Kg0Ou^WSf-r$X()`I7opo^Q**y14XZ2bvzs_$D0R>no4I z+{8jMu6lknuix7E2d0>s(*Kq+`<>_e$Efp=vhssuJ|oY!>G(28Ju2pVz2|LsaQ!c_ zYb(#ULyg}MUDbr*U>2X7!|@%p>^;03tWO73&rjv`yWZ8eFsQ2@ePhY^=I1lEexikG zPsRRuox|_pzXkeKZ;+9SZv~%U+uIM4AJ_}$GwyaU!h44Y&?S=?zdYY29Vm>_oFUAw zb@cCsxtg=6$!K}LGpy~v&Sn7_eoS7!YsFh(Bg@4UYRU6G+hPKAKjBU6Jy?8!uYc=# ze=1&T7e*Ck>ty+M9^nY}Ox6nXh;q2yZd){n0G!*IA4A2>Q!)L zr&zz|uUHR#&x`%<4!@Fc=cDUFeSTE55n5jp^Xu?A3Ei$;rxr=ut^a2q@cFa1Mez{x z@r3036Q18!&bC;3ay5Ojf$_)ltE)U0Gi*h^WPUPo^{e?;YvZL7Wq)WSTi>1IcfzAX zFe69I?^@qq@UNCB9XFNn+mbsUVQ0&8a6JEmWPUo&ucm!DluT+w7k*&=w>_uNFCX0i zLnXfkb>#Wgiunz<7dE5I{n`8#KE6&qKL^8|+VpAbJ=NcTX?;s@!W&3U)1yDuFn;;^ zmS0p8M}HObTfCzLR{pC`A2eb1w>`)2lCnOq`?0<7d;}k(2H5 z{PFs%>)#o(p3bBiRcilCs?Wh~ZK1I90!e=;Z+{o}wZ!Qbo^uyZ}xaxJ1~@zNK;vUm!&R%;%{NX z`HVBpti(gl_R#d%XJz&I=i22kr#PCNwq@5>5UG9s;Z7v(?|PCdOr{O|AAiYQ{>;QZ z82qj!3C}n6*Nnu?COH!R`TDhr$Os6}5Xaws%um6rX%A>|w?tX~|2rEC;lpx-`E#=n zYiu@V88yw!RITUZZzXQKU`%Mfq<)p>|GrgC{I^(XpATUCx8(RAKlUK>X!MXotz*xR z*Y8<csfx=coToy9#;bQvQ><{Mv)L zAE9;)V|r_@y#L)&>lwT~Q;)VTXZ;-k+e`L!+XqapUUSihZG+GF!aq4dG~plW`l_PL4k zbVy#lmfRVuzCS7d4PMyegBcrW;n(KX>!tcl>$pIz>@Z<}+KJYFxOG}8^-ugymjBA> zzVON@hS;oR*XQ~F(KQ~&n=Acut9h#UdlAQf)$SlT@BOiB`u>Kr{(!i8<7Ma=kg`}rOBNB zf3Vj=ox+aPs*3Sn#LaiJ%GeJvC541`V$YA~->^;@lm|7XPIp*--Ja9`imY5%Y5S4X zd!*JcY5(b)ZWS=@rzs6>$?9AA`k8?SS74lrg0?%DsoEbr|C6BRWmJKUDKM z#O$n38(wAh18=|2w|fc21^RSYx7sTEo44N$^8dn{cILF5q`pqtpW1%g3-~cZpZeBj z_B-#N*To)SbaI@qzO~PV`uMVP0KGF(p8ug%{b9cL3}Jpfbzd9Yvtc?l(PQfgmwy{^ z*aqG-Tp-M^Pr2P6tCad-KP9o6KdFD-a`s3Vkl{`CRTwEWQ(rY<(O-rMBBlBhXkNxTeflXqF zLOF+x+1FD2*NKn8lFQ2cx@Dql{_XAg0N7F}j=yI#*?@bZr2O;xKlf57WW5&iAEXnH z9XnsA3vJ}>|6krwP|Gq$X#amYWr^Q5FQ+%^?PK2$Yia#laJ!w*<5#|9{yNY9yc+9q z>zJc-$y*(kKjP-U&6to0A6q>nj*{=Uw0}+K!xz}uuNf_`FCTv&)bS*Yi2X?J*JID0 zaQ&%m-oJ(Nd5!6$!z}(jhqM1{PPz=ypEc;BU{)U%!0G?G=u)_~Tp7QA@l*Bt`TDtA zf1bngNCRR23aRl0R>qmqlfUb$et$C8zoOH#3VM$=r|z%Rd`bDg71b3w8;uj@*Bn>q zDCa9$(IakbJ@23IB7I@`;F;tWs=trY{Mwu@t%4vc zFS9Rpzq*|6N@VjPd41PvI~;CCd6U~`*#GDGE_!N_gUB1L(KvEB_dc4p#hqfA9 zt?%6Yr|zwl@x6&+zKw79!!NFWG$UJ{Z>z)GVMg1FlKIO#-#54Z1M^uO>3{^L@BI9y zf|GmU!D6X>uOL#s=aiMgF8?M}_x(8)U%Y?+ckpp|^xz|@Q+<9T&-WC|Qt+=bp~qW1 zSFPvc?}wINgf)L^2zLvwyb}J&#&tod;-ZY4Cv5KYJQ~t{geSup}`PC z+OTdNS-zY8`VOX(#QI(p-Wjev7$=B%n@zG3#@Fv3=?$Y+%_Q%N*!?MplXk**84jEB;w2<0E4IZlB%8h;%RCAJixl9q=Eml z!9u(>bPufv%9Yjc)34nCJ;i)~__zgY-%;kzlWWT6&tL9Z0ZqRr3H#4qzTAx26R$}4 z=KE7FY!8M>M*D>M^O<}0;Pa-h>6u=8RQsEc-|02j2tyKbg!7#)1gt{S#o2Vzk~`Jw zrTV=zIUYXjzeu+CW%|kU-C3s!yiGgOuk#t-{CuaPh!nVYq);;7iRXLh$6_!V*MvHp zVtf~I^|4L7j==dJV!ro!7DJOt6IxV<@y*-s?mP0J+aOJvP(6Q^aQgk~_cI7?U`z{5 znE%e(?~?{UgvNgi=<9xrAKrdn-Md`rf0)xvpP9b$^V=>(b%afW$CD*P+4Cbrvi%et ztm|N#30A`V_nMDAp!260WOPgQ^`-nqXPPSOFC1vXL#CfRzpHmyLUg29pMO{O!Ge_4 zwA)v8d_rn}Ki0H?k%N7RUoUxni+9_gQ(!2aSSinMGt;rKCwZ-K{;Kn;A-L+HGJZav z#m{+uk9bXmbzB6MfTxgUmtbdu|o`#9JAB6l?76-w$;rk@#m-71Dw6-7a*q=@FoHwcX z)4jY09qu|Mc1W89c4im>zA# z?C1Fr>={xaUa);ZD}uZIQDmF9a@`pWC?pH|kepq-Dhv^jW?t~z&H#dk6{AHCb)Xy|fX%;%wH9dK)~C(RsEQ2l+7&PTpjGZ_xFc}PCp zV*0@Id7u$O~$bLbN+mjk+tpubTg!FCbIkI_4Qrd4=`f4*#BKIvJEWN9xtpv zng3W5gZ5a_s4&Ji&*$yX&Tv4fuT6^B-}(GjMo42+oSaV6b}{|o`P^Eg541TTwvVUg z^un0YK{R?Av#)tR<6B$75N98vZ_N1T{omeg2jGHNA+*`O02SYSf7tjABcS~ET2d0C z{=Q1%+jdqqNc%=oom|#GqTuG6AD=iLa$kgz_)qNj@%FJ^@*HfXpF(GJmG^(+bseEs zd5mQK8t?xOH(U%oR*C)FIyaYLgVo0*`pL(yhVESj2fW4l8CB?oD{35~RX*~3rtc1c z>4(MsEphfl`}YTFNdb zA?+b3YBZsb$IJ71=SC*9i1{d~KjHao()1y8*=9nmm$Uh40bGB`P38H?o{5@tNHg{R zke>frZ%rXQY;8gxOkwq9JfDC2--P^5hC=_=rfDfy7MasV68lsdpW2gV2DWX*eAZc_ zfg6+JTsIUl*sF6((<7&?Sj~U{nN}EQxhX;{gv%heDnHQ zd4CMFtPt~Ad;Uxee~_Y#&&liOrC&2(&efRzvEhK5B6@^NBX;Z26cwUd=KJ&cJ{Qf?#ao@P! z=kvLinGxLIP4oHa`%;)6n#kP0W$d?#Ectdpz$e{birKstt{rFBpL%FSk%f6Hm zdy^mL!RPu8sEgqJE#x!(V+9Oep^i?+iSyYh^ahL?*%KYplzzUj{kplub_&;lx*1cM^`)q$X82jct}i9!8$#YbHlICXmC0Yt*~se=uP?NImLDAg{x8}3 z35QI{($irmH<{OGn$N|zN5Zb-fz16`Q4dCu9>*h5`$yYa`3k1?U$)D!gQRjcpO2!g ziBHKc)bsZMQ9dszPXw&9Q*eJDt)H1O9^~MlmiMqWwrFRtk3Mk=59N_t+^Uo$vEwbpNAF}9D-uix^@BbMzJ|5iHu=#XfrA794TZXj% z{NvYC{?=k!8YJ}nD474C`CN3#ki6c#9);}H6y;M#CI>dZ?11k2@ZX=#Kc~OF1BYtV z(Ae6h*3YN)6KyMjdUtmI$vKuoL!JhTo-gf>2=%kfNefbIr!vn6f3>s;N^Z0JJBD}l zA=YM&z~9pP+2fZI*=@n*^Vfwz5L~i^xqs@|Hxp8?7mhm4mA-$3^`ohs%)!EUH5Xkh zuAgOgmgIo;E_C<%_BOtR^BW=gws2D>OmP073@7xrmey8e*~Vz}?W{@LdSQR(L82ox zD(__aTeS(($=Ba$NM^kF{Kh;FcS!!TpL43=|Nk_fbt(%W=tUy)ex6MYdr0cTI)Q%D z^<6ly64oc5V(xz~u3JnR2cAb=O``eurusMbUR$67vGsG0$vje! z-4^GQbSQ#UZ??ZJy>c7;-f19>ed2ru-R%QoBiQ;mF}M*z-m(4djUru0DQ4?u%xOh( zVESydsa9M+^WO}BUoK0y9`?LG()FPy-3F3#>fvaHnK++|<`0EWi&t~{Eps+v{h9S? zqlkU>9<*-!?$+mY{#mJR4NnJ#ah1OO-=F5QOW`Q8`Pv?&wcfOKJ)!0++^>%Xr=dFq z`x|Nfyx;6X(Ee03^)a7+()HZ|AErX&9rk>c-X?F5FJbFvK!<3u`^0l5pARgTL(e+4 zzx{2nfE3!DN4p1$^ErIaCV0@|Z(mR6|2}kmsF$B7d7qet_NIyRdA2eFGGf^I=dUm= zBJ+7QI^FS+D4!vLd*ONRW5NDKx<1rDs}FfGb0xaEo##`A($9k4iGcJzGX3pjg}#J* zU5PB;tBLBT1f79A-Hr&QNq>K#zg=*x6g>8-qgCO&zm?&H_v@G|U4{$W*!7_<+|8Ez zr~9C^mU9~U`n^y;x6D(A>ZKQtH?V0Qlb!i*!!h95w$ zLK0ekf7;&~t+Rwn6~g*0&1d>U3zDz57d`PY6Xnxmx*a^%+sS<@=ifgxpLxqC5sS~M zNH?3Gf2R2ycVjY~933k-Uxe1rUM_(oprQ!Xm>&^6zk6!uIWWv1iFyC!4K9k1Q*3^< zWR}9whiv~_R^~-!jX96L8MN_B)ps=qtphI;Hope_XOigROce0>b}N5$e)=SGD>Rgp zaD^Fs{LuP3_|$CTk#z<&&*|F6k1#*oE4K$ix1p!xm1 z;V}F;^pQ(@D~&JV{G+9^2Kl%BKh)=_dh6%QQ1zqQc9{^M(Gh)EBmMqDe%(H4k&995 zQMcv8+tv&Dbq>MsI)d$g59gP{k%N8FtuINU{O-Ej3$Ep{^>s|<2k1D`8r?n0^F{OP z5~B&ts-E1zVE*@~`TcaH3)z2fHrj8-uc!HSifQrB)k_5T%hUR5yHB4CR0~I|8l~%n z{#S9?K-jftHFN(_ZMhZk+i2- z+QyxN`DL2l(W559jfreNO}$r=Svf7|Ya679@_A>*Ot|cx#Qpps-M=Ng|K`Epg|M>e z6m$Pz%?1yW;&dJ@(B=8#DE_j#2g1wEY=0XV=SoVCWuWC<#Q7tCLSbEte)e;c#;>qG zbb59l5}UaW`NlkH<(KxiS&Mc-soE2!zwJU)h<=nm`d-ZQNBi5PmiO|ywI7-NmCieQ zlT4cc6}{QT~>g6o5;9Pqf&dkAJ$q@@7>Dbb6tQ zx|H$zlj!=;#AFpH_HgB#Bcy*n;rzmxId8xyz#4t7;Nzd>&rYci%vkIxm@lOHyQ|QN zxObR?zD(lR)BHV&=m$f?mvGMg`R6o$qk{*)Ve>W2`cLnAOY+tv0qrU}*vbd3k8@|5 zK}Gj4!Tvs)ugdaKM87EkoqJ#}%Gd24Rxl@u&6n1`DdflTOjNe}k!bzrMz|xKu#IKr zmzQ5IBhMceBOQeuqWoRAb_4H0NzDB7v-~{hHz-4JKO{YWpnhaJxq9I|a<}98qvsEv z-&hIL&*uy7r=k6;e&%EnQ^Zu1Szkc-fI2d$=onHp(Pa%rqGm(tt1YUnB{nJc528VPyqWB5Y z_!sKmD4#yWs%bMaxI2ZX`?uQLn4czai=z_9dWERzG(gwdi8`y znyy@jw)qWueyFqVOUT^D=I_maYH)5WTmKe@b|k-l%|@$@dA?}=iu|=c^U1>GOUQlo{?_$0zvt4H!P;UrzwHM)lR^4f=tDR0{PV@}O`x1rBAEZ9{p)hK z-el0Xji}0*-#zkDT>yDL+F0 zdM?136fDR>=H^aq`X}tKc;ggkZ_|-kzn%QtoeVjigCZZT=J}=aPs3doAo^!dRG%jO zd|`jZ*Z4YUb?VQ&zm+WP4p77He|Eo61MM@c(a^U%f3$w8H>iSEEL%UTzqcdzhO+fj z+o3NU{ z;PCn+PPazfzs@z81^c}+IQ=-De_B5cXE~AX6V4!&_q*ESS9rghUY8}{kde>aKfB!4 zfy5lnK(UW*wXP>reRi|)I@s0jI&=PDx{nHZI&u@rTOiKgskE(-uJeRBAGG(80x1hx zg%Yl`=_ghHadU}*Ub3H<`J(}HCO`h3MI>U9D1TLZ62Zy7BRW4*`u7v+XY9ynWU*x) zD&4-OZM{%GRXd-B`7+ALAzqxnUPVQ)B)UHuJxKaoSpQkdDZuh0Z2xLxRt4{X&EH`s zW!R9(<}dv~GyJfagDzO{{L=cVAFK|8Ixl7NH+ZHBad^4~`TTdhHU4S+{BctUq8F~= zbi49DpVrSWv&_g=t0SoU0X~1G`AhF^47ZHKTJBHd|30*S_OLJ~6>>+>ktpZZ&kv@~ zpZku6!H$zVxm`B==hOPxN!5{bGdqi{_SK2%r-!2rG@gtV+>cD_=hsGeBDsSRaWHD# z|4yj+TV<08uqTquXW)tHqbLa#(Az{esF%xN&i5s}oJI1NTt>&w@cK#TpVyu* z0LQ=i+?BV|_!XW%cWnF^qJ1X=wg1fXOV@u=R<8yFgX@C+C#|2hqm@Wc^9{&vSY<2! zbpBbY9oCXxKjFH6m;V2R{S{-qPQ)}kdB6x!eqSBTg!9_UDB?W-{ptMkS;HmB&F_zrrbwR) z`8B@T73z>HbN;sD>_;%@vo$)a!mp?G)B2GT$Zu!+-@SQ1VXNM3X8l%gLT^xyUdrr$ zTCC_v4xS1@r8Or+`5iG%3pyTP=ck<;Oo>LnqbR#Fndgt1PZ%-U5HyX#1oO8vzfrfW z$!NV(DC??E+vf}WpVq^N!1e>|{z{srJsB@|7Imwx73FtK!zehlGnP4@VC*rKe4LDt zlFkrOejB%sgKWnJO+)wQJg^csIwjYQM|Y`>B|Z&jk&1^nzjx0h zfXX7a|2>!MNVd6TBPG>Y>$@3_QfL~gFOQueO^_STE=6czXk5#9U)oF46d`@OIw7Z|r z+`qPS>S!|T3tN8+y8A)d;Oor!!04pTyhP}#ulzZ6%DAq!Qq zQC0qbt?LPuzb4!`23O3LnfdDjo2lel~ zPtCL-Wi!trq9Epl1j0U+Bu5|J``B6x>F!`E~iw8QS&pV(u^B zRr?COB0bR0Z#;iAzj3vSprGW-tS^&SU5MfJP^5j9Ur+Np*-{mj7PIr?j;9BZqNEg* zF_ZV_G`}7#`^G=54-=fv{Qvpu$wNudxKl_YQJmiwOZr1n-$=pv5p;fBQ8J3Wzj^^# z1;6L{qxPpR=xz$1ud(Y>yPi)XiEmr(KkVfss?S|Mje_vZBrf2LxW7J8IEkcPDG}&1 zJ%8BnZ!E02n!)XEJHLXiZ%yjmvcI=?A(}B_Z!3SazYg+ng$afine)NL4-v_GSb$m# zZ0mX%B-~$ad1fB?hFxdQM|?Wno|I~=MNy;0^?BXj|3IsftT&J2L0@yLGlA_d4dF70KfKel9u+3&ykg zeG+*NA~g)qz%AnZZd7Xr?e|RM{u?6w{|oikSGgFp>}`;XHou9drmhvp6$y#pY?B!9C0rSMVT?;{7!J}35ToM{HAU$yA5it7*+h6OuPb53+Z!r12^AbU71)JYL z3X@^`bhf_MFBnR;9ypDLm-77|8A@N9^XEXe58FR0t!#!R20`ddYMZ{w2{W+cghCb>* zp1lY~l00!f7e43?3zLGF_n$2E*CVU?q@j@u`Sl!Czv_IhH%Ruf_0@XDC~|qI1ihUT z(aKja)xR}gtOX`XJGsOo{QHO2SEub$$b+pF=u1g|Q9f514*>ZuY=1m(<2bUp@jBuP zwOjSIhN?d+#G66wYj*wlg}DuQ^~mIIHSm95T0g&{l|`~yJH(+d@-9(h4w>9w)c4yyl`?GUqbzS{I?}P&SdAe z%0Z?i<@Pz0SSik@$AAM6zgHP`7R)ya`?D2YPr+<&19V>^&gcDoKe3YiG-m#4jU@2= zvNiL3#10GF!4w-W=6usllS=6Kc@CPiRGd%epiZ!6vL83Yl#d^p&&vw!$lzD({Iz*! zH+b5Tzgk-He9--&VlN$Xe}5W^>%z|`2ipqubCaAZ94cV%uQ^|4L7bidN_X1X$`{S& zA?O34jqLqzYBwg5le6w4xsPr8&nf-v*3JML{<8Tz)Nc`)me7FiRNrgW&qRvPyFe)7ZV;Ns_P-6!zJhFU5Yi&NzS8xnGs_mj z?_rgK^ATx&E8Y(zwe8NKu7-nJ`J?mKC#Qqp!|PAX^I6I=KETlXD^au~udj6eDnBFw zjLxv@%bz-#5Vv9H(W22S+xQpi>vHv27@V$*j{lJIDdhLw=5$y$#{lgS%wGumLle4v z#fjR}nDu2XuRO53V2xaLc>ZYryJFlQywuf`d)YQWOzZ37qWkb;xF_nI#IL9I_21tP zaCNLN^L&=9RlmXcQz)uW;`NcvUyBEKfgvQ2x&P*9kG^EzhBTB@#;>ROeYC6xjNQcc zzfErDWMj(~ng)qDzi#u@psQ)5;C^6QU-e2I$nWy|=;T&@e>&}d%Y1d=n?s!7enGmw zJLR7j=@Z|=uah{xeK!t-xJgNz@@47!PsneS!+3IG?L(&j9j-kByp=M!Usw3`wEnKv zav?eTHRxMhVw-*n^*1%p4sx?Ea_0w#^Si}x5IHe67Y*`#(6(NvzxCawz}^CO{pr%2 z_mDDl4f@&0>o?7Bw`wnl99hZq$LhV_gHK%`O3>o0iiOJm@2p)zumm43dE-y*LR zxVwR^zcTMX;9$b`$G0>tfM-F={v1`FKbqgH;2*g0uqP)yzlG*^Wz`+HKiw0JJI}AD z`CWgx9UQjtocX9ny zQc{H8%3<92Ytrv0+~2zJ#W3Q1_zK!FZ+ENy63QQMnxqPSCa~+rHU4&FlFfZIEmB;6 zbxO40W#>5N{+ul>`$tWze<7tJ@%nMjCqqbCnj|>ikk;QJv+T+ArEGppTINfJYO(qC z+BAtozO6%12}y1I3Hfy&VgpywE^?B8()bhVZ@$F<@+d72?e^jMqx0Ln@lIe_$=2VY zarI#TClHn2Y+Fy|w|^UFfx>t;zk1X9lM|yapt=GRQT_e8Xc^=UZQzmw_Y(>Ey`%8F zrN6NXMPgom>H5<(oe*$Vltse)LpWdM^WK1*=$eCOO%bm@E!5u);dhkLo1W6YpOD|7 zF-JjTl>zcU!1F=pwkW;a2{f+XGhwRm1Tv*%w3c7y0zRZ*; zx)!6qb7ETgrTz1lpFLocdL;Awh+sP#QvUZos)-TTUz62+AVV*X+22*xn?`H`J|Um@ zQc?fxVWJNiG5r6Z=2zu{E%|YZ&9Bjl!SG{LCUZVxg0Tg8_wp8+sh%LpuY8YD zkb8ygpR?u|kf^~I(fTmn|I++kGIfAXT}!!Z<^1=j=c|I3>l2HQxhTF)p_M;+K6&A5 zH_#ba$(+y7{i{Qkyg!egt`_GPhWbF(e+`_kzx4Bk{Ju}tA-O+KZ;N^h3&7+Q!GiX%>!gmCC;}&KQ%D6iDS-BhIDc!WquzJk;kHZFFdLP$_tY? z>yvzZ(tO`-**_7yo6Yyllg5y@h@Bskn}f+kr|an6Z}I%tddG0Mz3?J)eq(-tHo5GO zi_#{F`|FS4c98j&?XUNR_95M@&msMEe*Y}ZxBN&KSh$XzAHS>7AxDqpp*ufJTluJ= z=ASL^&4btBY`(8I_a!dvTl#x#{+j0dop}&^?JA3c1o??jpS_oBk@NZ4$l^XfzY$E$ zZ}eFm0WP=M^{wYO^-0Zi2@04TEy}mc^mxd>VSu(YiR<_FWzX>8&ustQw`CTi za{C8J-$$HpyI2)am>I{#dGh%uoj>cgoL?0${}e?BjuGu2jq9ulNfP1w2F>@rU<3HQ zfL)*VA8Sg6%HKs1PsH^(WAacKct#7&tEgW_&fI3=U)Vm%Qs6@nC}>?)h2q`nBb6IdZpa z3M##n-sYc$^=o~j_F%S;tjA9{c9`xsS{yE7Ywysc>U?{xjT|8ol%*TkNWPKxYF zUS*#}IZiy^bp6Zy+_;weiz_+S`4;It@4~>EAoMU_y#CcRb2``^WY@oRB2~x+n+quG zA@9HG`j=OXFKp0e>vL1LUSyp?4q9%?`)`_W*A-i!Up<>|hua#&X-FY*4&wPH)O@9e zS2V1;Z-A`p#QDw{@Bo+PvHMdmjE=(YZnkJj0KcB*yWw>;-hbayaKAQPAB$Hz4c{KS zqVje8{sWHcAD_>7g^%p>W$u44TlWw;I)x5!k$E*S~fZ_8_UX*=TjY`>p)a`SZ%%<`6rMoj;Gi+?|w8Jdc(SkZ;vTn%_G; z?ZEnNC705+Ka%c0Is8x|Woj3Z=f|O~>uG--`^yEIPOem zorLqx+>px|em;n1pCQ zMfV)dT0fuePrZrj0)y7G_4#?a4QaCYg^U)o@RyXs1y6$*U&Iq@%(w!4L!(v$DZF>prlAvZf57tiUvc#*rAkp zzN3X&HxhjR0&3qZ&i9x8Ry%q$U$Tu&$kSfKTo(G0E$*Bs7u@V zdotAhy9(nYV5yuTN|lrTd|`jt;J+Jq#^Pzr^Ec{0?uXDRwrIr(o-d9Q@_TkuIX;x= z#XNs%$MJOd)pZ71qRjhST7P4Vs&H`*TYr}wFNM|qVaWEcIKS4%USPZ3?EJW9>QCr5 zAr*b}<@J}&kC$xujORm`;QmZne-E6}BwM?bqZ4*~en98P@@aqY&M-E=5$g=dT-Rr4 zxy*1;ey?fE!P`ab`u5j>qsWP}CS>(mR+Qf^n-!q^G+TeCx18@|n)92<@5Y|J;QTRm z{j2)0Dj9b38VYa`=hqjs!QP;N*#O^X;gUT&e_p@16PfVq zJjz?o^Gnyie$5#Pchswx^If;Y6v?Q135q{&F3NAa`QxCY;%9C|l9Uf&eY@&aS5i@# zhyHY)CaTY;3THsID?5LlKD#HGX?F$L`)p}jFPsmVIbb=QAIs)<-H>jiF7+bvpSi1b zJ-vTv=7umB{fq6dV~-T$@K>(P`?1IW+yf21w&*Mt=lgEKEj)LR7xR9C@tu!Bl-+DJ z=Niu^&9~8qhqzw}yS}}_um~1y4nslR`2I0n|9Tks48J5NHItyn)&l<%Kk+ru+|Hs3DC z^+=w49SYv-FY2$YhIWOU50eDjQ(7S zwdLo}h5hGG<$b_?D4TEj8M5SUP!9SWD9-oG$;nv2dus)VA z>k9A3u=D3PIi1N!mjcvSwzh4(kndw>7QtA{PZ=im6D*AJQ=a<&!=|f-QgiGxDS6P7yx$9Da zzVDNs4U$lVUz3w2WJL&@-wmAUr+Np`~F(Uu`xvQ1NrAPzl#3~ag*gV=KRQ% zvD=};1zY6b%=1b6Ys>Lhu|a?rbAQC=3x{F7i5JrT%EvdIAE$M=i8s7t>+c(xeE54X z3{BD#*I&-B0!K^=;<~R9=eMq+4&K~NMI*ZM`q^E}DNKiz*?xWte+{{De#8h(lD z@9G`x;nvY4ZudI=|4ZwyMXDjGar?>C-*L0L!rgSX{(9b#Be}&zXkUmpzvJbV;ds{q zW`8O(@iz>5n~VI{iT9_@>uW+xd?`2a761L|`H|bDf8g@%JTzHHv6Ua1-@Xw>P@r4I z#kAcIM(eM8(NFlB({evc5YKNgl^@UkGaS4t+4Em+oBn~ri;L*OU0#1_e(Uaz1NQ~8 z=v=Mz`wRKC93n%WMi-#yCUJhZThD@LGgQ!$@%(z4-$5r=L6xB)vw!SWmW!`!X4kjE zy~3bdqAhAD7w7khDqwdLZ|44C|E4&wk@sTiukO2I{OuyUf1EY;IQ%tSi;83p^ZF$t zJm15z{3c#q#`e$4N}d3xkcRAC#rd6S^B8aL7S23BcJ&VhvI9LvIqmuUo~}>(t*pcG zzLCuP51hv;lekN@NY_PNf9=*a;EgBQ^{s^W{mAr|`OUuDWkmHi+4V0T-N@G8U7EV2 zbSGPXgVg1qsfJzOs&i>i+~SH+{0(t_M{iPuh-qy9Y_@O$a{>9E;Psczj|2Yc!aY+qzXN1GK`57vhV|z8rTue*yeXJzd}hvn zDU~*Y*`@;Y)?HkGHI+H|*upQXzBMy;D)^0J`{Uw?OCfd?yMFch?m0Z-IJz<(m5|A({_F(t*?jFF5v;I{J38;c>d}7vu9Q^EFx=>NeItp zu&t2Kd7rQ0swZqdd$ubFdA&3gu~3{(-MoAF!z*_E>ZM&*5}aR&V)J=_P4oF_Z53|c zC5pSP%zuB{A73$6A-zYxM^oQA@b4FDf71!2H&}Tq+aJ5c$&*VB)kvqCm8ibP5C4v* zr6zIt^Q7-*;r@vBC%X{I#V1UC4N_?j`s!I+jW@6F^!|wSOTQq(uL%8_F3xAJVOMw( zRlueANY@MfvB|P`pt>O+dBpO3()FuAYh`db%huP!M)eS)mMy41)B0-lNE15EVb`yw zTh_xWgKTu`H$R_A^Eooa7_8TP=6u@rm(cfrg--bdbMgz3XTbEf{8X6V)<`Vjv>%(# zveOOF^{E8Ot=-VJUYOr5ZK;2Ec2W_{SJV3HGJ76OvS;&ak)4VE#If}?bblaxlh~r@ zr+j?U{@7^C1w3!QH`k$^G=7BhmpwN}!3a0DKhC;UfRA@y#@rwAxAZVH99oaMn@i`r zg#2pGzlnud=0iu1c`dKund!_IGgN68Y$-c?9em0wTu`(^Katnq@K z-)es8Om6R}LuaO2it_uZXC1y)z}DBV`n`zVs$WR|p18iMs(!?JhRK5Sb!dMa79dO1 zH&ikCjXC`r-~7hbSA*rB!PC1Koy`*Gw@5czEii>_^0*t$zC-`oLR-}509^^hLsDmk*A)xzAm|-51I?v z^{KDl-a_DIf;O0Ww0=JAkAp+a;LlEWe|Y4^S1^o7ke`z{zjt@qgNrMh-@P+tLA7_*L3>wbV(fCzxXsqz;rKKTcVYWuwFeRKVzC#p{v)2> zZi&mmtJ2x?S)E2Fz{tW)Xn8N`{D+X=Umk_{O4l{a`{U09T!r@w(ok#`&mW!N`oAj1 z%Q}WL&#zojDMN~PSE2u+`SmovmzUng3a8oi<+}x4NK)i`RA%ca%J0sSN~~}%j(fa@ z*DpH1oxGqAnQ9_ur_|n3)E}SzUXRbU)TdbU)5>n&@R<+n{!l`EGt`jBXiD8--oH}w zS2HB-pl}a+{wnoEHCVOGA6#9}?;ob?PZj;ULRt>He!RZm0c?1ZjV5}F^O^oZ8D>vo z``;AzhcI$cPRseAJfC#_I{dmel%4*}9e6H{Z()B3o4FR}r*r7CE^VE*%IeO+kf3d>9k(XZ>gKGJ-iDM-aSC*7Fm z=RBIR5DN3y_2XBcPvGury_owC53CP`ejZ+^rtN-t+8?W`oyGG$u=CgJ32~5jCE!2|r)aP?E9^{Ebm7fgH4LRfE}hCF8Se9?TG=MenBh@HRM9{U0R{#2oX z&HQ?rPv>se@o$+ZZqrl#{X_d>i;i7L)Sd6>OJ{dcKIiVOz_pLrd|t~}CAX^O?D~GQ z66JGU?lYX~mdt6mNck4}<1;g?Ne_cTg8LOBknny53+4Ctcq5zNb1T2XpH7dF^8s;w z74|maB?sC3j`Ng->^p4#`@88TOuN>?=M-^1D_Z&6btEAB6p#CHqg|d&AiNx18*S&tJn(mo-xUgna(~bq04TU&GwrA36I1 zd{9n9>-zG1(R{{jxrl#E3}@bdvZU}m)Eurtleh8fX+F0qUdEh+t)Cq#I*=K9KakJo z>7smou(^qcUSaP)y1TYJaggt1H>J{Al+VDlhuFS-GIM|b0%H?0%t>FsrwqlXdCha2 zpqRy+pPKdZHO#;N2yF-v=X2Tm&vH9^v|95M^7+CBs^tW{X=G)u^ zys!5(uKg&UANqbGgN4%|wn@k*ou7KRC*r@;*nG~O{2%xcFVxG5|M|3j?%I6}-_c&i zoNsj2-UU`~!cg1{aXznRoWd`Y*D&wrJNhXD*6d@?Pgtg2zy~{rGv}kmUVREWHy)xt zDrs$e3Hvwy%`e2yn%Vj3-fqos^79Y0q1Vi|^{N7Wzf)0+{VuZSCo*q$A(e`q?DTJo z^J#Bz7n`)`r@bW~-*kR@ZhsYitjgw3YjX|Q#XLq!i^Ta`Tm1(ADqz=-Hdo((o}O3H zHi!2@vPc;AcljKUc+7+?2+*P(M!( zE&;Xu1l24O=kK#kcR=^p{`UROKCmf@?O&fwGlq4bf{YJJKVQffT51JuZbJQ|`7&6& zA75|p#++}k&7A-zf7_zlUwJ-gzLq^nz}DH`oOVCy=L_pU245D#nUh{9p*O#t=4)GI zA|9={jJ-c^$u?N^Dhzp!7w7Bl-8AgFK8SffmF}WckaJB%?do}dOV1~De4L5rw#*N& zb(MZU;rSRx^d5kh^%FGVns|TZooY6|d!4O+t^?YUk4mz3m(2r2`LebH40qW2H~K_Z z(loofU4({ztNwA+{IG0p2`*4#>)+81n&cAF6X;(JC-kTK`Q_N>AA7!GP(lUN$2@8| zAB5+R-rv*Jr3SxGW6w9dTXz{OKVC)gzj^*RO8;Jjf5eL2Zg4Xc#rYc&nFBrl<)TT! zJb!fk=gReFyegADpLDsh5bPdc^sUG6R{f&&&$n+E(8cWft=l^lxOj?P-%(1}g+04e z(Dl*M_!sgwq_;UNUCpk)zH^So@#XCL>)AvEALKdae1iM9{n*UZn>qixf9@Puan%bw zYPci0?xX`?w^EeZUK|eVW>%v{|Wu)cHcxi`Q%z|-aI}(qtAzX{OAz4rLgs_ z`gA&8qQ|b^%yKA$-H)H3YG0mT+JD}Q%EBl9u+K-f+wvV0{&cjP_wqkc{w|-#M@`lcG~_Bh(AKQupCs~_U!5_Wzk(a(qMrmHBe zndgVrum3*1z;60%{rdPT7fjQxpw#v%t?^Iu^T6yIUJ}RlkBuWPz@8a^#w`=)ry!yO z_!xfS{`QyhE3D7_m#7FcFUg{QTGHpj`GLuWec)}O3VOR)oS%o|2EnCNLo{U!|D4vZ ztuJ=snLpV5$BFwbp{ysHpB@>}*l{J>A3F4!2Ka>+8a`I455oLyzf3I7vu69l?H$$t zZt;hDqr~-Vh1)^=v+FwM`KK@Y?Sk>+4x%!rgRSvP=WkECC*%3*Y=5XZ=L)<_j-ob+}d_Li{q zN#pQVa5#Ao-F+y|*SUg&SZjYcSLw_De)Rs7hD~`;>QjmK{}Sh`dr%UNc*CBb`=R{{ zZvN|Kck8A&U&|Fw;(K*$e`sF$7xHB_?0kB}wfaLD${&_@K8H(Gl9~O5-H!@z_>n9w z;-d8ZEZjdf>til-I`agX>mF&b4tK7qR)e zm>LWvvWL;ohtl~Q;rR;fLiXc&E}VIPWXX{%xHP>I89f!}OLN9StZmHh5B!+%9^$t2 zw(AtJzg0hJ{jyz@f+wiPGtUsXuYwJ8XWkR&|2uFI7Q?`{^6)5isy%;?uVM(5P`d`SZmF{f7W&QK0Hb%in%|-`&unzywk7?J&@4K4@b?P zMdlpD$@1~c{`U;`IymLp$FBHZf+#=aN-}=v%=U-JEKcER2eUZsRB8MR^{IbkG7Nq4 z7|Gt`{U6Ow&EgCA#g78+$VTaUAwMC`IglLJh$gKU=STZH#>ZXQ{FLe3!0vL@%>G&0 z_s96pfiK*zAnE4|^P@{c-r-jjY(5sWlYui$DyZ94X?zL!sL@n_vkFG&cp?9s<|A>j zKlT{PuJ5Iqse-yYhjyDu*9-mIsMJ6_B*2@we<|R^05~?t8{JtY?%$qt*o{IaXd0AZG1b#g|Kl#HV z0Y>zwLQ4;e>x2EzQ~2ixcKv(l?Nbow{{tCb7mx4k%xoOpE~;a{{|!RBL02>O`#&E0;o$S^`KP*6ZKxW?j_+0W0XW%_ou9;gw*cd@ z;b>=pczn0NzYYhF31Xh_oHt<(>`zZ=+5ayd-*YQM@WmnQ{QvUz-O%V&iB{YZ_fH;4 z+wl02Z2x4{qYT`>Y1vJpNrt2EO3TuAlX(i-qam>QV3+ z!?ymX@cyA{_gp-oLp76+%??-b+jRE(-(zVx4)`OB_RbRLquBQ)=HyjT#$7)C>HH#W z-XFZj)(B1g#XqO{*w<$^Rw-lee>?ZR1L!-l^Y=4u^Kg@bH*^16b4z_8%+wp5T_XPe zpEhbK{xx+uH>8yRezZS&*)#~;EW(lcVR1f;GX3%4K|##lz|)g%vx$@Poa$ z$4)jsN&UCMfFae$t;12#{5{9|Anx3o&5z5_{gAM?5%pgs&QI0V6kNXL2DfZB|NGJX z)7?WOp?Fd~+B8L+pF^87ajqKMKb>>S$H|+%aDyGBKVPUXs_U-d>P~EZQPq2dd-qmF zP6GWB`X}3sAF%QQBUB~0pFucZ+xOE{tiR5UdH!KiMI&xl!1hnQ4$i=e$?W=aa*8|{ zP4Y$x;e342{h3XHUiiA!a_0S79(w)Yl9Nzh=<^%Qn-^fOf9(1A>mA3yxx>ep_xCJ% zvkYsFW#<>h9oNF5yh`M3D9%q%{c1e3CBGPQg6|K}{7j1u#($03`Slb^LZvU-KPZmF44~zF+d? zz65+}I$J;X#Dqe`;Wx{a+LJ<6V4AD-j;<&?fb%Ao6bL{_m_qhqztZ)o>;`8%DxDqwa$jWN-zc_zJS%m@gRS9Q1c2${~q)DLC60& zrI|Rolsz9X^pY8@vPwrE8u<0JejGz{@nA=G{6`#|57P}Qk>MtBf2DE42XB}X#Tot* zkAI7ot8l|owmyuTFM$&=wsvO*b!g4M38fE#zt-a=_H2E)lN5>{gtGf5DXzhwa-s=c z{(3@`kDaf!<9pg{eMqp}2=5yjQARY+M=;gjf75;scHha?2fcqsU`m3Po#T6ce^fA4 zf6_HMfFtaxxn8}b@hjw`>~}K$v7N0CZ?9(Ieu`{;@RAf_)e&qyETeB>-AE&}NZ`+e zd>Eay!5c!^`Y?OZJ$yQfL)``U=Lqv_+%)#Gj(GS0 zwm#gd=>%1C*?i2_bjEMi1ToLI-tkcnET^QSab5WH2WUR@&QHTpKJ5AKX;&wMl3Nw3 zxgo9(itRjbLgy&v{ZONH7vNGN%qA{T+f^B-vV8*x6& zUAN))n{RNh9i{7q^PkUVN5f<~BDOv_HeJFaM|!vPkHqz1_t&Ag=Y(ZkXsq;kdqI3m z{#Av0O%ldG?VpxQhPTX@t!19i`a!cJTpY{xPg*NR{RML2x-h8YL$vq~fBp;| z|NA{T>@l8QpDOCI1isa@^sgrK_b(7C|L&ILfU8c&bAvt3wZ=c4fA_^vFmB@nyJ7Ci zt`mra<4Tndu{nhIWOJLe!J-b9%qR{4UKU-S@5=KC_+8$H@EY@D061o@>PO^VgAH zSmMIYKTbOPVv|yKeYczWT0FfsJO8lz6o%(aQANx2q<<*Ew|iu(-a=ey)x$-Dmed27Wn!ySTCY9|1*u@l8K=e*SDhCO)$; z9L>8Y9{(N-wDIbv?EHN5jxs!ZQ99buM?C)LZPdeQbJ_DF2MT`TGpP@e&L+M-OY4iC zk|C}g%&t#4Y7fFEMzQNtTAxhu@ItnK!gEL9AxZ4`e!X%qJlv>jS07Q-stF1Ho{vvn-491(vG+&&Rrkj|@3Q9$yWda(`vLlP6N`9%L@0kW`noZ; z^D5*b?(*?L=hr5>3h+@&+b&F3JpOGan&NL!?Dzkjha<4pes+9c-D-pVfbDNeD;;px zQF2J#vWVPsI_ws>pdF|D3MB&iLewgRijP@BQRE;O5hAT;U06{0i*5Ox8nZ zZ1sUdlS-t|h4m%Z!yWNzpShgh7XCSX{_GBkC$?JYjRx(K<_E(0_Sqxk@DEpZ{-EWt z8t*7Bx5IDAfB&)ld3&?X*glc{es)U#E74M6*GJt;Ww5_5d;VhAp7uE5 z3_E@UQ##^4X>5P;qEQYjsIdL_rNb$BxQnh`OsIJL${z26ha|H72f5S@uZ*bX90c!2 zp}+84sf1_WWBZHA&s1=+8M}VzZlZzLhO45%tNHk(-@h*(>fmEV?DwzLhHA;MIc$G% zA-W?@f65`n^WyP4ZQfJKx=Oac{utH;`|k8c+uQEfkyq`&~{g3!H(O1G2E5p&j zT0Va1{Bo07jikJH5Oe>zOtl8?o0pD;?-q~WrCGI-<00(%xefCN;!Tk)=c9cWukXM3 zP$!wZkv%{0^vDZIx-;8fbZ)skB07eBzL|2L*AlB(cKyZN>a8T*jP0N8pE}`2Q(Zd) zU-9^LKK@?ff93}F)t`?adcI-G>Q9o&c=r1@^VSzhO8c+e)wc7G>H3ILQKQ6s5ZfQ$ z+V@-XDM}UH3gJJWj^ETGnU?z*g#9VnAAj{Nl^l7`p8uIR2k7Idm>( zf%y2Q{R6pjS#tZJH@a3J?jK4GN+qNEE@Ph0d90R5$-*z^> zE(s#+{BX+463MQs?D>VK2TCN_-`V@CpWiqwNgl6j7r0S8evhLP$^3cj{na-fU6X|6 zRdYdt_!7Q<=X+g~{QUBT8<@byA05BxH;N_d3*^wL&(h~Y|0|be zM*0uM4=m_%nDJHNAkTxT^fPS-9dS3JJ89;Zm${>S?{ z)-F-f{6G9fx8{Qq%`0qwdOpy6VZ~Y|M7ml_cB6a@ze+f74Y#* zzn|wfCQDYzx^r@Z^A7~+lgt#ahlTSL5xVt7Jia5YB}yDj+3)9)e?EmjPI{w`x5VRn zx6={H(U;4(8K(Ttr~9KiC9-)|*zCBf4F zk8nOf@xKU(RyjMr+hG$bnXAX{-xOB&wmA^Xj$iv_>m=^c?EEgs+fOp`f5dN6mWSkf z?H4X)JOBOZ_w$+c4w6kCa%gv*^ttf;yz=M}iN|48qTenUc1yh1u=_7Ev%ZX;p}>yc$oxpjr|<0dbC~B%E0=rT=;&|p`1R7;E{Tj{=XV$L z$5{{B5RO*<6!#Z*dTx~{OkvmGe#M@%9*T}5Q%~{u^?_i?;w@}{{IM`dVlb3lUpDm* zx5-h|wRURv4Y|Uc(-+y|VlHypl|GkVmN<3uP{x{&wt-_*N?D#C3 zyS*^#5Ia7n#9uDxsX72HQR4qTbbRKg21quwXTM+Tl}B0Ynj`elQ2P4|>u1i|ev*Sq zbD8HGz3jfrTCLq&G;t-)u`@<`1`f&i>;(_2s?g#-wl?Ok7oOa z{`p#x|0Hbxd$CV9N%kG~`;|NNv2f;OcKz(ddR#c?-3_iYmj3^Q^Hb5Qw-p*)t>(7x zQ9teE3)^XZ#F#@%b~(RnokhJwMpt^a1PYsR%8bDqSy(&tCT(C6flS^?!dvg>^vpxhT$FJU$nV zu#()m#-5LoQR!jxti|6}w9UuT^)WKvO!CT!{r)t*N@%VJ? zkX=~e!`?rt|2(A7BrKj=+@1gb(faOVXk3U-vg^0xSzy7)tSl}&O8Wm3>U&MVs?iTe zv*Xjd!SVm__1xR6G9#muJ%88d_Iq7j=X`I^$NTSdJJ1ndzEH0a{n zMf_&vxv4@;aR0w0ce5&UwI1uOQt-#~>$@dss%9xB?BiAC`aFJH_WGd8k@P8s-=|^@*{vX5d;e{K{xF2?-Y0qSQiuqYOdnVcQ$Cde3&L6(ttXBt1m zQO~m=ld5tUuKf;9*N96R?>@WcK8 zzCi}iVW;H(Ej8m;>#u#kGmXM%(0b+ix_knqmX-AtX}$|~e!#h+n$?a@w+Re7?k)orlQxFdV-{bw>1i z@DAtS(BKmC191M;THMKcge}g$E#q22pF>aBA_vX*U9%(1I@t@aj}55y$l8$N^|3u# zbyN-i?m_kI;%!zcPpQ6(=>z{cQ&n@k&d}w*Wd0KM>o@x_Rok1{G=QsL@%muUi36&k z$MN{;qRnkpJL?L1@sDzS{`_vL^>0vvOinQulD`kfE>s)VRI|@i~9AmdvD@c z$mgd-d}{SKPJeEL*KhCi@+SqhIKR3Ejp~=;i1*K|HjW`3o8tIvQQydV+YOvwKVP{< zz8?!@xqb?N^8GV|!>3qBT*vDN?v^@W-a3(euv7StuOD2Xsn&&3{q}4F*?z?Nb>D9G zg1ZJ!S*LTF@tILxW?i)h9$%Hav{G4*$NLYmCJa&CmEwOazZyT@M>Xhg3hiMm^NZ;J z4d>RT<$I&m1-0bDS8zrL@<{{Q*mz14jGd)@qBDziZqbZjl<_w)E3*Q7pa9;nBhhAQj4e%O`WgB-qT z!fMx)*F}79+~`co^Zy6FCl&QOtmlk=UuMRt&7`FZV;`0(_Q&hrI<1FWpWK7%2hS?U z$R%?(=CDM@kI27XS0k)5lV;Pcb>(%je$chz3AwyAkZl^E8Q)IFuUPj^z~i&+e)V9j zeIk3w`F9@Q&AREUnoIqUVWCQXn4j-((Q^olmhgT4l4g8QwJ}%e+vD}!wsS|R8jr#8 zy?$~&jBf0qKBFt^hoNeIe#3!!D^===~b*-#li1rcmem)5-;`3`F|1a$lYW+^?k1v`k z<5P?eBedg*(M-lVbMy6h`#5ZS(Rz)C8x4+?_lx?v`ikpBT@{ZHb)3IjyX?j7qkoGZ zv~S9kMQ4*=rz<;HQE%94@Z`-Q6;y<^S?b*k$1G(;*;rr_!j-cs?m9>Qy#d!nX|?s8nS z{dgVeK+biM8z#k58jJ_kcZ;{hSBQ_Op49rz&5C>-&=C3*qJbr|g1Sv;7?W z7@}I{gy;XRZ``ZW`ycbO`t;JK&wjb9$CX(9*MAWy_?M0g&#K03!SjO+s^+WUG9I6< zyVsZA9Urak`%JU_B%J)E$^_iM*gxn?Z6-#mPj%O9Kc}MWkor>o8;c)~7WAc)JfhX* z37YMvXLMTnI<4u~IfL2r>i<+s~|J?ez zP_@%VUXy;}61iHEvc6V3i-!;%73`fj{FX*ce-YU)kAetz!V5c+C( zw7NK7v;C}XQHLB0K11j9mGL9S*CA(z(Dj|9_@a(x`{`oPn(V%e$1l;JhS14Q(dyN^ zG~3Ul+#iiPt(i$$r-8sq~u3M`ytD%ReNgS`Te;T`J^C(vG?5hAYQ+%pEzEn*T9XAaMNr* zO_H=>MRPZ{Axv54&%eaCU!mIh8uvfmEm}hRc-;S7nYdBavc!+xSRvboXg@uJ9UU9_Jk>l0PecjNQtEwk4HNq@>N?$K;Nb@k4v{@UUG=aFTBYC|Jjzg3|Psj7*G zdT?jW_7hvtXexCQ8O|I9+_1nMoYlxKxZa=^Eqe#+4T)*A9 za*Bk$GDq{X>(@?Id8CY@;qPU9i~c9@_($?`Eo18{{i~?oHsu7U`kco5vmA|TL#mY< zt8rAmzUY5E?rv9&or&jX-S%{WWowL|zZvi84v`eEFEpZ;RTo2W z|Fik-4*2IM`5$-9_M<;HPn9JU@`K%ZzT;@=(97tJ!`^dK!|pd+_|& z-G$AGnRI>TPr*Om-?g$}8r@zeTK!&Iv;9nZ zXG`oJWK-i;GXBN$4|=tyQ->bW>VE#3?I&f;6jHnckAJMSr_=czqSb*xn(ZgmG=P+P zR?tyy%J1j%Yx6C)6DukH!Scr~CLJW?y$SQ0Deo8cThfi|WL~j3*FPrupDA}&t9s1E z>vPfH{*u${80%E5JRjcw7>y2BHEE6Kk6Z6)2;auIv3-^EDaHI+_O$~lqdNF}`J7sP z;lj;8cC$dU{ajmpR&`;ZA3gP6S?A*)y?I{nxeK0Ovx&}C%@4%w=hWjkm@vAKU2<2h z&*u;BlzdW+v%vFfZ;sR;sWb5Y#`$KQsrx^7RKIy0Y(g5ejiVz+EAN-@-`(imh3xr} zLUozEF8Uu^l{f8bEX5D$n(e1kV1H8E`3&{t`U`pcIbO}1mX$}TcYX@_Fa8((PuY#} zWbq+fzx7_~OAg+7Li0b$_!0G4Epu;rNiSM`WUglWSYNV^%zIsq*8fzVv7}@M9^cGK zJ58osGht;G^79exBfH^a(p1uCIX#ti{(MG*;s{l?E#4nAVqZ1runhMv?Yc4&(im2|osc(Ocf{}iPz-ly3`%Omf3ZHfTq~1AUN>PIEBQsVpSWMeWRXFd@0HA40Gz^_Vf1YW0iH$Y;?YGt7Rjh z!?i#*>!pHUzCQV{)<@N-=YG^`w`?C`e3LzRjZ^_hWUEfg>!SU{eAXo}5x1XT#it<4 zw2;-bRPN9FmpRLf$*GND^xQEyzbDQYP77*BmJh@G>$aw;>9!y4Xnd2=w=Zc|um|m5 z+IK93npKTPzpvVB@^JF)243H67ZpOEy^T`0M(itP;51Tq5N=OZZi zVn4io+h>zbzOTpa>xlb9vN#{tZ|$3ZCowP0*+K4n1n-|V=$u!5>4W>HYNn0BF^aLF zTz?^NUk66qR~aA2zi+JXY6TtJy0O9B_gQ%V)M({A2(v_1cc*6iTHdf8v3?Rr>l-Wjg0KG!|8f!1Ep$-s4kmLy@1gPSWPFJE1J4f=N%=`U z{)yEP{ zBW-j)O6_8y*?zunk0cSPxW4OPy^(Ht9HnkEUbFplo|{7cHpKJS#gSLZolSbI(Mje1 z@%;ssS}(}8Cnl_pue>h$r}}2vU@4tX#Ox<@_yd(q%qaAHVv9#+P-7czKi{ssQ%!1u z*H0^A)X=RaoPkn3EB2RAM{wXgk9M+d7py#{Z zcW*}Kx53YkKd5yJcI+)=8PApb^Y&B2t21d|ihrNjYhr)W#|+OOJl`{#R(t8Lw(g)= z-+dfDn%Ftv=Wo?J=aTZXxc@0`5J7DZN2$G5Yqp;O9Ri8Vlrwbta2Y?M{md|pps$Zd zsb4+RY(EX3Z6RTE@c#0EjuF%;1NT4M()W??$+-ReXc0lzpN>-R9irKO#-B`+`m=EV zQ(AtHtXQDOuB=i1A8$Wj?tCIUPvZK{IkhJA{b>)&biaHXLen|@Ps{%vih0de{2Ne7*f^^w@0 zL#z2gl9WHFUr+WQqW|f8wjsH^3;%vZm8a2AUCO`dKb7~3`fl~Gj->CnK$>Zx{660Q zR6p?u-1a|ZH6LiszuleDkF=KZ2Uz__&vpcHmilwvar&E|f4p{vI~|gb>$_%Krjf3x zczk4DzJe4>^F^@pla5=X>B`+v>Uv8x+t2#^FtVT--hXg!Sv1`i9HmZ7(`-L`*X$-m zlX3ew9u`e&hexT){$>1^e-QK6HQWx90x5s}yPk|MF~6|jKs2o(*>49s&GrKhSII1? zzxa%UykD%JK6_n6zDfP@nEzR2ss(;hegVtBok}-?Zm)6s+3@nW%E!`~?szEUU(8>Z zw6X-}0Nnq$Kd(*(mbjwx&(>5K4HKmNb(LQ-KE?c7hq(<%*B!Y3dEd?--sS|d;VotS zi}sUDTaz0Rc>O1SOFRrHPGEy3%lk$9`P{D;xhwUz9p}zJ^Y+sv;2C7pEo26xH2WVN zGMLQT8%9rR%l}V|k47AvM5eUH^;_}#S=8m8yLv=7&Hg8TkvCZ>ou9wWonPYfZ}r9n zlSt|N!dU*=!ZMyN+#IFW_tR`YFFtM~i39NZ>CSfXG%YYn?R!qM{RDK4C+17={M%>g z{^nbv)RVL|>$mNrPm}dC@chEjPVsd4+9s3KN&eLo^E1J9~rapN5 zQ+J^ryu59~js(j4Mg5lhs4?7jUJenk7bpVN=DbHl&yy+}J1?E5FOebr=rDcavSCkHZ0nva3?pXMC;20b1YvbUAz z7sT`3wvO&3w_g~&=Am4lKi@ULa|yA~#p9=?7gy39*WA@x)tc?E2U|=0Zs7Tcm#rd5 z$27ct^xf_Ry%!RtHeI3F{*o6YkYO*<(fPH0%}>y9k0|wuBbx2ca`S1@(>t4P;QCwm z{so6_Cur^YQEHPrXkV|Cao# z3Q-&N*xGUhzr1~|Pc{ZUseb{ppNF+NLY+V6?8P>Dzi2HEbUvK4%D=BcIc z<_Lk3{<|?y-Y?ou(v%J)I1%?>$6xrsioR}am${-ZdHZp#-Ip9#kLSn#eA)(g^nzH~ z5zY3q$9fP+o{q;);V$Q)L^{8N`7Z~9i6l_^zAJWqN7u3ny*;jwExxVUf2AaNkx}X} zI%m0N`x)#RNV?U;_1|E>AZm5VU43DgX8TEv0->ES9OpZ$ZZOykR_~HFaqtn$P zW+m=F#yXfnO-Y|^N|E=A`t1B%3wV}i&X!c_KM~)DKer(P+ee}2*AMO;3ukvQW>>ji z#P`;63*s*I=V0@l9imr4ax*vP!hJuD$M^Q9{mI%XczkotdnZJ`3uMniWqgbC6&BYU zK_(ybMdv#^hg^kSJrmiPS_=O7^E>6sr;~OAaeY>!NSAiCD`ao7HRJp0=%u7_C)__I zJqaaK>*4jEsLv6^XBmF}U{KXWvQPRx7#6?$wvza{Bc2~Kb-Y1>CgJ>@+Uf-<4aVd1 zd)@yMhq@Is*k8t%7=O>6QX8UH;rv^;y%pF=`US)1&7{5n<>pLxk9>U*pHYXplBO9> z==qr<@PJ0%jCnfB`$c^AS_35ig)7>>>^M3IJf-tx>D^`i75m2qhBy#UssA!nUs{KHxxo>V znUq53R`$n;@k4UNC9=CV9$z~ieMlmt`r(es^C4pYm!1Acve_2z&wr(*3rR=I(f<3; zruCu9Je*(OHthg=&*Au;YTh3vO8r|HeiNPhkmCdJ`o*rDvmiN=v5uQ${Ay9Y{#R|< z5OThg8!c_A;E&J0Hmn{BcZ_)bAmX>%t#Ks3-W*D8l>Iz@>()wy&IUoOPqB<2kzZHO zpFxa1_|kRl{*8%poOgaQ_cLkqERRz z24S?>5as&3{x-j{gBX7bN55}f>;5+C``BHrlcX8H){scD<8l39IsFu=E6rcR@asJ} ziyV^XvT4vyb=mDJy49>mf+D)`{*Z#QaqlhKwq z|DL-41WKj;_ri(FeqJB+iwh#F>;mcQU|Ii*=hr)}G@;+5`dg36`HW)xn7d&U@ob6f z-z9%zh_OWk^;)PrKfZqO=3^wylkhw2yk`9Ni8w^6CGVk2LD|peKQ}kOK&l1f@nh`u zyQE_Yj^EB{Z%A5vHnkilUth%U%VaI6?||cX&cWK?^Pn8fKSmk0g69!9eiNEmLGu$P ztos@H{vv)K7dXQH7v^k8nzGL4AAk26Mvg~}qGz|r{3qrg53}W9e}u7jx8?n!elWG0 zMAk_97CZkGm$wb(OZ^wlF3RxUZ6Pe2!|AU1uhfe5HNf%v)IO2? zc^8h(4~sn%Lv^J3*WoA4EPsh$TMPDx`HT-b? zJ#VcCb`;0&`D-T7Dg(!F(?jO4NXnlVHP_6)+piIDzhuIUUdi|p@!NUcIM^rYhp@ZK zI*;EQL!3#g^|=1sIz0eZZDlMeUEVL^chbXY#Ag(qf3SHT35Oc+_!ad-q{ULQOluC+ znJnX5tl!>Sn+~=FXDQzG9d)ZwbbW1aS`xKlb zEJLdHhCwaU~rj{fp^`!Rf&;I~d3B%=~#|_&^-L zAD>6VG%Yt~<*eY7=ijqA{v@X@o`MD?6+R)rdQvZ%x(bs(Z=B?gGw&>ve>sIR|dGaM3?LX*O zdWC2Y!{amkOOMH@O(}H1YK1@e`HdTzd?3B<;rtrxQ5EhI9G|Cp)q$SsC)A))AB*+> zYX@4uj$^pKtrOo9VkhdcOLa8!>(QP=VUE-vbF4D|EAnem@C@j12j|zrt7Z|826+GT z`iOM^zBoR|r7kC1db&~Kui%f5&p!Uy2X$AvvB^J`bsnEiOG8Mg^!?T>Za*KN9bAz51Q5sEhr2aBY-yWRO zfmZn~@oTYWe%-~ANmR)?v_8^2@+>LN3rEinSh(IIkLKX<*M>FENL&Dp&#n)@k~`(; z==riL5&BSd81DaD$C|+XDmZ^uoN5c%8*%>pzOEmWNOR;`b+pXbj*K zZ7HMXbL$B|xSwOrzEoac%+J~mTtWP%kD?t<$oLWCE7hcJ z(0?^!S!MF?6Z2c1OV^P2Z!Tzkxpkex(Ax#)&t6Tpl4p-_{=B{XK1}xvV#h1z&x!n5 zGGsT2%<@Ig$G?BCM;q@;WbTfd@fmdg0GU}2=g;T;ENOaiA**E~^RJj6$f|yt6jZFE zCOhPHu|KNi_bhTE9?x%e-d;fVwa5Lt_o*`Sy%VlKzvXCy*CU)iXGYh7hY~*ba`V0U z`tR9W&0#k@p`>ztqUhh7UG5G6$>ns!arym=^#hYTgP?r59@`h98J{(8Kuab%`6-`3q-;Wz&LY(wLkv|&af z8@E;2&-3RXgQKM4`)Zm$OI{cAS5Fr7rF~9I`23<=pVyz0gU^%GSvY^*^u0?qUc>cg z`(-c5o4$B_^rE}eAEUzKd)?mE;L#~OKH5Le1m@Mj@wwx5Yq%L$#2VD>c% zazYs^X(R6!@o8eUl~g<7N~^17{uSr*Z0eN`Yuwz}U+#PhuRkrSN0Vi*J?X3i3O;!K zX;$_O`uYd4d6oDP`LkV({RBGs(pEJT{P6e;Xj_{`txjY^?d0o=`tzjJ-?-TZ_wV6L zfd2mZlo?to*XQxMB^=-)rz4{hMuj zUjUauZmg)XzfR0Q&4+!Yi!>j6#03T4JU$OrdjsnNg4jTR1z$XWo(wodI!NCK!{)CU z>KM@lTN2q@Z)HEvpDDl2k<+#C{HZ}x8+tXmkX@-N`)|>|KMA@?21@lStpB`1t{ES~Z9Jf3nc}l+F6C zu%R06-zUFULySW?+P_kAW*pp5;rzMi;3Du1$MI?NWF3slHD~%`G~-kCVhcIm0@t5r zZxUd_0^GlESQJGn=DVWx)xP#u!0eqXyM9B#AJ3or&69}5cTd#6e_!VcCn*JgcFJkG?Oy&9T^(WgG)nH2bLA3u$>zxUVeU(o8 zKbQGWte@Vg+8QE$WzoZ2e;uzs-{kj%Je?~*$e;A%CeAwvkf)bA*CF{`(3I|7?T}CFX3?8fBgL?+X@2kh>j6q31{Znj}M4X@1N8 zDe`{Nzk5F3LmC+1^(X3*1zJ-7psI4do5-J$H&RId4W8)vdTqbYaCl!3dsI1}N%Zed zNvFw=k3Oh>|9Q4C)k>D?|5r5QGyZ8736u0ER)4xyoJ$NIt)o*bzYi(mPuKAyIUk7U zk7jkP0+Bj6Kdw7w0L$y){p;-(G=hkkczpgwZ4PVR;rNRV?E_lcPpHcZ8DAp)9Nyc5 z_vmt3k|D2)@y}6{X;9*<$DSl8@1OVI4b=Y7UFtu15GSvT`tsxQt`zI52eB!)6#Ve~IM(U{i3swgv1y9_(YBO%!p=g0X| zXG4-&k6nyV@WJEL>OvrdNZ(J|#_=D|k7pAiV4w8;&L*ej{i43Sc{7&GrFi`F)b<2e zOvm}L<@;oE!pQ~wKH^;c2VhjqjWz2oKVK1_5!=(q-EvR5w5{U5czx*&pVTWUt3euFCil^PA)BLtw#X z9G_j%c0sCyPnSFLei5I3&*Dj~RXBe>xpEpVENAR`q`Y6`Prt=SNvm5fX#dC*t2}t! z#EqSrq&$CKU(R@To;W|j@!9LBHjUUA#O!Ly_!a&4^ZnW6;24}g|D9<|f1gNXgBmOQ zdHx)`{|RaTX*D(cF5_3^PnBeQSMmy3ZSH(GAD_Rl_&_!WtV8?%{j#dSqnUXAsC2dg z?9Yrv=ik^mH-f+kDYRot<@xjVOXI6;VeCR2pUao@f{&N7(Eg?g*9L=LcmeG)M0r0v zKJT`10Yi^+THHXnKdbQi-?Nndt-pse%!`Rw>Q$lQwi_d|1IVD2rPKd%iwKvp-x z`LlQXbMR;>W7Q8U_vhpD?w?Z0p$>Td=to>3tefV>I^IzJKabC+hF3^Rk|)|9{WDdM zwp|m%it8!(;{E%B_jgEcsV{9gOW`-3KTW(lP^-v9rdv(f&*M`y;RW%zhVy59ugNrF zzl6_i%Jq4C-n9How&bj%lbXr+7WL<#S-OxBf%|v%t2P8D#iHLo8j)=ZE1n%h>+7Yj zI>5G(>2%C``T2_R&w8_d&^jlJ!YXB*kAHr@vWJ;R3Q+y2Gi)-X8kW<52g-gPpY>|4 zgt7s8%+SLIph2p+59r} zS;^Sj9C^RUpHmv0CH}EEfBtRs3e?hkzWLnwEgqlNk=Z1t#caAhR>qH*e;?7d27MJ6 z#Ll&s*G2wxJo1S2bi@6-`^PTy_Ju?SmEU(1{d?zEC8WC4zpq*?Uti?UH@dUvfP+P> z-UAtbqW&D!;U}ryZyh>+qHE*o5GC;^)<0Uj)ELaQasPgPNlQ>QNui@ZEBN5~^M+qn zxZ48HZ_esSp-K|&--r8;1i$^bf1i*#6XvMP=?Zh@{qy+j=NO*80XKbYD22GDTvJ&E#pVTr~Skyr0G;&G{31n)`QMFjN`NU z*HSVo8RyTIz30%GAD^Q2q3{STm=T1>?~~RUz#9plSbcq8jfODdWh`w!S9w0X{?zT< z2Eq#tqV@H>rai%7aXM9fllP1K+5P?i7XW?@b+o;B{R+_T!|o&hux$pm6B52FK@%rO9AbV9q)>){M_3J<~|PFC)?US8da? z!B+Y{=a4JP{dxah^U+mOU*&?H&okIv3LD3}F&zVWzlcw(BM->Q6}bMaJ-7}%9UR2; zD*K;Be7YO*|OZ;g!PJVwPKD*2hfgY{(*o+EgoyTWTLL@k^GGX6} z<#mxir#c;mxzha51wAz5^We_&qM&pCC$axSYtd~8nkeySseFCWzvs8PNu2fZ z{8FPkpP`=_&Yx`z@`-k5JiinjYD8V7{F3i7`S*$V%t?Mj9-H9)eO|MEw4&L5Hlw%v z{zZK5?(&=HZ^HRgJ$5mz;#R~yWNY^C3$^rNi-b??eBP4;BiK3v$7jxj=8&>C7Crw_ z#h^1-M&kH{ z_mc2+@WK$+pF?X$!CFTX=6yuQkBCp#dB>s0Gjo>ftQnuqw=+oipOI+(^XlLSP#qX+ z|4P2Th|fXS?vg@xGad(57dm$ zBg0C`>*2oiguTLVe0*f@0o0-Pezu&*&tJr6)A3c{%ly^o{EL~PD`?THLe^`NW_)&D zR0HNo`V;F<+Q1q>{f@Z)Ty@M02H(Q@(|mMy$XtZymo|DZ@a}@whYt9RgfV-vsB@0| z|Hb^$^JUZFR%8La_)cCI@%iuWN(g9DPG8Ja-aoHDUsT%&Mz!=Uu01004{&_e(AJ_c zQvXMvY4ZOQ{rjwi#iYwmPnuu(eH1Z1y4I>Oy%`?FEGy@Ki2T`f+h=m^mk+8xyY}u+ zw^ZNHE>+HN6Y*)|paZ`q#p)qtd!1JFz)!M=R zl{kNX8f*#27vTK4bCV4mm;5_czufU|G%R11MQ?NGb9nuE-)1(rOfH}?*EHiZ$}IrY zmvR2Q`)4!M_^ylk_saqM;NS`=e($5;kI&D4T6hM|rsMqis?9C3{`g3=f3BYXQ+U)_ z$}j24*BAM-ZxxZ$i`K4a%o6<31LF~?B z&HUM3{gW8{^+EgNYrh*v`xhso{ylE7KJ53$^Ph<^tLaw1LKfFZGd^vy>%fFgxPRAg z+YGLnhw)AURBGdCw_VfAAy<2O*G)aH9 z=qBS|%r7->7)-x96|#3VHRE&MU}LD5x{m7hk=Moi=Z6I?p?`HeexEYA3%px`TdAU6~|}8mbH3BT(rJ?zywU4Gi`CuHMJ>!=`#Fzs5 zyta%#5uZOFhQhcDpXib$^16u6RqnfB=ucf{G)%^qh|lP&hhXw36E=E~ye{(RxxSf@ zebk&KL@VpO{+zY=3Hg{i64jq9<{gZvD&^-}%lk!q8s0AhB^xn@_4ikCwZl z{ylfVZ&LLt&Yw;%+tRo_(tMK2`2!++UsSd!( z)wJVK&HP#a#5%fcS0UTGL*_>jpYQiIhHf=*{aJLx9DY}9NBcwi4ekXq{bT9D%K7=? z_Xh%|+rVoz&Y!yaqd`@XMlCA&PxSBf)J%8-Su~&PujBRScq#rFR2z@qOZ?YEz7y`> zn=g%q(RsS4e|Pda28QEJn3b1|9}%C{<8DA7i9c&+DC;~vSH(Xg9~+KD`{TPo8LTLm z{5z*F`21(7M;U4FJc;W+7V-JS+>rj!lfIw6RklAdKAP933YazVMC(V}Y&y^mC#Cr# zmH9ytpVg)BPgV8A{kzrd(R6g{{cMS$e19=M`f$<+9=65vOP>=r(A+PD%&M7!U%tM1 zwnsDQ*9Na|4zuV43+`@5^Yc5>`almeJU)tlGXz%n;r!{@cRchh>BkvdW=ZmCwx{ zB0dXCeoEhWnS|Ci500xxouvHd%_s8n6Y;4!tp~Fu{fXt5*12?}jpKt@*Rz`OnU!A) z@_PExm?jE-`244ll?w&){cN6te1A%L{W&zZ5tv!5M!!E)(YrN-Jqktpk6k-iK(Blp ze`$Le^jsZF_3O*`7yWn6a!0t{9golBzIy=NN~7)V6lV z*4GD)m<~ztX|!|Y`9=|+iEJ5|-o*KFakEgcdX|sI=i^IuK!k+PgS+JCFUCJPjguiP zN0;s1q2PnZ=d*bip*k~RKQ7Aa|BwIvo)29Yn6r@u$~y1ALymtTD@Wu0duZJ%v`Ic? z?Ka5!MSlD`yDF5lm_&nPWquOzX&2dmRx5L5?SIJsPsC?>6$5a(jN>z2+lv0Y7sO_b zlJ|@FtoqUzYR~YcLpI6x7x6jo$`m@lG?A_OCF{eL0zMb!H;0m{czk~1?GAeWKp~qj zNZv2vGvB!bX!(Vr^FLl&^o3KGx6^cPJ`3-^*IgJ4znbCkPf_o&(DyNp&&`RRP({+0 zX0Gz{5%Ia_{Ysd8`8pc^d`b+1r!VuV(Li~>7@v;}+67LvaQ=MyE(MlH>$0vB6@2jc z{IDSd{_5fUN!}E~hh^q0-{6GC{-j*(U&Nyij?b5Cv}tG#Wz+U5_viVuUL9S~y*?3* zf4)p>O#fYTW!1}+|IgPiZ=}_Np+je(^S>TW?MpK*{11FyX#m|yeNg_ite8Ou|4v}z zOJ#hC`tnv)Gbq0sfSw=ne7cKvyimxpx%oMK{G;mB1?tA&{F!=I1re+8`22n=duTQQ z=g-(X6QQoepIHB#dh9%yz6HnUJf{Fy=zE>oCCdCS)-Ov&ZG_->oIj68L__$mGHS9; zet#l=UYvLo+U(Lr^P5|jWWw;eCT#3+89yR_R+znncT;eDhN}OO-&rHj`nqkBE{AO*TNnrq*-}D+DO;sBTS?Mep-y(mS zT6TxAD?-u!kA*f2DnfDnX=huVeW?TLR-g6$em`HKGk+;C$UUK8inOQ$Ja zw;_matJHU*|KIt#DKx5r`~T~z1=ROwA{%cj-(Td{q(kjt+_wNU|2ZXO5B>1BkgcjC z^OK0*ktch?^_e(+)6HxkdNuC<_b#f*2F4Th(q)?Q>vYTsHdl+K-Tx~0=ka^F$5hys zpN!`3KMz?9W^>cf`2Kv@8rYe4ovz~MBk}Q7uas@z6p>HOxbx>cevggc2T_@2sD52< zei~x0=(1JyWc-QwCqMrj=wF26_hj$)Kn9t!mTlzyVtjx8vkt`l9f6)N?(JKHw#t;^ zD;;^ih~FYhLx}x3kv^;<^OMNGuQ#`%yYpRH`dk_RB7Rji4dBegS+qf+ykG1e8S<__ z-MO3RUlG44()>TeA|F)0cD}HP7SBy&lPmjgMf^@**9m$(3P9_hrA_wHPCp7+Sw{sw zygvBVu{RiO2}RF;%u@}9zx{E2km+K`W~qt#y@6)@Mp=%5rY~dY*vj+gVt$}!?U@jk zf#a8UT@JzKc>HxWbuE04xlVls$o4JjhwTm#@bgqYof0Fji~9CqgG4YrRYq+N%IhNk zelk1*t@i4&L7(OKFXGqx!(HfHV2s9Jdz+QP`oTE=Hj(-t1CmFe`GK672J}g|6o0)` z?$7Io_f2a<#}T-`y|KFuwTPF_$NS3o7x8;@V1C^2Kz=a%p}8$KSkuuo&JImS4s3yL5a%SadLyI?s`>FV^R`p0$H9 zp4;i)n)3S-jaBfW z4vtR~?J&sCxK6`1EBkqV4ci?F&35DX?6oNgbl2kiIyvtgblZaCb9ujqkom@#`F)r1 zBkF^jdn>@o0>|f%71iNd7>>_%q-+A?wEkR3CV~X-D&P-I)Dr z<@fRWHg23LTzWYZ#b?liA+&UQ5UV~>e!e0;_lLCwpW42(LQmmmK7YFO#By4DZ6f=z zP}$Gp)8Jos*g7)+?H@hlkwo1Z7BLg<{1wly5e5W$_rUdmbB*Cp*nT_OfA1JjmrW{B zsm&kiYSg!zdbz-m$QZPK+VjgiICLzT{;RZK5x-$}0idgk>)W+0Hh`_&b?Vtvem)|< z?yt5R`T?#Fw00eYj{C}J-9lwQ-(PxN_Yxdif#bK&?OgbfXUrPu$@miSdnM%?Y-?rC z_K#B5`TSOFL`_)ObOhSJS5{t!Ca$C`p_aT~#IN5_W2o14B6og7)CU&69q5#=t}K+Z zFCM>*e>Q`v8907*n%L9E(tNSYmFH7M{Lc7p4i$d5K2Q%`MK=aX{d-&F=PT-i5$i4C z``G~6bGm|m{`<9S8z<9{?@!rEFJ+y_?=*7;x0~Vky`MA!yco{E_2(F|?O`f)#ylCn znL>Q#@X{TgZpQi7>5Vs>Ov3rsazh|gmGps8wEX|Y{8#Udn_!nGu5YI29ew1mhg9KSo= z9q7pkLCmqzzlr#De%%ooH1eSfon`+m=4W+B2hh}!iR{@N`TdFbwK&upN<(pduzd9) zI%Y>9^RMi$7UQ$&b~fNK7uOG#^PFLY#J`w+*qUm>Y#deURs%HS_ovP@plfh_`_p+b z42?>r_ZG|lPvqZ#o54{0?lc;oS+(8@dE>8B{T0f7UOzN)+XKd(^69Ac^17&RSM@#y zy+|1?JS(q@`nJRPOt?Q9=ik|BMeuUFG3)b0Gk)#!|G}r)=FB2U#-A9U?YLbBmVI+X z^JA0mnNYo@IDS{`Y6R78O+fRv!yk5~o@-p$r!3|7@%T*(ZVfu>nP~ntH+m#(?GVI5 zW98=~;`esrt}tbY4?UKm8NaYLkbdw>WJ7K%`+5CP@v0w;3c~XXy%!v%G^dc6aQ($R z|N58>hEsL${(u!##z9Cu9KZeFHDCkVs?-m=XvXil_cLMt@)$I~Kz}x3TMmIbaz`Ub zUh#jKp-$=sT!JViW;qz|Nu~)2^8Xj{J)+%OF#U6y8Xi~H`Tl|p?%TnnHXgrux7Y`T zz4K{shP+?Icaz>H!Dw(9J;0r>xHw_^L3ptr`D<(4S;;rY4K z`zn-tZHMCfWH%%DRu|XDy|SeFb&gX0x4&|Ko}c?XXaWzmOyK4}i~RiBqz8RF#Fcq- z`8^)r#$N3p;m}O9zaS{vnXdB=VoeR?|0m*mw10Q#`f(8&zxnzG(_7mU+3e=ZejeZ9 zT?yRmh}S0${X0$*%L-XvE`P=2yZb0RNNyjB_FwlU6XB-8c1qhQ@1L)q)lX@}dS+Uy zr(V7KL{B5%67DNxm@vSqn7>+K$@jW12 zo9dOeV?I$bK1Kd^2r+@eaz`{jk@U3@wN**=w_);rQ9nP^Z3cszPoO15n)QeNfu1yk z;`(FGxAqX>H51LRRlFWcx6BJ-8#*Y@hwtx7eb*C)ZuX&>OwqS|{FmP{g#PR!^>3%j z&tKFZ9?KcHj==TDTeno|FV%-l9w_+(9^YkN!=RoCj_;Dgt}t15JKDdnJi7_&pJJ`{ z%F>MQvaj>tr3;Sl&9D98Xn$NkZyC5Af?uDe+E3;GFXH!5W+b$Hl}Z1MR@Qm_aVvE{ zbh(j->W|q`>2QLTQNzmf(;|L*c-(=8o$>r|QCbO{nuz0fU7{{6ebtVgJt^Z)#P6V( z2Jof5Bl`X7{Yy;gJZmX`QJEhT@q4vSOZaGy^K<5ID>_2$%4U_y_!IMMwv9T&wpBA} zw5fs*e!kkb`x9u720^Ude&zY{_}y4)1vz#;bYg4G_#M_gl!hB7vhd3IN5t=%7Xu*K z7S|sn^)$`-@|5{^Q+^+hU!#^IAipuLpRagNh8pj;q4*u-*o-YWW38T9N3;Gge&r1X zmbm`d(mxO$xF^%P=alEe*XIH@Y=jTef57-<@lj-*%ygrWKzDXaU>SSX!wo-qH`HQTx`ZVQYJGLW9Gk)`4H-=AF z9ntd%aqpYaab}bS2gv(H{Puca1})5S{5GB5m%cG_Me}b{YIcLsV{!Zjc5RpLN4m?;SH!P&gTav02It?AW6x5nYlZBSos17L z{tFEn1>--jr70uj`-}PGIU}b-qi5Ubl}dgS^T)p%w`3g}s?^nP%J>!Q%XgbC2Fu-?)D9 zBD|_qMq#Af`#sXnwim|D^gx7a3n7el6kEoBw&Q-y%j72o0a(<{21CsI0$=`2DzM4BY*=7Oj7@oj41&p27L|oXs+5t&Q{RrY<4SyD1*O z?J3&|zB^CTKjrfO6ZOF;>HPnN3z^g?URme$LI2A~pfn|qCR9Ejkzb)h1~j@^it2-X z1$p58UI(ooKZ^VUhX+XcHEZSl^YL5$`RH+?F7(MFmN z%w+o&@oBV(LRRV`w7yZgdlNnClE}JN_8*D-T5bL?XkrsU9nUEGg3k}POus~XeUk8* zEx%t8pHYrWw`~aFi8{Ik_!j|IrtT}Tp zTwa-p=Feu2KMt$b;`r>}=Ni;{QA+16l%K!IpN^fM!u}6B>>eoi;Pb!Hb$>vI);NE* zyJ$%7N4I0sD&+klfA))S1wHgf&~wW)^Jk0LHgx4jVEazV`$c>PsXM~TJvctQ_f*sT z92Zt>B<~mX>*tGBV7zq(+CTpI`wZG%(y!4D^79e#S$4fYOxE(DyOt{W;^QyV)?4VO z^aN&+CF4uPXK_16X#T|??a%4n;R@XnTF7p4=Yx3t+E&j6b|1mkWUSx6vVMmG{r*zwS3)4I@uPqxswTjvHWI z@d3K*zPw-5pCg*@glr=`KfBp*Ke*1xq~WKP{k(slHs&XESev%W{dxTv>#Bk#r)SV9{bc?Y z{d+BYFRE%1#J(MnpO46&&K5)9%$7y8N9BA$QGfdM4X5v4CNTR6%6?vdKC>JR{>3;x zTR3IYh>#+7;D@|l#AnReDX`(@TKeU&=J?5+`oXs8c>EM5oex}T%-Y@d!v$_`0 ze$9BaKf$eR2u<>FVK!am{UU#EX-h$8BaYAdi3_NggwNPq`T21&NlS?tee&vu-_St#_#bzHp3>@18D!3Wk57^yLSq$Z@n%!2z#wEY4e+!`P0?@ z9Hi#vqV=t0$Gc!Uq7=>lcZn;3N5^!S%~JXOiu~EsN1Ki=GD7)ts>+1c_|z7~=cCk) z@S_7Bzb~U*Xpfar{C-opKVRSKHpvnWPQmf1KV>Lwv(SZI94YS?@tJ6(hTx~u(f+SP zaf@inW~`^V7Qv;A50W-*!{}AK(A&opB%PH^t+l%<&(awpvX4v)rItt^~HfGX50t z89raCA06?hgJYEVijUvJOzzR{T1719x$^$__~>xP99Z9ZEn0uQdTkXPsENn#Gp>ii zqE*o}w6gzF#Ak&RpFfiL6U*Nx8|;NiPfyVbQ~CFa_zd2A6r!8s{(Vj4WeCX2rMb=I z{i6PCQ2Q~gwl1Z!ugUA8{(QK(3}(&IVWnLCl8@hieb%Ek8AfdUdgcA|@lj4`Lwb8d zTeSahW@a~7_R|5)F9m5?(6o6tKC>J4gLg6Gx%n7k{&T`@M;fDcLHoO-b_{}AYjOS@ zuwWU@HV9;`5r56U;f}jnlS{)Z^UESWJFU-y4zE6<`t!@>3W!^z!`wpU z_aplEyIZPJqc|g$zEWNn<0Jj}#?)|VTlTM^vd-(z@i%+GuK=7sADLOwDGoe7Mg93A zK?Sq7kLTtGiuk-W#feU~aA7;PDEH^%qvtkuuyyea+Lx=J^Yzgi16I-@O@r9Tjq-jG zpTXyy!MQ80KkIahrEQMl_-wX&DmWeTr&B*`=FdwZkLW`)9G{2Fydh%cTKd6U-Y>@Q zIRgX1T+*Ld{BC`C1N4rIrkma?_~GkES#KjDQo<+JUuDxd5oSi={5i`o6?$Y}qwPN{ z*XQvWACw96qjFLI{;`TdCatZG(+>diM|`J?4^5uaBR zOlfy#oIlT2Sc1n32Q>fLH^7QUwvzInhO&Pb@p&`@ATVPb8XxsD9!+D5C$Xk;<=;ms zk53wA4_R^3x%xe&JU-_d`O|@|r1@->`d7qfr?RooqKP+JKRWq+56w^|uuXF`^QTwx z4A}4MkLKqmJjkQIiwarrZF#@QpY`&6VVNn;pBs7x!@w_FX&Co?MLxfDWYH!VJ~*1o ze~SLy(QY@)?RJ1VR*~;7=9k_tPl6kMI6j|lI1QWQaD4uln+>gEb7_-l^7TdjG&)uU zgY--3jK<3Q7e`BdvI;AepAPih$r#^p(9 z{_|KtGL!|JqA$kF_!9M}`eQmIFT?TK%;FZr@5`ljyXE~NK2MB$0a*t=(&)Mz2YnRI?Rer_5p zUP|+KeN-W6);uTs>l>?Up}!`bUyful_-i=L->BtExbu%PIluHaX%HU#qs9tWao?X% zAM4*t1D`%df`86YrwI;9qAv9{&Eg0WF_~vL~-B0kUz`*wjgKbg4=la2k`6j zzI&a)q1|EB?Zojd%pc|Sz2T+n|D%6hPlEcNU{s2d=6C%3@!XII_;!ibzkm*xAaTqM zd^4N-{e}A1Kk7CNT9}LD`$&Jz&mSv(Jc57SOHk2-`?*m6s(-$P?>6;Vq`-YYLjAk? zq7}xDZOzoaOMlLf&+KhyoK>Jqo?jikcL-+Ys*&+|dw+n`k_DvxjoF46et8B{n6LJLAau=F#uV;Q1+u^oREU%>;)zxd^=Z zOg^8djGus4<#TLm`MHo!mzQ-g#HAj`&*lF9LOu`8lEd5WB>vD->CgFmraLI(u~235 zeAK?p>bU7Pt&avr7<78DfYisCzBBRNQJT-(uXDjBi01Qxg%#?bwPYh(@;@P;zsH)x zn|^fuxaE^4))u?7W5c-pA>{LYq%|C@+)2jgw^|qQ!R#2uwsLX3_&n}gG_2Y|>tkxuRp^qIgpIuZBLDo7 ze!FbQZOkG2kEH{igQ0Q>nkR_sV?+CTc=6&R=}*R8XpMnYa%BB7Zj1^B`qTRORBIUC zJElh7|Fa}t2X1XyK>FwFzs=`sA3o+_@@S4fVSn7t;x;pSMPhKwBG{ z&(oi0!_C(VP$PuIkm8;Lhaqxb;FlNA%nZhllPY`#VNI60!1OH0w8j`}+y?@kd`r zNdM+c=8rpdKH*5mDyCzZ)G~j~udiPgdjJG^lKEw}q<+4vLHj=*UxQ&r+Yk(Nkn+LL zFQ*QO2W7)J(*Id!k_=I{w0;^j+=cy*bIABTe@Qv`-F=Rmc<0mk{l{&Kzrmrd^|+Qd zKg9QcHaw8WG4Zs1-t*{z22+&D`+Js68-+^i)Yzw%e_vSNbiJn!;S1^b9XH=NQkLoi-=EZaaTLSS+*$f* zZoQDtQCDo>U8ybE-}#_*1^+5Y<~QQS`84_B1aRM(^v^Fr18yp*WL|~b=L_}o?`BVE z_VpzF^Qqtb!D9fepW7#g!s+e7y#9_*KfP+tgK-Bsz84-(fu?;)Wc|}?%02jZD+jY% z>KmbcnqR7fMZV9;_+Hoi1D4c&B>7CYQNZpuEjX@SPx_NyYkhHeqB{$?#H|PnyIziZ!FZ$ zi~cTfy26=`@29?Er^A(OZ4CGMLO%EA9EPMhp5*-7q~;Uw&eR_*7EAS!@1Ixq4~K?r zbbPn@a1o-~(fV0emhyB$g z`guY6{qXZo)1zkaSyKO$&Xnc{{P*>u_io1}UoDv29O-&KpTR-akR*xklz(p4`ZyMy zacB2$bL)kCZhWu{+~3)f_0N6fB>Z_dnoYjM{e6XemRY)iezP;i-Qa$IVg0lJNF%m8 zSjC>n-VlxNDtX?Z>n5quc60GVn18lCdJ4XE^2dO7-1m>j=W}*t1gL59^;76y)_hKc z`>$fj_^zOI8wPGo!s64?f1h6;ZMt6w>YHgk&!@eD)e=6b_@1lU3{xh3B>Oudx*c%a zVmTHV%l&MbrH7O+e*I&qkO>oeCz1V|*9OJ#eMJsF z+$UYn_lID{8&GXe$8Ynrzwr9m2eN;2y`UpzkCh|)-wTZUW5FYuzwy_`JL3v4e`HGLmoCk_@Ik%>EA`~o3-ime zWm_fhAFjt;E$?#)`O{n;fN`Gg>|+P6{t)u#`)nWRC)<+#Wzv`w%!!I-a&N`?+iUCr z-Othd?J#M^f0Fwb`q^=xFO1*c+WUgB0j-Y-pU%L>%YN8}H=o1TN5`)*kfa@q-6lx+ z;nzQle_n;(XJ~!QI(!GrrzhdvJJR)heVp$11O}_;puq;|&-r{lihl=~`izXu<5ZZx0spWnhaQ=-|Hz2bbvd^`m0Pdj7CS?>QYjNkHmj{(Z?>l6HlKaQ9$@=Dv(+9Yf z{|xsRb9@T($6S!bi#{}eFYa_kof285XvzKkgz?$0NEK(F=|bMWq>(=n3qyvmE-in5 zVg0=`bSZRqnoq`O)%8noM(gS1{6*klD=;`}irz1|{7G2fT(;YXhNmo8Kui87)W=iB zw$K!@j?~BQzNfH$3C$mZGnkCCCH>2cYiXGIH;TP!x!+P4pA**|2G~aH<17n5aPH%Y z-hSNwPsrb9n-GZGPV3)or+8SOP4o9!GZ}vDk42wZ93R5@pSd-8(DvhXQvX(NcmZ=i zW}}I(bUk1Heye^0ow#Rsq?Y@+kU#ktIdnCr`O`L6Mx{Hly@s{@Ko6}l0TK_>i~7>_^r;tBik6p0TXC2vJ zd@}4bu3Y5KiVei|Z^~g8m{PNYtY6~8Z(~4R6xqM2%=Lm-y3S<(=GO^XwqA07zU~3> z`emP^Kb$>xi07XR``?-dVKDuGA3js%zJFo;@^kS8_;NXj?CqXHMGde$`58Xc;Pg$%=YyZE@zZdc&yt9)xZXvU zyq_+2x*E3GOvh&xm#OGuK-VwJQkO&5fca#6e%0C>a}}oZ{2yU_zB+s(Jbh}4!y~x( zCe+6j2~OB&yalu8)j$0BoWFbzd< z?CO|>eoWH;9>MJop+1_RknL}eyjn|*y*EgH9?ty{rb<+PimRSLnhqKB0 zW<%9in2B`!j@4t?`gG?0jQf6t^|kM%O>pz=GP1t8E9srg>1x5Q-IcEA^Lb#X z11w8hOV-y(TY~W8Qg;@VCC=wCbccHmw0{0-xPt|1(QN2M?(>Cwe))G4(oCE&^)t7> zg!$vPwryCLt3*F7#reGW@+7ESKScUJ26>TCw$Tqmwn+Ko*Ee=~i7vcG><$SV` z&k?cRF?p3Nd44Bv+%Qb~+?n+XeI6qXrF&95uM>F@9&lmEk6YmR47dvCoFs^?fVXAR8&6ZKe}*mAy7m|v!hDuRmn zbbhJrUIRT=((!wH(@!Y>`xJv3x!+G1zuT!Opu>eavj1H*vL_ChCQIJ`64z@4-uT{` z^dB4hGkjG(nDieTKCb}>1)4wS)~m5y&$g{4{qZ-Uq1a=PJA3wsTQ97yN3T5u*ChH#@uwA=hY%OVdew9BMaZ93 z{V_QI$BFdEBVWifpLLZ?^_sXoE*p0SwB70W{W3oWPGuY?=QHYJu0pt05CZRfB0qlb zevk<}ubm^~cY<{>EFDkhm-_j&U@$lvOCvb`g!*`Y_-}}EeoD@lpS5X^$Jf`9{`kkT zUbsZUCv`sDymTa9D(y_x-{(5(U{Mmyr#f2)nrZXM_`Sp03Vn*EF`XV9AHw*Z`Nmvux7eqc&@$gE)K7({ zia2j9&F4nzKA72$=5x522IhFt@q3M;E-D8OCg(H0#alyt-aN8C@4k5*W?!1dYE`9t z@%3}`nO&e=vy7~NF3j@4Zs(Ru@;m8zKA#svJCX5wd~tiWB&U*H3rrU6FCOh344p^O@jX>9 z9&W`S=k*tb_0O(pH(<-(vt)d~eK!Z9Ptbg(?|CM<|Lq!CpD#K39@clyM!Pm#{1EEr za5)*=t@)Ik&*(j|Bc7OAN7g^e*?rMdmgciuZVdMG?o7V#aj{}HzC1FRykFxo+XT1# zX+DjTtkG%5G#1g)UlHo3o6;UgwOfYYR&)8CFuzPYbqGH$Th0plaC`{k`>!c(kbTOE zoWE@A6opT|y0I~%#rYf*;tiJ`Z71XVvriAO<<04*@O}Em=O>cimqX@oRmL){WI?S2XJ|E2R}7P^_TB&I_bB<{^d`|{?4tKPFVE$JvpE5WYHgg zl(ZuK%_p5SQ7@n~@B9uT|Na8C5`FAwGMMz&M;zHAdH2ufd_AXP3W)NG+hJ>-{a(bP)hGx@crRg%;4RR#?LQL zM&yI`Fq*&0yQR>0nAXQl_4OdL?+)o--nb%*8`{$KkIE}092oSTtbYt&48Z2BR%Cwp z(rp|*Hlg#&m+^D3Yz)m`y{8R~cAkeB>p6W8_80YZw%{anI)1m!+Yj$=E+zYm0rS1k zL}fW!+v1N4^)Y;l2h4nLMf#WfhR0$-4|mqc?xO?|*rjplFD#78)@Ad)$>-0vlf z-#2su;o}r1(qA7tCIX(+c#!_&k@!T2ns=P%p9|x2xmp@jT{}zWk48=RB=?`6!}}gm z{o?13x8f?G*Q09~*m6IP&_C~L+yFR*&L3YYw#I)Co{;tTV}mX@dFFevzg@Up74M&> z^{>0h1hgAV^EYAtT#R`(i0No@`Yr4)PVw0RPb6=&y&59UU+4APaFpyc<~mAT|L#w9 zf^O+c$@<11+#7GnFK4anrR(|mV`|PJI8tbZ9-7k6m*ov`dU?cQY_%KPk|WNaONcM* zDY7B^i*Zkj(P(cZd46`?k<;)~#)&-N9V+qGc8;uKew|Z9^T!;ANH`Ygf&Mz;@mag* zGE9}|W6UEdUwnTuqc$CO9;5jz$aw&@Ut-Am=F7q=P`12=S9ty-KR)lV`3gCIvdI2p z>F_qV-0=z7|GrqPj3d{*C+B-R{v3o)yjqd-lZ%SAu-8u|a{l~W@O*6ZX%Lw|_O!Nx zUz6schNqMd9v(8QZ*NDV_fyIEtRLVE>m!$v`Q!4>N3gumoaA#yt|#>GWQB<*rTHhH z&%Khj8_xW2WB=d`9lf0GqLANq3Y6?4)cBq{%{QwTKb1V{ha#jJEWIpk@dIh?6zpwiOwIhda0oA-*`>SONnh5q^ew63hLb`?tw6z8*lbqvIXdSF?eIGeLnM~)Gj{_fp>E#$QzQ><`1x`BGFl4ioAHIG%-)aQk<5^_?@qCCp zhEAg6yJcWEEE)fvoIh8}Q^RPW`E0E+8B0=VKJ$VXV%uSZm}blUIEeiFuXABNZx;7%ezA+xxgMCt}X7l=|isqLx zQ{qAPkOw~QDb-hg|8c~sWLW*}7_Lp0{{8uUt{svK!+V@XUEcS@=kv4OQ!rRT>*L3r zZ((xiRnq^7QfY>+Dp|bwN+;y|KP8z8cy;Mx@_wslO+7GM?;TlxhrS<%#r;~5=O1o| zO5Vo_SK|3U!u~gync%f&s-!-)^Em(-OK3iQ!}em8{ZuA*p8I}o-S;va)3 zR@_EfKk@IkDk=+u_`CyT{ZrSf7u)Gk%}#z6=d;%1Jj@>DLHd(w-*3Y2OUKCmxZnFc zm{)a%)KA6C=P-V24BAyo`R3=BpWnTQvFERn`Z;viUl?^Qlf2(${v<`z+Vq$_pEGuP zFI-dcmYmPHv||KXHOr8E8jqZTv6f0?|1nW_Dc-xl=Tn$pUZ3p*A@zo2eSXSqA08Pz zmDTK$^2PTjM}7BzX$nixqK4BCp?`j3nLp0%V$LSE^tXlaJ2S=?D$cAyLnCQ^%ddZu zzg)qp6>jW_o;aT=E`d;GZG)OE=R1UaIxeopno&`#TTgL5uWXBe#*71`ermnx&D^HG zWcKpuqWU?f{Y7Z4Nb|WS_7-eDdkhDMO8MgJ=Q#g-I2eD1^p6G_y?_VpY5jb6=mV_L zzDmvyC9RjiujQF!eXg~m13uAxOxEXV!M(9V)?2ba-t>GV_J1Nnp5L(@jOgX4MBbmC zpJR%q@`K3tQ&7!cW>u#_&y-_i zep+<)9&9^G>ucJBGPpM+2CG}ga?rc~h9Hvy?x+zTP)K4C_`cA>)5$tCKkBsu}b9C|%Fz_t8K8!tZ<)<>t^Ytc+TicMZG&hIgaKlEzJ0n%U64eQGuT34|) zo5kb*tA&@~SkXbUem|5w+=7}>wPH}(NU%sE5$kILRvz;^W* z?APM|I3YhjI1u$2&L&?W&u0uwlEs8wwEn)AQ9{jE#pL;n8N2%7skLuO|H-dmG+LaZ z^MiwPbZ}T(C6?Tkt1pH5>xMK7oRz1_Dl?@&=hs(j-nhcq4ThxuB;)IhW}#Ea`YK9t zzMUk z>ftj3b;bEz)06>|Opak)op}Dxc|;-XoqvX`zixR}L1L*`+zl=Wud+e8BypB}A`TT}D1!C1?GiLirx}LAU zT~hcefqv>4o7lw@(x2H?%YhX3U}UhuzPM z;H*5I|Mt;*3F|jRlk>}azI=nQ-B-x`S4r|dN>*oDe>Jyv!NGR4{h>o`QF`c;e#4iw)V2P{!TCog|Rob^73CHzfa2R z(Dq3r8~Rb4-~Dsq!L@Whng8Z&P-SuXRV+POJpYZ;y$u!_Q#+0iVSbR~cM8_1tS0;W>!MOIr_hy^6pHhC z^nMt0y|k6o*N#RXF?ekx3vlE2I0R^0b1^k3WT^@StDOvv*`dIy8B_^~OA1?hTz{C|8g z5HiA7k@eT=<}}nj=}PveTvkND(>q)7Ou2acUpP?m_M&#A)@H6apWoz@AwuaO>A!|2k7aHN4Qylax|aNx?;o_2%zxG=`I7mo(}-uV z&EYgze`QU73lSZoNq<(W|8KB-ewp+Sa!uOdMB5C~|2iMT_j)?FIE`Sn*(sVA@3)*8`!2t+Ih$Sb#|PvJI~-5Hn{{cyiQ}EENOng?~kdD9>-ewH?Y%zz2N`W z%U}=Q`c)s_LGhg^GQaRyIgVvNYhYC|=UdkI9rsWb!M>bf!$Z}I%2tRM<5eci&#KZO49oi^Xl@=_#Qm?vG&@2|}ooCx1;I*{)h zEjXpd-ep!W+x6o6L&5A8Y?nDm_J1Fkjb}Z3Hn9AQ;`^gy;XMe8@Fnw;-g@KNvp=7i zjaPTk{bAm&6mo1%JHqR9EhSv$rv(}@kN#94fQ6l?y2 z5|7Jd{ixwIp1m|^U`xH*;{WYW#9qApwZ)=6?y0)X>rV^)>8?fNS^TvI_WF_bf9qwi zH*bC9-X6H!l#W0DhE8C6hks!&cdY+!{cY^STYvw$I^K_ZP5Rq+mQO~@1OJe^f4@9u zK5EJF>r>(RhV36V;hQaVd}_1V8>|=3LB)Gge}wnz$vA>1+Sy9-|EJRU#;;GaxB7!_ z?P4(0mh5-FK>g)dol&h)&F5pu5>;Bevlnow3zq#2DWQYWXtFG?Vt?NHgHN|$643iQa_$j$?PEatPmfL>Mm77% z%z31AfAaTtyA=VD+J7-QA8nBqj_*5~vNgM;>-qK5cKHy9xxJFiKiQ~koS{hjPd)O^ zfv(FIp8qfOpPml=iOs7cS;lMe{hc@G3S4Fmq<`8bawu!CC}+v0;`{rCK|0LX<4)F3 z)9R-%)xaO@mW7RI{WQq+A^3Nr>!-+0m7syA(SDGWAO8M*dU_&rf-mI$&HnQV%#5SR z`YPkOHj|v*W|z~%_ix3UR(R9kGU*>|d8o~{Yc;U3sp9)r|3L>lA*ms#`$g|d*4Inc zw=WalzyIF#!ivNq@_edNls0So_cQDHgWJDGj2}P01P#Z=DX&TYtew9$%XssdjejP- ze`g<@hW&p0Me6;A)Z5x@%Af{zWs&&)UEFyQ;<1jr`5oc@_5PyGR;_7Zf%4+}_xB_l z^qHf|uJF#k@asqaui7j{QlFUoc=F%=cftX@{qNi7C~WzpPv+0s0bV#xYcgZqrTde= zzdgsDgonwCF?)?Pe)9Vx=D#BFTgfu!+~S`J>B?N#@U);W;?}jSJ~78saK>8yu8i%o4P|oHZ5Z~X~@)_WHz@6-m zyzO5EO7%XZ|8dc@3gRCGlK$O%(5R8z8Dj6nQ?P)%`@)cE!4x z)BDMC@rUv2!^UJ;tgX02`X|GmcEmCIx5@gj>2GgrG%X_MgQrK8wLcAhnf`SxgFhMm2+-yiw$^VFB=I5v^qfB!a4VqNAmFt6j{`|s>` zW4sgGk>}3{_a7dc#1b4D*fKrw{daNL4lJLb%KDs@=C}O)S8#F?8|Bu(Cg?sD-GARa zePD!~0eQc|Y%gy-QZ$LopEpfB1?xxB`E%OzD2zV7jEt{NL1EB_(ed@TX&zdZx{&iB z$*%EW^?NfJUsZIP@!6C}_Gha2{+oGP(w~{`K=#*Nnntj(HRbH2uXz1BA}A9Km(u&M zx9)V-XTx_kdg-?R_J1hy{mHnI#n7+Whpb=Kw!H+^dx3cOi+Fw7)Z;SiDM#;5yK7&e z|C>nO{uKJ}dwXAIMs3&4tWpu*pZ9Lbq1xF?^nA&$P8g>|?@wL*zSw7E5jh`qX5A?C zd{s;OH(R^`+q?cn>U|B*91}e3)sgkF<@T?P;C%e4Z9CDCsWOc};`<{?`xyMSG9c^6 zy(veq^u{F8pSL<12tDK%zG~RYx#`;~5#xH(;nKeEf26R|~rGL2ow(x%L z;MV!*oa@5UJ4*Rg=EcvY@#n#84IO{9x88uqD;>!G<)OM!?7`LwX6GT^zg*Dv4!r8> zPR>91J)XfrXMSgcj&gj<2>AZ=<1si^`k>ZE?)wq;k7oRJL+0a+ zqZsKkiA5+%`QztL`_fOtjd#Z6e2LN37~DB*84EikUC-zDcU}bCU%G-k|J2Gsa{tm* z7dC#BIKRop7h%YS&18QmbdC(`Vi3u;zm~4&`;YSJ$>7|d=KIQy(X1}Ef@yRUpP&AA zJ{u1Ab|?Ku^-joM)qi8Bw~6zer}Y$;`}mOl{N3_ekl97+_n5tn&^<7ctbdMVwZVRR zbbbUQx?uEWn%{Gh`KR&!3Q2##^3rHDRjeiFOa2+o#L}mK$oj(KkSVGKb!5|rNd0lX zf1aqa8!yxkWD69e{P6RW^@IGt<*+{4AMIA-gNL_HBI|prlV?Cf&6u1o@fjD3sw0=N zq!-f9=ksg2JPP`)T|xFo_Ll~&9?M3Js${jY+y!P_ zFE4#@Z%;aZ2+2GP4*847{{F4Kak%l_Qj*`wSOc+ z(3?$U{_Hn26`GVB$orkzXpLju9+m7(rZ}H{>hdJ-uejm9@!b4?&|eO^QUV^ceelvm zF8&GggO4ZQfzi-F(jV@(`#0q4@bd#vXZ)jOMTW*>Y6Cjx4CVIDeb}I3S)K$oy2r`Rlhm0MfhC`q}^U zF)VpMk&ORK+62R(bBjp*>=O}>UC%CMd-9~8&)3fZtzA!-v_#|>X+jD znd)5zuLzpIBdK!i__j!v+L`k|g!;MSXc~Cr?j`x$6*8W6-Y4NxHsings|xw=Yc4R# zhszOeWc=TtT?!gXe0>!18Dv!lvlIeJ|5K@<85WjCko}3e+IFa<}jfbe&ajzdRk^ zpE?Y}le1`j9MO9`DrCJP&*u-nGaG-&{y}Pf-)^D#3`{-& z=^Z8h9&x|P?a#;Y<%Nl4ef8@~2zV(Nlm6cHb{Ehta4Fl~h4asa{$6eOSeWK+NzRYT z^>~EW>|L1SdvQK@y|@C)5;tM%-<*C4{d@aqtyySF1dE?49^Z>{(;-`LFL{6Cs{<2Q zadrh8V<)bkOFas}*Vv7$zZ74W!SSz0N&W1*>I0;2Iz`SmJ^Ly-KbjXo`U9`>6|l$p zM6&+ZINl8#9;T7?lU?9ov~7Aw&Ns^GR{K)Ceqvtt!F`(>4xZ2L4`F=ovatfX#veru-u<5Z z^QU+0>LFm=DbjyFvqJ`l1kil0t#6OTb7}qTe6~CK+NY885!3Gu!5(oB$@$Skj#}8^ za}7Cv7oBZ@gAX;MMa%o>!uOFnXs*V`T{|+z^WuDNEpe2!L)hYAY|4C%{#ze0a1 z_1U$mLs?z%Tp{6Z6s2j<~r-;Y*-*Q=?+ix#6o#K9fA)oDCv{{jV zIkS%u=ksoxhp=3q=F_IQ5*n?JlJ}QMZr6t(y;J1;oRMlPyx1=So6MyCEPwu<{ZK^t zp>+PKQ`Q69>`5c%2QFl&q4T(hWPjuPd2L+fQ$yB23kMnE?a|F-{j=-)8oVywk^O6V z|3K(JS>ATWk#aPjN&`=W+EhKV{`o%m1g>dK>*qkj2-rDl5$Qjv6eePG$r4gO`;I;j z$+^o({XB5?Df&qGr1DRh$|QK6vXS(k{#=k}JxU^2%?fcoolo3>b?^3It83zXj#r$- z9FLc?j3#kDzb`BVrSGm}{oeIVH9XcmO7`zMDSd%;J!n3y7RzFLOvLC?q4>SyL$d#UMtKr`F{vT@+as6G#R~_2BlZ4kdd^y$*3f}fD@y%O zzQ3e;&jq#W2e7+G#pC;I?=x_IB(0x`8&2Z&I&C&sTe_a_j~==k3C+D|{d_v+GUlFI z!V(6H>!3@#-G#R&hOYT6Z z=00C|zg~UvJS_R~i##9l(`!BYWYB!J%5}xdi33=SiZd^g;E7Se-elm4fy_bEJ| zE}6kFl&9+aR*tTS03X%^pv zms2;A_0eMa_N?vG2)4AnIGGCHWXc^S{d>a;-{D{6NishzS8a`#y~D}*-?n{}uzGU>S>K!L z^ufD{G{5?1hNH3j15#g;#!SV3YBl8iLg|79Xp!{`S9wYK=Fj)7G1`DX!#gn5q2l^# zmF$MP`)Phlp9Vql#o1(jI`UW`KJ=jZ&FU8e^$rWk`o8MTRlK}>39CII&Tqko1UQ;% zj`=R)`g;6mDP~-BX3un`^$*{__dkCNZUk&Z*LaRUVST^JPLTynk7S?Zxc;b6U;ll| zgRbSf$^5i$##E-hN5U_WpVq`YfwoUw@ec3(c>euoE8opvs9wc>Ze1kGuUW=xu**L} z)>rp;HA0-*Niu&`GH!!43E{l{s!)G#bnA>WC(``pSoTE?_f#@}-IO^3$IYhsojY?H zE{J|f`lsJZjW8zs7hb!;@#}7YTtkkEX+cjU!x#*bel`_`$j7S2B*))H=U&U zJHLOr^zLc=a#+G|sJQ-GjXMY9RcZY_Gw?bN9JGYV9TMj^Pw5gEuQ12fR^t2y%a^0~ zVP|GLPn_SI!Kv`OdIOmsL5dcDu2Xo%Ivv*JH+8sPjES=C?&TKjBxulcay;I<+m{-B0tozHb*itdv0d z|2G!*!``D)N&o6Xr%~8$+ym0Tx@$Zg7puP{>#v(T7vVpjUp)URRKV|sE1U7a_6|&E zlQ_SFb{@ow9R{#f8>Rg5^M}QqLZM+it-l@o&){h#ZI*@HdKA1b-+gB+?D=Ix>Tl4Z zB#f;zA^Ejlc^NXbX#IV$xdLCBIkU+##QFXHAq`ds()?Do@5G|6MzVgJIR1qCTX4Mq z^mS-{^=!s4$s4gOuqm!ZKl%Ru*oDu*%G?$2S&Qelifb5~;$O)!SBvu--RC`cA3Z|) zuQy9(vQk#fFz-#O*!jGa&%dCJ7M&kgnB=n|AFRpw%MCr`aoY57-u!@2zqRz0vA=Qx zd4FKnef_ahXIj61%W9y(jr-*M*21SVFnicbJb9GUXJP)V|IHX}SN!7nV?zE91aC#7 zJsns?zBvDLtvs;n`~GD9T%sHX!^(8Y{=%jBvsm##i-oP^_!pk9PM;YE&PGP${ecUD zZ{Yr$CKCTnT)$g&x(ZQt=A=IsSXYVFlWF}{`j!sw{#ld$!;=S{*pkJOOlgof{}u1< z!RB;(vj4TvVJvGOE#bdJoc}4-CE)bih4de^jApX9&lRkH{=)zEk8pl*RAL?It)}_6 zSDVFR+g3}?|GX9DU-wWmWHp{3^OMKz?lJEk8%X{;zmUg?Rbga*ZPoCu_$BQkc|M@v z!~levTV((D)BMq>9dV!ZhkuMi?DDUg?5~*|k<2F={=$a~IR96ezg#o0L8av#SWT@s z|F#;Ex8+Xvm&9->zkL1Q8W0W!HM->d*Yxrr9GIfTs_mrf`Ss)b^mr(nVnog_wtkX~ zfd(dI{@wrDH5g%UPS%fm-KueMJ39Y%yPE;#JvX4Pv3UMny|gpi9WS|GK#A**3H85k zyN4jxem4$K;PN-2KfELjS%F?DQ}E{Yk8pm*@6HSO8{tBpkGX$Thh5!S!Ja#D{8tI) z8>d))1fxMm$ojEnrY=icS;cl&*NXBVvE?sJ%B1-}mUW*+b)oscCZ~Yyio!_!R~@c` zC#)`#`A@pvKvY_Pi=3~|OCN)K-0zd~4>cPZe%o11zMt{cZz+DU`-KH9??0m;|9OWy z&|j|uTiaL4C*R-uG|m%cHufj`BhTU@;O0SHvVT`!6O4bi()yqD>O9!JSU{ftj2@LD zc^}AxvD4!Ezc=MN+$%RD_5X)n4UYNi#7qy1=RenLGGW^uYtld2v8xL!lFX0UE)wT| zzjYyKow3JmE%Tp3{=I)mj?UD*klaxq&cBaJIcU|okoo(bd$ZVxt`$ssxj6qf7Jq`y zeUFgyz0Xe1X4iUFvBD;C{_|vI(8l%zIbWvl^^mpFqWPa*rGT>!gz@Ijg!#{lrQJ|_ z@kNZCDa}v#?;o^%u8Mk#Zjtrt$M<6~QS(0OA1XhXiE}1allALRIa7R~{0kHEIQl=H&dZrvEEcD0E^29K`vbdQ9thCA+QjN>u*~(q+(e(g_T7;Nq9?{nv5XlK!@N7&)KO zcYb%2AAOO`??Y}5LhU~(WPO{|ejM(QrS(1Yw+^2FT1E0bX@wc;K5ZiP-DaO1W;H9a zsEJbk`1I4&nUJd-2+`gUVKG>~&O}Z!@p1 zEZ-}V*;k13UE)&=jUM)>w}<0HsPFwkX0fKk7i`QEalXeERzlB%G~csi^jN!vFlKVM}ywToOoNt9L2F&_YC3`;ewJ6`6BU<6zZnVDF6)EDgg<+C6khp(esNa4A zd*J4R3uJ#%PugE-Wj(yCUa8I1Le%ms8 zEcl?v)V50bq2}0So0L!f{r8&_-r(Z{bpEouLoSTEyPotPL!POy zdx4Q`@-lAzQkcJ=2!9M|(Ywg}<;-7Q_ID-C_g_{GgQmKW{h!>8`s|Q=IeXfH<9nds ze({H2zrqYVZ_>Z9T0e)$PN-zV?uzFx2LAthel>v1U&cS_fX}AnVh1 zebw-IbP8FY`dd!GoMrb&e^T@9Y?KYF!lpuQe+m7WIVKjkVFaz;C*SVI_VJ3WmREoB z`Hs2hjVm|zBj@86&prq04ztMoT%ASWhoA|heh0R>49T4qkpAQ!>)ZGM7c=|s;`xbI zmsEJy-W&tZi}P(__YQ;BIai8OC48H3`Y)_c*E+p~l*i8G{AcxJ17??6#>-EHd|z?<4u90V$^Ou>WJ9*P zpn?sYD9-mtcR37;q4}Ov&=Ggu4<-9YPv`f-GDBLwy{D<;NaGYT|6ZM;g>6UNBkRxb zR{D6qv68Gmdw;b=new0b=C!zfKPcLZD~>3#YzJ}u?)~@(jVp9p?)jtJ%il4b|l|9f%>fa zbqO2uT|7V8@Vy3l-E=13Z#>$^kU5?%V=_kK`d#kd2o-a^$^83=-aOXlO9lJS5{*-S;&c_xKNQxNgKYNUcY8_x9Vz9Huiw)TNY010qV;=;PaJGlrupu& zH429;qWNyPe-$d)EdJYKaF{riOxmFtf3b-KPt>m=HE*P(>ybL(@wgc&$nmr z2UMKw#4;46^LhOKzIRpu{P0_kS#r|#{Q7eGhMsI@Vk9f@7w20&;yEZTvm^Wa6DQ1J zKk7@EiKV!HC!DH<{6NVJC2@cGZI`*sW?dOe+spAS^cQ0lo1pTa7wNB@UO1nvGN~Z_ z702mqkSz)z=T|m*Dq-E?P|`otTH6OTJ-i>*0fQ-}Gg_b)`S&*O&jY zbLLbES%+J%&y3b^DWmt19F1QFm|Z) z^Z9&lo=}g~nodl|NSyDs`|rWcoOPssqFLONrO8IJ+5++XWbecmu*BSs%)d`b@`FEJ zUNDoE`c#;otm*g$&K__k&rf|wn#cZ*DPtr2#QAQt{sj|qyvX}6>g^Y>Ld6QwKX)6@ z7QfC2AmRu_=@iQ{=gRPRUU zCrvxnppC^(yt_i2Z`mS8R0Tzr`&P;?U%w-^`r@;KzT|v>VfuOSJE}wGCw(@?ppWE^ z$m)FQzt7K4!cHbZV)J|~h~)TmLVkXdG$I?7G>lomU-A6pphqTzx|-qmwcL8)`GLDZ zpK#@SM^>aM&iCtO4?z3pI#Ry}D)wfR+eflJlg0IW!k$vNcYi0DpG?Mi%uV(M>o|(r zA40xa;#;_2;Y`+-&)5R?Y(N?N@r&bI*dO&Q{|%|Ty~zGhA6a>{R-pO4HnIzvr-$(R zn?iqN&B%V3ZgrmYN3NTXKy5>sU%B~HFs&EOufNtjT+^1;=NnB{n66Cg^Sl@*v~6rp z>a&B|FZ*&-E>{PG{H6Tx^|{&S9PWr7&obVN^V{)T61=@TkMu`o@5sT9 zZx@mJydW$KY-DJCKIGMa&A%Plp9pb&G58@E9bSi~uci4pKmYLh(wlkSieL(T#Q81! zPzFYJG{2Xh&u5QXzhEK0;`}BRy@NMDoyhvp)z66iEG}irt;FYBn%w@t;@LF6a{2No zbHks^FWS#m#yJTgWPXu2xWA;fK2P>1e+7?3?Qu8B_t#Q(PQ?M4`DA~lm-c-8y`q9V zf6(4(9opwMVygq<`ipy=adI}z@4jiranIboq`$W|A_4jY>Y(CvaenXJip4=L;~DEF z)la_u*8I8w_J;Gw`R*HKx!5!*6DJil=6pAExnO-cRz`1K2Ja&}~1?&AE)B^H9_ zo3&(p7<0Q1ySF%k{VwA86V``udn(|Y_D=Hrf!aVLcH>eB>*&p`7wYfqm^xVT#fi)> z{392!@cCuzm637Fd>8+ItyPVG!R+T@a=vg*PCGOX@+b3$3C3Nq+&6^ur;Rrcz}Nxj z$@kSCJ|2a>?Qi0z2I=?De?Qpg+%(kLP4f$q-gLB81(_euFto;1S&bO~T%6zfxh{DA zIL+@v6+g`R(}z4CYwwZ>tc?z4ER_EKeEr?^G7h^g8P5i2iSs)%;UX!q3^-Rh7Z>;|}{2;mEi_%~H+eMQ5A=Z-qbdR%rnal5RrWeNXC*(If zxDwVJu_ezZ*vl+p6Prtz(p*lzh5Tyde1Ne>oXGhS*d>EQ>kpIub3sKQ>$+sX%+SH5 z|J`4{lJW2N*Se;FZae+y`{5?4;7}y5cf4 zdFi00h1CD%^ZW91JdRf%&sNP5=XdbHTQK0@JlsEv<6oHnW?1H<+3ZE^Zp-~ZLjPi5 zXfEtGp!IiQ_aCVE_W&!tDXzay<%^-sH!G6g*?#@l&Z2M@mMqS1hDtRsV_VX{I5OOr zC5Dx-?3Vml$Zz+J^N8&>qE^)-B~D!$ts zPv*B_KSyJ8}-b--Ml7H=<9=`{qJEmA<-S*BR~E z&{8h{bOL^Twzb(Gb>jPw{&DYZSK!5P9n5NZ-xHC~=bTsP(LQG!s~#ZE=a{dzK&f~x zcD*CbFZuOZ;idxYk-d=g*Q&1PLDZdPr2p{aQ6t)y9AGJp;(X5A{}|+wt;qSkPY?Pt z;}_w~P=nJ)p}xA_dv_?ne>wdFO2a>Tjp{wCsEpblhf=`D<+B1$0l4 zydh&E&S&1EROr5ZE?IwdetZu@9xh~h2gKw5V)cBukiQHYT{-;~`Um!Nn=l~u0K3~y zdcKhF|Awu40>S;Q$oV>-qyenMm2eiN%kd@T^FwV7WMu9j{e#zWOW3FWFPK(9R!jcL zKVQ&oe*=_HrSsRgzp}Xd_+hetQS(6&4gCGc`Jld!yW%mXgr?NM;XEV=hOY} z_@+#Or=P<62ev&pfeyxf$oc<=m#)IN5Jvi2spAvyx7#@8=qS!-^L@$v_^EU8q!q`P zFuuDRJivb;3t4r%IG=kZ=TA~&mZ5V7w_eC+WZo}4tA2o){1eyDGp(ONcHd-xtvFazt;xOD%lz&lkRYFNc2Chw;xfX@10?U;8++ zBWlF^k@v5$<{oIgKbZ7a>qZSh#l$!=em_zehk8CYNPWcQndrvuVkL0DpRj-6eP9U= zXSU$~zO=NqbWw_(asn!o9b4`N`j0`s^p<&z)3qUNb~1>;pL;6e6Uk9;-8R2Ywy14#rG<*vu&TS{-b7S3in9|dctY7Y|ZG$#XJ<0lI zVPPj6H^7hdhlV}ug?>MRNPp-as^gKVab)~$zhnZk{x@(_g>?V&4HFaE#yES%r6Y1I}#J9v`yOWHvtJoMl=>AydJ z(HrNy4kGo@+;S+Y4UHrH%R_s#aCBo5nIDcEH5;ppXg-I&HNy?TWu!ia+wa8GsPCjc z?z?;l9h=*c{iEK8Ph(fR-mLDlly822zrW;u@P8_dtY3z1x`O9U(tIB5bqDO!4N3np z!lW2=!;DzTH*r2Et}2Ak9!p98{lhsKw%2q&lfN#`r+;WEq{^@6z0WA*GlQwIB%N@! z<|tQx2~#hguk6iEJ`?9NXsDbO4RQTc>8j4gdrrJtlf=j-P!>sx?wjP%dLy{_T3Nt$dxrS$Xp z@x5kjE;O1M;=fni_baTgt3Euzhk8cr(`<1*Wb9DQmNvj~TzZ0xD0)MesGXLCs zW)gmwO!H}GXn_Ai*O^Dv^nQQ5G?|h#Nv2fhDGEuQ_tT(BqD)C;Y(PYmln+TINs?wM zLI}y2u|Xt+WXe33G4mMx?r*K{?VhvN*?-@4t9#F@_ul)x_p_f{=CppEdg=w8Pxqn! zRy_Yat`mwgTHl~$B;$k6=gr1-u$)8d=T84DyixDOn5Ojot2jQNi|bBvfeL_ekcQPBX>%9H?}Yd!R`3d83^I+nq@B z8Q}1UyLHJMo`&Llo*U4MMds&_^C4G#8o1+Hf#m$&)2P2(=a?0wKK>lu3O|moCF}3` zEi@q4n&z*gRadwcZz1{nIJzHN8}1?V%V(u#c>eAfsgIu8j)-1%0c|GAo-coXbpQ0} zC^&eZ)W;52m!oyjY`-r(Gu74wv!m)qPSKQwqd;Wa=dvs_$Oh2oT_05#Zt+?1ymp7jwWM$mfcER|NKr};*94zlJPn8a4pm%Gq|x!#PzSE^KI^|!$h)wSd*^E zvNUM^R9&BPU30y$__#QKPgMG_Eab3RL&f9sz`>unjO7c-^WX2!nlr1Lg=}H^W@&xH z`1OtT>n5&+S2#Hzci~=Z1kPJa=8xrtni#Psk(|Fc^`aZ925cegn;!rA!y;@q8K18n zFh_s8V`P83y}}su&pMCezs33dQ!^7at!aJid42`LrqFy|c85p4KF5w)Ga%6uyaq9`xH4S3fM`ZsWe0|)%`7)Pu(1GmFJlDC8xkFu8U4l5Dqt)+n zh7%@|{&>uEB{n1{j6Izwu8%<{o^jgNG@mzy_GJ?da+rItIG?Qwzi{OmG@pr8a!_bX z>tl;!ZSY_)&EK&iEhI)IlJ}2%($z-`{VimF#tl}P2Ha0nA>*^j zsT_2x>PY&NM|+lW1F|@tKPd-(eD>UP62X@SvB#CN-_PgITDgi_bie^G%cY-BSiiXI zK0y1Dv1ER@*0Yw|tT&PLCkF>8vu-cK*f&M#`M6aazkbn;ea;z2d*LDz*T)9|{n#;+ z9Olp{&Y$zuuiTl)1>}51%y3KgA-$0GQW39TB2LO9R5P6PFF!`NMOCY{mpK@A`yLK&6X(-z z&?@9OeIe`XJ5M)YEmL7isj~W+UtbT2-Uib(9a$vretCZV(jmT#YqQOg?B8^+IfaC+ zgP8YMaXvp5RB>{T?0NpVkk8?ZA0j$tEUSnX*T>)?_c-P?fvm5Kx~njC-!RtggSbB4 z9{7^03GpK9>+44J=B!)xk}*wtee*YD>j9Z z^-aaUw&=Y&hMfOhXr_a0uQ!tQwb{iUxEh;D);9)?gJ86u<}>WKB|a^s`F#D?1>HNH zC(nN>8T-O^!9D0EO8FG_x1SkCAbs)|3_302gRh@GE+n8uH#)z3nz zKKoUaa|e7lOjeZTw|xD)c!-rSM<|*xmPMQq=Tolw zKKD0p0;!*2S5(;5@5@=;BXK@2u6@N-jr1b(%d7YMv!`y^?Db@E{WKpgIbR$cK=!wF zV!=j_DP)1}Qa*+LkKWf7*!^@lS^xMwRK)||7_z@}!KfqNUfxLh=W^u+F!swN<9l~o zV=OE0$2rk$yg5d^f#&2951${aicj zI;Xe5p3EP=ky6c7OZcSnPZgu5h^=yF#n;67bS!?z?V9aI#`k!uR_vPda_0V5 zoX?L-UUSnwdy@T~&#wovjqZ^P%T-(d16+=gE~uc>6ws)X$o_AsD8RN7hGg#!6;mUmk&a zGv5HezjH0w4Xz>OWdCuD);#>&QH!t|@%Y}aX*E8+{6yAA4LX}JY=bg6KRK%RPMkii zL&kUKmlfO^2TO#NO8-BFe4eN&#*^g($^PTWyEiyPEt*fu>}U9t>C8fvrSp%%{$uRD zN8E-QSMq#Mu3BsM?nNkB9}W2ahTFc|6H$)h{l}BlgV?~6TiK5saXz1R`@{Knok09Pn_Bx->+a43qE3+K>Yo)Kt3F7;kgY)rmc`cr5 z$>J}+KmO=$B!Y84k^W{s$^D)Rt~8%sZFk}FTpgyGC;R#Q_-^p+A~*K01&>b%>h}=E zQjGH%$hw(``Ws>QKBFP0s(epQ{I-8wsSpnLDu;_ROXAvrT(bjM=&iNhwmkgnT9k z+2E2Bt)D8nlaR8s9ByZ&?-%kJbuj?LTh^lBt5iRQ{?e`$Yfx$O3B|nmZ+?9=WOowG zwUkMJ>EeT3FzBU2&KLbBIiH}LNAp?UxeNn!Xg+%kzr}gZwIkzueb1N3mUm{i^u_ty zTJV(XHqVvJKTqv#!>sH>C3g^r^J#eV1Gi7Xi=4k)(_qZr`EDisrRP`wa(d?Tc=y{1 z^>dApE$ik{z#beC*Utf$l;LAU^Z8YBe}TdAXhhUYpTF?_<$hM3@h~!htl#B4d*iQh z2I()|)*FUHt~8$>$+r0O>o6JLPZUo^Yx!~*XGs4(A)j3$7b5iMUD!^M>YK2BFCP?z zjQo#ee7_X38S|=@$ogn%Qy!Aq>aY{fr9WQ|eEl3f^D=ijzyhzIN&h~fe*QB&hjv#6 zkor07?k$c>8%_F41`A%n^7t60VIt1wpAXNt@$G3oKh0~)N}n$y^;7k21J@MjNuDq3 z`E>}hGu_HgbP}I08v5%W*K_+^ocSoOpEiY~nPNl%>t&ZLt&arpT`NTePimHt@jbY{ z1GY?zChH?_hb}l2kU;wL=ZE)!=CgD%|9sJMI2QfgNyhgU%SIz1@-QO$%bqVkzUTFF zNB`&N5Y+tqg?t`69SF_%yU4eb@+0I^w;&2Po;9HKhxB#f{M#MJWNhE6MCxah;vRU^ zY4hecgnY`yU*V37ups>?0oEANRk*ZIXNk)cKw5o9YlXi{^9Fq8HqL zC0Ej4D(<4neypJRv}^r|Yx8#+d44Bp|4=rpI*Zjl6p!z}cgtZ?pLt|`WKm?t9$Oc% zM-#;PES=O68f%x4`>V~uG%)2y6q$eiS1Y;y=-&qN{NuRkeevpLIx03x`4ZOe>92-E zci&F3emBpv!>yULey-)FLM@5r)7p43R?NE#wRKYdgz^3TwrJ@8Z6M?OaorR=TdG9v zPwMqz4{{D_vpL;m{uEz7l{Qv!u~nl;{T%3g9_^2$P8^*^>Sz2j6E@^x7MpA< zuAi$~$RoG63@z$vxmd4L!`enaG3{;oX#QgtCWACe(sJ9 zLR_c2$ZMWIU&Zn3qt6L3IQO*yk-Yg`e*QV?N(u^l((ye#XD=Q(X_N8&XLS|#;k!9G zKYY*V0xY`l`4rxN)ZVm~vnsXa&A$oxEd2Nyqncrm2`KeA-{#^-N_V=AuID3bec^^)_^ zWwbWiGeY)$zCJFlxW*|tj3VQ=sZ9l1)%0hNgT(dmc)~qyzzSPl{1)=(HsUREB5D4% zEve&f{5OuAKkBQd#(sYbW~aW1`wLP-S#=nN^G4GCrO@9r zFu#cKbu^!EpWo+Jcu3CR?Ktwk`asC1^O|?)G2V$eB#7%{!S{MjeepPQe*t$>jZG;G zW|#HE^-llO3-v3@aI~-N`SRzF!bgYTZLd41JtfZH$PuylX8eJi@0k5E4dt^H z*_>GE`-S@nUQOGN{UutYK9>Bg=B}5Sll*nouSDU{{w&K&s*l3>Y&7B_XJux~o6i*T zmlO3KQyx3As=4C)1$BSJDR!dy%UIi<8IB8P{s!XwDXsj$E%KuI>o|7=b1dJ&<~fP; z*JPrIg*pDP@Ra@k@cqjz8f{_lBADc_%?2HWb*1^UaqfX`12*7~zl>%^Q!g4m*Lh}asFH!mZ8Uv+hqMR@?I>q7r%$G ziMalKc%F`*vlN-{cPW1Wf4*o|j|12gMC;#$n>RS0?&duIT&RB!O)p{W(|$bug!Rj{ z$&a|{Wi~v2Qpn$Xr3NS$II^94#rd<@`o#H zKVTalGv*LV^EdT|BC7xTp^uR`e|eYMV%&savOf7DnZJ0pcMVye7<}o0!Xxoy{GA;) z2-_{w$o_XpkpvHdd-~ypI@bt`6+S!N+UvH-s3hN`bqf_ z*3V~GtwW9BdpuMY=kJbl223w2Fk9aKY(9Te`xW3awAf`E+57qVVPcD0+>KImRH(`P zd0u#so73Sk8dmpX#m)OGh5VJ}Kjw6^ZJ^8BPs2YSep>q@rZ_q>-!yUlE{DG3PTIJT z{k@Zcv zRUGW=-;w%h*e??}pg`6)`E>;t`c9L~AAR!faQ~H!!sTXveHF*&_sI9lFz(ln=T8dx zjgEc7h3nG#SvKPn9&0%=g$v^R);@gCz3J>i`aj!xX)yijrL32n^!@?i{P35`KU|4q zzdW^nIAF3lyW4pS3*9Wvuk}D>^mXy$ozE54*Eg>J$9_JjVc)DS{*T`rfq!1!sU56+ zmqKr=cz#*8FrTe+X=h~^AkMG*L0x>bT|>?nho>5%i+w!l554v@#+ciwq<`runGOGu znM=n1dmb(ry!9Y&KJJO2J|DSb7G_K@#gE0}{Ju~MM_kk`GXAf+ABQ(S@9>Ma|Ce9? zBsFAWTDSt4e|D)lh$|;F$^3JC&24VtjgeT9FZ=uW{K`+Rf_3kH%yX+W{}l2&uI)3< zwWSSAjb!@3*Waa^KjU1H1Ih1zjtyM+nXx3l|FzX*9y^yZyD{SYzV~Y6{%m(A{q=PF zQOxIVCQHl^=hxtxGHzY+<;8zF!Tixt1vNakT1wX6Ufe$RN4cHVhw0*c)~xM>I;}Ni z|EF?=5mYtf;XG3I{qgftlbaGgO;XAEVz;G0hhen7YQK?qAIA?Ob-DECmk9WLzk4>O zzbhg0(vu`5E_4%bN6$)^z@gKkFUXuXfV?1;Y8G zKBGT!*4$XKKJR{BlRej2$`+Z5^QoTnkE?j)PTo(jx3dM?Fh7%>pC!)c>{u22oWkc* zsIR*9Y6$$h1hWie^PT+tZ4n*zGwZ{uR;%sB`E+pBLywD*q<*>{?1@Wi@mNtP^{!t;HRp(bT zjjp#?xA~Vv^Vh}p?J={%5;Fd;dAXl`3{$l#njp^a+E$%mvVrEe(!Uq3l&?o#x;VeP z8-`-g>l8A7y?4|K6P|3xiZ`WtKR>%#mX^>H><&ul@S?>IR5C|<7DAoJJ0rjNKwr$>_h!11^nICZBF z^ZX*7ALyyob0;@iAu>w(|0(oW)eV1P|7v@dzd@W&?=j!FyIRh$eIm~1yi^@_H7JOz zuZ&9M@yTlnnZIrs#MrM387#lQIG>{?wMK76n$J%AJK%*)5ShQaFYAgp`AD+Aq;#+k zX1t9f{eA71!z8as?ic?c{r-gcspd3W%&gx=_LovZCSl5|0$3=B^Y_el9=5eC!NY~p z`b5~@)Or?y7AtGe=Ao1?A%8tyCLrP5YcfCmyf+8COk0ribC<>(gNly^lRqS`k1ZBF z_uPH2I3k0z7)7;It1W~OB@Z%=XlCY!W@ z{L?v@RVCw}-(NattAWz2#bo@x)3qB$?O9FM@9InXVsU01+24FuG#sxrQ=oEJ`uT?Re~HnLIMaBVzv2xyk!`})KOuiO@rE<(YK7{T((g~m-=oSuxb@SH zZM!4R-^!mqxPpi=jf=_psGyeuVoD|>)l$X}zdmwrWz8;_X0XyB;{4sb z(FUgObKp@Zdq1DQ&s{WO>#>;BzfLc^!D24WpMGdR6#o}T);FbRMj-N4GHRR8XAAlB z7-om7+%_^lG@LsH0cQ?i=mXjJ&yT+y4g}!*++zGq66bGpzere>-azhqas9hDAQ2}| z)|2_6pCmV!RxD4RUz<6w2svLmu()U9`WMpi3Abv~2;{m-|30DqwcK_K+8=w9`Jqbb zTkb&~BlYi7*C6ItJ!`K8O80v0p#0&)Gbysv;ofs>&y zO~wzOzZcWnLa}Hzng6wZrHQNm7NL!$cz*XND3UGGy2?6NyEW&B{QJ?o-*rcg=V~(l z8~Dl^=QOeXcOzvS%dMWby9ZIZp8Ute#3?T)kM2T(g(8owZ@ zPvXNCAnEd1x zn88_b{>FBB!dcB4&YSNL^5?(pHa2AO`4j5jyI1cx=0Nke=tvV@`q?v$#nSl1y_ms7;m9h1oTd-#J5o4-Gu={bq(--)rRxSTK9@$*{7 zFJJ#&@7KbqZHsVtia4LyW%{_)cQussWY3>JUzDac0E6GGBkSW?Y9rD8x8(jlqCffP zzCDT;NbYZ+EY9Dj;;HyzcK{B}^Fu=Zj1MeCTG&}K{Fw@3~ra&@2ZwT*!^bZjvpGvm} zpnea{=h$B6xKY2E^v{1ibHF;w9G-u^N^pMna*78!Jls##C-!Fp5oAE~d8ktqUY)E) zKsOmbeE;04Q<9`Ut0VPsLGBLp>n_i`KT0_NcHrts%o*5$UHdKj`F#J}I^qR4A!P(S z%B1;$P#@<+-9?&4Z}zZ@v_28`cLqHAz!gLSSvzIVm+wC&J(Oen)9qNQvpApXX^q@2 z1t&5;?9-|<)9FX^`71;T%Ni$=^>OKj(JZ=iI%}{L=kxILc36LY7FnMtG-@OFVj!uH z9*R-S<>VD+GD{l2e_Qe6_uTp(u!)Qy{l$`mftV3M^Jz3>6sF&o+|Spnzry@6^^zl! zm2!CVNkTp=H%`Oot@}y;=IiN2SaSUgsh`)Aqfl*A4fB6eKI8=Z;ZiOnVcYLlq<;2t zm&`7IkYjc{zWMV>s>@En>z+EPpU*G8FrQgu{N8hWE&JA^niY-{@9+3N(m`2RAQU!;$M?RK2H4>gLHau; z3kG3WkXMCCyJl18C@%?X+C+@iHC*!+I(_(B6J%cJw@%)lA zjfPX@b+W!$ma!SNyI+z08=ncg(DI5L^PMHrM?Rm9^G;*rW_7Z@NgPwh6}gQ-M00;q zsGoZZ?jbL}7yIifm$x*aq&OybxTLm zUo^|^!qP(m*^d_De9k$oj8?s9K6iC@U@F?_?5K@6pUOAY;Q4GOsh?ffb%alAn!oxN zQEd7A%WPnnt7!exZIL0gThRI$K6Eg~J&z^x&xjWmXg^ZI08xK`E*XQji?hl4dt|m3 zI(^zl>Svd?L6B2EL)JgZrP0{qex39mf9fSm?k{@<(|t01<@aa4)Jt}UERkb%{l)n# z@j8R0bJdxahRna_$M;?z>$&(vBaqi#`nr%$^_2Sv9M0EIA)g~9=M%X!j`V*<2De~V zmZMpA^L|WW{bSo+4ra9uWPD#@(UqBeTFCU@iRYisXRE;B-UJNLm(?%)`n#>6Bm43; zjjaq5=TkelJx&GFd|pz}MTPT1vOd>|j%L>kF0*$##rgc|D48F6w2It+;M&O;&ZlC@ z`3=8&mhe{Hi~?in|G!W_zZ`Xz^#8I+f7~g>8*14!pP}QH;=%jVq(7AH9D|(K*U0|N zqT|Wfxc()Xe`dFCNOYZk0&IcVVn2vm(eWu1K~-T3^q36y@ex_DM{ zeyu&Ty(H6DzJ3~qKE%bip6rZ;IDc*4e&x2b=E(THv9|)-c*BNeb{FUGfV(_2tsF4f zLsmcW`!lwY-B{}f3&{GsqEN}PrFM-xpLWwU6+_;=AoI%ti#=G8*90oR zJodF1E_>Uvu;J49ESwLTnEMFFCii6b7mM>};QXDte8-a1zwUVo?2D5PYx*qSpLt#_ zk4Jm$$@ttbv^(27bpg9`OkDpCZfk|B{U>05wK#u%$Hp*)@2O;cQ|H+M@@;7SyWLR_ z$Vi4AU$@|OdC{oN{~7oz*DBK`Ari9?a~Yb|-cVzmxKeZwZwA4=#m z9)=gT!flgG-}wHy%9WWIdoCYt<7Kb&`!|`Nmq9`EG+aK2^VhmXENa(XCFgqrzonv0 z;tTS8Q2zHl_@Ui|3f}$S{QAc7dI?%ir}=Ar=rMHFda^ESrThu=!=nv9xTqRSYdpop4`2gg#rf;0-Wu7#ZlphHnc&Q3WTmny zM{)hTI#L52o=hkG$>~*k@Sace=b{@hoI}=9BSv@y<|OntclI zBgFZee=`=_7F^}|Kf?aa>zFhw`0|{b-JSRv(4nE$<(|Hak0S|a9x^z#e(3oTP*Chpd3&UtbDTcoFelke=v`3U_& zeOBimz|=2@^QU~OHTt)p`8zv$EHmkv%JTk*`;VjKG?5!VUD5-SJ%7GGK45NVI2X+) zJ7N;b}4oIlmReQ=zuB=xVqw{Pn|S%3kiVDClHJPITVY)- z{r-jgjn$olt3&efGEVk7U;ie|2!r38Q)K=(VbVGjU92MG??2OYl>0p=``2$%@-a=H z=I`OAGH6^-BjfLyJx`%D(}<^kLjG!Q{^oR6Tf!(t`v0?vrWkdIg>t9oVCVrNClm5*p zjV?G~P4m|^Y8^|RTFK-tOZk%%#NT(meeg!>KQjOGZ!(3uAsv4+wpkzw__3!DU@nay}w)+BmlDMhZ)f5a;ivsutQ#qWK%s z&;_;~=ac=H!;W!G(Wa6um^?w$KRh4Q7p*n_Bjc~h_hDG1ycV_XW%|UAztKfDlH5L# z)W0`H6EM;@3!Z+m_w)0=5Awb^7rU3#zy9l1V9be=B!3qs$6-a~72f$TVf>9+o`Df- zY5r^)_MuzbzhwUBH>?~*mTD}^T0H)0ZhnrxmkgO_mXtrC{^<<+%kBAM0rv`V{mUG$ z%!)eG{FVJwgnk=4JWi9vKYsnYve1B8w4cuks>Jng$HBIe`vY9b`om?=c-C=E3h57y zKdXhG|GdclipHL<&^k2_9zjxnN4THr#`8F)`Tin%uuz=8;eGnSGkFEcUsL69biWpZ zg5ENI`25*f*z0Y!InT)Rhdu7^$H@ncr2Y*wJ`cN&YRqAkIDe1lzkuF6Lo)tO z_W8%1%(uXzI_cjpjK9y0DKp1t#y(9J*FW1}C2UU^4ZY^`nZo;PH}y1RdE@4>FQMZ6 zP5;~$Zw8Gg=M$eyb!A(Yq%f`5;`(=Vr8Z)Vy~zA8XnZ%^wxRiZ|8+gHMJ3x;JW*8t zk~{Q=>+}`md_;2A2!y4^NH$o>_~G;SGwS2?>!~!Uz6R* zi%%2h??l{7xDPPo#b2TReUoqEZr6`OD_?Q`ZqHF+HlrDNKA>--5>ix0lks=sB15(u zb6MC8Y5z}h-k5j3rG26*E*6g?`Lk-{#ypymS(jbn{B6+D!LLDHWc{1m0=|t<~m7~znX&n=${u(_DAIG&G6DRhK#>$#iA){CzZ&gJ1qA$r&bb{u(8BmnxNmxde&p-{C4{Xg;?^ z?s4(>o8)H1vKsu^3^l3#3HhrS(GIKaY5p1mCNQ^O$!z$D3;*LoINuQZP6wl&dLrIJ z_WSwu@6H#AENOEUYbvX1=8Jzn=*Q~r_&jAUIp5&DegNhT3McE|tAEXK`C2qNKkGBt z9$U&blJhqiXQrUQV+&dTF1DTruSt9Gr&gT5tol{xX?TLHfAt^7Kb*F7Ak2P- zA_LFmj#b`b*?~^6ZK%%ozQI^arPYJ_zsM zzezp=CSQa>r7Fp%if=v6^`iChxRE^WoH8fla~s`OOmamQt4tN=Q=?u5b2`%cSk|)_ zJ5l7%>kkY0>=C4fck5ip`uJ_eB-T`v%u*kS^I5E;iytqik@;b5yG^X0&t>-KnfUxy zb-NzeHIC-9-KhlD)c+z|cXyIhUj_4v3%mwlSVd%g^AYV&^Xd600)NI7k^K{e;}Sk~E=LJogND;+|L{N$3@`E{^GB6!gOIy!Ihh|iI*!8oKT%|S-r7fU|9eaVJpYsGx3E6( zHTHmmWJ532pEC|zfCvBWhFWjw_b;4J2nt$_ps&Z_EhptiSRX6fC7>>|5}`e%uM7D~ zot6!*_%V5Zo!QhwIR5Mx{I840=dzcTSYkx;)#^pR){%igD_tIk{_Q(U+>LQ2Kux2bEJF;_nTch+8!s%$CB~+ zRpVrK=;3B2zffHNZklyMt4kiFKXdFyGCMcsDs$1Qmg<+_{6J-h0TwOvBlE+Rv4bU_ zZ8;oF#PzM9l?8?zqxt*W$q8DM5_tZ!kU#y=)1al5N#=*`bQWUw*E}*mROlRuq>AIn zwU_cGYfh(){(+K8(zOUu67!_UID+Yi!Gu{KWOm!}~3c^z6YN zR*3U=TTT&n2BYwFx0G)of1l2_W=<8BWPbRfsFmc|Tf_gh^#5Dv&)o8toLvp^W4VLH z`5P6Wj+mKaaVJGw-!_`KGpFO5ncF3C{yzNaguv+@WPRK!IGG(~S6Fi0)&KD)+^<*K z-4OGy`jYvfU$8MsKZK&Hd45f}-=Vg*^X4uw^Sl4io0Y z(vax`U;i34`m+8V{aC1-IDcVdJHTb}SiJ2cl1kqls&RF+u z1Ft_KuS9EtjPTxZoli!+b<^c2URN- z@k7oWA-%=*uc@XD^H#JZ`@Kl9Zc&|{G^ z8Gqjed9cEjn^~I}asGyX&_jjpRB}IVnVk`K?(re#vy|@-!J}8pNPXKG!9nB88q)uZ zy6%jkgbn2W5QkS@c;AZFH^ZRC(C$y`+mh{)-KDFJk@^;$lL*Ui6=eM|r1f?zZ1IS^ z->9F{QB*zof&919=Px{;7kj!2zdYKq74OCQnjiTdlgqpF&W8&5(sypllH)AM{H?;H z4K^LJBI9RybU)UW`7)!W;`~JR)IeK3XEJ`Se&E3l*C(+q^5Xnh7I((BckX2V)^kcv zEIsRkKM%$GYm*&Q*v;xn)-v0xIltr2_q8q@ij+;u$oe!e7^uCz1|CzS|3AY0i5*JE z!fVa3G+%KT`)7Jh8YV$3Ya{)K&q zws^A0ij0rv9QrfwJ3cHmNt`d;G7XsS8bk7h$J3Z)ei9iUy@I>IXstV$pBWVQg!g^P z{tu#m`zO%^_NL2l>$2?m@%;@GJ%(%Z*O2|$qTDp-Z#=s`9W6uCVbMGvDeO;} zj9G$(zPpfYF5`>O&+?s7xU=^t>A&53w+UOED#-qr-0WOT?DdemUufQ=WBAnK2m167 z=jZkOYZ!jD4LheK&7Xwx$+qzgm_MXDc|OA~T9w^=HHx*`E1qAS@oS5UbBydiEdAM^ zUGnu|)!W7Sv6`TX%HcFWYaV&B8_SYd)J$=GI;Gwf7dp`V%vjnB!$Rhe`P0`r6Fe9e zLi)QS|1uO<(E4-q=Qvb#-+<(+QvQVblV|!2+|x}b>&I7SOR-Cp=4Ys8G>#8CO8R4i zMz+(wc0;Vnu3J!BZ;&5sE4qZ8W)u)`H|*q=CYe%49$vs}-0 zBJ-ot{a(ziO%iLe5a&nrMpsnsoI>X39jbd{Lg^g5T_LMK`TK#5x0vEdjN}Xq;Xhpc zna1{Sm(14kdD>1J->WkowfwsR;A#eIw)B z%C6OrH)+FOs!RD1>Jz*C8P)FHS!lI%f4`8gHGA4Id5uxzeEQXJReZVv9$!NLVZyS3 z?A*FJO!uxhUm2NNP@m;Q`l}&%-t5)QO{{Q%IA7N`c0;ga{~y(#YSpO^w5n!f+fQl! zBsojWt4~%gNn=y4R4~PU;`!4}vtbzZdMP;{5)o#Ni)oRh|8QlqD?9_^(XU9#pOCM~ z;j>`7G>wdZfg3|`TXO%Sah7=eOSF!`{m3I^e$EbUmdt)!;O*}h>X+NlozRH8PwJQ7 z!y+^d_(taEj@mcyTBQw37%R?Kj_OzV4C>CpdP?J)kgstA)!4K&b8`MN+_xR-uL8%1 zNWVX!ejQO5#PaXVCgb1q1Z|j2cfv$FaeqPX$#gd6#3p93&YH4JA)a$mvsM_wr$>jUEqb<#!g#JR~ z{S(Ol@fB^Hq^}F>ziwY{pzE2|?C?}^zTQ3iioR#Nv2uRvVwlx_ak6-zQ9UMVzm;b4K9W44SVWYME?FZUwt&*IG0`oAcNfTW_p} zar6J5P~STIn}BEue^mU;Y~h0x-&9iH4!A7GH{TuDA1ltE&%w30IN&gupJh);!LR&s zvVL5(BoA^a_i#!@reA#imYAKwocb@MzCB%g6F2*`X19FA^=)&HA6Po28`F&z=P&?}Rvi9n3l+U$Wna^5@;2&tg6rn^?kf>HSGU zfBu1FKc1;3&EN6f{ZTh=7829M`8)k5gITynYe^LNwQ487%+kp5}*(@gdn9=5Of>d?op7D!R><@x}MQ9{pL44!3g2_-f-F ziw9p1A#s?rz7+N^ZSJLDP}g#@KIrl~4-0SAV$f-E{X6mK6l^TN;PN0DpM3wTY{)J6 zoo&UOhKcj1`}qfYeD2C>1I78fI7ywY`)fwl2X6N2*z%9VEFbCjBaE+;HXF0dD>IpC zrZ|5mnmR)6oCEr;7LTtAnsb=SzeHyCL7cy74m}XNW+FL%!7b>I6pxu?{3wcv^~P50NAvl8VSTD}>L+YMyE6CDQvT!w_a{}>sx##XGqQg8nX3*9 zI}Tc{rQgpgj^7_r3L3(`M9ySxb>jRbM(d(-hyzMzi}M$2vuHnY{*um&#L&jYP+KMAgYVD2>tGMFrxB#TKht3{ z8W+d${10J%*Xpw$c5X<)03+%5C**4gw*vRva>@Git?N1rYI}(EXLA(Oux<1?(%;|S zZ4Zhs--Y^qaed3_c?Qq_e!^R2aeXsrcL)BCt(bY7xW3)2`i1G;yRvi-alSq->%bmr z)B4tOzdC;ESn~XRAz!;Shq6VrGsyZOd}Jq-U$iInZRlKIroTOr6{J=EPk)5*^+%)u z(q~T~_v2_k8-S5hX}$)W+roByDQ6cd#pCPK0CRk_Urg%TEXi(+(Q_ln{^XX}DL6kd zju$_Ld=>BU$L&@rr2o;={XZ=Fu^q<`%J}2^|9W@V;Z}ShS)Ufhr=jv-8Cjoh`?d%9 zi|-=xwK!ib9-qO~NuS92;lkHDDEZlvd8UfQRnIVuBRO^UUElimYwwT3;9akGL&_3p26B264$TCv7Hdw(VooTDkQTRL+ujT z#8u*a{aav&H*+SC=MR+22V#Zg3^IRP@GXn&nR%Xl_nY4Q`S|_G;cv`wFm(}GpN3v? zKo`l3^<&=o6#n@um)7q1^lBYhALvKV#gy~OWPN(Eo8){|(sok6&diL1qFo_bpWYvk z4x4~7vOY-m+Y6)GJ7j+L`1D!q?)HhS50ujGB6oXBrn^#{ugv^EI1<~1S04!D{i4GW}zg`*ZVLHsE)GaA`Tx44wCs-@s4!l zz9=R0|I=;rVdj4aPM5{?>#Achd=`Er`2E|w zXJG8tW=-p{vh6|ApBPh@fp5yC zWc(|iwhxCU-zN2`>R$;~tZl&CAo2XYkllyL6%|(3JU=b04`&4a!wR>~q(5=#uolzY zGMvR8lJW!a^Q-0av=E_Vfxr3OGke`TOow3SlG_SuT2mbtO zW6SxB4c^FNI!gEV3-kBGMLn@n+m-ZZ&kt|I&2 z9`~nV(2H1TOlq!_v!~ye})=9z`sZp*6)dUd~=!9giy&2eac@QtEA216o<1! ze{p`UPSHlHi3J?Oq@Q2N&zh!T?Bfl|j6}1)AmnGlP~K%BIUi^%nT;(ux{~xqYrao|x*4rMt^X}R zOsCCcel%EVHBztUkol3`#dtKy6_ELnmcbVMnovTX|E=A=AG4R-BI~>56UxwX;RjNG za%&%;l^M;C^SLIZ`ROq;b!mPitncTpcJhGR{_~W1N^$*y| z21iz~u(P+Ce?R|x`6J&UNWJEXbbImq{QNZFUBUvAuY0}5qJ3AIFVkn9aBEsi&VR*K zFT}pGB$6+s)vGZ)EQgG5V`ptZnB@L2YQOH0k}a_KQ%vsH&38Efn|8Oz{?D?nWpKFl z9!@^u@$KiihuA2u!j86=&ff^*TbhL&)2i#l^d3lG7xJYXr_DC5Hs$pnh4F37W*sPo zjzUe5xIT4SG=d%a;>pYmrF;p`r*-Vm4gdUXNqyQ7ynxvbO<NHdp!sTd zZ3i2ebe^@zt@$5c!t+5cfkUzPs3)HD?nmU$?-&~~+?K>BDu42SJr*wE|B?Fj=)9Mt zc3sP>?}Yx;qu4+gJ13F(lW+cNBpuBr&jqsx6X$D*PdB&~*dRGurayfBy4O08 zU2#ibpOmEMw}tuBce_4N_8Uj~Q<~YiETio?7PR$xbN$BGuhN@C@%rsFa=yYcf?=s) z06D*El>YyJtUn z{%3td7B2NHruUQP6`+6rn@~5E@*|vIbzM}BTQ}cfK!WUbK40-3k1=|NGP~1R%8yXL z7Jrmuld5%D<}~T+LjBqut;6;#FyWow7V@>`lo``GGmXts73b&8yzXd7v_U>^K8(+g zU&}?z>dOY!t%Eo}+kW;z#tj#epP|9I>|A^)duVn|l%F}dCYUsP8kt{xUt@)|;`wC! z+bTC6^RBPJ%Ym}z%dhVSrA@~RowcY@m%c9apXN+l4Bxm-q&`_ZjYNxnG(Vf)C&0^d zKk1(*`fY`8z*#cCx-se?k{8yH@h`~cJh{o9oA3}c0R>-rm zG+pMgMf$pspX>S^*`sbIy!|~wex^r`WFdajn1iD@KW6*7V^*m(nodjgM_9kj9K48` zjoQF`CyK|nLl^p@F4YBl5~c44`1#X}0lQgV<9TK}|F&rUR0>l`ed9s$gNfES;W?i? ze=&Rcc&z;xPWnsHlHQN;`4}EQ!uZy8RuC>s+(h<|ZTqgl;f$^1{8oYEMrdB&N5;3^ z)mtTZ2cIG1TV>5b=r&017$@du4nI4OHJNWo{TbBiDYB0$k^H>*C(i=Bb;0#z;`9|`%{)papTQQp9e*NgL0qtg%3 z566=FQ=gj0R$G;`?3kPXDch^dXf)X%$7L=#KhWej0jEENk^HP}n1vs|qOoG0 zlrN$F7)CC|3Ef0;e&CQ_6sCI9{EWSjh|XK{Nq=e4$sFk1Jx$)vyg2_5hD27A_1Vyd z3V5`5gMhu_`SYU%&mnhLk>tnkyaKzJ-;w>=DbCL;$^Eo9PYh))YsC5Sn`*({Cr@Qd zPmA+2-_QUXHLQ64kuZLhIxJ;}$HueQ_Tu^T?Op@$F4mdMfBwmh!1u52WPA!qvc>TK z{7L`XQhp*f^a_K{F6r|Z#wX{H*)R@>Ci9z|Rl#T|-bm)hT6Ixy{IrGCmyeN~FndNm z>0iTQ8+wg8P5Rdbeuq)evKj+yWY3?kFG{T|G5+#vs2WNAX<_}o%j^YOE>&bRoW=D; z&q9&SpVE<;os#k)j88*{c4kFehcbCZX@6B1pH_XhU;|ZYKK|Alz~}+v#U~*ja}|P_ z-uv||Z&VV+@AL03!8M>L$5EhGXJ7(~^Rd^kORiH7?Mta6b! zADLUpHqwx>7hjIhm64yE6Ua z&u=uIOv1G4J*2*PJ=+e`M<+>tZ^z)HcoR(XlQiTqo|@Go!9!eM+E>3q@-79o^nf@& zn)ymh(@~-?AI166%IdJ2e5og?ReI)*P}#`ogb znNi~W%=H+A3VSCq{;Z!r62W^Wll_I!xqDf!v&HPfNO6ApCEBBYxi8P(6Y>)?bPC4) zScXNs{Q-P`Z)=DzdMHKl{9&Q~Yz|qD-a8YZmMi0ff4;>3VhnN@Ws?5P<#C`%tn zpN1W|_>gfDX5+=<)AVykQT*sCSzk}9x{M!d>fiz?KSF=6?S?vRv{PW?w~O6sP*c~2JbT_^~WR+Oufw%_Dk;E|Ng&){i`EsMlg5e$oOR85Xufm#<3bJaem6o z2jgs4C!DDi_xD0Cjl{MGlgR$TfKw&3Yf3zr2L) zzR^ka{D|uADY&DtjMS&P7(ZNixQ3kXn5!Iyq@D@n`K6sdV=(n%2D#th&ZEuv-hB_* zKlN(816}1#BB1$xdtv_5HslyythkCSMH7dh`6NF#mBr*p-DD88e3}aeeANm9fkvlUZ_0alUk}8=@437`SA#X>rep+}&V{*SLS56h{I+J2cchDeg;G-#4EQRgZO6%oojBy*93 z2+?FJlthV;d6tlnd7dfrJoA``%)a|OUfaE|_t@+Gz}STWzCKq7l=4ofx;_F@lCAnJpWULCN<~zy69*~505!e(miFq zYPxunrf&!}i&o~V>oN;8Yvsw#hqRqCnU*!3Lw>K7^((cjBes0+fP&2uKN`aM#Mp{k zDAfKSO}<+ig@uR77|A)pNZ*rg5gM3;k^LMvnGxR*zhK-*FeW;fp zNy_{kZ_)z2(mUY96Nx|ZeC+s}))+UqJL|u$zu83F&+MmR{gwIJpy!XxcL%fav+=E7 zsM=sW8z1k?8-b(C5@h~MzwBz+*z@f^Jv}R3G2U({d$S+`V}apj>M0sUw+rB(xg5- zU;BF)(d{4hyCQ{7+IM%EuI=6{bWPoXirW>e)`%KXey z^_Q8JwrAsG$nZAkcBUJ9exZ42GmYH7pB6P7s+j*Bt`vZJ8wbnIH$;7!dbu}tT#JF9 zf%N?m>yNopN8<751X=w+g3@Fh)JudmEcW}9kM`?(J7ej+^=^~vdy z5gi$4&(ClG(-X^ys)UUndMKaW=U%%a;~SrLiq$)7DPP z{_D=47D#Q+^R@3>8%+2V%+@Dg=WL-JQ}$D2u`*xla|3YUQ<%(u#S8vEa#tS=35~&L zS^u;=KP(+R3X`o9*!sf!*lGAaHWga`&QHbp+~cbG+mwfk+5H0_0<#eJd=2a0-(FjT ztJ`<8`V^Z~1dn@X*!m^ix`65$k6HizEc`#L9HGhjtFh;+(djKZr0XD^&x?HJjW#9& zGkYp_SJtODR>ttvY{~XNKFV!Nb>DWQE`21vG=%#fV&g2KanFPG_i;m<5VP2ituN&7 z^2F+rU^c#8YrK_=%lA>!^~(HQ`WA@)%m(8{rdmJb^{E!k`r^dcacq4-r+Wk%y_|tA zi>3F)`a($acq}nWMa6T{bCI9crL&>GP&K2?_@|foS?~{8!^XD<;cKzOXE&=)&1&w& z*nl&b7A5JE*negaeGx8wAF=vW_Uu0lE7zc+cBF>VH) z{JS4rjDHhm#zQY}E?d8v*lP|N+Ae16SH8}RQT6F+wtl7Kz7A{t?84Av%Kp6St-VNi zcv|M4M81xw_9OmT^N{sV?}xueT7(8$KfilSi^4zFSKaZftWV~BO~|me9U0eB=4-$U zBRt7*#EH$)`IZ>}Ug`VL<%>a-nJMLuB43_|tkCF>I~)JHE{vzeA+xCPrZQi{zqdrA z7rv}NfA-J|ncSZ@IWY&-PGqrsy~taP&LdZ|`c<@V9bPB$eChZXW3|g^S^N|E znp<`W!4?l?@lULeT7G_w?|=S)JHPv3U7eOssZTxIDf4A!W=hqr+fwEvWxg(tHNjHb z7C6*K`u7p}x^vZ=DtG8i)B37^zWn~oP4%qN+07lgZ`J)l^8Tcgrqe0A=`4C{FWs*o z_Ggc_afa60c5Hlne-)U~rYmk3sPjX4eamY6c8YJZk2aYOSM=`-RK1rkFAhYmtba|e zU$2Ms$IEGBS^r)?eKa1Pn9l0gm+8~dz4}}>|BJJqizl73*!cLwa|vqbu4et!!=dZ3 z+-w&d%a!#j>TNOncAP?ytp8fxKVX=88F%MBfcmrl?&GANFX~r_ ztqn%`xy$-*#r*Kq+UewbV3Y9|m_}{n!2%L1=YnAh!RT zABN!1UpNhbqlV+^{f_MdR^ug9V3h?+Qujen)P=VHRwMQnfMwM$D- zx+|aUKiL<%9!92xSOH~zMwaYDMz2$7cT4hDV*TK`#ufM!+?VyAi24+e{T2}gzp*-8 znV;nUs?(NL^=N{*`t#M6)wf&LFe8_n%~^i7#hc(f95Cmsa{TM=+@6rtRkefo=)d~8 zT%V>o*dVNn8|%;0O=ghZ%9(Uxt1>?}39aC4(oR+%73)(DO9=Z4g4p`!jq^Kb<)~ts zc~V)QKE!vy_5hx*eFq1if2$}~pIji+bdIJZ-ouSSjcqhRAnw!V2_WW?n2XAEE2}0~lNk7H?)I%;6(78UvbpP-O z#rStcvn$@m4S>y7Wq);T?m*05I)>G+k`GbHz7UV%E$a8>`vY>X%s`cDbMQi@e{#M) zElEXR=SA%Poa5WG(ev~wc7IN#s~d1Rc_-`NyYJtRmu4qf|9&>&D*U$GWBt|O`1d$n z_6x?Zl=bWWo*LBlWLDlQ-aJrB&ro&J*ki1mkv zx2bSbozZangQpHt^*-dTQtj}R-WT<&#`KNY=du%L{>_(&=g-Ni*`_A@Pq6W^+)lN7 zpw&H$PE__+*{a=hCtv?$^~=qzCTR|;%f`ou?`A}Yt?A=1Wxg`B&0urDj*X9-26d#X zjd{Mxel^F*$1bdXJ)V$2af?!D{|9BhnuNHbJlTiUuaj+d(ZZF*^fvaoB4174`C!V3 z&Y141tZxsx2gBB>KdWCKOv7+$$Y`7yEPcMB|C*|rU+PmeURK`{>kqDL5^&mMHmhH& zho+&cH_z9@k{tNITgl!pIqAtpte8^3>euS>1L#`)1ZwS<{Fj&?t~gkV9pQIb{hBoY z1J=Iz0d@Z#AirO2W|Hb|tSj1V{k_&QbMhHtO`Df1^X2Jcjx7)D*!?Fb4g6`-(jZ!~ zN?E_U&9X&6AD*x1uL)EuAcaz_r28Mm{O~^=H<%dt;F6}~|3v>4(zTHKEGnWYP0JMd ziksLLcEz38{Bf>TH*DS0kM;L+ZiGRks*L=AloG zOm@FTg6~q~%vj0#ugH*1IP+i!ob#3aSHQ#)Ta=D$R~dY&)C!e)12Unc37*k7*u z@&mliewXEkB45pa)g;q7+H8DW)LeD{d_8Mf|BN_)nXPGtZ~L3G`QeXa{^actMB7g( z^JQ;q2d`Q#YJ_S-Yj26`8z4^^=_)+BhA-|@$pIXcG%Fj z6Rd)j^(*&4H&n9V`3j0v)$Vn9zHa^)hp?+tVSY^6f4PrO#H6HIc+^p?e{%m7)pZ`u zrz~Xs*N{_7QNeB{u1uBQ7vtlFDw{DZe+OHCxM6h=+0|9|(=hpCl~&iVcIX{!UoP<_ z=8sjze8kR5-=W^WBl1;qL@hdJtu3oRi03=!6PwZK$=3Ae-~F{BUy(W%IDOZaJwN;& z7eLQSI#d60Wxgh<_E#RwYsL0AG%QM_=q1Ti=&YeosYU)C;xY<{Ve+a0q{^~D5R>GKoo6Gy|sadKM(I&V@xm!BU#a2k&#tEOUwzw}%@ z|Cx0-5y7>2{Ytzu5AImV>X%N7Tm)`gfg_`&pD*&&eDY>!= zF+b-TMx@_n9K1Wz+UCdpe!gP=sZ*vseg(8*``>lS6RF@&5(QpW*00&q+~M4s*!slk z%0-lFzL(y|-caPLnuRZ3JPVNZ59SH?AH9g}0bQTI_#yM(^7`rEv*8%EbQJ6F?_3>^ z#7$Fh;a`7|=)aaYB;jn{Og27l95Ek{?q#t13u~3+!oz(9t6xslw_xMk?JQrtMjgVG z@}rpcP4Zu2{Y!h&bD-)B{ydfYqlhSjMuXnMZ;Z#(PW5w#{ za)19Lzc#r%uFd+dxKEZeNA=&KrpkOJ^lXM5O`Eg(qZh30M0$ap$SO)%zdAN?!059r z+5FM7aewk#+>ge!UH*?xd4KcAVIC;|<;B+LN6g<%2`hJz)7(-;zHC&xh1VYTm+6Ma?iM+yb+`txqqZ~~d7$p&6*{A>87JuI~SVZ2Jp|3v+1_b3#X*Y!e?uk`td z{`~p*VfgMfg7xR4v?igx;bcshsD57_-@0E)hLvRsoByR$SFvNB4sL(1#oFa?oV1*c zZ>c`pF!sP!WV%WEBGyOWsJYV zWY=QnbBd-|Q(1B|GH_ScpJv&X2<)TkQDF4v(WxN%az221K2qkVw`xCXUZN9w{yZlz zg-p>9nDS{j zrkSe0-}3yfm+mAuY>Q><2aAkTkg`6R_1_-`rDOcE1*|_x(#k{6=gV0CeR$0_oY2|I z*4H<7J_;vSo}ZulZXvqL4OV}&I(@@|^Pj=>_bv9;ru7!JSpOYa&4%3SG^5@D%KRin zT47T&Yc{`I=+K2UfBIADGG%`JjaB`_=`Gm!Wwj}VD%VY<30sx_^ZWBvEuq{$e%IF{9? zT`4K(1fDN{n+)toSb*UJ)cPi$zoAQcxVdK;{C-K##rXER)plrPZ9!NgWqtbm@F>RS z9b)w^?~_u*ibDNg~ih6E7qSLYt2Nxr%7ylJ3dr3 z|9*8o>yNbitiWooWeBMw>7&Sx;gRjwSefT1BJ&vfH8_OV&Qkmm^S7^#cc6Fr8XMp8 z4t+<8%O`O2r^WVl>2$xE?D^k8ljh`UW>Gld*XsI!JiZ+aoq~mfC&KWu^#3pBXXrN*nt zs@>32=i{2W`hB_ntU9y;Uk~K6`jc392fBoAX8rZ8(Bs&*?;s{mSLVn1(H*Stx`w)c zr01gkxTXAn=HidIby?XT>88~slXo@P`sI|2=H$E5oUV;g=I2Bg8{F5hf}4i)|1aie zo}P|0T6KPNx?%QTel#@X{OG-LLPJNMAMYPC$-YVgZLg$UUwZS|3-?#F#@p^{KIHo` z&s_CK!7D$u|7BWmA9TtI!SrlWft z_B;gFlinBiJ14JPi7A(tvifAHQ-B`*H?j5a)YT`Dez^o%=Oq0RjEdm-Fd9eBav@tEnsFRAXi^_a` zZy$&-Z9nLJl>UB^uR^=Nh^@%;bt^amEn0+QMV$Kcm&d>J&8DIHml!-qQ$Ls22TB*r z!k7U(U%rhqal>^U8~+Adt-`>lr5I|g?4O>WEP!qOO>BK2yT(bZFe*X8zw=*_uM$;n z-k)BjZ2SwJ_Y0}f@7egbwX7Z;I$WKde>m%CM}FPS==EV`zUm~|;BFTS+5OjI{7YHd zotoNppw1VR^-C+q8PiMb+4{iLcC$%eljrMTIH`Jr+*SQ4%JFYhkQ0q-YDMEdfBCCl z8YJIO-{^E8UiI>2>jzaX^+nGf-C6zWU>AwWD+jasHNq+$&WmGM{mRgsjn97)aATaB zKY9N_aC#;-T}VS;H}!LQe4M>-73x3FVg30vubr@*vXPCCF6&O><@^JQvrYx&L!-p&b>RFlG6&-q{@b11#A7 z;tFkhP>!P;GZMKAL`UqWSAA>2XlG zB3~iHJE7XPb}V0q5A;LF+uh(5tNwiD=XVB0k@#E?#_HFY7}ecn+2dIM{@?i7IJ-Cj zS7xbyzMQY#%@!ejTpC_StDnpH@-)at?5G@8zk2<*6UVhS;#ebx~PHjn@OgAa!e`^P~LVUO#JAc|LdJZ*Cn@$a!rTa0&`ncXEZ?xI(#`^d4 zT`kFQxFvOK{#B8$@JXusF&4B#|A}h-ljnyGb^2r5_h44P5@wFZW7{xRzjCyvBdzy1 zJ(KU!~nLXj^=FIE4!xgA@d`s(U~4rV+*V+J^rNo5s3 zo0R$Sw+MoM#dgrjQ08Y-d4I&s3TE}GqyHGhqzq!~n~x2qBUK|>mLH1z3~*K5jecSV zt55qLEW)NZo*$zx`4}@In~i@4w+nIU&3f2&RMw~L4X5!^YdhD*>hkS$@632o&^Wh zj22g4XgO##j@01wr?$o}oN`~!=6~awpTUugeXRbJ8$H69371h2tISV+eGRJk>pw(& zRr@b_{^$NohwiMaMlRtJKk>r+Xxu^v8h+ZCYMqt%5&NHhPgTVxGGprt+DAg^yst0S zGF8@}hJmX21WQ}Cziw9QT)NgXo{ewy|M+132^W^Hdxu+*=g?+!wCZ<7zKr$;p-gpu z1DF3*c{l)_D|BV!+p+v8400ccAGehGs$FRY_Wc)y6E@26?Zk&UX!&D0t54r|Wug0q zx$OB%i_fcJvt$WU+DSiOte>yR*o6+;*0KF5<8Gb7uL}F{qMgK#s82teJVtM=%cy@t z{ao(P_fFKH&#nGr`_GRyYCz}fR+IHViF_HmI#U1f##FI^v_Dql>wJM743bUR{R&2_ zd(zD>?Pz(bGGD{)x}uTF$&??8`c)~v3u3<$d%oPi)*zhR6~yY-2dijQ&>6t?C%h@1f$#*? z9g5!S&tG1@^13+}Q$nU={~a|ya=x0*S&X8xIc)xy{%j5Q6)(ox;p(4XLpFczTd*5F zFRo?lS7V=@g~QFgtbX}-dxEJaFQVY7#Fyx=bc{7g`|wMderX8vS^IA`plQZcW&H^v zUoA$rpzsw&6cVe<*TgNV`@?&hvipbboA;)@pW2fBS7pAAd~<_mz72anUdu_Tbl~9> z+I&TsuMJtM-3ppKUk{(TQu0s>(r*0oFJIb1{px^MS4;`u`O5t|2;W?SSpTklLgmd{ z^=I|#r*;CGXN{J{M-Acr>Wc5@!aOIQ&HrjvU4p`}IfzbC^C#D@ZLw>y+ix*Wr7H84 z*l-VQ8?R;iUs9va;YYK*IM+(zM~shG>OV!g$whqDRPWD|$49?`n)JNr1-Sdq8`?Ld zz8k8@`Zqs@|nA zn4as5%E#27ue^TMf5;kH|1u3;0+V~Q zS^qWQ=~|?n%VPO@rP}|QGiwd&zd|dVhevJ^t6vclpF+FK1w@}w^C#!4xnYovr%&FJI#P z-_GH|P_5Wv`Racs4AGlAvGK8SlNba(?#srA4smuUD-=qr9KX^h>N?4X>|D%O9)m-}|?JNaSm|ofEB{-BdLnAmxu@{c6Bq zM^$~)n61Bu>w8ey6mwcwahW1t+jKq9YMT{Xe@LwBLCs^#>FLit|K6APpMR_6hoiPF zW%`vT@U_<7L)E)%PJK2>e8mgr(-UTNL;QCywmy37)nI(+*9k{9sy~0Zeoa~wgOZ

    !il3)<$|eW4L<#fXA)V4-K=+08RWwV|K9{cS17V8&Xf@n^Y2H6~QO$uWhZx#t%LwIp zK7OtrHX8mGsnbC>+2@br=SBgsU}5D!JFgq5)OS8V{^V@{X<=m{oZn0ss@QL*uSGkb zdL?~-u|E41EhCFn#Qe`|YXVOi4x)XsS^qZXziU}Mxpvu8=)V&Vy1AhC3bk`WB%4Sh&k^a^mN9VgCC=p$`~VnNq#S%zxwk#`C{lA^s`*xc$bM z?-K!@@UpKlwK^itch>7iWNHsyzj6Kgar1BFQP6c^{_9vy2uxTsgOY5LP!A`9&tgq(@MTQG+G^@cdSg(P*%^rACW}viU9Sue-d9gXl;Ph5j>s zasKQ2v0yTEfrT*tUH)qd{An?ePOy3@egAQMJg{vPG1%+C)wgi|OKsjXIPh%{U3T}Z zbRN%dM0`vjk3Br0OgTS|>(g%WbD(jRF7^0%knxA~dw`<<()?41aQ^zZQ4ri8W=?-8 z_U!-f?~D6Cbr0r}X}_X4err&FcV%fh*yo1OC2N_#2E^~vSp{UERT30DVefy;Z(8Rh z#qKz7`h4*y_I#B8`n$1^#5=Emo?a}z!uqX0I}r-hylBF~GKp{8Ki0BIDRGU-TZ@7ht}t zS1anzYKHW_NoO7Q{pRPlu1|kT&ea#k*ONak0IPvBxcv$^|6T3;gN*LL>o?ASukv34 z;lFLD(}Jzi^YQ(n?q!W(((dPqJF*$SxIgsf^Hlh&BCtF67 zb)F7Tn#{N|2M4tfL8JGc|OwjmD^8~&{x~J{!yG?o75x#Hn%pV6W1{Qv48(L zs+z1FD2~s6XnI0s)?`{4+)?L${Nw!%1GhXU)i;j`^J^;k{?JVE{t5B-kq%+PEczZLV3?EQ@Sx80TsD(!sf&otH_j`cnK zg%)UbP^I0^v%eqC&o#f02L1l}(K=I=^INEYEhBOqyvXcAXX&!}4IH0)E>8uuXFgPC z9pfMS`xl27llJ?~h4UfJ&CKAdPJgN%%J|3ed3obFl5fZJkNekD>rMw7b1hmFz~XbP z?}du~(0=vB@%jFPp5We8hngK@{OclrKWb1G8DuH;_XB<|hOFo2G}~FeK33|!jGAjsU6#HC39aSa{R04HQ@Z+U*~dIsg*-B4*N*wvA*wG zSxlaEf4zA_=$JO#lvF$>HF7Ymd!EnIKkeJI6mLD(GTi9*QeK; zx--6!exG`(0%nQVxcocz@2(poA)%u+jhe^$(=gx9*EWYW)z84Ag!y-@-x>|FpkvDr zs+RLsmhVAdJHhf%zhL4S_I@6U^nJc{I?S2jOXpr?eB=E4%|(M@;f+>w{VI9B4HWT1 z?RRgwwOE72?}%^bB@@6Zy$gL9AkVi$_f#m|k}7I0jNkQdn}MBr zKN{8Hne_d{{ypGV9C?0g7U$nF-!@%m!0DWUT>c&Nt*e(xW>$DWd#=Bo-(UP=TQ)Hd z3gPP8xIbk|lQ6iRVM^1xt(Sg3tl#ZQ))W7{C~ki-=66bNI#i|1qxZ)!esO;7N7ObF zcwWqJLB%fOU77}^Hth3PLHb;twF1=o`O-(>Y`-CnzaxtFlTCxO6+7zL=ZE>MJQxA> zn)3S-aQuB?;svtVU(Dx)WeXtO(uA&WBUtneBI?k9XLPf8YJd0zA>N2yDx+Niv2L!8(IB&g&tqO-u|rxym>n!{77Vdo2Gk)WkMW86PmVOrC#Q6y;FdCfiTO;5%mA|n zKD2&;JfF=!Z71$QiD2)-zF$~h+caGX!H<0CAf2(&^Rd1T>RdvC#->59BdmUb`TeZW zUY8!8bS-82T7&w-A9OoFbV{?JK@WL;?V=XKy+^#i#{6#ZyF`kt`S=;od{@-IMX+p# z3GHxGp5M*u?vs7FdxiP&otX<^=SO3@Q%g9qgnOyrJp|(@vG+63S8GdgI~?M zL8~3V;pk2lKPMu74Xu~KqEY5_T-itI`B-0DJ{({@8eXBIy($*3a1~ zGr`h8i#oiQ_s3zHD~PAN2Uowsd_I2W3X_+Qr0;)}NZ)@vpJlu+m#B6M5!SD62Zh6n zqbAh)^g8K0?k_PvT|hQX6UWDX%`;(ObA>-X!T81b?`iFd$iTM=aCFN*|Hb>`nxaey zY~o9U6Xp4Bb7l{@*@5R5`{USJ#r+tUGeJW+zl!zs=e$L5<^Rz?cG33=d7>revwNCi zKhiBj+OR(JzZz&iQM;oLNYnXZK1VfI?B579qy>&$r0*~8KY2?&5%r5lh5mT_ohay; zVL{tj2TSL%{+cD$haoqwa{7z;P1q9wBh#kR=ph@F&*$~mW1A{W8O!@)%&({6QW)xE zO2_-0l+NS+6rH`@;eyd$=pV&C-vGq#sSlCxtE)N9xxn~UQQ`IXR{x>!yQ(>TcZNjXV;k}g8 zsrYUtjDO>6XF$6zeQ3{~Po%laU=Zky&k{xc+UdzlDvn;Moj? zKVHcAtwHrG&s{~NQ-=hYF!h)8^HouN+h^1|n0Ygdt}mY~{eP^#n_^4JJCjssl>V>2 z%;&dywp{{MiuhC!U&{7}zH3xTG_^CqSBuT3YoPdco^3d6+b`DNd+o20c6YXM{h?TY zCuv7O|1l=?`U$4LIKI7j;t`246!U%DbTN$TWJJU3bk+Ia_YdoDNSiNYC_O6dFPrxu z8omxx@ZFB_U4!D^tl|ccop)8Szk=yE_SXf5k?^MJRGRX7z4Uxszczc`8YX;x3Kupo zK5_h8<`V%GjwW4lZb{!$eGnrcl1a-cmeE0pJZt4RUuHd{u2o>cB9LVVZS#}Jbu zGhu%FUTg{(5Tdw);3ms|f^Hoye-rS2B?)Zf!R4nhpUeI@!S~F;v{Ud7>HDvu!sn;I z&R9b{Mg$A%&(tjkUNrNgp%si@UBvH{Tbs$+mSX*VugLurWX_}YDdQK%w==bOk`C4J z@TxuIR|D~T$ZS27-(5)C^=ACy{B&+)83{^Q4uco5`Vsce?>-$Q?R#f}z5(MC>u)$+ z3jGSj`KNp8H%NNHHevtB%7#nfS_dOqzLe=Nt}m57dO}`(FN59=EPliJ=aI9*;ZeFF z*FS>wcT3D$8bLP^mT1`5oCnL(HjZuew;|uKVr9NILxYOMw`z2 zm%rfaOS&)8VYjs_eH$dtpZbqUFgT_?_0N#!uUD@P;5%p$z1hQ1(r2u%3pU1*(>%GUD(1n62c^!$|IaJFK6-x)ng|e~W0$e=DWmPZ#N@UPv(+x-1^1 z?qKoFP{iN(*BijDZWwnz7M_1>bb2q@IcPcbZYR&*_m=U{`l$sCG1(~F-xZmAnAq3j z`NZ|1c;96Z(o)Rl8O@tye(pBm{FCO;NC;KTPYoC>-@n=Q=`*tJl9*48#|nRW&w$3; zGJlNq^F+xHa%T>&pE!T~$t4=JhMCfZyZt0S^O1fgt2Ksh?XQBZE8_?I4 zf14q%pHDN|!En!~ur`9}C+`2)b1)8Gx>-=||IR9(&&RjE2YN$8MgL~;YxaI}LHuqz zp9!}|yVLP=8!7!Q?~jL+jDTI%&8XKqmcLL%^G}+kc`$C)eCnJfAK#9dw*_4FBk2VV zmVb&w`q&{WjvO1R$T11#8}(~uLiPFH^!OmQ-v`IHW{*;dTdln?|D>bh4c}^q(~8`y zviy$dmrY))^ZWwJKlOSP2I>8DsCFCHpNZ!i&oo(2<{k?Y>g)QF)v$ZLADtB~&-cE{ zZA9y8q_Dqhe52jObbdV4o?!eYB7WDj%ZG@kq4dlrUFqM4`86D|pM!4<^82;}Aybd9gjMaBzT*DOg;|l%BgT-MUj)>@QBV6eNn5u~IKOO^ z76Dyi^l389oy7cWC(i#=_IODwu9iXj)$IF=_4Rm*C|EGjh`vr`{ul56nzr#5nbhPc zJlMnd!~7c6M#GtYCUn7WUnM`hzJ_`>fkCas@$JTIG2jLhE-g$TzoEsHS^-I)c`OO|a5=uRq z(wJo|{?S1Eruh^@*Wq#0qAT0K4=BIv`$GpB1h=JgD_%(7uLCH)z37z=`%N9GYOb>X z6Wvd%`~T5()?rn2T^mPiEbPJ-JFt_MMhQ_-!2lCm>_h=YK*UD{gAx@Hl~5!E-S-v) zyA?113llJ~<2&!?Y@BsnXP$q37BlCZ`OUr7z1H6Q(FV4?iE{oM&}}r< zY&5vbQl4rh@?*+((u)+PSw8?KyF~w$=EoY_!treHJf1T{{r=jKcffKY<$P0pUekCT zhB*vV zuY@Uz`Sp-qd)bwog^K6XmBx4@d5k$f^lgvy_o=^}ofOBes5Gp|NaXJ{zwX)l7@IL< z1HuXfpHzR(Wv4PN)&4D&xbV^dVRfMvxyBzvQ_k#qBgpscRO8PsaW)H^^CP;`BlfPt!#s8kEz`3 zf6u?%f9ha59V@4FaF4tdF4c(dP?~vzd*R z`JUcB3U@J=yFMQxU7zZ2PEHzob4j&6@|Nho)A`AI2!_eEF+9EbA&Gyw|G=plH(BnT zJxFl*_x;P)N35CXix2nZ^)coD`saLh`eTe@ecZrq9j<2^@lADw{!;!w)G1}xKORFr z9icx|fBRJQMx~La{Cui<{!J4r;P_aMyZ(Y7%73Tn8*$>X6^|G=SK^QMkMiHt#ET}k zpxaf%Q~ujL*?>t+thnh2kzcna{olH+nqq*}Gt_G<_^17&F^x80^Ggdp-bB5>yw0~P zic|lf^jA33uo9C1W z{;0mT*A0Pr?nLfe(o3zrhNStk^w+kE`*T`dn23s&x_p?ksE-TCdG6--K`f%e$Gyp(%>}-}=rAU~k-;f2m#0H_4v|T-e8)iWeyMj~q@P zWm85f^Sf!#e)I`d@oOgLpJ{(6HZPey+2)JN9fUs5C;9W-8fWmqVGH-XJXw4`L;3n- z=i+pBOSL{qYlz^tHJPt6ed>d2w!?VdmtAW4J^t_(yL4)g;`x*jLpPwzTA5!B-$FKE zYYcj63jXQ*bJ*qes`)=-J~%+|Oa15f3qP=-^^PmfXUrVuiyJ?O@gd!smp{Mq^-YJK zXkzCW<@`CFB_Q0o2XP(J--WrHsYtg<^THoQar7XPxv;) zmkUo&lKe0Kk?-&0)oKGiwle2$;A$I*vh-=jW%_VzY_LrP5^^(vqJtxpD;$j_(q zysPT}=8fkS-U=sW}(_T+O-k4m3UgXs4{mjleaXn~@?eSK>L9(QuroQ!eWdQ~j=R&<}5mEO<9p;g3=N_uJM%|GhWSpsC=G>bKANjo1)r&ilrN zN!JJIKb=Z$iluo4h`cTQWj$j#|MgY93vUeLH8-3ozkhlD-ePoj{M`BrTHi(eP3O11 zKM2J1IwSbW?KDhoZBYD^D6M)=yFXpI6w-N@v(A&POkM<&Lsmy4>`r`1`F1{~rT(u#$_; zvi@;_kvxB&YCZ=xKf3bE{vvPO&K$Ep0}8&w}^?f(}Zg#TH`64|wS%KD$bDUIcFUzq+7`d&cv{oRY*7{7TE zZ!ol1`QMl8d&cri<{IXQFZ0#&t-s+OyR&+a?0g!^@3+o=@N$>?+g_ypUN`qSE3t`D zT)(vHyDt_DG~q4x34a@;{{dvtDJaErQJ7rt6p7 zw`@Y>ObdRxf_i@6&(X%S3CjB2_24En4Yc5k0)&1?5q`BlH^cCKa(=xCzwO>_gnbP& ze*cepe(mP;K)(k+W%FB6M88LBox`r1K|JPx*uRUeUkY;>j1CQ|a;I-1f1~`?HP6E3 zO`Ca_i-O+*!f%a<7HF|vwZ3_}n6HW@_4kY75Ujj1j)%?>`fWt~uU_?o*xO$=it}4N z%cfw{g!bGgOXUCdgx`RK5LPnIS>}&XewPK$fkj{!o>oKXH$C6x*o6qy`Bm$e{=lZL6*zwRmLNA6#b9dL~Gd$Ly1A9IY3M9sca`G4m&O7T&o|9tT4 zN!EVw2CQr?-p{dwU;8kv`|2v^=S8I(aFQAGakB;AUWD&b)xKnBXB|_V z4_TVO0ZB2&e7A=B`dZ((3f5;q(ccc_n=t2+8L#BzVJP0O^8Qus;kvlmQJL>s<^dS@ z&4Sz35cM_Xdqqxj_-Ey#RtureeuVFdZhq*0%am99#ii>Tk^Fr8uAUg&`X{WaiQk{j zZ~1jUfHR%vaM$i)eFUwqW3LRsm|Io&oil>(`9z=VbUuf4|IOU$w|c(oRWpN@XDyzm znv?ze{Wy{Q{E@*~?0gc)?H*2&^gW93o!);7E4if1x9;|-uy$_8r)_yE{ryRV?>C1- zS%o{QJ$C*6<%e>8_P8?#T?TaKnz5q(rhK<8iey_=dr1Dr{@hP=?EaXBCI`g@#pRc!N->o?86e-95p(O`34xxuXRcsbv5Q|sa5`5U-(Lwx@< z|Nd|;5KkN|dBHNlH_g8X7wh1PT|VOSgnv!>Hm~cC{>z5(ZnxCycl+x-QMvnfG<6jD zSuoM>*$w>AYQHf*mGwfpe+@Dp_N0kEa{R0C<7))pRKJg(*nzRtNAZ(W8kF-X?_bSU zY4758b$O=(;h*m$`W>2i0cUiA_zEre^7vLV|9i!(V776IjiP_v_Q-Vj_iD$h>=t}e z{m%NhligT3Ms_}(hOwOQ(y#Loe!4S%xn8WVNF(|8-j#cqx0kYhM=hC+wOc#zsBs4* zehNtaUH?KHV>{<7&Yvv0cM0bTgSeT)6Dgkdzq)lh!7k{pRh%#D6rF(T^Oy35h5w0o zqVKM6PO*O3zVN;w{8!o^vz(yXyEEL5*O}a2il_6Po~t=)ZmV2>*A6{{W%V}k3ateH zRNvP;d%!H7t7dG<{d3yC?s6mmF6ZU_YwDk;?|8%Ne>|Y@`^T#Q_7jMspn?WbO?4?*gLFY>rPKag( zkK7dd)9cTBV*l_iyw^ZcKhyoSpXeQ73q$5B=I2^(uj2ZHE&N=4Q9n@qZnr*#+jACD08YT3D`sZu?x1(!-9bdIvJ-=~H&$E&#{>a@S=F9Ym zf1ZEh1QtGB&GSZQOZsg@@^gRhN6Z#-eqkiu6;5^2H_p2=Qxq#Hy?u%Pt$d$*adr7@M&w3Dm+A~dgau>lb^~XOZ^})`1 zKaiOz_>Cp{yd>Bk`*s`iUcHLS?_chZ>rFO5M~%w-Qr}YP{e6Sv-z_VKqQM_W{=iH< z->?~uJG1KWv|Yl#qI?fu1oZOUz#Hg~k=_rK@6NCPW4~Q(6#cQQC#GZG#MV5pg*d-v zKFPn|S?pn_Ka57e43Xbbz6X9*^`@3~yFUp`DA~P`p1qk$NBRW{qfu#Avm+p{(t*NNZ&8zJIOeWU9Y`Xwm%5S{$F{Uj==2R zT%J{1@C~BRbNxA+`N>zd{*m(S|8@ta`q}Y8`vu?BAOBq8221<01%6EQM`2V&mOpLO z*@@sSj{MHZ7||aid=HqL&ph_;mi5PIe!kFTGk$MUo^LTKEM`|m9l+Oj;`-Dd|2$$d z9QK&k{?uq^w z&CeU`350#L39rAKOZQLtuTjU=@*{gYaMLV*t|9jk)g*!9UH<51bv0nZqjZ z#VN0(=W{3FKd|vm#Q8aLm*(pEAMaUgBh2U3RdwwOogW#Xk-@kWm zV^jRCaW`K4{$571$4|qg!E|g2Y{`Q!J(BKkpox6GrOC=LRwYB3f5)8JuwB=d?_7LF zimz!RKR-Hrfr`tj?uz>p9RBEuU6VWVphGcIJk|HevUs+#k+Qz)mF_?^hVy|7_DS(H zKaccHXIeYfDEe=bM(JVkbf3!Zo`8X8r)9raRFI_2~ z^1oQMKG}0pFtjI#_b1)|)24nQ`!z?d-<0pgW?Qg*x3Yd0Tq|WW1|3lBf7g8%1gkc~ z`0a*beFx=xoClVfpYn&YTwC59M=G=@zu|HRFwn)bm;S zur54DKb6gQQ~&$GtzEJgn7Me5@@xgj{NVaM~TtLJY}wH?fmSu6V6 z?GH~ypFujj>`b0?e^h^u@NkwGK3cIpPTnvLf!B0+%exs;d=#mVZ46@Aq|VCubvM=i z6ZX?Pajm?AQoI+@-;=h9?D+k8iurZS*d3_c!-iW0@0H@I{?31Yk}Y#o<}cr88>|v7 zdE~%(;{FMLGsDiZ)0w`Q3GsYU{hhaG7j}NN=h-bgi0f;}`&Sz--Da(|gJtK>QT@G_ zz8izqIP#n@p}*80J5~6E6^~Tb-(sEr5O!XEGb=zsTFydRq~Ch|LZy$t`>$3{edV^7yqt$$F~--3l(F)ZJVcYP%EH;Uxn zU1m2yC70`%KSg~1lyAT0TQPrz86W#iJ>RCT9dRMyDcmcH{x;=1Icp1&wwv;ZQjvdC z|2yGGUpQVagL$v7((hZzM85y-+Wp&L_rQ`j*;Oiieh_~wcZxnV?`ZJkDMEh}iT*kt z--T999r&qf^(6hI>o<(f*?g(4gln?23U;2EM|Lpt-_O+{Ojfb<)51N0sF_?mV_nY!FE7PQSKf-^<7YEtu z(QbK~V%?@a4oH;0NCTt&J5UGORt<`-@G&9CM8v4-5g)_+?I z6&;oJ)&I&iJlD72oQwLnfbeNHwJC;QyoTCe#rFfF8nOhh`@>)ywlMu)e^TOu`dd|U zIw2tJsqB0U%IA(&Tj3XN%G>nIlHzH8%!2#lMf1;?kS+MEN%$N;dmDyknsXP2Vkw^T znX%CTR+N_&2^iO^q~|90%gp)(>vd}va)*iUpXSF8csQytNB+M@Ug%$A+4G-0^)p+xeLsTki~5Jw zze64WL!D)&{B#|WA5*@yW>&(nCy9#nZ^h2x$ot^HADVWQo^PtZskQ6id2>16wEo4N z9hlh3lJ{ycPl~7ddqb}o?0;N^hpBqLV|2G-{R?A0V#Dt8_~x?Df77B1a+g2F#L?>Y zH@avmVqTf>wBzda_gL-#1n(}xy8yv=BB_5erI=Ku*Yzo*iO5=ewF*%+i%%p(#jfq$V%Z)(fP3b<94C%BU|p3*ItUJ^CcI8 zcCu>UtQ7lG_Q^AG_;@p(Ha55X{^a#}dS+W28cF{a6Ti=rBc}Ga`u|$8zrzf-Crt=inPmZ6t3p1P9a4oH9DW2xv zTbD3av|_bl{oA!?Dl~l;^8J<7*S|w7FETfMW&bOpUN}rY+VRK->g!)WgB+IMehbWF z1bw7w((j#C^tU1hA3!J@$K$W9Hx%zDdH?z3 zqGoVgbp;wJqJGsjmh1QS?c1Q^X3Fgfg?>|iYqv#L3_tS(J8z2ooa*<8XWI~a*_2PX zD)gJ?*Z&<ZQ#0#_9Jl%V9I$)aQ`6 zKB=#lR=v!A^!7!)2jcmm^>tCx2y9+x$K&>^=ez!%T-Git2>QnA`M$Ct0&^?a^M#WR zNd7hm-ycg}F|8HK`hLGG6t~=!`M%fxJIm_0AMLrgKIQw~rx;YPJD#8F8gC%@lkbm^ zI;je7I3!|7RS{47S0NU4krgTDoA#Gut|r51=o}tdImqzu->3eyM@n<_v%doEZ1sGj z+77%8H07RpVNyKpU(IjQ4a2S%Vy@P|-$y>*JvCm+qgH;wj$`nhwOLE$=a^ zg6J>mko+7Ic43mf6}M^gq5S&t{?(O7gYdE7BQ`&O#QuK1V3MC7N!^XI3O2m{Il(ve z&${|Kp!L$~d~wFVc=`H{ZwXNtcHfcrtkFe!KTy8cUER&5%&}73-(;?<2TGPV;h9My zf2Vv~Y~IKCbtgsrzB+3PzU^tib^jcbJ|A75>39AJ)4MSVfwjf^f%dOfy3WJNlg)Wt zeZjXM(eE}xQrUZtxr*zzw%^^27fY@9#zyM-{%v!HRlTX&1FN^VK3!j(eEvLw9M^H( z3jgL$8_4p%#tB#0x-Pz$tS$0C%J;F&$MJdZOm2n2(&wl1Wexj0V9mpn`R*7OiPx~> zF5?8>1%&U3x8AU=Dh>EIUqbae|Itp>`XRZ0M(4wS*7(T^zweXrP4oBYvRKr~9nZtR z3%;qpUAj;;A7-Ge-;Vw3A;<7EF1w5Ghvw&Hp&=Ol(Uf<7B<4enNc}x!rVd8=UdHVD zg74Nuzr%lQ$Jsn%UPnW{e)rDl4)eZGpuyGi9djxao~r#v`#(7+@k#kExI6%s9ZO(V zzJ6AZ@O|j|PW-xS&YjnkNbwpZKfjZ043`c+Q55%F`u+Qw$oCiPe{naiO}FAxFN^t7 zT7NIlk3z7QJs&^%-}zPY`LOf~VXU3KvOar1osDhxoA4j=h5zM6`p;8O?Pm>kDD#{C zbPAl}>+=fr1iy4X?D>bIZ1B=aaQZFY@08!#&I=LkqQmtH1;4cZzP}}n_3f<8ub1y0 ztW?&q<{Ieq@pe z9Zz>Yv_gL=UW54G%YH_o(J4Fr$w%->^*7(|9UEpM=abHVbu!+K5w+y{OZn_r>o=SH zdY>%6rhKjmio@PUF8s^*1WA7>pPs?hFnv&>;`*yzi$YcZX38Vob)@Gviul`CTxCfypfT5Vogu|jeuo6Mz`)_k{BCL#g11MEdB-Y(U#ichR;u~UUQZPL z?TyJhv8I+8-;^x)jUw}58-5PLl|LmI|6b(Z0|~!v4;x^u)@O`z7Ws8e!lzD;J*a1B z$)~jud{X_re|H}&JVx?O`9fd4h(A5uC7gA!vQnJ?ii?{CpY%o?$L~nb7oE>$onzRV z04KN)6#7K#W5?|?P#q0;!>z}qc)CBy%>@bUy2m6%f9%z?#aRAPhc`PIF2&RQdDgdd zmiuImqP|{T5r$Bezw-0n`H;k)9%g-x4R={3tB>h?h)s`FG_&{M%Q6F{>r+1azPZjO zefPmJGr=d-SBK7bSf!+m(De|%ZxosD;#Sev6Jp2vg$h2YeqQWe!h*lD$u#7*fG-w~vs>$<%71i-AH$kz!eYGYOLD|MUz@WL|-~6wD@aMI< z0Vb86QsnPr#&(z(8Sp#)Q>1t=qMuKpny;*@%wOolo%mE_qL?2~J=YUycMG7EE&MTB z{{|)P#ASO^K2lHQ#~}P|OdpE1)88ZDp!)oH)ZU$_G1QcM#J`d5pZeDiZ<^xHitnfx zE9MKSeiqIShrt9Zezu|d{J4Mb{g_eJk-zy+zCMfadCW0_nLo5t^sgdyM`QZ^s+_-M z((_68FNkP%kag5>!q95!`Rsaf7Vd6r$Uh{D^@VhPD{o;UYxQ6vg7g19Kbo@V$J}Nq zx;@t6?@tLn>HNkWw+uEpV~%3~IQoui|LLL1`nfy%JZscTSwBrHr(x8RnY{XB^?cT1 zH`#@nzHmqseCiSX{HT+HTUyikU7JDD_eb@!B&2}pEe*ou9P#<7fAw_!0aSnHz^8_Z z^;2FX|NZi$lpVS%=a=Tcm=}(5nR0#$2)|QbX+SGbSzoifw9qUyLD8Q+s~d`I+>kf9 z)Kq$YseVq`*${CTPs#i%s-F#uw`14)p?uRocPXCon_9Uwx>mZ3a4V7jQvYgj!*Hy( zvf#A~BBgk$pAC)m@MBLto*fnQRdhbnRf~uJZ+hvkTeZ_nR%z*LnU?2s~oLqaW8%>t8L69)*5BRk_vX z2U5Hr=|3gbIDi;;2mT{mJ>M^9MY8YHEfvpa?Nw(CR(Gq)+w~QEYmof-QC2K_+`&n) zKNU549y-ix#Aj7Wk?xPqU;iGKq?+%TfZo-_^G);PjGuFGYDYs}b5DpApGN9ir^}hl zM|B42BWv+~q5a|CR#E7*){2kLRbSusRn3iFIl1|ML0F=;bkZXXe1& zMhd>EKF6khU=MrK$R-Pa~xK zS%b`nB*oOgp3Mo0^C2V4cH#aeV{SFGxuH7!UV5<+%r-0Y?{suK%w7!USG6Wf@sxiL zqc$i`zJ$#K1pl=D?Ynyq-t0Ez`7OlyXS)BGah2YPxs;E?z18b?LXF+{ctEv(%UAXN zsrSE!AY|lQe5onczft~+Rs3GMVa08Gi~S3tNc}tMn>jYM{tn;ALceK#?OS^v?tQc6 zdS691gtpO*f<2HBrz-h)GIebPup|9bBAxd^|}fUmU>`cC`PomM2U&|~9pb%*%Bs^2)eAE2<-a}1vYqC$V|J*J!0SFRpxF>bEW4`o2-9sXdQ#zhN}60Yr!|IufNRL%WlS4;QK70uXO%8tT2wfb{(nc zPjA^X4{h}t@Zb}oey02$c%Q&D_l`we_zuzll=g-jkxYThU3MyIi_m@1S>(lx;c->vLy@ro${RExgx-j+y^Ij69I3Inf z%MmmzbK(OJ#;NTemD+x0mqzZC?H@$z;~__*u;;X#PpZGk+bd!`kB0qr@%vE!%H3`c z%$ghVv+vdKAG9vG7805%=ijg0cA@1-eLgs;iS&Ha`uSv56AUQJl=;sz|K4&p1Yfrf z=0iIOKB<4T_>nGrJ71NpU$!TFZuznR@dp}mqxbWr>w6JCYrN@$MFEddG)_IAyip`> zUl_)%x1N{cDW93e`tUD)4aY8GeN!6Yvtw)&Mym3cIloG!cv?SqsAhvjZGT|qh!^ZH z|7nEJnxCSvZi^M)moMsP>OaR+9fj_w$XoXo{htD&zfV@H_IB-N$G6N7d{X@#@GhFg z-?UKdFV&gig3G#9`TE;Tx<8tK`?Wp7F6b!pYk7An8kE-L3tAnP;wisw+DUADr?F`5 zrk>yDg=3)QR*6?+zEXSv$-f&n=j_{^*^2$+*zH%?iJ}!UeWm@Q-)ACFCB=ki8qX4+ zkND4RJKtxgO1%~5ub=fjh{bh>^T$JVrFfcOZ~j=s_6!ZeJO`0qQ~k|el7#mM#&YM# zc!_T#Qa^iE`pQxo$?Ipzch-PtwErmQoBGrCCo5r4cC?~D?KWx`vT6dI%2i5ss!&Ui1 z&?WWx_1L7Lm^rHmogcoHe%~8}?|fDNc6~iF9%Ui=O9e!K+Xq;oZI3Vb^HI!a()CY{ z^Y){^>ikT%R_gWFDBl^=epTXImx=iey8h|S*xF5rlD*>O&)s0P5S!<#J}EF_ZrLCCFh&!b4lk&^xtC4 zZ98~K@ic$_6`jMLr+drvIhf?n_RV84YMw1$^R9jQ=abjZ^8;V8*_z7vby>+#_-`1= zcfA(-_fo#AWqe~!xuJ^n^SX}v5I9qrZ^xj@c;gYR=x;yh8iB#%jAZK@>G_Z5fpu_j zYrJB9ZNVb2zLqgRds^^K^Xr-R_OKh6UO!~l;Smre|EX*0YoKP z@@>0?e$)JVcG7sn?x@UbC+AA>)IWQqdjy_i9e75FdcH$+4lwwItB{PvV>RZyXyGT+ry{#ul~0e{w3 z3_l3{rS&sZ{ZsE6LwNfpjSc_uLG$yLmO6-;kg3?;a$FdJ1K$n!?~&7`cx_|3e*bvU z1scDvBJz@WzUcal9&4h}^MNUEWD+68)B1Vvk$#x?Ef0nU;`!1rkM5Mut4k zUp?O!XBomV{RQ5i68cU3v2UsS@nw@aPm2?LQ~my&WsLN|SLpX$+ za`#JuZimQ2!c^{aisP8qec;La5n%udAyA-KRL#XCy&2Ow*EX79=zEi6{WQ&5makA`}^zU?j~D6p{+I^I?+dmZffiThKW=(4J3N20;`*(ZZV4!BX3u|}7ydcre|_aYY?7^9|LOTW zwf3iAONz6Me+|cU`cM7yOaApRqVT9<{l3a6 z66v*+`5!vD6>@b>VQM|WFXjJIaU`yv)#ql@rWuO-L9YM3c63McFITa({QXDQPrnO~ zL+^#wyu+7$Qat7V)Yk#HYMqBgHP!Q<8xe(+9R_^wO7;4GW2_Ns4t<7xnXjei<0aw0 zQ_ewD>SV$7etsywe|diIzSR+XbHCw@kMQRx|5NrJ!e(H*c28LGFnmpZ>j1R1J(X6ho%btqey-~(Eb8j z8|VS23gY>p{qg5XGqCt|H6C0?@K5#sXU1(dwToQ;sef1aJ`UDhtoR3i!9UgihK2>K z;Jr7D?S+2P{`g27!76JT{^gqb`u<$EQr6KyS^szRK8{rdj{Mjl;m=1A|IU4p25xr_ zRh(ZN>6wb-g=1v=8xj5&&#w-jOgaBl|1YTaXSF(Oz)OA!{xyu{>pRZ=S09THDf55a zJPHizkxfvvH&I1?Rp#P3J>zq}(7O|J~$x2@IJ_l75W;B)9zMg6a)tJ1$| zRy^BLJ^vHm4aD|{T$t|^`jbQSzh~Y7wCbkXKf(RH#4pwV(@P9-!LAS;DvSP?HmUD# zT#3iAN+7m<{P?13I6?v{oxfGbL*vlr|UPj zUC(BwyFC=^`wk=A5Y(#@@4kPu6z@gy|LFtoviPRU75)2l=MJO)QA-{>Q1DOvy|f<% z?9nW59NO`({*lke44f5@uV-!ey2&E{FCh8F#M|@)ZaTZr46QS&cx|o;`3Af8+_c0!+rGmabuzX zAo>5Zgr2Z4x{CSL#ruQS|J%%#ORH0eLkxG`dBIdr~du@f;cw+m6_uH zWrmeq5%%*BdJRpL?vLvKWw%7;X>E)DYKZv-n*VoSHv_l#SK-!A_e=3~|D-R=Q`sdi zC(LXozJJR9fMetF-t#vC_pg)U>3m$Dn2W5+=9%~%D4rh;W4XU~{r6o^ z_Jsd2s&#F1W0xuB|66Jwh5I~9e$`m;Z$$F{qc@+h_hY^B^^$u2tEl{!(YLJl^2$R0 zY5kwnvV{3B_ebI%@&2Ue`z&vF9N{bM_{`@b|EK#W`RHn5S!RgL->3ZN*fCVt?y9K& zcWi6GYqVVdDgS*P4L-GEQ=l|0(^iVJ93WCx^Jmvr7wUt%r?e}v_hnJMP~R~t`6nyv<~lO*_$CH23bQxc0w zvw`Vh(I27w=MJ5OTGupqdTF?Hf5V9W+b&IGR&Pc^=YshDDgWWj1;x95p~fV^Kh6Ii z-p^)NGp3=!Wij7K`PW_OjvEIw`Hw{P{J(j6pXpX!hCAi+`!xUW@3;Z!cFnk-^-$^l zDgW-vo-xm%-q`zG@DDN{Ym$+GWlvP|6_$d34P$wK&+WoTwzX;?esmPiFV+7!$CL3T z)Q+$3t6u-dX;nmlznp(MKi6*KG*q5dNya~||IZlL#H==Q{%QW->)Udy2&uzACCo7R z%OBs$0rx5ELQOhlJ||5X2ns%D33d>_n> zJBa+B&gblTq^H_n=d$d4PTJoq?GT6U%T?!dw}>?Sd;gUGh;@UY-{LNoP8Rd+RR2>Z zB*9sgzbz}eF2!q*^(}2PhGDwq6SNE${k`@?|8vrlpw-=$_j3{adlCLMr`zMBM+vTK zJeHoX_N2dO={Xy(ZdT=CiR$^UQ-1=UwfY11q?=Ma<$t2~UA#KCh}-qF68@i|-2b;< zeU$Y~R_1@|R#&uL^Ap?poRI!L2>)rR$Jo?EHdyvX@K5W1o0CrHGV22_-rO$YjpX~6 z`uL}_Kl4W7zfJ1-4>Ov8Yi7#)p9{Fa4o-E)`^Dn=l>ceE)6p}zB6mp?`9IbF8iBd2 z#jB-?{(ph{M$EHn#;2@P&wpjR7p(eVZ|v$P_@(uKf=3bxx?A&@Ou@eq$^T~_`OKPZ z4wU(Sbp6Zi+9%M`X#|g+D)gWB_dEZnh}Y9X6zl&f4`VR9gMlLd%%m3TeveX|->EWi zHSSty^C~SoB>t)YSGJ)snjKZ`@%%`<|0w?+U1QOAzaih+LC5eff7Ji)eZ4*2Ue8d> z|9$T5!=~iHT&IP4{GLt1F16uKQ`Pf7@WdEw zyHN(sA(yK zH)6w4w%=$NzOEC$AMNj_pC5y>)jwg)*aYeR{0RTiS;tuqI~z>6Ecm1R*BO6OwZE?; z*40+e_w>+7sI2)LbzTX5r|ZL`Kb&Jv@+YF!3lXnP^7|CeX{!BK|F5+Q>EXw2M`o3xOSC%w4 zP}bk0d{6o>1=_1d@S7(E-?Y9@j;aLyX9v196!k6D_bC--qHdPT|5g1b^iAI1^LG`hK};{X;?(OTKBh`ug5>_ zc&a^L`c*x@o~pBTM#jkbO(g!^ipwcDkU4_a87Jm*G)Vsb!z7-~-(w1+pQ8Up`E~9w z3WIG*;MVbo^n8{QexEN$W`=>*c+f@gOY`@HA}751QH;m+wn_2YB!7Q!`6Qco)BzKk ze3Jg1=I>j-xntamKXA|z{(Uy_?@LFWV;|PJB6F9>zbM~DYdvrvtRl~JNH8m}%?<)N3(`Z!=F(>)#b@sf>oIGY*vc_g9?{p?zbyepCP6 z{b6nBxkM?>*IT44#@?dpyr<(NNx!LoKV@@Mc)A>s_3x;DAGcnDlEGSh%gsV5-iYMy z7ix7xf1eCR|Gq%wA6&ROgx}W^{vDmq+y0|B8oX3}$L0Gk()Df4<{UwVKx2NOotWRD z`t9;_2)b9ijf|&a{R-uKokbEtf17j7tLpW;mYyx%_I{4HSKmp$FV*ixJv?!5Wi@{F z=Rw22?>7ySzkk?oi?%7xReOxymE!6APK}gw_$`+6?`0^j-@C4KLyJMb;d@Ht?{t1= zU;Q-XM~>iAmkIuv^O`G^RE5Gme>@Sn6ZgI&{b!0>RvFXex`?Nq#3@&}E72>+hW=br0wjxC8B zk2MA2_oMmy#0LxU#IhiT$=?%dePe-{{%BKA# zE9>{0p=X-RY zPRN~-fulXe_e=FVFLDt|hgIWoIvoxF@al1F~V+>fifOKA%&ZvmO=~>T+A3 zxl+6a@#h-Gs@9+PyoD@%@qAFe+q)z}Q+0m0*~*LM*O%w#c{Qz}*SruxxuQO&{rPcy z$HMK`do=Yalzv~De}_Lij-*+Zy!8aJKGlfqk9>RJWN5$rjsWxPQhYbEer@T_QcSC| zf$x~@TAshl>+ha>;#vN0BMdbV{x8+UEmY5MY2FD|PtywbUWxuC{$h)t2gveox<2N4{3$d#J_%p&0s6mu zx$zO!AseQk5z z8C&kY!{p-sqY0n$-Bq;O7V2QcHY+OEF;4mmCApA zs?U%73RtVLOBDUHl8Ey-@p>%J`6B*4NdDc*`yH!mqpZL2CWE`Krz@F;vfY^KVsgy~hq1m-mlpeSLV*d@Ovatk1rzE}ULQ z%I4=N-yuD`;2T|2rq7h`+V7iVa^u5T+*>ha^Ot7})aKvL9lM}S z!bzEbPS?M!NcD!Jw>Gbu(92NDU&;J@KtMn2>u~`N+JbLdU-x`@6!upQc<9bo5*Ao% zy{vym{qv${Ct&v4?0@IqN%3AJ|IY2Eflo^UWd1qj|9lF=mRD3YK1tIijRu)B_7FV*XN?utaTtzsnGpV5f$-?E(zmREg* zX#p>!-Sqakruy#q)*kn>3UPCV z;D0Ca-#izju?uzg1pl;uKC$=|E7Kp2ajV7t0F?ia6Ww8) zT!y6l>fMc^Kfic1z!ETlN3+$cP}&5dpC5ktp29{`aavs zXqq^lxA)j6#cLbO`S+Mv$|gTwr^x@CPbv5>*^IyT7yK6x{u7EcP-vsf|IL|;(Q8*F zzP!oU(|@0Tn%^%@td5e4+ZFYHo4F^v7bxq0hFg8u4~tav*Wc>-pd_a@?_Mxd;-B`< zj%;p$hQ@K&y;<;YPx#MyzY4G8s_|oK>iG{_*yC@=C-{aNiuzuD{z;&dF)Uu+z}Ff=f9U#|`PGi2 z3k+`yo#03H~P${V%aO32%GV{PomtQhWj7Kk$h?EYb_{ddY3+ z`J(xKQQtI-t!*JY|AglE&m8SAqj~`rX`L*Om+zn6I^Yt1Js!vH(N8V^uD=sm&uo2M zoFKkG%74cfBhV)I5f(p+lKy@o;XiatI=h=;j_?`k`PU5}hwC$5LvPwvDPD)v?={L! zGhJ?r8;0unzwbT`PSsWCM`)~-;%k!n{oS~tIkJjrau2~l<5WY>RP;P zRge@PMfAVvP&-)ldyMN7MgBjG@c->=2J$ys@s?WOrFhDJt+!5?H{uy?cfTh+pVYsr z_3I?qT1!69O`LB=`Cs|c4y}qGWBVla`XBh;FU!NzcC#(eIn31F$|N3tOrR{h|78oWBkY zdus8HuiVSy<@^qEGe*=I)%qE2k-yXR?{AJLqH@Kde3J8-@_4zw9zV?r3#{+q>+}NY z_gO~x^_+Yf2ZOD7(EcA%Jcxd0v~$MSug{ULl_SM>Bl-J(-_j9UV8(C8tIyv{me@h- z^h0#KA?8y{N&a4~)*rk`*vOZBo2-`Km9EEG?oxdm*ekw2s^6_k?cf#j0AG$rO7}8YWcfSw-)nqXjDnXH_?>{!Qv4*s?-0)-wttnJUz)$4+c!U51M* zD)J_}&T9E>yQ(H0PTek>f2aCA7pJgwzNKtFhOU1PaczW4cOzu}9j)IdWS_#vWvcTV zv-eB+yAk1g;qz8#SQLu~TLs_2gm2T{Uby0+n%~}*FU5Ni{ciWQ2U^}v!^Xkl`)f_+ z-#5)nhQ>AnZvSGIq0nD>{a(FbAo8rTFyW@~kMzj?Ht~no<5^WL?o_6p|CP^;;db*1 zMq7#gH|2lZ>Qv0RZOnZmvZd=&{a#(e0k>~H#IV33>G!4ed+SFGsfVq3>*hbDc&guv zRr;Owx&U4N6Zt#spATAm5|7G;@qK*-|6Zj3Hsp&v=43v^t(s}l^)*QUEqT&KtW0y_ zFI{^{{L}dvm!HSkqmZGfmn*(M%D>k&2fV%e03r3&>-Xqa8SM76VF>A{p8vLIT=1V= z5mFln{njJ-d&i_REc}lRwog!>zt6cf9Y#eT@aWP?>GRR`FOKUTusMIGD(3GOt}a90 zv6?(Fbc_^F=U;nVe95l7^2Cl@@%&N#+gH7eunZ?Y{h@mPk8b(Q=5=< z>sAu_ZAAFbY+4DX9{zY;e*Q7l@A@NFA~v=nx6Ts$dy(~TuJ*MMU3a_8zoY*B6PLzl zy-S&Iz5WZ)@zO6$eq%53sX_Q|Z`KA8-(zvIj;POf62A9L>4~EAsTkZ@`1kgN-(|k4 z-r->#ZavUMdj6??KUp>yS#DXf`rC-`8}=(1GxqEATX(|BkyMC9L; z-{EmSI8~tr*K86j#nbwGP~G8(d3+D%2Sopy&aaQPK7kvb^m+XLw^BUiH)EGGtUf)F z&A-t7srpaNfZMoXyw7*Be+A9I8@zGA`%)h;(v)B<| z8`Nwg`1LZS}WD0Kso8 z(eH$Xui5+;o-+T9`tPTT&g0! zgA`Bs9hg=LRqFYp)`x%Z54nD8A6|hL?wb73r_qvrQ+_-3s*Q}d+Z5;Dl6KF4$B*~; z-&ZQ>AKBl%OYbK5h*hS)?oayK7$8F;`yce z-NGydqayUVZ)M@X(f-?^|4h+y@nw9U^j7+PT9f^&ZoB!yJ4=gStS0!^AoaJ#NL%D= zxdR8^d?}vl_loMO&*ovkkNdroK0nRheK7`ho&~6(+DGB<_e0Mw)UZ8`x?j!s4QKW9 zGY69F5z;&tDVt76@l?OL#TDrKIPu(LLcgj1{@ddOd*nU@bxK72O!d2L_$UO9d?@qZ zsQ+GAn#nqJHic`w@xbm0s=aV zW`XqiXOsFo`cx_!T+-)l>IuH1NPWH`ay(q~o}j+fJt?00>#c6BL)Ru%_^Rt!<)2?Z z-<}`zs*& zUg6p))_%JQYMZO)dsc_>Sa+xZdwl|>_+^CesfW+Aus9pc`YQCD_ScrF&VT4|^Al`t zuaV-liN06#%V%~Sr=q&H=r7ay+<(h5Xx#XX4?9On@lizIOFFz`B`rJ^{k0KSybx8r z65sD4_|_x-`ptSj*vTX>MSs1vo);F*tjJS(=1KajLGttZTdQEx$4#>SI<3#$*RR30 zMVfrtVd1Y)z9-$UgDs1<$?|hrpZ{4q3of(e`aX&9?eVH9=4Xd1@|_*vjVpOoxcU1D zlD^aa`d#O?=r%V7^UXzn+mGb$!#)A=*UY$M|MrH0U%9?}Pw0(G4^m|OdlCL!RcGV; z9#oBQ`ainPJgla!{o|<&5sESondfAP&~PLbi9%+HicHBAB901`Df5&{N#-GA#QrXl z1|>6@A}KOuDjNLGbJ?qR-@of@|2)@w_1()1ZR=ENFXg}Q(l-@ z_g-bfoJsQfoo!zoSI&pX_Qx5WR^oDnCOhzq$JdnKbr z`F)<&1U6gb`7Kzz0jO4&DU;`j{A!T-5}MQ6;PHq<@bpp7uTkL**m~RjH(yhH|7d<~ zR{vfo_PKz@=eT}Te&-vRo0IVod}=kyAC4{>afQJoKGd`e_1=%4!1PY(eWYI zXB)!j`YV?aVqnRdw&eY93gUkUGDqB*e-|G+z7W4(Iv?7m!xi)huw)Bk)blz1(|D|Y z_yU7l-xKY>5uwT1 z-<@}zo!28e#e{GIM9yW>>exfP4nlz$J?O0Lo7}W<^K8qi@yy5(aBAl z#m#*#+Ec!lR`kM#WL1s23;+JZh(6CQ3xKn|HcM;Ae;?@l=tU{!$T)Nj`BgaoH2>DS z?KMgcBdxf9Al2vSTwCmXmV!lRK8WA13E@9wMk2Zlwq$`(>iO@P;EcVu@1ti0 z*Jlir?k^p_LxA8nkc~_HCa$kX^tpMhHRwO78tYf*fBG-=zh`V4iIT$)p#LadyuKPF zKYlGg06x96S;_P4xiH6Ls5O8svd zUmsnin$KPo4t;0-`$qZJv2Bkw!Xeap$n$4W#J?V*9Rwc_ZPxk*=a=@ccqR5mEyZ~} zuG~LM^JmYh?ZeF_P1%b{JbzC6R~&{|BKQ6^%-YJ|Pntiw*+W(TyJErq4v46Hzoq;p z>Dgm>bPDQR=lnJz{4So9h(mei?BEj47uE0ki=A+|_FYW!85XTOAbvj0pS9fw;lV*G)fp`6 z`L24$4eL(5!o(};e@B_%AYPw>_}3wt z--V>~`Lg-(Q>y&dyHo|6FnzvguO#|x?WckF$5zSm+t*NuM{g>i{p5kjuMyE_=UX~x z*-+m9Zu~J2?t`@0S^Ej1J)Q5|*seZUsJuQ;^+5l|%Z| z_r16U&6le4PbYAFru{2{Cp#kjQ5@F1=K4zG=e+j&;OEwaU4O4(^-muu--}fHONPXp z!^P46tB*_PyZ?PC;8>0&yHSPrw}AAwoIh#~?}RI8_nYTm^oW06FBr()V#T&=tM5-U z{px@jg=uJ>`APhKX@BbIg`@Dn;~oxo=K7mM^tZ!+jjHo?bXoGf)8hTn{CDSO;}KNt z34AwYh@VgE*T)a*zF`EB&5A?TO#$psXiB+ zYmRHh`|#06J>On4QgE?{Eo=0b_pjuT`nI=jXUy$-ShBy=jp+9t)o({GYr=BetBCKf zg7mLkYu^Xk+MYv`?_B?P6aV|?hYjdHxfW}8$++_Um*&SN54V7Z*%jQ2;O`&xzq`G3 z!1;(&+}z6JYs&9Ehif?6)0~wIQLoQm&W^^qiTBWW2Irg3cgSDA3BkX0*}Q#c#OqU% z{P$d&G1!-XA4A`yitn$2^rxNqvj(e`+H6HTp8uwNrw$p1LHQ5SIfnC1^Itndv+&ts zID6LFSmawt=Cfs9xhyoZ?2GQ7dH$N}^Bw=OSnhitSBv+F*GKbTz6Y-hg&I=6>Hg7~ zjizDD%NMv?x?Z&JO8C}YmMtuFAA_)0-2bET^|1y^&|>K~c>-|!+w*G;(`?&v2>sxtuehQ2F%JV(Ydo5mn&|>MaoNub%{+gNy?YK%d{~Z*h zL{9%Q+%>x|>aUXUtv^t8{`VnyzWsl!#a?f1_UP#((OyC7TXTvH;Agy5Hvhe5+hX)7 zlh(I#xzk8XEumSNJCdwfYTa?G|#rLHJ(ywKK+Di-X%D{`)}r zo>3!-)U#(}e9J2DPr5&R|4J7;QQk$H54XhYqw`l!`>sJzu_kNTlk0a5(eLOf6A-BC ze=Sh({2ARpy0Y^-e0e^Vh1axF>wlk^a7B2%vk#VfspmW9>v){^e1H|N!^P_>A@TLN z^EZT!S1cv^P5BNin}*YUUZCMk&NtQX!mww;j8Ye*Lp|RI=Ptu}!|yQNvr1fFN%VW= zjRK+elW7wDrvCYl)+;bA;U}&e@%$O(+w<`+!7IzYK@*@l<>r&;4^+-yYWH2JUyYWOa&fiPul# zZtxTDK?X|(7fJC+5WRO^#ZVGTPZA^ zxjs|>JK?S_(v9W$JszHh{I7#pi`OwCzf_-d;v3+2;ucwbE=^d1?_0j$Kjr$z53O(g zb#00GmV426FOP5C2*2O<2cqK^)%=|I>iK=3(+#7?#;JO|xIRY_e&;=o!qxRn+44Be z%J)ZFpPu}qFP`O{!TMsJKldU2_p3`c(ACa@jh?QaUmvYOxVS43ivqd+xRLl;W8DpW zYhb}#b2z^_M4z{u9)Z74QxKNK^_k|+n&{p@qbPIM^04~+_in@Sc>LwAB>$a4^t;cm zAO!5tU^Njf-hU49&o?N>sQmvsnCzS^zJJ<;-;LvgG4#0>d)|cet1(cTKXdCa2BVtX zLErPIM0{QHYA4Dv7Ttzt=K@ zu-?8L=?h&%d%FK4!K_qxwrQShe_8vy0NjiIjn^lei}rN?=By-bJnii-d;Za#w|CLD zy*h-lvpdLmkeq28o}SOzaNZzEXZ^{M^-k8;+^YkKY;lvC==6>hs|j zW>{o@8qMcd_74$#E?hDQXFV<>*pvVMQ~&w$(qv=}v|xu;Mq2&jhx*S;w>qM8^(5>} z&KK{04yj-5x|W3A;qv^Rx-bc|m)t|ZfY+iu&5t!}u@2pzXt29mIKK*_zd>ilp?Y*C zDqOk#g4C~C?;eNyA(dlYiS`N-AM3yTBs6oE=X0`V2%6lh!cI1uDB4p#BbJp3zWwF-bXA=_8hGtD zs+Dj)>Hf@IRe$#S!Tz%OuNpBgap=cLHt}~4aednVxwK|o^axppxT^p252X7$&Q(#J zz2i8LrA>_%`K0}0Z;KnjwkS-t{`{n|s(xotAn~uilKj`7g{|@H(;gJL^Y~an^mkN5 zIy}B8*qM6KB7cDqW-Hz{XF8+R^Ia|52^nv1;+5kE z@%y3uC3a74BF}dKyERO`KG!)h0k3-9!IoMtMSH5xPY$lb$F&-)uLtLw>hs%)s`FIp3EE-}=h~(X#Vzd}^B@-apmnAra$nO?5uomv>yB4M_h<*7h|pX{Va8aDnqr z`@hS+3c`li-gq0SUZ3}#nv4bqv(RD?*XII~AA5Y|uHfb|82(*L#rvoHpRo5r!2WEB zK7So3J)guf`L)o-f3&PVhiiWkG=8|r_Lro)ra|Fr$r_bJiR){S`Ne$;%Y`<7ye085 z?H_C0JqYLTlweml=bQF-pERk4c{^9g`p?6&>#EMCUMIAhMs^_=c#fcb~nu!UYUWo4x?JtST3`P>uVAVfyel{-T#}wrEfJ4a{JI zK{Zpn3*q`p{cF3MQ&6h%uPrh-zcjyf#Ne?|`<*?^E6<0DQb_k_)$yB&LW67^ufzRo zIv;7KMy{}}#%S66_B`8_=o_G#uUvhFcz+sXzQT==ufp6DZnFOMannG=Hvft2)gwfE z1>xIq#9tv|nYYBhrui@5y+P=9sTi+}Ip0*j-!-g`GS?Nd`E9$pSuh!E%~mYq`#-3D z?~B#Lm!|UiJvwbSdS0xn&9C<<#@v)zTJeT@q9?9(aD0>UY^xB`!Stg7G>ImG8f_zwG0!QP8@36OX@h z{igZtKl!TjDGm={g{^pgo9^E*Ju(S1nq}h5R`vY1SM?t3JoOh)`qc@kv%y>wMTA`czsmAn?*elHkaGO$DaG2l>da5({Us4A^gV& zi}rNB%E0Mwg-#zv$@=fpN|$3(`g@G<jal_qPTz_bM{cDg0YH52* z>Q|KS8|7yOLsV2)D3j&*7y+G}V?&mUR7 zSr1E$)?#iLx2NX^)yZ??-JslJE;0U z^=oLsK~d1#Mf>fJz*UbE17>x_h+`rd8pd^Vav*UbhP66 zBWZlyyTlx^qfepZZtkB)k@#Bk*BTt#QSx7WB-+#b*}}Dhk!5oc9a2Aw&zHvEgLN~} zv6~g^+aOxBr}1}+xeFeueDJwr3q^aHKl9&|hTJa$Sf|VC`F@z?ih?Vd*u3qfXixLs zw{n9~s$GHpefjz{|LynQ70LH9F^F-#Y5puQW-VeK|Hk^j%i{G@zDFxPk@MvNo;zF+ z*QfQXW%?mV9$x_yaK04-rS+?z2T6jPiz#kY?w_IhzSG$i7qf1|x*g}6=FfaTJ{7tq z*<ezSI8jiq=&y|La`Y{Nk0()nnqpH;D8zdJDXeI z+GPKwu}&x&j;TQU3BEp!zd!77#nHMMlKdL2PakL>it!sNP}Sv{xW0n)r`RXBLSd4D zH$^=EM*a7imZ4aFu>$(DvibEB{Z71nQ#e)B8!kJ3h}Tc~UNUnEPE5HCO+C(c4vD`t z(zAs>?d&nOqk6tyEuVuAqo1J3Zk~Um{`>Yb?}V>4M#=i`IO+%Y;dyZITO?ke3E{i< z*dM~vped60obuf_JP6w(z9DAvaM7ODudhc`fl>RplKDt9K949`i>=AY62lWQTW{@r!2vEaL{LCt)3^opOo)5i*1p( z{yZ`rdH)FId-;buxYpB>)xUK>wAUbfA9Wdnclt@l{qtV@{^|LjJ>L6a^}0M&jI>C! zS6WH=E_)J!@Lpx8y^Vi9<#*o6DM*UAjjMx_#m}ewYFT(A<;znX?{-D}yMpwOJWmKk zjXULdURJ5Ugimutsvx}SBbk4sQ2h5@^MCsaT+wAq8rl}^5{`m- zAL?J5XU)Z)W=}BgsCqsdzRDMDR5=d0{;?qg(@}cPj0yd3^7|wEvo`GfDGcc*<&*l? zEzSj@q{oBKkTkc@y4VtHOTPcWe}gpGn|GW)4btDKSJe{V zRp#Nf&p7mC zsAy01)qJ`OzI|kp`W5w`GwO%J=7*~PpmYsipXh6y4z93!oeDNBTl{|M{*A$lUcpe$ zfqfgQsrYyO3KAdd=(-{yB^5ujZix1j&qJLyVBNI}3^EY-^^^EmYlSz?UV4IcvoDMG zK7`*@_3j9*zV=6mZ@Kt)%4gZgsTejZ9oAX9#lKTNjTgTV5C3%e5L z$mXvvsW#}?p8AQM&A2{N{(Pfr!eWG&=qavG{okW6>*JgM8uwp1s_Eqoy&J|kV%ZSag_2XalRsn~Oyo-6y%-N?<&M(!^Ve9O0&gdL&b>;ps&2LTi4MgKfpD-s-J-_|hj>TWI>*(NL zz~2v2e_qil6t2^Mqs}DGFYVtn`{Ro54yowfkn>CD2k*BCMTb4Vp*NlH@1pv8tJxH^ zot+Ao8=POd|H}7lD89`7gZx&B;`5{N@71I^=q@}&!*-X%>z_pGQwQsALV%S98~*#b zXrDv$x5u`-!l2g!(4rI9AIi6)(=^-^(hwNN`3CWi?*_jV7Ot|Bjei3>&B5Ob_o1-k zeAE1vU3XP~W|6b12G7^0_306Bm*89fmuOVSTf9Fyf2_StiSQy!p8rQiYY=tjv&#Q) z5bbIFd-b3eTGf~%>mOH548gPSzwpMmg=nuJ`g^8#Etu_ECL8}Y>Q^5dN&`{q&-IP^ zzc&ZRBCnGHD>hKicYa+XG+VhDNlu(kr-9Y~6I=0L-qsaZJogR$`=9^#qWxc0y}RJ| z$vxQDh}%>Dc-GlvXrBEFJLYo#n9d)1RjUvDdd0}j2Oh1eZMUq@VYgBXxqnUc`Iyr{ z#5kV7yA!;AMfv{n`Yy6Nn6r;HIp0*D>m0VnvNvb(*pl;2^*LEH2v<&jRGnX`p6|qn z@z~q&28Mp%{xQ|(jvLqGk?9|-)mkg^LG#yFetDqOIs>_QDSrQ7Nq=W{&GqOt>^Ful z<$P0p-g(ItwntTGv`@V*+Ec!(SKoxOhbk~FLcKnZJ>r4A<+rirEze&E6McS`v;pxR zWs>|g<=gG_Jz?<{dA^?%c%XJ#I$G`J@voBb9k=h5a9iI_Hh*p7HVgT2Sr{F>R=htN z|3)4v6c(g8%j&oLiUsJA^B8Xr%nidL^>#%l05rXy(uYA7s zMK=EX&&&SW=;t#Vs}Jzs7wTX8hrC6n#SW}#Xn<%>`A*T$#c;c2vi^1CRYQCkzD6~p z?|+{!&0kGb^-EK{(r7$9#DAY?{QG)^0z)SsL!#49@%hmB*7Cq! z^gg1)Ud5VN{kuNOZ} z9z6e}B=d;|o{xR4j|WzDQPudvdH(7W;WsyJJ;vvk;7(iKKSJ}ljr3oKe$vL;TJn5a*4~IWUcWJVsF8Sml+V+*b#e9A zQrY~}wU1%YX{Esi9eq~GpEUox?_2|TTC72^z@IPmzt2tCjA}vU_}}~?%J0^tMu>j3 z5si0Lh}Y*s_?>zy0GBQEW%+HsuN(YU>_PTKuFur}?xR?Rp~qfh@_zOF*39UOFRP+a zIFj>AyX@6K1M+Giv9mVi8-rqp^-r3AJ$-G+DF;?^3$-1h-+~j=hv#&=LD;KRo*%u21=1 zaKQ~5jwPeO`HA@aHAsH?Ta6?5G~bZjsKF|)U%G#?!4Nmq?5t#bKE?T__2qzZZ*lMS z5H@OdqssVOy8mKKr|G!0A|0EIxjxhW(DR!&;6rE$zL{{ojY$1z^_d64UZFp%-|_c{ z@?E;s3yR*i5#_yCygyohs$%j+xUkz+HoornWHu((zXQ)->iJ&2Agvsfxye=d#*gIh&8>>Fl_{3}WS_S2OOp{Xs;f7zGkh$$P$+GNLy z_B211yQd{Swc3F6*F3)#M))86S&4RDQvaOhuSab&2JH5r?hO9?^+ zcbtD(f3Dxz4Ekpez-TpJUrGAQPBzbl=S({`yI&Xa{ipfsRsI7pDEA0nX!H6At zPicI;{e(NN<=;Z18a%$%C4B$gRfyl&!`b`0RV(?F@;!dcRP1|t6DPKFzG?s1*J*jc zj3MlX6X!dM)Sn(5_rmv~w=t#L8S(m06a7woz5%5Zi=nsfk@$S5|9!phBVpdR{_xt! z^@Z}?YV=H$N2WvBkMr$D{BQ04xx&?9@_gS~ITuf@?_jw-_rGa;y{yU?!FjurY<#VV z-GuigD*wZb+xI5@V|{hXg}e7A!Rsi$e(HahEUAW(XJ^UwhZVfsj491ZaU-vl`247T zyVR?L6(vg~@w3Ljs{c8=;=iBu8X@;W5VR|wAB~@W8sR8TJ zpbh7P@_D(|YB-p`#(&GH^RF-V><*p0-IzC6J)foH_v53p4!hP-{rOqZJI(O9!2#HO z{v+N$<+Hxg8=M(4m>r7e`b_!kq_oEDt4Hv@3+I#8kK>Xz!gEnEoI_iR@1K(7x6{54 zMR@ZwC^X`H()yC#hhQ`*`HZ+tj-oxyZ*NqL!{!JcBs`K9|aymJfj@|h!hH-+;{^J7DlQ(>8&gu;gq*Qfjre*X^d1BbAM zQR?|MJvjp@-P0ugH|^iP(?1N!iKV!Dh{q3lM4vk~eJs@S>5uh8`TI}#ol$ir>J+CU zpg;G&X@0C+)xXv6*I-$F4omfh->*#Ub>{q0|NHflufqJKnxqn0ZL%t+!LFvgdOg-|H>oeIOc|oT!Y!3z@{Rw~m)IT>7jF32T zJwEs6d@G6m8oLJJ`@%d4-?TopzMl!IT-`14zv+B2*8KBne4M&kb@swS zDW7!zV|uG_q>rr5ywi-W#Q1oibbiosg+024oj{fQTp#It?d@x~VfN*}uo^!}w5NQo z(j144s`*3Squ+?npUxKw#~FOD+l1+Q9^&hh_;};m8R&N`1wT}CG{oy8`r4@OXFMA{ zoLwm3eA4)M5+`05cT=3h;s#~ab^gcR<&`ZK1==Q3D;-h-rh9ax8?pb?e7?v zvl(|)`S+R?PsHn2lKgeD_Y>jGaCv<_`fx5xuG~h8-TTD*J5BU;$+kRUV5B^s&a3Ca zxl5+%d_(noHt{PG9={kNtFONM1CaGH2U$ZFitFc)`f=%@zrq21d3`mF3c=a0ACVTI z-hY1gtU4<4W=iyz=C=aQZH3*|GTic1&!_X8y0}&7E6Zotm#z3#T!vQm+<(p?{&TJS zjiE71$|tQa2T$FKIa*~{u$Is7rSWt0(AIc+c0EeR@%WX-&l?QZz^S>E->;;8RjA(s zyXNdhY-N6&&i6D)4uhrDZ4kq=hg--pEI5i3`r?@^-zTLe;@Oke?1a!JB z+DDQ6wxWeKmNt&V)}DNS1+70P>_33oEo-sSReFo>FZG`(g+J|Ad_$m~t}-bC+@dn$GXG^VVV`ZKttq#a%@HX?~2|n+a39RLq>i z^J6rA?xC|8MgxCgOeFWOLHNJq|5OjCk>2#I}AvGL6`2r-=B!-U^=+wz50hot-}$^NQK z5erfBDigPUa(+|D{>U%2e+V-z<@s%BQUxbxOqAU};Wae`(a!Jj$WT3>t2K47__UX7 z{i)W4SE}BA3+8c1J)bFW^pK(_uh07z6kwqHU{>oxXMw+e(){+1hD|Z&Y#>%m;QZ3~ z`Ny%RX!Y2P)t(&5{co!V{{_S1zg8z&tJn*LyT||ZQCfdKt(sj>UT_b_T6;PLZe!f$b85fsLbY;dnN;`>Yat@>~netkKC^+EaK^Hq}k_IIsQ zFo`f=1_|o<4c$HgG2saqwDGlQPxD`SE6$^D^CqmSbDX&T|KoStJf!=iOXibYBK7AN zn~SjB$Wb=`b@J#e#0*xQVZJ{}T%XpTpVq3*ZcXrHpWpv)ey5b*tp;=OZD|VHj^_N* z_<3gM54iZmmbED8ChEHe(Px7b&jja*@_aY7oreu?QziK?8b3R?dM_+JZzJjNq=I{ zUZZ7>1q=P6o?j>EqyMkPvicg3tJ=R594M(DQ+-XVUkLpPwrsV-F_BN2f6kfM7Jer~ z@iUdjr@M*1ehlA&)t7%t_@wvoCOaI)s%d0!2P3 zpRsjDAng1}Jov=x!?ZsnrSLeu=j*e{o&78ArTV&X#3YP-n}A1yxV}>V+49&=d>Ar< zmCSlwX)o=c&h(m(M`zL{`by__n#Ep(-;XA&ARw*MUaGHSZq3G)qGSo5!9-s#&#uL0 z+0ACtFZWXGKi@m=g`^2dV4BB;f4{#eL|;b)>#(SXUTmDRL#4fR|C9dZ=fe6AX0rbC z({VnSJ0TTOjk*3h5&hj=^@H%HwvD8|O!@r1+y~E=q+(iLpm=>HM1PkD{1Tc44VU$w z!}{%l+thNjuO2GeD@gpDIzkg#V<%wiJpTSte#2YrM*G(lI1n;fw5Rh)CcD>!{i_+W z`uwQwd;GN;#1>3nDcV#2dC-h{uyhrYZX81cMP?F!K z{2y;vfJQ#nYEBKo{YcO!g9f5hzx8I`{uQvS1i z24VG;7#ywO_2aKZpC2zC0q2YpXxTwM-%I^ZVuW!$meYKt759Ind@rpr8U4E^;P4%; zzm#vCqa`pN>BMgTdQ)jH<-54Ue0-~(hSB9O#rvatw<*$Q{RCGQb6>xbFDc*i>d%5- z<0OQ2=Kiyi@SS=}b+-K!FZTNpKc9-$pU&A#M{WVoY{U_9eaiRtS2dZ}DKD1ScUa~6 zQogMYybvbE%JW^Y!3Tm@ilqN5ityc}QK3-d#UM$4C*|9C(?T42ubL5}!|Thm{&X~` zSa{M$p6}e{Y1})E}}ijO!!Nak^ES{+Rb6`BtX*N zP5tkOAUqX@s7ayMecoR9ENRL^g`lPzwW#Udww$HxZNHTjQ= z>c8cw(GVi5v(6|iK@;wX1i1HfFPMfON@6A0YVrRq!{C<`y+Ec!F_0(qWwv*W8+5G%x8Xx!2 zpM{DlH_*+M=f6PsHe6Mk5luoQ`w8>iNCj>9;Vh z`Eb>IIUc`J|2gNJ7But6OZcSvyXoQ%bUIs%!BxkJ*GKz5N^aLe4~H4D{U5H!;xOrK zO%^%Iw9?){@&Km1t&jdE7s>k9BiA0r3NO|94Gq4F`U%44qdU#XZo6^rxTKee*zj2K@3cNOVc9F;``NxYUA@x(Bzz|K z^FmzSH4J;SRkY7h=tT1U}^T;V6=SHeR3$t^Db- z{8rETg6Z7{vuVv%i}z3Ub!VUfj(1)p>HnbhVZ(;s@#nrBs~Ti1+A9dZ-Bt7Ff2<9F z#X$c2ssG$C{4j>@t;sIco?pqoG{5!wVJ8d-Uyok{xIL{uy*?fZBWo>*{wl4c{1G(Vl#Xd@o0_K>aJnI`fN zlAr$SVuSA<2e3Yc^Y?`K&y5$y;)7-lCN%45CF(EX_tCS_(EoE1QTZRl=W9apTeWHr z!^XroOx}?p{v88#CGYS4N0%{jXJdA=+hOtZ>HgxUk0)VxsFcqr!l&Kyx~xIa9QHD@ zDc47`zwy?c#W<;_nt^V}`KI$h7WXh(;`lP>fDMxL=HT{nUS6 z@GM987}8hL-$C_tSn>=^>3$U_Z*LLp6~sS&v*xp~`i!+Kzb}sYK`Z<=LUK93)IaW$ zP%1oJ;wU@+dcT7E=LwN34C>!5y`g8z8yK1wyj`<>Al+R*^mRMFT07ciizEOSsulKl4a!ux) z#rdT9tv0(m!ft;Emgw{Nmhu_k8;M?>G-de=JlF?!45a?C3E?xS;2p;LnKQ>e{QMaW z4e9w52`1*y4c~*#%Xof@@>!Iy32*)uz#=DIh?~2|7d?mr!LXh=BmwlUYt>BFO7e7>e{33uo$GR zO%d%Wzs@ssStnCZ)_O^)XixQZ$yo=qAAAVCGA@bsw14Z{^XhDG`eatzw;t!0)Q^5X zoQ$w~=P@nxoM^8g{&D7cH}sr+5to`oi+?{&@>icVTeGVcL2R)wvyyLVe4E+qjWB*@ zUrGIl@|!tf7IGS0Lv6WrF+1VY2$`xwk4} zuZ@%V$CO{aE0K5_R)wwY=`P+s-Jh6(+L%%7DVu-JYa0!XwOZ`l^RA+O4yo^28#cg4 zzlE~#>$?}x&~K*AI_^@>uXVDjzj@DU6iimnZxinVn1z_L73&XH@-Nlb0LQLac|+Bo zRaswmBl)RIX9`pqa&uXJ52=2em*;E;_Ve|rz7C)B6L$6OSl??WME+=eJM5V`N=^2t zYP{ai_p>iP9(QH5D9b!PYC zE?WK5UnQB}@g~q7Ut^;YUXSxh`?s3kPsF&+joE`y>h<-_OGi|zIE0}e6U6U-4(Z=I z?6Vj1H~dkZUmh#2uR-*6Q1E0}#Gl2>WoJeEFv91-AX4hv1 z=bzMnN{_t}LN4`@^^fh$ys)6h73kdv6W4bme4aYly?75G{69cZPWVImAEK^{j)3 zTjcqDQ7Z<~sveoyHM#y$ew7{#0N(|es>k1dntv+39<7>>ti@h=z7zSQ`6sVcMmX&z z<(K-$kqgSvVE8b$aeus8eoewU!S7VCq`#8Jw+(t9!_O);CH!iT{IXYbGq}&%j)pe; z`e}Z7U-U2Z&$4Apv()n&zsLe%msB%$-+ilmKXfGi=aO%maDVYTEE&)JW2(O^#tz1Z z`jINe-i!8>U%dt;I9h7Q*2nVrmg?`jeuJT37J+s<9*OoT#6LFkOTd;uLl*1A?KKGB zi81zAns@*U9BzsBw0|SQyapR~a3V9!D6-=5nKb|W*>e=4y^f;1_O(iT>G|qf3LU1j zoy;_+a{Z<8?cFM_DEt|Z=enHl-GuM?r>CKH;sxxi!}XW)-PiW5@aAP7JUq$cBdV`y zhi9PCjs(<8+ALll<#$YIkr1?Mpk#g)%|E3MU5R5C(($f>^Gp3>!MQ@PN_2p~2VbA& zpT^gz#&T1}u>CK%e?{}h*G^Z1Va8ZgY~c1(e{~=VW*Q4#p_pEN%s%C{H}x3 z^*m+kL(^4f%V{K9vxc*j+@9#~x>gP0*>(YHcH!?o<+sL{7~C19#Ui!2{^pSQwxO31 ze3eRs81nfmK4gB6@$@cuI6MShv()>?d)gj{TfUAgpS@0-!Q{s_cz@uZPxZBIcm$># zRGkmg+EuN-?hdoWq$9f}`szdS#}jhGP|>15(m$z3{NsbEL-6a+0Yp9K^&i@w@g}_l zdq&u?Q{MmMOWHsEqK5-QZbhSggXiM&*CTwE-nxiR{p&Nm;MG=~FR6b#Z>~MG!lK~N zBU!Yk^YKbeYO}R{r?HmHeplK{`MjAs1!pFnMZalWzk^A9d+41G`&u-KwVuWKr1|6M zeXh7SIv&lg#Ea|G{*3SvBWC_X$rh#CRr%TgJT#M>#;;^}D`ES+83RBwb#^}3TpXvVN)xuV^ zKKdRlU-SHP6v_+Tr`~tSTSu2q*s=p3Pr{L53Gk6xs`KISjbhq}v`-Jm2lyE@&{4m1rn>N?cIjjk@ z+^EC()sXW0dDA;#g?%5`WO03?{FbZwzpR535H^VWw^W~pkN6>=!$8UYB&yG!jg_c= zI!(6!xz`2_1PpSJ^{+$nv{=W@PVCP!p1)8Mez)~e&5xZnRyO~fvZ4&R5q509eI>sd zQhozH^svI&LpDBsTUrdyx;AXxP4)Tbcx5BZY&&1pzxEFOgVzSOY~L%Mf2RDFhquCr z4Xa?ai}OSI-Q6q}=AoJ_Ldok#3Q|8Z-qsx@cS7;hhX4LjezU6eLy7%Xj40>*U2cTW z0rga8w|eA389PKRpFNu^urPO*#DAvy50`)1jKMo{(Xuc_w5R%f*l9SQZboXXs!di&@Q2o7_?FQ}SGnn*< z^GWqrv91G~xG;!?{&D2|k^Hhr#0-3EaS`>0^87NLFYom=Uuf9055g+vn^Hat=gh|A z$Cq$dOFf^Foqh_xRWn%rw?BdM+2HDG7++S+AGpQ!mG)N!cCVt^UpZ8k&($S?ST^7e zx;*t1pC9#~Cw{MiNwvqyo{wB*$6Jh9+KV;Kj1cWL2%onG=%Yqmd3`l)`UeMHZJ4`x zfM`$S-+j{>eN~Y7H{n!2_@r$?T#R~tyJ>8} zf-||;ztLXgkJfizu2;aO+b%4#aO}%{AU2yqUirl;>%iQ6jBNbdabzCM4SW4}e!ckll;0V9^UfZF?`UN>k_@())v6}s{*m?^(HRtPx z5&a!CZ4375=c?xOaeit38JPnSFkY&^G(L7dAB|Z?71-1MwaCAM@LTK75E$&)kJ(#! z{)+m?t?i?cySN<3Cvkq2q`qtFY6qh;`|z-)dVaNZ52$`WN|EqEJ-;r=_L!I!j``oO zi{B6Bx5I^N*znna`OfG0Wm^9|=<5XE^k@t)y(rq#{;KaT`{9uI6Yez*TK)Tda3beF z^4^K8T|ynx=ZoL}1ie0O=Vpwv{z_D9Znyb7yVCc_?_Uy%Oi(ngvvdo@I! zU*#Iq?sx~!HcuCy-z731-XlW?nfF~}`A!HZ$L3QuY}3J$qCMqXPu0I{)YVluwQM`h@S0zHKmRkU!p^<$MJbeLmx4 z$XcG6!H%ZfR?GLe&fSsyZXJ#UbN}0k@QqKJY)U5wS-zj>4ZyP2Tj1r!*9YM{cc2#g zbj*RR*FGomN$bN^QwO5n_?=Ll@F?CNjejq;jK#cW8Vo+UYWePVXDDWFRIUj9EYI1 zTR5I?=6uuq*PHxn=-k|ZnLXuv()#d)_apHsItFp8d40GeiI1(~Rs9{mU71r$!%F{I z+8>>eD+2;y zqIVmKKQD;(3R0iS_*y7@cws8hZ_59NopbPG@&$~_=KTAR`c$9D5@FauD_Q6 z*W0L@6)axg6T*L|cug3ukmtW-MIauXQ_V-HIZd>u{0DBXi5lT9lKdCVZ{M;~&GuLA zADH>)xM)xLPmHgJT^*)jLXW@V-|75-nvY7bIa77MNct*nPxv<;+!T?n^JMjXZ1f*Y z=`oP$-|HgUD+&KT6WYRQia(Y*aDHk0{OHFyd|6(LRjOO^jNa2J=J&DF?OgC zw+A)#?}^Ws`sa%s6S2OXKHF-<^J5B9pR)Zq1jfhrVW}hMKZo>pS(%K4jdnEht8@Jh zBk^_f%sQ+~he<3asJ`0x`lX*IbaGE)@*vJPjjtV3W~gSr#G}(n&M)o%crfpikeP3a zHuw1VOZn`)+8ccmE?|L&`uw!RsNcd8Ei2jj(*dg>)QL&MjOv`v-Goo;o?39KHUtTS zIUm%&Zhv_t^4s6QR;>x*^EV*#cMKcVf`yTbWPc&$b7Jpe1h`wUlC;C3J>^qtM}3@a zHBHw44mk1~L4#F%uIGGG|2t5l85Y!-CtH7NoL!2)-xSRM1Lspg_{^Kq5)blxNdM~t}9|FzF`GSh1 zTk-p$`x84A)?+@+r?O^K)${pjryV{P?1r!RUD5t9$$#x=uE)OIox~<&CRwS|=K`ez zwiN7>^}lnA8?mL+X0exrnw9!0&0p^s>5Qk7qfl$r`O5XB_2Z73*Wnaxz;ZU;64$5s z>)Uf?;L@-&Fw*4yH|-C3Yj_iP%Nwvhr62kATS@CvBPPwlk_~5Jxr67oY5%mzqzKH7 z{f5tzvqk$TqR&n@J_}BJO_BXZJ^xOz^I&Rw0r$pp{-cOK&-(dC_>*HPtIxU)L0Dp$ zivI3Af7Xb^*E4ms(fyUZq&`LY7mlq$pzn1oyf|KbzB$A{&wpMEBd?E^)#v=$ztPRx zf-UZOM6{>;>v|gCQKG6xUgmt5F#l2n+gq_Cb(Eq#_0N+pH^bps-V%ML{nbZz{)OLk zYxZ^r??0jZUuf7KuMV$}&2O(L(O|nwY}hgHlh^*ezf_;!b?c2`wdD2rW{on;ino&R zPwP{?i_OvE@@71p`A59J!-W5u#|@eFNq08Xo9Dl1{5@~D4Hl2sfg`Iq|1|$Setvys zG}Mg^vbDGRcm1?JRZwJ$e$Km)R`rdzehSHdr#aMT<$7+cX%+SS?;1A*LR(e;s43TH zAHu)(%6hE$u`3I&`9J=o_36V+9q?fJUcB4M#Pu%`eeN{3F4Hxhz_bSc5U-!c-=+D^ z2#Sk@ts&>1=EwWrVX&K7pWPgr%}eP;u222**gZGl=FosGna=rF zkoMXwjbX-}vEbbXVR)9iw=0eGvW^&HN$^s_2dLr`7ZCqc;bxzVWK_ z#W#qbPwQJ-RJt*6o~5KeTS4Z7{B5=t&y&-z{TSE(-h}_$ecITel;{6MkP>Fj*D?MF z=b!rL7d>=wcJOFf{ogpJ1T!-SFsnM1`cL}Dihdg4Ucafb`oFchYW7~RCF`=C>p$hc zrcHDBsAfFXd&c`aX#PAxQH~djtk{9U>h*uWa|gtfs?KMh%I&HCFW=uA&DIB_{aNlG zQGK^fjYo%0)g^puXh`=@gq*d&u9=%LZxrX7>if5|=MgnoHDB|>qDp<1_GeH0Y6HhN z+i}^N^G)+>htBDrTY-wLAdB{$22TunleEPoDQ_m^|NX@A+I6^3Ya)eTG5aDHg~ zoiw2gj`0?3(Yux6`jqdw!<(z}i*wMWko)IGWPa{)Wd+ubuwqku)bl;UqXXg(FPEH8 zL;225Er&(2C5!KORMdA`AJcx>8-YL9VTdljewtr*sc{wyw^x($PwHa}6qcB$wHZD1 zIR7-ie$MFvI_c^#i>>PUcik}h!e_ZGxESdTTV}0C2dzya>+2e>G z8}>rqmGd7=^u5^OIv&@q#|oPqtXyBpf5YaZv2;PCtbcz}(U}Q9SFsaWUDd|tZ{B*~ zVBO=GAAd@`em9a|k8hI<=OP2vq&erG*3atonT6~+r%^OPJ^#fIZb7qe1BPGK#r0|a zt=r>o!k*!#*y^R8|I+!h(K7WEp4M0|ULVcBam1v)}lS-ySv#C_zjTfyV>VB#IQdYX*E@}r+jx@ zqMHAgw-*mgZ;0PN_1_OOJ!aBj9E)@NUU~gezC&uc;7Z*{e3{4f-G}7g3?e$P)k`VkSNNQm53-S zWM-6hR%w!vU6Ha!=zZFH?7d}|y(#N=e~;&L^?c6Xao?Ulon_=IzJs)bv9)L?V!}mznCIup4{Siku#dP@^PY77YHsrWwDMYCiY{5&K`lW! z-wm5h#>zScIJiLY$^G|PigQ)As;TDt(zG~iNiPO`;-%*+Vfj0&xi#RQ>mi%Z;_>_L z*4o%(FhHe${yU%?+bkUD+3Ky*_j7*#ZZW_n#TmH)eU$Titfv}XoZE#i&KB{xwVQmt zvZkF0PP`08inVgSHJ7T>&7rO|Q$u-t-r2J?mffC@{G311{rR){+3uEq@G{?-0;=XH z)$csRj<9+ci`)uv|Ga+Iet8k@*~#}W;PvsuEJf|3+j7M1FPE;*^?O=UO$ztyMJxI! zub?twD36cn`;`px$b(%#sWPA*KO=wBj#t;YO!_m{m8`%DqvCknp#{`iA$G^XSS z6X=olT9a17|EXd@4LNykn(bsEPu}X zOaIYT>^-=o9JdRXO7^_JrPZ_n7+t;w2BZGVkIVCO(-vBi<;I0HE>*dHpO_hhU;Xls zo-6pi%=G(OLQ8UTok!a|dMM?4*0G z-=CD$K$CAhROOBJ68&F zRnC9N=hkpEo)62}g8#mZ|EG`CXsu2cs*|bQf3FkV5d&RfW&0m+{$W;|b}9D9{7>IG z|5MUj@wduyd^#`q=lb3}tpN>QK8iGUoR##Q=jTpm^~66PlCdRC@Xzz}+v*<21|uD^ zs-o`l@86&EZ|3NU%_gb%UQ!~xU!I>I`_P!0T%ADaBb4+1(#jK!8l>WR=0(ZAFZ17@ z)i+oHm9((mEbd+`PZlF8)DjBKb8J<_+C>*Xc7#k%K9_s@5BjpYS6L^ z-92R~yrqE6bm8{#<=s z;qY!L`Ud`xuFv^Onr=wL$Bm-z?*w0JY=4pBmA&A)D_Q10^Zc0mQg^aGmPn;Vi(UTZ ztAy#Rc4ANDeO`&}+7BzQFW=v*^(0gJwl;`rbXq6bbA8Qz=ZPi-DL64(@DXMvRp&oN=EY+Cic@G;BKQO2&v1t! zJiPr>`o||H{Z;Ib>p)Wj=T}}|?jM(Bm|^nmAlPII|Ja}D<1+0k)Wp9tbq`j~r}~yQ zXcG`7+kb@jkA@YhQP6ZJYVuL+ugUXUce{2(-$~K3`O0t>{}wNDMWg0R(K_b4bpIhN zzIDA|NXr)bQEaT>lk4AcA5VPrOjcQ+>RP)8EwxIdJByX`nV8xKFL$Kk>xL)N^?7_d zVXZkG9Waq*?^*BiFW=!V^8W4y%llyVwp5IA68URhpPuGtLZ?>+QhM=a$=;Raud^5V z;6Po)9<470pCOD-y~CDdSZ5v`cveT^$CdSWztA3n+?8w4ySk_^^ZxGKyC$^FdpxZ; zW~@{npIS^seB+%kNfmsTGJPC2e-V<^52LkbO6Bv*>(k3^Cgbp~9XR_$@XPy0FZe{F z)TRjAFA9Eneag;h8t$d+M8g?^U)~@3B269YE1l5GP~?X=zw1UVM(o}r81_NLhZC58 z`{86QOjMj7mH0^L3y)umigjU;+)w5C$g%4_V0P1XRI6M(AJ0E)I5tGW*^w&yzwUSc z4Lz@pbjxk7w7z(M$(PaQ*pwEe(tkC#twO0YomK8n-)C)GRPj>epIeCMGh_bi03UUl z(Ar5Bzw-Rl0=rJ|?Hi4P2EV2I3t@czxS>wH-#W?tS5|+j`rQrJM#=S+*Pj~1HKb?< zKb8LLs3E;DV}BCt{NGF0=l<(1eGl^2OQiT*!EZRz*XoMBQFEMAF>buzm)D^qD4SYS}F55qo^V=au zasJ+hld!GsFTMY87M~vUsf#i7`>Cui4Jm7=`0W{~QeSU(_zkTV_6iM|Bfj57uCKM7 zo8auEAcUC-ez^Y|u&W9^(sZVq4_XU*)*t3MqaD1|!er-5xH5kGdsL(M{kzb?4m*_Q zpRTOwguR!duqaFDJLk7*&pPzEhwA)tRQIm9M@tZNPUtW14_RQ}mclyCr2+H*o3D`P zm-BBcX5-!_;cxp7;`!Ko)yXSu>3M^BRO%AoBIzgN_uch@IMsL+b{3XO_FR9D*fyuk zrc=rH)kevl=a+Lz`@+jJ4W)0cR9;`+zdfs+2|Z5_ps)uQC3~*F{+a!7zc>wFJq5o! zzkFeBBhr64iY_$xE7|k@klpWxp;p9NWE2a2dHuNLa$_pZ8cow?8&&$h^8RhFs3|Z@ z-!6+!d4E{zw&UUMvlWpI1;4z099S_KZ)~<>lbO&bo?m`&dMV786{F6JLzT}j&p$o* zG#x$j@?`#VII9l_zNw-(|Ita-|Hb*$P@LbA6?_tPiejYqZ_V<@&ZQc7W2sty2h3iA zsK7ILv?V~YH)HkTbLZ=#IJ7TR<(J;hdynW2mNfrureyER{O5rijbLvuQf2&_x4#S> z>bIcA#$zS>aK^W7OcONnn}8+Z|M4Y1U$r8q3SGYJNHdHC-#orO`nw(4wx6dmzI`|N zA$EK;Au>vo_zq|1$N0uOVCKdsng5)~^m)kdHk2}OwoIRSe|D64SM*lwZ=bnB>~G8U zxxA$&g~hp3mj+&z(u8eP+;=!oC zbQK~>#QYWKd!>gtElCR`?_lNmrL+ofEdQ1)%P+e!eI7gBl&X{lP~((K()F{Le|@m& z0Q`ENCe!C|rq6iZh}J#xqtCPdNcNoXZM}z~xAq#eT`2tPA55POdYr@jCpwfBd`hzC z@o&|3Ay~3|I~*)T{)+Ekpw&MJUH{pN#V3^W-MHyg9Q&M$mz@OPJU%`hv<#Mt^I5Gv z3BJ{sKL7d?ic*c8@O_|MpO+1-iomswviub1Tkl&u>Qs^Q-Iwv5FhUbq$=y}vj~7o* zz|Gw!QLWbKqJP&17~faI>H)@mRmR7iuYJIT`j*tA*&4~7^WDI+5hAiisN~z}jpFR` z(YCVl+qnO|`ePH!3m=cy`pWr!(*7m%otx3-yZV*a*Z*HKSNiw+ycPDIoGbIcdH(9& zMG~^b&KA3StALidzJg&-xR(5KA&}HnQv8>fB$}JYV!FDlNN*V%q#;nZG?Wu zvHGy~vL=-EF_1ET3BI|0C#(CwsZKIhx{3T2@9#Wb)tv4eA1jNWdHy)kWgr%xPLt)2 zd46l>;KpQR;zz3+3%>dM)lIMAa6Ov|&t-yd9zWl**onxA-|^lcS9*TF|AEfY$UmhP%_`Mv}Tl|Ad4u#V9yE1-zXwJg0qCEU~Dfl&G z`h4YRRmJ|kjw<8haYte>!s{4T*N>F$uYmE}>9!_H4ZF+EcjEr_=GDuv{?8e_bsZdo`xdxi1@`dwbRVZi#M+0iOfW?dMO)K7{43 zUQB<1V@I0M<1>2F=ix4LK1VOI#+e?f`Lyl)7_YTW$?hNJeBOTQfRXNzD);Z(vi}5J z?d1FS@&4;omffIpEgrq@E9Y}mdTlCc?oO-bDCbkNr8k)_;GGo*6;^<51{qXtcHDAqX(6O=9r+AHv#5b$&*81Ut^Y>R`&p5#+kB^@} zH>2b(0rdN_&|mIfS7Z-FNt-k**(v;MJ|DH&)R>-@ja1Bk2tK*~zH2Z7yC-GJ^q0rS zRUR0V?^i#Xm@Ljm=KAZYIDhHHp&X=ME|8v|_irqn7=jUJa`0eZob>$GY(6r3>@;}H z&c(DK!7ta}7k%d-(QT*7{^{P!swwuDa#ZO*-!6}aiN+DQ{SzVGUn1jEeR6F$=66%c zr^d}C*xdCbQl|@j&0>6NudR>TZGBYw&rKG7!GV>Q)Yn-&AJK{`f!!?S@X9w z>EWp^)L2vezJSd)KC*3w2eah-^8E8d=q&S}Km0VNc7-G9)?VfO_U+<_+^?Ck{z_iI9r?$IcEt^)t1S$a#>ZRcgxdjd?`L-yF!DPh@>E2F@rN1AqFV*@`8*BQh<~#RcEQ~iF#cbDM zl0Bb~c-l)3apm4B^>^0i?=aVFOMWGyKZWys-`p5s{f4XbpLJiWQ~V%1GEWit>u|>R zTRp}3X+eQ_GEVr)!?k++f<@v7{ z=6%uKHA!XtX^z1~R9w}e$g0&`l<~c+?m&e7O-7S0Po?|MX8!XmYjZOF=}(idt(NRL z-~D&?M@mga{VP=P&FfEvvn}ZE=RjJkbzQROd^>3j!k`@~iv0_Vr0f5`{;QT5Sml2m z^(KZ^+RO9TS`+*bY@Z38?|UVC-e0+Nc^+)Le1cQVHp!mnuXjueg<(oAh6joGSg)(L z2(A?W|8!(3u6u98U$9Vcfsob|?;i zS007NcELB#U!OjrhvSakvhx{vfArNR-*I`MB|Xa#`pxGbvD6qv(}%&mT=X~b{;I4k z>a^mx4Hf*DE&csC-{*Tb!?BA2nAJ$=C-=XPS%1cgjFwc^u#sfX^}FI_dwA`b1@n61 z`aHk=b#o0GSKvqss)+MhdHyT8gA-buiBQS+tvY8g{;%r&c~|Q6fSFG`tmg{-=KUYR zpS9@4ly3B=n$T~a|1v4>iwlnukv~c3H}}8W2DG3J1{0`a@gQk^^8PBX$%AodTM80S zK9k;0DdYQ<)gbKpCmHptT#-KK{`K)=7PSA;I9fdKn)LlVzcpj&VDvwlf|a#|f6e)Q zdp`p$K3{{^Ji#xIe`ntG$GAtCaI@GiU7!2co!`$y%A#D^{<>O>&*Dd+7<(cIqmPO8 zcb3(UZeN%S|JFNTcvi%(oUg>38i-owfETxw^A$KX4hD+zqiU^HuAgRxb()1`UWeUFd{`6ZS^)aACbkJPU8=4b=eYS$%+bqB2yxbj+Tg2h;^Dol%dH!gcgAQGq=uW3>_bJss2m5}Q zVV$UQ{|?Q2t*DcEFm=8*#N}W8}iw zc<&pAuZ3xF$+#iiKkq+oVrM~GhXUwl#g)qI%j>tL{zDKJBIk$4r!n1E;bOOIXxC0T zKTd^X5Zi4H{`n#J;r&rTZS!F=`y+1d5&CDw_UGEuD+1N+cO#>Hp>+SYjISfzX5on< zezmH(PWqhZkL;%UPTcEQb~iee6m-l0|k3)^ zm)CbTYqX}mRe~tpQ8~Xa?hJx;%t~4R1&>by3_6gLW+=I+=Sb_5^BbQy0!60jvhyK$ z{oTbv||45vSiQmOI_WTVsHoGdb*$VIoG$bHsdiOXdT);I3)f3sgI+b7mU?WLVil&zdkw-*W6Z*Ww0J~-bWtKDdAthnZ;lF$4< zbt$Z<2ff-S@(XILe_~&*0d_R%qq08JG~gL_g*Kug-&aWQhx0k{h6%1a_~Pv^5#MqB zTsXNU{CbT;@gVUzj~@@!{D830P3dvh29@70&kuRS7UsHg{=!-R#EGu8X-i6Hx_d(T z{u)>FoUveXI4WKU{*;90>Y@O=;b*fl;z&aVV>~1`P^}CHu=P zKQuRC3A%qfil2)|NcNo1lLq54%WEy-Dg<9VKXlo+}6Bo90AA{p&sik4h2u&+@w|EyEEudna~SY?AENy6VV&e^2R|QoTf9(v9@2 z?BA02PweRtjw_jY7<6x0<@M#~lYX?Tg%`e^aObRYes|nYz{2;1viOnbe}nI8qwioh zmG#x4Il5FYwi~5~JQerP_-)_00gmVQR>`k#*mHFAY(x(lB}(?3-;h?OI5S}gPA?UF za()kP{frkS&B%15s1I>{ExFec5piR2wYsqH%j!2@JHACij2T6~(W|_FIp0pz>~Q>7 zsBAum>+70Bnxp|IGMSpERA2KlJL8ylI2N`O`Jrs)|Jvl&rOuY}{q1=E_vD`*D9et) z;NzdA`{R5MwXRFc7j>sck%DiY|E2c>a4~p=EdQIu`lG%&wV^K!gQ%ICuZ!d#v-(Y~ zv%|1bD+RvC1>cvMe{AjAirjU_(X0XMC40{IZx25_2u_23q~M#+=RC|2k1}zbkC>ggFrT`&^7``p(4L=R=oOU5B6a&UI9& zpCLBOVDS4WM%5GkA@^^q#Off##7$-Y@b#~{q^{MCXlNyWYI6U!^k@UTv+S+1{!(RK z8T2fTDY(T->G^nmcI_@xRDCoUM?wTYoIm5-3e?}!lB(-XthAT+C!RNLjq@+Z;_z2t z&;47M)*n&Tr3qDBH<0YPe`~hF4#}RO*jjo180RnCLyI;PIaB@t<@#!kE*La09MMMw zf4o2O{xL;w>+!C#`U{_rv-{?O12Hj3t*+d^{TNf1x?bu=A6x~0JbzQoe<0SCEXT9e zLSK3QrqLE#+M_dr+J77EqBK5jJ`62Std#9v$Mdu0Hf^boRuH|KBKi|Kf1k$q;qIDL zgj^KyDc4sI*CtfrGmN@b75s7kw#Di|Tx^<&MiYd-eqj1~p}7TpvG=3ii`6UjNuHnW zbZ!cIZpp&HJx8U#ZzsmzuwILi-X|aR_X_`*=U?YkS%4q*x#)RaIbXFWhND{X4w$-# z=MQ(0>tnls2%M>w2fLp_AG2Bf>94MdcL|*kB%803=U10GEyKQhN3e5clvv-aK5FHx zi}**bD*JzZLwD`0TvlRRA{=5DQm_9CQU60~J z<@Hg{=l1fR$Q%`eYdr;@Jb&b%uy3QVZ$CgepO@DUz<`CzF!aJZ>H3_{mYZ*2#Vu{> zVNl)W-}~eF)vpsqz|=1pS9c11OPZ1S$iT|$%k?#_wIQ@OsbAL)X%L2`b<_|2;7iTgccWceZ9-|y*LlP0~l zA$yN)BEQSd@9vd901^9_V)@Uvm4APEe0uL?N6J|kN})Z*x=8xT{MT#xBhlg8N}P!m ze1iF}Ize}EJ4%<%4)B!hd4021w&L9mOh;7vJJR(NS^saZ6XuklJ%oDPIV-Nu{MV=+ zA-H&8J;r&6`iddr(`!QlBKjPJHi`U}E1R!d-D*BIu2Yxz8d3`LR-;;o}(#Y zt~eiw$ETm3&cT&wThO6efn=}C`0O5k5H5qh;>xje(*5)OWAcA4z>MqJNU&GVZ!_;` zxH{~@2eWOGJ?~%8{$P)|EPD|2prgygrVx9 z{!+mB48L+0?;{j@uoo-mQ~f{y{*F!qd~ZwNU%>cG7}A2K)EG(I$}YP6yS})8`^;|! zE*{K+vEenzp2wHz9}l5f##dA^6#B{eY`6)C`jB`T2r-FE4|GPa%HSi>kc7 zJiaW+oQJ6JEx5i=IiC*~FNBL;Hda3t^%t(6AKyn~{>uW`Iw~qboa~C^k@+>aXui=PDjb&(HI>Z`_Qq zC(%=7f6&9I3WUyYMo~ViC3~L#nZMB-yIfWC72o0)hODq4_3IOaJ>%=4eOm<03_y-z zAF6-<{+zGdS3YCBfftAc@(EWQ()M<+FZ^POC5blRv zVWqzS#Zv`;+`m;Ejz?=|s^;&~Cr>1~MgzA6e?0$VZPP4L59nR zAR%@cK7@$)Gn?gqcHC}EYTx_N(bjG*f)9Cr{h5}2Sor!#D zmt@cN({|`+MgLtge)|ajHjD9j^NTAPj#)r`_r0yOm)A!h4VjH?fg6zlVb9MuF-<>= zsx`i1oUU>{?|+>Et#(-mzIsgh`}6*SgMStCB^~!+kXCr*^UL{sSRR2Yiu{kq`2CVS zufGi2u>c#FZ^h4)_)2^Ed}~C_a3q^%V@Fq^pVlltv~ztV4j$Yt^Kbe2Vk7ysX_qw&x<8ACI#OV{WAXS<=T$m7EZx^hzVzw`c_OyjvI4&R8Rz?+gi=f|l_Azt?U zf)(W}r2Efe{^!ci^DunRCK$~>QE6XCrVmd7tf`e*AU*xtMC5;1d>G~zf&4SsSbTA> zWS_<6Q|y;TU~9D;+4&)z7$5qJ7sI4`E+X?bRNkLFJ`7qLt>`_-L%%yKr0@4<{^j3e zF$&jUCvH~GPpdI~b1bQc>{Qi!WfxYbYq4$V@z?X>`C0t;Zek;h-_c8@zRj+9i?)GA z^mTrcuve4sKUQ?N3Fh{b^T+*1ziICgG_(;7nkxDi%-H^8+gn>=vymTe6e#C&_TcX* zm}5pWTMIsUe${ewC+tj{itqyAzw-Tq2YTqx{#OnZK1Mm8@vGbrYaa&vU4qXaEdCqQ zP@k;l$n}l$`S5mcjCdI(%ir++0fQ;})bNEHHGQO<&nA}@^Cf;uu=zIf4q`FYxS>C|#fPIcv#6?6=qg?KP*Q^<~K7 z!_4$)5MOU&&p9`cC^0I5Mr$UaoKTdPm`I z?snJ>-Xz)c{(^1IV)1oWB~|zhcQ86Z$Z~U$W0) z{^i9#t+1l+aD*6$_0RS3$(K50*{ma7d)B7%`ttbAp|u0HKAEC&|L)pHb!bP319j=E zoWG;#T`@{43{!Q5f642M-F@|`*A7=%e8>0i{}$2*xzSPh)98zIf1JOmH}vUbA2(XM zSMbN*H0(oIr<}jMU87-|mL%&RxXt1}ha6|>Gj0am za^K;ijK8g^fjFq>Kkak(mUMl?uJZjC%&N4YTC;}GyIKE8_B{R@&~7FgwN#vM9WU}T z)+|30WOWpi>V3hm8Or(VT4MoxJ8nY4L7|T&Y(6{UawMX)bCK{~_>X-5zj2EF?U#+) zj(JlAKfJ##Y+Sm*B&;-H0zsk)HoD)4#I96`1CHP*&gP^Os)l z>*Ltd( zDrR{6tOQ?bOyBklw8XE>;TTdwtZ&ZO$nN!MeV7xynbf}W{^WeUIq85R<0-Q9>A1e- z@6e^X(;VpJQRRHu{L>XR^5>$kpWwS1>(411zX4UBUc~=gA}PLP`{QfX@x~nOC|Uf* z`Km}ZppI4K`o{Uvs^*J;X$d$qK7b?@z8@hu=lRe#dqUGu$kFKi4nAlqkG>pM&hFf&v(DK;TQInm};Rsf6}LeOhQ(vxJS!0e4$r0gU=U?=GEQE8| z2AGE2s!(}sLRavm%lJ~8xd8exS+IPXCw)KP zzpMBBrO^Jo3+MhQ=PM{b23D(cvGkJgKMPoWUUOqKes<5n+gQPu8mrI8UW~!p13AzO zQO?()vXwaY^&lpk6Z*%`XPn(fA7$U2WaqPT{$|~8Of}}a)25HFrRU@G8*w8{uws;l z%KVGfvvM5nqwp`^r%Lv`ez&Zb1<;@`3{sTyr{((zbCwy>>>r|j$NkejT{~dmB!8^3 z6Tct)e8$sx^(pa<1D$B4oX@juo#4A|BAQGP*Uw^np6#ehrb%}6qq}lGwKd%_r0yIf z1qnWRe)L4p1~l&Y5B|60{^f)7d9%m|>8BUV^pW$qWOM^Mm)eCUUfZj*zOeV$P>ie_ zkFqquC!gOiTW>~xJ9<)9fpY)ULeYEQd{82$=nDUo>tkVzHPz|jN5@VHKDjk`s&H#kpuX zTKK1&PrF|U*if+(D<))1&&T7#YmH;kzFrQ#I4bA!cIQ-h;V^Cm#7Otg=QnKC3=px$ zNjBfe`Lud#L_rVSsH}CVWY7K6sK+K~d%1_o_;BpvPk3{<0oC{}{L}we|C?ihW;#B& z_qsxSKkIKZ8>~)uZkf~F;_=ewJU!+5Z}-G+opeZ zLbUZnjExX{^7{ITe{{*x+K!s_Q_g3%)9x4-He1Fg-#;%@djkyP&#C0|V^LqM&s>b1 z6NG;9`uq4s4d}6cXL@)|%n$SWU)i7Gc(FMiQ5Nr{=i_|ts4%CU1)j7eqtbtMk=HMF zbPR;4W+FZ}6@2pkwl;p&RK9Bj`DhA0xqjL`o{8f(S0U(;;FH(?F80iT#)@P3pkwbM zexKy^zcuFJirE}FpFBT0{OBTRRLPRXhv6>r`o!e2NZi%kf~!fBrSIqcYny&9f_keg zwCTH3dOv)A<7m$~%#Y8-ifF;#2d0nlH5Id~-Z_|YSUF$D8x2qz<|NCnaDIx%HlhO) z+-PSb<^1#-Xo`IA9xD5{x8{Dt)v*RN`M0Ql@c6D@pXQkG%Nyz=#QNp=7o&tKG)FN% zJk=^ltPd97Ii%V^Cu$Vj`YPAA^^c8c)+tx=UEE2s=kvp*qn%*y5CqrC{V}+{UAEAr zDM2*Q0sH2&;j&8T8?T=m{HaF|KikXln_SLhs{TY zEoo0XD@IUgvfzi;|7`PT!68b{57)P$%~ruJ^BAHRDCcLug2js8o{g|+b+_{Ra{qJg z*>zAr8#NkL=66~Aw(e~lK90@7?q*_r^ZIyelLk2R$x&86;Cw|- zv83jD11Z>4tY6;0IpDS_a*w&ItRIBBl*6Wt5$S(R7VnSM57N_GV#A8Qcv>RzAAEm{ ziomM$WO);6@j&p!`@ei^*kZ*#KlD-)_s8{Vn&S6iv9l}H2oZeo{cBE-cf!w`iv1%s zME#HJ)3bP8YH_IpUB056uO@mPcd@}uiPp9akkZBS$|j-i|?lC z>r?uaPW0BgK*V=$^8S>;>LajKKTgr(CHzMo-!<9w63%^f==LJze0|NGfD^A)AiqNB zlNRG^T(~E_ikwGlZT3p*m+RAq?X!{DVHM_m6#B&ZQmeTd_Dhf9?L*~!O*M#wi{(cA z9wzuIW%CjH_1D2R=>%4E75wn?O$J6qqQjnzxZP2Fp2hf@JU0S9ZL+YUv2wm_Lt4}fs*PS366TV7u;$c{&UyBu5{D){65 zo5OxLz`3iAviS$jUz&Ss%J%9<2ZBX?jq_LYg&A5Xd?XEBG5-M9s{adCq<_EaRiVr$ zrgY-QD#0JCpVzF>3ipot$mRoi{chxgD&%+1jP|QfknA~s&p+D2GT2Y0z75!FK+W1Z z&>v&v{$U-X&UhX&0loTHNZ-%-tI@MAJxcCC$+ar?mtp-aEwVf?-G3%JY6^Yh^S|>H zzkOfqFXMl&L-FXVp;u;_qQAh(WjJxj`a6!zQms{4Gm_KWMD!LR+o| z)5G_VrSDf``zIgJjY6wI8_}Z4J?Z_{V)cXTeldt@y#)`>pOZe%a+UjkFC!wccFP9r z^$eE2pX=AyqY)T4cRel^3;&PDXO`u0NFJGu$16pCgxBX59bS&45Y_zTY>h{%b2bLt zRqh|2DAAyd$d)wxf~dc`vi_7qhYVqovH>=r0#4%)(@sg*XQ#^7lQ5J za(E;@7%A7cEw>El&G1gt`-t-V$b`4fs8bqeOCz7ehK?@X>|_8t@YKLhEv zqu#a zLf=YQ|K;*iBT!rxgVvdXFFt>J&(N4&tGUuIBf*y|%U_0H4?^~{<p0k>Vh^HCQPI)5!J}iIvXn-SaIvhYTYwlIr%j2(~yCN_=avfUD zR-PZ3u`dng9S)+-Hb2S!hnw7geDE*^SvNPM{GQ;`mGL?7Ya~KEL$Y#GvBrT^H~NU?w6v&K}gC0%;|JpWiQw>55A`l#HWLT_~odYb1&7nckF zlk;Wr%?=&SN2>H64HFvBsg|9{^|NxmO8peIkJn@2l`Zs#>sR8&hIDYRBembOM=4)t zf_q@6*)$w}B=QqyS^t;QI78C2k@LmlvsVEFQCcSg-TDiAu3z873}{h_J?VWB`lZJ7 zOUG*@&d!Q~;|RgmWu{*N#~ahW@Gcah*Ga5z#@E$5L1<;TT-N`^`O;b5fu{ZTrRg@x z`RbAu2CYXK2(R~4`um16zTR4GMpEnHB&8{9GL)v~J-Dr+LcxZMgLp`ff3#_>qSsd!C;> z^voPRvbv#vga7nN?tj)ftwnVjwI+x2!hh!Z$)p38Fj1VL_TT=7Jiqcj+#YvgN67Mz zeEuN#oFUn+??gJ6l>3({ir()}6o?uQ!oTGGD^X1v(XyFNGX3NI(-jSS;JN=)+{pPP zJ%1_V)3K!?O}*byrhlBz3o8fW=9F-Z*eC2mSbWzyu@PxiI8hA`(I3Y3ug(-d3=W8a z$tl67URU}2o>}-rl=ob&$ge5aw*#rR z`%POgulZSQeOZ~`Wd7yHXVLgmyaD~ogn!BN|GSqi#jzVX=+Ig8fBG~2{A@E}wxke+ z2gUt!eOr(p3;nN~Wc6{d_-^9H2z1`E20cr5NPi#he{K(qLDBe)7#5!(JwHD`>qcB0 z_W#^0tB-U2)2QM?DHj9j&DqgP`KzhuZJ4)o3%({UldjMEr~Ca%!TXQ9q4q-Xm&N*5 zG+~4Z4;`SkO7Iu%Qbp!})zkljd1;2U5X$+>9nb{ze{{vd`=Y+h=id*^u1O*Lnvh-f zb<+KD{+`WigNjx@D$l=LSiK#+tJ;rtTVzP~YAnC`PQ4?(UL1~o1^-=Ne!h<96GKYN z>PUq>mGfCp;({Tw0&yWqIiE-OH>UQE&NT1)K1n}0pHbO8;FviDE#?Wnc>nadcth%C zubR)iL4)wsSk5Q+Plv`C(-*tWbpMs8uXFwM`{Re#ucFZ|Mme81hBuuhP}2Ve4erCdK>7SBhA%jq)zG=%A=Usxo{Uav)A+gsA# zkDrgVq|P$M`FV0ad3{dvf*Cz;;zmuZr%3w9`7E)F!;NKfK6(D7N7u!;H)9RX8sv%f z$NI|xhsWT{s10!X8!x>do_`sx*uQX9usY2Y)_ ze+CvmE;%;}25E9WwU~b1&o-j$&7DZ^fQ^fYf93VN+LtH8|LZc9e70M^1sa8?VC$(X z?3upq%bANFwNi1Wa=w%Exg>Z!g8LssiPwMetK7d$?H+~t3jcQTZozLgmcI!LS_;dJ z+wf*(Z|VB3tiC>@=@PtaycK>~GsOKd{X7{HiJ3LlqIZj(Mbh&#KHJxb!5#H19BD21 z%yO02A3iDeuAHN_5f{DJOZI0OpAjxgQLtbuX6T6gC-+Y~cU7F-H)=NyH5UA-vHiDy zH)@P;{TvW~Q#pV6k##8cPYZg!@Pc%Gp1(;R)fAB*-B7R!U6@`)o#g>aG>` zEPqqAb~|XT@kYW?!5{ZePfpOJ2j0!dc4UZT&-n|e-3gIl!!XqUzw68O@oKW7{vY0v zs@AX(*Jt(f{T43Jdo>0Z?|zp)=ltEQ-dHg|=Rme^l=Cz)`HLzUg#70V5Rm;*x<223Vr&Of>h{Z-98(2<+6lbJV`mbt?zkO{Q zQK_A3{ya`i#Hx==@MX+1>H2*C3B40r5OU@u&b-rc5%HURzNm1*A{4Aj$MInzzU1|Z z5Qn9hKWi%nulJJdIX@d3FF`=FEtq|3y7W2Ee_9`nM)HYuviWn~KlTK1*gj+<@_#7j zqjs%!6rJHs`YB#Y^~+p)2?}e-^^5zLTUw>zk=ZW%lOX)dW{jVGa~k7&QYVa&?LR8_ zFJtX>$o*YQI%|DNdcQnB6I|L9@k88@v*Ew>E7z|rFKSX}Z^iug-8GUuub($Q*$#ot zy^(rH@WbnSYnN$K)2U4<>)=$$KAicNEmJyS>7k*}v=rCp@!z66Bk~Njro@Y7_GuWWx_&QC^JBbxWfo;-Yn{_y&^`)5}i z?mGq}rwjj&^W&;vOeNNx{?|XHl%LNdJkenIWY}kj{3OqBrkggQi7mUx^aredpr!AN zi0KPpJYDd``?sp*nUI6AqssZZVV(i_Q@+1!f8ADl@%@7^ZK|^v|>K{RXUt2gns$6_^j)VG4PdM}M5|78AzV15ctrq<7{6~uMA=sPULHy!E>Hc{B@tH{?&S>V~ zSkN|U{lQhfe{P{-f1*#r*TClPYGKd%mv{79g@k9qRW%D_0rWsRbMSf%UJX`7edH-i{P6ta&waiakNL9riT9V- z#F|ol9Y=bhFY+5)pA63jpzEzDS$_$yZ^1t!)@Wc#0R|80Ex zMzmi|!H>Ukeugbs3>UWy*l39SAlI(}A5&rUcqf*%~yn@l0BdQo?;V=l>D_a{`^_|)If3m$r01_ zm|rB~C!XI}y=kSwzuS%(XLF?W6Ye7CFUK+(e*H4h-&*j;_vh?!H51+T@5SGyF_L`< z)357JCYZIjqssWn)2JEV^z8zg{$G7s?%(ws+>Rz&dD1wyGt&3Fvi_~@^Q}>s*IOk& zi!axq1GAga)*sU=?dALL4eR2Fv44ih_P6DHZ3uD0m%*y}c@k<&M>7@kH!Aok9_59h z_b1{(C&3TT54s*|MaOQ)_lFN>`g7@{FZw9}JNzVn1X!ihHa<>tDgtPtM+s$5x#mkf7IQNnCe);|h z&faO*-ghTz6bn9hf5_b!Eeb4eLjGU8l&=3_w__2yWG(C-3Vq3PmG9r|QJjQcb+hr# zex-DM9-nl+vkrAl55UzUPWn8H^=BAwFoEAgdzJaM7!6(eR=YWU-7MmJKEJXpw;AeQ z?<`xt{P%y#+B#(H)|C49*&tn?*N@*eXpd0E8Oo~Sld@h`bgP~x?b!0){EK}3c6j25 zT_N)I%l#|wLtPO*&mXs3g#X0*FU*p5AocxeSZ8-r>Obun(;GL}PL%miJbsS~Z9!FQ z%l8N2>$l6nA;8W#xV!ni^!(g^3O;5=qrDwyp{w%W|M}|UaR0Aj{;ZwwpKi1Gq)%`z z(nC)oTkCii5kJWNC%?y2v9Nmr=FSrSPYH`pj`(jyg9}Ayuc__wuYCzy-_zbk;Qg6Y zT%Dvme!u-97Mk1F;PW7{KCRjBZ?A6&=%AP%xieDye(SRH18TQ8hG4sUc(nVj^nP5K z{}Xg~4ccAZi-m!EEALNUfBo&W5_2NAA?O-@@%Vgam;+qq4n+0lqW_)$KARuyh9jN)@no~|^?kp*DY@KqA`6#8O4s+SLL1{tSzmtEY`oU{0^|B z>^>~-ZWi`x^8IT@tcpX~+%+=)r7zJLw{-N}d(b*r!qcR{lG%ed+Cg}mHUVC z^{@9*lae}_(6^?Q`CaC}T=4IJ(^g(s_f>g*s{URr%5yg(>$Ovg#P6H@_dh@}e;=qg zBm2Me&H3-YVcLE?tGI+mi!Ms*pU>}C>Cg>Fhxp-7D-j>?{-KEI-stsx0xlYTlCIDB zD6(rsy^qQFr{TZI%a z`eq6H{ZG0$9fiFTWc@#UzA3$Y6X?ugSZdam){iygBl8T>1OU`0%6iit{bXaDL9tN_#mU=M?8t zEj+OvPauAOxqrW?e+bQb6i3qorn-vtA?Krc_B7Jk7*DA+5~TI5#`NW5`BbWz7e^0u z<0X4OfB5vmO7tJH6+6!-75)4D+`rnbVTPZBRP%A=k0#kKG$!q+laf8x5Bs#{SVPX3 zT&i3@I$74Hm;z%OS}yXt-2cy_4#-;KsZu{Q`qm+T6Em9kUht#F^1FVD`HPAn17+tc za(%ISy&u23Uc!~G%K5o}w;KXpkA!PC!4LPZvW_TnbM0NoIP_>GfAaoT>xn+tS$!fJ zUHl@wAD*AmJkyFSMycj2u3!kxj}65(kGGON_pfFiHKkR5ZK>@rF<hM#N_wL^aZI`FDMQ`A;tbqfyu*9iGmjzkut{+} zGAak%R=1SwdH(m#wKX`gdl$B}75dK4C-vEz1b4$N=%Xh3d-!~Y(eEO>iob*Og@Qlc zKaiO3M(t+}r_D>7Rq`X}@2tTxgg;o1X1(@F?}zVycx3M~%uCF|>?2Dn?_bW}sQ_L2 zxVkBgn9)ore|9fIX#2c4vb9pq-!tP>)VsOuf9JzV*AHj;tx@LnD0yx(()JVUuY|=n zjjhdK(A!qlf6o28x%Sm4=#n1way%@3Kj+ipwgp}&`q$sztdKtE`QssTwdiCc6Uw+N z^o{fRH{1q?H9S?uH`#lp)2`Gw+8TUbJfDkP-@YDjLP5^~@Y*i?KQos9${ujK<$haK}&56SQ zJIMR%GR(+U@t>mqw#&bK@c7);JrMiTBCyCy@Rz~#ZH<@W>;=XAQnZ!WA6U&z9^dqO z7m8~)<5kZ0?s~dTvH#6(^te{t<=^Y``2F1MaE!`G1S-!rxy>D)mRsU+ageENC`>G`6({3 zLEUk^5V1kIf4H%BJt~Q8N?$x@3VxWrZT{+nvD5lvhpXVnmGRTx=peqEUPPw7a((M= z(H*-K`?o!*_$t1i?Qd~4ryT_???x6Ej!XRU{u{4LeGz>wNTzQ*|K;c2f>J$HpHFI{ zGaRcQrs)SQ`uUGB+08Ij%Fp*535e^KiSJL>NcMbxneQQW=w+}m&8`1m zd?>HaxF^)1y0ONz(MbG$a{YR1Y>rEPZP2f+a=xb4tV5w+6*cM!r;5byYdu;2>gi7{ zVO&dbhV@6~^%=`STBL2&m`3kc?q9apU<>zJy;SPgRmJ&46Z4u-bbhFGecnINGshWQ ze)PkD;ex*q#$WGV2hqal0u~%mu3uLIyF)E)7}Dn}=Wld9D>`?(E6rJ>oIg#gez(XZlg(+#sqlL-6Iw`qvIMOv2m+ z8}L5$p!E0W_0Npl<5<1zHo680zIgp5xVa9U>Ss!)gUyxlAT|NVg>oY&82BmYXKJrH zG{>hg1$I@gU$5)hp|pQbmHOr9Se1gpQn6%+kQ4jtwtT>=LfO*h0s;4up!D3xvt9B?@`71JYS=Y$memU^nQ5!l3Z?w zf6RK~dM%+pJU@MQO*I;Kt1g{N7*T02U%$R>oN@P~w_^V{uem-Oa|L{spl<`TEv(Yo*wK zK=u0WFm5DF!e(H~a`F4m^9z$*b8x81Vbm>ilzzWUSbia?a}fTxhRfm`p5JahY72%x z+=qEVqJCMz=KE^f%!2LcSXuui?=NdK@Bs!)_>6E(<^Ixqck(nu2dyoA6tIt5_ebzu6~!A5Nv6M#ZfH>2t97 zC8g=!|D)@yqpJFzHhxWP5W7)PP*4z1no9@*7TpqJVz-zyh=qwF3W|Y+2#R3fvsDai z#V+jb?%#RWcW*rNt_%O3HK#bAJ2TJBo(&sC32HQ4$&XY2aK^L)Y7FmDsef>k*6v-p zc@!I+r*r#EvVTIr!!8IdHJ9mkG`}esTbKQr*_?GXP2=`aME{;A?LTSSqfe#%Wl2-2 zOM4q>uzG6)E9~WbJ$ACfk|+J~b-d7rLP>n(Ra$_=CnqqXb!i13a(!U9wi9ON`a#oG z#8*_m8)&G{rVg-T$xBu1cct3~qIIiq-1ioIT_^RU%cHuojF8Itn)!SXI`5h&%Wo)O z`I_6H^QQ>5HkO<(y8dU(x}iAUdL~wX6!FzNq8~)omgb{0PL$O@>HO&aAzj&PcMCS% zYN7JK-+vlE4X(Nr#!~*Bt0&$s^&b(}rol8m5uaVb|38$EVZ&Y_!=VbRaW{*fpX%dL zwsF|JJ_TQjEBph|2dnj_d20>vrL)Mt>HLPW+j;mMBgJ^Vrg3{MJ9+-$ zw680^Y&Neneo{M?hsk4(U`0nqaeczaREu7yqVEK&JEH%K_WxT+y|L;U4B4F;RoKh< zh^T6f>+}1=X|wqMxe-1>2K2$`Vn11aPyNf##9es!pcqM8Z7cYZ>({UQxnX?5;7Y%L z_1=1{p{@M;r~A_dI|L(r?*v(Wh}KWH=4^#=Vj=Qvgnyy)PmJ4!qx6I@75;%VJt>4;llhLz5z95XW? zw`v|inWNy#mhkoHkUnM~vcR7Of=^n1&3=%FJz)%6*7oN255kvEPg68(;Dpg5|Jlpe zx4qrE8ynSum>|sxdpTbr+SV|h-cPo_0rfv^|K#F{_hBraA@cJiJGuXHS98W6D?fB< z{Dq&N@^@pC8@v~VA?b^Vzo>uN_ahjw_2m4}{Cswa9{ZeY&i1^i$gh?1`CVm>Qh%}C zY@F&O@&oEW9@Ou|{*EzXVL=u87@3dv=Jiy#PLD_3cY;6KUsI=AS5~FelpSs$^jWGu zzf9}Rmd*2G^O}kHi{{_CgQ7A1#(Y@KKEdCQ!d5>2ZgGu%Omk5X8&`(c> z`{z7vPxl`-UOxieUS4r&TTG>QzSE=rqfjNVY@mJ{Z=l;?b#x}$|UvG z30r5em?cS!nJnP;w7&WvxBw@A9EH`JUHty2f4VSyA7(ZyL9l-+KTi3%rQH!z+zs$( zdxd`>`wv*%--FGeN6>V*h~G2_KjSBL!@D6CmChGx8Hc?j8Y81JSDer(D9AkqHTD4Nk1>d{~M^U?hN=7HVN`&*0=+XX-42|uY9oshr9 z8;0jae`P4qr~7_&N8pAqSnd_^8P%WP@7{qbD~j-clHq^cL*@p5+jBCij_= zKR@wbXMn^UpUuO9`GPOHf2yu=7A}YG!ucJ7FRD-fS{4O+ z{bbCE%;fi%OX9Z#C#kj-w+y%=zJJQs2kiPfBL9b zh>_=y;d?^G`APgYV@5}e%hMt{g@%yL#Dbb`mp6Xi2=HpTS zl+u154(Cb!v5qshFDHB*J7fl{QI3`N2aRmE7XueESi3gn_J)M7{;QPGFYZ_A{&KfF z=Ht!S!^p}wS`pvL{ga!T3tn9ELGVeDAB`t`Ro|Nn-zx{Pv!jR)ZSCaoA=}>%!6yRn zSRv{!l)vYuIf&EWFXNBuYdiXeVDh@LSo}!zH_-TS$O1jq+{2XZOBDPmi2g9%DgqG$ zXQ0cDr~Lg;{$4b3W*;wjvnF!`l;Zba9v?orHwD|J{YUOE74aeMFS?YR3%l%t=#{L& z?G>c{Q?2+jQuOrh)az0B zzH1)t7YhEWll|i^J)6Ytdc?5qJDn^1kKDh_Xci5(kMj_`LGTB{-vFOun0@{t60aVt zct7&~hGVS~(LXE&`87m*r$yq!v}1EvN3A558YTFo{_o15eK>IH2!hTD|3~YuI%kS- zA-DwPVXOH64}?$smmTp%t2Hz+GC@V`fUByML3*w48s~VtGK>Ae!Q=%MBRpcG0;ckXVm{C zMY=+(sV_bs6Y(Kke{FhoH{L%#hzU%x~9 z_w06r;BML&JWdw;QGKHB;|QcCM8Y6d@I~Xtv)!j2>2@UMi0hwt{{79em-F@W*Hr8> zh{e}(!557m6%7s8!f)oR!Tm)_!Kb{xb>Es;^gTBpP8PTM`_(1;$E|4k70%Yx*qj8x zAI;B(nk8do*;3j5Rv_`E&eQ?S-6N0{JQn=X^*evlqi``J36@v?=@0Vxm3J*-Fx@v9 zRg%~9`=k1ITJ(CnPT7uo*VFj(Dad?-+tm|sdCX!oo4lOcyAi%vzou;E<+iN-9(4%+ zEw8UGseKAg6UtCHdLy?FCH!3JtBrSSyWygtYJP4EIDjs1OK|A@9Bv;)^uO>K26#Bu z9J&?rEvbJy)p9>FwjRUPCa&CGLHJpbV~#$iy({hC+t*`1Zm?spPZs>p^`(bWY!Ddg zf_C=>AC#Z_+OF7|?u}Nvg#V)YUbW=in3#S5Wlxmc|3xX~{!25f9~vnAFemmIzyEBa z?}b)RMdpf(O8r;XmkncY}=q$xYTUF2ufe>Lwn8V~a$@yAnKpYnA{ z>MtBS(1?xFH&y=k|EKd^(*hz<6|opP`~koJZ)E*LmQf56R!B2W9d7XBR3AV2!h?Ok zAI$owJ?7`9{G558gdGJb7_HWDN1yz^{LS_^;Qe5-?}nBJ?U1{XH6lACLa^ z*h{ZQY-xTC&QFw5&QD|a#%zXEe=<4$o}XVq`hWa(X(RWoK3qOl)R#znxO`?Q4rP|1 zk>5OS??&>kr%w#fZl4(rwf$FLlCOWe+rR>WVGfn*6Q6zRvDzVx*w9_!7569iFI{RY zF?WqKE^ZfmP<^7xY*$!s@RI4@RDYQLC?AiX9>l7%b|OAh$oWuA9*7s${o(Xh#CKGm z2>xKex*j!?t*@s210WD81 zKx)iVetyc&Wt(Q~!~HhwVvg`XlpoWy0;I1khR+b;zd-njZQBWR2k9fOOf^5IyG~D=3*A#P6T_pGH|0IDOf^Qogo7(qvD3TCh6H z$8dYv-_zxj66vANvi*Z8Uq2%XQ4#}Ky*MuX3(+qgNxkd7<2+%%`V&7t&96+O+)=ta z010t|4;sJSzMG5N>kBLOKRcI(V%eAoG;x#)JiR7Wos^FOHobjV>nA z{vCcIzB@_yvP9ZXBzyvMWb4ud*b^c`g*D|8mnF=;9)<(5ABaz z5%(3DhE>@4gm|U!Z}R+U(2H1j@0ka+T_^bYSCRZF$?Xb0?YN7EHi93jUwl3jjjnSO zW$_ybKlATJV~ND~%!~|veyUIS<|jcTe-XyL7T-6G&vK;wyK2tO#=0B3`2E`wePT$P zPHf09J=Sk{YnA@T=41gz9y)~JR^t4$KD9erTiTnYE8N0=@%y9tM4bcD{(jMI*t|6H z`$GGBmJ}Ic&m_}I_dnFEVTq)U_La_O{F!PC_Not>_4vxKA4Td*ug*#SCD8-sCgS_1 z^E>V=^TFNXU>u(>{43Q5Qo9(jgYV`3gVv9hKMF<5$s;lDtH__J|ESilJDV+i-yJur z{=R2EAC2~JreH{kSRY5{Lp4aug`;vG>fAiU{f~n5C(ODw1Mhmo$mZWreLyGCgXJX$ zFgv!D|NrTH@2lIQF)}RyAA`mBpH2F&s}`0^>yw_t3KO_Jjlb5H#9_+ic~~{{B!B-j z{(5=+3eNqygX`VJ_fPYez{YVH*J>Ubj@!fS>G!YPaSKmsJ;KqyyDP3Q*AMF3#-hG5 zNy=YT>jy{k6Vd7J0%(sE@fYQTxvj^6$y-ovshW?{&mGzH4qce?TuYUF%)ht~+twYz z@~MK4OyXZG0y;rwsWhWIQ#Bu(dNg4*p0;4S62<$Yd^m>nK=6-V@T#IZK6~^l9~#?> z;HI$S?=OnvH>uLviCqhAW&6v}`TNbxHQBVQO<8%JQQTgG=y(3o{0{9WPO|uo<~K|C zyJEVQJ07`xBBU-`j0B9R+ox;E{Tl-#^X&*9?$mM}IBEoYopj@%t~& z|1X%v;J#-9I;~L6&qnV;yzX3#*sYEg_HzHBI2Hx3vN$v^Wc>Qs#DC;1z6Pg3ck$|u z;D`E;U0vcZ)jJ7>Uqt*x^Oq-GZ)10xhtRzw_@VJvjmc3ci;lz6XXzEsFQ0D^bo@S> z{Nx#P(!0X*pK_uPXyhlr`(rZpU0=fODPM;rz8Z|!42Nww{Q0T=7T&ojTU4_p^SCa4 ze`$VGs@)lz#&*TaRw6#5{-x>6`s{oAhD?3kA%1eZ6-L;D|s`b+xr%{?%1tuNjmS^x08+!nKMIpTiZFZ_5C@lPLj6-)cm zAB9@kX_4QM`E5Uj^u>>jZs-&t_{t{wcW1`~NNWk0y7%GsnM8kUkm8G}T7xiJU%X$+ zU!QSdcxgKvuFX{Q)il_EJ$htZssHkI9*gp^lQA+^HD7IOS}>o>Htgj!C;tDZ`A=1o z>1dHY2boXr@b^ROOWJ=uSm*>l)~dN`|8?y^G+H)^$8EhU74KJGUm85{E%wg(j6vmd z`SqhneW_oIC>)XYpgz_G+@A86KI#EG>hO#W-=E6A|0uG)cI&=qT+oo}&sw7YfbzFv z;x%|wy(7(^+R3j^=jZfZFc%XwW3h1k8h(8m-?iSIfR1{}h#sYyulJoVW6AVu@UuV8 z?G*~Sez0suYxbeM9oxC{r#MdhQ_z`Ch%xK}n`h!U^IuMD9sT!0tG+R|14bGoDI%t z#eA|lR6L)&e)OVwe_VBS$BEOQ_;JdQ_oIUtF4dPOMmuwU==ve6Z(a!V^vCiIuem+d z7jEW!1uNFEVVYY6A5kQ}tG;F?EJLH< z<|p)Nst**c@MP&`pHR>zf?E5j^>%SQGJW*?|<-U$^X=o=1(Yu z|DpAt4Wr}Xpp%68+ZOZtOCtK&oMmlTL1{a7)BRt3C7&;nJfbre9M(luwSULu^FKE^ z7vSvmLMZP|+_vD~KS=*}dIt~GXy%RZqUYS6?w^@BGZZVb!qI%c(7$MX)cfT_cBI`? z*0Re4C6Av-eY8`vaX2+;A{Mn#%|~4B1H_d-M#Q6cHmdZq?AyM`c^rUFw-59Cqw$+G z*aVSBW1(iJ`uorE`hcGYKf~{I6u&U(xxWHBaBe>UR%trRfT8 zPxY}n(#{37^rB()c00d6+Mn&vGZrcJ<55_?jvqfs^yA}mVi4mMhX9QQ{5aho#plLl zq^`dLv%(U7+?MoT_Y7#mnoBbxEi2Yv()l}4Mmk7M(?#PL)qJ$|*(cS;3Z?Z$llb|| zN&Q7@kTFKzGm+)*wEz0=-94B$qyS6zDY-q>zsCKwlJ&yLvevUIjgI&?3spzkv^_j?B z(%y>oH=<;-9_J&9@ZqBEfjiGUE3I!voeq=qvv75oARpCJ_MpC91Et_go}bjH{TXQf6@BkS^W$!0KH$L#Q{Wdf4QHYX z`1>&ObxnSY!AKYuWyjG(JjCb-+qRZ|E)&_ea0)ZUBe;#T~=zZH`Q7^(dIzY*_?xbME0;3D{-`tRj;!I&{31b+@c=I5vJ zPq6N9Sm*vm&Am00B7c_G-?i+0v1P9>c62Z1_MznauCd??{4~B|f}I1mr}Yn=>N!{t zmV@-Wru;bl{eE_95>5tB#?FfQHJK#8zOn8yMoa#8O~(b?UP0pfw|R50LE3-8{@%93 z|J{E%iEpenl_99v71Xj4@fTfRV{oB|Ra9z6{eqI^;`n3PK zY4}8Rdpr?O`$zNZ7n1K=ziLx9XqL1Fv10wQEs5`YFY1DtUv<%Lq4<4Okow@yQB7Fh zlg6xv|3CjBUq5i$&;;#Mj8R#C^9r*9)Lkj%018`ve<1mDw z28-{X>c3ti)?n|QH2nVCfq(y*B^!BA5Fm=Ws>>!Utc zQ7-fk%8z<|8->8gTLQQTY3Jx7Q3O|VK;31S_*p- zAFXZ_gQXeKvh_D~|G5?iXJF#(NQ^7q!q5MV@H6JjHN35R4X+%w^YhdEc$RV|LPBO> z?WvXAp7yWA_u7Wsbz9N$la z;D@gNJiN#i9@)-_Fc9BA<>!G#I`$q-gI`!j&W}PNug|X^?T2SWe9-KL>iqda^>W;N zaYx1v)qhKjLU5wxAk@fL%}->#1L)hg2sP3jI6qYXZ64%>_Q4*=t5V9}59McM#sS>C zU4)>1L0#!gw%i4BN~G&guX=c zhwqZM`=ifo93Hup+f)CeWj7Va-cP~@`;Gkmok@JvJbgMEOZ%^1J-VD9r|Zuqe_b!l zkIzJ(%OZZG@ssh~$X5}_m+e75flpk~5ow&4Y z8^VIb{%n*V<3v}Sis^&2IpX`L^^p&~nlZ~SjamErwJP};KG7ddd-}j7Oz`)N_@6V2 zLeR}32q(q~K4^XYS6UHTUn{`j6fvKsoaEon-}u1bfG5lzo#yXvJn=76R=vQX7Ef_v z?`M^Ktg!iwL({+G@om+7WDW9#gRU30h3w?#FDL%x$KNmb=>8GO;UYhw^~HnJX5rSJ z>A16?Vtpow-#YfXi!D!XN;4XlDF5Tnmc(!Keolso_XH$<*}$(){f}Ep88U`m#OH%s zD(vO;#d;o-&_J3|{lZA-uavJN29q&$!FWV<5&Y2n{N=Xu@QOYShsKBb^{IcEb!jZC zU0a%8@ZFNv7Zrq`R=f4k##Xn|_0hI}Ycm~7HMX7Y;peCGp$G3Zk@|Nl=cmim0z5mL zhl1^bA6oy|#>^32s~39q68Q(s&vR}!VS8?AvV$z5;`!wLUz2hi5OhR|qhEyoq5Ua0 z%XZ?v-!_a}t(u<)Gy7rvU}sd-7x5eAXPRC%7M$6L32(Y{eyD!i{g)q3Nd09N4*&R5 zQ~dkuYZwBJeF5kd`H%4OB3QI9z*A4b51pU!x|J6e+!_eAJQ1JK`2y-;(tN9& zJs7YKoF9ck?qAMld1G0iJ9h2Z&#zDQ-KI_c!uZ>FtSjxK{O|jw{-@EV0O&gSAbasH zZm&i3-S@e-knM5}{gw^o_H=z)>C&lKvVMXrKcfCA&vGJ)L&w0sFq5C3);C_8--PbX zD_DC}#BVgeZ+dnD{6CGxlb4IRJ=M4R`=q0#$!fUYSj_J)lf-YwC4Is-LDJyn2)-^5 z|Mbgu9LsAol9eq8$Op)j>rTW*)e)_0Zs)N(`%kPioN2dc@u$#V3 zn7)Jf|5Cor2bthbmVs>k0G&@*I;H@BH}A&S`hqXIzfJqg7P$MSC&u4Z%~u1TB9ut= zkyraP`2E=u|Fkf}5zi;u!hXH#{K&XjBwM~@A{$U3-XEP$)63o+%TM&ho+_XC`7?<= zoZrzOHj_PJyyq1^PW9h=5l2z2f3Ylnb0h25x;FGjkHMapvgkIqr+odC`m^U-?nU7r zTfqmJPxI8u2ahw|u%oGn-{|_8aB2V235N&b!xiBlnv?!6k zQv><+waEUzOm{4XzZ#B+q_zD0Tp;<;Bcln>dk}%xc7h-3e~Mo1!1|%tD9Tt@@qF_2 zF`3H~aa}DAsTqs-`A-slYII7&`Bp1&tMi5md-;6#&6o9Ip{$&bqKun3m2w#_1I76% zA60F7qV^C2+57>@N0UasiW}b$x*G=v}X#6%n;fY|wezN}L3xp3($1S*YcRhUH z>I-{Pe_yoEA8m3y5R@+XNh0yv6|X%Q9FrsC$Cl^^`xgKzTpGv2P&Kli10 zIkXtPZ3{8#dT-7T&3{%z`C{UHHzaNq{LuMM-PEPr;87Y{_Sh`=BmOC(l{Xq$48Q?R z!B;lX=iUvg!fs6b0l(=k{QIH)DZ8Dd?{#xS`y5gK2qk=toqZdcAy;5nMKxa|{6i4Y z(GR=#i};Q15B2a?1dcg{V_JC{e?OF;R4KQ?;0O$H7W`2C!1Hx19(d11d|)!SuV*ix z-~L*fZPs>7Q?@a=0rxMozxeLBizr%q3O-}9xINY1+QoFkcr_g?XdwExsDGJv{w7Xl zT|&5K1wW*|^2((rZpU>;mD55$qx^*Lt;g&qtFfxbMSM#AOE2l$Uwz&f?6vk z+!ngw<_J*}`322y(yUss)bUMN(-T_!`KbSx^Uedm)ceZ%hpGQi&)JOZ$(dO9P}EOo zeK92<0Nso|Wd4QjFKE7b5BfaaDdU6c105UrqIuncXzMQgJLTi!j658=upKWOnDOsB zljJ{(Q$2AZw=Ys>9_P(BxY` zXwMP(G40Q{xpN!0)|O%Rg&|52-^u&KEH8&3d73YpZ4=+W8}Tm(&!(gJ!%Eryo#Tmr z`I|Zx?RE`?+xv9>d~|(uvsL@>=U^`0*^Bs#_J^gsn1EOJN1y}5_gRnV*UhJ`!ISJ2 z*mGeazkjM-J7E*I z*C6w!t650>ZD0Ch`g6f&6yY=CZWVTE(KkGAE%>DU&uv4zpk~<@1D0j;_e=Z#XUw^S zyPq%1_@w#Mxd!2Q= zQU7K!sgCsg)!53+2Hc+V<#fRlb+cSBv%iQxLHL?*dmUmdQgP{{;7dW`zh*W3aVd3x zZ2o|TyZ(mrw?uW$z*ZKX?{AsLZ9;~--Mf{~+D*YQf;SKMY zzVMy)Z+(hh``gV|UCN{24 z#j_2FtW7^R-Y07f4aWL z%&BvuBjh8b*a#H#y=`U%yy!}oT_VOMP!)l&WazZrZ5Z?~R=Z*}3{Y>EFczSt8Deso2A z(GUK9C?7!ug;2}iiHSDW{5b7D`;lOY96v*N?pDo5)}LA|>#~Ar4fEjkl#iAtdLzBA zIoc+^t@wsZmp}c9*;!)NB76w(90WrqMV_K68?qupRL!)gw~ps(DxSgRSm*N z>ZAa;jOmYMhA;T_>H4)BtM6cX_yxItA^KcY8(*|_b;YZXSGhgyPs_XZ8zy_-VA=R+ z!G}UVzwO9;FQnel!0l;&Q2(W?upn|VHeX%K z@1L%}nRF%*bAHUmsNl)mp3Z-JX4ZoFJFBxAw_oz(l;0^^4WR6;U8#P)td}lpDD5%+ zcCz?=rutyS{9bsL-xVbdMgC<={F`Oaegrz^;L2E$e^GsKaxH5ZmKfqh72#iKe0Vvh z4%@%03UeOk#qU3g?C*gY(Os@z+oE zztQ^asJ9*%W9x`S^Go9TM8C_?&qv3FTQJ8~#BU11*U~&6v?y`Lf=xo7p!w0%)D0L| zcNKOv7y2FLtERRWs)adWi~U}H{S*?vHJh!*8V&o6oyo#~Q2p*{UCIB}az*bATe&^m zzu-Z+KUNm^#o+FOpXx-P`0k#G`7c-Cil4}T%1M3p)Sh9OddL^0Il@2blKzIofd}Ex zJQr)$yVTqxn%Sv-ZsBWfOK`r-sVt;u!+*9qp0!$mTvdgvELVwYpMg7;c?!9njWEZ5r{Lar$ z{g;LJejIV!iKow0`>&7Vt+BU@A&MV=;`TJYi+#BtF&B5jsI($JBl%Iz$KKf9$rOuc zy{-8F%Jp$~sXqB+s}o-BRsH=pirb4ir?X+FV^%EU7kU3r@MceBT<8tAefRnKR}uXi z*W3_lVvlC4&-3Hd|0o*&g~IqXMhvO&KSaM<=kE#IdA%{MPK7>1;=8<$S-3Q16`s}G z!u?k{@js0%rTEm@38(g{=0i;v(8$e$MX9DzmH$b7=!=ug8LXk;gX#x+0`KBN$vH%1 z4z945`=7){gRpUVf8?u+_>TIY#kpFKkKw!)`-E_}%SL>HOgNsGSR>^^cLbdk-+vV89~xm$hlND` zm11Dk@nM5*4lo;Kg6lg}`h4`qm4U1|Y;QWB}ul_Xm!7w#Bf3*JeaMxaFf7}Ai zOQzhO&X218+!xnZ^g(Q<@K1F8nq7-iIPpk6f0XL$#yak}=wpW)-m3XDeDMpc^f~4{ zn9KR1^`}P66aK{xh%P_E|NohUPxs*)(dN69e^u~F{g-2)5A-`b$>Kwrf0bVKhfA;v z_GxXaIKRAqwR_<`+&p^@=HVj#qxIV`k6^Tl?T`Dhfsy+?1wM70y z{nu+7Y3-YrCL5wvQJ*4w9f<9MX~$Y&pnsJLeXok*-=BSo#NUSomGW04^$zvg-=Wg@ zZl>XLIQ6*-Wyj_G{nPy$i*rrU?X)ghrmN=9K<5UYC7(cW>mY7V`;S~LY@j&X9qX3} z|3>4xkKG%vmRqW_gLVA4eH8I;M#D76eGug@IH)}fb85`o&TruSDM7DPPys2E#soAi7ob4_zSn zRnI$;{{7fT(kKOAw0`T5e*+nHPvWRa1s}F@eL{Ep74WSCY}Ey{(nk2 zU!xUW*?gB)tnPThAN6mwJbK{QxAv9le@m;^Ws|@C#@SA}{QNY2bpL1ullQtZ{oIY@ zPt7gsu&|_G*mpoYKlN|dif!OwRXJa8TGeN^j}`3BWpD9(gf9zeHeAi=MsV5ik{_q@ z4Ya1!XA8|L=c`ZAKrAk{Mte13pG)-hI_nDImX(dFCFX)J(qBHTpC5Kf>tnxGtgoQ) zWpJ4X%A^{%&u!KI%Olqv>d8vjy*|wEpVog*vn|+SwHnV81z!phKfZMIhV=z|l=l{V zQUB!H;3Q@oDv;LjHdFq`7sz~G_jdl$+8-wbZ&IyaY~P)OOG`5<fqbkW;pofH^09q!q@Bf zHCaaI&rp6l!;jPaOxIDG|52m8Y(71mZ}6^ZUDh$@7bchP67~xD`lsikq}jZq<$O_n zqV4ATtcTQNrgeEyg}q#V{~lt4O|SG}6Di_H>c0-1Z^dRL)@O&JM~UYneAUnH4UhFk z=&@9_{|esHfZbkJg_WFE7uP58V+&t57};1OTuU`yWvxANPwLN&I(V1c)AfA^x359T zu!S=HP>bk?b*0?H^tlqRN(5iD|6+^#eneYu#fU1F+&@K;{OwFXPpNlTi7L;9f1~l? zfkPgcGg^sGJ9qQ@D<}Fz*R%H#FYRA>Wm8w>e|*^zzJ3pt>cd+caPn@o!(Yjzf(+e>B`E`1^nPS*;A*nw$ck9t*iWh7e}%n#KErb}Bb@)CCG&rj&nI2#Gv{i5(cz2u|0{_8pQ>&Fe|25t+!OjC z^?ym7o?`t;N&lWPqT>2;K0S<;IGL}Hq0a@MR6mJdRe%<6He%(b+7K2Jk1V16@+LojCecsU z`KQCuT+U}XsUIip@j|GUEi^Y@sJK6Q|KMWF0<=%t2)zkHf24c{8F<5eu`TjCiu{f0 zk0l+lG4rmpzhiyjA8m<$9Jk*Skv2+5izxW@PZEChrM(aK9ovnBpvFp7{MH=ci&>HO z(tJU|FYTWS3&=sMS!>ZFP&L1QdxhdeylbWPGtH%6pu6ubj7O{HcTMC-)PCrJ-OX0; z`=|V_%E&^))5~!8$uxfd8l--vK6Vn`ln26hlHkvbeJ&1zaF~nS&z*c%*0J~{?{`~7qQmOpgm4?e0qJZwEycF1q(hS`U_}$ z+Ihbb`i!ca&&wa`vA#8a!^}|dN#oOQ&&;8Ar?a#MK;(avPq(c8)b%e_DF_fPegZ^;Fyb3F_9Oa-4b|9jlW1uM6jpy{=D+@A8eWr8}Z4FxN|sM>!T z7t-q#}pEuo~>1cd5t&2rAY8=OY*;a(>;*%+zQ3_Zu9GB6MlV}H=f;6Lc8h3 ziu;rExkOr@Q&f@#9bMIYF81<4-B4R;4Ts>9u0KgI+k;t0)+1u~9+mmwE-No+%(a2# zPx1ew^?`a3CFsy&H?|EGeA4*!jK4R&&ru?NE7>O; zFY5I}wf7=^O(OXr)7XZZn^s|Kskf5nr$ql8_eSbX)O3e~=W>4i=0u+v(tRVo1ua8B zUEyCr{Oi`a)6u?e2o8S~`X7yN@BUebv3nO`+VBPZ`cX=GeEY^P9=f69(4kHuzrKRx zmv4HVLQvWsWE?xq?P-2#oj18w*AI@qpRZj z3b}thV{8oHhwUo$uS1N~*^z|5ST--8+f#mZZ(5?x8XejC7DJL>&ewkh-NH+_YdM?r!5`&!O}l;gGB^vmu7Y1$U)S??M&2PKylMEBpP%wO+4%r!x7dPo zC!wFx{;eugJYaBKs`0OT$?a)=8ROZJwJ2)Hvev2AZ%(9mBIKwQj*Y#;?Wun1mgpt* z-dfA_Q5yfcIqyTC#4PyC7W`6u^i!q})aEL&VX)wr>N|J8JwQlIDYCvi;QVG1|Ehh~ z3mflPSIV#1qY|`Ck?PMC{#AqMJN0Y$!uProF7})F^U?bG{o?KDD&@a5OZAk(Kg;9e zp{>KwaDyv01`2))3BSP|x1q|}RNQeB{L=X`MVp2q;&DH0s+b>1*JrB7O~DIkjgDWr z@Sn7QYsZ#&+?8gm{r#Q5@4q$S?^5h36rIk;heXx<`Ob~SsECn>ZmOEUlfGT>t8dfF z{paB}>{gX}EJRy%{lZJl7}<~7Ryu!UOYsfZ+A)|IB=P&F@vWDu6@Ist^QS@hTeb5w z96m_v2Moqk*vsSF2ZlDdbVe7h2L*pL|Gb-i4>41Z!_rQN+n1C4({-f_TD>sB)hhq& z<@Ldo1MS&^WObJ5U(ugT`oB8#_k`U%OB7ZU`D=Cin*ZcyMYe56X8K5jsp$#+X#Jwc zWDgXalxEnnTm1gM5&!vU_sS5<3QAB^86jF$%8?tcrt=K<0itu^Q)eDm%tT0Dg_*bgG<}E)0 ztGpdBOKzwX{!OmGwmT!$#uJp7IbHBcY*`#~&r3=xj8XpI@8sd#!c`4t8FM*>*yorTr@hlyNvbb|i2` z@LNvw*`I!0(bBgmZVmj)&#$nR>$7bKYp^Rf{$NH6s% z_C**Gm4&^73X8?}Bd=dvY3YXit){qo_bIoh{_pOw4(!%ub@s$%eTBWeejne@8>UJt zM0OMU5UpSI{<|L2zAcjRry%*~LTUZWhUb>D`Ud6ir}|xV|9KRj>jZKBX#dNTYd+9T zx5lMSjNd=)FZ(5}efyQZ0S-_TAzUpDt*S3Eh}q*A_ehN-jCxSt50s5(9! ze#RJ=cDAW>|FjdOH=$L27(d#H=PxJvPtYK1%x%~i*J`NdZ%6a?ta+dM%<`3pPiX(= z&22XL(o;tkpHls&@2Wp&=yVTl##!^{R}el+JNCosn#TBbT<}Tb)6gn=;B(euS{_!Ng?9fM>1vb=R8Q#J_()!|uO`dR0H%I&p;U8&yno{bC zp$E;;Q2lJh`Q`bg@0kKP56ndI1{2O-6xpA*<9Mk*^sSYQzfj`;W_R0%85=X`GjuN#R^y`BBAZ-=#vPpaR-JQ!ad z*h9$#e{_CxM$@hEbyI!d@xQ zA4~jA(9En&rT%a5C=K?x^d}};=U3Rv>n9qkt#PzZC#3HD#gEheHcj7->{WOJ_GJHh zew_Aq8V$C^n7uk!l`i51KK%`o7y&~Isd z#U*qTT)L*n{3oriOw{y51BDqJuAJuAr~PrI`+Shw%@S>*ME!*Fd7=M)Y#XrwFGm)t zPNCzKFZAls|thqVIU%8CpLn#fjxRxjmg9H$-m? z+F$^}nc$1g7rog&7LziEK+#I{r)3iUo&-pHYb}q!jNzmB_38T4Mx}a~aJwCBdSYp}3M+T#96ez-l@6Weu7F?W;Ti>`l|KCUx6W~RXm*H!RE>i@|m zUifq06mwjK|D$}J-jRh7WtG=QvbuQSe(PRXKekl7AJTvGX+;6XnXbdGImVoya#FvH zlxFk3ZfuPS?L_}6jZd$)_QKS&rg*C>_@en=_K#fT2d>6fMK$Gr{H!AW&!VLt;_WTb z;dfTW`<3gfmz;C(wni%K+Uaw9n*Vk53_z5Wqg1g=<@VQ!J`Z{jZjKvzYfp{`R_&=(j)_o%Ft*~+kdL{|Jq6lAG#-zdIVmwa% zUCpnrVJDwIviDd#lnKKyx5)^8|J1+Lt*sA3tHxjks`*RRXvbQr*Jg(`h5kVK%O2em zPM)o0{Q*&AK5EmI)s8GX`heY?yMg!rWRm?8EsbqZ?_tME*XOk?xB}}=g=n%+@JHj% zR?^-g4W@NM&2Mk{^U?V8{_OYY*yI9Mdm8cMl)n!y1Cg9=gwvZ<^Y^7jXQtLbo!P~A z6z@+d_iyvgc_4XXPYj(Z;!nE1bu??u3L8rEB@V0>{*Cb0FHl+Ix3weQW}^1E=`?r4at=Y82tzlnk7j-IMc2=Wn%)kb1{phS83PE9~X# zTXoWR;KTmqs9ALzw;yjO?~j{Z%?B@rn}PKg`5~=;Ol^{fArn{QTa@5aLHO+J=Lg*g z3%oxr_@w%2_t+e)3SNnYZ-jrOd|FrpLh-~3Lt+J=-w2=E)@{a`C5tiQXn*B@zYm$D z{!z3w0%b<77*Q(tJW2GKjKqm(^TQ3VnkVu1L;YXUgLrH%8iuEa!aq_zHK(T|?ot9~ zWUt}ZHza&Ie~-tu?4kJkVmLoP<@2VkzO+9;BP@9P&%ep_m*k5YtXTQ2()@6WdrvGM z(Mq9PBW9$vl^>_^ z=aaWeEQ!%Z=|I6JjXxKMx}j{f5eA2S;`TKE%dyW#<4w|hvo5)UACmvgn&*Y(U3;O% zb=CeatnVufNi4=a}o$S5`6UL>%r{QkSABaA> zRVN5d@~p7*ljxswBl%&qcL(sh@p{~!R!7O>OTu4LYyf__SfWKep^sAiW`0yIuJ=iW zUsN}4Px+g2BM8%7t+Ciu^uN*m?;SfwVz7&|tUfWC#GiEzUdM`~MHnzWlb@f)pEtWs zfpZ5BDcKQXh}T^VV9%%aoXP1z%J%8b>PD6fvx<0q~w71lI+Y8M$ zi0jk!>l(&7?DfP3Y@4C#_|(4G1BwO4xN0i&Wy+_rjwgyG4eTF(bbkKK>>^y#UxyMC z!Cw;LPY3?+k2A+pccG7F5`E_IyaM>ft-;FId7Qs;!e6nYKh#^B!>L0afBsOy-;)`q z@gQ&~l*vt$|M6!__&!2$N47V-PHB7AyHnT{(vJz;VrnIEV9;cXv8 z!^CY69;HU{hw7*vhEoclD-@g{&uVthwVyEfB++M`jbpO@jpI&Ga zY=WLT!oSh}w_(0jSX#qdXnTF8O8@4c<$ci>`<;3JCk zpZ**hh?!;P`1VxjC!wUiFm3-1d~sTeId659|M5lrld(oH)-Ejl7U!{QQ)U>VFrarTRGNeVWAYkLoAko4Vnvo+h%@Rr{w0p>5e6 z_Zlqbh{#W9e_D8wiIh7vL(308#Q917w)=Tk_WiCpYg^?aKTi8wOqW@q<)OCdoAH$& zr+oO;(Py8f7CT`gWn&m-z6nh zVf8d`%Hl&>ziYA369J8lVBJ^nMdL%Od)3*FynEbyO+ObVdEDs*qTRjdph6veBxSkToZ?m2EzZ)`uB=PT5RN_8f(O#Gy843u{3QtVlM6A{6yKw^^w{Bz9?yD zf-6aazYC;3r&rwf1NV_@e7;6J~g!W>F73*{GVY&u_gE`rZib zXC36vNA*Rm!G&mTo`yMrf*%Em@3!9e!|CBYW%chU65n~8F2;=&8Ccz^uJXU{pYpRK z#24?iO)$QuYJT3Xsm`8VxdXFW(ZZg@cQc2C!8E}N53h^(j`DMS{|Gp4wa1wg!hccy zqR4Rr()K6f)Xg#C{0h1M%1WAmsWqkkv)h6%sy`0Wo&(dRURaqY_@epMU$eFFj*f*^ zWLm}f<@)215%<{KcSX#r`eDu&&9BCO?~bFH4J*yBLZ9?Rz>sFxyG`g1l%ML>_hB~m z08$#wJIvod(f9k8OTCMOTI1}(&-^&$r^9JIR{LiImUB@xKR>1UcMFW?1PBp^E z`hvf5!q29fTM@c*fo%VnDAGUen&Azb(>)N@;0C`w(#WS_6!L;Nq{zZ68@Kfc`)QF?|r*lItwr~R3ZKmAc((vbi8r}2cZ z9y-N1Z@&(!h6?>cLE^*9kNgqh-xD{NZQ$pp`O`yb?|@ceE0H|OKqCt#T(7}ehl5%wg1a%^eu=sz?*>{Dohd6SwzYp`nn6*s&kD+&FJu!#pMt}oA@?j5$o5r1`3;5&iJt>4CU>O%F5d?{oXsq`$Je)E_+NrvWZxi~NbMKX{=0fl(jN$@roEDKg#@ zqh57~;kgsy`G`KB*8U^LYMeryVG%aMf5`hMo!WcBVT=J-O~DUcKa{uB4-Z=yBPx6s zKR@LsM;}=FY8}*~g@2;+zdmjbK)p*Q__0s$GoIvEX*zqQ`PVCC{MZuzbiI=_|DnKC z`u@cFJlek%S^pAd?A?hkin&VheDeNCwbY^5EcIW1=`Q*kssGxnp9S^z35abtmfO?$ z%Inw9#OG#`hI~GmKYtKeA2c*FOPWudh{zH1E3Pl^AL-RE7HzutBXGFTFUm=N_Vv^i zM4rjT#zq$_?B)F3^+~{hH$kYeTJUE};>Xpq4N%m-a{hF>wP#UD)!FHE5g$?hG6(j= zr>0FRjUU%EY0kQ}`GIXFh5Y$x{8;OQg%lsPfTp&nZ&CiXT-IaLTne7-Clh88ERabT6;llEVR2F1W5+y{^5i1?H8r+s1rGH=9V z|D0rgemdWL`UQ2onrM$>)XDg+p}put1-iIg1<~#xqd(4oe2iLYlI`oLjR-j=kqHq*qTK@vFJ$= zzdoJcQn<_lBNsG>XR8nVIOT8ZvvNc}+y~n-KYrYn?7wzEnjhPDSX){AN%Obc^WUT9 zoDz&p?k=uR_zQg88+O06uynfck5nH?TK5p2q&;L5VYgKJ$67Cf5Sw9wcNP1mQT?R< z?blc|;|R=p58?JS{!AU@he=Nj;ne#kzrR(4&pWp7Fl^j08K2aD&X4rPAALhiStIzQ z`o5mU8I=6kjF8`|`TU~ii#wBw-PGLk7{VKA5v|gK`IO{2`5&M|N-%n$*z990zNJO?& zVuq&Ri}r6ds&fTa207TDC-N`a|9p1SWOP+?hLdjsKR;dnzl-{cQcK1YGDBh-0y;{omKwh6o?44viF{PtyL$LFygYo&0KSXsO_j z`o9TBO;GEpCc^WDzDW5S>v#_LA1d`xX^3tV?>2EEUsent5!p8Wu`Gz#(l zvOj-6l)poV>`~jHExIj!&5u+5J_S3$pjUgGS}XE9%Ga(FRoQT9kG#P%e+oWG|490o zK-gy*!EueqFR6bsn5Q$uNyG_-tPm$dh!sj02KP`~?q ze9!T{@89F2fBNG-&OPT|_xX9f*LfcaUsV6}#r|j(`gU0PiTign{%<4p?mBH^k3oAl zKQw-_M?9a$yuv|J|48l67oD%+Y{%VLWT=>*VvP})xWgGshjRU*_GdHglbCjAEm9x5 z)O?>(|E;?2807YAFNu%P{8wCyeYo^^v7|nW=D&vIM8fKrJKp+nzUcmRgUvhe^=u-3 z%o)$-cOd%tr4`J0nviTCz((Q_F;A1B^JCi(ZJ%09hC?wNJ}L+o#`^hPBpTUfA&v z!q0j_t8&kuK&NRj~V0 zJ}Y8$gr7$%uw*RvziEBRywlx~^wbEqqWE}fpS~IX1S@_W#=!a}HS3qwH&6M|9i#8H zM2B?6`nc%FSNy(QjGyn{DAdP`TZX}RkRzP0bNiIWXS&wk2j#aZSlY|1X1tVNJNu!? zv~|GmI``T7s6M7G*nvhR3nct{lKnxA`iSQX)VIaF1kNwbFU(&!7^m*op;Hqc|D^eY zj!Feci(UtZcHBOt^(F7-4-)Gm?cnoxA6p;Q$9}5U5q&lbo<5v!PZFQGJ|`Gi&s-(> zZJNJRk35b63s*zw7S~65K8SAO7?>|?2j6q+*!%}beb@B^cQ9SdufJ_l6F-$n?bnAZ zqR_3KJ3Qk!-!#84ZG0v^tW3m9tr!ok@6!0_8M7F4Xyyfjy_|2lKjG2x?aWGQ68rHghVPv%nv_@z{<-vEpKEiLMrKMokNL>gyd!AjV{^iB??NRr% z4ob5=uUGcJ<7LwL&U5ds&?q&8T1&34l;6H>ZG=||^@N2vQ}}pd z->R+jL1~@|LPwOd>omT)zWZ?8cShXbjwt5S{QW?j*xUwFym|bG z=Kp?%*Abr1yk0Ax@6Qc_XJ1=rPv`HC^0~W}Sf9Mw7EuGazQ&ULUeT3PFr2s+nVE|B z2kC4djH!QY@iA%XZND&G}qQ_}o&RgZ4vGaj8u}&HPe6*P4#Q{VDF4Vv@$z zPvbw1`8!ehG7+<*V)=LyUv2nkJldCfK+m1?X-48d7pHF*bFcH!`~tUcss3(lnT*j{ zLosOOd^W!p;d89vCSYV7@Nf;ApZcHf(=Bl`P7SxSxqVCZcV4QAu(e1@NIg(jq5g&# zJL1b&O$^E5`9*3Uzk22ZqcAN*m@4LTMtoC2@cxMLR)^U7slMi=i?vN=I*47Yn9uhO z^n@_WPZ;CL-#^VCx{c|I&A*%DQ8u?vDW5SdErp7k4^5&QGB63=ht zeA4={(Qm)t<!*jl7;beoOhCYhO=jsD2*}BImjD_=z-r zyUJ(?{`R*;KRM@{#)s@072sX|8eE>Nm~V@eVOZm3k6(Rr*z^07{K)-D@8Q4n6k7bW z@?i6m{JomqD46Iu;mILxU(@)|havTZD?azpvdw%pp7LGcJqD{gyCUi1S~fqepXu(B ziWiL$R-e%S41fRBe(qM(6_Ip#o^R95o!iHB|DR*udcybT zr5Mq^hF_VK-$4_Gpm$Om3|pm`-{s*2XsELWqlYWz_v^x;SRP`Ft$NvP{j~mO>i!_y z>n6sZX6<0tDWBTL^@Z^c_mQ`b^GWSvsE);$qiu0ao9i#lzhsm~!f;RrY}8&_^L{lY z_Q8dM-FTb55F;}tdGOyasr@_AC1>`@lWA~?g&RFk_oef%IaMp8no$^^nX9(VU+908l^QS@bpVs&H<5ufM2utMl zG1b=@BL?EHp%v6R-)8rx@u%QHTX8gPPOW^N>^Kx|)@|T6n8$Z%{HaMuJ)vcB2{zPG z%xA>VK}dOSg|{P*vH59!wD-f~sEkavK}xmf(-^UO1&6X6vK&?OpdIv=|d8*&jjkD+_mS#;txc z@ztk>KjMGB{c8i2>uNZG4B%GhTiOxRIJXx{P+d%x7aHS6n+&(^x={F>)isQ!)YYAJXbBJEF4+w~x{Ye^(PGqEyEn_o}#mN#ncIGq&TCXFN7# zB(wEV{VTnhgbnWpKvRp4HzxYmXlfY3#rh}v?IYND+CTWmM;rM4RjpP3v^UPf#TCBL z+cAW_e|r9y!F?xO32q?muTT0{Ts>eaEHL?t2?IEv)IKe8aKq}NhB)_|>!Yz(9f|!= za6q|Gy~|~xg%j65PojUrCwf3|(#7&y-2SEU-Af3d|tdg2q7+(a6P10A65N#k|yc`qQH- zRw!-F?N{o5HjNqvufNvt`ory0x;g^SEcX5=U$aDgo3qUs#!6h@XngkG$6NUJITL5n;ynK4*PrZ<-#RTCTYI&W z*r&8Vn$DZuco(?<$<7nm_#l#h>HmE?VpO|etX)lhfy94~$1TL4P5qEDm)oEIgujxo zJ8;t5g+uo*vHR2b&ex0a&|KRSn_3TK&+ke4H+6pQglik?OX|bp3125Jw-%yQ>j=yD zePH9`Nqxad*LFxc*$}O7aQ~0;^|@VLp~~PUQrm51<7xc$-W*T#YORZz+rF~vH2&I8 z(^iOUswOlT%l&_9UuypCj)+JDN&J=OH=C|4N9n{ooO{9f0`dO_hxv*9y<1}AJg#4q zuT@Jv!Y1T68a3kjmqGYS?l=lvev0wcH#~nr~Pbuc7>gGtOXSIRF zJI)WykMzDMpv-bLR+-oHP^4d}woy3M-W4`m_OSVBf2Pnpac@ZAex$esu<>+%lW%n} zW<0USj=`(hc*@_&^|ui-FBAJOE9NieXe8P_Y75;XOW1fCe=Xg*8z!;yF{Z}^K0n$2 zG{=4x{$zAP-KI%wd>YyR6xnGPZmdi|Y2C$qyqC28?za$$5V6L4*!5BDI?aD%TE^pH zzwUUPK7if7jQDpCIyqxtWj%bd4jPK{5XlyHXUFIdtU;ez2%cM#)Cb-vPp3-w`7)E5aJFZSJx4X^``!-P`>}s|-l|zcP})+CQ;_xLlp6Z*=^P#YrXNlF>oX;SVA2~Lv0J5bkpxu@8DU(V2Q&{x~Mm7TfYf9(b?=Y)kGXvoOZ3yMTRc8T zc0RF|@AG=*l%{*>XOqK5nz>g;!n%;u(-!zbT*XJG?;o zyc{?ta6ak&#FTac7=Nr)t$e<8mkDo!PeZfbC&nk$$Iyro__WYU(%+Es+40i>%$}J9 zE(hf-)d2D`a zpZ3iaV_$t%;^8#TFYSLA>pBL1PuStrZ605x{7&y10*eNAnD%@XyFc|0n}!S6rMnVm zo`x{KjEVhPPb~%-%5FHE#p8FhzM%8ZE3llt84Xibu<^9Ng|^B}>>B4G*?&d*`_2xy z4~q}GYUQ(E>kSyXW*km+OK0n+`HfYF!m*`|6Y4)1&gKvDlEznylAZ~9I{StA$KpBL zbN_MdGKjv;Jm>_?3U!3{sbcr1`ugNWwJ_aO5H1EP=J(;AcF38b0nby4^);wkxiJ6A zIpMtd1~$I~@gL2%c_G)g2{OYtztq0{p;}kS{d5J(TFhnZqxs9te|w_6sXlz4DUR=` zM!!Jg#B4ZvDdu;I;{a4ew8DfiKAzgQ?bGTA_S?_k^yRONUs}Izp*0*!LR(AXtCZj0 z7Y^cpQZgRAP^_<;2aQCCiIqfO4T-*bO&pDfb8Ilh=?Z&(S|6*GR*9p-ksk^g5dMrT2h~$OyV;!*9#Hmv=YZYDCW=bcL=hhY%!)g=a1UA z<@LrQrh|BX-rm)0{d9k0sB;X0zO_a7XwDbie^vM0bW9y8_GkOHfQ_g9VN!gi!fa?q z*p2Y@`1kvkk^Er$N6~0*?}9v^Aa;E%;iKgY3&HkEB~DuN{lQeZFZ1WuMsmRNtI)dcsOo50!QJ_e=GwO78_syY9!!Y-2XQjQDrKx&v@_tT7VKzN@*v z>OVgd?4SLg*U0&C08d}uW8Xi`@8xe94&VD0DAFls<3aW>HV!|Cr1uNa-=2T}4n)7~ zKaYjgD_hC=pVYr=9FmE3Rx|O>a`@j@kFD*W|FRa2LK{sh=-0W#=BN3E@)p(b9xoUB zk43rvJD&0}=~4?*nDXumKdSJ=U`-%hrEnjc)SWh{2=wnc}NoFA%Ri<@19?S^$I>d5U&+MiH% zG79&4IpJ}mCG7rmf5*GbnFvVhjQML5*>#%#Te^7~-gX!HQt$2Y@B8y4e1+^xL3n;Y zoTxLOjra7F?r-cjV>~>ExgaxeG#gL#$*zTk;Cu9!=>IFOp9$UKfa8J+%zSu$j`Ek& z=b_*-Xs6J68`l>ZiNDnS=!WiI_2GO_F@MeaSPMgxWWt)hXW9CxeL3`4XXLJLSZn_M zy+<9v=W-GDx99l-ko-fxy*)8lrztK@{f{pd$@g2T`xFB!c0;Y5QO*2P|8Jn)0HjB@ zl=P3G{@>pGH_#b(04MYm@9&uSdL;6ew3gVH2MC`*Ho5p{oru@FYw~}D&o1jmp;XHf zUng<@FPYevS^h!DTW^U$-8p~MzjHlbjX6RAydQJ^%7{K$JsFCN3(TO@;23*;T7TX+ zR}MejG)aFZ8QEX;X=Mn!8`((CKcxCK)aw^=hn)DQ{{j2{WQ4!lSHkh4$_~#}cd_}Y z{iweCFU+igzlS(q)cA1(!k>Iz40fuy;LjD#Up&#jEoE(> zW~PMPPk-6`@ua?duAhbQVd_uJiBinxpkYqp*+#0^XY-qnC-Kp#BdUczT~7)1&gUxB zN2jEAs9RDGrz#Zl**{XHaP6&PAw6TgLi^EYzB?9(XS?lx#{D;{kBwA5A*}u(6h1(N)G5aDmcjSzIUx5jqeM{Ir?e>t$Xj?lk-5&ro};lIyPeKdO= zgr#*Xfnl6as*f8+JV5ZK9WWo(o9UyB@Y!I_P?)=!!qG3E%}@ImMzjjXjklIKYH@&F zPb2nYO4V-|i~G-gyzD)={z~)f8|=rz*u@4;jkx`oM)K=!kN+aXRF2|NiuoHK6OM$f zw)p*0F@JSC7h~_hbbRX{%H}U4@t1e|CgN<*wiv#68CyTiPdt8n7%Ltm;dJM@HS3qg zUo=L}!uR5is1vMMKPyVbv$aDyBC@y-8?Qy;qYD}&hMD|+2cVUz5xhQg zeyRUA%J3DIPS}UHxXbKcPm(*STmao-y*DzEb=5(${bdZfuL( z%%^O9w0}o&`%&0?*Id$noATRm$p}QPHABV%Zog7K9~j(&QoU`kJaK{ZP2#6JP6s1u zhNYx`8|Amrj9_&0vV{3%?w@23KCjOX$Jb+RuzCmQkH$au?JI`ngB7q3R?OdOi)g%_ zV2?c!i`nzj{f`Cy`RH1aj5|6B9{>J+(E8Cf-RD5}RVS$L=J`RYkN1bh;o7W@c)iY# zjSnLHHSlE>&vMBxUzvtpdpgEWnqLFdfY#yeCcm_1x;bEgs*tQ*My-5k(@JMQXfP48L%xH@ki}2B>x5b zerSLD&3m)3x$%rz^>MqHpPY5WOx&Y)o{gvR7579{;gNMQ=53nF`62q~KQ~P5zhRAy z(+b&m8edsrAB=Uf)=-_s{X=S>Ms2P{>Dgnj_{r^4TK}?oOBg~`Y+z-S$?i|%E9cin zVw|fjOtaUr>(|KsjQ0g+p)o5R!@R>inErZ5_h&TtH4cjp*+b862^&xMM;>WC3ofzk z(I9O)onJ6zITAi)kHR)#%G3qn~P>uoiJ9fADiEk@K^WLLiGC410yHKvGFv2 zfAPx%oY>)nu-%-$1BAa5Uv1F8OO^cEN5%Yo&oUGGF8zeY&T2LKBke!>{ely|nknPH zwc_|r_J&lLo$3qur0#5eo?g=a0j-C+!e3Cu(Ak_X%I7ORTVdw=YFxf~j*X}FZCB2C zA;qL2Zbd4N@8qV|7k+qMM1Tjk?Q#BRg*nR zR%`SwlC$+`bdmPIe`P-gb%I)>WCOQfX?^JU=auMMln)<4F`wo~$H8HQ9R%&&?EaL` z#<9`pInEX@6M6kiJmK^AvT1N#-4<1|m$UJ7|3tlmM{q`IA(|A-@!3FRaclD zbQa}v`R^0;A9I6!v2lbBCI)c-GoJJ}om=!0V+LlS{{`+pQhhvnE)WS{#Qy!;xcy1} z$HQs1LQ4B;{Orx+w>1B7>SO@APicmipYE~uqfhEfjd~r#Qq6f7^~JQ{-|xqh_?JgI zhQOf69HqPOv+JK6ZHRhm(5T6<5%z53x}7}@z39qfB(|>Px;~zxVyo)RzBZ$R}!XGRw z%OHH8dz*-@HeIlw-wgJAv_HtlYct?2_P4H=!tHlz|E9#);lj8|iT+Z)oAg|Y%qD## z`b+tCwQ|NmBPG6%qW5e=(9XVWJmqs`dNdBswU+p=G=I`+HTRd=$HgkM#r_1Y$XLbe2k8E)%a<35=l^!WsmU|h`=R#lky}$>Xyb^EBge4& zQ+@rYZHIZ|e#t$ns@Zr?&wqZ4`M=BIOOe#5H|lgztgn+UxL|ye5~jc9{-?}Kdj8Y* z$c}i`Lk&G`zp?vM`*zVSQ=yCS25L*Ve$x6?{{daFqC*38Y0dppnjh(7s8jg3!!6-? zRTAUt8sRJZRBt#PXe{XuN%^{HIS{*J3?%%}_>TI5Q7AAqhH2glw*FY+A8s~12=gv; z;eS;zKN^>V(R+>w-aRj6v61( z8_)DBgYa`{+f?`-a=`m~m)ZPO|9tL*B0bm~D(!OFby^>Oba4pE)l5;Hl)jnL z{aMEcvoLR>3qEZ0W%I8k@tN(-XTs3Y8J1-{f0<0|%c><}?sUpeiG4}G|M98I;5e{1 zWUIsY`yuw_UhlRTr>2Az4SuuhTIBnGo4E`cGkQz>zcP~FkDlHUFQQc?`F+YqN13_s z?cp29rgQzFeAoqaMWu2B2zM3pF-}LP@Z;GV!k%4<`H&y)jai39{i&%xqyC?)(4<&9VD`6)kQ<{jRS*|4-Ig7n+?5I$m)Xjs@=Zi5Oohf1CY5X+4Xaw|bw?JRBGweF$XW87TI2>b-#?yFy zk?Kp>tkFoHX$<%LeQZ3n|90<NxqiT$RmIs;8RI^yhI z{{7Sa4NB9mB0Vb|D_Sq};QA%i2lsRF_|(@;!UwhAnl+dWH+>h3Gvxl+0m8?bZHZVX z_Mh6+aT!mrGGt`=Kxqxv z4;nvdI;|}ZhR87TqGJ6By0r|y6MgYcuLoNn-5)W>u7jArQO4M0p1-61*^m8Z!fmzJ zICzZf3-!+~bnk}!59>?pH&2qk>pe)Pu*0kCLc;f_?w={Icaug2euGMrh{8^@-N6 z?dzL|mM3Ooj{}dN$jJFIQ*=VGdABhdxpRG@^=q>NZ(@7mD*R&)@b6FRpLtCULhMx| z$^O3sM4w7O)e)xn9E0v)u1~Z-amQ8T@I%iM8ri4W-&cpkH;)Wa5gOn!Lj31hxXtO91S|81Er)US8KbG+O!T$z)FRw(l zwHdkrq?u^o<%lQaxqV3Er>QDe zP*}Je?H;GH`DLX4%;U&;n6kJXF5F6D>rW&5C(Nzm5j3nVtcLor@o9vAjn}C-aiy1} z{w;&l-|W&B^B>b(Fmz@V8&CP~aLyisyZw-Nd8wFx6OSb*?AaYY!+HLj^55`HTP%P6 zS6-X_7}vZ?IPae;{Oq=$*>}``yS}A8yqDHN{s8WOQU0qER0=f4|2bk`hA8_X_=T3lzNGP)?!nr^QSl6;7Z3RF z7mc3|oH!U?I_lRNKTZB!SNN0-gueQvkpE1jkx(`lqYS5>vcLZ|VxR7R_g1W*&cs}w zfeQ7r^N+DGDrg0z6+FH}`^WugaSLM|YUjVlj*%F<#!#ZK)W1uKP!=ZM%SX(y8vcoW zx@UJZDkfQAP;wDlKiwZZa#sariao$LZo0?#kN1%7pPKww>@TywmE?SZ48s4)$e(b@ z&&I76R_yzw=L-ZFL}B<)bIJY-S|4yE@dmnRuf%VC&OhxxHRDta)HYkfZ^}Bhe!9Og zepej2)ht@|}HXl#8$R?w#c@rj_u%mrTA%Kj zUIp!`;u-J5+pza5Bk@JH1U$g64MBlHwI|#$NeMfv$O@2hC`;XYNf2&X~18u_3Ky?GDr{Z0nvDnHTR7MQfBw`HYlQjl z59Pask4|CKugk&!aK1tG+snuY>Z3G}_Kn-$ly5B<6&fTw5d1v`v-x$pNb7@A>JP%U z!Ma#t!uggFzH|Qmg!+el@O0+=J7|7o$o7%wv!$7YZ>rx~o>ee%$iY*aF^q3|e!=u6 z5zv1u?*H2Skp2B=f95BjZsW+RmH6kA|CbNSx7G4dnAWYiM89c&orPXe*b{7uyJ?(X z8b9iFwF14C>_o?VHT;tL_WZk%urn~l@YsWFeRO}MYp=(+ti1sdP4wCKN%gtiz;Nsy z)(T1Ox3TeQ#6Fi7pTp^x#TY!nm5mP~=NBBUo`k$fR)|R6P&2>AKQDv*yFDlmYn#u& z%Vq1M{H{%X z0`;RC5EW3PzodR)uT~fw6I)8om!$FI_EzW7yevh+uRq~;%#iU|w8Tu3|D^hR{Q5n- z(^`Y^h0{HFd_u}^+^Tp?OmW1GrYmdSuXKNke&1^tdvzK1^xr*3=kn{sfByY_0V>2E9u|uxvHMf|deJ8bye;}H|Cyke-w{We z3OI8GpWJwSS0db%2elV>nKsQsKF_P4qx=C6*bbAGA+d~)zS<&J`?(a$b<4Nj?xHsPwI+lw0eAnL*%DX;E_>A|I$b-z_cc7qiSz8FT zvS!~W)z`Wujr^#_*LnGu)Zvjtv{dG$6eO?AfrKjbk*hdG39gS zi9YyXr-9IHZhxi``*&K0Fa$1bA=y7h^E*wgs*rJgFSZ{H=6sU)w3hc+M07Mn-5j3Z zq5aYK7~F;0@)h{!Z^HdQX?*(1?s2&Ku@!=cTxa}I`*!9OZJ|qtGw?62;g7_pd~HAB zaNrJ!K2pBwu8cynL}MH-=lV$bY8i7DKF^czSEkOtZ{nYhm=}$?ty`gMD;|HQ`JfARsEhp)zgXEl5g`*!*01UUC|Ku|E} zi`M@wt@w$STXtjYpxu0anKb`&LEIbU*~$fbt9g8i=4Wpms(?e_c8u9lz{XSiH(Ja~ zZhqJft)qGVNk;T@%<2WWoa2IkTNBuLPh$VJ3~@x5&qqoAmhzcZ-c)!Pc?n-qE7<#? ze9j7JhwKAl?x|+~C*||U@Jiv8#~#6A@17d{k=6&g9dd`WwUT82rzff3y+2*0@c6_$ zp-GNnK6fbhLc(-)Nqmaxr;fQ!;qm?FgrLQW`OMfL)@H1#kJq2L{Y&G|&370Tu77by z@EtXftzV1yuW8%+;7rd3FtXzO((@0tSBAoFqM_t`=Z_@*RCwq+qV#tmchm@l{CXS? zMM4)tL~P>uCCab4X9-SBBm9#7TSMNAgNs=!ENi2f-=JkN80lpqi646seJm*Xgu9ow zW9MhZ`q*r0C{F2#=er!)&%O_u-_70vF*iI9$>w$V_e;(vN!S#Ls&XS-NZ|fy8SziY zxR#*hgcS%Z@4~-d!ta{7QD~9S67$}2{-{3g7X8cSKkN{EFP*KA_CNS=VFAjYI7{M3 zG(LQ5>qm5{+y>>poIk36t1VLS)3hTF%;o-PJmK&0$OTx~*BP&V#q#GT{H5J?gz@kS zc?%D2zf%7Emgos5eqTgmeQv)}{u0FgS@!FG$p72FLhC19E-@B%>X$%$75{!{eAwiU z2gWs1LfH$&`Z%nsO5sV>gF-_K&R;ySUl-W*#LEV1kU4x}@0aT1vMAlBn{43J`Akz3g^rxrSs-Nj= z#v^yRu|z+q{W^d5Bsf%>V$G~G?EW&spJwc5bhO-##tnG>2E;x+t2+jB=Ncd?eJ>kN z^EYwdBVabU1$0hqW!FmxU;QTK<55?!$LdFO5AOd->yI=$j>otFV@dr*Jh49~E}9FK zUp9F7eL1^7?ccNI(gMsWaKbx%9-pQ8)y0`fSeNdK2QLS*`6*u`OHy$3NeA5Ws)^4M zzH-kcqFCDn*BWvA6NIlzL!8iipmTxQ+tKLO)m}0(sd_3X4RfbFzKA!rA$_^@p8%qxeSI@0v-#6teZf8&IOjSi> zAI=xmH_PiUu;s)$Y#-sr)<^l;v@`&_7HDF`SN?pIuiP2+1L zSYW(|ji>RM(YuP^^<*9nWGj38%SRcB&sbEB!$HTE2yo{1CymdfZ#{}D`=%iMxfvTz z^Pf?lBH%d35Vj+@K9vx@8XL_{nw{&q`(Q0{`w zHv-xGGUC4(?lluE{2m~|PnUmx9@6?HNA)Dc?R3HG2b0-&TL1cOt`qi;d|#`64Sb?2 z9O`>k^l{&@^-;bYb6xT1(`WgSWX=cWOQ}PpkXV10khpF)TOX}o==Z@B$9u{o{UfP= zx64DNaLmITVPU#rz6#IvK!Y|asB^W(z9scbfuA*nM};TRY!c7^()j74`~jF9tBHNL zIG;3rTA6KBxJl)vaNk+6eqH`C40pU5V~^Y0n!lekemeP9Jt4~bDCYkCUSl6h^P6T_ zW1*U-U+eigcFBJ+tb8|IDi!Nn{izcXFP?83I)=wze-eEwu^SJ+kw*B_RxzK;)xKce z>a7z0?*I5QjKK3h&2S|zn>`=Zr_tljVRW}dEYDP9-xmm9RvKb|@+}59Y_x@qr}afz z;@)X@jcG`kXTiqD6Zmd2VFBjcVb@#J8Y0(e1e#(#Co8LlfBK^QPcVV~Ya{kw^iNxZ==Ocs`lvqLZX1C1$qn#oJLiw; zQ}J=5LYHILg>fYV*!!(Z?7x-G{jp$HJ*XKxV)tK5;wSw~$Dq;CrZ^qR?L(?hTZ<}j zy8lk>v*r7*sQowSNhAi?G)H17ukWGtvA+gIP5D`b3~t} zwEBXq%^Bz)&Hbw~V&4@nkHGdmQhsQBq@;g1KF>6OTMp-g*5AAgiAJ8aAxs8x|A>D7 z?ym&AG>FH5s39Kz>Km=ED<3=)rXl9IWzYGb^>v9K=VMoZ9TF!lWY1SZ^ry$%a|oZj z0L|WRV)v)|lf7xEkR7choSWKRAwPq}{ZW0y82_4giuvg`Laa?seOs%2SM1kV*k=kn z)!_Wl{Ci6;vHs2bi~PU-j?{m87}rwBpLiYH7TjUaNByUsGrjOa_mBL)^BbxDbl%re z_;BDlVhzO{H2B=zwWX7)BTMxzk}gZUl&{MaQlts*PqU-M(EU? zIN5JB(%5U0n^Mf)tp{4MdDjd}wtFn#?pwmxeA z&AYS^Gu0e%wfQ1;{UhPeVA?PtsJWK#_Mu|F_FYUudZ3fUzKbRP)3p=M7!v)aR=zGK z=nJ!6pMkR<|NW-(gGGi^1wqhPC=vnlIFZ>mPG4%{Qjz`%Um2d#{C1mX33wWAg%dwGpBbb+ zWzLWV_$!_d-D42fH(H+}vwMv2#miA(ki*tT^-b4TOZet=QaqoHpRXp9N&Ty1s>uk5 zaK!f0+`lR#{Ectqf>u$lYvpfTpuTWwMln{d`@o)`>RXE^?a}4?NBOQdKiPH4UzT?Z z;o^&nxOwVE&3I{i-q@rIVs=-`|BGKxeLG;RQfS(1uVCnx&h?w{_ho<&nwu-vTA%W` zxQXDDCP&kl`8D%P^(|_yABLBxO7h#(zj|3{RCwdcWubbXV*cLT8;qYzHL$P+*MGV{ zBzUAv;W3LxLO_r{Tfa*esek1@Di}t`8{^b4&L_>kc^oXkrpZerd{X=ISYjy7N9saI z;r0XNv*=kg0u~#zc;k&2XFbqE5r2(K$05MF8BT<9`;zv5 z>t0ff6`kVIcExZup5~{OcgG|AyalrSIlpTOe`R4m&~h1lwD{QD*GkB4bt4`cKejRkaY1h@~&_`Y5c?TaR)p&{Zank{wh<%h}Q{{M(Xp5LZ?4qstZnB;d!$g8iIPyZIfaJ#i8s`dUGFO7ff++RoN zBiaV{ewH)+qx-k6^a@6gGuoK&kk@BZJ`?lqA^X`9oapIQGrpDX@00G&nknuNIX*=n zHz#go<7t26>ez|6YiEc}e^#^WR6nnLOTxr9_L$pi9lNeY_-r~X5i!?oko1`ABjs=Y zm|;R*pr)`qTQOe+BT`VehZEGB^7=E%SF?pKNVYDoHNLo^LSMLerwF&Q74ucMZAbBZ zmWo>WnmMk8(0R>yJhS2YN8^i=!@44|-EaAS=UbGK^MOD4i}jf?yM>-rEBNmR(Lb%L z-e};eguvrGK0^6w7haC>Rx9yRhsQ_$?|h4!eG#suic6b#ewy-CKi;VD=JyLi>hk_< zei^Yp@2L;PhqVo0p3L>nfy76yKT{Gu1?^Oa2UXUhWr zV8q>R7&@{henRR`OypzH)u0K6XmY+h315|cqp)~)Q#g+0e8m&KZUog6^55iON^nj5 zpVXHmy__M&_KcyOe2#seWuDUhZimGF64$2d;a6YI4~?I!TON(6)AYm|BgK5Y_!@(v zZ3cL0yNcbP#^<}uF2pvC8R8iPgFXKJeU_2>kfPs9@xG}W$_J;h@iac~vn>_ZN3=!1 z1|!(`c(T7RXY?}UuXjV!zVU24t?&5hn}R#y{^F$Qv0loDFLkK8+ zkX5sOY5(7+DZbb`T?tkLKiAw}8b2J+;uX4QrsHfs#eA&L=!+eB$_VVk^~00IKa|ak z3ZL7Z7nbDqQ^?1ujA8hi*8r;L%K7>TA3az8MTZsJ5MGDZFVpicoT7sfuBL^pZ8#sX zgb)47vAFKt7<(VyV)u6--+%v-NW2)Wizyo}u@Px8Huki_l$ze4qZgN;PFGM4^i_39JQT_0vj6-MfTsl5izjuqL24U zitWD#vSMu5BE}HM4`t)2{kL{s613L0LFw4F?D@mHNb8He{HxKc)mBU`&f?=q{nUfd zR75>r5E)VlxY+EYCt`nw$Y7Vp^oGf4b?M5oSpYF#0}xTKO@FC+bzT)Yf~ zZsHkOLAUttBaJ_rUFj!puu4T9_g$Hdr~G;TRW1y@xl?GNqgbDgZ}Y|XY?&lJqDA75 z!%x4$9=&wToTr$-=7Jw)?WzOqMVuck!e2zPQK4+aIbq3l#r(}5I2_+QHIUeUWu8*| z@5@>xLHXi#>^oCae@yoG?OGCy>sE~<{YQfce<$mNqHu^d`pr?yUvy<8>deuRoKH{f zyYe0lgo|nipnG+)!uZGvml^mrQ#>EM9gjac5dUkz({Wf6&{T3hOc{wUPJH?b`>oTF zX4s5Z(iPL=0*!7S6zy3^=zZY6>F!R$2_;mN<>-UhxM~YYU!GMNJm~@Ws|1I;B zo-cFzNQ=Ums%M0;gZ-KQeI)0L23;D2j2Y^1ddB1XbpPGc?&A5HnhjCU;W3||@YQ77 zSZG>lVYB=uyB90-sy6&qXJhV7~8>Wi;Yd`HV5lsyAQQl8r_ox0- zgCmo$;;%mJR^`>qFFpVBZ&3l7B*x%@QdJGV()j(`#^dnpmX4%96Wt&8Hd%n}--(!- zYVDy&|9*@9oz`>%Ty43A&3}&6Z+!PX4~>F2d>A^Cjn^XQ3*L^K2lG2(e>l|@Y&?xW z?%Gv_uNybxPF@XvME`osOU2%Oj*vCt`gefD{|8-NihF*}(8}QUWisI}w|5%$+KT7% zhAFl$FZN8q_szBl)t}1NPxWtIOIJ)E^h}b!ru;2@n1ZK+Y_Z;A5PLpqU$#2Z8NS!v z$=CMg{L%h{YcBs1Hoo2<$QNaD`;Eju4qEn?cd=2Hf63?iNBQd$*-TIqfDS&qzDGv< zGcSK1L@ut9w^_;UUr(ZcL!AwTN1f!DdY=2YG=F_0)DI;$#QLrQ+`ppyX-#WUxNX^K z;rqV63i&g)4a8_oRU{U1zW$Ft(LXzDx(yMt73<#)vtYQIYeJsO^WX7=&%wHSg3sEM zxaz-v`**}Y`!+umw;ngb6<4m0H2yI?ClbwPHb&Oy^ZffH{@J_W213}M{WxmI^^wLu z+~Q)OGDF*5>$3WCc!+0^1?pIO{L3$`4-xXFV8l=Z$^JO%-yO(}$I?t=Tspgq-Jj;a zV_#L_aOoz@SX;v<(Z`}sOVI73JvMdW`bg_Xyx*pxptU1zJ{eZCK52Ziw`>VY3&rzI zW&V2@8q(}oIl#%cVW&iVF=a>rlyMd zQ#%$Q|JhDiqJN&Ge&5lyxnMdJ*mkjoKbh43oAALK_x*m$OS3+(_enHIa`#&0wdKx-dZq4H-R6kEFKY@M;;dqp1#=dVYvOl#&me`+ESr1-K zdHj*qr<~k=9TPt!An8;n8-I=H=aaSx2(&g9d%*Mf3P^l1C;1Q737eoinEQ|Miv_<}=MSEIbu$(r>``RsNx6~UM7CH4Ph#D9EKvKaY8Y*AFr z<1-n=ew`8E3ZHdllK!DIf3T?eLX37chm}fSwmxGo>HgJtvG?5b{%<7qE7i}gV|9i3 zb@O4?gZCei5&f*N>MvKBs3d>Vnd_%N;dfaRmBP}4+k_0G<%}O%pPU)wgSEYX$-AE6 z{5lZ*EZ%7$bnv+h3tevCP=43E?T5|2N;o=}$2Tdzf0wor+NhkxVV?o)`RV@ifklBx z-mMImrHc90sHY^{{<0bMTl4r0%^#d^5`t$B8c6u1`Z>OpzMv9z0s{&Z^E=-v48MaK zqLn(=Pip_#pNPbXbS(_b{x3c$%^zGJG6Qc{8sO9`{`aBw?ds~IoNuLrl9kHq9wlKlac&!_6uuqxev-HmGWli0Vx(PDpk@qDN< zH*Vh=6Z>{i^%9itw}svgp5LebrS(f~;pwqF#F#41zxS_Pj2kg+(Ec*#b1mU>16(m@ z>*HGY$H^WgV(nE^yy@o0{ys9|U*3=IjM9tca_hys{)NVObOsv;KX;tKN~8bcf71N> z!;pS*%@#6w&%`=4fB!m?0PaX_eZf}uIF!!qWY=l^OM5FHB#izcKdsC8r1tH`U50|r zK{=jjFJj}VeLMG6KRAzQ+BV4vR3=8`%{P|_l{pA@ahDiyU68|%e=;y*|QJABxg_WNa z^Jg}ufuOl!4=S(LG7}qMEk2`WP+dH^%IdN&L$U zqL06f^n}g1M=^CmX3hLk`&RXa4~8%LE>{`P`J?fjEiN`feDiB4OX7bYy1$@cRevn} z^;e$l&GnJ;XLPTL5S*WfBk5i>?@!9#)@>uum)P^s^MO+;z9Ust=LWE>l>gC^Vf-@xhRNlrB zg^T0ac*@tuolEfUhqWaCZcOxV*mPIC?e{=>zM-cCKiQW3y28U_hhTD<#~*3^r>>O; zT3&l8>90cduT*C_s>S+(J}K@s>yzrA;1?j@W%{?^Kl_yO=la|S4!^%j^i4+W&(*hD z38tY%$ZyJjpQ!!0MRNces>&qw)0D4QrcH(HUWeh=u3OFeq(T3^;Mat!vrsE01k73*8&v2d8gYar8)^F{4Tx1%xWpRa|k zw|Raji0q$}$!B3(r5=)wpJD5#^_#7qea9hBQ3qED$fi9_Wf7`#le|Cc86*+IJrnpg4fpT=M0?+?PO!C>4^?&|UH z`|~9An~#Pk;X|w`T0Y=>(fa7FD;8m0a|_sRO=jz-`9b~Bsn~JI8iN{f`!S916FXxG zDmGf-X#lqmX?=7|BR5>weqX-dS+V{^T+|hGj_0AyTFwXEzx^=T6J<)}^6)-YY<-lE zetEir&89pQ_Nb{JBL3UF9szR4In@P2WZZwFe57~u#ofDKBz$CeO7rW+hX;uHhre>S z8*kYB^!qQ`-AtId{1~=g@MhO(|6TX;;mA)^K}9fsJ}qM3J>D)8#tdFB`dBsJKgr)U z@)P&3rPaf-VD7)s{GImJ2pC(6{mF_IfB%OrOhMhrP0)DfHMTzb{XhDnDXbj12QwSg z{SoLAr@pU*wt%K8IQepk7rH9u;RiJVk{ zpJ0NYyfioVXi#yP_!)B11-55Du^EltOY3(g`0=k$ldIaF#M)V6f1&oJMv?m5r*$d& zcmEiTZ;V<}gXj4i$CfA;>G>32P8Oax*<246bze&36ki|bR_8{I)$yI?`qDV9PpSEG zJl+{qfMt@v7xkZNM@)vzbz|svz9Zxbf4eks9tw9?LcZrMY22CEm%{mG{K=CY(3vOj zMeh$QObfxp71h!5r?5}-e(J?fexQm+BC?z12>*%LpJ&$7u_fG0)?b9)|2M4bSNvKN zhdEZYm4Edc1YZ#&W}-B(qU`=^8lQBp4GcFMkJ^RxC3(u8 z_KDVq8PmH zjJfsURwDjK`ct=kphQxO7c%_O`mkZ`-B^b@zf}L?7t}skM3u|(__~h2trjbuPx5me zA9=F#XLZ^30)==#g1>r$KOyP4+6Q$VER9qAb?Y=7jWhqS@Pql%IJIxhqnq*up;ysq z+gNFw#uwMm_QbRZb$v@2_%m?0!Dog9^7!CGn)&7Y?&tUkSTV&=9sd*fqxF+X^`{`O zqcJk4YR6ym2D33gR^3H+#Wm^q6n`!EnDNM>4D}tE+VK|}7>KnWEM)y>E0X&mzK{3~ zzwAU=e+243wXQN9wc<=sIB}0OKdqm%aQ%Yn7O{BVtd>&nTe<&~6*n7+*DIovVv8hS zNciEk-+@@(*%BswMEw5;$)9g3IfNg>h9mBRz!$Y&(f$z_A8UsfJ%xM(!Pl&sDLDD1 z<^S$)mezNS^rs9B2}e|)+8FyLOj;ksUrfW5nC;#WsrG^&Qvd3fZan<*njq`U5=q{h z;P1Qb8h9;hi_$;g()@+QzdHC%-P_VFhbb+!+qbcQe0jt!ef}Y_nZO6ZU&Hy%_|Nyb z%)g@c@5j#{JZ)+`@9Di+lBe;FDyeSF{MnB(@mXtDxvbY0*Ydeg_xN1$zm18;|Cjdi zV1K?USjmb~$-kleGGVL@fBo?&)b|Wa--qJ!?$Y7#9aPK~Bny1nlKdU(+l=2Yy@K#| z<0N^C&n)NB=yg~ZN)5lZCHym~%|!M2Rs)Q&%9Z3P{*-;DVrG#MVy*5<<1~Jl5;_MX zd@9P$r@9jRH?^7>Us88FQoe}%cP@!v{01^QFyWU6dKaVAOMSk=TlDv# z_5ZWhEJfk^Y8YMfw6s1G62Dl#W-g*zTVl$DbZOj{^q1Uo>LBKJ9D?R&sw@BgKWD-p z_Z**(f?4YN92dd=8g`TScP`#?7+LAVkXKjWM?vhH&ew1pIay2A|Bm`!t)o-ms%(jQ zJB55I!QZEC(b(9{9)nq=w0`QJZPZzXb*&q!ZM5K*<+{o9Z=HBNT-P^|)ko9&akpE9 zW5I!%m@s{^^!^loIl=AFchfx<8K@n9CtN0Qk9d6^)3>?Me}cc~qr1YT-4DSZUImMzR!YyO=jZPANyU|)EwF81FX{QV1b?RG zR^gC+1FXFx^53+7gMPmxT%6ww20eWw`8?v^Df|=AcR&+3><^aar}l4O!;Og4?SMM( zqa^uUV*mcz)DF#E@0Q6w*OXZC4i|S}@*A;#)A)%+Xjc?&$YlqoYR8|yy6(AKtOIOc z3;a0~|8Lj8q0BVko6P>DlK6hp0CVoLWE&1N5cs3{wIh0-toOK5Ray3Laegh%f{vlS zz1ZJqe1BuaaHN(0DT}{Q{7tDo2Br&j%EVX3aX)n4W+3ZtmqzeqmpTnq)bYiC=T9lV ze3s5Zl|^QV*ev+veq!GW!qv4GBdw7#S>T7p-z`6eU~0BCri2Q7Q2(s*i9ayxmVm7` z_Tv8&|Ljb75H4hx%kZHf_RFK{5sVq_hHrIiO7avR{=V~(Jj4Qj5=8xFEa8titBzr8 z$KmSyV{b{Gp3nK*F&=g*2h7#UM8|(aQvWDiZv}d|#!$8?XUX;Ud1A zO7dU)U^2EBG(!))@zVSm1V2YT641~@ogXWs{<4d88p5;NXH)$}}$DY>U$M0q0=z(RDeWvHbFPr(}`_KwV*(~@c#pm~s z1?XMHLKc5HM)0XTy9BpZSYgPD^Wysv`^Jt{;0<4I!0;aLwc59p{X$W^pbB0&3Vykt z#4mRpnTH`}6)|e4;FmQ2Tw}p!G4-# zDjD%#4L6|K9PRqwcgj*YjH`^oWMRMHEYA;{wA14U`zPaDGY92g{mv!!tA=$5MnAMd zotQUdFp@loSBHWhK<1OG9`Iuf{)KhahS;Kqmk}LX*_`7 zU*&D8x(_6dGR^Iu;BEAl;a z(_!`DmslUEZ@jWD5e4lUp`(Ss4~;L@pV=PwE8LRBH!60O+oujIE%}%8+tlY1wBu(` zfEydUp-|O(pP@8A#n0p4R@`J#28Q@EX`G&qJJ4h(%bfj5wfl;WG*0c)lfLG>NyRNV z)=@it+Ew#nA?tpZiJxXABVc{Ch>h+h;uiq~KcVaFdEKEWW%!}-i$jaXAaqy>bNwOW z`_%p@UsUD$iub_QS>*RCbg8WTi!WQ^KQ)gI#;QJ+=&^Z+Bv0!XM_2iT#myp7)lfUWRJWHQzkgK} zb=oA!2NQhli#>(pV zZNtuVl{B74{HrZ0H|8_&qiXG7fj{bB)j4R+Jtu62ub+1OZO-*zW0(9;4L_nizA-J@ zioapou;b@KX?_}C^n5S^I$yr9W=8}+^d|V6=wr|AFCNFLuEM@ieD?0;jp(31>|cI6 zfW#Nqw^Y~X&Ml7`Tc3;fC;nH1iqlcOiUIOx3j0Oxm-`gB7}YPEW91ovKiVJsn%+`0 zEVRU_dl#kW)BIV@3dY>5&U*ZD{UGp1@@MDHF2nHVRgiW;?2l;#fBqLgpzgy+_G&||sq}ql{re7GcNW77Rkc28*KhlwB^ZA)2F>?~ z{2+~wN9PP>n>)N$*{{;B|Bc62;FJ zj$a&n2#%ei#QGKT^VKaIyW`}CLiX?eVv3*lpYHRRw=?b4BdWKPHXS_+Cu-A7uB5L7HbBr8fV_ zuI~c$s9*xaUt<5J_?Vh`8mIl;;AAc2sr~5Qc`kMgH(nw69e%(k3;);beiYSYkgSx_7{Ew`*+q3SmEJ{d(ISmHGMe>A3tz z#J_2M?Q=5^mcQ+@YQ;el>HVpHlr^gsKNhwR=eAvz#wotmXANbgyYtKBXQrscgU@co zf=a^wr1<(}H=12E`=%OFMSK4D(eTPVW@yAqMKeA#6?e@uaNlpHF z&R(>d-d7_p$5+@XZ`AtqgOz4!w@<4kOoh(}U0HlQgW$*2ZWf|4^kw*QCHCd)=tY<@ z)C2){v&Hu%_GMGKC8*LxUH`7BAEfyu$EG1Dv^GcBAb}rRKO5*Df-YmsG3=1AAGCgU z!ro(ukMEDDIPLN8;R*BL*TD$;$0SMXgR?w;>u#EaS~cq7{6b-0Xnn-_CJDHrUl(z< zUdq4tJx28VXZvdW{)rt}p;J!mZwk5nnEWmo35^@zo!(MO-j?Y16WQ|bK_#Qzv>SevhXxEIxp#rc3>r93{} zclb~?JLs({@~((4Q~%>(N@boge=CL`68cT^t0!E&*!tmL%Je^cEGqNsueYG_`$f|F zoXP#1CEMNM==6boHWm6EO#F{Y&x(;*J{oWQ?KJNv*YEV3-niiSof*v1uHTQ+D{wFO z6l|IJPO@+G{6@1ieu$W=ko5<+K=l8t{~Uz9*T>wG52X3&`G5OqGcl=GdD;2@45I&! z$1g_LhsLu0qp`$(Y{*%P2anB>I{Jk4{0!oMocvgf1k-4k&b3o&^FKP)SO%j}mI!FK zSCV%n{zsDmr?ITAE6h3yd1^lvI));!OGR~k&N_{}93SQTsq-`H`q!)#!oR2IFZ4&O zMz7TkG4yl~X?@hce^oOP)(`7o{NYv7^Qrx~wJiaS-RmH3j=&eK9~$#;EdMg}2QoT$ z6Zj(bBWuo9^tsg@gH`DuLmX!}k$nS51tf3|viE${tWS=wu)NVM zaqbsYvqNUmIK@|lK^>m|b3ZKNuZwY#{~7nhjj8o2YRti#OTuo)7GmUo6}=9lxcj~CqGd!c|mx${;Ur~GV-X*F)r zWILYNbQkjEexqRXvGC0(Q3^N_UMW@{~N57+n-4vEAw^Ho6)$Tc7Aow&5Jep z^ikDtmUjEoe(!faziT+3?Y%*)kHo*4b{xtwD!ncfAB~giagWeU=(pJ~egFSse>Qlq zepNn{iI4KNO0Y{6iFT((2zg?E{=4sv!`AsMD@5Rf+MoIDs`8iR)6w@>S4rNP;3I3q zSVZ;v%8qr`j*qL8ZFqeA4qQe#&HQrz-ynS|ta>SA{dscJ2i%+@I&9aT*_6RezcK?mcz=UWL<|ak>A#$n+Ps zMJ>l#o7zfk_Qys)47+X3k=|vuW`1Lt0$nwDkM#?Jv9Cj4jl4Yn*`-f7{MF}o^*#xH zLGwGU_Qv7rhnnd4Vukd4ijSM>__Ld{9R`gVEj_;psefBP%bI_xz6IZZC^Y&f=V!}m zZ^F9W&2Yb#h)?e){Ot7Gk<4n>JJtSkmSTQ_4?|y1Za@4zYA>;uo=@v-}$>28)^8l%=p); z%{si>nrPHL?;*V(t-l%Z)EzBWyk+T4wc}&^#j3ngox?L}{06~?iEkjj?<|K)(E=Yde!RtF zKCWHWhhyA#ShJI);zr&MNKTh{DuEP>(>(6CtzuGEi{=g;y1Y@{xw>C z_UikI+W4=7;8zM_KU}9)<#F~~;TWW=(NDSlw|qL11s3J0Zii~u?{{mwxW|_QT&r78 zBQNJi2Le3V!bAD05i?E1`xE~o%)V4z+Z=&CTLpil{`JcjLs`zI7iI4MOVVt(*}Uzj z-*B7se7gVZzxH5Gw)v|4i?#Ek;&-KZa5Dm9Q`{waS|1amHxg@&@>pz9o-|JR(a-T! z`2A;_aLCG8$dmnlz^1XN+VvBwc1yc{U-Gl#EmL;mXq?E;(*6w#lBc1oQ3?BIu3f*^ zO`e0K)_Qm~OvJC~{vSAC5%Q)Oz~1_%SRdK{{Z=l*rj-WRHXutgF6U2oUxwndzA5(Y z7W|3EuQFp&VOpy$y4xR?o`%R6i1?SeFEoa$%fs`c15x1suuMN!{E_wN=X zBJt?HC7K-Qul$P-L$ZJGDXq%$Q?{Ul3H_z#v(FA#jj8!{aZ)!_k`E^PcZb=d*%QwK zRWF~)()uXBX+3N-&+Ax##j~{QcU`y9>`429GWYMpOG>fj)N+}AI}?8MyZJCSAnbXW z`aN=MExu+|2HeauH0zV||0Q}}tn!_As&bQmYvunQ74^7dw`gpN^pfOhe$Ri|NYtwR zMz()b{a!htIxjHYs?I@Z_&@1S;^sCMAN)QthgL$rX?`QJryYMjY8OUy)2`ns!P8KE zR55$MGgn&QezJcj`2?WL{@JPXF#LPNZ9J}W)n zoA}r1&B8H0UVT1po8UKUxXGSxl0O@pYU*OEiH3hT%lXUnor%!>Rul7kYxpOLuU1V- zLeQsLviPbq*`H^fUIXXJ_89RiQCgof*`Mo-P}fFJtBz`}?#jRVPtULIj;_W>)!TwA zhT8dkp6yz^zh#e&voRpxW8q;cy1eyvvuzb)aY-c0-cZg6NQYr7yM2e!es(suED zgCnfjk|xfXwtydBMdl-JBJ=l3~7r=i}wU+iE1bIR{0bqK`d4>~wG zP3-Tq{^Z)pC0O`b-JfKk_W0@v_1*E!4pe~WxbxEdX+-}$T7<%SjuE=nKQ4`5Ao@Qr zN!`0GUwwaR--DX<%i}-Wm!=~At1Tu@-y)6E{9E4Ibtvdv4+E?8R{qsrZ&H8w;rw!B z_BY4Oi-P}y#82N|yv6Op#_)r44+(xj;yX8OlW=KVO|)vTSb9Fy@5Mc4vXQ6%s63n3 zk=94`TW^{T?|x?smQ>D@#%cXw{kAh$tIfr#nBuA$c^%pQV5j`fo6Ha4pI)t#)<^k^ zk=ZczpZ(J^_1nIa2M`d3?0at+Ch1E6c`l99{d@6yTRwP21{y~jXyoPk`+m|iyxjJKJ;;43 zjZ^;p;qGiKa8h7l&OK?I@)P^p^Wif}55_ive+LkLQVr!R-h`aL>~@U@)v`xoZZG9u{o7CUPq8@`{nYilx37!*Wh|+0c=9y@)z$q8 z_OIJpEs(#Pqp)pyT41Z-F_Kvj1ut`%CAdP zN8;P4=d6DVfj_FhF`upZ)$;3c$FqwxKlLA-PLD;!Tklwh1nv53Q*6g8hh(5rC&52x zeE(v3wf?U9#{Tu^rt!%Kt%L9>K>@$@+V|fsBj%%T8(o~3bX8g($RNEf=>2D=*q&+Vk$pzxta)^fxG_Uj*R~ zjao-w={{50{+dek_uhZL{LRnz_%KX+{9M^Q4z&%cKzC=LH2<-#a{a9}U@41?)n~ee zO{MkI{M6=_b$Gjw?TCB-Q5vW5j}AUfd6ao3T15 zk2uV2`Hw%z^)s)&7whlyQl(!(yZ=}3YEAy;+h(+l3De9kkB?`&j)c{;T=wsN2CAQZ zcGTdtcp7Hv^bqpI|NERf7Vmq!WpBN->*uvYwfV9STaj&}uaTGUuUVPXaDILfySYH@ zuaqDB850EkxuxtMKcMGtRe5u9GhBf^`67Q!_g5r@qxhE*bdOw-=BNGn+8Kx9!B7Ky zsU-5RX+%G>^TKg=h%vnD@0H|ZNql4T*Jb~|{vhx1dTHF5!M|yKDMTj@)~Jjz3!NnS3j`lld(3&5cOo3scU=E{KE+2&xO#st zF~O%Vf`3qa>>lpRyI;?T$?mQi`!0`vTf4%UB znRgNUH$5Lw=lcSjX{aOPAC827TvX1-irxyGG!pSYSF(Q_URs2zRdvzv_W|ksX?#Sd z!ZIB5F~r9pkv}>{@X_?Ya9A`l!n{NgzoYnAIXw=p)hnavtE$Ss`b*D`$2vu#*B%qJ zw2znOr}fpzFJf^sN?ku{Ch(C*@X`I1Ij~G~F%}?tad@Gyt z@B8C%b>wGhep+9BbxH!f>sCSXLBW5@k^Iu1AIsUjU?bM@Pisk@;^SB^b3Xc09PEbO z(mY@8f3}=w&M(-HRp>XZPe`2^fy2c{IJRk@B=1f1U;k1h zmaFyadyLTESdt&D{B;$IHd(@Ya~q{L{?q1M6ef9?%Ho5xKH!*xIlp}?4&5Dueg+f& z@maSNBv@64!J{S8^QnH;`MsQVT~dLKI3e^i%~?j@6^NhRj-c!i!aLgxy=nTeqv%QTnaKJ`7{zA9M;91MQ(o}%kKmeetzbgDKCm%1-ER$ ze}aksIMsa&dwu6wnfrU+-PU}>s8rO~UntE_`FVq)k#P2T#J;o^`b+swqkE0{X1)gl zrvKyja{uyG=W*C_M%`cRw1{8R`pu5_{qc3_C-$$u7Uehl`vxJ{_!kSCDD;=cKc=i- z49gP=HOCeD>rC|5(`5;kTBy%|Ywo}4L;S~|TW4U;@ULwD?+oevy$QcDUlf5fT_Y@? zBJ?+x#Q%2gUWzSt(wIrWQ_)X!tSTyprgg4iW6a9XEDHaVTSpt*WD*x)YVK@2t zv*As~a>IQuFg|>^v_H}Mm;p8`&}O$O97YY4oQ~f?4+JtXxum`0HhotAz`j-Jqyjj@LXQ~myinYf7KKnP~H!JQ! zA2-2YX#R3qy^+}QtP=e{C_Zvyqtvyj#<&nI@!oDQ(# z7Dk)V&dyNqZ&E*_e|H%(>Qi3E?f0T6`ap zA6?zsoTu(viAhDmKI9VoEI2TNZNG9?^-bD!d&apyXA@`46Q$}Lm{u~x(Bk)7{&6_-X{-ym^e6blQKNA>xaBkKN>e*Fc0C_hS%Sc*m^IWi_t66ywA{u*|HMRj(w4 z7vE6|`%mnT)roP4X_Lz`+iB-lv5TgI-!3TAzPw@T{z|1^%hdk?n}X4MqWXOGTkZNk z{Xi%zI_e@m_MEhSYCm?bUXGSk_0jkGDQTSg2LZOrP?D~Pyy3#W(E6B(-9qpty_EgC zU)`JFW3^)(9w(TqdvI1!{>4Wj!N*CL7+4)QMi(Cu|DgWy=PuE($*h2h+nP!86d!A9 zRpL?e;$gJNM0|g8zUBGg2zXu7$KhO&-=g?P?B&3{$8X0mS2JNh2>&{jmV|NNt?)Hv zfiyp@FKcQT#=33OVJGG^lfIvV;G@dA8SJ<6y~?(u;9tQ+|8ItjWTr`XWc~xy@6TSQ zJnu#njt|r5H?a@9&Brob#p5#L`%CWI@w@NUwQ2F;()y@=|5)yhBO7nCuO33bDZe_= zwhs5{yAf@gyNLHw$o+@oN*{c!_mt`R3;m}2>ZfOIer4f0ga?(=$jjrWkzE3CGB01| zUx3sXoX&9II;*!~+mscOeF#=s%k1avw}EIk=QHb>EzW;Y|D$}r5QOCaVJ4Y^KT&@5 zcx^C36N*`OI+xbxOyWnOyVYm+`|F@_m7~%)qB#;uupRT<)Eq(PcV;H*Jld+C`f){bo&Tc|5qM!0=463+qP^TbAKS8 z`*6Qj`|`*z3Qo}mczJ%JG(SCmxlw01dlII{P*eCfG{5%!av=LTrBD^$xw`ayDSom~ zx8QT@@4>G=Po!}L;a_p)>i(S*?#RwpdK3HcYh6WtFn0x3FBIR8`Y#VVjAKv6JyPjh z*6zPF4YB7QUDIG3A0g%^{L9ka9dmd#J9GVoSU<5J-&NJJ`khPSzlRC?5kTxmx5Yll zU;mhmaufKX^_N{P*5H-Sq+oVG9Wg(tzdSV|07fm|$>Oh+e{Fs}7boX_W_O*0|DH?g zlhZuH(eQ;XJQGEHme%)gXflDX=#Y!-wyG|F^^4xm=ddOab2=8X{L#my^*IuJRm%v) zlCBC=zIa3$r}*-^o`j=?7O0>S_)(Di^%s5cvxb z`;&Ji8nYY?)ptmV{neG=r?1mWJd83z?}sgv+VJyr_(a~+>zVp~;!#@d&u~Q~d;-hk ztBdeoXnb~KY&LIiJAf|<)sCNag)8B!G)9AM)1~=o{r?R0z8=;`SLWYP{GHE_B-kyz83@n?L{FyxU8Kh!=2#ns?l)+OUdk?_xG{-WLM0NiNzR%V}Q{y8--2nyXo zcCp$$Y5pGsKXbP)$I+qc{`ONu{?wMlzdA>#I}fibWb0Oo`c0a@D9Q}QGu={VyjkFb z_NT6CxC%|?8G&~f<1~Kjw;>sEH!bk`qPTx6fZ(V7+b}%Xt$+p_+F6d%8*n(@sS zA`p6A>_5(3<@xb@i+tI^fQMz`XZ(RmeDT$lIN2^xtdHdX#!Pa@**n)+e0S~m`82y) z)(P(f{%cMb34hf7JRj|Y>Ru1nnN;om|3&NCeD=ju81B{6%rED6#g}K`ty3QR*Pl9# z@Vhs`&3M<8?KpjNmGJ*b{A^N%d3f9Sqq+l*z*o6$^7_)|lNMs>q|fYAyVKJA^nA?M z@nJ|FSi(*X7W|Fkr>Wrz)L5wQ-`3=yByUUNW4ldLalpV5Jum*2>>I8B@8r7-AvF}T z{uk8#j4+MG5_cn1nVlj%{}{0^{;u)Z9%h0+3k814k@)h`6YKGFeiht3lPJC~;b)c^ zk+5!E4y_Lh`$FT(r^aXV$`xHWUhUJ$&sv|2goSH4JoeCzpC=v>EcBZWb987W=2yz- zx8i_bEACOc69()4)pyJDf2Jq8;daV#=05(jB=1b{(<{-Ew>%V$j;jQI{*V8^+Kbt> zz9qwtE8%ae4a|AnArYwDL3|$&|0w^4FY~PYpiKN!%dNy`zKp@jCIUY+{+t}*j(a1o zu_eX=KeWG6imtkT#%~SMF7?rTAG!UBQQz-4Pw#%2_*pb+CdL-OX3u*He9`>)d$$EJ zi~1<5AEEkR{mWvU{_~lwOu8!OC-x=%K_C|Q%4Zf=j!EOx|4&sdL)T9w>|g&2%D;xZ zTL>T1PpsB%5r3ln$tq4tLHU6dq3iie@ITUjebJjxbeaB}+3E;>M&oDEO_I^y&KwIj z)lmMm9|44)bzZXq?{(DmS?k6ANb5^(j97v7S>^Hkl86t0#Lwy(r@<$(DvD1gi|<45 zGuJB$<#Y8gW45R-q4DKae%bs_R3Bbxhj#od(p!$cdlh&$ZLG9@YJbuPuVSxb4498m zCow<4Pv6AW{LJN@(C;Pc!zn-Oy|z1s=^kfA^@RPQ_{sG2W*=JLRxSJ{_FsyR+I1}X z2&X8#=^*wW8ee|fdLnb$`#|+4Q1Bnh&z83`<9(NeW9_xc()wxsywMtW=s&r_rri2h zA5u=XLHKbSKB#*l{B^o%-d~Q7$qRkp=5UWK)ZAY{`Pt_KGx09^Rhjt6Tr(d(^xv~l zON9TDNBCFVo<(T$@gp12^NKWoEWt;JYCNyn|32{dSw7cMTimU;IQ6{PcE?LEF{kk!>yZM|!^D#>7>4ve^JXMzxgW zDSoWJP2tmz)FAYDJ$Ddc)MdM|P9t!)2`V(4z`>0tqXP0~Nd+oI2r`F14NZeA) z>h2va%^ytav!1>3=eBOS-~mlF^ULi^@aP_R?Q@I;ofG(=@qv$bEcw&iNNgG_{$DPM z4-CohW?#Q#%kbk&>`T-hEAF-{3cJ$8_ow)|vUdU-wk}6CR7X30+WU<}`TAF6{tLAq zO@gZNgzB-Vxv#UNAHgL5@;-DNq7U9?>u-tp2F=gwU7d+Re_qJ=)epk2-fmh1GlviC z-}(Iu1RoOy&BrvOeAc<&MQQ#E1Rrs`#`FA)dpH%W9UmWR&qhqgSL|q4@qH;iB437K zTD-dddl$jKsC{{8zZ3i!gdTa940TI4Td2|nfp#;fsN0p|H_lz;JagV>MiPE&c8YmcFNqFw*3$3!FL zi7r}<)~^4xT4(dQV|((>y4v->c>OYDs(a6_UZh?B58Nr>)6RMFTSs>Z{U`Z-r?ejU z>~geB{a+X5&6w*=)t6(!KIA&f^N+XZRpOH-MPZqjhwi^_IY`YTXHh;Y&?@Ii8t7q!Fu`U?F zdY6cg9V7Ta?;X6Ux(0i{uE-xM$oaVA<>T?9mLbO15%@_X_{liy$5-Xw$E&^`LVrnq zCZZq;1;IKp{zdy^A1&J}$_=4O6z==| zK8CMsq?uoCKb~FciB%PjvT<*|O5catkGc^>ytb1MPqR*y^{XlAAB`_Bo3VqZT(#jzUqt+h;^$JuWPEsHgw(wDk~}?sx7A`3 z(oHMl@ylfC{b>DfLGviwV8ef*vY6ZnRx4DX38y$`e9`r7f~HB{X{uUiBbFBA5i;$vj84-2xmscP6roUcqH_NS?Jxh(fR zGkNxJ?fBSeHJPn6xThLCPCGvQT6>`0=!>%aCFNJW3QTzB>=5(`X)1j`TasV7knMxt zeQvT&U7kwg5v0FGWp(e}Hm`GK=lf}X^2~KRZkC>i<1X6mOQ+9^F}>A0cC)&$FVsJ| z>KK7_PQO_977wKPy$S#7knPL2w93W~EA95BS#S{Md%j@K=Eo#?ijT@m7GvARx6JMQ zUTK`#m#0%gaQ6IrwsO=K&A8mY4E-4nkKf;!Uxd(qYCoFqPQ?SI2?jM4`hSDikE;>HE<0 zeY#tE;nBB4>_BgkKcW8ltRY3bbnzG-p}r^X@AD}>7FY3MU0+;NRoN%(M=-%h^NB6_ zv*nv%KT(4(Qr~jPZ!){G@=lrfuwGZ57tff5hYdZX_0#-+>p>oHx^kX9)7<|_`P=iYX8M$jNoVVe8|otzI>6_4fr0@ZeLcJEx_VqFWI)~ z!hfgzEq{hD#ANf=%)99x>HQ-}{c*(VU{o3Wj!mpA{Cj%7YNy|7M4d6l&?5pLsRSRl z_UzzJN!7XiQSJChNQuSB6Kel@OG~BDPkDaDZs{g$sB0y&4-_B!BX9C+=F1 z`-y+wZ+|enm*>gi!?gZ|#ryIZA=gl0gm!%7x1R%pn8)m9j+z53`Cnj<+Lu1NLy$S} z9ow*4@Gn<_52Z~oo-TO9Hfipsp!_Sdax@0G{$|hr-X5=8wAJzvFC>ronN28+fbzD(<1-tAV`*SuC>^4S5( zzwb}$$8N2-$@dTL%)MQ-3@= zV=Ze^YRo3uIE(L3@+X6974fcmo_tjW?f5dj>4JL3M_BiX1(Lji;LBIHTvokbQ~6Ub z?fff#!4T{$IK^I{5$8*Sm2&@NWlIC@k~tF-TYHK1k^EzYjvnCW{*%QAf(gEkDy{g9 zMq${H&{~qG=c^`6^2K7ktE|Td5g(xVTCiXSILl$HYd)6bY5v5#sXce|OephyGOOAl z_;%?Hn`|!RLGZI9M7_2r@7ai1x1{G&|K;5(U;eHBRrI#ijvwz{bI`WIBld8wzz@yu zFDPD$-*xj@LM!e5e@){hxRL*oT^XDv%}?)NT2wU_J%+36(|ppU@mS)YTun{ED+@zh zpH)NoSAPo$e)?_S!3%p;<=why$Ir5Tt6-w;y|>X)@UsiVzi)dy5$TJ{W9aHAX?|*d zYR`Kp0-0Zav$FVEa-XR@ctSRkemV&J zko#-Tv|P{T{4!?Kyt-=ECqLgcUAKs*Hy*_soK4os&vu-1LHpQ4tjI_^exfc}aicY% z7&%hpSDcA`x;t|SI*mWcwoMWEq4vq5R-iQGRy) zy%FCzB?!0cHIm*B#6Gz$@kK(=Wma@d;3t*Xr|TAV_-of#R2!qQpXB_@u^0Y`Id+?^ zo+bQ~{UpAujI!ruVezPQL%V&t5HTA=*nQ?|a#LEL4T%r5TOI*Bb#CileOa)x{C=i{ z$G&{&<;!K_D`wt&EUEC6ed>E$dOnRm4?Gl%nr&aPv>b6hjK&8Ho~rv(Eq%r6T@~>G zR}z2rJ)4To6%298M#$6t<6c&)v3sB)R9Pbb;!W_S*Cq|aGR%=L5m-X#T%N-Bs{;SHki?3j0IzlQErd@;ie&@WA!j@$)$)4p!+p_|GXoDey11 zKd(Ey=M`2B=5zeD+aJ}$^=zqe+4zZn@RghQbLV;UwBzTRjSCVZ4>Hql@1*yq{H}KO zN__vVrMMC#@Doh%Q#)ZWEbNXm%Z9Hdd5WLYO{b?grxg5- zo_}$>;tQqCB^f@beJRoN$8P6r2Cw_l{Iq_hQp3tj~HP-kqNjaELgrHU5>^Wf3+Wdde15IVsIg^?OWo2ppcgWY4qqOXHM(z4i`) zZNf{oyuI*GDF1r)BNgTB3}pIE<6Cx3)Mrnp>dW{S&7U-?xgMJ?8lmMy@%&&CAO52g zi?k^vY^*}qj~~Q-m|G{J+6`S;Y>kxGPwj_K*h&Ok{LQAG6ZK&l~h5NGotp2mN(m2)sPrKegN4Fo2rcKqz%j3h|s=+9}bd+Tn zY1jWEZ?mkZ@OgY(g-K%lgn#)?_QWrHE~`JL`d?{+DSvz|2z8D%k>;o8C+qF<#Zd1H zY}i0yKPW!*m(}IR`>w*()*`+~&wrUcQJ;Tzy~#`;3H(rgHYB|s-&;Qpl|8lNr%h@w zI*)$F7Q2Y}Sp?x{fo((a>gy}^@BAdSA8sAT^IcCaV9iJE_*$v%?b><&6E-$j;47BI zmmQ0iK+h$Y9UCv=XViX#sQX_X>-LO!e--?U;_F;mI2wJ*XA9qI{8z%y!UIxpKeHTO z@2Rf*tDpOc{U{%^7Pe~pa!K?2T!ODxX)Ce%+fVkuO87Vb=X^|#`hMd*3QQd&>eDH{ zE~xq4h?~FJ&gKK9`F{|8R^99-4|8f&mTOE#RkjeBEClKlZU$h=I6qvtnqw-FB(7CHZv4v6JIjRZQ^_x#n-K_ zi*f4JBQ|BYz)u9hPc5GiOv%n=j#k?3Q|;g-==tk0>&u1zPw``PBOF(h@8tL)=l2h! zr=SM(WcZ=ylbdZ^gT2Gl_lKSn&j-QJ*Xyfb{^BS5-q%t27k>>&{Q2?nc=T9T!Y3$=mA3>wX#KJCoAG$r_MFWBr}%KPZ@`1p^)th+Y4Ab(m(|DB{VQ%>Wt|&q z$A@Y42K+h)vw-{R^ZV6qG4r>gzKF(;e`H1CZuEPmvR*GeU!joq_iWrc38S|ta8prL z`B#5w{>AwE8U(5D?<`CI8>wOuo%EB{a1#8C=3nN_h{NGaznH;}aPfbM{&(6E3!8~Q znL|0D|I~h%{<*;qG;7V>L$&MwZaF2h9~2+!2byxnycuQM zkFTZ^Q2g#cS$?15Bl5>|yqkEH#hPjN-?wMg=ZU9RBJ7NI{`I5LQuy3`!kin3_!zA} zp4&Vgb-VpyeS_af-=F3$?Y8>z-iOa%_Ss`v{hRsCm*DQS2h1Z$*bhfyKWc0aLDhoC zY*(r9ziIx`)+Y!R_$@YK$Qo&W5dYobPBO;V(81(I)g=9LB>bvJ+qEeFupA8a1b+)A z{&_~N1gw4do4FLUlH{8Z`>?NBJT5t_-@k>h56%Q1D_6vz!;sJHUws(GN5r`syw#zW zd|*B8_y~WvN`3d`H#Y5|@LvjveK6_v85ywy)HU3~KG6E%Exze&(+Cqb`lY}}uu^Ux zUWI(X$FVLj+!iN&KZ=i5aW1(0e3y)0f#BoCWzdh(>3yP|K)g!EB2P|X9a0u z|EKoD`<4eTEI+~On``G!Z*$D~j#{&kc&nN8{0zdMPSu-$g1%?U*TUlS|9b#r=vGRtf51{;}nDs@-=N+u`l{{&Fs=wan3SpV;0?R40rEyzw{_5=P!Eg=O zFXKOHB)^zaq{jvWM1f9DhJ z$^O0CnjUbub*YQ8RDnNfX|fAyQ@|Gam9MEJ|T*jRE#e1D?fvlm7p zIqeM_^vGM1k0AQpZR00gQR`@3OM!1^5`T(G?1vWWyO;TD!B29@{#$$4NBG|DjZvEg zKcVLb{gw@e)#tq|*;?=us=t%2>+-OfqwqP^Ox*uD{RoD)Dx^ z=VE?TYe}BwA3VN{$9MJhjEB`d7XN-f%1>rBYsv?%iG`VgMt_Nad%M*PRGV;7wm(z< zcAcXGuhKIHd)r26_IG)Ii0;+Y{c+zvU`4OQ`~gINm2=egUHOge*&_A_x<7Xfn}eQ; zt8Ca6!QZL=8h;H!?F!e~t$o|2_oMM4FWu>Ii963KMJ8(AUtV9;vd&^OZ+V*)G#C7| zB8d+*7`GZemg@X-#J~Mro0aI+ozix&jJ^5N`fbVij8MxW^w(Eoq|sbyoaPVq zWemoe|&s~)g&YqwA%tiMx&R zuYS?^|HCTlaCeXnob3dE_9o|BO@Ayy-1o;!r$Svxp2jEpOin@I(_hTmUAunfA6W_G zIR&h_VLwTp^5^k?K45rpPwf7ZCA}Zj&uN!dz`W;MR(xQ*Bv0?3a2xmyUY%U<_@~fM z%AfC8TJrBtr=vxrsBfYAxw-rR>>8d?rhcB7`CXlV=!Xi*`O^Am{BdwAH;nSz!y1kf z@yA@kFAlUe;sIaB!BTIGBp>W7*UwtIUU(aLm^E*#eScnVZOjKu^hLFH4JCOR-|swq zJS@kZV)gHf`XQ>nP45`--@kn@u;{7SU&;Qwx%Nybubz|f3%Wm_c@&C6kvVL~R>5Cr ze6f4^Ftojr!wSw`*Sw!R|GRpDy1)9LELONs=r`rZ2|bn}KIZ{bT^IYaBdI@HJjWkJ zm(H+&+d{u-d@*alEV!OM&)Ob}l;)@XK_hN&z-T{R3`(c5#f{;#v|2W!(@=zlQb*PV*g^-Edrn14;7|1`e% zW>gd$TfJaqoj=_-q7*%=x+0;~VQGC-zmI&gAE z^;abR;rJmwd|^nb>SB%}{i-=8``@bfehU*Eqv1z)Rv zXM@bzN%FM+XNr3Kih8^({SSN{g#+WCv$=JJe@W|yUb_5%|40{HG8f;Eo^OcMDa8x3 zfjFc(B)uQy*RlCU7<;rAc=aS{oc8Y+Hf{had`p+|{|(QYW`)-r&&PG~)fyjMI?)S?yo0j%2-W|6>nrmxb&rjI{5zQF z|H)0`Q5bWaHH#GbPwRiidd@&c!!t}bNbnQ7e_!hDz!NV{mePWnE!M8C(Kn}XwED&}#2m*)S-;~&o|2EePBvl_{pq;cvW z=34t>kq_AW?n1w5{f@uY8XQ#oWQn@MzSI8w??)U@|E7C;#z?SeAo3v%f{c?|O ztWZZO?f;~HVbjhOJgZT}zFCR=JD2R=Bh~%S`}WFZ9gg>q}z=j-2U*4PC_h(fWi#dj`TN zDV@chDUiNzMY6vib{>j;COc*Ow=L1%Q>KR8SuqN;&ySMiX@7v0ySy+z!G_9Q#Vyg z^fz5U@NjDcUY&Ly+RMAjxjvV!4|r7?g9AF3!iYwb#c`^i2Y)SOuT*-m^a;xI&;Opq zU}V=)09{9MKCSPkjQN4`*oioABe$P4|8{J`Y+?V>G)e!Yg5)nu{{6-UmQzvV*h=yH z=#%(wzC?rTkkBfacho0eS*Ief6TCJ_(2%ll*i9B|7O-A z2(8BFLdFkoX!#N?@REvwjc<1dFMgHf(zm}tv?#x_s6LdFT=GQ zj!y;A$4_jQqVetQD0t-KLx3; zcxG+FWZO4z{V>Oe7TN!Jn@I%9hus4&;PGK3v9BM6z3tbjzJvkCxc(hM>g)Dreq%wG zsd%*8P4WF{e%Z0r8tjr?0(C}n{L=kf{qO$6;g_ePe-)1(s6Ke?qrwh+oPiN;+r;Zr ze2;WG4o&7Yf-3b{HRICt^&=1d!;h&`QK6v_$Lao(N5bdfX`el{;=7%*IxBu{f;(?> z`%3e3p%1LFOjz4jn?9b{MVk%Y;3d%q6yJAVJK-0T6Ci8B@lEY(-`oZ)`nUx;By)Vz z{qZtdx#64QQ_$D3Kzu)%-)P)fIA6{G29#Xk_@?&tfly!9Ig<~iQ}e|6RR3-?UX53} zUxTv6XT@>apSADHQe0$u2^JXg{4qUWuv>C4wkgO3Up1~D3W)yI9UFnGwTs|tWiiJ$ z*>tL*5fPm%x^2N#y{PEWuEmqykb}iZR_#+S|rgIp^g#w zb8ZoQOyc-IL-3z^V=vbGT^Faxd3^c*ORmys33u=&Bk*#?Z5XR{N4$Rush`|BvI4_Qv%z;RU;jz_ zt6nVizz*$C!~B~55JO_$U#4whj+!rVR_6@4XrJY6B+r*)7J~hH=0c0}oFDZ3tDeI7 zoq9Gxf7v*0zY7TdZ_iFbhkBo&-mf;|_38So>1V?6y;mWu+sgGbJs)xWt}4{pGX-0i z^8P)#zrFpJ4Or;<3=W0Q6t7Ru7hm$Fkj;Uv?8gD+`2H(=-wE$;!?d-Q;(R-jpUzqR z1s@(8gA=y%_=DCLb3>28Zqo*};K=rz!5qJI{fGMV25j+oQ_S7fozExwdGcc?47EH8XV*Ot z$7%g=mrHLpuu&*pwovEea;bj44Zec5I|t?&_r!4>g6~aX!uq~}Ip8;qkJJ3#CzWW7 ze^~_X0eqasf6J``G5&fM{I@>}U4Pqjp*MC>IRp3Ka{EH#zXk6$u_33QaOZXVj;vFh$U0 zY=3O4_w?>j{`$Z(0xfd7%9rc zahf0baq|Y-<=>9Yf3I6pACl$=jhouwtrh#>UVqLHy1uZbcSAO2hbcNv=lO4avOY>* z-x;^dGQfTx=Lfa#6|Z`;%|k=5FhMy#%5+Uo#U&kdw}bfnlpmF*3VflJ4L;}YisQ6? zZn()GFVDOP2Ul?aO7;84<6b!E>`CY`n&Y3wmnx4pu^7cuA^)iy|NBZp@I%0LFsZ}y zdsN>mb_@Hv7v2JwRb1a^ko|#e?V@qRvOC~Cl>h#E#Qry%8IIaR^Pu}?HF-5YY5%R8 z!DhUc_8jI1bN);v`v2a8NL->@2#s#>_?7Zw?d30crrT)Dm6eF!Pe$@9BVxj_VSFA; z^5pzzNci#Nz!xlTHX2h;DDOY9JsN>0%?sdD^BR8WOZyLheEo?*GsoeDOGo(qiT=?^ zkTIK^6Y$)z8hu9ivA_FiXzHs8fiAqhNc&F)O;u$@wv*A{BbZ;G#J^*GO|a4+O~MbF zf7!HHgDsnGgyW+vYvxP&p*h;gc{Gk40NN7Vg@Y{SzeMlyg?$7w$!5J;n4omz8 z<;Ul;Az4{xqgbrBmdMYpqm-V5%}zBt|UJGNaEv@1GZp={0*3! z^Z7{pN3)qxIIr<7FzDM&Ud=Ch{@jYsYw?Y4F?>szB93<=_@DPO5}z$Bfb6SQ;d-%mmC`&jP`tZ$?V$yP?^Zu z8{^NLi}UIJx`xp<*i~h(1fO*O9_OkS?9C55tUq9oIG@^Y9p;4E#}2~sv-ibuiqDY( zK0P-^vS*W&uZxSCgdC+ zC;G&9w+c&mX@DikoIg~be13iw3S^pKrD-hAr~2gXdQ-fnw-XBVUWwz81izCOsSD?$ z%*3cg%JJK+hYbdG*bUpmOU3zAf81)+k}2NW;F1O$zqCK>l*6oEm(>T6p{-x<4 zP1dEaP`|zOIJ5fu(fmu)V^3UWn*mlB#u-4u_PlLANgDZ z2Xo%PNAugAQiS+&(GloitQ^0-5wYxG>LctqLOFiHB@DBJawPjp(epVIv?Fm@_zhT4 z%I&Ly`jl$_ea^a-Y7V-J%`qT;9;W$3>Dja!NPhS0fXno$d-VV$#eh2w4xc=8C z^~nL6v3URWL *iSsGG>k0d#4{DGHRYnHlIK}U3pFcwX^BBx*b3=SS1?m4Yv#-Zo zb0*=c5B&bLzFu$01?Ul_38xm#7w1!a9;&FvRwYcvjVV07r2VN4HB7PGI~iU%aQ^uc z{NC-}D9eAA5i>t!$Mro~pYu-L7ROlalGtBbUv!$~fUZ~fz~wi}@!2;_lXZJG8;cv( z50fiIPlhSaA?W%e>DHC@<)Sp-#QZ;@3-LiCiR(f8&~7Zz>9F;@g4E|Q2X2T zVJOa!WlQphh9p0(skaFI*B^%iYk7Uem-L@TPWHx5bQ ziLZVbZi~-`F|suA`LsxUd0<8q9*nyI|D8We@vFOHJ8lkp11kq`e9->v{!J3l?cWpl zZ-31K5LJzhv9MGCmerdf6ZwL>o9-8ZTRo}v%W+hjDGtaPiPItEq>ho(){3W zzm?dr{5-5U!}ISnf1>l}H*Om_5-)gXi1$ZgpI4WuGW6BQhc~(Xp!vaX<1Rv4TTLi- zGvUuq;z#SVby?ev6Hsk>s5nmhTW=Yd;=EBiB=}bl{9B)@&sfM5+<3=SoKN+~wmUYs z^hO$FWODmW@js(mb9QE~89sI%AkL@j)24oL!e%q}!r&oXf6)4R&&ir>D9%J3ALaJ@ z))6m!@#_%i?&bEoA+g_i0~)ZZ?laISOF2JcRhDC0VgJ%~1M)fziv;#rbClKXUf_VDy3`FfD`Y1FBy%^I}=<^!r$6fO7jk;C?Xn zvqo@#$?;A3k@7Db(**2UW!x3@3q4<>&5;m1kieko^(OK8N=f{gcrP3c#$15_7ao7= z6Mfxk$|h{s@E(|q7$6t*hrYBvI&x4YX7~=n@4_0@>T!BL&8BD3nA`6rtP14%r6=Lf zEbBkmBxoeM?Bx9?wEi?f*njj^?s*9AI!nC2A<4fiwEKaclZIfB8t-qT{7Gz{3E3eH zU~y-TUwy)lJvOFj{&|}uzew?~pVBa^?zfq2qlc|h`=1+PgR^_2f?^PVe;OagraGb4 z_TBLIFt^`SpLCdFhl706AjvI9{C+7!Kj(F8z)a1iq5X2@`1RYh8hgw<2S%&7eW&`w zK;Hppm8OHvbRK`x^~dr@Hkjp_3e#t#i1*JR_>J!Cizn+HfqD@fe-yu_0)BsZ-m5i# zvgl~AaQ;drw2I;LWyHQenG}ZMW3!+lVzYRE*?8&tOtsu_+`jZOrK#t@(3|5= zLGai2OC^5K9E|dh9DnruR+*WMb)P>H?L4^tqWw_@ZU}eE8^Fy-u8$RRX?^F?R}(xm zc&lW6eG0M9k7Am!t~-p;a+90*{B(c5V@5WZ5}E?0S=_%-e2yQ}f<-kp!FXdmaXyU? zJFRuXb#-^aXB&=R8Xw;L*MMC(H5HqOKN9ta7OCIQ-)WC&uTx>5GylH61m6{z3e0(P zRx&HppFNweMCY@oz)7&d)%J(hZ*;7~FhDMO$)1(J@#&4h_$P$hj})R$n%G`}&$k-EXf-?W z`V_x~)2lE!WEd8tt`x^8`D3FE7IsLM z;G4#e@0#kciwn$A^T?2z`%Ck4#><>>XQOm@_D?y!FSc{VL8Eqoje4#)UqSGz(l-d( z9Xlh*Z&3TIAKZ{Vc{LUPmr|?#zB2t*|ND>lFE@8Beq`5S?6`;G^-D?p@)|S8*N3*k zoGD!YQT=VEvKSwnI|Pdx?G)!z`<(hgIDa?@z`Cn){2!PXh92pe(A4U-Qv3&bMdA*v zOEBPMf_Qyjg8#=F5g65yL0m6xpXvIB1052uqIogQY?D~?eA4wd&z6K^h(1D0G{?Uo z(dTcwZ9$t~4JBFay z?-k;BDalVa7w~VgDN)kDl1S{kO$S@dYr6ydw7I^Z`no{wg0{WVpjRl@&s1Nywa{c| z+D*blJ#L@R5c}MCtsU;}m<${1aQ#8;^Pn{0eCl(jCFcWEeVnXqgRkwj!}?L&zblA+ zc6z)Jqn!@Gpe|frl#=x`jRuF|xSR`;{eNkFWy#!7tcW}hE^BXz_|zlzxm~*z*nH11 zIH|El{JzvazZ3T78l77VD+{>)rS^Bm%SE`R<3X@}tR?>b)c!_xtHR&8Loliv&kxZ0 zN$;t``HsIYfuc}foKO1$b^6Fy$*!UJ^9%29p!!yp=ZhoL_d`)6pHKU%c3OYNb{f6$ z>h-=Q>P{ z*&B_)&2#37_ow|++1+eWv346clqlC1UA0^=(sd_9wdVMw`XN%g71ORV#)}``i~51$ z^GYXMtcuzOha$QEqWR_Q7eQEm{3-aP!t3J{pBim#(6(?ZBx!Mc>JfbY8s>@D1by>r zJRsbeo76%=(|UNX~l@&kJi6W z+N{Lo>?rIQ^jn;NmBe3T55)?L6Y^n#G1td*eawN*3(>dFKA5nliHJXX{#2*YzwqSR z0l3`%sd#_d9}@L<1LpePfKOkz{VOK@)kji);##OxJ^ND?ZzEH*@w-3U;f4RP(`1U<&i|NAN{k6q+ zWkUb8m!l!h2^uI~|263!=@smPFewEd%vO&7ud;^BEn_@t4CMI@+JEiX(H3>OY=xdC z9RJil2ZjXUzt$(ftq;#HQvIQ^!4X}BJ@|s{xPGJY-|6vIc%a)B_!ZCfHRZ?aR1Z`L z+CjfQ|9vPw2FzCAGtXmiG?$Mn2tOMB490-Yr=a|Io`~;Ggda|0g0WNElW@v@gZTZZ zzIa|KoPQ{sjS+uJRbK7iY5(@zo{>+9IYV3XY5f~45M10DK{*9dFiRGJ8!0H&sUjf1Avh+Z7 zKYIW&ck^)t!RN1^7I@w#4yIf2_>A@+9W-{sx-mQ8!XU2Cw1~dAdT!*;@RD|Mf~a!{PxHZ)<#=ne{%mp(9zNsa8wh^8lrO}*6=^W>*;)R5Nd94GxfM2<87I*PhD1M?XnEkI{yQL4 zFG-x=iQxOw{y_9=z8}_@ar;W^7rOm~{DiP}Wbs{YU+suK_}VQDr++^VPBrIC#FPAR z_q)q*SFgPwJNHe*H_g8_OOM3t!)IXYu}JaxsQvxea53)IPlv%HdHhHFgXRkO9$sIS z4LGD6-_KpWQQJ2KJ{;~UueRUx{P01Ro*2|98S+PReAD%ZOokR3BUB*<$;LaWL9PxqTjuE*KM(B&mN;e7_1)W4F2u!4Jnc zzI_S4H#cxbh1C|gb>*7)e7>Z<7wWQD*qsP98eR~Apiq(4{ZW_;j(fn~|=TMw7^C;-K7l`T4B^=bb2!jmF+QrZa2 ztsTU1x-r1g^?ix`9=d*|aCXdIDD%$}$Lab2pKEs5r9&K8H01t~u7BC$;fA;RB|+y~ z+&)wLeX_G3_T8Qe$J+7ygFcDxK6-^=dcC6(`z<5-q^P$7k8AD+xyxGd`Dp$5&a374 zQdnC#ZZ6j+8AP9$UEYB=(hFf~6tADZCi>Yj#2>RG(qODgGkNv*r}>Xm9aUDG)EB=r z(7w0PoKW3K+`4ivnm?`WrU44C;|JdEb3y<&J2HS$UeJ>{Y z(lcgFZXlBW)%q%`%m-JKR32!CyS@y%aNZ%e$f0!kg&EmyL=nW{lWDM)i+(n zw`5QHO~k#6+{O7a(*LAW&k1+lkAs&B&x_BONcdykG)Tz5?t?wod47fR=a8Qb>J8ci z`QteLGKl|(w{XRX28rPGi~9#dqJLT(TZ%d0bxUj+v<@zQ z_$q!s8oxdq(UE=WKL=-|^Z8W&Px*NVdTnR`mVdZDqWqb$L&g?b^}wz#r-|36`p789 z7IP9dg6v8Ozd!LW7mZX|qu5>&{?Pin={FbLF(DpiOyvHB_D8MGYs@kWN8;z!rQE-e z{7c)L3-D&0ZIb>db)uib(p#`x4+HcW@1~SLZVsN9*L4dVox{ZEr}-JpGHcvxvjH3* z?Gwk5#1CCRTVW-vhmLi*{z@VIF{yIFj??4eYNB%fYzYoPojl*SKf4evsmM;dVCm2&^0`??APZ*|4ky;H^OQ+@>RvBRAi8zk|= z2EvcO_Bw3zw26rA2G=~Fw0_^&)fJ62;vi``=LgMC4)$)$+W8Mhv*~<)s#3y_@LXYk z$wf)9!;k+yGQyA2f)-5ks2sPDHb_&|KVtHi&&x?qK6z1M+z{(tok zY5(Ab%~n{y={gv-mD``agde$YU9p2r9K317^%?aqzN40-nb6;}u4lY>f9hX4d=t*! zn{WW4f_QvF`7yu0&|hbs4#%vxeOD0wVtpqN#|%t`bHO}5q4oU{c{^~x`kN5ak^2`J z;m3>9i}A^iZ7}L%6L~d0>HZYA`XDVihmoFBBl`sVvm{CPYX)*DY0=hOa{Cu?Qw&Fd~0V0u*iel&mI%%nM6`EWF5 zK0YLl)A)P%5G$;*UjyxOzSYc^^5;{>d(gO>2B_Xv9-mCAP+?#9cEhRbd3-|ipKGJ+ za9FqX(7p}VU$p+;v`Jm|$gU@PH*Z_>d{TZaOLoPr`(kV5$C4|J88jG%x05+PXnyqY z<^^bZAra!VI6uyi{L;di+RQsujtyKqxc?ygTX}yDLDMmN;qV;JPg%XDXW99h28{~-*UE*QzLXLmxA5JVQU?X1DWvOL6zChBy_%bm7 zr(`8V#fZsruFs_P*-N%E_CThKqbhj+ImN&F)Q{}jwpQ#z+FH^6)A;?uB};s`KN^A> zE62a~i@UHrp?+h?wYX8*W;qWC|PS)X;9-3R*` zbQI^yNPbnduPd&4yb%uGzbB4U{glzF3A-0N1a;nU{HGBAaM{uoQ+{uR?)$Hc^J)G` zZ}3tK|Fsng7Vz=D ze4bV!lUL(MpWr(~u^mTTx&ko~9N%>Po6GPJY@4tP&K+wb&Zqn1J9!|RT=*H&VwB_G zy^|--vf2z^)HwcWeEw^C0W0vX!)_)i$A3ve0PgCr102;k{%Qa2!Z)3nn(1_G{FUR2 z))%_&tnx0I|%2$e^-x!viZv6i~IfSvlkzF;+)l?;_px63yYU`;FDTC zsNa;w7c_s>ZeKliSG@-=t#2gGr~2uNlO1**wg%p<<11$G#Tq(y8`_` z^Z16YKT|}}EGb2EExN`h|JzAd)eA@#jKC8h$sXxSr7D0O3x{~?>jjx?Asj~a|ol$%4O!4>(phJ zExX{>VR@pyq5IRFnc|ES9<7DNtFDUktw{Wk+PW2+_-ho7t?S9>6aKhevBsd`QIIh6 zB!54`A3Y6Q98nboxxyJ7)%c_Jjfb18aK!RRuvO>w*O&N@7CA1sOb0_ zUxb(X$3w^|&L8SOo>_$BK7-wm`<~b5X#9{fd=(Cxz8$(6bN*2O5t1K@?q=yie**8{ zq3cWUz3Rg53+IQFY~}lt(DkJoPKRR7sC391*iK&k{`CCQtaG|-ip?~Py3N<8)BeoI zeLYbYyb*@vbQb5+`g6lkx=a+e43wf?xo8v9G;9m zZ#aLbemY`HoPV!Ld@;n!1}h9A1^>$NPxVug zsWm1iM!>{{9RJjRMD}#SR#j`jd8Bgu&pojOXTOevfNZ`#j`|N=unIQ`u}5wA-g;U% zpDOhbq%Y_CiQ4}Q@uApsaVp$>-B!fUYhwTRdFrx?s>x_tv;POpubwmT#C;t$z}KV7 z@#}q}GxP2^8O`4O6Mr9y-`z*Ou#s#dyk9>`ygxlZ#Sq`IaY6=f-Tg zUSI5W*jju)1+o7wLVk75+6YjXKNiO+euK8CunLv-*deHuIIc(V+e_0Hr?!oN!C}hr z+ca_kHrCk)|C-+t=T{PZRt<8*qsdX=@67urXnwTqM?2II@HKC2OADF|YCalL6 z<@lW?cg2Z<|6gV)!5fwpHK7uKR-HQ(4Z(N{aKUWBJ2N+!mP11hDz2S(fBmKy$fC|i-I}japLpq zllqtHyCvB9iV(l<R-bKt-`nS5@G!Zj?Ydc|JcyW4<9v)71p0D60c9s7reG8 z3in<}hoQzCU-W#4NrAe|@8Wp8H;m(x>I0L-p4g`KT38an=bs_?WU>MlH}fa9*rgnw zd*02$;yiy?qRQh_x<2_p$~!h?aznOwpmKb6S|jKKmB#GA66N?jrtW}Af_>O@;#bZ4 zOY@7?8QSdd-a(k8!Sh>me_T7f1Lw#7$t-zmBhIJz{Ln~~c|7ilYOBq}aV>KGnpLvU z|GpsO9y}aXeo|U{9f_3MK!-riG8K{`Qsne*pWXSF|t0#uZ-Zg zB+w1LZ$-h&4cEo%_a*we!zdjV9ykP-lyiM8Bl`NBx+gB07X$AXLCyQsm-J_7&UC@` zVUbYp!C`S+pWwg0nJq4I36=B@QT&&_a>0*JBcXgIx6c&+EfN=?zxq0uZ@6B(KDE!0 zg+Vy4d<)#U#``1a{^jLU{BV`)M%cQPtf)mm2&*Ys1z`d?cec`g5#gYmvuV2W7k2^5It_VoX6kN{NhNPcP#oy z19ti8&KmnEUH`FS#Rv8#q#=7XOF8~yTx{`j^AJeh{6qYHR9~p&3H?7Weq|22%k6I| z>2D|>rOE!-cR~9Ej&B-2-nX*F=8Z$3hc(AH?f>zZpu!#>X@!-ixqYVn4QHp>;zQLC z7%i;PseXT&UmQ2a5ic2s!IC@K;yCSJsHfA4eVjEA!zyd~7YKe2$er+4c^DL2=K6y6 z|1>*ojY-|;#_^j$>~~u4e0HSG7xX##pZ%5Yk5ystj#=qx zu=In<@%hK_1JnA^fb|#lL9hOOY5uRlPHVh*Q~`M&-<0BW>HtmVp57V1$MgPpJF@<6 z&#xjF9#mN?ehY>Do#R}a;h--QYQCQ|KR))aV4t;uYqigx{8X5`xi-4o=J=)dInL4+ zvyTNqY#WYWYM97zn~sQ(*k>BQmGl+XZ@dkG#LP3| z^V9wtn|&5&{%IwYW$qHkDSn@+`(Vt7Xz&Z-`6ok?-zb>siaN8xYqh@z4|!pQ5Z^|c zaD3AI#x36<^fQi!hh6x%LSL$nE6&FtOi6`b9o6O4zkdqJ|1CJZ6tCP{4`$1kh|e!0 z`(qtC7>rZ15}@LbjyRv<`}GcF^5ahsBbDR({%$Y)?hysYKXH81{ND_%d^T+PN4&j? zuK` zt7^sn$w@_E+~%7^e^C4UOW6NpTd4xf-zc}g6Bnwm&si<-&S8#UYJW4U>~P5RAZYE! z^9MA)-CxkZ8fPOxJzsf$W%NI1RPPlEPoDAqVMCICtL$ol7mf#j`v{Itst>v+IiuN! z5Rfh0DgOQ$1fLN?f7ri|p_2Rq)d$(_7vLM0C}4+peNms-SMPekIKn#)()MzEQhgA5 zHU=ASPJu`jj!y+SUn=vp&>z-s0~C8L6`zml=Yt(Rh1e|u0>U*!d}NUP#MVE^dR~8w z3(qLW=j5Z_=pPpei^947rS+MrWBKgxvG@4+5yvOh52Yh#;O=$q@X3PXldi8b8v2gO zhO4n{w#xC@HmM1Ftk(tS7T4fYCf#3oekW@*ogN4WmnhFq*F7rBYAJ8VwB`oX=o4vw zi`l^JDeB38g#pHd{cel*|Rl!*04X`+ESs^J~u#5wEh|f2^VgP&qwnYv42~!$wL2} zQx321=o?7Se~mC)h?m<(L67oF{QU?&QnajaW6J>88M#{=*CYCw`8x_{HwJ-6Zn8K| z_a{F%djVem836?by#7P;)5kA+Vx1phaA&=8{gGx9jB|Qy2DNhK{AlhKh4uSv13ee+ ze<}X!rn_Miy-?`&t-ie4zEl0IdL7w9?T2{8MLGU$@_o_nP9!V{?JCaKC;FpnYCik= zwH)UiRjOXN7BDl)U`1?f2$*oYnml~Kbl`2_Obyx-n$)+8lEbS z)B23rT%rHy^isHF`=w^SG=6OJq#;}F*a2U>jI5b2#ea|FBJdjUu~z$i!m$!<(=_qI zCXRo)|InfmTP!~j2+g~3{L}bRQTPvg88kur<}LX1k^J0r1ABZvVI?fG;P|KOM;`TP z&1Mhoi5}TCvwE=uORW`ldr8<*9W~N^-USU|K<8iu%2ENB>u=2 z=TraiVv05Xy0Hwb=W_c)^V6$K9fka&0_=V$$A58GPwX%-6v7rH*1W%T|K-))U2v&G z5FBX}Rdavo`cw;f2s&(xg=<;df0Ppaa@9Wu?eez4g$Rys+Fu_(GzOc6ZG(x8`1KV; zzs&V>!)=FyVL>LJPwOw0Mab3{6yv?w%K4FXF$jyFY!uel4wP5(i~5I$rul4qr#EP9 zq?{jZb{XQAcn=tA(nXxVhOAFDI#bSOmaDS0*(o*lTN+UcT6t!}IXwSN^^11?KlBJ|g#LDu#NUVRk67YpjR(v9pr>Si zmb#MsLvV2w-qC4{W1~6#>G^GU#ya4*If0UCndCToT!N0>= zEA;-m1awA#_`&as1XL_&<2Z4U=RFiT&O{ z@O{M<*~E3Xv0~4@8v7~DuN++vjKe(FgZWKvziEDaSa3dz>h%J@4p45t^)AoB7K@x9 z+>yrzdPLv+ozs9t8fxPn`wRU2NdJjbGi!7*@P%31mFt&vV;V5`(b^bZCtRGbAocO? z21T$c>s4lSm2&%Sdq!Bh-n|L_0p5R$q`nwcXpRPWFeTIJ}y2#?N47LtbbfSe=*#C$?Z3dZx6L~$0jB#h5T-sIG^_49*c9u zF^2+?N!uSBmqQPBB9UwJjZHxT__{xF}pzI=+7^OW=BkDn=;_4I(A6MKsDss2yz*q%LO zJ#pdNQ{wmcCHs4MwY0zX$F6ZCE4i?vnk# zXnxVb(h|pQ@q}R)x&5c>V<()|VQtjAVzWw)|5Aeg^Sy1cAY%bE^gkg!ACmahwT?Xo z9$W}rxA6WFivKf0|E9ug=7 zejn-ni+c0i@tLr9)}aEoIO5UGF_02L(bKDi`0$cOm*Sw!J zzU|*hm9-es0O!0BazOvrADTk^!-2RWcy#Yst^7C;row)$*T5MKri$}rq&~XB&Ky6M zxWJmXoF6j655)!QTL2G|dH$X9V@SdeEDNZE&;^w0`x9p@ zFk+?~xHRPa*h~6Tf@N*l`Q)zndWKKUd})5Cc(^TgYVHj~g*`B9(=od~Fpw|rWP z<8*z-@*(zu|MP-pbClyh$Lj~~I;Vnx4>Cpk>XZ1^=Dj7xrnpG-Q3k>P(P8aaVtyAa z`nEuvuaHaezqhe1UVG&Z$Fw>AX?<#rkiVQ7?gLx<^8PIvA9Ow7ih&;%!OQ!~^Z$Lk zU2*l{MbM>2zuOUgw5P)U#tgO#owP=j>25|dK`){n4De%GRa7bR?UtazEw0?Udv4B0l_yAvqa{Wa4 zwNJ|zqb~+Z_9u}M|6;OHlU>fx!Z1Y*zhu(k# z|9*0*zG^YUQP^ACv)263W4B5Sz9hpj%a!{Nn^r=8sE?C`Kaqq#IVtVg8}}~w;p;-B z{ArYBgS|hvNaBkWqOa6PJ77+v2kh*q+;>}V@IaBp~DL0{-bl22ddaDhQJnFU(xe<&*^w$>`gz=7^@JkPwQ)|{oJv4{Y7Aq z@>JvpjW3=)c1OF#izNEVj>Ok7ht-%?iYAVWeYcV>gq zdf=+7ziZ}8^G9P6UC}|u7e>w=BCqC;7Qz2n-Euba$4BfDnp_j#OYv`#UcoXWzhK1c zDDMA=e_1@PAxk~e1j~Fm|7m~On)^lYq5H$klb5Z<=cD-}qW~4wE2FNk|L~NW=a=ID z%1<*?v9y744ep5Jdc=R6cKC}CMJf{fQ~mT(*k5m>whxS5&*O92zu-{(1K0lj3rEYi z|Df^3hDZxM{KXdTE#dhGivOg|ZP+#U4tS)kw}^k*U#2$36|;VL!C_BcKc@PrJk}ne zkE^hLn#UKkK2Z706^m27;q7JaKWKbyW$J?7jlAHg6URS|ugzj@+0qWq=+I6%{(oi( z{cl?r!uw4e|8#%B?|(cnyucS6>#P#LKka`gyyS+HqkN#ljZzW+ok)B=xU(*s)xA4@ zN$yaCA8CBCGtUjpH~YYZHaxzd{HR>0#>{gx&`PG9AIrC_#`iyhp_5BLIoEH}{Y9cW zJL0HIZlHcbPaM}L__uCd&c1xDz#lfs@qf9lB^nC7<+a)WW25ha#ogjs?YqHe6_yfS z2bXE{_<+`boxuiUme@=3|M~>q4aWb&sXRWW_)R|IDa5ZnaO5%fk2Jr(ew5H3*1!XX3ww-m z`y$=Hz(2tib=^E9{SOqsF~y$3`e+}?`c<0WpS9GM9qI3YW4lcLh zV_}yy;{8*I{`r2v6Qh!RplIbu5ubGb9FzDUOz0H??S69nQ+)S5?2e{kUXUNe?YkYp zckxO$G&1sp8MoBL=cD+2>!rps#6p7|b<)6ZHRq$z z`d9E7OB`|46879zu74ixR%0tN)UfD&kobJXq z{RDA7@sY+YZ;WZy(-SHB>E>` z*#9xz%M*-}GHTvW%Ac>XF1Rq=1%@Q2h~qSV9;5KV=^K4umN(zuz?bMBPi;H4u)7@= z3|DUd=WTIE_5JP;*NW#?Y5bh8;fdSZc!K@y6P!OJzce9Ih`+aZ!Mr)E#pjce_~Es= zJ0^O#LtS;wAG$u)C%_FG$GCx7N5`7^QvYyLsQ(!+cZ2+coL_W(NkI=a<~mRfExIe` z*XX6Lm=oa&V{W#SSKB8&l7Dso)PY_3(*g58^ZFO%SN{hN=vj)Q~r$p?uLWQo#Ev^&L5h8 zvPl1l(e~e=;sNK6g48F}-`QZSsuk?X=k;ZppY>edn!R4zO0xcy`k$%GSD>ulayYDg zLwr6OKlG1x#s%>X(5K5mah%qdn^k$>=n7Zx+mt4b7nA-wUsX?B_t6z}wGzbfy@Wrl zU-;nIY)^>a6~*x{m)7S#esaU_WzL|xh38M~i2p%he{t8Vu3#LkoIe{K-EgsmGnl0F z-=FqptbOZ-2c9^?l?7a1=@I`kWs@tujBx_ZCJy5BYmxm!y0mt~zgo_4&yn*-LE?|^ zUDa8JwHkI^%<)O%k2zCZ@s)uStXQL*KU?>7Vz%o#;8pjZ;{ECVhgZ8hV!r`)691$i z{wbw?J66G1(Fa7tDt#s>=P-BdE(( zEmT3Dz1%+0{Fa*fUGO6H(aJU8hKF0kM z?cckHZP`U(9HO1^b)hY+a9JwepYrSK7dKqj-4Tq9l=CaW%N;GY zISTnp?w=^X=IXlP9190XGUEKA`Qs&C8f=JTK&`D`O-4>M?p zx#D~p->k{1L@R?2()gX^e+|=}@YO3zxV`AIIDZZ4@4KnimMv`45>?8T^W)8^RX99! z30xS$`LTiUW8r;k;e7DF@bAHhJ z`GsB@tnIrxs9AHq3FXHo2N!G~XAOT(x0P4hFJGeH&TlMWd$(N0!2QbkF-2Hkm9o|X zymYyK+d%wJH?y~_O=St%&r;5h!&O$ee9~Od-=v%$Lo4gB9i4tdV8P0o?nf3}k27C1=T5I(1K zeHBUYAD_JdTkASORNK>ItA9U*Tt|ZM>*H;(Y?(1!b4n85kM@7xoNgoJ=8a+87LIS4 z-@1_Ffs-9OUHn_+jCDcgg-&)PMY)?}3fJ+erKewjAI5b|HotYC)xiFkisqR)P=a>wPpY~aXp?mtRNeWd4;gU=orO8A*b{L{E&9{A463cMfH z=sUvC@G1V-ZmcVOXwLl`>P!3A z{(vw&7u?_34E{OP!p|mZY&HA_^Yt7bGMTh~)8nNh_W3m*MtO36`V#*&sM%ZgxVRXv zzuc}=-x*ogV{O{}fTnMGen>&$r-t5Em^EZ3blAr23(Zg5Rn%dV_I!aW8~FF7=R+s@mbbP7@Tug#2?Ln&;IrY2bjHu<_1m0 zamvpUCtKYAbv6vuQ_jzUpMB9{xGjWi%M<6*{d*s5^TxbRR**g9d|ixdg9AIl!CG z>&5%)k^DvF40jwU;CIjYVO1}{gms+jrHB|=vNa7|EPXEpMp$#$uYdzPC5T_m$~4ikohofnR5P>meymB z8dX9!-5UOp{Cdy#ju_O_Sdzb>{JWc4kF9O`6~6U4A$~u)zsy5<0~WFB59BUL7RPCR z{lgd=Joafi>~#Muj#K`nc2Q$Ff4)NO8HG45BmD(kM%;tvk(VX;LCU|2pDZyz$X(=Y z;`uw8pE$VG4xjy+34Zl>d`11+@>bs1F4zommkbsClY;2Si^qL1?w2_tYiX{9pnr4GC;q1?zGdREK`NTIP zJkYX_2~3IQ{*Cg>`{WY5;%_VAmpft=tvPe0vng;(0|6Y`nO?0?zn06e2IUf>$e)u7xbsx82p{Me@i6!LHBmZGJTHV?C3o;{zdBF zu3T}(f47Zb_477z{`*MlSFgY1vz}!au?+uPpCa{d9Za3jAk*O$akEACj~I;|;Sa+ULg<{#P?c%ts6c~CFmxTyaqKlB^h;fKm;uz48Q zf7JiH5YF$dm^u%hcHsVp^265K2D=4KmGDDG{Ll3M9=N)-G3ZX`{7?}8vwXr5oT6t1 z@rla)&#+84JeF$&gPL-F(DPw?MejrVJBgt7=cM?3sQ>8`O2Qw9!`67I=_I&4dzbirls}UDi~LC;{>9hT0>AYb z4_gND`Vrm#>G>5;Oxt1vvxam2Y#{z+@kMLw(Qy(4XRWRI{?hfmcTalYtKEk1Pr>;^ z{Y%jPCAdvt4reYX=g)_1p}zWlHWXJL74;kCk4m`EU#wLLcKch_*mtRadDz?yan5Y$ z>B04zg5)=bZLH76s(*s+$#ul}GMTh~8}HzXy^hU-UvlOAN?VF-e(M9+Jykis;=VZJ zE6SL zyjS4$mH)m4WPQ!=ro~`*@}eaEq5OF>|1}K%dn5B+e|z!z3b}NB@9Lqx_`GZ`%!-W? z`H@2M4`1p#VDBZ9p{^E>Unsxcx_e^tqqAXK(O|C62*0k6T#EIy%wgyv&M%tZ>;BLa zSGAY}W-iM4^`ZA-e6xDKaDZ%94L_v*$2CUaXWncHzak00rdC*E#{Kay)|vB*>bD-} zJ<+vtHmJp&NWY*UT==XKT&@57xrH&i60M3w<_n? zmk}N~ch@Y~(2etJ1MyGIdkE)8#LWVWcijKb{lQbtYO;S8-(b@X<^0JN)_)FbJ+s#M zCpz5~SJ=;h;d41ZsQ#Kg2-z&yi+^V-=f^Oi{#Myxdae5FL`6QExBe9V^HJ`9Orjmp zJ!c9OY#1P~)^D`G;r7tqsGWQt_P*UKet)|DVB;rMR#EZ{zNGT?ckPJ(>9)HV+z+46 z)W}foU#?A8VP2}GaBJBl@%nWA!262V@c!zx%&HyA`IC0u2mj>HhRwSoMf}tJcygdS z9-1&6{+_)fUZ3(OeYPj+7tetIN7q%yMe%*@#RA1Z#YP1bYy<-gU>6Xu#YRFg5UHhX zLDwKf$`*q#Fi=!f4DLOnB6bHLC@KmTcGo-K*SYJQ-)EM8=W}<4nddp@IdRWDvz_q= z5Pv3k@#nJ*pCIB7_D}bw_(P}4VRYB4Lz4a}duJ3(9Og^6S=?jq59RN)&HdqI{xA`L zHX#1Ay6p}zLAKQMB+IX3{@j%NgWsiL)aCXeN&lof%oP?-8Axj-GXCKF-nImP$Zjs02h5+a_LIRaKtZ+dO7mxdryq>d9;T5$oimog)s0@F^V3x*{#iH75AJ>$D&iOR zPj%cHat|^-)150?O8O_I+bl30GDM?)ayJP9gGv{gQ0yzbe+A0FU*Yrj!`cp^?_wDL zu>L!>=sT4EDxztX#q9f`{Xa+f{KCCm&Xj&-{t4G_Q&xV54Z6kjNH319NBM>B!)8Fq zSx4Hb9@Bq#e)ycEL0rzEPSCemE#d#i`p;~7ZLYz_C$xhr%kOz1|Fr2+5w-u6r;&fZ z8U@3vtHWuhKF0+9VE#?WsG_m+&uR2u76pMYqGTx5(qjBmp!!sWnJG5%E{{&{Q7hhuB``p-S)zsgbn>ZB?^XzDwdehy{)i$VHuM?ZePaQ0vk zzp@a&K3{f&fqMr~tNR(k_rd&H!_PO=Z!m=ZuEqQl)_>O$Tww;+PvoC4zr4Qq!$_AQ zbaowS{db<9-@A6Fttfx4hvKKor+)Bj=3wgY!Tb}}f7RtGNapL?b4-{%!TGyexBMV^ z;$S+fFUy}}e!Ytg1G96ZDDhgR=7(7Sotwt@H`qJT++ouCPv>h8gr68rJFc1~tOvv| zOMd@G_ZIwmb$o^Wo9nFa;E{2Mwm-=Dh3mf!+xvi#nIk15r1N)`^S(p+fjfMErZm4g zjhz7=m+a}|cg(-#p!|6a7j4e%_!D|4pT&>3|ESgBM%=}_?`W;oOurZ+el;lzf(v(t zP*azu0)Grq|Eu1VVw&>&sAxWz4CNnW&4M7vjK`PjQDMCcim$e;tfFJ~pCM;Id#UY* zSU>ivtAu7F2GgNU8UI`m|K?tv2Gfdc>5nN)KjQwqI=udx=ix+q<}?0b|Cil#0W4lW znvO|l{C$h~*P72yH*D=hzn^6M+kp62Cv_#feeXvn+we_1I1QC&9(+L;WY5eG&I>s6?Ky|KLy)ZA#Vk)I=X2f={7L+J37e!_aZ zKku0346v-Lpp!UhesaMI3izZ8g{-8UD}%j*t{;y27sQ(j*_f9*)ue>ozo4@UfqD1Szu`ccx!a*A+&nL^CZ zH~Rx2wvi(>xfreHw|IYEdOkn@^oF%)zAEPD*ff8rc5|Q;;~77%Bma2CbpbR#Ig+kE z!T5>$|GYx{L934g&CF!{#Qt&mvUnKtYZh&6T&{k9;`pwr`)90X3&o#@n5#!r0y--Iu-V4SHP z-AfrivH!f^GYIyLbQ19s5I?z@K44iQ7xB{t^-uK~9R#EOoM?Xw#?LgQPwN-YfPtrM zMEz4(pOzj8f;1isl>!#XM;}O#Q+%>&k^F!}I@H}Bhk0}{Hy^#NGIcXM* zR`%5B)|e=!lh!pGnAn zzMdKj#Xes2dkxmVg7=?)b_#&&UlkhpxhHTUkas=#`A>|WIKO#jLIC8|=JC~6THosY z_J9Tvedy4@4Z`;`MEqRl9l+;L?KJA!>>D#-+j48Vxb|vcy$kZ6v157r)Jq}Kx4|g? z;_y}pwk8hL{QgQczr_6^7DfT^rC34B9x{H)?AnO(yLX+Hkdtap-FGv7;`u=PR{6oK zBsu-@iSZNH2d3%q{zvXW^AytjY}MKiYW9+A?Eg)_rv$^s4m8}J`AdQx@0pEC*!aMnPKve?{{M2sPp7gO@aDw;QT&L{@3}E42+9vBsAU-AXE~amGIU%J z1nyVR8Esk3_^CksA(gHHaL3t}j%&;KnT7o4{JnnAs@ht#KiCWL^J8HE*reNv z{3q78Ei3(?bvql;d?L(Go92PwP;N^*4rTq7E{LDCJ}Tj*mqIju0@t@kI0VAVT5`HC zBiHt?{>A-Uzpn;@)*QKLe=+9goRI+#Ah#9mzr^#aBjzb#_fI*UxpJo3K8WiN z(Lx(q_^FQk@BLMZwj%qG9IgZ^Q_zKXMhfdOKlknOg|`OQ^i(?Q&&T^S3pXp_Kx+ln z4`Te(vlG|1*V%YOyTpE?`UB>t?MGM0GU-kqbYt}sm0a|Avd+JhkeqHqt=cjE0^)C3 z=49BFWlpmi{SlsDCD#)Dz#YpV7=O)%YPVwiK9Bf4n?K*G_`A8r{>--tN-!8|Lj$9w z`5*GLh<5G1PosYBS6c~pORcHWK$`y*H=j{ir(;BRZnE(FnEx&t0wEyEn#z_k{%=71 z-}TiS?kunrozJL;_&+~309G6rNOh{2f5!aZn8wfEs{j^WV9301TZt@W1@3 zkl$4y|6KWjukUwuprdb{5uP8%x4GQ{!PcCAe*RCuKjQysZ8va|^`JIaS$u1V_;2|m z01E0_|JNTNncsbJiPv9_w)_#@EI(n6_#byM5S;g0Q-{Ya|D;0o#}nF0xb?uA=7+HS z5!TP?{gjYi+lDGj8UM@C{+um1KfNJ0+)^|jzzgMv zMs{%nPrt6T)-7p%Mod#egyjHwY-@Yr_pyI<={p5d-OZ?8k~Ba2-B-fpH3Mj)>pH@E zTwmh0BzP?nxDQ;is&W(-6H*r=Wkr*&(8>a+n?&! zV*FI0`1V$2B|Y{omkd-+5$=!q`TBk!cwOl)^3Rx`zxeqhisyakhW2cKn>pfV(Y^pk zEAJ=b=LYPbkMsF4`+>Ajm+>p#Qs?UXe^pfnjsTYq8wISRzjMWcdX z%bNl8MK#<16Wd*ZoEFZ7@Hd zObUd{KK*GwYsSAAw10c|VkImYK7f86DeYfv%<`ba!$i9G*BJR<`-bNqtmEzfOaA^} zEu{VHp{aY}z{5y-W|_CJUL_azkI|=rQ2$PUTD_0)SAqQNJF8jX=iQgCcj+apmnqtd z{NJTQS2(%Ml-77&LtQ@+U6wuYQG#}RD>^Th@z>B!oL__e5_`=uy>$T1LN7uNTiBe9r3^w{BJ%`Fplw2`x<6CCVRT{+_-P2w7Q{ zw9d&~A%4dBsdB$()b3{vDQGM0Uz-^zA*;%grtDz;H4XV!`)0G?tV1uF6eP`G(_VpK zY+?DIz7+0{{cC3~2;`mn(a86gg#RD+zxj6vgc~N78v73(n1n+4@BZ{>5(w+PQ2y9w zyb_A_tVI09{XLa29`I#G7us$<<1gNy)YUWydL6W)+)KvaV5F~YCiD5zQY+duPny54 z<^)5l!~N)pLzV*n6bkYFh*ft2VaI+;x~qdUe}BCUgh$kpy1ixlTU}88$*wdIE*`d| zSGO^KCLw;Bdn@6affbExBF)cnBLkt($&x?cN7_Fgam@yO(?}|p&5|>HEasm}d>~Ap zYe`FoG5)zA{cr2l`XzjS%)d#T5-ijD&^~Ke~{7pzy4+Q^NY{lI+dq{LmT_h>Q5Ji_Xo&-HZtMy)1}XU{nLWJ z#r<_JazfxzktMy{it!Kk*F9{`pHEcYN5nte|MO|52bflyiujj@{O7H#V9;u8Nf&-O zBIsMpKlctn;Qpcy9k_t;&jtCQvA|g z6$oFC_NME5Gk#(JMvqN|M)8I;$WWR;CKr|P@R)^0{>bil!ta(QRGA>nALp7uFypa> z$bXfi_|PxJ6Uwi4)abtg+>~&9h6T;P&iI4#L*==}^jn<_QGY3*^B0@yDPcwr3yuD3 z%F}1`<-NTc`Qz@OgoLpcBK?W;Lqo!SVQ4`Q+I}I+-x?zQ*}It%`dC=}x4%u`5B6WD zOO#-J)dnuOG8)@W#4jA*9q6TmV~5N%@+EQD~FpDswKW(M?Gl}<4KXlFLY$L`W72;3Hs05foU1(%iTY(>MQGM_i zum3Fio6&|frTx>`IG+Gw_keNc?P>1@KZWm$`K4PU2zGmPr!AwI{=@v5&~`FB>|v;JKG4^%N@zEsyT9Hx{={257&^4-LH|%`eogHj3iWoF(a4)e1^uUo z_+`H*7}h29pyUVRmkROgS!n=lzuuMZ?|p!MAH<(>ryv-f(4C)8z~U=B|3Sw&2z>eL zj-wdAu)e#I696SSUH|J3l=M%=eE#WYbT^uON7_G~c^e38*LS0>vKYT`{$um9Krk8H zjfNg${z--6t4o&x;Z=Ay8dpP_Uq-=v{5qhUh+kfaU*mLELci$2RQEuCfgiYjaE0GL zJj|z?Mt;q=jDr|gXIkq3^IzqNUm5+};PIi>^n_A6KlwXW30+%vq4WDl^Xv6!et+`9 zHuT&uY5z6bJ_z1y?jnk>aDDJq4SqgC%XS*)L)!BB+wUE_(4mKzK1@ULRithStxVY@ z(ubH|`UjLSr%xAp;wAH6UMN2~H02rXGdq)P&6f6G`!j>!{-Z8*jS1_IQz3pm>oWuD z6&i{9<1oLDe-45Z23_fryNq8d#IFJMf+3-6SB?Jb{l#GDewe?mfj{RtE)sB_V$8YUdB>*{0OS=b)hfR7n4McjfE9E4$E9Cer-cK3550 z^}A@yPqZ*sLQqL(k-o$Hd1I@DPZgc1pJ#;de8Gr6hc5@h_tl;0*oqm#bsRr+;PqWz zqs}xecer}JxIUhHG7e508bnw1Wc-mK|MXcI2vMUuQ~3#L{pXn#2cy;xqG^h8^1u34 zf%5xy^(Mj1`YmXuoznVm4pL!|jLvA`YNKD4Cz`=t5P`D_r}C^Hr1_j6Eu z)G!^N;4TwJjBZ}!=kM*MZJLb>Z8@&FkG^MfoS$4yWXevb9u*oaW5b*3|o*=Z&CCl|z@ zE$%_kXsxLzzN$j`iEBB*uwq#!s&|?BAFS^h>IXvg?~Y>rD8&46D&pV&OH+;f$*ma( z@gF+=*S{(mKhiRfvHCRJh-9+-(IHFzlL;u%+Oc~PfnPK z@(-9l<$Qhoy~>2PKF9cj=aUrj`JWPn3H|tj@y7-EpJspJAZWfF9TCL%gZ)qcoIu#( zZ=x}N3fvkCDXZl4%E~bUfAkQ4Hh4?|-E;aHvf;F!QdOs zXxEkB1pZ@vM;--14fBo~`Lm&>C)99iK}UvGtJjP3>)ZSB`P)++Xhs88A4@{~ah+UD zZ41|k<`ZN7bPW!Mh~$p+Z6ns7ZI1ZU#qb%8UA9Fde~RmbLh&vW8sfqB_u>9*cTaEV z^UFZAe;oI(m@Wtc|EdlmeqXr8P1?~$ty%vg#&@z? z5R7SRL}#60`ROEt@4)0>h^#Q8@hhb9?Pd`SWtm1aeS|c=f1U{f2R9=TezE=j5)cHr z?Tx5Iq%?k~b>j8YTSHO(6ytYJu@Zt$8EVAuL;pbVJ=dOU^_0f%a$X;WY8#61YmV&q zJH9@0A=Qu?&0z62#&2rYS~wUugpQ;$B=H-0eiF29q^Gg|X~hLYL%a6$v!^tEoAC2b zBI-7!?ah8M{Gk4#E$$&;zND7;{ zKi>=Cx7@XuDhd)c#^0x}hJm(|5zPzE6YwWP_-)np88xulKt^6+_{aSV8~Fb6Pr(MF z`S4i(U;3kjb1mA@DU+q~*?xa81oE-fKYU_+(qVTn7+JKZmc>l^6K0bN3yq!p& zV|-@$1;O0O?KJl1G+M^54{S#__hb43<8yHzKL0zQov6RY3+eL{vjSmRy|(nco-{s* zGhZLy+E!zI30A`M%aA_U`E)OI zoIi#7$d}9i#*er^tjs+WEPY$kTxTO;J?{U?FYCGaA|zrofihi?b^`R8yG&# zQGB?2_hdL#+JMrt(*A$xnAtFUcN^MocBNqd6lgx!o^i#r>AW~meE{Rryu1OYJfBM! zhD{KjUnLixzcjVYGg`SRg;=kZ#_#WO3T|H0Pt@$$B=veRe&3zo&xg3xT%&!pI1~g` zM_X#d??rz9c2;I9Iv|(%e~jM|r;@-Wu%8&eDE>RRD;P$PZAEowNZa4-!xF%4bYFU- z)m0X@izAV z$;ABd-t&xp9i606A1@lC;9h0DrErn)LxJ>h^Sl5^Y@;u-?_Mas?{$Fh@BQ42n(krx zBM0f@8g?P@;$3qQKd}B-rc8$CKl+OKf$V#{bqKV7)0`g3m*$6U$tsw%)PlC1ctBkZ%$<%()ia|5D%V(J?WgL+XVclA^hK85el)VTF~0( z;@SI0_z#^E506gwqyw#PtNA0||MTK!2rTkxAv(X$9Pwj2-@m+QNHbA>66aTD-{bjp zpt)%OPC43N=P@=O25jg_>+K&P|H}_NpXm9KP=3B&3tH8ozwrEk_U|mdkO)m*_omdt zU09!n^81ccen8aBP4tq{F82Q;ekeNpgvtk-sJ~C5`nq`jSN-N*@GG+}?b+g;a2@OK zN2DqDe#sHK=$&UKj@;r>{E zr&r6lKZP&pCOc_)V_Pc@~&{jvXe z+#nPtW$RP(L5I}W#rs!n_9ej9K|N`=Ma)0o{t8)U2psm;*Vunwqd@}HSZYT5&YPgd zr`SI{)DDHL-TKt%2IGee`3Gayco;XUJKa>eRalSvdu0b_L!IHxY1?nBgy)wj#QWpu z%vEqUw+A(ezoWjtm>(xB!XVYF8TGxXQhy)u{0E!2L9olKsi?nDhR&B+`z8ePH|f*G z1}?&Sygz(a<79Z)w-<#mi$*4#^=Wb7AL}%qvj%hs8IjL z!>|V20i!)sr^YGudU5}5dD3_Ivwt1!6q3NMqxr{=GQHqH3vG?_{Yw{Xa|^#@(8Qkq z-jCRSkfc&NW%~-E-PlX`eHqgK_MY0O8(+%+%EO#lRkHx&5~%nuqK3|`yxXh`Qv!t-H%Ofm}vD0{B`O) zmYZtwjeZ!R)-PzjX~&IEX=zwAd6g?|pKpFta2NMJq4WB=sqZh=_m}PkLW9xu=?eY3 z!gY+l7`I@sx!gcxpEn@;Jbq><*l9JQE!-LY6sW&oN$W6J>Caz(#PEmrFLyIaf^m(y zQs;$5lKMTyHw?OOYD5d1b_&m@XD2?N=w*2#7kQ=&9KN0n_(;D=+nwR#_i~H)S?=RlJsH;o4 zr@m9+anJ3-bp_HNiljYIE+0a*Q(696h0c$3oa)K#+f)Mv?C314mm&Qzsvy- zvcIdpuh@QW>G7OPuZ)7zq0;!YsH@A-@-*rcxLmznjL)2z`R81;IweYDYfN~0oHkc0K5@%c^1j_c*|P=rscuhaPY-r4qbsiRyvf8u*381B00 z(j#`vKE@z?F8Ue@-;(RokP{4_E(o8Gdxyb9KED5lPjggX8ELr+rg?XuQ)=9nw2wzG z&Vd`f8&a=3Oy8v`#Q1ESyAhTYTkss`)bB@ZAHM{-bAPIS@%in=>hCMY@8QgNASaD! zc{^!+JfQO}up2j&o@3p;uv7K7NwM?|^siT+-s-^zybbYJ7_EyDoe( zXP760r$%!1b#Z-vevRSKpwTPRexA0R`G4{LgXN|L?*YF4Xt(SK z@mgUbtjGD8>Qg^KcVZ&#%CYyWK=$`UXGgAS=0ocLME(EE#rAjU^je&5w{`S-&xOMK z!TFU&t|gT2nJ20rVtfzVIG!sS{GJY~l`gEu`q(?Og39(SC2^aXeZ~4XvA!Lb`mKbT znX>CDbiR8dzW~r`R)Br^UOZ@*x1*ljZb{nTo5k0m!?OVD^te?0`(pjtydVYYFEXWD_SciM-!~BX=i00G zav#^(!xk%MUu8%i45#tXduMxUbi2KJy?Fn)ZR;sqwB9dzY%RmLN-oB?-}>P&v~d+_ zcbVZ^hU{})KR2!e{X*v`Oc}oAVtw&$+(c-i_(*P4c3}5M_4iTw4xEj15$zwSrG9^6 z`(5wU5Y8a$AwB$~LU=zagzvH2~+U8soo7*Bv?6QTM55&=g@kw%?{xlwj4N7QH=0T3@(Z4dJw! zJ*0LiE!6iH?|-Sz4S^*;Yg4;ohJRdN9R7Yb*q+xGo$rD5hfUKtpeoU(&syiIpHCbg zdarlq`p^DAZJe0>RmsKncZ~gNsJ8Dw>%A;v@f+IzeC%T?=TO-lydN<9Vf%Y+MhZ+C zVN7)gG5n?>{ov^7%8f05LtE4trT+e6`#a_!;jH||LdgD1^>r~m5APh$IX`$sf3Gr@ z#9wjt1gKr3n)IC@jlY{~e!ys(80vqI=_{;n6LYJ$A3EWnT~k^=bYESY+q^f4D*J{D z?>7zQuMM@!=z!@#qWB8q??l!ZZer&Ox@PxQVLi@YpC9&==1!ciQ9oP+CvJelJvv~f z7h8|=bKWb0;7+a3BYeDa0Q#G5!LaL*Z!ensm7BW#KxG zzn;Y}0`2}fw2l0na2@9-3_mA=@?{%p>~>bT?uGR0w0F7C;+q4VtGvPPkL+i{<5bS~ zPG_ipTpC~P>L);6Q7h`+n$5?+`m~^h8#kx#E4p-@3&RJpkCn>t+|n+UbU=G6^>s16 zN?VTMqT-)Wlk@G>*TwejtoH;c?^8v58Zdm}{vzG&&fIXtZ92%U7F#bD+qWx;Rh+kC z9<+I~Tzy^azkN(Xskrb(h&6jIWA&Be~60_v!glsp|D& zeF}X1G`IC^jrOg5tsrRL_BWZGD{a3foj=d%%^MHHjadJI44tpC<5noNZKg%XXEOX? z`!%QOa`@w>OLJnb3eSh}(^EeYuD5MT+jY1pTnB~Nerc8Of!2Hb(%V0(gzFeztIBu7 ziqt-|>?zaFF(^N^`cx|SIK>1EmNR^%A^oV+-klrrxr!cDjb`5m;b-xBH_m(}KVvq0 zpl}_>H#T|W!L;8Ka%qvV{4c-Ek^kFxVItnbQCmC}`Uy@_Y4G(G|o+_;wK9#j1YmjA~7Z*Y7CHS8Ej zrgvxh4ePu2g+n;g$v3EC=XCY`#qsswj)CCR=rbAdMq1zPUg69&t9^}LY1>>_kI&z} zP&F6!x0H#_pTqIZ$d>0gos}a%ZalQ3%5i&JQ`v*##}R9<=U2 zrZ4`d{`+wiG#}QKzS_g$cbP)0{}wLT2OB^2qP~mR`!7fKYi)KarxRlYFQ!W4%l+;u zSlg{BwZ2+g{udwke77exnsXO-rc&+63?KM>g3uQmVAP&=w87*a!g`$l@jvIrS;(Hy zZ%GWFIKTOR+$8R{>JgpN#YBx?v3(=elhfUJQyKD~CwSY{w&xU$`fb?aI;ZO`iGhmA zLm7Wi{kKMG1&tgui_DuLjo-j}u3TgL`*h0AFyZ-eeDeH@5EO(9@-j<$u4QN-mBse2fU^@L2)PKV+!!CHAk&;x2Qe){TNA(^7@& zX(&FvVK)&L%q<}#iuqSuUwU=YjoWjKKf|I(PyPF1{LN`TiEG~c9_|0`lkog9nb^NJ zgo)g}(|2g_G^Vd{eN|^)DeaZ%Mq<3A?Wf_YI;RsyMZ%k@()gR|^OU|FGM#L_EsekP zrlYxz{jbr-7ya4yNAa;LG6>9EUX!!W8UAp7@~HV)ZueAs=(lt=`~Q&tb(Dw0iuqCdMMtq)I9S4Vp*QHHP zGW^M8V*DA`+5oOwn$z2BXR!DJ?cX)Op8?nT{>Q5~nSMw^{=4VwRL;3}Ysjc0jo--a z%i(%p4O-rznOv|hGBG}v_a@xNP-~6&yxijo7c*oSytpQf&oujCT$94Hbn2=)YWpL` z-;Z)v&ieBW+F={Rp91;sQ=eS9arJJ}1+&@zhyAxJEu}S&jMs?2`*w9s=X_fV^&bvV z-(Rfnb}F9I^0%HE^D_mZqqy34&eI1MeI@Z%I6N4xW>k^fSQbBE{B4+9z)k5Y2OHlt zlK8W5UIgnLK9GOsx8VHw&juH`;O+L{HCGycOA?ns?Mpw&Kl~*j`&fJRGAO$7lUxp` z!u?%Pe&^QHY|wJ+OdrB4;kp9lCy#4ygQ1^VQRO@4zf}ldKc6Il%&|Uo9h#}m--yp= z{%Eupj_xy|SC174zwd?W`{t$zux?9TT6~JtFI94J{c=TRO|G5y5<1C9S8cz<`Jbhy z_i&?JOdzv1i+^!`C+k%{_p{6jOtPfyt3}Rt@HrStqers-Bb+}U{(J&#X?UINGhy~M z2l@A_zsGTx3eMAY@9L}ZCC2yG@=DGs#SQw}N&EL_!^Uz&-3qC`uKNAT#qkS0c%P1G zK1wuy563TqJJ;clCJu*wJEZZwH2Ep5WvO=!tQsh5rxdFH<~Ixo%-iAm=*6AJzxs>h0yS`Wr#y z0CpYY)Ba>Wr&ZJotd-LEjC*;R>)gc-beA&wit+iXEkFOa;39cvBaP2HX%o4{KhDuU zI~q#jGx%vGx9RtIm^?rlpEK-!aiO`s;HXln->(>-BZEunGyh?t`8gP$!>;Ob(`zoJ zUr?xdWO^<8roM zr{P&U)bB@(&v$9xp~~5Z_Fls9iS6r%om=70%qG-sJmWt;Upske2Gr;K!_w1Evj1Nu z&OfG2PJjkeYts1F%zonetDPsMaxL8(K}%rx!}z?lz5*QIkD+~9l&F7StY6y} ze{R}130gU8(d?N;g8jwwL#^l6;B-3q@$*OOs=vS3|EE5G3i15;g+7k=)$d1)-{Tqi zT!(I5A>NkZSBC2AUX!C>y6HR8>X?OqU%Y?Py76UhT01MK<~FJMEynK{BR8l#b%q!O zu=*t4U-r4qQ!XXP8EX4T<9EmLv0Ub+JUU>`8}|H2|Gvrk$)ybAXUOp95J<)UEjN@> z`2>YV`@2le_utW-^v&8t_WQ{G9^=o(sg>YFs_(lB*Kz*p?7_O+ZG&Jc``VhVNA~x2 zix4R2ds8ER?V}4h%db7a>hxOmdNF>TnlA=}xH7V11+%|c|2C$}AtwJRDgVRrpI9F( z{Bf20Gp`T)CrQ}*5$_MSS~-<#xa%z4)QRB_=SRCu`wp{5xzU2Y4BuEkd>)k!ZFknE zU1C{(E{?CN_WXcmN_VQ$ll6zlP<~53b{!mQT$Ab_f27tIVtwn@HI-{NR2%F=r0sL{ zp*@__9epUv|A${OzSH*RbH!6k;FQ(B>*D;uw^mW`xac`48P4!+j`r`o|7Oj-KD(Xz zII#Sg0_7LX?p1JCv+W_$S{lD`ewEzG2ZP}Btz`l}as4qR>L;grdjgDDBaPn=No6!8 z!dhc~{=SQX8LqoFK+fbH)urw|xte?_Ek zRY*U)spG^M&dZ`Y>skI3>)ZEaF{B(TBJXRk`~x8UFfBh4&cr_<(M_2B#rnbV*k>qs zJevCL?WE?nIR3w2k^v^~>e9DSO#fp1X-!Cg@7>=M&LoZD3-wp;oAeX-8Xt9wmB#0h z`m>?+)@vki39AnS%I_Dw*u&}hGzS05fA|vP&-86HI1a5Ou7_L6|MCy#S2u>_bJw~U zf&ce(_5UZvr}>#k$Xxe?xL+|B*2f@xx*r(Go!_&KM%ps{it%}PyE|MdIYAoDGZog$ zP<$5HwjCFBY#Dv_N}WGM^`#t-N^Y&A99D4B_~nNDgRV#YM<`K??Ll?I9SaOasHvd;ucYDV))HL`0Zb`8g7PtBzKET^9B1V6W0&c zeu{*E#brd-jo~{D4qC5HRibR|Ka)QeYJjpZr9PY z=t(#A`xEnHUza49>{(6Z&aMpqC_gqfKMnpou0;b5U10AI#eec~nb1I6n>vkG=iiY1 zelu_m%+J3_uIMin)~6wUtbFtoI@GtNUv$*^1J%DS&B*7bt~P*_$I|#8&*!HdO3Os{ zISJvvbGw0D?!isete}CKKVtoH^3EjK-#nMp)n)oah4vSeUaa7Bc3Z(t18MsmIv^RE zba_rPT6YxwKN->=H`2V}{J1=F)$fyV9q%uwQ*m8pHk}zE8_A|T3@@*xXhhs(h+{#da8bYaeZx58Gn8r zr6l1j(-&A@r`~qt#$DY?zfF?n$FsUBXq|M0#QtIY!1mqVVHxx?zCje>EI!2NgB*=M z!)^RzAi}>&F4iYk?xl%6=c$cYicYgdy2a$(B;)KMc|NA7kR?f=yKcId_8LUnUdl z?}4Gu;K|Q^^xjf6{$*nSuuY!Nop{j#h8~s1zt8a~cr>ht6n$p;1lxa`1~%N_)9Yy; z3#LzS{zJD%0(`W6Kn9;4$nc5!|DKE}qu;)C*BIYDY>@`NY`8T3tllQUw4}%6Wp##ny%>LUUn`*tIU&Lyu8+-GlMIH*Pl(ZAH#Ppn`Z#4w z1kC(hAj+TN{*t{bSHsE7XXL80+CHQDMA?NE;E{5Tgn2Xn2gp8`)uY@Wmu4FAS^Mw` z$WmS-Hf>q{3-@PF+n)#{HbtZ%~HAN{_kmCSG7Kti}82FHx^!8zDrJb)e`uD`=?}E_i$!zwc+6cY5h{^ z5e*3&Zjl2oS_KuIr)s z3hlo$ChkAg{ZB}rtfv*U$ItE>^~ciiK)A5}FwyqAE&M*lZ}-)Uq1Flz<-(i87<_0htjG1UF;7;&yr1XEkO+oP+<$PWig3p!>uJR2GM{B|dq4qca+u}s zaea5{EyArIsRu`V8p@^Yr`xwxF!#h=qDw(|zBFV%htEiZ)ob4qMRTSfRB~~D!>&AE zcuI0ea7L7{9>;$dK5gQbOnyQ2fBnOs7{ABTW8l}0tE6a#On5#({eRoT_HbjL$>8Up zf9u8eHF91we1CkIy#C4X8;s8PZ1?6AH?6!OjCPa8uStVwXlZ|$6b)nebwT>WI5QD~ zY>UaXdH?L6SbsFM9Rj_3ZXhitvimEL{jM$}?Boqs}<|G@lNcPI&>$KEFLs(Va-Bl{lVzZB+H<&%5AS$+cB_lvzwa&uhk zYUI!1v(eztzmR;3I43;63iU_OO9@~SdxM<2#_TuFU(b5G1+uwH^57Gz@2OD#&u*7^ zuzq@loZ2D1|9w%cFZ`OgmyBA>_@hGl`+Q*>oZNni6lz}=`~yBechJX8+zhWLH2v*A zeu(+?+cyTTbvsW!bYlF{vlI7+b3LOWck(%sm#)Sy;?KdUiO|FQCK-5lw)*{u<5yeL zXdo`-e#ZKJs*X22Nys1}_FC-z zsK5JZ_arFKx-8-cp3nX~yo}c9(^jMYiLgw9B}Xrd^p6V7*IB~vUl`(StWp0&geO61 zt1BXY;Q5=S{QST6Pj-{iZ%lt<|6#v12`&%0Lf&S%3jFXw^8@?2F9wsCTw*+it;hOj zxi+t#^N)~|r&<3E#{c266P!bOEsgkhmPdhBG9eaLtUo9X;s4^t*Wk#{zm$a-spBtk z{8^@z0J60g$T~Vsz^6|I+TsChkbteY*A*!#}R?7*CIZgPS;Vyd}fG0^#3lND_>^ahV($63g&~ z;@871qam|^66*-Y5A0uVyi9;rk1i6cpR7L&P=0-Aqi7hMN67|D#t#MZFAbh0z{{eG z2%lRZ;zt_dN4QM|KYP+ZWB&Zvx+K{4s(_?6blLd*=_`mZh0gfI#Bf@_< z!oMsl3XYG>BgN?~zQyrDo$>@IU44e6cVPI(^WRo990%JvB$EnnL-}9*>Voo{=2c6e zuJ>-z2|5eUuWv8zKbbjkIoLkRCMhlTCHc`~#tfKXwx0aHEfdyzq4?tR??kwkPRNYz z()`)`qLdyT*hFLhsS|HsX4Rr1{$T$ikE)0vmB&{4+{u0+uFSSVmi}Qp;mfjWg z7d}5H*dY?O2jq~9QWn49{(SCZA}n7+h>ZXH`~3{j`2-sjvHbj~BV^f9=D%=!owH*N z_*^_oE^lD*2i9Na8LMFG(vu`jU+sU;`En16KR`1-BU*I0CG%f0as2Y7cqPmuuFz7L*X z^s68SESnq=#Xl;JbW=(MMf%&&gYg&l zkN@hO1nY0*k+P4Bzg6h`gI_x$!FTvxvd5qKM_gb2v>*{opYrF|s`;xx{N4X^8FYKH zi+mf!`YW;j)aU1CUL{xDfrx>;BsgZMqLRRA;|xt>JdVf>b%{>+Qq_fdVqY+Vg48I-)Li*2<8dL$kwim z-*|p}gTv7<<8?Oa+K9zR`20!FqX{tQ#ZmG(jPV< z=6B$>8L;wXJh851{#S+SFV0!ZV8s12vd@k6zhZvZ9h3|q_YRSrBXor4$N9fa4NBojgclO;~+ReR~2l-Ex5V ztYPyX^w9Z|c1KpiwLg2wvuXM4{iFP%^HhF*Q^Wma`6kA1bHwj=OH#noBbV5F9~0K6 zA$|wFSP6se_KEy=65@BkjsP&)mrO3SW&FbYp7(@5f8^I5qI|>jvkLLs~6`yLXHDsbep$pI&u{fySBXM7LTxe_3)W0d~3UCi(jqKMfH-jSJ%7 zdg^v!-Sm|3{DAoRi1)v$FT2S3Cybx?eD(Im@le=*Cs9p5pvI3_Uk~Hs+uHg&NoZ51 zud)9vI}-$>`XrDUk68W%^E2pT9JI{X&Q}nn`MK*q|22L$nOCt^xPLjCf4HdGN@(|E zJ2|kRhWsyoRdO+ZfARh|=Fx7lv<wPns+C}|o`LZj660aPE0D4qd@ z@0XGV-x&YO5&ya-&4XsE<4O4EnreL|o*!DXSq=n$EhH07)ci;LE9-9!vFj>K2UTroU9nwQdqA-_`h;y1~lrvP^2FL;h%ft4|d;Gq+8$* zwjRyTEq#5Co4T@?TEz`e^FzG9W6i@7TJH8HKX1B+dcAl)jO(cS+hngKs7S`kW z3bz|9hELDqMEOzN-*&5CGLUOq$;Kg!KlpsSwv!@Z?X6@He{g+zX>20secdeL&s(G) zJ9mkKmd8>^yF%6n$JdVKsdK9!7~ z%kn?x5r1Cxh=cY9>&eiE`-JzCh5Fw-&&EUI+l^#>sWiV5NAvUhmaHKAhOT7q7sZFY zd-M9$cN58TxFy7wxPLz~b|GZ{iXjyXmkaCPBL6fqZxtwiY$B)AS^duo@vrJmB5WSE zh5YO^M_7;ZtH~QwV38hAI{9^x|K(3Pp1;(?AA;Ab$g!Ok>gN~Nuaiq$A;Kh(#9!+m ztjGMLCNp8RUNDJFZXvA4{5v?&2M&)4A&tk?5Uwi_|Hw06`0+iAcsNMsXLMG6<-F6h zptziS+*HquGZs^Qi z%@{>Jdb0i7GSuIHNh=gWgTgiT_Zz}#Zehnuv~;U9{|sj@goWFdk+{7#gy+Zo{o54D z@P65P5&u+jar{<)bR-;Zw32+@$NU%0ua5eV2#%fBiTHON@z0|;3SMQ!ll}Q;h5O_A zX04|tz)3zq`;UL-NFO%LkAXSq3FLF1BXC#>?WBw@y@h2fL z3C{0aM{L{96`o&#>Jw9MEQGe#ml36ziTp2r(hz@UYzu~hUki!o{5@2^&USW#^#`UC zRY^x-{dMHO9*vp_f$=j*!A@!ZxIWzvW1Aiz!|FH+&xhluCnx-1(^o%ovh{c2I?jI> zhkWJ24t=E?9?g>E&(qWg)c@`Sjrwh+c>`|G_y+v^xv|3UWBs=Eeg(bI;;Bad9C3B# z+O2Y?%lI=Sn7$VG|LJrMg+sof8uK5@giGA}GneSc9vg)9*nj# zj*L09RrvihD}e`&LEEd;?@5k=gVelX(CZi7XzfAXUL@&m$p1>#5Q@GwY;4#u& zk(B2R^LM$ENNZ_+TrM~W3xDh;-3Ja9ejodnN!xv4kk1s-sPe0D9rME^tB@OA#mnDz z0|kEI`3Y$|9?*&>w>9#kay*}(KRuIt3t{K8s!)IIl06mFdPj*yefQvDA-Ab5r331e z3(trB%k^#sj>p@zC}Kj z4Qi@>e`5bKG%gaRcr79S=F4FJ(xGWI+~~AaR3FFsZLKU3#+`~G{$(uw!TCQ`Ml?Lj zSxP*19uw}5`El?uA75{aA>OHsA2|PK`!*gro{1vX19F7*m>-+Yg~NkGAtL`!j`k-! zc)Jz~Cnu7mC^i03f8pHa;jk|>gscLFf1JM?7Jibe;dq!X&)KH7uj2lvYt2GIYoQPM zcm7iv!hg3d9$@o+3>lYbD*wyBDun-e)4XBpnNj52&*sAahxJwT@PjaST^h03?X12o z?hhQXcNX-{A459b{KBrI_$I~vE9YEVPAk%+{X_rJWmIR*`TV*$EdIdp{qn+4nETY7 z+~I35%s-0vC-gc}L9oCuQ(my!ZoR=>jg4;~DQhLq-WNO)&ye4md`g!;9Yk@Q4%J_7EKlHG`b@O$$} zLA|}g{k>3pvMoUcBOlEoE;*~&|A*|qZqY*U={=o9tYq;8-oIvWARHP$m_Z62Fnp^} ze}~@2licDLyXi_!8s7&X1ZI74Bi`Yb!u>J651P0`S%i~l|E~h!d-97J;H&RQ&h3)M z_u{|A>mv`SnLh z#}6m(@aIFk8clX6*!hrY$iDX{6?9hhS&jG}o_L9CtT;fwG_4Tc55~6ve|}&6XQRnd z-(ul9#&^}VCE#i8A=*EQ^INm`T<3y!9H#z?HthSO{#T=Jk)So)o1~6l`o{(3k8fp1 zLcJa{$=7EL-`IZlNsNZ)zP@B;IKwZFuMf?Sf%iZB$o92+g!}6ueC}~x4)MCvi18)n zpUP2x#3j#gs2((lWQ}3^U4iWL>^>*CCEe0#inlcW{MV{L*T<9Wk~96FlDGS>7%lw0 zQTV~@eM88I%jUxKsgV86%XWkQgRDjS!^{yruYU4|{yGCm!RQw1_2T}ad9x2d=HUbp zKFbk4=T7^=nf19qV@~;~{ew7vbb4ADecLcsqkX+g!eG9w6B*i>;ScMJ{UuLm{^;ZR z+kQ+`e}8d*_925p&gES?^=R}^xQ_8R#y$*s6+4oF71H+grnd^x?z@m$SMCbyG5*FZ zqx}A(RQhUeL-qZ|`eDw86_D%TO6;ny3D+_HYRPzg{B;tkKau5saDPCiPAuH3oJ^jD zvG@|>?{K|X=>2js8SlvKBcS@q(s5&7mhE-o}UF}V{M53 z?w-Q?!T78m?*cEM1J^4<8yy9z(zY`E+=H;v@G+@V6dL7I`uIiSz%1tz*HV`xtWfkTiZ{eBvPC z^H_52J*(W-k*MOb`mri=t&%#*$UUOeeDo89o((W$o1@Q0{*c7&(qI=VUHFQ#aoT)aZ2d^=ow8 zMQQv#K0X^Jx3?gzI+h6Qv41ydc!g`i&%PVld82S0=QoTysG#Yh{^a;bhHso7Y@5CU za(>9kfGG^W3gq8)Iu~*V9g{TTH@m?Ka5R+@&oB_~kL_=QQ7k-I;za(BuCoq{;`$}iTxFC(L&-ePm*&|``8 z_aS~?*Gb}1-nyt%zP0PGgzHlte@f+w;)7JzEyej=T6X~)8`MK-w|g9aeHl8x@zbS^ zuxX2pa(NWxSAy~r1J}F4+!bAvt_ync^D(~*U3Y@ywX4#@&x@t{y%TjV)c+Se$$$|9 z{FEepAwOS^^zTh0Tll0hQtB4I*NhAM?_XcbguB81%8Zuc`HOxbi$Tw#tFlpBalY+q zN>q_ew<@x_*XGxR^`{rN1Hg1pH-Ub}e7ERVsfx2q(#rSWntZOs%~%y@N%_V8gQ8t9 z>{4`B8U@jD%y+=^Yuv?=>r}rB#Q8S;90hfn_0#I#zWgr|j_37J?p;ay7m^X*P4doj zP3EoC%J+1aD9AY0SJ|pb4*&jf{O0pM7OwaXQXY*s$&Z_${9LB-T3C=XN_jkz@?D1X z^H%FM@Z!`+rPG1kn(r&@zu&WXD_93lR&FXP#)Qhok`O;hFBwq5x76109%-|!hXI&{4%KqpaSzlHws;#RiMf2+P${;jqK!<~6; zl_|X&@b?GgKX-9i43~0SDU*Iu{{-vz;tfw#``5%NR&uWN`BDAH=TQI@r?(dHkIzTw zF{Dyu5gf0T|K-UA+@vqTs{96z`Ril;+0nt^(66oX+y=@&uD?!J*I$3W2~zb7q4pc= z_jbo4!0KT~Wd=+87jXVs5`3LodnsBqB)ScMf1JMl7oP7Tv)vcDb>(hnuQMPp}Sk7XU{O2J zG*fk5UtB&eWV(T@u!%BZ+Zg)(kbGR9unBs<9$x59u9-8?=`M4Bs3y#kJDHe?r_kXTD3W6?^ z8Y_n=4EXsHwEkqZHis2rZE&R&jIWUdsKk3Jsfx$TJ_stBTVyEd7X zs?(Lr725i9o=q>}Qf9iViqz{|c>9RzqwT7fK-Y*S%2##i_-eF&)Usn7SJG;(%6aET z&3s}0x^G!17!PTx41GrP7dZZ$)8`uZF2Glnx2iQiAInFdm$BeFrHyh{uj_Oi*^i`t zF<>^im9q6=g=Sp1Kcyrw3g#|vu55RY>VNG2932${t`4n~3sUy;^YQuC6Fp*}$@*5x zcImYKg7^2cI<$jxO&Fxg{zLi2`hTz5{~6;rPL*j+$MOECi(9)xfr*}S`fG8%Q=T|M z^=!%i^2_}5VSdM+o(+B{e<)@i?ZQ&~AmsP+!xIpZVy={orv5w5KliAb1%D@0DsIM# z`!`##^GPh`)XjGo z7^mtrY@8-O7xKGKuToVqGf-=OWWMe-ZpuXmRc7>a{{3M6-q2|YObk>%|1zrov3?)3 zDxWLgYNhHpN?gDD*r@lfZmqA}Vsx9nf7Jh3wyBUyEwWL4=w!@~V}8%IQ}6%Pu(7g@ zKIPv8@f&?J7W$_fDlO|$|J@AjPwCz}26A6EP+Hc@;ID6n{2R9;5isDEzEb}@^f^(k)@Lq_)C?~ncS{go%-#*6;SA5w3AT!P}uKBhBazSj*! zznB_+9LJX(tU^G3`GewWtA?6!Vf|#^qAy(jCqGry8Fvj|!u;LAn8&J{yKEKf_lWm@ zx%|?}H#3r}zV9BZnJ?rM8dR#xKD%h;vw3DAw{@yaRoI*APt0fVF!lL~ig$`y|JxPm z*Q5jL^<|Q83SU#|U&s-E_6^kjO$Jdt_-@4ie$3ys?JFQ_w~nB{%LwuJvOE?xe~>6o zwW0js{BgN720o_!QA}u0`NR3Uyl^>Wn*UT-EKa8PNBlXQih&&oe-(yrSJUr<^23)e zM#KB_zZE_vOXz%5znHpl3)C59tUN3g=dbBF54djfOtGbOEI%LfH*t?2>=<9A2w&HM z74r|;PIQKzb`KS`{sHE5ZPRHGx%86a=$v-^{4(S}kD46({kKt+>FiE0h-+Y~bhP{9e)1r>e_I;}zQW zzxnfCCx3L01*){w;`|O(uTNcjdXnP2w|IV}Zbku@bFQz-OrPpc%y0j~AlTLLp<=NC z^`CM4xY{KW)*g7O_@$uyV*6itppg5sv7f4*skr{!DqjgP{%;kv`}^Yj$j~pbu>0dH zMMpErFV25la*2T+-CrooCs2N|{tU8@hFh~M6^SwX`1gzLKYWqH&6Em7!gpGqb4B?N z57TgHcDzJUTc4Al{)`pM?J(lDzB2b}AC~%8!u+y)trxV`yP@bDN$bC6NPpg0;Sae} z?kYx^bmZq_|JERT8bk%3QRo&^J|(FBadk!zbnI84IKA71|9#m0?<#TvU8f91gWlii zI4k6H|J6X~&gCoWwV`|_Bm3X-`$Dj9o1@THpRQ;6g=>6otm=xFxc&`TUaI;A0~OlN zrwTl;lh3}hR%MPC=U1xkzumrZm{xwHHZ;k9>fo-LnQo$qKZN;dJKbO~%_&gi6Ur~v zzwH~zq4SojirW28asDoCAIDuh)>dWkvI+nGu>Os{xExk@yQ^p#Li2lONdM~GSPs?w z?<(GSa{T;c)PLS{ZwxHWxT!ErqWt3gh9o>1vP!NilGDWbjkJx1IR~yQKD*KU-D<>d zV9YXbv$~?#HF*VpefI#Gd}05D`{MnO zRZvG+x@neXzA%50X5jBP^+d>`EC1V%bZiu